From 2917b9bea880a2c9262467409b1886a79de4be6e Mon Sep 17 00:00:00 2001
From: m-guberina <gubi.guberina@gmail.com>
Date: Fri, 14 Mar 2025 19:01:48 +0100
Subject: [PATCH] idk when i last commited and idk when i'll commit again

---
 docker/Dockerfile                             |  37 ++--
 docs/installation.md                          |   4 +-
 .../dual_arm_cart_pulling.py                  |  11 +-
 .../dual_arm_cart_pulling_control_loop.py     | 185 +++++++++++++++++-
 .../fixed_path_planner.py                     |   2 +
 .../ros_dual_arm_cart_pulling.py              | 181 +++++++++++++++++
 .../technical_report/cart_pulling.log         |   6 +-
 .../technical_report/cart_pulling.pdf         | Bin 288786 -> 288863 bytes
 .../technical_report/cart_pulling.synctex.gz  | Bin 62003 -> 0 bytes
 examples/ros/myumi_cart_pulling.py            | 119 -----------
 examples/ros/navigation_example.py            |   2 +-
 .../cartesian_space_point_to_point.py         |   3 +
 .../smc/control/cartesian_space/ik_solvers.py |   4 +-
 .../controller_templates/point_to_point.py    |   5 +-
 .../smc/multiprocessing}/smc_yumi_node.py     |  53 ++++-
 .../smc/path_generation/maps/premade_maps.py  |  15 +-
 python/smc/robots/implementations/heron.py    |  18 +-
 python/smc/robots/implementations/ur5e.py     |  10 +
 python/smc/robots/utils.py                    |   2 +-
 19 files changed, 494 insertions(+), 163 deletions(-)
 create mode 100644 examples/cart_pulling/control_sub_problems/ros_dual_arm_cart_pulling.py
 delete mode 100644 examples/cart_pulling/technical_report/cart_pulling.synctex.gz
 delete mode 100644 examples/ros/myumi_cart_pulling.py
 rename {examples/ros => python/smc/multiprocessing}/smc_yumi_node.py (83%)

diff --git a/docker/Dockerfile b/docker/Dockerfile
index 5e76c53..2d2956b 100644
--- a/docker/Dockerfile
+++ b/docker/Dockerfile
@@ -7,11 +7,6 @@ LABEL org.opencontainers.image.authors="marko.guberina@control.lth.se"
 ARG DEBIAN_FRONTEND=noninteractive
 ENV TZ=Europe/Stockholm
 
-# pinocchio install
-RUN apt install -qqy lsb-release curl
-RUN mkdir -p /etc/apt/keyrings curl http://robotpkg.openrobots.org/packages/debian/robotpkg.asc | tee /etc/apt/keyrings/robotpkg.asc
-RUN echo "deb [arch=amd64 signed-by=/etc/apt/keyrings/robotpkg.asc] http://robotpkg.openrobots.org/packages/debian/pub $(lsb_release -cs) robotpkg" | sudo tee /etc/apt/sources.list.d/robotpkg.list
-
 RUN apt-get update && apt-get install -y --no-install-recommends \
         python3  \
         python3-pip \
@@ -32,10 +27,20 @@ RUN apt-get update && apt-get install -y --no-install-recommends \
         zsh \
         zsh-syntax-highlighting \
         libarchive-tools \
-        libxcb-cursor0\
-        python3-python-qt-binding \
-        robotpkg-py3*-pinocchio
+        libxcb-cursor0 \
+#		python3-pyqt6 \
+# opencv dependencies
+		ffmpeg libsm6 libxext6 
+
+#        python3-python-qt-binding \
+#        robotpkg-py3*-pinocchio
+
 
+# pinocchio install as debian package - compiled with numpy 1.26 so incompatible with pip which has numpy 2.2
+# necessary for ubuntu 22
+#RUN apt install -qqy lsb-release curl
+#RUN mkdir -p /etc/apt/keyrings curl http://robotpkg.openrobots.org/packages/debian/robotpkg.asc | tee /etc/apt/keyrings/robotpkg.asc
+#RUN echo "deb [arch=amd64 signed-by=/etc/apt/keyrings/robotpkg.asc] http://robotpkg.openrobots.org/packages/debian/pub $(lsb_release -cs) robotpkg" | sudo tee /etc/apt/sources.list.d/robotpkg.list
 
 
 # qt-binding is a really unnecessary 300MB, but i don't want
@@ -48,26 +53,26 @@ RUN apt-get update && apt-get install -y --no-install-recommends \
 #RUN yes | unminimize 
 
 # make the environment more usable
-# create user
-RUN useradd -m -s /bin/zsh -G sudo -u 1000 student
+# create user - jammy comes with user ubuntu with UID 1000, so now we do 1001
+RUN useradd -m -s /bin/zsh -G sudo -u 1001 student
 
 WORKDIR /home/student/
 RUN passwd -d student
 USER student
 # copy repo to workdir
 RUN mkdir SimpleManipulatorControl
-COPY --chown=student .. ./SimpleManipulatorControl
+COPY --chown=student . ./SimpleManipulatorControl
 RUN mkdir -p .cache/zsh/
-COPY --chown=student /dot_files_for_docker/.vimrc /home/student/
-COPY --chown=student /dot_files_for_docker/.zshrc /home/student/
-COPY --chown=student /dot_files_for_docker/global_extra_conf.py /home/student/
+COPY --chown=student /docker/dot_files_for_docker/.vimrc /home/student/
+COPY --chown=student /docker/dot_files_for_docker/.zshrc /home/student/
+COPY --chown=student /docker/dot_files_for_docker/global_extra_conf.py /home/student/
 
 
 # this is enough to run clik
 WORKDIR /home/student/
 USER student
-RUN pip install -e ./SimpleManipulatorControl/python/
-RUN pip install crocoddyl matplotlib meshcat ur_rtde \
+RUN pip install --break-system-packages -e ./SimpleManipulatorControl/python/
+RUN pip install --break-system-packages pin crocoddyl matplotlib meshcat ur_rtde \
                 qpsolvers ecos example_robot_data meshcat_shapes \
                 pyqt6 opencv-python qpsolvers quadprog \
                 proxsuite casadi pin-pink
diff --git a/docs/installation.md b/docs/installation.md
index 3d92bd0..dce2c4d 100644
--- a/docs/installation.md
+++ b/docs/installation.md
@@ -35,7 +35,7 @@ To proceed you need to have the Docker desktop GUI app running (open).
 --------------------------------
 5. [WINDOWS] open wsl (type wsl in powershell) and navigate to git folder (now in wsl) with "cd /mnt/Users/YOURUSERNAME/PATH_TO_GIT_FOLDER"
 5. [MAC] open a terminal and navigate to git folder with "cd /mnt/Users/YOURUSERNAME/PATH_TO_GIT_FOLDER"
-6. build the image with "docker build -t ur_simple_control ." NOTE: if you are on mac and have an apple silicone processor,
+6. build the image with "docker build -t smc -f docker/Dockerfile ." NOTE: if you are on mac and have an apple silicone processor,
     you might need to change the ubuntu version to one that works on the apple silicone processor.
 
 #### pulling the image
@@ -45,7 +45,7 @@ To proceed you need to have the Docker desktop GUI app running (open).
 
 ### using the image
 ----------------------
-7. to run the image run  "docker run --rm -it --net=host -e DISPLAY=$DISPLAY -v /tmp:/tmp ur_simple_control /bin/zsh".
+7. to run the image run  "docker run --rm -it --net=host -e DISPLAY=$DISPLAY -v /tmp:/tmp smc /bin/zsh".
    [Linux and MAC]: NOTE: FIRST RUN "xhost +" EVERY TIME before you run the image. otherwise docker can't open new windows,
    so real-time-plotting won't work. [MAC] you need to have xquartz installed to have the xhost + command (look at installation for more).
    NOTE! if you don't get real-time-plotting with xhost +, do xhost + 127.0.0.1 and replace -e DISPLAY=$DISPLAY with 
diff --git a/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling.py b/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling.py
index 8414bc0..1a3f9db 100644
--- a/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling.py
+++ b/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling.py
@@ -14,7 +14,7 @@ from smc.control.cartesian_space.pink_p2p import (
 from smc.control.cartesian_space.cartesian_space_point_to_point import moveL
 
 from utils import get_args, constructInitialT_w_abs
-from dual_arm_cart_pulling_control_loop import DualArmCartPulling
+from dual_arm_cart_pulling_control_loop import DualArmCartPulling, DualArmCartPullingMPC
 from fixed_path_planner import contructPath, fixedPathPlanner
 
 import time
@@ -35,11 +35,11 @@ if __name__ == "__main__":
     # TODO: before running on the real robot change this to just reading the current position!!
     if args.planner:
         robot._step()
-        robot._q[0] = 9.0
-        robot._q[1] = 4.0
+        robot._q[0] = 1.0
+        robot._q[1] = 0.6
         robot._step()
         x0 = np.concatenate([robot.q, robot.v])
-        goal = np.array([0.5, 5.5])
+        goal = np.array([5.5, 5.0])
 
     ######################################################
     # 1. initialize path planner, or instantiate pre-made path
@@ -74,7 +74,7 @@ if __name__ == "__main__":
     ################################################
     pathSE3 = path2D_to_SE3(path_base, args.handlebar_height, np.pi)
     init_rot = pathSE3[0].rotation @ pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0)
-    init_rot = init_rot @ pin.rpy.rpyToMatrix(0.0, 0.0, np.pi)
+    init_rot = init_rot @ pin.rpy.rpyToMatrix(0.0, 0.0, np.pi / 2)
     # T_w_absgoal = constructInitialT_w_abs(args, path_base, init_rot)
     T_w_absgoal = constructInitialT_w_abs(args, path_base, pathSE3[0].rotation)
 
@@ -138,6 +138,7 @@ if __name__ == "__main__":
     # TODO: for final demo replace this with disjoint controller
     robot._mode = robot.control_mode.whole_body
     DualArmCartPulling(args, robot, path_planner, T_absgoal_l, T_absgoal_r)
+    # DualArmCartPullingMPC(args, robot, path_planner, T_absgoal_l, T_absgoal_r)
 
     if args.real:
         robot.stopRobot()
diff --git a/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling_control_loop.py b/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling_control_loop.py
index 3c0b05c..6d78457 100644
--- a/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling_control_loop.py
+++ b/examples/cart_pulling/control_sub_problems/dual_arm_cart_pulling_control_loop.py
@@ -16,6 +16,10 @@ from smc.path_generation.path_math.path_to_trajectory import (
 from smc.control.controller_templates.path_following_template import (
     PathFollowingFromPlannerCtrllLoopTemplate,
 )
+from smc.path_generation.path_math.path2d_to_6d import (
+    path2D_to_SE3,
+)
+from smc.control.cartesian_space.ik_solvers import *
 
 import numpy as np
 from functools import partial
@@ -24,9 +28,186 @@ from argparse import Namespace
 from pinocchio import SE3, log6
 from collections import deque
 from utils import initializePastData
+import pinocchio as pin
 
 
 def DualArmCartPullingControlLoop(
+    T_absgoal_l: SE3,
+    T_absgoal_r: SE3,
+    ik_solver,
+    path2D_base: np.ndarray,
+    args: Namespace,
+    robot: DualArmWholeBodyInterface,
+    t: int,
+    past_data: dict[str, deque[np.ndarray]],
+) -> tuple[np.ndarray, dict[str, np.ndarray], dict[str, np.ndarray]]:
+    """
+    BaseAndDualEEPathFollowingMPCControlLoop
+    -----------------------------
+    cart pulling dual arm control loop
+    """
+    v_cmd = np.zeros(robot.model.nv)
+    p = robot.T_w_b.translation[:2]
+
+    max_base_v = np.linalg.norm(robot._max_v[:2])
+    # NOTE: can't initialize a priori now because we're not running immediately,
+    # hence nothing is initialized
+    if t == 0:
+        path2D_handlebar = initializePastData(
+            args, robot.T_w_abs, robot.T_w_b.translation[:2], float(max_base_v)
+        )
+        past_data["path2D"].clear()
+        past_data["path2D"].extend(
+            path2D_handlebar[i] for i in range(args.past_window_size)
+        )
+    trajectory_base = path2D_to_trajectory2D(args, path2D_base, max_base_v)
+    trajectory_base = np.hstack((trajectory_base, np.zeros((len(trajectory_base), 1))))
+
+    trajectorySE3_handlebar = construct_EE_path(args, p, past_data["path2D"])
+    trajectorySE3_l = []
+    trajectorySE3_r = []
+    for traj_pose in trajectorySE3_handlebar:
+        # trajectorySE3_l.append(T_absgoal_l.act(traj_pose))
+        # trajectorySE3_r.append(T_absgoal_r.act(traj_pose))
+        trajectorySE3_l.append(traj_pose.act(T_absgoal_l))
+        trajectorySE3_r.append(traj_pose.act(T_absgoal_r))
+
+    if args.visualizer:
+        if t % int(np.ceil(args.ctrl_freq / 25)) == 0:
+            robot.visualizer_manager.sendCommand({"path": trajectory_base})
+            robot.visualizer_manager.sendCommand(
+                {"frame_path": trajectorySE3_handlebar}
+            )
+
+    # CONTROL BASE
+    robot.mode = robot.control_mode.base_only
+    trajectory_base_SE3 = path2D_to_SE3(trajectory_base[:, :2], 0.0, 0.0)
+    rotm_z = pin.rpy.rpyToMatrix(0.0, 0.0, np.pi)
+    for z in range(len(trajectory_base_SE3)):
+        trajectory_base_SE3[z].rotation = rotm_z @ trajectory_base_SE3[z].rotation
+
+    SEerror = robot.T_w_e.actInv(trajectory_base_SE3[-1])
+    err_vector = pin.log6(SEerror).vector
+    if np.linalg.norm(err_vector) < 0.2:
+        V_path = (
+            5 * pin.log6(trajectory_base_SE3[1].actInv(trajectory_base_SE3[2])).vector
+        )
+        err_vector += V_path
+    err_vector[3:] = err_vector[3:] * 2
+    J = robot.getJacobian()
+    v_cmd_base = ik_solver(J, err_vector)
+    if v_cmd_base is None:
+        v_cmd_base = dampedPseudoinverse(1e-2, J, err_vector)
+    v_cmd[:3] = v_cmd_base
+
+    # CONTROL ARMS
+    robot._mode = robot.control_mode.upper_body
+    SEerror_left = robot.T_w_l.actInv(trajectorySE3_l[0])
+    SEerror_right = robot.T_w_r.actInv(trajectorySE3_r[0])
+    err_vector_left = pin.log6(SEerror_left).vector
+    err_vector_right = pin.log6(SEerror_right).vector
+
+    err_vector = np.concatenate((err_vector_left, err_vector_right))
+    J = robot.getJacobian()
+
+    if args.ik_solver == "QPManipMax":
+        v_cmd_arms = QPManipMax(
+            J,
+            err_vector,
+            robot.computeManipulabilityIndexQDerivative(),
+            lb=-1 * robot.max_v,
+            ub=robot.max_v,
+        )
+    else:
+        v_cmd_arms = ik_solver(J, err_vector)
+    if v_cmd_arms is None:
+        v_cmd_arms = dampedPseudoinverse(1e-2, J, err_vector)
+    v_cmd[3:] = v_cmd_arms
+
+    robot._mode = robot.control_mode.whole_body
+    err_vector_ee_l = log6(robot.T_w_l.actInv(trajectorySE3_l[0]))
+    err_norm_ee_l = np.linalg.norm(err_vector_ee_l)
+    err_vector_ee_r = log6(robot.T_w_r.actInv(trajectorySE3_r[0]))
+    err_norm_ee_r = np.linalg.norm(err_vector_ee_r)
+    err_vector_base = np.linalg.norm(p - trajectory_base[0][:2])  # z axis is irrelevant
+    log_item = {}
+    log_item["err_vec_ee_l"] = err_vector_ee_l.vector
+    log_item["err_norm_ee_l"] = err_norm_ee_l.reshape((1,))
+    log_item["err_vec_ee_r"] = err_vector_ee_r.vector
+    log_item["err_norm_ee_r"] = err_norm_ee_r.reshape((1,))
+    log_item["err_norm_base"] = np.linalg.norm(err_vector_base).reshape((1,))
+    save_past_item = {"path2D": p}
+    return v_cmd, save_past_item, log_item
+
+
+def DualArmCartPulling(
+    args: Namespace,
+    robot: DualArmWholeBodyInterface,
+    path_planner: ProcessManager | types.FunctionType,
+    T_absgoal_l: SE3,
+    T_absgoal_r: SE3,
+    run=True,
+) -> None | ControlLoopManager:
+    """
+    CrocoEndEffectorPathFollowingMPC
+    -----
+    run mpc for a point-to-point inverse kinematics.
+    note that the actual problem is solved on
+    a dynamics level, and velocities we command
+    are actually extracted from the state x(q,dq).
+    """
+    robot._mode = robot.control_mode.whole_body
+    # NOTE: i'm shoving these into the class here - bad style,
+    # but i don't
+    T_w_abs = robot.T_w_abs
+    ik_solver = getIKSolver(args, robot)
+
+    max_base_v = np.linalg.norm(robot._max_v[:2])
+
+    path2D_handlebar = initializePastData(
+        args, T_w_abs, robot.T_w_b.translation[:2], float(max_base_v)
+    )
+
+    get_position = lambda robot: robot.q[:2]
+    DualArmCartPullingControlLoop_with_l_r = partial(
+        DualArmCartPullingControlLoop, T_absgoal_l, T_absgoal_r
+    )
+    controlLoop = partial(
+        PathFollowingFromPlannerCtrllLoopTemplate,
+        path_planner,
+        get_position,
+        ik_solver,
+        DualArmCartPullingControlLoop_with_l_r,
+        args,
+        robot,
+    )
+
+    log_item = {
+        "qs": np.zeros(robot.model.nq),
+        "dqs": np.zeros(robot.model.nv),
+        "err_vec_ee_l": np.zeros((6,)),
+        "err_norm_ee_l": np.zeros((1,)),
+        "err_vec_ee_r": np.zeros((6,)),
+        "err_norm_ee_r": np.zeros((1,)),
+        "err_norm_base": np.zeros((1,)),
+    }
+    save_past_dict = {"path2D": T_w_abs.translation[:2]}
+    loop_manager = ControlLoopManager(
+        robot, controlLoop, args, save_past_dict, log_item
+    )
+    # actually put past data into the past window
+    loop_manager.past_data["path2D"].clear()
+    loop_manager.past_data["path2D"].extend(
+        path2D_handlebar[i] for i in range(args.past_window_size)
+    )
+
+    if run:
+        loop_manager.run()
+    else:
+        return loop_manager
+
+
+def DualArmCartPullingMPCControlLoop(
     T_absgoal_l: SE3,
     T_absgoal_r: SE3,
     ocp: CrocoOCP,
@@ -97,7 +278,7 @@ def DualArmCartPullingControlLoop(
     return v_cmd, save_past_item, log_item
 
 
-def DualArmCartPulling(
+def DualArmCartPullingMPC(
     args: Namespace,
     robot: DualArmWholeBodyInterface,
     path_planner: ProcessManager | types.FunctionType,
@@ -127,7 +308,7 @@ def DualArmCartPulling(
 
     get_position = lambda robot: robot.q[:2]
     DualArmCartPullingControlLoop_with_l_r = partial(
-        DualArmCartPullingControlLoop, T_absgoal_l, T_absgoal_r
+        DualArmCartPullingMPCControlLoop, T_absgoal_l, T_absgoal_r
     )
     controlLoop = partial(
         PathFollowingFromPlannerCtrllLoopTemplate,
diff --git a/examples/cart_pulling/control_sub_problems/fixed_path_planner.py b/examples/cart_pulling/control_sub_problems/fixed_path_planner.py
index 0116bc4..d13fbab 100644
--- a/examples/cart_pulling/control_sub_problems/fixed_path_planner.py
+++ b/examples/cart_pulling/control_sub_problems/fixed_path_planner.py
@@ -26,6 +26,8 @@ def fixedPathPlanner(
     path_base: np.ndarray,
     p_base: np.ndarray,
 ) -> np.ndarray:
+    if p_base.shape[0] == 2:
+        p_base = np.append(p_base, 0.0)
     distances = np.linalg.norm(p_base - path_base, axis=1)
     index = np.argmin(distances)
     # NOTE: bullshit heuristic to deal with the path intersecting with itself.
diff --git a/examples/cart_pulling/control_sub_problems/ros_dual_arm_cart_pulling.py b/examples/cart_pulling/control_sub_problems/ros_dual_arm_cart_pulling.py
new file mode 100644
index 0000000..0107f8e
--- /dev/null
+++ b/examples/cart_pulling/control_sub_problems/ros_dual_arm_cart_pulling.py
@@ -0,0 +1,181 @@
+#!/usr/bin/env python3
+
+
+from smc.multiprocessing.smc_yumi_node import get_args, SMCMobileYuMiNode
+from smc.path_generation.maps.premade_maps import createSampleStaticMap
+from smc.path_generation.path_math.path2d_to_6d import path2D_to_SE3
+from smc.path_generation.planner import starPlanner
+from smc.multiprocessing import ProcessManager
+from smc.robots.abstract_robotmanager import AbstractRobotManager
+
+import numpy as np
+from smc.robots.implementations.mobile_yumi import RealMobileYumiRobotManager
+from smc.control.control_loop_manager import ControlLoopManager
+from smc.control.cartesian_space import getClikArgs, getIKSolver
+from smc.control.joint_space.joint_space_point_to_point import moveJP
+from smc.control.cartesian_space.cartesian_space_point_to_point import (
+    controlLoopClik,
+    moveL,
+    moveLDualArm,
+    moveL,
+)
+from smc.control.optimal_control.croco_point_to_point.mpc.base_reference_mpc import (
+    CrocoBaseP2PMPC,
+)
+from smc.control.optimal_control.croco_path_following.mpc.base_reference_mpc import (
+    CrocoBasePathFollowingMPC,
+)
+from smc.control.cartesian_space.cartesian_space_trajectory_following import (
+    cartesianPathFollowingWithPlanner,
+)
+from smc.control.cartesian_space.pink_p2p import (
+    DualArmIKSelfAvoidanceViaEndEffectorSpheres,
+)
+
+from fixed_path_planner import contructPath, fixedPathPlanner
+from utils import constructInitialT_w_abs
+from dual_arm_cart_pulling_control_loop import DualArmCartPulling
+
+import pinocchio as pin
+import matplotlib
+from functools import partial
+import rclpy
+from rclpy.executors import MultiThreadedExecutor
+import numpy as np
+import time
+from copy import deepcopy
+
+
+# def main(args=None):
+def main(args=None):
+    # evil and makes args unusable but what can you do
+    args_smc = get_args()
+    assert args_smc.robot == "myumi"
+    robot = RealMobileYumiRobotManager(args_smc)
+    robot._step()
+    modes_and_loops = []
+    # you can't do terminal input with ros
+    # goal = robot.defineGoalPointCLI()
+    # T_w_absgoal = pin.SE3.Identity()
+    # T_w_absgoal.translation = np.array([0.5, 0.0, 0.5])
+    T_absgoal_l = pin.SE3.Identity()
+    T_absgoal_l.translation = np.array([0.0, -0.2, 0.0])
+    T_absgoal_r = pin.SE3.Identity()
+    T_absgoal_r.translation = np.array([0.0, 0.2, 0.0])
+
+    goal = np.array([2.5, 0.0])
+
+    ######################################################
+    # 1. initialize path planner, or instantiate pre-made path
+    #    and make that a path planner, for the base
+    #################################################
+    if args_smc.planner:
+        planning_function = partial(starPlanner, goal)
+        # here we're following T_w_e reference so that's what we send
+        path_planner = ProcessManager(
+            args_smc, planning_function, robot.T_w_b.translation[:2], 3, None
+        )
+        _, map_as_list = createSampleStaticMap()
+        # TODO: put in real lab map
+        if args_smc.visualizer:
+            robot.sendRectangular2DMapToVisualizer(map_as_list)
+
+        data = None
+        while data is None:
+            path_planner.sendCommand(robot.T_w_b.translation[:2])
+            data = path_planner.getData()
+            time.sleep(1)
+
+        _, path_base = data
+        path_base = np.array(path_base).reshape((-1, 2))
+        path_base = np.hstack((path_base, np.zeros((len(path_base), 1))))
+    else:
+        path_base = contructPath(args_smc, robot)
+        path_planner = partial(fixedPathPlanner, [0], path_base)
+
+    ################################################
+    # 2. construct initial T_w_abs (starting middle of handlebar pose)
+    ################################################
+    pathSE3 = path2D_to_SE3(path_base, args_smc.handlebar_height, np.pi)
+    init_rot = pathSE3[0].rotation @ pin.rpy.rpyToMatrix(np.pi, 0.0, 0.0)
+    init_rot = init_rot @ pin.rpy.rpyToMatrix(0.0, 0.0, np.pi)
+    # T_w_absgoal = constructInitialT_w_abs(args, path_base, init_rot)
+    T_w_absgoal = constructInitialT_w_abs(args_smc, path_base, pathSE3[0].rotation)
+
+    if args_smc.visualizer:
+        robot.visualizer_manager.sendCommand({"Mgoal": pathSE3[0]})
+
+    ##################################################
+    # 3. get arms into comfy position
+    ####################################################
+    # print("putting arms to a comfy configuration")
+    mode_1 = AbstractRobotManager.control_mode.upper_body
+    loop_manager_jp = moveJP(robot._comfy_configuration, args_smc, robot, run=False)
+    modes_and_loops.append((mode_1, loop_manager_jp))
+
+    ###################################################
+    # 4. get base to starting pose
+    ###################################################
+    # print("getting base to start of path")
+    p_basegoal = path_base[0]
+    # NOTE: requires passing a reduced model to work because crocoddyl needs the model to formulate itself
+    # robot.mode = AbstractRobotManager.control_mode.base_only
+
+    ##########################################
+    # orient base to look at the goal (yes this should've be handled with basep2p)
+    ##########################################
+    # NOTE: gets stuck on real for some unknown reason
+    mode_2 = robot.control_mode.base_only
+    T_w_bgoal = pin.SE3(init_rot, p_basegoal)
+    args_smc_1 = deepcopy(args_smc)
+    args_smc_1.goal_error = 10
+    loop_manager_moveL_1 = moveL(args_smc_1, robot, T_w_bgoal.copy(), run=False)
+    modes_and_loops.append((mode_2, loop_manager_moveL_1))
+
+    # NOTE: alternative hack didn't work
+    # q_desired = np.zeros(robot.model.nq)
+    # q_desired[:2] = p_basegoal[:2]
+    # rp = pin.rpy.matrixToRpy(init_rot)
+    # q_desired[2] = np.cos(rp[2] + np.pi)
+    # q_desired[3] = np.sin(rp[2] + np.pi)
+    # q_desired[4:] = robot._comfy_configuration[4:]
+    # loop_manager_jp2 = moveJP(q_desired, args_smc, robot, run=False)
+    # modes_and_loops.append((mode_1, loop_manager_jp2))
+
+    ##########################################
+    # go down and grasp
+    #######################################
+    mode_3 = AbstractRobotManager.control_mode.upper_body
+    T_w_absgoal_1 = T_w_absgoal.copy()
+    T_w_absgoal_2 = T_w_absgoal.copy()
+    T_w_absgoal_1.translation[2] += 0.1
+    # print("going above handlebar")
+    loop_manager_ik_1 = DualArmIKSelfAvoidanceViaEndEffectorSpheres(
+        T_w_absgoal, T_absgoal_l, T_absgoal_r, args_smc, robot, run=False
+    )
+    modes_and_loops.append((mode_3, loop_manager_ik_1))
+
+    # DualArmMoveL down to handlebar
+    # print("going down to handlebar")
+    # T_w_absgoal.translation[2] -= 0.1
+    loop_manager_ik_2 = DualArmIKSelfAvoidanceViaEndEffectorSpheres(
+        T_w_absgoal_2, T_absgoal_l, T_absgoal_r, args_smc, robot, run=False
+    )
+    modes_and_loops.append((mode_3, loop_manager_ik_2))
+
+    mode_4 = robot.control_mode.whole_body
+    loop_manager_pulling = DualArmCartPulling(
+        args_smc, robot, path_planner, T_absgoal_l, T_absgoal_r, run=False
+    )
+    modes_and_loops.append((mode_4, loop_manager_pulling))
+
+    rclpy.init(args=args)
+
+    executor = MultiThreadedExecutor()
+    node = SMCMobileYuMiNode(args_smc, robot, modes_and_loops)
+    executor.add_node(node)
+    executor.spin()
+
+
+if __name__ == "__main__":
+    main()
diff --git a/examples/cart_pulling/technical_report/cart_pulling.log b/examples/cart_pulling/technical_report/cart_pulling.log
index 15cc14d..aee3289 100644
--- a/examples/cart_pulling/technical_report/cart_pulling.log
+++ b/examples/cart_pulling/technical_report/cart_pulling.log
@@ -1,6 +1,6 @@
-This is pdfTeX, Version 3.141592653-2.6-1.40.26 (TeX Live 2024/Arch Linux) (preloaded format=pdflatex 2025.2.22)  26 FEB 2025 11:47
+This is pdfTeX, Version 3.141592653-2.6-1.40.26 (TeX Live 2024/Arch Linux) (preloaded format=pdflatex 2025.2.22)  13 MAR 2025 16:38
 entering extended mode
- \write18 enabled.
+ restricted \write18 enabled.
  %&-line parsing enabled.
 **cart_pulling.tex
 (./cart_pulling.tex
@@ -282,7 +282,7 @@ m-super/sfrm0500.pfb></usr/share/texmf-dist/fonts/type1/public/cm-super/sfrm070
 0.pfb></usr/share/texmf-dist/fonts/type1/public/cm-super/sfrm1000.pfb></usr/sha
 re/texmf-dist/fonts/type1/public/cm-super/sfrm1200.pfb></usr/share/texmf-dist/f
 onts/type1/public/cm-super/sfrm1728.pfb>
-Output written on cart_pulling.pdf (8 pages, 288786 bytes).
+Output written on cart_pulling.pdf (8 pages, 288863 bytes).
 PDF statistics:
  131 PDF objects out of 1000 (max. 8388607)
  81 compressed objects within 1 object stream
diff --git a/examples/cart_pulling/technical_report/cart_pulling.pdf b/examples/cart_pulling/technical_report/cart_pulling.pdf
index 9c4ffafbdc6ff237ebdc0e4f72fd896447bdadc1..eb4a4e10ca10d8d9554aeadd889292a37fd55baa 100644
GIT binary patch
delta 20235
zcmbPqLGb<s!3ipiX44mXGHTXejquLD?Iy7AdH4$tCN=MOpJqnCRdMB(FiR4(Rk2*N
za_Z4pkA%E0wf%l=z1et)N;F@QMpCHwyW+Hcb7$tKm+q_iep)?J=aG#_;VhkLuUk77
z8=Ml4oYS`HjQHuRkGjhjzIniIG%e2D%=hlSz~istw4;A2eKs?>G|Tb(zwJ-u73#Of
z94U-gw$fqcN*>k|{4RoGu8u+aQ}=#%eJ6Q?Td7Vu|1ZO?Ti4b)NpcHLi)5=#(fFKl
zFZkg+-nX4kB~4vaf-cQwoTW0w^Vt`+jUtI!N0dAqqNW(hUH)bCjg5Ey3F#Y;*2GL%
z5SX&VkZEs1-JFYkH~76KR$ae#$E=Fmiu>i-`jYsYyQH%wh;jVzjA$$Kua2C(V6XWy
z$xPk6u-Nq8RW+Id-4lYQY?$DucYibUhAEyr7Iz{y9S}IvsjRri->$=`Y_-$`t)=EG
z{>_VGKPH;`sI_i_+r`ehM_W#C+R5Eh3_BQ+KkwH;S=$B0fdLh>rJn6M*l*k0n<b%Z
za>~d$cT4^H#Cox&gHL|{b(kXJqu11G9&!21!HD~bGRp$h>MbTck?{-{&?=S)RgmqQ
zzV!5wXy=}XCvIqTtx(bPw`gN|R`ro-6|=N@=k_C8By+ue*c#UBt*g$us(a~l!iw_B
zTE@qoV*5??Ds{{SCM9@?r|mAi^XNi?SxoS9=67s7nl4A{HLc!+CQNFqy%2g=IM+$R
z?nfru&3Nqv5C8S7e77?6_O4f%M`d=eTE_O`boc)oubv!um6Kk2DC|B@)`eoDuYJpO
zK1_M^qiLd!um8Lmo6<eL|Cwxb>HM#}G}b2X49ofZ+%i+{3Pt~aJnbOIlSIBbpM?)~
zpW*KlK2);V!m44mam35|^%H%{wj?Z2V$}b8cDwiA2F9a#vHiKN1q|u`mZj`y|13Jg
z_<ii+zirM25<U!qHxJI;D1B$DV8iMYn<hW$`BLH2HIqly&orlLYo=850lD<~M%!fA
z{N<y!9X9)@IAx+p+q9qOM4gtcQ_$nq{8v8J|Jz=ksdE<2{~8s2H*8L|!@K&5#g0i~
z%^Ur#=gGc_5EONk{BrHe%vyEzr*kGhUzHv*%~9#541;gE!{ZkrHe!2QOqSk1UM8wA
z*(?2Pf3tSVKjS}><ZCrf+2~9X+V^0+%bE52B>ZaL-(>IE@qbfQWa{PH>pQ$BeGre+
zoh5f%x^<=1eMN&sAC&j3-MLm;Zd1i`g?h!$&A&IwnQh5hd@J<)?}|%3)1+4KN|$4I
zEC0Seiy@DReOLa$#gC7!)HyUU(fDO+@A;73N)r2D&C9WSRMu)8w7#fbphM~7nOSaa
zyasw<8H;=zpLV6~7R=3-dUcg~ZEW=BrPugcs&D#Ed-Nzia^1rBl^*w>E_)X#_3nY$
zj5i$j>rdv0d}1?uJ#AlCSm?BOZByf94=<bhtNqrjvehrETx?t)e$8MJnfmUF%RKoC
z-rs9iOPKuP-p#!JxxK}TX4N+jzj*Oa;4<0f#OPljux{JZ%HrGntC|i?-xU#6s&cWU
z_wtLZ)ya8I><%lMO%9c~Kh119x<zt%<blmcH#Bxc=2iTwS5R2EKhV~6R@G9SX%9SK
zGD)^+ZM_=yQR4Te^@hQBP78%GFk7%Qh256l{c4#}ko}K$`xR`MdQ@G?+20!P`YNLT
z`|l_Jf9?ko8)iPe+P?a`$+x2n3eV)b+@n722tU@l_n(-R^PS%omNw>AtP#)tt+-Tk
zS;Nn)KrDQx#Md>gr6tkEsXO*-f2rR0?2wJOBfCIbf~?`?%VDK=W0syNkP??J*u*>i
z{AI=s&%U~Bm~zdZPhB@LY9?Q$|I&o1A_dh?--*P(v$<r`(=8(*IL|cD$WX~=@9!No
z-}T*Xy0fN#e84Q+ypy$kCo5z7PFAMvJ6V}oS1_BJSxi5;mRXG1(8z4^MOO9t+)7p-
zxw~Sz@7|qj-@RMBy#3KS`A-ku1>9M?BfGG?Yxi#F!g4N=+P(j4zwf*ABz4lsX<Li0
z#iggKrMGqYoML>k>fzIjgU5~>J9COZV0ut+N^*KC>jtA@g@C|L>*yIfm}DJ<)Yggp
zVbJ9+ZrIhT+|VogLHtmg1FJxJ!IvVosQSp=Oc`fi{NrTWcWdSh=C_UK8rJib@x5~}
z&Td$+d-rega&hytbo0b#`(0m&i7|v{b2q47ILD;0Zp|X))hfITriNW&@rZ8FndAG0
zK`U=rnS*fy(}gokPm&zjH<T2x-S~T(afW5Xna2N*o*eqa&p2Us>*m+-Nz=~pePeL-
z<PFrUPgUh@SYpxLW^sTeg)d;j&uG4)(ue=Mw;2>~`yXE3!*Kn7RGHfUtv>&=|C+yk
z^E1C&vay#pfzPCvbw*SKqa%mT|4Y7NDK8lw{42k4=j=!OmHS&_{(WM;@bBsbzJ$EQ
zpW<)R(wC<s<ufi2E#FXHQoOZ*O~YzNv_&&R7T-6u1@-?I_`GQ>i~Apc=fCTTU9<jN
zbrebY8g6;5zP&*&$ibhxSaiYb_?5c8Z~l3G@sBzE=>G3T8Hs!)oBx;ZJsNNO@7;=>
z%qPyh{;&6QdvCp1%EU>Nr-p^4{&>&uXYw?bnU*t{9m5z(ukVkVWik7|`3L`~qbxt(
zzx>HR^S_U9!`uHqyXw`}opbPSkkkIW|5)?a`0MpL&Hvklgo{6XNlbeDl*yoQ!)B%%
z7XR=4u(<j6U;Db5vo~*MJ@Hlk;Qw!*<p0li+_d4t76a#q=rRN0A8C`X34J>pzbRuI
z)2zg@TM?5JXY$shzIwh@&Z^+TtvfFsOnTtgtZ<*XvqJ4e$cyVo``*MF@2vOS!+PoB
zkrbZDmV-tIi#c6er`Dgn)}3{5{x6Qh+AG%o_?G4saDC$Tb&{{M4{CjxJSTEzx@nPL
zs?&>0Ifloc%GO@UxXrnmn_nT*idm}1=PtiWw{2V2mdMu^4rvEZe16xo<HMf`@gCPh
zez;w0wQrK)KUDf|XU6RxWn#By=B2!UQ*Uh($Dq5)X-ieRAg3YIRkN1z6)A^qG0r$A
z=k@)_G+vvl$NYSb#p)|YaXFt4+!pjM#w^xnvh1dhN#`y(aGif|^;qyu`Fnej%1jUL
z<BM&>9$a3~8+p$4VUJF1wDyE{rDIy^yM;IQdM=M!zUMK^{Y9R09&Pb4t-CJ~8k8Hv
zX*Rn)roefpTIY40o$kkaQ*$3kUGLrPd%Z)Z_MX+ES^xR|&P)ltn%k0l#O<Ba<Snl~
z>eL;yzJBET{CC5C({IyD<Z8OL8dldDFm)X?iS^Cff9&46Ks(OOvu|{~i0l+DaVy#;
z6+iWCMNK_h;lZg3n^sG|o94r}RCL!y$;0o}3SQ-~|E^!7n*3$k5%FEGA3m)=#sB+{
z#O^x^I@4~fJfBr{P{_buw@~w%<+UB5bAMIK_M5VAK6!nq+r#Q-#{)#}oZDGi*<|mg
zA!`tKu(9tvPvnVddMq>kOg*D^(tP^CkLkz$2Ata#B!9H`t(4EiU;7wL?Nz?*J}x35
z`|$S_$p8oC4U4_@2-W{@3;7}96yP9pJ0Vkb?%KLVwkDmcC2v?ee%x^&!6hi3|HG0^
zy*uWn9On4YGwIf!b#ufO-moc7khyC7`p@E>jN9{{INwR@@Zhp;e(GLYJz;zHdG_^p
z+GX+`GFSPo{k59?Q|7BnmY07Cz7h^9fAa3|dIp<Vf0ruf5VqM$i*|Tq*1N>7eKdEY
zS<U1}Wp=BpT$X4?8g<`|)7kD@zq!!j^5KOK@*kVcmN$#}WYF*bP-ZskO`9*7GIu)l
zmhHR35^>~F$dvh!^&E2!8{EBG%eDV#bBDgp&Y)jq^)ILV47vR@@>8v`ver(XIYrw%
z&E$?xnr7h=vEKg_dpOsdlc%khzl;y9ci(F&p~58Gu&<?Oo6Njte;<bLE_&;9c~N(N
z(>u;jYSVI;CRtzDcu%<Gg_m1Y$-c#QFAp?T-I_aVcSguO+v^F_kCsh(sQFuL|F!9k
zzm(H6uK(&$**xK?&iZSMdA`{yY`#$2#@l+4UvTEi?dztz6H{&KJ^Jk5vg>Xe^1`3r
zu9@pnA0Ga|cmJQJh_|yk+|T8RmOQ;zx^#}~-W@`R=PFNNFL36MTQyhfb?$6~<jlvP
zeO6g&S<b#v;`4jX0<9wFNk47-uIGdv4sJi~%V)7JD{7%e#9f&+%wLPoJ^b1jr1H%`
z&mi|U%Q*o?-^@KOt8Vw-RW|(7ux{bPKhK+gzIhk1tUt5<)Zx!P-KTF(-mcS?I?Lbq
zR=4kF#r@`u{ZD%i2T!rNS>4e0ZQ5z^B`v;hcP~&3ci*|=;u4iOZy$Zjr1OVP{|M4Z
zyn4np@NwbSGklfYmwfq6Gpgnt<Gi@&_2(B`PyT3V3|zD|Ia)FNM%#Iru3sr!yz6I&
z7T$ld!&utabBXrzjO+EEdmqbZy=OieXmzcB_uqbPqu*6OWjwwVO}N_oWv$X*R!Q!g
zJ+F6GwpLoi@H#6BG;BZf;=Gt)s;A7;GwYo0IEOa-d9R-I_RppGXyg3N|2FLWyzf@v
z-lTckcf9?^$i8{w>4gmkx9nCrWVb+t|InJY&kYM^d3@q)bNP5S)+Oe-`2Tv9?>t*o
z_U0XGTpb^}d}YF<yCJH@38~q$^Wz&Oa(ABG{4sO#dh-pvMK5*o&v@lpiafB(`7Ylq
z`|#1uOLu(UOu6}e#>=lvHRW2<o^efWj+YULzx2E_;H}!yl9011=Y0<8${tEGmc6vF
ze)okb0g^l>0!v?XJo;mG-qxh#U{9F(sd}#cRjMzNemuGSI^yls+u1CeIQe9yw+FUA
z)X?<^y|%HEv0gOm8NbEK*V)lKizC<n7ny5%DQt$?t3?q_UO#^p$cSuu>QQC<`=zi=
zwZ+w^3)nQ6mmjbU3qJJu<3hzhp><2=o=wsF68@NP<yG%n9P0!RPcs+l*KjN-Do%gy
z-6wdk{;~Os;=ArI0@{DxTC_JM&vf$3w;#G5>|B4a_tL2XzCAh_$y&YEKdxTf?cO<c
z+vJA5%FD6@wck9@eWbR#P-JcKr=FrGf2M{oNN0LVN8Dt*s&-Iw;l1foK0hvW>sR9U
zJX>W_nxA*${m#v%sp+}<=KO4Z@p@|AXMuGKI2T|2q>}WnUbTGxR}mM@vop6Au9g%&
zD|-IE^rK*l#pbQ6;tLb^g-WYV_Wj#d-4j)1dCTO<4QIAx>wYrq(JnJc^%HV2WNpvP
znmlQ%Kx@?cN0&GKzRG6PXU@C(T!DY8zMKB}9j3F_h4LhcJW(!Qpfl@4=jvIGu9gYu
zAC_m>eD~;I60ZI$cVT^YFmuzE_tqC@b%^>tkKzpV+AKfi^G%Trlj56L;{}yeR=?KR
zyCqj_XRb`TsB(aWPf#tB`j&)c_ESE_i`po6b4;1FX>xRh*oI4z%*%L!7!rPaCf|50
zw5`JS!iK-iXZE|OSI;{qnVtRY++txNhYhCk`K$uJI;EnuKUx}_@APV~Z#V6ERiNS4
zo?P~qPf9OW<A=qOpE;W}SNk2F{9w6bV3eiW$N9$1?$>|bQ*6|<ka?MQVWN>*^i$(s
zeH~l7PJWZSz-VyCTaQcQ1K$qw2~WQt@q6}4;C6rTp(3wV$uG*c%DwvS+48jRJ~*Pt
zEBa+$vIm#+y<3$9UuxEFTpLiC{-fUIxvO4lY);Cttu|_2{IWbUx1!^Um-Dl;#l4tp
z!*^INc3Tangw7NG8ykGDu3Y`~%j$|LukST^Ec|z`$6%+LNyWOtga2>E>g-dt*7E0Q
zZoE;~e^%A*$V3m_&<CAN*H&(w7m{J&pRz7;rL+(4tv*}xL&X>CHmhv8v3}yR1E)7$
zte?p4^Rx54%Dw~<#m>18%ig}cvF=b=m|$~trQ~Lv`11){!_7GBKQg8)_kOrm>ED^D
zmVD>qe{7A{?NjPDd+rj<EuG8o<`&n9Bf^|^>6(@~HOr+JE_R$V`8U&9#)HTIo&D6f
zEl+;gxgY1<Qg+=kn%-qQ|GATt$Dw!gelB`&BV2*0{?z&RrH-0fw{+vrF*|Tnv#m;0
zFn-9#%+9xbUsFu<MzPj)n_L$rc<Mw8uc&7AP5)!{@rB*C&+RjUoa+icA76fZ*30c2
zOY2W51e&eelkeg4WxxEFuK_;Zaf^#T-Ck+WqOi{6;```K<=J8)Y0Bjv=iU{bw@UT;
zmPKA}PLk7K%?YTVDDfk>?Nw2&+TA3@Dr3nPFZ^D8ywUOU<DbacJgK>F1Xa&BE?l|#
zXfoe+*Vru=O)qgQh<P{v`n_rGJ-Ph_U9<n_u8vr^X&H}<^0~;ntqP%YUp<+yGDfFq
zPT%upeU6Z`@82F?^KF)UZE>jAoZYWV*Or@JT@k)S#`I9q4DbJSQ=ZjF8}FLvkgqWD
zwa~x2e7u6keEuA0*f!_k9%EOhJ<pnF$h~#1KmF(Ug{7SL_UQ56IQa6E-}MG1v3;c}
zw>@)yPV-wSuxUzJ(ubd7syQ3aF#1ft&~1|T=ahfn^~39~JPl`hZj)&=vo!I)=OHn*
zNnakB7T)IG$#U5)pY3P+JCP0H<`wnE%rfE?2g{fHFPp@%PiITlhQA-Pj<fE|V)b%#
zvzB0-meb8zeY5LxwAZ06r^EAo^Ikmk^a;*7d$rYSvuBc5m8jF9cZ&CNWZzs<I+GE*
z?_KyaS^MlS_Qv&gTet67`toz$uQf|I=h!Byl=;}cnmSGP(c|2LePt><N1tS<R&0_}
ztY@wCR-9tXbn1)5N%hVJimVs)z8&1XVCjz?4<hDu8kGb}=4u@Fd-CS+=^Hlk=a-#K
zU`<fr6Y2;zeI~m(Ut<=pucw|6E7t^>Uw>U59jq6QR$Xv)(zY$TZO``wd`X_f@^ZCg
zh|rP380lB5r)jKwIhEu0xvnXE4-6OmF}kmu_-Nz$`k46_ly`CzI4Wn@woQJ0Vu$BM
zr3nSgyeD~G;8u8_dSQv6^ZvT)Ojme0>rcNopQsTV{QQB)zn2Wx>!!D^Ira9N;CJ2M
zKZ7I9RqfpG?avJ74*i?;K0Tu?eeE;rl-V{v5?<Umm!!aRM!cpn`N58J(jWB9`(OPr
zT2puG>LSk{k8j<rS5u6xV!4~TUoUU_`z3QfzGhz~UcS4&%l@IkQCmilbI&W<51#K5
zDixfl8Xo06-}UBXnZlpHqNh1rJ*ekv6XfT&Y<ckC^%=*0-ncKQx;Ia8qr<-V3x#QQ
zLHApQxz24BwMt+}m6*u=PA8%}{nQQ}r7Ju}`%<{8qeR~R<>~1R?yNUv+nvAutO0Y2
zj>Ocq_dj^IH0gOCE<ag4*WhKQN?BkW(<#}-oY9-=?=AHYUXd_KI(p}pa*a>o?-M7K
z?(MS_+`cvHxfI{Qy{=pb1Ez`E-p=y7!yqHa>LbS;dbLI{@Im19@G12xUj*K%wNyUo
zRmPU8HpQ{%WA=i$nS!fUIhcN{?>@|OK<luB;D$3jT~{YWC8^2X^ghr(LGhlC-kkjF
zxz3xSujg)&>j|Iy>*<X*&iR?<K~+sNij(RNp5zP8p6&4TU#0o(9(DdZ`&}3Pk?cLO
zr)1lQ&C?TNL@g5zy3H=zX2berUeNTHymC)(sGc!BlQc#ChrylGiFQVjwgyvYtle0@
zH&34Twd9QO@_*Le3^(6u8u(v0TpDP^X||S;X=b*jyrlZfq$@A?2s!<p=j^P%i&H7;
ziiIw#*^F1;zxq%3;qq<YnaGlq&>91crh6e_d;58Qd<ihCV|>5K(c<f6_pO($4Q{RK
zmfO2__gia;^3dYT>EBk=x-P$NEz&Rj!0Cv*TRm&2*q^6oE=P9PuJ;V={t|1eb=%rz
zi&WCv1FM|3#EBehVBKhRVL^>omXA(<gZ9-unw2KCjVArN%&XXSGUUY<g_tt?scrF(
zDcRZ(H|>b?%EPwzm951Yw=^nw-d5|q9k0GsX{S>D<Hb)HmK*Gi7kd(<RCaTv&h{<6
z83r{UOCsupm(EvAWwsHzzdK=T(3JTXBe(eR{pQJeK3}!a^tq#;+u4aBwWt4t-Cz01
zdEVcP^R~QFX0cf(xw*Ff&cR<7Oc`H@gzM|bn_pV=^iofXh~BfT^TMa2H!OFTKYPZ?
z^(<fh#-I1LGYhFNyT5!9ceLr&W~pYz+{<&hulkEfZ&;<f;zs?$9ZOliKA9WGb~{{r
z`NiMi#Y=Z>t<MvdT&-feNNA(t2B8_bW>T+(JMJmIsg}Q5&i=ecWvdhKiq*-c)q7X>
z6}`-7{r}!u;!um`n&WN{T`ONsa*vUHXR=YwY^RjHs+`W7j?N_B^Q&g}C>~h0_fA~l
z23?;`JPfn8ztP{cP<=yxQazjXTy4q2zk))!qqh0^>+bD(bj^5;7nkXsWs-e$1&@m_
zJXDGJ&~i#|;)X^1svk4b`eSF-W!63FP;1#|y(s(Tk%sv}f(}OlGA5Wseu&%2m98te
zJFL*rLAXOF;PS@#qH?R`nKt{q6L9s>Ihy?YjQ7pXi<uW!n(sQ%S@M<TUE9|BxnF%3
zbt`P%#hqlc%Quu)Drr{$!<A>!{4&Ddg=^B*%5P|V{XFHPN^*0_YRe+ON9tLZBK^*V
zC0%+s>8?rFb=&Q$%LSENR{fiGa})F4i$_mKChsj<zdOr#Md;Fw%K_6*&YbN1qlD4#
z`OTxQ%hv?|IrzFNRC}g!x6{h2-Q|;xKiycr{BMQ*3MtLM<*e128=r1D72SXTlZAL#
z?k)XVXU*bQ4|qew51rg`^jBW)skh|{Z(=8urfNT_(L2J_8LRNg;e^wf0^iTvzal(N
z{gc0C|Eo%^v{%TY?fSDlc`8~md!L6+EHle{TCUn|oG~H$;F4bFFh1U>rxm`Id||oi
zN%vo>)X#fcsQe{)We1Dg?fv3^qgE>)Rhr5)d2>rb?9;sV8tpalQv;{Chi`amv1ISx
z43E&aeOGugte(D~xcj?W@|WMsJX_u7l*nX!%rkuwmpfPg%`YWBW1ksnhb7G(Okdl^
zZNGg=_WFaloohaQEnc~O$)(lnV~n?!G@mRns$%}?xlL+KeZ;Eb$Dw_}k_VkrrGo{f
z)ePOW!gzUhn%aGpauG>={%0uz+b&fHR=X$XSmwXmYrn7VzHnOqIWw&pPDc#??GC=N
zt~LMZx`rbz<{60#WOs=6{QH{rYZ{|>62nj1d5a>-I7>APr~iNa{bXeNe#2K9)3-}(
zlYYu2?6l?I-zmIBIZE{ho(5j({e5w#=U%;tcnPU_ixaJryC-_6-Yqu^I&-`^HeiAI
z@gLihwaU4+rLIh0)#R4Pz};14>SZ!-(M=6Umpr}Vn<u_cJ-@5}4wLKaV;A0C-n1~3
zNsc|C@(OG7u6=R~Zu?eTF4;J9vJrP>$hI@?w`~lQm<0oamrV_Px2NYjN4@R)hNHsY
z8$@<xrCfJ3<2x6;Ys#w)mRtH>CP?y0u$E>|eyXzZ>t87;_VTc=Cmq;!e?GabESV>m
zS-DiKZ&v=+_US=WJ`^iEPM&nDuQK;>ZGCg^>&$gecW#bMt;+l;-uGR2ny`TU^q2pl
zf2&TE2v=a@e>;o8{P&R;rw!~1y{kXeTZM(5WjcE8;ECAXe>9D&Kku~tcB<<5o_CKM
zk1lXr*2h>>7OphmQ#xzcv<bfD3gX&-OX6G({!$m*BQ~WfgZ(m(tKOlK%Ma_~51f0)
zzVn#nXUl(%KYrbAn-;%tzsvd)u1uxh6IAkYlYiF~hdi3rF=6w|UO#rp5Ra(EPdQ2!
zOxRX`J$&(=@QV+-Yz~V3*GpTS5Ip_g6mC<adkO)Qmqn&&D_=?8oqBBc3TC%mUQu<6
z-c7oD?b%EJ>$$$olhrv&Crt`^a(Y_0<UG@wM>%SNI*V<j^<#3`y=R=SNy=?MAJ@#v
z-hbo8s>kk!HP3{_uUq$CtvB<LiM-#(xH9FlCbyTdN7mPGI8w@?q>|0F<@Q~!xAyTy
zkB>@wS_ts7TF&}D{Zd{2%ewA=O~xNfg6<z%)PAHmF4CtfXhqw+g-(y<8}?Q9c0@R|
zUvyNg3ieBQuuHRl!_Fn1tMaE!e)-r|<Cn`On|(i|_~!}!_&3!>e*@o_6a3E7?lXM;
z%+vg=zL525ywcyo`j0ZbQSCXE%idH*d{O@1k@F`pqt`<+Xswxs!Hc?Jw>gh>53KGf
zF3w+K6zhB9&~>Ndh9T`i7E`ZpJu-o1U!d2gJn7D!%jTYJuNj(lW}43YAh3tGY1thO
zwSZH{ddqL9e^eI^PQD`Ed2;<_S*f@uO1-Cwti+q=c;$Tyo!q}ZWLo`G;f+^AR(;y>
z)O*L_-wTVT+=!}jyb;=SbX(KvnjfBDW`FPBdvZcltx~UuTbBAx;b)6yeE7HI@W*eV
zj?5ksN8Q_gX{H>U>Q}QsB*wG0SzSK%J=eSM-<LnP_*Y!;;^Psk_O8dT^y*u^zu!H|
zow*|Kg}u0k!JJ3eE$vD^NMGPw)KqUNooP_PlGrS!$#$nNJM3rRO~JaE8ZT{24W;e2
zc<=cBPUE%y8^ai%{)LN{#{1uheKtwN>wt>=RJ-I&d+u)RU&x`KlsGSH^|DP_(_)&N
z`LY8&rzo=u?_c=PU|Ij;3AwALmafQ{WbJrh?%ws!qaTDY&nhkzEtcFo{dVpS`-RfK
z>+^Hc1;frBwJiLooAfRA$K?we1}5CXUI(wwjjHD;efwkEvt`N`ZwJ}Uf8D>ZKydxl
zgCZG@FYbM~?Dbdc>-!Z~?jCr#^Mc*k_?VRW(Vy1rXXTCLGqcF+dG@^K?DC!5D!JKz
zf9~FVM=XlDO!RYkg3=_3+T^d?t(>X;J<iE>brPQShZL=uzc2Wh_|Ccc$PP0TkH3c9
zFKU+^oqnKO-?Xyz!K+o9<Qc`Drhhx&ntN#SQ&C~Lg*NPM^}G7B_VVy(ePeyJvuM*j
ziNKjXS(=yo0{=aHJMW51mt}=ehTn3gXCZgbtL13CTVoZ^G$-)N#4X!0=LeiTXSF)A
z=h@xm@6R8X3hl3-^r7i%_8%3!nM%jGP2XSc{KI09y3(Tatich}hH9Zbk5z6(mpzS0
zJYTxZjwj=OOVC}7Kb8M=x<XbIZS^?0Abjh;3C_%J2e-6me~zfxwnu^?u5W$*?~h+@
z^k=XCDfZs9K{g_U_v-B1sXAxsIUnutTA1GzE$$u^UhjJK{>x8C0_rpUZ=Lt*%a&v9
z@R_vYaKM?!_GvD5a!)Lobo(wAWbrRcIo%<%zoTg1lDEt6D2JZm+d8kpaQf$z%mdHU
zs`fn;Dm~eyQr{9D_(aTEXSq%38<SnZD^9vwo(w$Ba`xPn%+r(Jq_>?ldRf=oU-X8f
z>&4ssnGciiWkg=zv)8%scVj?AeaM{io=ePExE^48f1tDNf3-pW--m){edI-h+L%}G
zWDSYyo%VFOLWStmci&FMKPy?lpy={!MeDK<_6K#HlHAdrzmBPFyz|TWruV@fd3o7e
zP1g$lY?!n;gCSmcZQ7P2zqT%B(wzRg-1&#(ibdSat1SiAeK@+>;Q14_Y~H|n+qSOy
z`E&j;26WzXd%+RcW&ZJnT}8-+dS~O3Q1g@bmxbJ}ES#G;?S_$+{uT~9-TP-JI0^Ku
zb_lu?-|%RI+^USyl3Q}xXFTq%ntYnebKUcZS((>Ya5T({-ShkK<T9rxKEKo*@0>1{
zp3WxrJEOKFg=4aeL%oHMHv?a`q}U_n>2vBQSJtarsjV?y&CqN&`GG-btp3cer_P;p
zJI5IGX@$v&Y@VWxH)~IQ;LhG9taQ&|b6Urh0|v(zT(i<P3hSC{+VW^ib8_)=0XB(E
zruiYWedP@vvClpJaBJ83<!&b7b=5)l_Se{SoXgoTOaA{nhmXtC1Ww&G+WX|;ng;Kx
zdp|D8+_uoFufNplyy2L|r7~9Lh1(dTY>v!|+akw){@+^d56qlpFZI?qC9br-p7k`y
z_Rj@(f$|t1#guKcwq1Sb7+Uk&aaYLW6`A`)0_U#TkTNZ+OhS0$Qr1tGgrg;19`4)|
zJXO1~rN^iF#@%>}lb0NSXhqL%+jPk7ROzWDCiX|As$6Swo(pQ%*QM)a{1JM1{f6<W
z4~t!Yt=+D4QqizdW&M_%n^|8NQ;zdoVLg_&nD^UC?!qf)R;It-taCc`*W<r-drxug
zTXjl)wZ%KXW#`VkkbCI*;qLK+o3}Wvla)D=wZT$tUGUmF3*$X*^?a_DeWTeTY`%8-
z@rttieRHShtmb*!|64Pm={|c^{r<b3&n$ZVrzWNSSZ1loU!GYHdJolYPr7!p_nkne
zo0w0{<mr<YUAJT^&kR1___guz)WH0#TAtE}Z*{e_E`_&6=|l)EJ|lN~ufI}F@v&Q`
zRtX)-pKl-je%-%%{$CZjX!U==ie*g2E`o=r&$pk+wv)?G%;SxLZovD!lC!*iT-K~l
zYe*;&`n6|4B!jy8_MShl|E#E5#ok-^UuCQQ;YE@jkL3Od?M!?cCg!cIHkohswQrkU
z=Or;2KH`~J|KqvWs!9G*Ka=@*zg@H1^~Cp1w!*2?8>Tt@*50X|uWNN9BI7=n$n?Ey
z=5SvZdvw%1!foE2{MBBIb6Z{SdK|C5Wp$vZ?`ge;YM70n*zV~(C;Ea`s<?2vR&Rf_
z`STL3RR<iHH0^>PUH@OZZTlUCq7_MLcipZ{?kkN{nVxemP4I-Q4{wdjPq~>)f?r~f
z2F=Qz#jbm&vWKJk@9brK^0UjEuAF6+KB9KC-zi0ur+?~x9gW?5)+Y|#`gK!uf01Rw
z4%4;Y;ubc^*C!n=t9%g7b8T&kfd8xZldJbKpFUH}DX`wOe#g?B%(%J9-i1M*``uQm
z&x@!#yfr}BN$c|UCrnr4KHZ9YRn2a%IxjK!Th*EqJOUkW|0J=5Yi4+U_U_i+Y_%{d
zZP{CU!~1;ovFCJ+0+$Q<O;m`Tb8PC@r6+8~R2Q6%3Df=4TRo*-{eoi4n!~^6g_Z}D
zcX#goknznyck!_;3!im-I-)bds;KDEuiuKImp0vA6#VdBE=#ZDzu%T>i}qzi$n9QH
z{axBJq+sgHz;gXVS(mOT>a4c&TO{4cxaNuEme47J%PMsZ(h47JefM4W?LoWm7p3R_
zmAtdCsdVA2Lu^^!yHeCySRd6hKKr8jH1W~CZQEW8cP*Z}>hZVoyj5#wB_$qQGU<6x
z=+nPZM*p_7-7u{870IlPJbw9~-u<#khBK#4xz%eNa&@V~m9w8uw&e=VEl?G67u)dh
z(i8Tq`|`qPwD!m*{dnkG89Cj;+~D2W-N#M-<bAli(r|w)%imYt7LU}*4t}@T!Qob4
zUZ}NTvUZ+Sf&cn*`&lz%cC@O?25Pwf%~&a*UAH#h*ZN4C<AI#Af-274)hwH@-C>#I
z@+<n?cGb!5O}bk>9`2gNW!TYM>-c+{tkna{idU<`@2MItw^-VBeb3cLR&yr(KUO{Y
zMES-QTUIWZ@#~tY+!}Sm*&mNG>jgaBed(<Ax()SF{A>1yww1jL`|N-Flu&@}oWFKz
zV*6G07Ov-Vxs<`^#P#(M=ShcO4Xy!u8h-3M`1`M5SSK$-@5|}$4lCF1lF~Z6IE!<6
z>8Td&&qa5gZPw^+eVw>3@BHE~^Ic@0I8{3LEf7<?5;&{&$5M4GX6qA+HcV5E|6why
zy=?na+Y-Z$wt7zyVV_Hu6K?Rh<rz(HSRN@B>F_MEyXixn6UVJq^XE-FJ3g(+WIgkH
z$;3jTq-Vt&MBciV>nR@p5K$E4k~wG62Ipzc+`3)<;{3e+-UmugN3XE{W&7shg{Ut<
z$(9<Xd+%;by((6+?d@-=_qH|s?|L`wo^v($<EGoMW4{Y|9o@aF{@6y1Ex!My`x4%K
zG1RVUH!%^vS(9|`;~K$*t1`OZpSG-*cG8mmP?@pQ;rEqhmLJBancFx1skh(j@MPJA
z>S-TatFNwMo1=EPDVsaDk-KEd_K+zn!|GUqPV5U=G|f$hU8zThX}?hw&+}J7Q)m6N
z+Z$>f?{)2`)*2P*YQ4KV*gWf3%dl)bTJqTR`|XaL_ut><&#cPgo&A=3^)vb0{cN#&
z7y92xf3JILLAu>z!Jl(DAMWBkdS`X8cbLGJtT&9`_5J==XZ^TVzvZguNf~Q5vtl8y
zEpEnNlnaE?M5^l-CkJ~>_@pcA#=bmohXBvqyH2020{A*Cm$lEFW7nF*(b~wquKv4S
z<3r5?Z_%%LmC9ycUtjH>Q}L{SyY4*^KJ&H5HhwN!b=Krk|CMX=+1zJkCh3^p^<X`E
zH&gBSv-zoK^6&6D-k9RDyPH$YJbB_-ISKK*+1m|ET8{Th?@)jLb;{S4XWnH=Z4%Or
z2XfbUu-Y2zUVOvmu6U}^t%g~L!au$86^jh4*OyP?;(W7|(ePD(ZK%#y`K-^k?(O~Z
z=fpup)~xG`^s>rdJ1LcSFn-!)SD#fIa$j+Mh>FuEtKvNZ%Y$BTFZ~lDvRSG6=88gv
z#rsQ4cRY#<U~HT!etv1F#5&$14>Chs);x_oVKBoy-#g>p(O+Q`B>h&hJji8Qnw?w_
zcC{ovLc9Kv%boRNb|PwNccxh+zCLtb>gR(*(eLh-Q)d+vKL7LLY0*{3ry{y{iv&MP
zPhyr;UR*Z)?ZO-F_qIGqJ6tWpwb$`Oz<tT<4V9<PnwIbXp1HN(b!LEJ=d!~~_N?>S
z9Q@jP@ARcbnhPez2P`{R$fDcQzd3TlUXfe!de2>ow;H7%yi&i<bZ+hv4zr;9Pot^~
zx$NdFymvltbK=InB9%3bdnfI6KU2Hvj)v|0uw6ao{dtSEoa(;W%v&)1@b9_q6K5TN
zp&YjS{af)TlQwVASTgH^;2{M`-pS@kzHJWg8xngy9@9wi4|`_Rz1r^C(yR>$2KTQs
z`(8V9+)!n6x&Fz5u=d-Fj@NITBRA#2eg(6Ym#!|jo0pw%X-@S^_oXr^DI#4ufqxUu
z{t&EFV>nqqF(OQ6PRq>mR?;rPhpMB`&f45PL*u4XtL5bGWtSBNt{=7iXjF0~r0?S2
zr9Wr5zAxzFTyykjT}zJ2-R7UNq5VPgq?<xy?pwaS)*bmvE_riRx$dz`cNuw~)Vo*Z
zuRgm#u~YJ`=oCl!?j?&;&KP9ef3xmorJl9^$wlnDoi=icH6Bk~tt9(OZeK*iq;sk-
z>SbBqZt^Std1`;r`%`R7eclIOi+H-{SDQ(5^Ymt0v&0?h>)yC8>id?vdYZ&X;iNxx
zZO<?KO-Z#@Y%;EyBijG}u2?|u)E{@ZiB8;KpD%nj|I#Mkhq4o`pJe}=@l&ywW%9Is
zdA|wYuCipmX}xH|w@UKWsil8=`0Eb1X6e^wsOa7j3jTRv_r@Pr_U-UWi@&n<aE<il
zvZy4^*>f*(^j+-`;k?s-Y^o4{wYz!bl~2ptelOp0b;9<7m#1FM+PWl%iQ}SHUDmTx
zd;hvFK5Woa&)b|c*Z5*j$GXWznY#|w=EQa;xPRIv8T7#Puc_Tm^~4T$BejQeUKKN1
zBUz@+Q-2av6Ts1)dns$zjbM2WA^R2Y<u?DlI%DEw)%hNh_skRG3lw|3i>>ZoGnlz&
zUx`h6&U+V^m3q616I6s%m#N(hzPsm1YQub&CEZh1ns&3FYpkC;%`V(oDE#u04St&x
z_ZB`XXAnKjlH?)gHSI4`?ZKO(QuFzOI>cw>UHRk3VpCc#va3h-?7s8zHJYs#GSyY~
z8>Mc0U%zGZgx-WHoob@BXT?sanEW=mo3Fja-BVuuN%(a)_NNzKyop*+{5)}9OkJl!
zYkB_4larp^JkcS!`^*Q=dY<LBRUThNe*R#YV)3Z9aKChp{oT%kvvp61Nw2#2d~)yC
zsKZI~4z^yqAtv_V6Wg7`Qj8{UYxjhEWGh`rT(FyO=~8F24x!z%Bd4?$`7XMC;(~bW
z&b@c@*Iw3MFypVhqxic!iCs)VLAkP@zTVr^^-TD)?UB}uxpxm)m%KTAit}Ms{ke-K
z52p2mZ_L&ByilC|uI1cd{#TsO{uzV>t1xr)Byq`d81&UF=4tbrbV6^<zGI6ghx0IN
zmt}t`NGVY<h*5lfYnN~<BiFur>6%Uj7uhb)%DGuS;i2K}noUz!rmkDxZ=7*`*+s2y
zs(w4OZme)iHkPts4ZEDPD}PbZET!1$i;4A(QnKA5K|3wBv|loKw(HPWozEYAUN08p
zW>jcY(qACLE%sw~Olv?$>(eEEZylurMdO5~ZaTMixAc}tx}SbCMV;$BpnpGsh5zE;
zHnlPZS?TX5XImNmj_VFCS@LrN8<T0J(Q)C_S&>2hZA<s@xUWw7CvhWl<@@uc8U_Zn
zCDR|@uD7|UwWB*!Eq5^|_kIz{nKvFjJUQ)E;&=Tm%&x)(>>up5c&jDVOQb#&^OOi=
zah6Fqf9r99erwXBx98<1&bhwKbdQ$Df*Uj0;-VMLZgVzQ3;1*R&AeF~k7Sp6y%b)k
zY8-I)`<BZ8YbHJy?L2tH<B0j@xsux$^0wOCuT;osb`6ZGzxqFgoijbjdE(Qm;Gc1;
zCdgHveadrfOWuKh^Z4GI^KR?n7m9zVf2e_1Ze>!?70bH5>esh(-6R&JUilq)@WIsj
zb4EWuWc+ewV7vXw_<*-V(U}ECvd+cNglwt<g>G1=&Utp_$&Lf3dSAU^lPO3&wyakA
z^E%z6aK8onUwo;$J?~-toTMbHtV^}Ec4fQwy_unDcd8`hI{U^)RRX+cIt}k<1<P!A
z&+Wg^Sopgn&bXkcmz^#5*vB-UzeTB+5;GOn9ABfU==#(7;)UNE7B7jli}+oz-JI*A
z=@RF;|CAj5XD&@UQ}>%Kez)y^@Bd7bpMROkKJR~nP<Eu@Q?@l$Cxo;o8rJKW{(1M~
z-p?qXzU?mhr+-=}H8fqVm}NR!(*DYZ3d?%Sa}_2(&azwnzQ=cC!!P-#X8jLEJoHVb
zGMk-L`0%qmJ&P}CVab$N8oRhN-<@XOc=6gbJ<T?ON6pQ4dj$(4Z?kKEJjv}fgY%oK
z==a&b#NT&3SiW0?bMx6V!8=YJnz>>{LjBTZZ?bI`{aJ6!cOc2__o`CIZXM<`!q;4+
zoG#W{h>D(#x-YL#ys_GD^VfNfn*UzE@0}reC125&F>3RV0_p43d6JLgUVJahnic$X
z(b0+gMR6B|9$$^<_q|c}Cx3GJ^}beJy@S$rs`_o;1D@ab@m?tR^$Jt|QpR*m&VCbB
zYeBa9y<XZ|u6bTvr}JHPkH<^Zb7GGgY>#frf8urRhI!@oGe?fRH_ewllRj(R_Odr2
z+rG{1+Wqa<CD(Oz8`&;QPU5|>W$U^peb)QK8?V2bS@0n5(M-OO$G;8qbQF!FZ(e+?
zvRdrbir1!HNAFDiZKtfc)1zaVQE~k1YYF!jFWGFkBRqIh{nqrRh&3xS4_I9-teSM@
zoQ|!n{Iu33vYpaS=U?CRHYs$H@!vQ@-Du?v2l?zx?JPI8DY1w9oQ;3D?)DMxDDjAU
zhu(dkuIFl6wN*Ik&D0xe#Uk=6vh@SZUDk4?)vf(|qTt@|&<IDSm(GhC6z>^V1*z_h
zyts1V^GOQ(zKCl4{k5xp*Yq0U>TPdNh3s6t_?&>^t4+xl-mSCBy83OxnZ2Bfm%m<I
zSjo%4y^$^XNhEh{Eu&$B^o0`po!n-YOI@Sm;ynw0&+J-uOD|^0Bcr(;4_WWbe=6sf
zqIt&O<X!#Iqgvc61t#5GFyU6@+5@LG+dG=V|D9c*@w8-PjL6};E57Evn{vN?&5qx)
zw}rFZlJ4g3&W(!wQF(LEM~^V6i5JqGze}dDz70P(cVq9IwTqW}rdLJ3JXE`0objm8
zyk+VKKK{8;%Vqy(>A@eJ2GWl#8cNUme(-J4x~r(+adpOTlR0~z?fu{XaLbYxzNtBx
zk7nCzeV=G`we+Z_CX<Ts#N#WA9vr^ssp(!{&Bn~Nd-|Qi;`b$y^79@yzj^rP-1&J@
zYdmtB4xdzw;pVxw^ZCKK%TG9Ln8f_dL0hMV&#aBLuWI6zx@ij^N!;yWOyS;@rL#EO
zNvmh!6~-9(y=@^zfy<;WM@GwjooCL{8}ueI@^s8Wfm*N9`jqp9tNeOz#z}OoUjO-W
zNzr%SrS+bhmuzfeocFOu@!)RncK_E`jB3MDSiGcPsb?_0k&voC-*Nn}#-FMg8#Z6)
zyZ3yi<hu_?JJ01z%S))|>1jAqRO}(r%*s5W*yd$#&BA-u&eKa%H7}m-St-dSep$;l
zBK7x^Yo)L3gm{))cFg}6KhbH9YHG&;`<_)CCtux;4S&C)UiN6$!ac8+Z|?LeJ@A*a
zEH(X(4*T!LYd=;0d8%1yFY>GPThg6vT|LZ3rI&s(nbioIxj$NxSvPlU@-p|1t?^eT
zBpmmiVzc-_jnIN6Hk-oMym~lkHqWdyt}nUkma?Z!6nE!mXUSu@5`Eh6+ofRV2Zz6}
zz4dX!^1R~Xf*)&6TeiKbpW?gxr9sa5ZPT9XXT5q+)yw*#qt^V_Yqs!xDOuh|D+-?q
zy0WVDE3n-^U0WP!eq8Dm&tlcBsi!{pn;!hCp(Ax_t*Q~j>l()m|K4rtp8H*Qf4iWv
zO^NQxgOS=MA-Y+6=d#w`cK&+hWq715kHx7iBBhdC=N-6iIrjXO3|Yh|^|bzkjB10=
zp%S*otMAGhmt3>{<kQ%YV3nq~w(Y}db>H1KNvjRcR615Yj<vT5m=Lmh*FH}3&4RoZ
z3N>eyXVqvw7whbqKi9H)NruK+KjqdRdyap3_j=vT&$snYODzi5Rta0hK7W>^taru^
zzTDgphr*dw->g)QT|Bt#-Ja?Dc87lGs$cNZ|5Vd@p1nugSNS^q;<&{0q`x)aqc!S&
z_m5S#?xwY@shqI?g1+(A=(b%!D^l9lT%I2Bv((pb>4BEyPuoJ@9Zyy?O!e3{yNcD8
z`JxD0QlpmMyLQQWmqWHrI~aR>-gD+_53BD~-(R#QbzQmnhI8&O67?@P2C?>@+;6m~
zae|Un{g$`O{@p4+6s#s3&#S6`DLh1IW&7UmbLF^-GgdC1a(j2wzMIu2Y!%WJE(`m!
z2Ss1<U8x(Z8|rxNxX1bTb9=Wb?`D<P_~!WG?=>#{nhPl+lW(4v-Zq1M^R7Ir84A<a
z+Se+bGHTX7CCvRRaivaZ()L*HgPC_Od{XfFRrNvXfpcm7+-t79{pzRLV>U6*6!W~t
zn=vI@{Yb%#6ZrzyfBknTvWi))ce~}}@9X~Ujw(0Xer(F#^mpsqzqOO}^M2SSc*y;}
zCAK*7z(bQdzP%SY4EW-A{h3@4BC~7prPUl!m*<2UTUe?k-V2&?_)(uFb6*C_<$K?6
zO={k%bSeMb<zMy|E-dx`c@8e+$$Qf4Q<V0w)N1W@rs>+#j#gf^WVOxk&7H9`f4*tE
z@Z$$_-E}^j$NoC(ct})@^SJY}u96vDYni;R*|J@`SMI!dKKH~F0~z5QgY<t_vrepN
zy#Lc{!$p-#2bV66KN}wr<;M8Bo4;ajLdVqJ*-PGhcv##1Gt5><;&7swasB?*g>Jm-
z9<*?B8)S#hIhtnKTfQo3!Q%4$$5zMA`mn^m#P3_ErH`8Q&JCw`nfm8HT`zyVM7E24
z>#Kw-3D@twJ+92)v9={|3H!>HznWh*PF*Ol>Br(%doOoxSUg{Hx&fo2vTTldt<Jl1
z#T9qdH*KH4VcIjhu(g>5g|a?3y8`Vt)MqekT6Ox_HxKzw@j|(af4x6Z(WRGdaBq9Z
ztCf+-F0-ZYZ?5^9w>3$^*y@2#UBwy}5%anAXYZNtl=dC=nAJY5sP0%`g3X?uRTG2d
zwomccTvvEvSHAx5X9xP(%r3f#eu%rh$f9rGj`j-U*H68qe{SRa-*)l&AwTYVrN%WL
z?*vxVODPJyF8V54__D=l&g`rzn;BYrx2?SJ$$Q%&=lBliqu(c_p0w)fZcUo8j%o6Y
zWxp3*|8DR=Pc`D;)w?Q6Pv-v!KRa=!Fk6ZJVXcB*&6mzxrC-lZi8}kCBZMs`zy5~W
zVSUTHJwCFR1hq>)cA7b#$#3Q|o9?k*xaXgusL+S}qLBJ)mrlt%;(eLaQ@Ko!dG`i3
z@o5Vln#>VZ&G4w><8ss~R_Ii@C>Ypb`y%1o{9`p4uN9Z9Dec{V%H&7?eRcQX+0*w%
zaRjP*RjgZdm96iN#lK+PjMa@i@gFsP+)mwWNmgene;4+p`c;}Zqty9HGv{rd>}|T-
zAZbHu+eKcdPfLv1wK?yc4)n3uEp_mY(7B^>qFJUkvb?c6vv<DGerSC6rf<4Wlx5MO
z|BPyngLiEI_<;FOzK*e>v7wo<g^`K2fuXvAfx0G_zHfetOJYf?f`*Hgk%5t^0bI#+
z$v~Dfj24p_{WR<M#=H)e-nr@jx%h?s->-#9?3E9VUamD^g8EIJ6ya}6J{@f2{BbPd
znwjOzzpwr6O_I;@I2%le7M1E<rds-c*VVg|lDAB7>SS@@7HtmjdNHBp(;*A>DZ<y-
z5~qClkg|m1M~bV@hZL8t#M2KX-h4G^^*p4taE;laLsR&UJMZ_uz+b<)bxBL>NnxM&
z4{Dq0*txwVTP{0Ur*E4hcuQS*j;Pymje^+ZhmtBr2i_#Clz3P!a_ztpzGZ#~o~v#+
zpuoSrX38PyhozUI<#zS7q^s8)VdwWc@W-x0V`Z=l_vBwHNj_054$iJWcwbct*jY>z
z;t+T6UpeQlQ^^umUIz|U<`pvaye2{)+%5z*nl&|SVen;1dz$EbA!a4V>w}jLOlo4_
zn7S>DJ40Kx=MIyJ$O<2B&eRa57b+X1vz50r+*k4LRyuN^`R+BT0H&UF<${cE-U9&#
zV;Z=>ED%k6FpW)axnme_u*GWI2RytC-VHmaa2qwgTqt-_<$}jaE?)172@VIO>kkNr
zx3#fuxwtNFw(f@BPl|_1UYK#d;c{kLp?~3#Rm0o|=2~0<D<7!xxb!v5Q#h%qQz2Qh
zNLnMtfN4!M*YoZN!O{Ew?F!xd`}ZcXtG7>P?hSo=PCxAH(JW0Ki}we^N(1zthj%}&
z;+*Fr`}^z3l1;|{_3XS}e0Xq6@uh#XK@DU5<ATtX-`DqNJhPqQ`{&o{72kNexbin}
z_RXB#(4RkxGvNeJLUh(4ovXKx{`s*XuCrg^;bhyuy{q@HKe9ZnG21oV`R04g8sz}@
zM;>gu`{yJoEU(tERGzi#VDQ4z&$c=Ke{8m+Im~yz$b%z0?H62sw#{k(`L``{^KU<S
zRJq3Wx!jC;!EH<Pj(Wa0^!>o87j|K8_qbQT{<D@ll+&N{utbO|&-ZV<kJ*0BV*mWm
z>8oI^x9s(8uO9~Ny0q2ePUv@w3wQ0Oyqmi>Kx$LKz5~l2|7-12Rm+YpuVvUYTQYCA
zby5=hzx@2?|F7k>cpkrzDx)!XaX?W{vcuKnvjXSakERINudS}v@Ui+eZFY*w{d3Ru
zr*8QDLQ&sQbu;hO;3*D@x%tlXrc_x!`M2QCwo|rT+R|y7H)kG=-1^oox0WX=zj>Mb
z!kz|2pWq2!9@pG56YxB{?d02(r1i4R?Upl-A9~Sd<p1-U%k6DH-_~Z#o2;=uD2RR2
z&t=D@E|@Rj;BdJh`y=)in|S?a#uDCR`N>-|7o43FmMQUif%{<|Ho?hqx4d3$cxxo=
ze>V6@Y6+8?M*haLrw!Btm(GddS9>-2-NMtk@AM}=-fpvXGUMCGExnsF&NrziJO7RI
zT5#vE*y&{Mx@RY^6<6JUTJ}-Q#>Ml4){L(1$_m+#Bdv}BSGPEp=;$i@Jj~7bU0>+)
zu9rj4E_vs^wZ_gT&*+?s*f2eK$CBoxT@~$d(gDT3Q*QHV{jGa#CbDIcNy_HL?K7sF
z_`3IO)$4gpm4A6|%a*ED>8@`3aAMB9GX0AZ%9SQTJ!$7Gk4)Amp0H}id+8{SldD<H
zrY+vP#CD5wKnB0>oCNL}s*y3rqbgo^RLx_r=X0=A<8dhX<0RI*PJWX5a(BZ;N{+hk
z)b%}WW-uJN+~;z^;o%!s?~Btuyx8G*JM3g&ltY^Ct_u^)UPw1}tjvpPmzlfehys_1
zg43O28n3*&=DkpQ%jd0?dMcSsB)RM4mN({Yzi#^Ja9kEC5DDxF)(YO{wCv~{Ro;Sc
z+Vu}+^wjTq9$#?o@D2AZGEaG%43|voF<H`8czVCm!FifH)c*ZB5X0QRcV^l@oATXm
ziC;V-w2sOh*dV-NC-=GgUtTX$_hc6OY2tryb6;R;r|Dvc(+k}lc(yiax<yYh4N%!O
zg*!O!^X}glY|<SIRnIi?9!)=E)mFA`IScEjik{yyjwnb=)%P5j!5;kVh|P@(cb;jR
z7Km0B8*uxbKAg#Tf~(@-;#n_e9^d3RCx(Bs@4RAJp0>A}*wv5qOz#qVW)ZvR{Nfej
zpQoL(o$>P%kFNgy^I=6Zig)a-JDwFFt*vrulAr3Wy>{CR*^kK_IPlQqC?`kw#6^ln
zI#V*klkGnrj`o`J;_s|Q_1e#hd#ha6xEefhd{8VG)v41VqMRjEvG{QE+Ji;P7CooD
zE~@SQHr+5JQlRvrEr;&&9!}Ng|2Dl9UDP^NEWm&36t5Ic@7*GMg_w68o^AJP`3v=(
z?=CFRyqXa*UGt>QB%wa{txOe)dL0)QNHa$S1#)ega!Sd{!QsWia~n+TlU~<1FN$f~
zy5MU>`qVAmbDnzMU=#SiQR<*eTP1&$4x88=V-MeLJExktmu{GGr0%ikIUP~0L#<0b
zw<R2MmD!;#W*srl+GwRI*IhM>Hw%|Yo9<lt^az8;0^_Xd&HjG3Ij27P;GwwR=S_1N
z-%r=XfHq^k<hIX6for#f3Z2=1ZpqU(KkDabgibo-Ii)mecG72~*I_3^)l$PntiG%h
zcyD#^Slt%~u6bL}9F&x6@hjTsxHo0hoR6|vVvEiSEKW6KTl3XrvC7q14ZkyT=FQz~
z&N%OR{^rej)60DyZV%gXUrS-Z$xWtRWr?=0-rfjV|GXph<;5c7_JyAgOh`{{7RleN
zo+$liV*U1i3MvPrmw)J)@>)N_{-UR-Q1+osmwvf0&MtHLur|NSlhN|#nYSM-Ryo}h
zyum&vY|)#OhF^9()sU(3b(ioze&L99ho3r^z2rg$U(QA0LBf&`s@=_ZzYA#EZIddU
zY{kVDtC{7uUnJ+p3Mt#St~@dl&kFm47Hla=QEqQ~Y}r;Hm{}lq?c}4Std_Ht?NT{>
zySM|lFHKVNR#0ll(o22m6P9DMEIVY!no=p@xmRVDX1J|-vsQh7x5mn&hnnAH?5JV#
zPqX{u)71As(QM`PZIdRe$=ez7YQI??Fl&3bLiDF)!F_vNCVuzey4}~Ee}cJl(IVA&
zhgm)gl=Bxbo3!O8*PBlDnRV&luKBko8np*n{SJ4Yxx6NuNi_e;v+ds(R{Cv?Te{?2
zfuXN$%Kr&Mq6H<M4@_mbE|fPNagus|KsHtM?RAgm`rC>MM5f!`Ef)};cXva>;%b>J
z_jNxx4+yOM^!16}mMuYXTZ>HYd3gGL{rd2qkm+%89~0A?+S_G+uG~1IUcQp;-T55_
z^@ns$+UBga+4dk^?zKm?ckVt-?R!R9chtD-4tp+LBJnh5nNFrx#Ey@h6U!?WM7;WB
z8feL+yz0~xcVqkQr|a_AwS+&<F|iMR_Hs||<#^-UwHoISPYKu5R6FXnttMAPIbI?l
zi07x*#o&iMo)=T?9$RW2v$1;b_O$-G_=G#>!zb-&Dzw}k5!d*$<5~9hO{cZ5Ha6bA
z5q;?B`%RJucl$0s`%JsiD(z}^!403K)+xop{A!;5o|jS%Pt6aM%rjiN)iA*E2Vcpy
zyo^KDEk3gB65iQ?yWc!7^O<p|C#jrY#L4+|@IKQgi|#-Ib<rL#&xKlf;r(`j^;i9m
zJ8KmrFNto?Nwb>nX_bHJ+oof|xx9|iNm3s;nfFebbFfo&((~3AFJv6Tw}tF5ZfUGM
zAzoRy^hM4zRYj>48#FFHF#A4zhvoG<^$lMSY%lU|J}bK{P44VoNzqr|C*|e++~U0L
zlrneSvyF_Gx0kw{ta=)Ktmn3mBbUyK8~SGTOWs`fQD$G&^l7EpcL|?!jk&JhI;LsG
z`?617qM`ml*J^%60<ZtkCCh&&>7UHome^Ucy4^i=>g^XIZRTs1Z%K}g6FV2z_f2N*
z{>~~c*UEUYT?O{1WA-iO_smdF>el;pVe_qWNzONm1&*ATS&-p!`sDl1dv_e1kXG7f
zlEBW}%29vsVFlNz8^?rB-0l8k<J0VZTwim3P%;0>$CFR4w7+rS`|c;s6F2QT6%!Gc
zZFTt4nvy*S{__ccs-7o!{Mk-ZS$Ey~Zx@RMTdOW?<@bp_bSA**K<>Neny0thY&892
zcxBgG;W)7=Hj;d=%0rrq_~XtTNy|BS-bT%9QN@i%W_y=z@UAax@>99DX7v*XQ`ZS4
zmlS{KTs?B|LZkhqs}ffipAlX$>A7Ul?53%gU##20_F2$3M1H!h1Q&zhExih+uAOK9
z+9dxJd%jiciRg}{$r|^J%)hE$?>qKd_-OLA&ljp6zf@9RP<N-Te12EI-$&<j>R&%q
z819WZEB<HU^VugY_f&5D{-*x!>$&k|-{;F|a_Xl|zPxn9nT^i#7usD4v$=Hg@XLc%
zXFmQ2eD(OLVeJ$y=Q8!_=U=~kdDH6vvtE<F+`)wjtE)E7I<xF}zrJ6(={}p7tIyvn
z`sIbXSGJgPsaed{`JjC1|4KW3wc}sc{M+=)#@2S}^7UV}?7z$HKEL`?X6a2E-Gcgw
zNjabIypAZ9OZ@RADRjP`+UChGKNXq%++7=Y^?vwO)w-^p*KZCSdCPp(%iqNFci!G7
zpI-f`*);2%{;bH`e6zkuPx$rdNlM+<%CP_X(h2!o2U^e7XaAUJYj0Ek^V#3z4bT5|
z8&*s4etW_%_+nC0uHXEeOn-Ub#K2a4?{2%GZS@;7FDy2@yK-LG`qk!F9ZMtjuKu^8
zZ<XiQomT7mo-e2^4Vrsp^VKD*R_kAV$x?l8Ri^3cw8@{(t51HlXxAFO*GEh0f@0_S
zuHL`Ob?ch2t64>%YtLm#l!w-?-WOgU{=Y=v@@$1~&rjRO?Wy+a*qO~}toWGK^bYgG
zsZTWG;;m=h=&d)odDFUPulKB$*S_mFscEfXzofD%(D%Zt)}trym6k@``1ya;`h?fr
zS$t_}rx)4&Zx(yI;DNbg;`@Z}H!mtKC@|Q@xF*M}Vb65O+Y_E$*5L3zv3LH&Q~3v5
z)l-+eIwE^RSpD<WClcbTU+rI~W_*C_`yoq3ll?2MUtHFqd-ds?tdsRG=IXxM74<ir
z@5kR@{b#ZqkKG(op8veezh2PE{E<6vliMwM1&#dH1R3`UBJ8r>rH|YUKmMG2xA}PW
zigPEnT{z1Z9%bL*+)`Moc5_?sw%5I3x;nQm)-C?=?bVBf|NK|}eK>!SXZ{gouMb`i
zr#42v=1;hzt9RogN4wy|&nbnUD(k}>H`%+F&%b(F^>C5h-WM~g77P3+d;j(EclRZ4
zA~;GGtPXa{Y@fdQmtx7@gSSqLE?NIH+~Z67n&{Fx(`aA)^tl}3=3NE*?JK`0e!r>z
zyWRSCvRLVYrB{P8{_y|v6qn1bJ-_&J)ai?p)|xCcU)sbjYiibIbiOa{&EDFtryt%s
zS3i-b=!~gsh&J0N1qp{koHkRcH)pRe*&XoMD|L<TRLizMErR9uQWkeluG(lbPyf}c
z=#}ZWbpGtQW%=W?>dVgW@0F__$(d~UD<Tu`V)Qco)z09zVg3vBZm+Lfeec<+H_q$z
z4tKrb{xiF-`P!c>#*;7BSpEL}Y0bV2<MN3!-4;n)ug}Z9d+pd}v-9QJ+qVR!RPXxz
z>u`51TUbAHw$TQG(}|4VjT`SWJ4pJm86URzt60%<xm2U{k;^R&3A@^_zu)aQw!7B%
zaB)&If6mq=by{}2ALO;Onl0aXM}MP4!v)5K#STB;A6|SvZZ9(f-?ydGr2?#>8x4Q-
za(2u*`HP8xr%$<l<EL#55|K;|?>4;9*b;c6=HHi$?`MU>GHg=3zEu2~H}Sfl$R+#W
zg^lwUSAWm?HBp1>V1e-6`3{>ZzRoL==U=RqByse8V&wCWmzQpRmmDryRJ>GvyI{%s
zs<^!klh4`BDK(h(@7}y(%Xxibzvr({+g#=PvCM40#v(o4h^zPeA9B>saW;71_1{3~
zd>+p+@!%Uy_FX4R4rC~Qjt~DF%DYv<(2W0#xBnd%Z@t&~8}1bS+AF@;>$jO>Z2?1I
z(c%mHzJEHp`F>q`^6SFn-EUq*y!w;kUe9KxXPk1D?ck5ETYKZW`3#(S%((9B$M3hl
zQ+Zf|Mb_P*;S$H8@*}r7S4ijls-G$GhKcF8>y3ABKCN4J{m9GZ;>SNvetA^W!|?B?
zrEJrW=;zji{9}_Bu__RCn)g3dtLJ33^Nb4?n+;Zex%&E#oKWDl=zFGb{vUGNBqYh-
zd+ga_UAJeh`RV(g*Lq6#Y+LhToiO{nL=}O9@!~u#JXhIItWC9OcyOhYBjC1}wdaxx
z^_**$AFVxEdF=1{e{(&*o?m`jF|Vf2etz3Nj=X}em9G6aIG4|ydvepV{F6L--PY^6
z@4sKV{{9<Z@zbJKy%(adzV^&Z{`euWYLiv;Bk{h@k9Ys{cWZid{4<)wmOp7({neY3
zk9}DhxJ-cE@7G$JINqn8vrk{%?eV7bG25dP0jHY%>v`?+6#6HXPgq_pdt<Wt9|pOt
zV(NTH17~+%-aY+w=j30HPV||yeqOTB<QLz$%R3*v;u2=>%kj?nu;V^Qa{HkfXIo#!
z1$=Fh{IOBCRgGuq#@XJN_Zz%A`8aP&$jf7C8hy88=G>d==Rd1pvPs(BqfZ0G_V3g=
ztlhoNBJ+Xe$*C_^)bDUpuV1>k^WqP6b~dFp>mQdMY+I=Q=)n9EiSF)yVoLWE3;55!
zwH0L7YrA@W>&BC}qdO|vBkXLfzPrf$kacT4bm4XGgTwu<SIRlwA3mJxf5haB#VX~+
zxv5)TiW%Kge8zu%b*$va^M!XZUKJf)5q+Yf-N(Qt{9CF_m{48L@g33iCo0-m3~l(n
zrpn|<?y1;$PyVrP${y!i5^~|cjQGCw@FyGHJ0|~rg7+`;=X+C(ZWwM{lkoV~xx5*E
zTmJtqw7vY%wkFHK*!IjGIj%}yr-SRS>VK^M8eWkW^WT(pu428ZZKE-B{pHxF@qf14
z^VGZE`(XZv_w3)7Z709pcrs0W(?2<P<0EM-*AM?({b#S>ZefdS=lr)<Wb79E@JBpP
zm=$tf&-7)fEO7y@F2-&qMi$N%PDZZI&Q7LArbgyYPR^!AZm#AAW{$>o3N{3l#B%BT
zq~@iUWGEP$PrqQyqE)YYey{)JK#}7gKUdFd&w4p~>Zh=cTd!qti)gREw&*C=)v)Mj
zbD?l{p+g7k7j|yi@Yu&mVwb0Z;RXW%HHjG6p3at*qm8V#`yYQg`F+mpJF~TwK3y05
z*v#RgbZFINsYr$MC%7x#dRylTOt+Y@uJ7$LPw|fm3u|xhRq8(x{AtFSN%cmWlY}ar
zo_Vy|sE2p(8%@~0`p*+BmA9J>9d;@Hbe4{vB*5v^mA!5CB(=^721~yE&o_P|)j8?)
zlJ+AW`Y)CLrZn(Ove@a^cEY)6vWmx~J4%{GvzI9LuK)H#_Qb0-p=_H%H}B%MjM%b^
zeWyoMYU3aF)iMFq*`_=?^&6!a?JUFU7aw?5zS`!3<u)m1Kl3&34zE14is5<kxmS#H
z^7pSf_K@vXm~g@D=V6lzwqIYn?7_c`NZ-TUdYpScEE9UGu~Bwuy?^KbKp{p|)8#2u
zQ{UvLe%TyUvDoL=l$o(hw=9|x?Df=T<-YJ&s!Iz~`1h*mR;)F?yZ5)|e};V-RuNpO
Yc`3!y-=(uiaTys|a;d7i`nz!f0Lnp0$^ZZW

delta 20169
zcmcbAL2%Lq!3io%<_6Opdl)t9uSR$m-!>E2_dNWC$GH|A#t$>2->S?lQ%m+=<HzsG
zXTTbnqv6Cn>D!L|`*z<@RlQlH*6z3HRTKNi8~GpKwzuj{TVGeX{#2_*lIEt8jWPO5
zJRU8Hc%sxD8mcpG_0i=If_5wRObIxcmvejB?!|4!doQlzOO?x6v3zs$%ftGo?Gx&+
zW+}SFq|Q7NYAos<VLvG~W}52SUyi%iFVtb;E>7&cf9$qF)3QR}<%PYjOCBu}G4MRP
z$|LjA?+qf2oURPbt`FSa%4P046JM-4QF7)4<_#ucneTi%TFyLLbV4jp>#^2JiCJ%*
zRGSVuOk`n}o*&+=wXSI9<0C9O3@S>?C6#)#>SwZEKX-3i8h7<Ht%#ZX%FgCxBy9CK
z<bTkh#o+AIyDDe*ZhY&JT)64p+c{TDSE%d?)Kb-!@bJ^&d&8g;%JoiR`==(u8OlPM
z7Y(&G<gJd52wj<Q;cxgVS;_FQOo8^mX)5Va9cy$r?5y5PtWH^D-v9SOEdL7|#?uLx
z73A9lPBPX{t&)%pS*2y4zePW>-sxb5)o*7dEv3on8+h2#Z_n&GEBnd7yXfm(pCIGO
z>l(C-d$S^B@0?z}+9ZPc_=fZxQ$sD$tCGbYNo%H`Ur@C{$+uax?d%IHAybB$(#pHR
zYhMP;W%FLke|`Fe`OhAuKMq=+#H{GqR+70rdcCe3uiIhMdebt6#|?_iVRIfg?&a_?
z+^~IFUezRDg-5kBo(lZ!Ws`gtzxj%7S=H?;w!JfUu9jYPpw9KDeDqwo$hq&=`rUjr
z+mSzwZ`r-mQ<&#oI-~#M<mNYTS~csNzC5Tga{G1h&e>HC1)RFaFF#lDo+JNgR{bA?
z7mXG=4#jm0dr$m%u|>hB-n@G{^A5|!Q-97`QKHW+_KDYG>HeQ(neQeB)U0{EakU`d
z1D(265^@h}7@w`FzMio^mCLQUw_&374&!fgf15BBOs%Y&Hf!SCXG`WBz3}+TVYR5+
z+qQDNNwf<-7UuB$XY%RqH`HufOeST#h<IP4lrmeYB2w$;{?j#|@?BRv;`p0Uf9=@J
zb<b`v7ao`9W!fyark;DlIljC#o?QyOziwWdS+A^iRc5mIuJn*T$3-_}7|(ula4phP
zpJvl;(t3Y)p6J3!TKQkUH*1G}R6e)V;%7jJYs@myDFtyW=fu}C+0=b_!|ZBP6KQ*X
z)62KvU0q>6xYvt0zkkwuEMV??ffpAeP9)T4=g*$DTjrjn#)&`Q>N47RdvCqSyZYJY
zUxvH;)X>YD`<fU1{vE!Z!JM^SF6zUB(n7E94e2+0ejhrb9{pQI!u#*k9J|6dQt2s<
zZ~tpgNR_%_`jtmIAm+@4l&J@&Y5&?KeR12irD4VwZfxBgz3Q#wkLh<)H2MBby}mUh
z?nsE9xo`dX)em{rHJ^<8@ORc)x4Q?jE(fm640-z^FJk6Z&75QT_4h4q=kmt(cP!Uw
zmg{X;a;e&1?C8aniMu~bHXr<a=-GkCKlk%xC2&>$sZ3?#V14y?$uzqgx9cvLrtG<L
zWKNd5_s!VX+dp|;UHRGZJoEA9z7yB)1jfxu63adQQk&tXQha@b)@j~)`y{0;=DU`A
z-Cnch@Ez;5Hq8rHUyFWh^8KUYH{Q06`k+G`9JTdD441wxf44)k-sJnj|Mo8gJsMP;
zO3DN3eXq}bmbkzE$K?N9A0!@}{`BhYRq0p1Qy2xf`2{Do*~mP}PtM<W<etEP1Hb;i
zZgCBX|ITY24)1xU(H#8fOOn{jbGtvt?T*y`^Izl{@BRG3iRl~IHCmt8vb??&_P(sR
z%II*Wt>%Hvy3fx}X0CYtb;%l$^Zjz_yot6m=hSRi`b4)glfClY5&if5YdTyb8$=FO
zt9hzxw)n5VryKv5d!v2NkLLNT?ekd~+vl?~ZJ*D|EU|*w#N1$V<8e_IV*?YT=@TC^
zYt&b;`o!MdX8P{kxr3U1g_`f)y(?&FmU;8QukiY#xFr@x@5*xNzIzuW)Aeuf{o3#Q
z_B=W7Rko~Wrs=Z?<80O0eO|{nc`kk`V=LNJw5gDT$t2Zeilu!~0fWVj9RV+1sKhot
z6PO?zaY}|sgyjX(T83E;=?u@^55#k*bICefI(hSUy=Y1@H={vR-4At+3xx*TnJk-P
z7_I#H{Nxn8qZ>A~x3|w|pKU#R^=^*a_mzAV1Q<55GOcmsb7)wyYSz9zT{;bcVXo2&
z+$_woXJr|(-ih%kcsB^05aK9fu49O>-pM5M?=6GQ+yh|?>I;jKf44K-V1B{%)BDV=
zt0x5)=&V)Mt6#io5$l9$Dc2{l%xGTA;8j$A`k;XM!TlKvmacxhe^)Z2!@q3H8UL?u
z`mz4&{WYtv@7FaG@$+jCJt4%jf#Fue0gX5RFZs&lyk&XtxBSMbyFcw$?r*vC?-R4Z
zzpEdZ4{&At6@UBg!GffB94rQ2R+d(~og3CMq^fH#(3V*6@JR;Wzk2>tcLbk2`1}9p
zUw$XKq<`V;g&WSsKehNL%e3=k!=8q)EQJ&CE7zWt{pa<?KSun=`{F>hsKz_8|6}?8
ztUi8Ucxw@pb;bYl)9P>kNOvyttTpw_^?df9?|^+~=7yz{MLBYqFSPu*dg;#9SNj|5
zFJ(PjQ15@f{=}d3SqyXjzt*1ZTp!~Y$KcGjt-hE2`2K74I*<RmdU{w?{@hgb=`%yb
zPP-xoi=F@LSa#U|`Y*q0+Pih@91NbwAN>FAll=erj!aB@8>VTT=JuQBw6N^u*@yR;
zmUO3UJ(!tZHzU(nzrab~uk^p!5jNgiQ8VAoog9-rQKVwgM1S_^np;-4r|i#LWaiIM
zzev`{=U9-dl>P*pX%|9nuv}SVzf%0)%6^lb4VM+mwuChPmMvvH857ADm^|yrxpUSl
z0}C{Nx9Fah%nrMEkG+5E#2qHp+|&LhoN1Vx`k{^OPU5;_vo`W-@7f?xdnc}~Q{%^;
z)^D@>Zd}>+B6`E;xR!ss{K=~iJd2Tjz4Xu4<lWEfg%?Er6<++XE+uJAz*gCprfO3=
z;uO}cUVe&q=hyOmS;pdFo6jvjzst+H|Kc|zIh(S%YbL+_#3{6HlY-QG{a=qK?zz7H
z{*<4R8r{c|ZNw*Det7nV|Ivv)YZY}xUpP-po;o?!^GDj0;Pb(D9}nppis*gZB^Fga
zec9BK?2<#i&(inQ7feVwIjgdN#gC0|LY+46D*P^Qx`_RK__-Nj<%xGsnuW$L`>|}!
zl{}u4x6fU<?li?H|2#+hx8Ko^wxxWYIQuH2O>XnVf-_>0Qe3-D`}lafPVR_(vMi-v
z>&^q=uE|SVR>@2|JX?5%@jM?>r)G}tB3Tx9H(cEs;aI*fIh_57d#q*s<>{4;8*=^M
zHzYeAIsSV`>w6_3Pgyq^vGg~M`|CXBdYAN=t_fd$cdbC-lSgL1c3#z}Jy|8)<#x+v
ztFAxK0nXnHUI9hF6cRfBo&0w=J)nzkYV4+Xxy{Ap&&~$CYx9ynyY#P-)5d4(1okTE
z{9FB8<O=(x>nnvPOb838o|>ZiQMG>Q3B#TZ6IAwn{FB6%{?{cs!pL8EMS0V+x@kA3
zEZQgcz%^aI()47f@C#Ah&EH&2?E{X;x@oBHN<a2B`f~Z9eG|<+cPko6{_**ie>L}@
z-Gq7Ob*<*C{|;O-*&TH@-T%wuEkA>=O=UjAzGdBtx3||iC^74Ys0sU|?M~YCLnAW8
zzW(m|*~x2<Jd3~0lJhF?;<6_z8*cBdc$dvM?Xid0Z)e4YkIS<2%WS$hzVi#lWVc$@
z_`HnS<C!N`_eG`R$)u7k?{C(7#2hZPHL2}(5<c)G{hH0n+S}2;Qukfu`+1FN;j|Rh
z=Z?Ya$~4m+S8NLUt)cz(B<lq&N86u2m-GDfo;4%9{#bKLfYXQP8w{@<w*RsJ=XJe*
zWyu+43dat7WBNVe^!5vd?_S=1$6;N%Y{A)`ahK({K0auh<NwztJ7BKm)n6L@@0E^+
zi_O|_XS(N4-SUjv-&&Mbcl=e^e{D0*M^l5<Cz59gHy@Q3ox64Wx-W-C-Bi?f-#weU
zes00tZFMi!Tdh2Iu71Jkx}%Yuw^9So-<hfP<J8>yQ@IXQd5S*EP8X1WFo|<lh`#T=
z<93C&Zk_u+F{nDEN^R%I2_FpuW4}yNdhKnq|LLS@)9w0qGiAiwUE~zGW0$6j{JP)E
zFMrlun{lVECg4|_<s?q7X{RbWeWw3+Kfk17FaQ1h)64Hioz3Y_{Ta37UcH^)?wxaO
zew;{-SpM5A(e|e4Opad@enk0O+q!56?PYuQdhPDcg{tdb#<KG}&Jlg&K6&!bwS{{{
zPweeFC+zjm<;vz~N6sEI-F!>5aZ2_)sSiFiyuy!;?)OigrY_9H?sjq-|66-Uf&KfR
zU%ImVLPll0p69QnN9Nzi^j;jh<CueAcs>9A%sqTHz1Ozyz5i~1{FK|KIuD$ZgBsT6
zC1eS{)ju=mY+~fe)B2~>AN;iYBFXk)lIZ7qIt#UY7tFdE>9S*e-krqU;7x%6ySCc>
zH4<)^@%^;F{;u#tue&y!H7v+i%Twerm{Aw&bBle_Gv}EXi)00^3HaVTGVxbcrL5$A
zMX?EQ>L;$8m~+F`s$gSi=^QrIyRPA%gjeNMzIA19xjbvS(c}qsKWjQ~ESPZc-=Srf
zW_dHeJze?P?1r4;O!d>Je@!%d&St(i&f`JU*;`&KivrGYe${*|F1hURlAe9LmVW81
zY}p!I5i>2A?ay3kXU@4F50q~TsV!_;dwEZ-u=yPc-%W2i>buh?`8_LVJp65G+~K)w
z0?R*KSQx2YYteXWjZdoVa`TMU9=j6`xL)=+f2{d<+0y8mV<G-8*(24@+Qejif1CK>
zd1?Bo(=*HOPnh|4rJp*lgQN-X!G&#H6W8lAzYP1?8ppT#>hk?k+fVDvHFo>dGs9$m
zK!qE(b8z&|UGs{2Ipp`%ADAz7=Wx5_-&MNzJRe>)_`gvwQ1DZ*`Vz-5(UYC?WwU+O
zCQjaAmG)a<<)u2I4aEndbhDb}H~HOrVbHg*+G}oPU)+WnY!8;`WVUMEUL37#sb(tT
zZEGu&{!!=KlxypbU;6UU_0J^p;NY@Lua3tCwCoLf`JbDOX`Vr>mcN?#obUA?;yqob
zUYr*vw|%DB^|&v)qNmPLlGv*gbY0PfW38F*!dbhVclFP!w~8=+c*~J}sqSy48ZEQJ
zr+q?43tQVIvnB_Z1ln(nQCaf*OEyo1+`5@1^91Bh&+nZ#|3jAfzcAyz(4d}Et;}XY
zlfz9LyNeh4P3YhFBk#gHP5r)}sKe8i*R!=q#+xT^3DlPIFBM)Ll6Ehn{^<n;ukKb3
z`^7F^;ny!#y}o(&<1Nec8tzF3vzPy5^L?T8ry^LjF6>j6mRexu8PCjTvyYxm;GARR
z$LjD_t^Z-a_f6ri2b90@Z_4fT|7J61)0Jy~Y<fL?Sd_2r*(-8LLN#-(zS<MN_-8BM
zyuV(*Awwx~#=CyYFV>kmw<ZY)PY^FSwOnr}kH3>VyZh^Bv()$a^UM9w`|wj{ir0au
ziJbDP>HFgBa-Z}>t)BDf1*d$+0qgh6S{mQDRB%SuIloI<%DK7FUUkuepeZL!7L~6p
z`k(t?(<NC?p=&NDKXCVL={PyHSv|bpueY}KmiA|BvwHg~%||iJ(hI*TM!MZdxNzaz
zp-t?;EE+G)bUdn)`1oK?q)x#G4}*fMcE0=9T|2%1QQX38S+%MEyoFCa`Lz6C@LJ=8
z&)2P=H2c%yt|c56D{{?$*i3Sc@%&=c8YdATyG#3|tJ?k(Yqn_fI=wh3UATOiOJ0@!
zwIv7cN<~U7im|SBtv@hj|C6*!!hVLcj&LSE@7woRD9K&aa?AGZlD`kV&)l=^l$)So
zyn|mG&qblE@_Ba>T@JpvmbX=<&E}fFcw5vFiR6IiRS9AfGfrq$pR7Clx_u%)&kB3d
zBM){au-LUl-8Z`SR_V&jzmdJCE<`*CEEf4N%a`5T^3I02qH@1DT@U@N|80MMmCNxR
z;u;l99)kV{OwWWo+w<_kf`?nu4VJLxzq{<(XCb51TI#J-yMDvbE%odd+qd^NDPG%h
z{(c3ku+bac-dXmkdrmLBXr{AootN*I{qMehz3^wkzuvRDFBVivckI$Qyd`^adtP9~
zl;(Sy1x3zPYbFL=Zqk%xO%GdD@8VvcDB~cVcHr~8n%4GLhqKn?8)TkHS5G|gJ-yPX
zXYoS!IacD03)fBS&^;tqeD2(V5bX(N3;$2Q*QS&c6TQUy&y%@(idt`N(#q(uDbJK{
z3#wh!?7gmNoy0fyCWfNK3002y@_Ado>z@(t@Va!qJI=%Qh|}u0nPpc*`hTV$o8DZq
zzkb%mt1fEED{Z!S=<`La;Fvb4`dH7?Gs|UH22C=}f8rBy|JUsLy}Wa03;#7rXt-q^
zcjt{vz%k`*y;-(h+VR)*|F-BYo-R_f%dh)KXdeH<&zC3b<Q+;fzy7%{{njDl&g^|U
zQ}1+n98k$L)^<I1J=OEKajQ$WoqXES+v`GBq?f1EdnYrQr#uXwUVd$oM`O;Kt`B!V
zW<8H=%u<a?6k}&m{3i2Y&ElG)FGY1TfBoFtZ>Im}gUUMAz27e7%zdh2sXJLpGxNGY
zeV<*Ow_#pSqr-LM+spRrew+W&{(aSJyG=enr`K-Vbn{yrN6>7sd0(}-{Wv+xSghW5
zI&a*$t20i9J){1hosmZB_XZ<pu~(i(6%mPRHpjm3tB_=rQ~Bn;$%olT%=*>`W!B>z
zMt<vmPnHkqaN-E6?tJ1MwSP{rUgj(x9gTC7TDUIG`SsUTc)|M<xk4MWG-uzwBcJY;
z@vBg?sn?`O+w;-Ry4eydr?1G6nAY**Y{xV{fsF|{k#7Swe6kFyU*{tcG>3Ip;>0a7
zN}5~J<CdM8;IXsLW16Q4&yshk*U}~&`1f}e_X=qtPTd#g)3su+J$WSdvdk%K_c^!l
z=cV=C{AVj`!c9GVPlWPh+_`r2%AOl9`A&aXb+xWFH?&2LNBZ_0ZYKu;<uDWG-q-sZ
z)_wl;((nA?*UJ?SxJ}%CU#_ga({hvYjlA8ZA8*&X=jvGH&$zcImvJTIlEWtEDg`X>
zAHO|zS5$S@qD7wt+_LXm{#+d6dGwd|H-)bU{c@GO^75{=Co9Y9Y-akSzv9xp@C_9S
z_J%o4FY|uA<_LN?f32&Zg@UEnmqXbK$FILMl1o_9R=6ypuS0x8#d2#6vpC&*JoT@Z
ztu?zW^r7<F7L%mQ^$S>Q;-ohE-hJJ4`iR2T-j5;??_`{B&AD7V_hYjg@AO+|j;&oA
z8~NciA7AM6&oj6yv%7QWofNp_eMOz+)}}}9)o(k!8!qpi@UwQ}t~PlsHlt^!7QLD_
zOY!X18=S6XUD_7f8+oR=2XKErG$|yOciqBxp?XDuKvBlNmfEV2MQxX)%wHY|<f?4p
z`dU=<tz>Z?^S8yhce764t1w+!zwWNypIvdxYsF{inwN2V*3F1JFQfPV{OYHbOr;mz
ziAv>`^Jv}vb26t~|Ktv<st0T4%02d})cRq%Rqr&r)vcYuE$K7vZc%tqwqyF~tdvbv
z30j)&*~v%i4cRVgYwUmbMK7A;?q5ZX_#47T>T`Q${F7yyo4$`>u0m_tm8V;T+}^i&
zpEg(~sOEM@$5zy^<=wk-^N1p)^ze5oYOAyqS!7P8D6YTh&RVrYSK8jWELwH$t8bz2
zKX7(!e3^16?`_s!rlZkUul$&2{3_z&!@pd|pYvG=^Ew0^o>JdlXZ5k@>fargSFG{=
zxk_^GV`0HC-pzZ`FYCqW_a&U^i;_%<u~Rixo9KUNa@y4yMzajPXP%$Qd7W8wk2go~
zs(GC%;@8wQ_l2BL@qf7T(!0P1Gbgt*#T}iHmNQlL&HBlaQ{qCld=4#i3i`D%TI@}j
zQsKRYs|@xxX4%wy+Ym3DTR%lJncZr_9m~fX0>kE9o4?tYvz|Xoc+SFxh>wXK3D3M%
z?@wvHR=%P(_)o=qkI1jzB(3&wZqF^hbFxf+5=T+zdhx&>`OIsj*-pm26B;Z&9sMZ&
zPQvKuhC-i<^)77d_I}H4Qaw4d?4@0cex${LUd0A;yE%2M=Ksh#v(Rw$GlvKD^W^SK
zuCI}M6!F(|uI7SS>Sy=9t!+Nzqx(~Ca*uFp^O2&p2hVi4{E<q%{(QkcZI$o3J6ZD_
zf`!+g{2f|5<#>kelmB*y44$odXj|sxzv}bznn|-fj(dLX(7bwNC1=1x_BAG_UCd%b
z&NP<gKJ7czy!PRxRE7`wum2@ks|g*?Fk4aoc)n_KMN;V22duYywp{AYh;yF2>WRT*
z-nNG`qRSc8Yx5>W>hG8%q$$13fb0CS{=#nid9&npBzZhs&u?c^{y@QhCFjCN8nx3+
z=YNgd)A2xK;*Yh@+L}~FLRTz&Z=q}yV$YH~`;uPYtPrmwKj+QgCAs?kn)v*xY0|78
znR45=&#V99o7BCixPs&Ho!$PSyt5wcy2xNsXZprc{jJ)sb2siiY7X;TDWq|X&0goJ
z)(#K3%oAz5cii$gk>*iusPX^Z&Zu2|GK!)67tT$Tf6@DM*96;ZuRrWrYuFnZ+VzY1
zosDXC(Yznd3r=UAyZ$J-PxIge(Zj2bu9>*gKl5tw^-Jwf3+s>nb-DjSDua1jYqjJ@
z(UQ~AeDR-lrcZx!>)hW%8O5(B^j=L@UQwa?Yu%euvgV00cQ5ch(H5yWuhMklZo;R7
zFXrEvAXR@>>fyqbY<phTzJ5K^#K8B7RNTLpwVI(1-+cC#%`N`wRTy1mF`03%nAf#8
zpC9cj>}J}}di~y{za@8Gv)8Y5cR%E@*uu(a;qPtwN25=dPN|q;6u@=OK*oDd?go9=
zuiizcx^8%Vd;7a5JpcaXE4vqMVV3S^trp3vSrPHadF#s!CnobZH>@{vmb<!*RcV5{
zXG`Lx63cfV82`)gIz5^Hxw0>6&$Sm>R_{OWRh@dT_UWz6rK{J7O*ULTga6ajfcp4U
ztFZZ^J3<3(u9_80{U|u8DD{!af(y|?m+G2NE|QHo$|d+<HuKd9_VKfY>nq;+uekr!
z>Bi3ld08jrS93lbRjrYJ5x!Gb#q=WUJlPE9we1P7WB%<(IyPC#q271FPc8d?%lTV$
zf0UJ%T)LRwW_jwda^riy-6y()l1q$J+vTR$vlQ%}UiN%%dG3`p+=fDp?$3Vho4E6w
z)3Rv~&4pDTzWx~)vBLcNn{$@E=A!p^UD5XS)YhLM>%3V?xy|Ed(G(RU{r<H%PfkCo
zz8f94a8s^x#P!0P7lb(H3$L*G)f0L7gusQTdYjS=uOIQ9-D{^6|7>;oRFR!sU8{7j
zA6irpb*#R=VebCp?_77dbH<x)daEMe|3o#~Yx{kXu;aV7H?VZI?cQ{{Y+}^^Ptx-m
z3f%r4jNse<_~5>>Ql4;b^<1{jxP+DM^TXzRsWlCpJ?&m&Zspg~@~M-bKTQ9e>^}Kc
z|IeMeO!L`o#03l$U;Ad<ww%f0FTf@Lc$2{U<DD0mCnkM*wyl1G=$=)xB4>TwJMp#I
z(d2FYzRUZ5bZfue&-3nkL-Vo7U&mfp&h=Ed^^S|@u76pqqm7J@{U>Ga@OvjGls+^$
zd@FK!=BI!<lXvgGvF7FN56qssX|B+F*EM_Ay!s{1>hZN}p6aD?UN^yOW?TMdb@@e!
z|9z5GxbnUq>vzk&2dh}@Uer&Xx4kd(-{v0$uKNm#9n@$0cC<#<znaM=T5qr;@V3$F
zR@Qg>&RTtTy~C;Qth-m?WWv3~+P6ETH!aMq`NFW+Gcc&D?%p4r<J*0F<{j4ROP`hh
z+;_$El->_<4(pzOxtDG8`iZ1?aA`%pQS0qT$1ndpx<@f~(!;Z=2X7}X=}bJFRImS=
zf8G*1&m|?k3*u&1Pkj74IIJm!nN|GNK7;Vf?`nSC-Q}3kBXRJ^;lNt$-HKB8GoOZg
z^(gVa@iA>{aCo!z{)!c?@&&gtkLaKF>`~0_(#ZaNYl_>noss+Onji6ta6c|S&v{{{
z<9aKRHpkKj)s8I3DlUn9x~{X+zVqx1#vsZ1@5Rd_zWfT|zMR^B_)&f(d&uMM&ZkpW
zZIIe}(D9&ocG095{l<H#ce1UOr%FoAZ>V#qeQr=2HPNKbqmz@hsJZ9MS2iip?eUvr
z?#b~)KMvx0X;-4n<GeF7XF|_h>;D__gUq$Fowv-mvgBNUnQng8MYd4ZzndNNM9Yt_
zI{7=@s{Zw-&K+4+rLKoQRUUeH*MK#uCiZZ`AFXNYza8>sI&#t{+x+`p%?-P17x9`b
zlX9;V4qLqA1ml#$oPD7OnKLZn`F(nVRyt|LvK(01a>?x&|2{T5(LL+e^Y?#jT7Kcf
zW6x4Q(e|rz8NHs%-7ZewR1o{2{@ewD9jf)uf7Lm}wfc+Hi=T`2byra0lxJBc_1Q}Q
zwusAfmtX0LDPOJ}UH8lAobbJhgf%v`Jx>$&@(b%<wfyzsn{nhy7O!8iPi@U^A7}nA
z(Dy}$@8QCwSz5c(<b;Iw#CLlxlv14|(&c(!lA)i&)@6a$)-CgW%hX)*X;%<~$_h4<
zr;-}aH$KtXa`WT9!{+s0;%}W_pcCm?BrL?7Tz;43^2UsUE!{%i3&Ufg_SL?+^CkP_
zX@}%Z%WG{+r4Bz(j9=%hai!I8he*nln_9dX>rEn5UsztY)|)Z=_mARxtN(G?q}cwr
zTUokAA$)nmL#vKWTbKS`xA=}+9Csn-cRdYG-=>ude{~+4vrYZl%7qIQ=F}?{{#Q1B
zzu;!wy|?8n3vDYlJgYUk`MPAYeCKwDs8dQOkGiJXb1Au%pF0ql`>6RVtG3`uC2>E8
zw)IteWti0dNxoW{)%8#!a^{>W&DYB^5B|H_cgAIvXo=B}<#nuwHZI#A`y=3wXKAB|
zN%s!p)ZE8<E4!L=%O<lNUY&n`{`S;e^>U&UBX2)%@pRHkU8i34uU+{lXTYmJ*Hio^
zpP%4x&-2B%#S-#Ak2)`vJyB9?ablz3;$4nU{yqzoS?lpOsc+iN4OvgkrZaZ6m9}4a
z_wV(|Loo^^mK!Jjy?waWe&OP8-c8>b>H-Q)WAfvc&+K?$Ipej`)Rl&Hu0p=SpCvD6
zY`)B0@4i;I(%f2gU#5tHmFL1vhtHSI)~LLy)4wmtVsk`k#ogJH^p%UngrC=W-S^$=
zxO#?UmgT23?dPYjIh{NGsY+4h^%Qa6%I+15PX6ZFJmJ@ceK#LCE?y|{c9Da;w2g7>
za&`ZWvqkL=XDyg4@b-?J%+1^NH+2qdyR~OgZE5erf4ocUSNzCkG@to!fgY#&CSh~2
zk9QOPoqB6KZK<Hz8X57pVB;Noq_l6xd;U<eI{Y_s!<kfn&S%0?H|tIFl5O~|S*BBC
zXgMV`YvEGsqtPdWCP+xjop@ohFaBh#jl-JWP~)hi-*@5~ryZ~UZu^KO=3-~_b&-~k
zFHd5pRF`ya@5$OC<Xx}sakhke#gQD<(l$NSSv$T<*l4`jpCYkq#cYwB(3Nj3e$P#v
zdBx_}>&r4<_>by63z;O~q}sLqZ>xl#cH${B_T#yQN;+S3e^ttCxYBlRX(S)-DTW<0
zcfPi-dFh_AZc4q7>fXI(9FhVb`NQ1Y+X_}P`uslJqjI6++Qa#^qCs4G^_$lnJ?`=)
zeTu+_<-&89t$Mw5^L+cF;-KQjP#f*u&(ckI-)xgN`g>S<z5T@XNjHt$Gap7gyzqLS
z$n2Fz&dxYcXsu9Kb)kd7$6|KaYTf!b8wJ?s9~0i{@z1L}XBAIvz+Kz@_q$L2%KM!C
z$6M*_{8^3`{I7c^-Ja|ucQZcidDxG%`ircS^I{H}rUicMw$Rvm|Dme=ZKKZX!UC52
zO4#-;R6G~o9<Fh={OL`ddD(7nesc-;d27_pTbY(qxGQw}ogGtkuUcjN3GG_t85&~b
zY;N4sed`WS^}AO6rf<)j?k+qx*~8Iwsp~sIg-JPYRf;AqKJE~msLnjoNMF}uYis-z
zncMYyj(gwuBWY9Dx5@NdhhYu>nH`@3m)%fb-uGzwRQ>3#o6WiN+pG`Y%-e9-zD&7)
zp53=swNujV&+piOGc_n$B`o}Rvhexa2X9Rjy{v4+zPHxCVp80Z&7KWWyk93zeI8++
zpTX_h|Ma@w@8cntI!{mg?5xx-zQ3>doa(b}zwd@<JgnDe-n-De#`wmsyWiy>az@S3
zz1OV%WAVrM+#6p$C*5*QzR)^3PDJ#HM&R2h&AO~-O23pop3XGecBg&k$M0g|;?gS*
zofSRjec@S8?tPWX`*u9ao&C=6c<|5n0_+k?_n+G{xqt11|0^e0I9V*{6xGm};nN=5
zw2Vus{Fh?L`^{q0-0E+=6|#0Pvf`|dx}oASVRpFN+Rxb`#%CuVTvI>kUVr5|A)V6Z
zn!bOvAHC%Kwas2L+b#ZEy;<ojOV$(4RSycjC(Y{0xB6PE$NcXX*S0UIe~JZ;UEZ)R
z;I^@8%YHHGES)v^f_=vW;|}(w%YM}nnb@kYU*eg%W$TI^+;0oq{pF|B-`pp#_K>5>
zsdpcyaNds7n%twc^v#QZU!R!l?9$WdaB(}(^ylaQdvDK9UlH?a$IbA-uTzre9+)y|
z>*^e#*1anmw`c5U<`(D@bWz&6a#^Opi-YN2x1=vvY^}e)MRHB1>Yv!8pid7r@0oOR
z;i?;Jv{G((%3Zv7|KV%ne&HG6x6__W*6Ten)2o@yUwN_Os2ktc6?HRq-BMq1MysFY
z>-KNv->;Ou?GCPy%&R(hG2`qK<<|jD3y!I8F;dQzD|l<U|L@L;{wJI-aoXjsf4=Ar
zL+6oaV%%Gz5{q}$SJlisD|nYlI{E*^t8Pa=JH>6>sW#VRmB`aO{7#kjv-UU_PU4T`
ze&t$T-@^XW>FxXrUw_7Le*Nv$x&qGh_qzEnpPEF3o6a$myU}vVt*=j^e0%1GYq1CT
zmP&sY)JZ$4zkJ6Ew?_|u${)4e6}RG{(<&XlT~&e8CN2LaXxYOt>5gZQ;8Onwxr=-Y
z*Je3xEM`7mS{~k0y?YP4K2x8%$8WD~u2NpBXT)}2k~OF|Sy8>i{#@qw$z@-^DDX?1
zGkbMTI=<rNwd{Re9O~0;rmb52?phG%vig2$?hD5zm`*CUd-wiJ_F{?2*?wzdZ4ZXb
z=RX!>J@?N($A$6>54}6XXBs!F$ou{G+$P`N{jp6Jiwy05&v_tpaB=4E362+JcWUc?
zJLh|2|GpOOx+LkU_U`)jl#<yCnCzB5`egm^<I&8F4cBH?yL@8o&HA$a8CU1}^Ivse
z{{F$CvBTF-&;Q}|?*ZFxWj8Ed!SMR-HIY{uD}JU)I&nNzPwO-^Tyvp!1LOLG$sLK6
z%dhx9)hu1K>}%SIf~<qw|5GO&xH;$4tVu<;yq{NeEWF~gY=(N!gj?cMPlwk#3HHhz
zVVLc+chA>ldB0By71&OCtfx0`fyv~^^-?~cG8DbE{=N}B>Try~z{1g^==zVZ&luJp
z;cGa$E483nf5yVblLhPJ4&~0aVoZ!)vD?>S%kuU&;u2r(oc`x|$z4Cl<RMpH+EJO*
z8?N)}e<ZwNh?co$^S-?%H~sLhO&gkZ8S6jS3LTc2{z*L|NlIP6)&0b2quE*p+500s
zQ_MdaUz^GQea+MruX<cr54~QpGSVpPT5<=^<H&G1&Fdc`ylPT1_jGjxZwoe7Zp&Af
zXO1s^@c!9!1O7MCN17Kto$<4+s36L1cJ1d$wm(u1zqdS?{)6ondvdkn?&Xg%cVA!r
zPP3=4zCLqi_Pfh$mt}=c-uPHsc0?^TLT=a9BmU1PvrSp`sFZPI@WHStCVm$lUvOG@
zZ=*Wv3hUdG8<zh0|F5d?q<88kE#Zz2>ms>q{2W`Z{ocZ-dnN8(OyIJ(pJFb`|3f+>
zr79&_jEvYXC4Q7SXS_gr>kjLEmn`P`U%W0DII-V)YHmb*TWSce+MCV%YV7lm)H83o
z)zW!tvdya-FHJXBch&9=`6en7+3<CDpwz~te9Ui>f+q-HlvlW6bmp+Y+nm@($to+V
z^EU7Qkf2cP?eOYF|1a)!T)9g^c6PZ~raDGgeu`SdrgG@_Wf5opPiu{hye7@R&0Trw
zMaiSHdsi1^B;HgG{ZXHp@ji6##ErM!9)9|D`*zl9er<`1eBH)gJE!SZnjChDSnI^%
zy!YiK&wHlV1()#dnq)9}`zc$^<Qj&knfXcaDYE-qMco>Y*goBE5**t8_r?5B#^!Lz
zYoaIWgqA*!C|whEA$w7W;?`~b(#K1mK4ZGS?%T$g@E51`FLYOWSug&-q(1JJHdpt*
ztj9O!)l_zyq|I?#b9zZfY{5eN>dc(3CH3>4WGMuiEHnMw{#NbnG_6_2`)}Twc<SKN
z&rZ7i*_FcADn3t4U;Smi@5OI!dhyzdKLjTK*Pd{w^T6ph$qeT=KWC|a{P2S9jC}nf
zeW!h*b9v3fE<Cgr(mnVk=8oNqYPUSb`Z;C}EN^-he6FSi-Jj-nQtigo>l0?)seiDw
zvts}M59!IWmJ3Bz{7B4h|8%;SbLxeNV5j2i|7J98`)6sg{lTw&2Y0_!6WTDbY1Pk^
zypQif+U_lQ5|g-faSz{1(>$Jq;Ua1k0*lu_zasbDscxc)_4gTv91g8p`;vuQr%L;_
z*apA!`fE{H2NxHZ{O3OUw_hMEVb1~oKJCk!8Q027>=p6hKXQIXHTQB4-@k9<C9ccQ
zN!+@ZM^@waF^krc0B!e^ik8YRjzuJWSartyI;-eu2XQvH$gcZ~Uv1^}397tO-9O_)
z?bTnKe_rPQa-)*<@ttiMvm;fP6-;JekdNQc(0Rz&gh#bLzNMq{s4$<fk&vcoVB__l
zwe|w6Z^Hb&{aNQ}yUg`#T=p>TsOO(5@r_daMTU;w*#GTGQ){*7n8CB<)Ep_^kR?tz
z=QnL@-sk;k_m9*`Y|pb&{x?3q=#tHNUP)htx8@W3l0^3F?7wIFh`!|)Kc-%I<I<xa
ze|lYRoD9ov_uVoxtUheb(Vq`oCRBTKTzt!A+~_S4l$$@BOYvLO$Bk{Dybr{EG|9aq
z5O8C%Xd>t3(8e=wCrSR7wkrD-<F@I9t69Mm59Pku9r?2^MbCY!ceweL_x8ifl;w>1
z7S#1|-MAzoeB%Bhv)@H5`8VdC+pp96^IF99-lF#n2?tIr3Hah6(YS-9UUcIgZtG>*
z>*ltex^~v*Ohe$Sr;Du&OEcbl@hx9vqa5#G9pftYa{CFPT9Kbhb07RW$oqe-tYM3P
z=e$Mip6l~{u9$e3xqa^Zw?-|ohv(tmim=KrlU~jHpYr_tIqR^%mzPT$S?BMsx#h7|
zLop)5_pjv5HSdn!c`BXwm4*A{vn`YAqff7Fa^ij}_j^8L{IgwUM#oo(iLXoh9Uh_;
zx!rPiz_w%k8*lMEbaSbn_v^tk<9(A)r<|yc|Ma{^Xs7t~J|4#KTd9lLZdLbm3-#X-
z*9|*sy!4J|f92NW$wFK=OOG$~6AH|<x!x0V!!6jw{#UqlRUO-zBT17Ct_0W1Ok1=6
z`rG<zdET+ST`Ltn`My@LGyKN6cWPSv<TwvMDQ**~ob8jtT3&oEzi%+v-|zji62tbK
z`hPc;PvL2vko&MH-gif!QSO^p&-1fpJlyxIG$cn%J@whb8*kRB=`&PC^i0UfRq4^+
zUmNQy8ufB>+BWw?VHwqL4zchvUJ99a@zea*%}+wT>SxyQc5LdowCBy&JCd$}t~o2D
z&hqa)XZlmJ-uC^bFMDMhlpeWisOswTb;q22^>SZvu-ZDKq?f(IGmMf>KR$kYVsFpp
z{!>f-rY)ZIY>mXqr;Dauac>Xf=y@V%`Dy9N(@McCobt2ROzM|CFL^fADxK@RCikY$
zkNnFY#&o@(6Bf>0&$lc^f=6k=$FpwFjSCo@bULprx@#)%w|nx&;*KTax;I}GX6?Km
zb=0`qw0Pm_w`T)NIzA>XvXw8KdL{JxFGVN&oj=ldtlu*GyX)+o|1N0rywB;KdZJ(3
z+Ec+Hc;kj8PZ@vpz22R!F-3U#`g3=hmYOLay0i7|vITtcAMY9N)UTaeFL*?0tzu=D
zw|D$@;|Z}UCvIsU++KEzYdwqaU4F*$LQl;r-dg)4)Q{cwU|Dy!Z!5o|rclODCOJ>-
z|DvWA_FLZ1j!?d&tN-$L@X;?<GvoplEbi~pinI^*3n(k{747KaP-&RHCTx06$@)1J
zt<?{1Y`7RQHE-98(z_enoz0w7TkGE`TV+4D{`YLMPXqURxszu;cq=SwYy8~w`|91<
zir3>;*g36v9A;=OZ#88_mHqu!-Y-v|W}e^3l(+50EyIJdHIH|HJ9y;%#9z}=%USv&
zU-cZiCpKHdVqUq@mm70LzEvI%eQy6o<l)oDN;{TI{L^jiWOiEj%+A)q!BsObdk5pE
zJ@re^ik-9#&k3+{W!b3sX7@^tDTh5(ay#|QW|o?tyk>EOgZ(ad(An;@DHjqBUW_$*
zdFo89u-SFj*PZ;8A$=#^8>@Mn6k{2sJ2qzj`>`zWLC*5hqX7+*JnA%#dR%(#yP>n>
zUG7R1A=@tx^=>>cQ)F7-9xt$D)BS~YXSdu@yZo55K6lN>z{-zGn;NU)Y8L4^oT<;P
zWmJ3IV!25A*wS;!CeB&&zP@Unk*JkbeCKw}oL@~+><2Dx-E(JMYr+3MwKspPSNyI_
zsm_;44^%#D_Da3oX$k+q-xgcuc?KFgGT)4TrNetUFZ1MzD{EJ+`n2QrB@1@vbyFi(
z++<BJ(``Ibu_~jUTYvJ3DbWe0Kg0_Aj`^6s|DJQRaADbDk-{>2mm8ZOEbW-3^853v
z?d~E^Kek`7|0tXAbYJ^)>*nv>{(s6h7|*p|_mj(I<?pf|OAP}>rz;E8oQUi5IK3nC
zk&2D8r*nMw`}K^zR&Ci)mTU9hN?2&;$hs_6x|AQ26{5Cg>imSMyX*UUtmeJ`n#5VC
z+M1)mJ1=jZji2gyu4yaw*@n-nG~q5e_DuTPzaDG(EjygPU)UHrx#>sOvMBZ{Kkr4`
zd3plhzf^zyT_-)*q3yg~_48W&H4%J%t<GzYa8(^BSpQeUax3?(!)qmKca?v8DfTt~
z$3(w|4Az<>J7t!hsh?w=U9m!-Uine>m5UPFoF=TaVDbwR-fVF6_<U2Rywmr;m@RsK
z<Z0hSzy2dR)yovQ?tTh!j5MF`X;Y~qHA7==q@<Kv;KKYsKQZ5LRXQ0wR`2*i(-z%+
zmHEui&raT?Jn`47@;Wn>4@PT`$n5!lW%{449X=-0GuAHsdvvR2lk(Q;R0IA^x8v&1
ztGstU`28|#c>C$c#*@3%#7vvwqgUULZoa)}TK9j`&s;xGs-04psmPseyp&`5|G71t
zl9H2_#$HVKdJ~pXWAf@Jo1PZC%<sij#XputgzS8#`EV=C6V@}wou~2LpWX8&DKn<v
z^z=Dx@|kQ?GtOL)xhI~v;PRqYdzQjKkCY#^KC8d;bFztZ-%`6r#_yXYG9F*kQdTUN
z+4!N$=lWOg)0RtYcl&9v+DJuot+Y{B=BfEm$ilKcMqToK{F4-ExuVOP{<>;-338T~
zi-c6PPg@ic>a<(vo2}C9eGXAOt$s2t_1th`^^P5HpK-oFc_QZiq+lCfEjuOk8Kr?r
z3GF?Khtgx}UoCSj&3J3GL_NGz{``jx8X2K`7aK23+g+}mkw4qubN{|+-~RkFGgD!<
zn-WvJxKh%5k)hyRtry{?Gxmv2`t$bS{>9x{3%9Gkxn5gZcCPG2OPA{2a*fiIb-SnY
zxRgFiHkdFa?)0nK22y9$OD<l>7MOm*Q(8vs>8i>r>W8Z$8ZOp{JI2}Howt9@x$U(_
zuKLcOuDi|TT(WEDCAFI$H2;S>h1#xQT;E~UG?#bf%@uR&3+&P>OYa7j?9kWQvsLMV
zu4aUu$ARK{Ma{Fh&QpGNZK-%+^G7sbkI2bltK;rh&q@Dtxt<ajFkA1!uATeVSI=U2
zAb3l_tLuJ8<9lAy9qZjYR@6_rYI@+>OV6xC?vr=#NP1M337D)h_n#v9PVr&W^TszK
zv-xLSQ%$>YNk8pHMy}hV2cI@ijooWC-AXDr;_tLAHixU<+6LXceOIh)PI+-z(Q4_b
zkq5r(&lH}%rndk1frC=7*SE~R{A5bbos~__`AnT1wPh;r&hZBE_xrlv74i!FP|tPe
z>z+TCME{u_kN3(liJfw$`|AStvnMWU|620QYKdpqhu{tR6CxNFf70Rj8f04R^4(PX
ze%z_09A8eJ+d9?%X==92_RlB1ydLTui~Kn!e{yQ^@6&6lKYtNq*WA7Bd4Jp8Ga@T?
ztf)Rw?6mVKTl~HyO!t*lA1pj(pCMkkIjHSGZoR_)ozkLFJgYqlekb~woejufd-3$m
zRfipx&uS<Aj9zbDt8QzO|4Z@F^XjIpi=-~jJbP7l`|<A^Zp?R?nAIoVVQ<A&Eu&VY
z5M};z{`YUQ)|}z|HK%*a{8_4@?z}V8b$O+mrPI_uU;AAem+uz3SILig-_^ne7gy!!
zsvrGb<9vB-{p>?rdjF5E|9jbKg5CmI{iUbBZc9tKlz-QE-aq!)zW<YdZn!IQ^38(X
z;zxJeuI3DOIBd!PEyq#Hu_5vH-L1Q&`n>WBwBzc3nwISUR{F8##fN#3FE{aJs&0Lf
zzwY_$DK|GS=3WqCWw5Srqv<29vs(>2`HP<~=={*Wkfr(0>K#>A>OWOK$ZJVw>XtI`
zsr<xqspjYEw}QErOzkdqpTdGeQ_8AU1b?57oL+Qv=9>u%tN6I;#iE}xW;&ebtvdGd
zS(Ed8?q7vFj?XI+++cQYfpzm8tKG%cSI_L5cG085tf}kbs~e}RqHUCOV+-{kwmeC>
zT(vj&&iB|`+t$8Zd(`HB&r`R0P0swyoU5)Ii)b9Q`XF+{O6cF@kJ)^T=9l6&?Q*RS
z*KV9JDf^n^_PMj>pJ@D&zq3VSVaAsgeG|94CM|A_mz3m}Xm6dgZPmKQjjivV2v5Fo
zAb)#bu<D1V#&3K{Gxq$bjqls{X!8a^>Av@MhnU-L?)vAIcvj};(dw<c)*8mRh+VH2
z(+J#Kde$p@*W?iCS({>au`Oksby=ukYPHhJy<9nM%(82F1^<_oS9C>Hyqfh)cU4e?
zO!g{a?dX)FsiCnM+dum4=5Jp=<<8nAj!mUDZVQafxjwpBMjX3zbh?_I@%G>Y-A)Fd
zrA#xwtDo8PaG#|6KjSL(dZo4JdiQ6a&fb|mrQVt^dVjI+)Hx>Yv8}fzyl|@3Q@IvC
zZ+TnWqqkWmulr*?>zW-bmNPtlvZl<wX~v?L2hz<Rek$BG%fu+<%Q4sW=MJh=u9KJB
zb>LK5s#1*AJgGa4i;I7Kxbn}Bxn*j$?e3^8+l-`FojDSmxisv_f9LOR>c>vcwo(dC
z&YZUI-<8(q^#^;7IV4owK77;5@6^Yp!|zLHd|c_x@AV~c?Z=}U5r;pBd_F(lJEc*(
zTFWkIj%o2LZbOyFUr$8r`Y>Tfvf;P>V-mYA?u@ipG||T<>iXk6k>DfJIZMyqueW<$
ze|YtJZ7s!<{|f%>?EEz|>CAjteZMukPPCS0&0Q*=bYri^mf9H|^%JkXw!T*R%rDRV
z@{<2y7f<ilF|$5O@a&z61=CE=F1WHH)poaJ;@59=FAW{%b)J+uy8E%=`AJ0w@@CkS
zewds!^K7>{|2OZs((|plce+kxw0jw1D01$^$2WJycvO9MTg{A#+Lzo=(Qlx1c&T9G
zx!bQ=v~LSKzkGjh>-1iO%+#B+>+SCNo_arj54Z5X0~gjgirn~8v6zMF{1(22VRvRf
zUnH+@yhBdv(&Rwtmi(pP?70>wo_Mj~@}Y@A`7a;bt3Ceq?PXhzj4E+%ss4gh(#<+=
zF78~C-eYd1cYx*HlrmP)5*?)_zi09N@?y)Y$Sz#<Ffdv6e8=rQ(Qo!1o~P5d^YZEJ
z(7N~0FH%lg*oj_X&G^f5{>{47x{&$1@8+I%e(r0x=AGV|i*4I0FZRo=w0$4IKVwTU
zv*7hzN9LTCcq}jd|K-!9nbGdO+r)%Vi>Yy?Ys_|=_rHGfL&rJO8`d(5Y!7<K{32h+
z$jHpl(8S!xLfgPl-M~OylS|(>KgA`nBvnDf#mdOQ$kYI?WO`a4%NZt13&;k^y)xOs
zw>>`Xu5Y!wcQx$79{JGdXi*Q3O`JD%o*azRlIPKQ5S_ev+ex+Guh+{fSE@v^Fz;M-
zp(m}X>X+$VTV;{Z4kt0e2CbA2ty5Y*ZJe;~!Zoo=V#j_soj!DMvRLbJ_23o`|6Lsi
z`%TUrjAK_R(dp4y61dC2;nJg;7v+M#8tZ5EZ!&POVXEYQEci=TN25i5jn<T{RVk$l
zW3IHCwuTvs>{w^^fk!6OVcUifjt|x%Zp?w)OOzj2GHMu{JUD@SQNgYPtyL47^>iQH
z6w`aq%&ge3@3X7Gl}Hw5mspmSOEhgVoH>8+KC+bfvaRFdVdE2;OUjk6^chGkYg}^Z
zaFt`dv$B%ngg~vOTtQ1VdI(ABwJ@nnH*&Do(VaSFBZH_{YQtiV6Q`n0nQ}c6L|-y*
z3o~-yzOeP<0v*O5R#q{m7k4ey=TVSg_9{%U5f)i-DdF(KKF7aIYco&sm9gY_u1?@}
zn0!s*g87VNw-UGvrf-om5DnPI7_vCQQGJPqh|a@?`XEMSKW~Q?(K#R2IqbHQbx)9<
z5WrwrB7Gr}G1!J9Xu;7?6V@{y*xs<-W8`wN6FA)bDUq>&%fYmP*(AW6F<P-t<r25T
zrx(xXyFb01A08UGPjY_v;-Y-J=+MnqH(hwJr+x9K4N>RTi!Z+_WHZx>Z`J0L73Kf7
z{?J%(xH0?p3cLE=gkMb09<J*6c3R)1QhtS~{r{LLzY~I+m2a>d_wn7Zdi89<D-#3`
z)UMzRIc47c^JU;xEjy-m|8L!&a=(^_)~pi0abnk-&vpLKvfH9$7Aw!H{`j)G=2rV7
z;{_|TYrRTtUb*(7{tjDtz@~TX<sqf}-Pil(e)@f-@5RTJZ!a9Z98=$X?yj+Nj`!6K
z!WUcLFVtSUYuBYmal39k$<Gaa`s(CWgC(nCc)x$+&8`0Qiv9CLpD&D+#gf;zy?&us
zzO=V$$Lco=)pu8G+>EYPG*3~hSvG&#?{uSQR*|=Ny=9(ox1|2|-9Yta&;LIw`<H(v
z%qmmTx}SMxaf%aPF3*apo_DW5C)Sr<>YjhhZi-*jr)RTM9PV9vwm)^l?-vUCl5fiw
z6mc;ri1=GiP;b5UapisQ-O9oIR~+pYK6%lT)O%;+d^h>MLDmW{-P2`!5+xQMIVk`7
zQD2+Ks`8R7cUh~q4`eT-$S`ltK4I~51>dsF&o62d7I{txKe>?gUd-KOlM}C#8F*PH
z)XRRzy~8M8ESK{2mZLQbZ|*UZpo1~owh`7@S7sDknCA3TcJ_oBCX+o*ui)?qxR*40
zdZJI0(5Y=-Q=0Tv^_A^B`*-KFiYcDa4=>J(jE-*pcBWub-irI2j1#JFBxUBcowqny
z754VVm2++fotH4IX9|irb9lpaMsYT`)VplgM00M`GpH=k%l%d8_lkE#%-N~NSu+HS
zQrtG)YS_Exh^p?C+czbu*1De*b<B&l2rG%+-l#Bjf#z-B-K>F3v#Vc!y=E)<>6hd-
z>r*}j%35<mgqAJ7>uu2DAlECfc;;5IubvYOJwon$H$5}s$yFQa)0g6c_-@_v-qNn*
zvw=0BlkK`8n_IoE<MEOQ3{RYnFtD_Hx&*%XWoK1Xm7?sCbmc)^QPT}(rUUaf9cg0X
zcpe$mwXMbZ_}5b=PJD-aQjaa*{+hV9)>kWOMb>picXds}4yG?F6!VfrN-bUdw=|Zu
zD^3)8Vrko9=&C;Bd$#Z29QCx8#4i@z3db~ODnu(D>`CLZl@qStEN`K<_{~dknSX}g
z1ka>f_MUoi*um|U^T{gj{Y)!u9SeN_{OsFVC0A|i^P{tDvs>C1hh0-9**0AD>++2)
z__r+H+?I2ez{%w^S%PJoE(v5^V$yAwV>G-X!ee+#Y5hE<jSFKWf@dFp$1Hr7=aJV8
z=IoC1GfGX~=D2fm{V0_9UT@gxXm&-S(UAXGOK0VVZ+#8Z^$tyBo_O1kYtqw~TNqMU
z_dJ+rT6xScM?m}9WuLjvbG+IAmfdS^F?@V<O{=9}>f=nYuSxfUR<aw%FS_vHQ^lr9
zN9P=V`&FXbF?Y=b4euz)%<sFd9Fvs@Vqk6$7ExD-VeM)YP+zn#w)byOzj$Q*42_Gw
zMP0+sJm-4K715n=;_zxc_O%{jE**lR?^n9a$~KuMeJ?3w+9b1=$Ks=cQynj`{Z=qo
zE~!*>?r-I7&nseKQ4F$IgN!Dr^1KcD;>Gjgfm-8l&0n1BtVKM$Or@@-1{riMXn7o<
z!ynhdy(sHKuVbWB5SP)EQ%qJ3?pK}X)+ct@y}DNExsxZ`@$rUprxK%!+d4P!D*Q_}
zZR+ItEcZo%M`uU6z^jyEWuLBB35Jb-Z+R}!QQ<n&x}<d0m6q;^0)L&d4K~|Tf)=ap
z>fL_B+0$I3$op_7qe<hr6**jXnz`;GlMXAl{;}Ek{g&pF^j1f?a~3_B=T1j%y%gdZ
zmQp{{WO?8Di9xEIGTnRpvV(G>((azx_-RSbW~cUJM&HZ~&Au$IiZQrq!>;~y!7CPV
z=_}sLyd>{0O0b);Bx#Gzv4*X4GNx!q3m3?r^}S+QJ^7IEUp4F1X_e99b=i))*ZQ!!
z=tL@Kr(auqZ<_DbS#Br1``Kn2noMP%Wuq;rBJDe`z9sjA`@LU#Com|7J(ASC8o!}#
z$z&~+YaOXe3nwy}z2$f>b-$#E$tW&Dc-zs(E52m9C&(vAHSTdgz3RBG`@;*GR);LC
z+T89rmRL>vk=DXwqT1o->APV0ed}E}mpOC3`!pk`=j93SlBEkQ{swJ$xHzj|i@0Gy
z!i?j#UX7P7Ozf?f;p%%X;nwPAr8D`UH+PYlcSX=-Gfh2~t5dor>NH9*u3Z*1?Oe*u
zW63+NaZTSEmbl2cYq3b+l2i9AKJ9LpBc)?=qHoq|^$#h>nB|`+@8B<ewRCMtt6#gn
z&tak8np2j&eR^`*o|j8h^(Q{DZ925==_Bb+4og;KoDdgqd;9Xl>zDNmy$_?MT~#M9
zD%tSvdD((93zvHR3w1tr(tYdlN4>Xfs^n*6ocgL|xn)*&<}1bDza>^SEcRwv{vx1Z
z-(yy>OCHSSQzmYSXP&$N#;JQjF=Zw99X%?_4m0(=D_kMF<C!|^FNdk?mCF|{U0Sl~
z;o@&@UPYU<`M*Dp+FWzcWy#67mAUmN{kI<cb3$Z?{ma(h%4weO60?`?l(c&+;eAOu
z>$7j9*{P_<W{w{u{j@BPXrv3J_$41X)a&1~=dkV3pxNs>KS@dirZ(Bk{<w4Q_u|{Z
zGiPK7)wcCqmdd>p@B7wn!b^iEp+y~@8=vXMN_QO)XPY8YyDO+9#3DIp3#Y%eUzg(9
zdcWO)yS}ojeE&REW&MKOQ+jRT2{uhHZ|S}-3fgw%K<=BfSC1y2?0Il^*VVMoPc3ve
zui9F4!)K?pO0h7Xny0&Gkow`Li#2$*OI*4ou|lDy+A8|G!6RFzrfJMQ3%9PA`@PuO
z#V0Xp)9z}nh5HVkbT{3pvAyz(oxw$w6RV#Hta_AI|Mh`V=-(2XB~0clyGlLMmKD!j
z@L4Taf3fV<YXVzXmobVPUhqCBIVXUravuM*bBraa-mTWFFBtRvRMPLu|5<q3Se?aI
zRBWf&j<bJv-dnTwz5Riz2hl5+9(X1eY<&LNy(OZr%A4}?er|Ez=4EVLbIefg^7f4^
zC#!yHyzaTp)5u+~v*L#Sww5>7d6?N(@qAio_BF%j+`L@ZZyaq}@viKXH8j;f=vvLM
zNZ@rpx@7V1B=r+{%iK6iR=2x{&b;+PWS04w#aohdqQuU{P5UM@cR!~UmuqHx+NJ{g
z&vW`Oc?;d@ys@a;?#r4qolK_R8Y~};*)?WeO!!o>OZ>XTr5>+|Z1ryzED$(oE#vMe
zc{_sXX0_w8!xyYe{>XgNH2o@IulH)oue~2@_IuljXskZn()x7kB4eGvrH@%(NZjYU
zXc2s5XXmy>k5@b_m**98T*03E`M?FYGdw%FcAWj|V<ew?$nA6XiqdG;Jvt`}Ct0ny
zAH;jgw!%>O6)1tdP~do!*nPYHrv}#%-6oM9&8iEQM_-n{eY5h?ho*D(OG2EdZn|E=
zEAZk_&#I7PA4BdNw_aH$kS1znxb|QLi*o4MN`5wuKh6qwTq^XqR-XOqV<_*s%k9?|
zrtKjgZfYb4$8R~CvnOPtO}cOUv8{_=%l3aNls;ycsvq+4>hsB2mAhudtbN8^CtClj
zs)kcp|J(e%wOfB*zIX6)vSvbpm0i48n_=0@v#*p>yWF*`EP^GvXUfNKu#1~_i92k@
zCi8t&alYsD!&q$|C|P{q=;K=a>1dYC+&Omh=K5>P*hGa+f3H~8cj~dp;S5d|y<^-p
zg}>H+N-?xsyX@-ot0$lQnKSR-ny{BUKi{Z}tAFahdiAf&#_p8j*U$ZqulmYyS$%V8
z={^bn^J=G8zx)yXdC#hS>rQFcZ0~vfhUww6#ub-@1v8Ib^VVChuYY{?$(pd>T&s>Z
z;tW^cyveDnHCp@cEZdFw4UcMG_si}}KhJ-@zV`1w!yBI;9Gzghm8tsEYSvx5B4%H9
zoqYQ;>)gnYNA(GL7u_#iG5eZzVcG7dmp_I6+-0NFe`@>F-Jf>IOjm!JS!u=o^7Q6U
zYi6xGmKs{8cmDW|;y}MsnU=Eg^XBxPj;sug3++DnXU(2nGp5u}?JkO3ck1eoT`{pC
z2Jd(M398fGKlT3>lV#g3-jLtFulnOR&CD}-Av3;t#s}QAov?3_#FhH%^L0JXgiU($
zPJZt#WzRopmrtv7e)-g>!dVm`w52Moa8r5cy!5hv`9IZfRE3>8cqS)u%k%pg7pIBc
zF^jrkf2X>vh9$~E<`#q76={b%rx*Bo6c+|?`k&Z4f8vS!1Fgp^mt-B4y&;_b`RWf5
zaqZRn*BuYOAo{M=`_hG)u(gYQ#p<I^t$z7+($?~gD^?YK{Vwz6yZ_c1+e0L_aVhOS
zKfkV`Rci}#T}XDo<M^NVRyY=F^R^}OPI{n_tmk(_OU<r+Q~8ey`J<9I#8%yV7_^eT
zki%Z*oW;$uLuGp}uA1o@eJNk`ew>`V+#ctb{r@D+eArmw!Wrka$74hGPe;k}ZtgUT
z`a_8>7Lxks{FbSz{Pr&Sp1Cz<Q<R?i=DwBNxf=7o#oN}^`yAqHb>Q9<73q=s@l=>?
z%Np~D>YYtrw*C<o`pbGcEH2JJeDdl{?L)0=mF~RvzgKso`rGA$7vCM6;HvA9IYmR{
z-_81vneNipKfc&8t!P8a>E4$mdJhu4d)6*Gv-xqo`0xC<e<fS?SL^JNDDvgL+SO*m
z!6s0k_x<O+oZH&>^sd~9kw`8|^i#A?JTmwC&5W`z-D%4|yN1@CeA;unb^i3-?e%}W
ziXN@~(=cZTyJ?O+=ke)EuYM>$y`%g6lzPB)*(v*{<_D#ITNpe&(e<0;Ki_>0*>!sx
zQc42jYIg5hkyh{f?3~eM2a(6O)~>ugtK!;|pJh+Qws+<De~+uJC_K;=dbsPV=SG3k
ziHyIMMR)UarIv0onk=P$KUD5@=HzKng-Us%JoEScseNznX@898rF&bH{f4WH{w(};
zleygbR7vr?Q-5Q`ZB@63YzSTO=lsQw`TF;pnE3cxWJ?4%LpNUgQ7_BtayBDo83Rur
z^TtoxxGpG#GweFNNcBRP;^&{2AMd^HAF<%!1kDSNU%plrbx`=K%=+r5<*xGO%j7#2
z3Gi&6_?J_qd-{9NZx0Q$nA-yXSe=e&e?RBiCjQvaj<>CKcU&&~{Z#pr$<K<t;M&26
zU)9Cuo>o{zyqO>4zx-;~qqik?^`{r<=|+Ub`#<EE<7Dt+>c2#ldG{oG(uHq0-S0k8
zav($LbNuzsp{!da6tD63c>CXR@zz_dzu`{Nr>(+^i+*2o+*{5tF=_RMeczAI-dkRs
zlVh5bGh0U1d#?PO7r&nxZz!spq}uG`@ZDHXBEWFTgna2G_q7WC|9bWJ;=Al=_f{L!
zE7*#-3hZF6z0GmyxV+|HIgh$otZ%OU%k$o)=wv^4?z!`7n~NVLefn9<dagshux83T
zw)fgop8smD`S*Fr1*^ARPQP#Ua?2L$-+l6NLer$9m+BJF>-#8ZUyO6yywUygGo{0e
zEN?!pbiZ_M(b*`A+g%Lj4cJ8P<#I8*et61$VpV0mLc@kDU916D)2df=>=O++zj^kg
z(@VbZ-?d%!sr~%C<%Ms9p8UM>-L;_k^<+`oB=tGTWyeo<?VI&7R(N}i`2O!p&li4E
z?|#ZPcUi#VPggCrZp`^%U>O~&^N~5lsm8kAd^SV-3w>tJ4{CY4rq7YhE1536(zxtF
z&;1XNQ|8a#VQXJMSNjN`^|s@EA1v*EguFif?Z?DNe1Ep+Gg<%n@qUH-x|^J}Wlz4n
zDam_c_2!74^`fJ`&uliH@7>k>d5hlmTW4D4DbJ2Eueh*&reST`mv3jbtY2nz=F6WO
zJgbg<-)VTe`0`$@S09q|w}iYqw(ES~-Fb7*rTVo?*9)6h?LF!`Uwpf5z5d_RU1ruB
zpIcshc57nd+PPmk(`6Tb+^_Ir<BRtXy!TeO@paqQ2i0ll?TX$|(SG2r{l@Z$H#;T5
z?4^?@8*fke$hUD%ea5>DH$GeUaLrtJ{q}*M?>Db_Cvflg@mqY|8|N3Mbh}^vknu>j
zVvqBg_wz$;+dQg2U$}VXXI|y}gO6p6>K*^P+<dw*-gC!7*<_H2kjsCCD^E9WPyKKz
z_472&?GHZkWiGCddHLzaZR2zNZ)e{A@mRLV^ZU6ylYOeJ)t-pvMBKjl?Q&<)fBEZ|
zb?+Zu9+kdpvGMX>K6xG*KW6?F+P``KG2_R->cay(pX#fp7o<JVzn}W+=zsB!Xa3Jj
z>lL-vcYa$g-LYEnQ5&b^cU!K7^A3J3__bxfadJM-@moKCb}To`W<2+wf!m(lb^7I0
zmcl?wBSS}Xb5}zX11CdgBWEL5a~Ef4BLgRMCr3+j7iSYY1sj4&V!8BvQuESFG8Bx>
zOs6;UuxQrHp53YMk|=WQ;pcnR?9ChBzrJxj@y+jZ1`=-S7d<X?I{jg^V(oNWJVC=l
zWzmI;0U8&&yp*##-4wOXRnJo2U+nj(R!OP8uS4ENVUpgONFmkWl%_KWqIYe}?%8pq
z@kd^cxo6FhW|n!m=KjA<N=Pa-r?h;T$Y|u_cG6;|TBizQeb9wW|DT>hOSBS_xjfri
z;&SFFGfv`qX}u}7MQ1|EB(~0HHy5_2Oz@fHy2+F8q-v$ge31!GK`vdMoG(?EF6o&v
zSz)EZ)FoU()f@CzE8Z3kGo5gHN2u<T!mF$JK1FAT^0)A<m1=k~D^z(yW&TwbnICIs
zHFlS;7AW|ec9p4SUS$2&L!By-tq<R{uf6r)PJQIo!@iN*UN!9gkbIT%`>PwPxZkyB
zU**-`>hfUeT8){nz0NJ0w12Tktj5xEuMg2H>w;eSPkE-Q`X<;aZ|XeV)CEqGb)m<;
zPx06<^fxGJ_qU5mork;Uzsh?Y^N+DA+VUD#YF<ilNl|KIE{K(%l*KjOBZGyP%h1e}
LOI6j?-;E0ZtR7)>

diff --git a/examples/cart_pulling/technical_report/cart_pulling.synctex.gz b/examples/cart_pulling/technical_report/cart_pulling.synctex.gz
deleted file mode 100644
index fafbe7f80a80ebfacefe75076a23a4d1886c3977..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001

literal 62003
zcmb2|=3oE=<|BK(`}NExsqWane-ZZuC8h~M=gcd&Z+_*vSp2gCKUZf{kmlVhEkQyh
zQ%z50Ua6P2E-_c0YhvYWD^bGbb=2MX@xseLE!@;I|G&1c|Mji@_q+Xnm;ZmfJKp~P
zhtK}<XWRe(xvc;H$J@m}e|)`P_wRRkeEqMVpY`qkf1MrwTK{(4zaRbc|NZ)^zrXJD
zZ~pl&?d|`^->?0B`}z9+A7AgU{rB+w{y#tN?yvp**?<4vU!VKq>%adt|MB<d>-_yc
zzizMp{Z!um-;cxo^Y{IGyF35?x6AzZ>pnl;|M%Bjef$5vZeOq8b@Kn0+vWS?k8Y6P
z|L^$o`2GL>Y|pRz+jpk!|L^bdf4{b$-~aIZ`uaa?|Nl?Vx2ykdD*6Az+y481U*49t
zk8gWd+cv-cNBury_M3leZvI?**S!A!pYQo~zoq|w_n%+?`+2JLzYg8Mf7Wj9tv~YZ
za=Cr!vX}ic{yqI{Z+-cXyHEYUrS7`#4gb!Ybuj(U$Di}-|9hwB^x3Dx{(o`y?C*Pe
zZ}$CudHY_`{RMTue?FJDum3xJ|M#%p*Gi&lKfhjo|I63xZ)aa#UVs13r|t6l{+_A-
zb8q(h=qWSy*M2`=|Nq(XdlmPWxV?#%eLs8ZjQ`(W^UtrkT)R2x^7?&${{=fQm!ETV
zU!|v5{oi-L*Vq4i{e8+e^<R_O`)avY`#xdMxPQCj?)G)^cjNc{{Pxybis|Y4_0N=U
z{GXZp!u<aP!!IkpGPSrZ+HCai-?zj3@%8_X>+gS%_^%~?&e46c_1{lFzh9@ed3{~w
z?<;i*xA$eumon+iy8rjr;q70%_Wj@Q`RDcex9jb?zni>%|Iy=lebwdVYG+^M|M$!P
z&^~|P;(uR$ep`G#<NksB|NcIYuUpLdwfOhy^AA>57JJtHdHX&8|G(?!|J*-!=dJYj
z+xzSPz1#j;a^3!4Jo9E*Jf6?HOKjoao9UlSrky(7^6=;Xy)Ww=*8cZj`}w#0u4i9<
z&i||M@SbVp{LLrq|NZ+p+rIXH__mtsA-dD*U+O&mACmOt^LF`vukGuc9amV{{h6L`
z_xH=;?@RtiFU>n%So7n4{jWy1^Zftc+W)=&e*g0C|33csP`}Oo|8y()f8RbH-hV@&
zkN^MOnjhhxmukz`7F~SyV`=|2ImOCXDTbE9Z>Hb-@h10NyqtX8yH(HY?d9Sx*@v4Q
zpYW?_soeGV{(pWSe%)?=dH?cIzojgbtqY|4gLIyjRftd8$aG+p;L4?!eJrceS&LS(
zzuEsbG+@udf_rT5t8K;k-+wNAnlUTuoT1FY?N%>Rj=4-;(;s^>_~gqUljQEs`t)#Z
zmh^Pq$d+Yte8D+h;dz^5UWHH2yIgB{tmI|=<;&(8>*ee0RToxd*`^-qd}m<xb6VX?
z@%Wr=d6)EO&I&%Ucwgy?A93?9KNgIg_i5w0fY{lV^Ix2D^ql-}O5Hxu^gn@nPJfQB
zl)b-+TP=`1JKwS@n|be3krk33qx-(xI4R?68|=MAX6HZk%KMAbGMCslbu(WR-(@!I
zyZni#{fTu^3I8_6)UA~bSl#MWFH`5>-DfqSm-lV#%au!uvrXFK7SFz1yUgjC=KM)3
z)LU#`MLSQ*cr?YYIn(Nn;j_&?<!16%Zbbch-TdVI_22)L!;)XiML)i>E3-sd^mbJF
zhb!B4IbTRx*iYtLmH2vg)wYvMo!zE;)@^&YdRwrE;x4tPx2!oncEtYr8q&_K_$>0i
zMYznpXAAtBLu`6xf04DVE86^Tiruwae>D$BW<P21Si5viP{H3B0zJJ?-&~lrsApT(
z2bmntgcU|L9@{+El~f;@vUcX>VuRKM)xT?(ZD&ucn9S^ZY-5b-43Q5lSJHj8qYJN8
zCSBL7*)Z*y8PBgHK6asRot75O{WjGmZPTgUDczRWqvL~e_0pHAxk_8THWz)Z>?`nv
zUu*p--kTSkcWpEX@zlGv{p`!>bzcmxhgBXgyt2^e!!}0A>63Kb_sKa28hokp%Hc11
zn!@MayGXle(MOFVs~O&^7BI%GSK8eiWx038$3PSADJQ+I-cmlQ{Pj#)U2fQ_Nn7pz
z`1(F`TdlOFVQYET)45$=XZKZ9FBf}1Wz`1vza>kTKZt#GN&oMI8k?p`^E~eQ{rIG{
zl%cI6@l>0<f8d3CTXWw>iR>=Vy*+y})1J6~rT0}8E@zoii`Jf6nb3K!`2RZIi_8AS
zT5GL8Yho-GxL!Zn^SODr<%g9{y6qRNr(RQtsV<-MzI&EWY5fr=mNT~xN9PIhCC}Yy
z>$cWoZH!^kyS=wqM1(GO{A*lS^8CQA-CtHS#VGhMIrD3tn(m^>lkEf}X01*8>!bRu
z)=ocs*Lgm_DIyj!s+SbxR<=K?+<)Qf5u2)_sGRV`nQF(J&q&%{X1TXAu(sgXmv`PL
z_C9f)-lMwv3fI=)tc2Y{BJOXu1S`upYCTj~R+}?1X-S}Y-ozE_s<!fVUg7=8Q`Vfq
zFICWUT3W@R_s;6O6PQewKiTeK7%X>OO!M-Niz~l+n3N@$-BJ|f<b9(3c7j3d*DQ0D
zr1I_eb~-3sa+Zo#N!qzLs^8@*d)ap9P1gb<%XJSOdi(lno=4-eo*lV@Cetq7*q19P
z*0be>?jc#1S9iC$TD;!ld0WiUYh(CsMOLY<{@m^YleMY)a|Qd{w#2P<|HOVaE%Ub0
z9^NNjIngcOUGDbYQ?lVbq?Z%j;y*F!#WvR;PMc$|MY|ZdTfW)m%915ynG@~u;mYf#
zdrD4AjHcvvbC_tdZO;{aa_mRkTKBH0$Md3Hwy>`Dw^o@|T(iE+xl2zz@3vBsosZvb
zF~>P4zGm45EwZ$jncMBrH)G2EZ5>ZmR#xtHUE(p%@!mELi^yv^(JWtmudn{<G4sbm
z!EL%q!qF#FZ!4YHzj^O1UQM-A6}Od&zPWeY7Hj0Yy!xw0tJF^I+hUFPa_??)o$?@O
zeVMb;s){AK-5Qn&PZOG-^c|iZx7ImpOY|lS9}Zi8+n*YOzjKQ2%PMVDc(ho&?ZTI~
zk1w@Uw(hv081r%#>!~Nw8@Hd^De*~o<9FG>eOI)z!!Nlfy|+#}uho0w_pt|-_r*;k
z)xYgi{+9E9o5uCt8`T08{%v=eWBFe>`2YUmegAUK<2!TwZU(uf)-X)A*_!0j9K+DM
zLOUx-F4t@2`i7ks9d+fGhVSmMQn{j}q;_1b@}g?gW_8m=t4=1f)#^ExE&Gyn=}qnP
z)|?49G;b<w3|^$T@$<(Xm2=09Ct1jIO|p=eRw=VH^LSHp#^dbI3YV;N$CZPM?M$G8
zITLRD4481_XN8;4^T(2&bNG2X=l1goS%Y<ns1(}Gn+TC~c20Vp+<fHRakkF6{H&gH
z`qQD37be{Jc|&32=Z%g@&z&71rhp}>Zw1I(?M+axfxHE?!bZ9C^FoDAh`&J&g!!W1
z<Lu8F6K8!^jLbOK{(cVs!!u`peweF$(ZDXYHRbu^b4yLRr)ZiyZ&v%@p#S70cTmQ;
z150CNyDfKq)=p~?-SCZ7bBn%5&fjIq_x35UezLl-JSM$-Y4W<QE4}}hEEV?r*tKu@
zGDkDzy59~*SPgz$dE2vF&Oh+NK84nI+(O!A@e`cBKik2uK73+y_AdLbv__+&VNdN6
zK6lp^nIu2o5&P<Es`kspizThyCx=Egcf7q@xKBT8)4Pmg=PsuF-tM|HuTM=g;4uGo
z_FZyQvMwIA`+I4*<cw!)ENw4%B%GeZZ#q@v^cw%EvwCM<?pFT3&A)!<rJEZcvIok9
zx%!^D`EX*_9QIW=ENycBRi)m!GZ&O_ZUsnMyT91Ta#k?Qg11w4A+M0Nle9`%i-<~L
z%e;w41gqSH+&!F=+%uYw^j%=<lvQN)lv$V#mAo|JhTtuQjmldbliWQVh1_3ALM2U9
z%391k-f-kjxFHxc0b&YBQjz*r*eZ7_FHz`J{?elYaUjf!^B#{lG(8@1fE0io2=j$<
zP;pDz61P}Y?z4hjbCp%*th035xOf-u<IABQWi9Vyd^bDH3{pORFmdvRdZpu>^13U;
ze1yK9s+n3MrEMIsV#8yWe>0q9zeX<K`1s1jh;u(({nf*Q4WjP+G}IK*>~Wue@b;pN
zE9ooq^y_$7Py9~bb&1*c!^zT@^M6=&T-y~nf1ciLlh@0qB>QZ(D|KJJ?DCTtQ)?c`
z-;A6e5qI#8{k53nia!sy=7(K5GH0gzZ0)zUrDyuj#;YbjtM&b~$a{<2bSt+VnvBMW
z+LS#Gam=6CB50?~seEO^48c4o)*1kDkQ+iKK-_Xi!4U2qoZ?ERZWhX>ZW@spJqD#c
z6GW}uW?0o-2j@Yzige*wtf!_(EB74xIYHk1&hx&w*jH2EYQ7X!J|nA~GWQrq@$o+v
z&&6$H(_3~Xx6A>Bx4BzKk?5?%-|4%&M6|EIxTIfOwdRTF-zgifn7<aU(w=&f*I&(h
zc8o#mM$N3GbJ`1X)@?a{XKll#pRcDDMnBJ)Bp$oyYsa0n4R+HOtZgux({@CAfwW2-
z<6VW1Tq~MXj(nH&toUF&=|ci<=g)U+5WKEQrRKY&=Z|;BlRm@_v^dBOtPr={<rVr2
zcMmRc<)FvAje{QVp457*y!d!|<i^LlcP6g~XMtzC%k`E;F7R3Ucz3HtW96OpxT;ST
ztHSkGFY&M0{-x&orOcY`U-o=E_0!e=`p>+VKi^FSN5H=BqCoyL3#*r{b`jjN-hcm>
z#h<U-e)h#D=im%W`B&aYa@1-cxvp%Hyq?rvG4r#!(Zv2GORA+VIt5+IoMl$~>-1E;
z;zyy1T<62C9Eo{$>U7LY_NDW+^*@K7+i`Y^5~zmr*ZC{+E27D)oy*U8lI0gk&u16X
zRc1P;FEMMkQ`&0zMR4WWg<O-)EIjXF)NZGIQpQRdD%kIl%NIH!g|F6a5=518&}?V<
ziMM2a^{5oDXi_PDVLa)~LXfJtAi<6+5Q9ZkW;)NGn8H`<^y=9K&Xu#BExB{~bpOg!
zX_ggdyi9jFxZ~J;v-W$(QqMA_8oiw)KKoLmv-M?_s=Et|N;Y3y8l~>;YjAc!z$DEn
zQ*ViIZ9Fq|&d<|M3;Y*dm=ZZ<b4B#j_h!9Lho4W0{htxD=9X9$W3<YfO+H->yNr8-
zGV25^FCAGL@J!Eled>YsxfaYzS;K7Y-X4+Mvu)4M4Z*^DbzGv%8|KNh+?wL#=VZEq
zO^rLz+8|EicH_rWGnlSTJ23CyEvXyE5z#Ec2P;H#*pHn~ur`QezkDD?F^5@AJ5kyo
zk}LRNg>DY}v2Kt?-pdD4EOVIEUV~%=f)7@>=CB|0PO>(L6TW;PB`}9sZFQ2gL8Msl
z!HU=%_G8@1)&_Bsmk*?5<}j;eCrcYd$^;*r@#y`58K2%CnDIF~!ReiO!l8HO2~O`r
z4W50sHc<OvZIJduYDT~x-WdgdcxOzg5$%cm$JdkjkFTe4ADfy>J+qomJ+oR!JZtj0
z{mjXm_A?4^Ti?ie_kIKC{rioE55o`6_y{sS|3C}K_+RD;hklhO`1}qvc=p%YK<(f8
zgx;Up3BA9()ug_*FDt0O_GZWam+M^KB-j;t&iu=-6SjFJYj(NpEuXWqJCfc1b4SX?
zOMSVit$sQ1rT70O-@6jNG5S1b-VpShc}Cx>;%EBY2M@6u%;i52xo7RE^6!kVY`d>;
z{&Ihu<QfvCpTK=*fdju~^aOoJ=4UyMJWXEDFMVn06)pH^^4#HKwxmJq1D-8mSysCa
zfTC-rj>*N-PD{RtUjEn-t2x8nWCfd=O%gK%JFzCqZDfYvg^is3HyR)~;NT4RHwPd%
zBjJ#;85D;YJQK8rVyPJ)I(Q+NL$s&z2wzX-5jLNS7MStu$86xnGYZSWjc+vUhZ%3v
zY$~^~!BkFh<_eobB{of_)p8f_Uc7y<=Fudheu-zMXP1es*&V+<V7Bt!<@trj%8Y+4
ztq)>xHITd3+BfG~>fAoJlIdTIuIX3ps*4l<dAc$7+{4_^9k)C0u9~>$>)+yy438^q
zgRQwTxQhLRS(0mBvc{Ajw7jb%_bu-rlU4}NDuwAnCOtjeFGaammCq5@4}QCCtHwI%
z-h&!dy3BD)CVgN0h5xp0P$AoT-Tb&kS&OE(dc0k_Eqd>*sZHVQr9zk|UtP^RV@+J{
zft0UatdFm*mX%l^_x3==S1)Gae>)k4t#&aATdis`e0`@8g0CECDb0i8RS9RT%AwfQ
zAaSlV6l+OrJ|_#oe!M;r&)Fb&IoGi@#q1Cq%q)CuCnE%}gc;w!`5I>Yy8|;yVaA&$
z9I}ELZ*7n^7iN6=hGSNu8;)723QsM))mO^p{3;?{UUvaF<X_9|=tv9ZzUIUe@G{xw
z-^U}(g}H(qU;W)yay+}LeLZZw%gV)bV;vYy{z+AgSQEE%Ta_v}na1yJa$DB9sNO`Z
zqKY|8_`;KvQpT&_7IG@3)%#BHIjLpgd*<MGrgb_}MRT$O`A)4`vQzBm<c%SX$Mi+_
zPCNKjH`3@rl~eiZ{V5+#Ri2*y#P7={ft7zZ?*338%=Poc9mmpy>+a8VZ+x9t$z4{P
z5_WLLhW7_%><8i33F5x@n_^9Bxyvq=i1uXu;)CE_d}SBE=-zO>ygfnOH~ip?W$zC_
zFda3pA2W$%O`f%nIeFGT*4-I!CzU7oTn;r@_R`v5*~{n+-OJ!kVpcPWWfq=w&nPgn
zN?gamq<Yr9yMOP4A|}qHc1g)BU)_i|8C87emK<-EQu~(k{ffQh4y75HRc|tXExmH_
z%Z<$+wLed9O>n%N?0<Q^&b_dwyDxvaarw*XDXbjNpP4$EaC}+D5wxIjgZKwwp}n70
zv2OiSRP_4cMd|c?r`8r`yRJ`Fxby3jL-xLn&##5Et)ElwzQ7d}5py-Z-TAdqM0UH_
z3O=75U)dmdE7P?dUyUOkUpt@B8=akSXstOEi*7i!cK$)B?R9L~ccPeu^Y$`A@Y)8`
zyuUn9O;R%oUh_h5HtU+g*XdAA*ABEq=R>h}LT|KvGepx?Hnlrd%n%&Kn0@D$Bvg~B
z!NY6PP|O8&4M@}4M$YZ`8aN@YfN9{JQIO3GaX#4TFbyCZVP23wXq9K%TzY4gap2C<
zH#@&By;=PF#^;pApGQ<h^J<ru%;M#`#`;oC&e3>D<lOt4?iy-@*&f!^Zt4uX{qD~+
z4b!OH-N{jtK=tkAtlM+%PXfoo#jFg4S({$V_p*ktUwLcIIDLAW!Sgw3jW?dnQjooQ
zPv-}xrNDF%|HSjN;!Z#4x}hqm!Mo*Etm1B!=IhhGi_Tmv46bz><=o%in%Z=@tTceP
zhkt$U!F8K+qBp$Onax)w8+p6&<HW7967rG32akNe*|<@A3v+U~2V=I}dE<!B74r_x
zI=;AR<MGYR$^Gf<$K?9i)a1^y`Pj_kol#+<B~fi-ZSbw4EaA<^jD$xYa}FGNe6yi*
zFlaDKc!Y3L<3@y&nAH$|kd>&0`vL6H2Gf3bql-3jw`C)R&z^g{@$SdXe9wfZPqCfX
zI6vELYr@+Tvla(h26@igr*`Ar2Z`77<$9GQw$E~I-#)9`@A+4Wn?ZV!`(M2L6;}M@
zeDqn>_U)k$^P<l#e8~Uk*3xRdx`bbzCEJBJu%6{~c_6~bYt_1{@|>1s&dyo72R`n3
zYq(B5|4-lPwU*9Zai<$P=U<t7sm#~?k45wKY37&rsZ~XGT#-w$a@(QJYJ7<8>VX!)
zJSbk3aE7BCicJj?Tcn{_OTze&ECf68`ba!vgW!c+$9f9bAvl0p*lh<R1g~f^RKC*)
z!B?P0gRCHAJnswxxbb{Fl5pdh)q3E@Gbg*jjIUwK?g?Pb?g=moluRuDv0>x%KEX0}
zPU{)|F+pi9%;FbwvJT#Q=<I&B_t>f9hub^us=Piq{ol!NA_w;f<n3-P2z#ZGSnd{J
zR3FJ9#{F<xG{<vrPSJ0f+~#jm)&B0{j))mjN%{%hPl7GGk|uT({8|+8<Ux|b=7tx2
z_OG~pet6OQrf{ce(25sZd1i<du|<7;dydTuR9~mn`GSkB71q)_bXg~Z16d^RKnobJ
zO7P(-hhkF$#a3x3){>ZfNEU*fczrw`vO(}du479I*daK8SvY71BLuH#GSs}&2*FpN
zMuV&%WIXST32@{2dOYFAGpj9u8_%2^1T(&dEqh4-WA>5&qd?EZa<c%F>Yy8QKfeYy
zEk*cLTsN;|eSMB?SI`Pxn|Zuj{tE8){{N)9D?zRG?@foWS00J=EEA0DBRRyDY_OL;
z0j{alTP>JoT(I8lp3E4gx>s$1xwHN@;SbGA7E8Pr=@wcUH7O}@Q@Pn$u^)4Kv`f+%
zdnaA|vUHc$YGsM*le0{ME@n$|eBNPnL8_+yPN#82ZYB470Z<dOZ1+EzE9*p@JXuyX
zntFZWxu$W_IAXDi)Qo^hybvtJx+ZW^`UW@8c?YFbFCJ)_lmo>Y3B8kSnjxAx+0>?_
zFhj5lWA>CMl2A=11`AcB4Hl}LPw1Tl)3AwA*lSTEr|QiHPSr}b>?v>!yfXrXczrZZ
zviWG7RE}`>Oxw^msX$Fj_2qfTjcNX#zl?o(p9xP7(KuOq=yFcnncj&m!p@evQdfEO
zDoxX0sbSYL)l5#&^?$0(hEl;NPFH__sP@$}5vZ=&`S?lj?FofjUf9g}S0yR2N^;dx
zgUEo1D-w4JGH4rp@o)c-_U^ns>v~?@soIA<AFffjUVGE`qk)>9=I!^PyMMHp>D<~H
z^DtSl>r#49x9iCx(Khp(KG_*?$GSc1_;I{<=EaaF8As+_<_*23`}eKa_b;zKn0v%G
zyG*W97c;(OcyOK9^Nd>>b7!2j`Px*qz}x)um8n`2rMTo*T$?=8yK#Zt#9b#Bec-&m
z!P;=PYL&KNZJ@rZp2Z3=b>pmT%><Pz7gy9zz0`TMrzFE8YQfbRuf8-ap1IU~=2^o<
zoswI(Nc=Gjo9ddsu(IS-A4kl>vTLdC&5aY^)NF7mY725X`bK-!({p0EuOp`y2ydRL
z9u{bSSUWV-fANkKYs2Nj-FAznz55gUzp3-e<;*JquUE(|=rA{&z0{*W@A#!o$%#K7
z{E6vGD!hCmrt8sb?-(1M-ajVM;^wn<9!{z+i<{C^(cXRU=|+)U1F22Ym+j>~8?ZWw
zocd((+SKQw{^iVghAUn#m;Ri_$vf%egQS_wKP+s&WVC*-6!4cnBQ#rZ_o;Qln`ahY
z$=vX3{o;d;-m1Q79b(fC$RAmA!RK75mof94AnTcl+2x&;t!{af-XG0zGq&gDJgwC^
z&m(Ns>XtT@qKfIElU4}+NM1L|$G=wQwAR8tscOUJ&5<d(bN|HGp9%F)RsQx+%;4LC
zve(vz<xPj5$9&q$mANCu*!l7H)4`%qEVbIHp{>(2glBzCNjv%2OG2j9cotLVOque{
zEe8z)#HCk%SX0@ta`uD-qs5lpZiRcjvP7z@&K~tm`*7lQo%&s#@|bT)X5L>G^((JA
zvtsv@xHD-pckuqqUY&m0GVy4pkv98ZgR0BzGt$;sd3;^Fy!)kXiuuy)#Q}yUw|4w{
zaQ^MHGBxkUs?^K-8cy0TN<5+Y(&bs~{C{Oj)w!cC24q&5E1X$AW6lDRn3-qhEEklW
zTxo3lgma^0Z>hQA?4J{Qzb>9BGHKarr_0Ynesq}2J%6Kgmg(q>P|YB>2~Nf{pEl1D
zyOVQQXY%p-k|e{^Pomkk8);vWtlqdpd9&T$Q+)A1Gom6=+$YcPUn*SOY|_4Tns8WJ
zNcgdmM_FOYQPVeH*D#HLtXn-RKizoNB@N3}8KxTR)h7w6Z+_8XnE2t!*%h0oPPv@o
zc1~34=c%5oHy@I3zhmm+yXpHfD}8ZfW5$KFQ|C=w%WsJ@T=dtHPg|uoUF2@4p44UG
zuaniDmAp3gtxY?{x91Uq`-RPm|Git8>z8JdGCSk)sh(vsFLmG45$a#Q?%o-J#|q+R
zr%n2I`o)|Ta1?o68L=(wg4bKtrSFvA&X;`2d9GM;^J2-_9ab9cvt-XEYc4zNm-b|x
zrTpPjXOi-B`6f#ihTI9hK0Ec*=A36bW_(Xh_S{qQUGb}W-9$@%cjosgVjaTMMA%Hu
zr(L|n{o=@+d6R9|%;cV*nWLkr@8!6MdF#~UZ+68MoX+zKuVViw?|=5l`(;W}&DL*s
z=>#0fpZ;XE>J{<jOD=zQJrm$;)^@C7{+%`cssUd!6@tH>XI`|qj^l}y_OB~imsj*F
zYNpA%)h-d2a#*}5zQbI0v)x`D;hY&?3>$Y#q}A#OC9OWT;=O_Ll*s$6pGvlTd9~@>
z&mYQa>t9S>FYXinZ~L!nOaFQ(D@HxJ8#sNV$<M31ZZS<?FFybF(^VJld)z*E>xf$C
zmuu?__lNU3n^r!!p|SdkP(t&xgHh?z>s~6mZ4A8ha;k-{{HmnYPo3+dbawQ;e6lxr
zV&bXeldEO!u95HA8h3H|Ec;E1<X4vUnY^C-cuMW8uPZ-!>ut8{{de=+)9n!{ez8-p
zo8Mde`Q&Pc?doj>`-)s2Ry~a<TWqy5|3;9q-8t>x$t&M~{dR8QJJGL;b-&hK3SIZ*
z)!fH3-<`bFW%1M1_gF@;z|)sv)AUVd&2)@$ch&r$VSh~LLG7`)$J%RV#5b>)<Q&To
zZ~Iz1`lb`>%<M)X*<QWaUrYVhMP2&x(mmiSchvJa^D+cVyzC?<PhRA|r!_6b)&6+S
zqc!nL$BsqrPni|^X$gN{)%E?CR!V36OgIww`Cw4WtIPMZe&_1WzAqPcEpy7cpPHXm
zKRy2LZs76{ns(d%ELg#>8y~py($c5*Cok<R{?t8d&GtVRww`tj<gz){Z^)hbbIrx=
zHLC2HKW}Z`w`r=ilV7p!m8JTZm&gB7oa|pz@-qMH-!10q=iOTxIPU(;5@ppoH2?MC
z>0zCMahG!E8-*X-EqZ^IQrKbs9A*LE;@YMa=Na96{8qdb(K{S==H!R1(|(+n|JPb0
z5p4IT{pSb$XFopNf7@Pf8vpFa#1lbBc=^}n7^?Nine>FatIqGgxO(3Iz2A<^xhdoP
z>hx5t?_D3>N6or^`qjdu7gsOqq_8%GDhE~j&B`b!3{#k1Ra$*Mj`gTC*YlJ5ANI<9
zjeh_7;-S~9-p)%Ib!86PfBj^U%|Ey1+Kx#(`|k(uoHOUwqNT57ZMMBLf8iO({?Rb)
zz}?xRzwX)I_I@5V?_+3A&{9#Q9g{wmUMz`><#z~{lAIFub;%2E>5CQ*tyZd7-<cnH
zY>&*(9EI0aae~ovW=-im5vXCgeCovGhF44^FS@jK=Tt3L*gCC1+k3K?(KUm+Q^f6V
z1n5VIERd0$zs+5F$IEu^U4lEW|JWnc#`NIDnwOK$?^$EXSDv!}ME9MLRiXA$iML%i
z^AcIuH&5O)(cUL^_vPLLd#p9p+hzLhsK!@be7)t0t$5|q<{6%oHw7xqZ`w1bRq)!f
z!-i&ovt>hXo#mLn_Xx-KdpvKYvQJCw|60bIxkTJ>OSVd~Vs*xKPWhW&ky~Epg;p6z
zO-gNCApNdmd1Bxy>37RmnJz68d{E%~`_%k9n_K$zb%l#AI`893)p?X^swthg{lddX
zhfat}O`APs^28UrpJ?k>t@3DoVynMSv^nyEsiyQ%Cq5HXpS=t&4ViMqiv_=?$#_Oe
zJZyH&3Nq6&6Uma<HPN=?)f2U+Vb1xMRrAH%Ou{Z6ndPP|<<vR1y>+7UtU8mGDw8Kq
z@84Lb)4R=uWl!A784d@v^4v-f-e8{<x`ioWuSM0Gef@4<zL@CC@0z%{v%R4&dgVl)
z=8b2MPnez~bLsP=c?ME<CvW8|`j_}=S-ZuX>pi}E{U%D@k5qCxv+c`fhh=PEP83)1
z9P#PXt4(MRlDXoWIBm7Y9REkY-&NEi^RrLvP~EE8_3J>c$W-mQC(lkeW8*d{{z}T+
z`%~N;+(0>azK5l;%*7X)eUq9CWZp)`rv`lK*n8b`hi1Y@m9m%Di!J=~JYRS{T+{8!
z<;b_8KhccaM9FHuN%xaW685tn9_q|FefP~DD+a?CZg(G+>D%n{6J0gO(0bPUCguBS
zfn00MFGiTBKi_bF<(Zq6*&l6dr^@PazB!sBW@Fg6#l-uHR!7pkGk+G&xN6(8;nUYH
z=`8N9P`@25y4j{LUWe*lX|?{C`fP)w0Q1BkxBIb+jb`<}v=O^oWng#r!jlcJ4(^}-
zYR|GGuQE>k%gFYc^zZjnztU$WwX;GdE%KlI%l7Xj^(K+tMgBeJ*Tl}e%-=fa?ZlrO
zSCpKTUD}s9>rkk2F00gX?~4&~`~FQdd+(j{c2>^Q-)$=OR+9_=Bwt(h^QnQOr~2|m
zak|DS$rp}ITGa1;<&vhU*3pGCS?{Nd{LRS?`m&MrqQ<YrIDf9qb~`T|ZHb&egK^@l
zNO}2--a%iC6*Zn}x);^y_1g;A`gocraMf1cd*z+e+j!rSH#A_~=1I#6wobe9bv}dG
z%(I7iUhG{|H=ogTs&;JJf$B{r;eK_2ldno%DEB_Sc#%lO6!~N^Bj!zR=FC}^A9z;S
zz1EISRMFTtIp*n7&(5lvH>ad)eFD#{_>`;u?8~o<PM+m2Elg_r`R8l;ePEQXYmPn0
zUi0+TkvV<Nx3_=Mw*F+WV$<abu?d^2*mKmMeR*@z@%82PZ!+#JP1+s$vS30lmqnWU
zXVJ=;wZCpp^>Yy~Z2bBrr}mbg&P&$!dwgzQobgonr%(5r4VHSl4Q5*AXqlyDPBZTH
zOfy=%Q7hrD^ZF>MjDnbys*h%qS6`f6SY~<5sir!VYt^!p#~+%Q&jq`@Q3^S`%b&UV
z<`g~SZ@EVnMk-wI$U7}5-DmRmeCaE3ld{fxn^wjOy;OAboi9}oTP}UMa&7II_UpIY
zYyX`xdG$GbS)l!d%WEDk^IACNi;$n2!ISxgKU){|pYH6Q<X3k)aPMlx`IF8+)@<IV
zI&1owHU0aY1HJ_E&a(UFoc)WB+pqGPy1jI|pn7fp+uW{w>+kOs{Tq?KC({1$?(b{-
z^Hno{-PpP4<?^2QH#XNTJE@}i%ks$_lfN~03iba^+PnYZBJHD*{~w3z6@5P-E_39n
z<k_J6%=*ST4R-rqW<J_n-M0AkJkH-`{acFO9lv+x6|-VM$hs0mmhUMue_H-@^}WXF
z_-ff}SmmV1vgV>NlPbF+%dO4(PFaK{`Rsk7wf?AY`^oaBXFHrvrSa_+@1B3=foG!T
zo4jW?&OBC|>USpXUXqQGw#kL&xHD-B^G@=6Z|>=?nKk3`Wk=Ji%j0ietp5J-#Og!o
z>B(OzPw5?hkUPIFb^6KWM^61%RHFJ|PwU(>D<Z3<Zi%IB(_2vf=ycC6?%slD5i@7H
zgq)R4eyICRN7a09y|<i2>PxXw$M*u=oAQi4KQ-8~FC&o4V)ja5@2UllcCL&~*nGEe
zO6cwdj(W2DguSiG(x<K5D{$LETuOSYjfmjR2Y;`u$W<)Yo4PT!K=Y2{zEaJ@zt4Bw
z49^u@9DP#e%(4<S&F_H*mrEX>V)ks@HDRLn-=+h3sk4|r>CT?>In*fG_(k=+Gbirr
z-q^Rxpx7e+a;N28>zdH8OU{SBSRWJ!T=MeP`h=#1mRp63tpqh^F--YVwdI_@!Ii0*
zUp8pZ@R7YzmSlF?q%ARV&&<G5vAWeARsqZ*JZU!`xb{4XSP&@JDYNXQZ)DESHQvm-
zB=si0I-28lICHOCV&XGnnOQG;FU+Xeaj$3dVe{WHVfjZUEpG^BDK~yIuk^{4^u28x
ztHoR{+`8D~<{EQsVR-1uyS&nW)Q$hm*<g@;H_Jf!($#m<Hk!?zwpt*(eDTK>A$nyi
z;|0DdO!wTD+PvDYYp+*W_{?DSX<vHYzbLl)s{U#5TbAOyB}L3VGgxD+u6N$#nXGY^
zZ}lbDoD1)c<hcFmo2R|*f>2zYdfMik6|<*Z3DxxV_B&JXVfi`vX34*?=iOhmF1aqW
zfxXUTb3~Z;U+z7ko9^*l?^d0=$*inuqS)KM9}icF{Fo#1OuU)@-cj9no-i-pS@Au*
z5qBc?NyK<PsNT3l{Q0Rrhc?{lN?x`)=t+a`h0ENBXU0T}OJ5Dz^6v7?)?~l`6*eB{
z_^!XTUHskG#Zb?_sQ>TetM7H<gLhtPeR_X#>p5_%Ytx^uV=^@XQ<(ZcC7*GMu*)vd
zi9g*Kx$oDS^-e4mH~Uq?D+SF~?&Dth-e+-Onz2-d)4L-%&pKi)h1oVANn?zj?>yto
zt9NzJ!!j%{UAW(QvnONi;iDQ>Ql(cysy?Q+m73JJ#xF<|x9pvEdGo`hD=sx9tzv6k
zUo1PhChz)&)#-;b8I|5$-u$qj=lH~5tWxK0e@}Yn?9vq*`!f7ul=$njhvuv+we4=b
z5%KAAOt^mOfw=$6^okeQGTG&M{gOW4doAg4XNo-UPuaCgZ+^af^z0dpw6`1Vj~G6w
zx_mvOO?&5x+a|_~UjMrj%}{uX(OO-7GtV{mmZdWv2Aw~V_C;v%_A;ZxmR}@3pIRg0
zzW>wSRR>fvD$W;b+4Q+QU^u5_T{BB(p>VNPVb%TFg=K<<-OZud`{I;(gD+lozWS3v
zzFKUl#*UTOeE3y;b57)Wh0mUM@X(LSfaeQeZVW&CN_0`(HDih8yK{v0%?~w>exK$k
zG1bl3|L@uz$(e3CIweVd>o2dL?JZc4_9kLl(+$2|CsN$_Gd8-XCAv*{`6jP9a--b$
zU+d1SFx(xWX43spd70>}qf+(y(@K^sTPd=mSfX2O^&1|$$z@4?<&3NU7r!is;adG$
zcXv<l{hYS!Yac9&O+Itlo?7eW=(=I2@a9N{iCZgE#f;a@ntky_<LgulZeyjAuSRn&
z>L|x_MlYK9I%C5$gAmcmdwl=iPSLyjiqClI>btz{`pz-$^mgr<?L6hn;+5eXcV>Dp
zYi(`QoBig{PB!6JyY$L@mY(ccrde|ToQ|v=yV>DoHkUhZ_OR79`~E85d?M}2ggI}I
zB!w;VuHdzjDwEvdcP5Rq{MOG+PTCP$-yI3BdTVYs&CoiA_hC1$uC-Kg&4V``fhkF!
z6OC3g`xtZwJy^5h@S__UZ0FqmmVZ2R<sP@;FN>KAPd~o%o=JC7@ti*&l3tx;&EfUZ
zn&oc3(8hY>lJpOcEN!KAx|eaP3GZBVZRIpRd9KdzZ;!NP#rHlC?Z3HGs(nk(*-r1f
zyUr(=En9u})Wb9GmA5_xU;Ug|^_6>;g#QuQ8M=Qj&+I#U@7s*8g=J3zz8K!9^p&5e
zD*CtJ$%?1_>#Yhb+-m34^weGR-|^DtqJQVHbXWO4mvfuzIM3a-d3pV7viWp*ZwAG)
zPuu(Bzc=>(`oR?-QhVn|h)Au}UB2Zns=Kuh?fTM~?OnWJTf^>{th%m0IUW~Fc~4r)
zBu5y1+<156uLmsJTH#jK2c3<ocTf7WNbR*>LHUlH5J(PfnwxO(#oPo{_QIyE>9wNw
zDr%d=Plm=Fsqd9=U%KbZymMct6#rX1?|SFWGY_wL$(+5lWv21EzU;K{s#JZisui<i
z(j;O&v_;E_FI_zCLE+lF8EyRPeKO}-B@L?=ea<s#_V0OLrEMHD?N+Dd-UBZ|%?mD>
z`4(x%OIu`(u6$qqra)ie@0`nmDUX)@FI#$fMgxCU)ymF%_xaX_vlF?M{_Zw99JudB
zr|RA7w{xC-@j16=k{pxe{Muiv@&ZyzmWb9cHNQHNGfnALiOFOu)$sQp=0;rNuB<HH
z<vinw-EOYScUhND)w{-NB0G1+<<yARo4WJ-p3nSj_JCDp*>?Yb@>dF%3T~UW;a6x<
z^X^WeId$ibJt%ryF_p(Uo$2D5w6dkimUqk3=E&w<E_@MLRmM2q3goH@3(NKzbr<Zg
zHe9Y=q_${UT-Vi0#=R+Fp87kQ7Wwb*YOTE}Df2mOP07r}?B(x|PMY_6ZC~)NjXNR|
z{nm%C|NgSUf9vXt8mU*J8h2b+bGy@0R{N%_r}{4+`{yN}Jnrbu=e83v*4JG7;H3M3
z^beZ5Jsx*Wo5%Es;q1$s5AQ9uoZIFev)4>?b%aG=t?=n*yQB>s95&kbF4cOL<*WN&
zk1Y9T^0jGQoX*QTth?Xj#ZKNFyjx97;n3vu5xbXtF8waC+PkVVVR3L(ZDLf_!4jk8
zk6S+Z{$C@w=B><*W1d}|8DF29?hcLF&+z-^nhC2Pem=!xzWi&F*<#L}KW=>uHO`vh
zu2W{DEN-{c>cWe(8~rysZ|YpW)0I8vU0UB+qtdx?XVO^1+2r#Y-M+S3Ub~xRF{gZi
z=>6sKzM`xBEs8EmIaw{5EZ5>ay+*>Tk^iE}n@cm6i|vd1_3|U<qd2ZRjn6vOo?700
zyk*0*K2<+e+bg}F%Cy9Oib*biwe?h^#o^qJ;Ie{*qQ2m=8^)d472-D&O&5xLTjgET
zI6ftISy(6cSMi&IFKzlBr5n%j)T_!qRwhz&w7gQM)w<yOyh-=kTBXlSS;r?n@z~i3
z^J^Yh>Bub1vrGPJc6k2tEyqe;zg}CZ`&VbuLDoMf_8w%*x^w)iN`|qy;cQE(cNtB4
zXU{y8_Czo}|5Qrb?U@B%-!t*@6_;(6^zG)H?xTA_;P(>o&5~vnk9^)S@m^QI`t``c
zH4ol!y9t|pt~ftanpy9_(U*5-M_QIo44t%O!9(T>Hr=^r4RQjE!{_rR_4B`d_{}c6
z>d>O#8Ji9p>c;%tqrvL*{A-dQ`@yZL=lHfSyr!>Q^>UIw=R!ZX%~MvG-j9n=sngFe
zaXWHpzk%O(6PbSfP4^6+7p5L~wb09nf9|I2yKm>+owBa%aLeIcX_bt8<>s^UotM`+
zKG^lVDVitB?8x2ouVWRC$z1AImDOgg{WVp#!}D0tGu_<>(o7!7Zxh}uc{OTpV{Kqp
zRr5aY$&m{LuO$Dwd{&9WQ9W(*jEAeAhAJAHNtPyg9$$22P9A@Z$i&Ya&U&*tpNQ#s
zxvyXSV8Pe3I@j{=>OH^RExK8Yt@C~Slc{~GiL00FZoc>X!=vn7hYk5}A51v1IjL>^
zwWEG%Uwj0oZ`1X99=xJ_yKmZ)M>j0?tvrxs@$%u~*=H6VZ%t2aZF_1fembQsc)dxt
z&RKz!#lqc@E2qn>=j!Cnxomjd;9~!SEnj-xdj+4pe4sq#&6&&I&kI(alrJ<pY$!Qh
zTz^fkX!Fe(>-rQsPCfd2IrG<TiK3P97fe#8SKXemWPj|-h?aA;-y}~z%z4IjR-^J<
zpIS~cuV8Z7kA#XFsb!qcMgQbXE0A=JnU$!$TlV4xL5BOi2Y9MB7dtiXP}t$8o@N|#
zA*QprsqOtg#&-`=+AL?X?N~bV;MB>sx2F0nmhkgD`;xVM?m2^q0E5?;9wz7NPb<07
zGU;9N-U(Gr3mcnv{1R$oJF47fY0YAJ@lx{2<M-8Oq!dJd6H<G8sbXn~<Y{(^Ls!hR
z4{nW7Puo0c#mD7)9GW-BH9zJ{Gf8#{*W8(R?4wv)dfwf#6L~)2yN&ni&6=<+J7>q_
zmBG)|a$f7Ly^t#05zCtQQ!M(Swc&DW0YBZjGv4a{ZCZG93de(uO$SA4OOia7CkA-;
zUrnAhU+voO7k?QZ-|VTeT4UmOGj-0k%a<}Qtg<O?(EPx8LG0^tP0r_jr|+)GyL8~<
z*^MR3C6Bli^u0+pzEdYxx<x8tr;B{LN!B-$Or47ll5QF-eyEZ5)?=6C&IohE*_AS^
z+r3SSHfEfgf6=2eA~q~Of>+Ud?Hb|DkxTBk7i*iaSiU}*Gp&D0fn8l<*ownP{d8X5
zxNf?9`@72anU}uidF!p&eV1kN*+ZWKe+K1m-n{<1z0XU<`I|pacvrxC?c&mY@75TZ
zHU7&h>aJc9S*M;E&mU`hF>;r5$MOTQv$l!t@V>bEDZg%kxcdBCx&`9P_s6kaS=e9Y
zc{$@@ro^Fnn-~u~s90)0rKINe;kSS0{0qB$`|SNs4y7y3e`A^@vaaiNEYG!!#V?aX
zSo&ov<Ae6QCP!t;FPnGX^+3t0{hJ@9?Tz}^Guy<AH}&Aj<z{_h71F!DTtCgQP`|+T
z*^G&W9T&q7Kf7C8v^Dsqr@aNkY|r@|Qipc<|6+~)nA`q4?DFmth2gAM&buBgXq$W}
z^y1qx<>!SeM!%PLUE8v?Yu?wapWdr8{Oq<yyB7a?o!Ve2ResE0?8ubYvz{<CTwR?Y
zm|x;?Tya8&g)7M2(R)8IUrkOpIh#8p$U<AMv{6>ca<?C+Wq7=lAK!%=PivQVt`Ux#
zXsItY@yq@5B^KFR%`E<|eRkP>zqR1Q$-iGG3Hm<N%6@e!>Xqmue({Cs*4g*<o&4{*
zzE~5~-Enrs2~ozqH$=*p%$e_hxpKc{-qaaq3i!nGo*g>l`eu1nlHd1hDyFtacKuBC
zaj%ImwN0FTdXAj&v`PIdcXVc`opoRRNX_NO+ar_uqMf&tyb^ZvT))wJO39~_k9Fs-
zj@YqSPwCbAD4m?kyF2xbbA(sSJ}Q>BW0HPJlHc<Ex_zcSHzVKtv_JM{$I}a69F;E^
z&VIN^w_hT*O0(c%n0}hE3!kr@&RMQ^L43gvvvo{VWef9t`Gk4)u_v=uFgmwb2_2ks
zR^XiKvZ<1O_r5*KYGYV<gZ0^_tY^2TpNoE&f6;LFn@e-f`K*?g2vXwzD#n%drQbt3
z-YzR+x%Y3ad`*sk2fKY7jz0?3;VE|S)jtvzzH9CLgg-N8Z!A5yljkO@+2VCY!kcFv
z);u7!FHpDj_=bC(H+3F7nkm&c`D~E~`}LKMcc#Rhd3j^&lBJJRwq3mxyyWMpyAL<o
z3ltjmN8e?g^<%Z<y9bJPiN~y*s*E~}m)NbbcRuws$xM4@)sYbQheoSs^8|B!Ka_k~
z!7^*1#!D0C*+Om-HR2~teR`v;x=)<gJL7V!%B0mx4y*G;St+g6e0f7}>Xa`XUsv1x
z)ymWPu=~shz9T(atm1R-pWUFWnefqirGI6dt5B}`v@aaD<}Q1)%KOopUwKZv%{_}X
zlFP1eZJd{T{LPA#ZTE_nO<%_yRB0}KdF#fe9U&e46W6?oD7>>p+nuv0bFRw#r-tlb
zH!WEzUYzl=RMy7lW^?Uqk+j;HDDy76jVeX?>9sXGi@mA}POf};{b@<Em1*OGrRw>w
zpKsb|W3nw(w|<t#r!RXF8aU?*vHz6{ne=R)$<oJPt_C`n_rL5Aj#>66^8=^j<>h8E
zS4w;`y{dTMJ$qKt-mjN;Z0W>1Rj&6RAM$mT7mtc?l`nK#yGXvqEUI#apqTD_Deg_{
zpBLsm^?T@a@RrNbz$fAPS?g9DUnco@ei)lcZf>f>#nng8Z!%IixqRCi9uH8qV(zt&
zuuWre7mJr$K4(So#WT;<YO_M7S*3c{uYMVOMy*ak=6HFVd`i#`t##c6i6`AZ{me{t
zxEdxC=DL2`e#<qJYO=ZyYrR}QozZex2wSpxchv#28-fgiTW#C^8p_7>N<E&!pE{|a
z@$QOvz8_7;XY~0VlAGNE+Lu>en6j=*Q!u<{CwKa!`CsSnuFyN@{)VG&2Ajw1^(Lur
zXVq+(kUQs3ncCx+ppUWl*vq_P-P)p59~t$`yf~*XyZ-Nt*(;BS&XL^Yo#a+?7&JXN
z<L2d6B3Hj}&NTYmxr?XLjN7>8(ZOq9Hh%cQk-2B~rp25V*AKX7J^Xl}^lY)g=C5@Y
zMXq0hE?j8q?<~||wM&{jU3~eQJ%=~_{1Fhu^~OVSeu9xRhfR#eeht>0@odx0`_nA^
z`ZBt>jbo0bTN}<+EKyz;e1*G{cj>{hM_Fy}1NP1Fjd6T^_!Mti@-O$L`96g)SN0uj
zKE1S-@xdJSi<1^Vb-KGLqIxQKxo2YWmz1`<ENZh4p4l+dzat`1%{XM|;oTFAmKRw%
zg!Zg{Yi+nZ*_mzM_MV%fHK*O5$Z4|L@vE9?pI9gCUDb45^!b~DC4WzJ?_#iB$n$xI
z?6>%3(V($P=X9^ttG0fN37mDNK$Y{{sTZNyh0MHpys~FkeRkXYnTc0AH(7mMTIt0_
zM;a8P4Oh=E?VCO0tk9k}B3GT}b@ML$_TgZUxO9n$6#L}2N9WvY3cb5&_9c5cnPaak
zIfBKHy{hfX5B+G_6WS}jsAc1++AV8KCA5nePcZ)GuWs8|#Bt4K$;Z2eYw~s_D`;~}
z^$1HZ5<m6ID`VrD2_NnygzbHoY_i(@sP>$zVb8nLOSK=UEeJJF^ExmimE}gCU&+Rd
zqTLF6yS19HOxoDJBDLqR+D{|Hh($*Wm+kI7xb~ZSVfo@CZWa=kJa2OBc5yP{R$))y
z<f%Hdqi>SWW%IC5H;zXMSO30O<oTZa=EM<K&g3}G<#BUmKQHQJ*e&t((WG{XBJtGj
z_RcEX;}gGh9dr~If1?`{ax5_K%>zwG=c3Zx)%vN*E=<QS&B|-Z*4{ATnthh-z25#4
z!9`0BZt~x!&=Di-Y`LYq&{QVq<&vBhW~QC_D{6OsXk<xmZfDA1?4Od->f})|WBEIW
zkb~D#S@^_1uT1lw?6+n$YplzxnEm<JZ%J>JePl7!(^_WPJ)_In*DtWI%bW9l>&6M5
zrDBKY_|#r#*PPswouBr$DPwc$rDJZM(QdgFE4DxJ4>#J$RCvwI#80kxlWu!&vDyuR
zr5V=qn<w?Wf6A4@VRGtD^Uo)Fy}j{<Wf5)0b2cjNi*l=<tNXNThTP>ewRyJbzB$jj
zIc^<#D5ySFJ2sDFxBBVOggJi}shxh9;kY|3bLakS=&;oyl{v<5P4*Ragde&5X9}}?
zU)cPwQ`f4P@OiH*u`4nRao&4>=a0zy7X{{s)V6a!75(cHyW-w;+ZXD0ti;p*N;Ugl
zT(0@9>sHBS^?%(K{*&$Y99BO6bY*(e;%R*xj$U>aAypc`_~QRhDVbl``(cjUhT@z$
zy*UBPR#sp0w~&}LwWPmSJoZ=gTcg+wD_38A@T;)+-k!B5&z}qX75!9ak?OIhb2lg7
zPx-p=xTaS4t}i>PH<jpuW(mH^UBBOLtKrq?{?jl`(YDX@m)!Cv3buaL*TT0cX~_lY
z@4U3}?d7j8uNNmYT3FrR%g*hlnkLz};BSgsoO0<EqZzDbpKsi_*J)|{C}!d`x#WFI
z;|-2j3S`!X?qV{!+<9}&6$}5$K&$M6qJ{O}^TVz7O%#}a`QnDii5b0nXQv)rbN2+#
z#=}SFXPPOm-*BMx;)Q}A7k<v3akfBd!M&(;HqwvYr$%qs{4(tDR|Cb~PEfDoT%Q%o
zrvPupTdA+N&M!Cq`RD4)iw#e2tYOXBHM{qv&zX11Oj{=|@Y$bRxLl^z+5W0N$78-4
z`L~-LIi%{OO|>SyJu*k`MEr@$b9z^9EIR#0Y2U?PH+8OY$DF#WBVy>i<M?8qr5ZA7
zZ|BLbh~QeN<JCA@w<BLWZAz?>xAEj!votMMzef`u+oZeOF_<Z=-Q>(NeWl3Pt{d78
zQ-j1U1jILFO;O+M!Zd$VSJ?aFW19}7s2#r{p0<|t-q~X%TT_K5FK>LS+2Nf#^DEP&
zWpV7ea}o}hvey23A6~WY_yYA>oi)djukr7k=QIDy$I9r->-#n=n*YH{^zWmM2OT|+
zyM8M>$Ii`IdF{Bk=bHIFzjhd0)c$$9swnW{@_BNmwK>n%r(}D4U%2DW_0Q3@`n53|
zKAXC^R9l|xQnQz4u&nMC{jp2r-<JLBZ$$pyw|{*?Da+%$46Usk9><q8fVKl3RGDS+
z`tiO46Vht?R~L!azRK9B@vCCik|pXbTQrL8PF_9SGTH8D$hFy#`%_pF=Y0`;{OyC6
z)jG#d#eW~Hnm6b9uZ=%C#I}BE@UV&fb^E8&?cLAHrwBg&@P}uGRzdQM#amTt1T3Dl
z+W4-_X3k&kB|fdq_)uBfnbrW49RhEiP5dSY^tOj_$h5oapNfz+N)I#r#dIi9!tg<l
z8sob!o>#Z;O#f2$ayLuZv)Oht_7+aMuVTONh~nI;>5_-Muc@9X*Hk+Gg>P^CdDB4O
zk5SEgMb4YvOLffjv9-6kwBXTsySHcB^~GM*o6NtjUmDNfciU1v$jJ1bVyT|egdb)J
zuS!EpV_(Wx`yF+t*~E6yQq=!beV5RR{H&RuU$0ke^8Nnnrc#2pZPN4JqntbH1ruMF
z9X&XGw$y}mqR&IKdNpR*SKT??d9hWWn=vnu>*m9m?|VP-OY5Be+FtzY_NfK6Q7axb
zy-uFm)&HfrZO+e7*BIyQOEFslKWvPs_#S`Fn)%a>b3$U57QM}$C%7RX{O4VcURf^I
ze<IxfN)-<rGt83vVKc8lVD7vl)%vP;S8hKxxzKrXajoWZpR7Hh*{Z_rwq7${y}j7B
zROG`&J@ec-uXDD}eU)yZ|0s+hsakGgXv7DzX>aB!9urun$I`gqoJII`jRTF-8f^Qz
zpK1RxTqqoQalf4DkBVI>p}Qw+U^}>D%WQ@Afb?v!J?A)*J71I@C_kFM_=0WC-D4L_
zUp4Xj>Y9tW>ztnD^r%CB?H8_?Kb!nYcTUxE4PN~(Xj#zSUe<kwHIAyabxM2g?mD?c
z>-7uo9@oxgk$pwS609bk5VaBzeIfLH>1RRn_nQ;6ZrdLI_cyscc-yG}Jtmp_f(O$q
zR&_QmoHy6wl6NP=#ggn<&%W}0QajbLGSl#~%au3N6S8mo5%m6WsZHQuw@gvidc(ts
zN8fFp^6KZ|s-+yf{2_;KG!$yr<`yllI_=JKG_mu!@`<Xw{1y*aTg+Niq8;NYn!RO$
z_fF1^^)3YkVtcl2x3Z5kIQeK(@8%`Xi#;8gEdoWJPV43<=&`=GK<VqhX`2_gpKi1{
z8I?c%(O1S_!s4dNRo4xBFNg(B|Ik=0CXiZW=l58>Z|$R9H*PXnPl&PKu!(hF+GFXv
zITO9^rr1V{-1+)4jeAvIjl*2llMhcFz0kigevRw=ZHx4FT-<xtzo}oiyXL~4$-7od
z?`nP)ep|b4s^HBp6XvM32Cpmd46Q!s_q|Kq`tIx4HzC0_3Cm9(pJf+3?`md2S5n>g
z&#SBU{)^mq`sPuMBVNTX%$x4X6?`(#`+M{7gdRQq$N#hKw9hB4uBa4?w*96fa#a0%
z($52*WIuNQe`xjE-gRH_<mFcF83N0gh1WA~Km3L1qg27e=CsDFu34=c62(@WbI^~8
z^6Qx+A0V;w*3tCZSq*&tDUG}QdLw;gkIKJx`g^cO&3?gF!Fydxo=?j<;G1}aX?9`b
zoVTB6Miko!@T-3n-KqDrv)GceR*v<!{%;$p&7ETHJeU7GN<PF{W4`}KghA`>n@Sg#
zWaQ3cm7Koo@#(`eMD;R{^_p&G?X9(YzVAf*8rS^CF2_urTGRsNFR~q6$m_#Ys!}=q
zk;(jxkBaOjKiZdVce|&v`e-4Dn)PV+v&|1Tnti@`f#sR`);Z^wty45VD<82)=l#6%
z5%p4q(QdD5zL|YF5m@_b)1nQtu5atQzGvIj$CbW;HM6dZe62H*K6?4Wk2vexs2TST
zO?hd(ob{r5e%CR}->UBpZmEoUS8cy;-uY)Yj|WC1921OS$z?fq$|FGMfk%r$^n<p9
znqPBSEfjiozdN?(M52=WowH(+yMua@0@oknaou>pkozrT@xi7YpBj!<9tnRrn|c3~
zM;m9}`?{!b%JeF~i0%Agl2XUQtvI(W{u5Lv^VGG_^i=nu-EKeca%>Ej0Z|Jz_oYvf
zmw#P3MSk{yKg+@v*DN>a`*iHloddt!e|p!;Jyl)&z4ue|FPpp#hsvhJYxXVv<CQP<
zboQg&Za<f;>$?_{c-iB-pLOXJ`TK{aysUQr`Tst*J+DnN=hkOdHuqF+^xJ43&3ux0
z^y!JiT<@hT&DNH!x9GE(9kyC?U-lD8xoqQ4AGl|_&D%G1m9l@ZgP_mvH~E5}du$F@
zPG)FoTYBrs8N=20%Q+ofw{dRp({&Y%`OV^TK#XI>JQMCW|BYw0u6B<SVeGplp}V?4
zKWdii35(q;BNWmWzGjVI!!k$oZ^w?=>8HA8_#9I@mNId}fezOvCzY;R-0yOA44Ha?
zMSn6wdfDFJ9eX$J2!8(O#f5#x93(dyWC{sARnuVKW@~bAwFqasT8=2MtJaRCyx&*%
z^E(!E`Wb18smhx^JMcrmx4^b#wfM5_`s(3)Caseeha@X|S?*5|Y<l*P@AE>7h-&wc
zzLgdnSDKm`Hn*-U|Mhbrr-bVVYwm*CelqbIe%yzy+8+~->KA-;DQ|g%04wjwvtn}c
zt&3)Qn{pm$TJg^JL)o`~dL8$#&KLgY^-`y0Q9-ZFwp=mCDH$@Buig889o_u4_1e|K
z*E+|nq$Ud0*My0@b`IEOS#YxXHOq9yJV&#g+bcw+KY5({u_8H5Z{~uuXI?$~G{mml
zD~NrO<M{WL!L{>Zh7T77xK1e0)6|H3*!1PFhS-l!vHELM4&K&$k>nYBwaXz^b>^8$
zKdC=#w;g$<ZIWi%%KEfbEo_Uj`f4nzK5g^c&6X2C{*>8RD$2ZPs*ox7o3}P5+>f*t
zy46Xr%6+#|QPuu6b4{8c*B$qxN{?121?nhW_3G6&j8vG^9IR8c>A8+cltM%}N0%$F
z<x&oT%x4~6VHSs?da?o+<uy8bZ#}?weobV;tL?K|H{X2G6w((RmY@FkrPI=wUR~EC
zD|hbNyQpAm@bmnIAwAY--rhKBaz(}Uf89H$tBH*)O){63ZZ7!MJ#XE-y%vI&L5~;Q
z?6TF830AB5;}o*%v3Qo86Z6&dI#Fx?=0dB({c{#^MZCH$l4Jk=m7VIVeajP9MsF<Y
z)iscMwCm`l&?gxkhd(lI<Z*MBv00PYFW%;2>8P#dTz%!m!Zf2lNs7;9bd$=jaERy#
zbhqq1=D1N~hiJ_@J*6A%+za)Y1uuPmHd{+wyu0n9g>;n;SBZW?MV9od+FQqSI>aaJ
z5;u^#6fj}a$Ir%3Iwoh-otyZ~GRr-0rn0Ri@BO?}7iBqY=9oGbrSJI|c)>Mq=hQ@@
z59hx9u9#2|>27ej!ht!e@cH+Y7t(X|^nK%JN$Ck5Rc)Olc+uD5;GHWTZ33-lC$RD*
z-uU?MxJ>3PoBaLzpT0O^@aR#?qx8cq9#acVzT6Q}uYB#!5&qEX;As_yJ^Q63rM5TT
z(trIfDQAiD|4UwWHy`_LQh2p?t@Rm`ZJcq@{|_7u^ZJ`0UaMERu2ANk#*G!1<tB4g
z-a8falw+OPL%sgC9cNyzcxZPeyw!T|tEDF=E1q4oV_o4_w^vW&rk?6QKfx#|?(BN5
zb$2Fy`m<`8o2`T&)84@JZjTMyKT9!+ca}t}uC}u>W9#vbzgI165yRqhgx9+2=~nqq
z#|j&Iy;Qp19!)y@S90$}<LPqF^Y%8YYcJ(F()&wpa<cyVw$j>6lbq*gSIwysS+{IH
zZ(+gj500)SS6{AM{bRG@I=hXgGHrP?Y~HbD7l|bV&+=d9WBG{9JG|Y{);-4Hac0RJ
z-jB6+4h!y+WHVf{uJp?3U&j~iXfkH4Jh$-}3rB4BLD`CSQRn$WdGXRby-7brUwyCQ
z|N2j|==h{03EsZLRev7}>al#cDK9cS!?&B|c)R#vy)EwlKWvwf`!1v2c(0#pqIP)s
zw)^L8Bim1_ERny+5a{o{*>3TJYbOprxGa+1lKJM=+}BwNeI=8-7argG^#MarQ_P`C
z{ko}--JS)U$?>>nH}TOHlQSQht#(RW^ImB9aUGAK<+jP)4Q~12B8*>sykmleCp_-z
z{hTbhVfF2+5%pD)Zz_v3C3!aHJm{PAyJ{cL{)iLjWpZN`4z68S+}GD3y>8jtdoq6o
zk4~6VpJO_YH&gEvN9_iqC7L&`3Qp$TAHjKq>By&mc~)2Ym)2#)#_K$pl+2+x>k4O_
z8Y6G*mA+Sh)j6jt9e%zwK1pTo3h^t-g^LQ>wyu1obi#c}pU|uap<J==&uvVNwD0)!
zXqjH)?<EEw(>I$e$q{^3vhIdwLF5G6-sE8GmID*L-+c<%m~-P$(U-P7F&#J2FAnqX
z*;>c{N_Sf)K4k)5j^@Fw%Vx%3G8MR9p|Y>#hKRoXx-KE!84;3C&fH|XK5zcTQa#4#
z2>Ejzp^I716<^<RO6NzCszA3#>|XIbbNlaHy&vl8qF|(yF>h&r$+}-(w_VM*{V3m4
zU-a?!cg0`L-Roa&Xo&q|82irX*%xu!*z%9skDk`{&suw9@gc+1LwfsGe9_xCt$oLj
zSH}Cz^iN!yVC8$Hsi8HZ<#Ga}z25<&--)}9A1vz)oAe_1&C?{0Jwk>L-?#1TQ2e&*
zdy(Ohy+wBN+Acdj-1~8J0#{c-YHDjoaH5ILw3`#yCM|BOoY3aZySX$a=Ju@1hDvNX
zP5Mvzbp@F7W;)rt7Zhyjd8^=B?-uhaw?M?rP-jQ8$um_YCix`&zc~?yGoOnp`7Kpu
zIdH+~SNHyQ8TH1Vso(d-6bRoBK5;epf7g{Gzj*W;MO;4|V>*)3wb6M&;1=T}Uq$!E
z@aXOox^`o!;=Ut4{O+-IXkOyBINlJ@TKeZ&@sf>y4d(8VOuOUuaC%$ks#Vjw6$Pu`
z2*yZ>3DhjV5_K^A+AVfH=lPl2a^5bllYRGOxuV`TMRudv3zQ!<&F`=_IvkKKFyVEr
za6#X`x^*U}WthLt$vK<TaXK!$q^C8}Mxa>vY}>?HE1i!_nwsdT$7(LE_KSV`1T$x)
zGv_)Jj~)NzcaMcrBs-^N!}5b-?U~}P3*T|vFU`r`c-MEgQO@2X0~yw;^0kR?g6Hkd
zcG&7&?wXOr!j)R<wle&yOvTDcg6}d-V{BNiYHyot&S-e?4!6be2_F(~>J|6w=-e{7
zTTyT8*^V6>4c3I8EiE!^**wc|)#inVKYNMJek9<qm8WfG+_Bal!NQNkxqr@7u2`b|
z!{#<i{2G>goduaP?X#}7dp}?PEKaXYtdO@Tt1V)!?HmcKM}6xicPsja^GRO~@3<#x
zzEh&A;!tfVU)x3TJ6DaRAFY#o{OnbVvr;I>Nh9fH39m(8YCFfwym|Vl!R0qIFD+WT
z^wowXR;4^`5>EY6vJTlsD|g9%EJ%Kua&$wy(CfpSd)pQ}yg&C<OYO7B-7T+_J2>*T
zCfB+dTJ+5Ber@Db!h8Ja;e+QYN{R$4#Jj>-CCsZBohxHFI!}0;YiPF}e0*!ZfplAi
z>$Hd|6OZ*rEMC*wHd9Ofbd2_qp4~gFc5-CQQqZpwOUU-*NL}ad-K%i<b<|YBXtxKs
zXWMqn(VCXJ_J-8+Rg=39T<zFjTpH=#teK}2C#w2LOv*ZZdavoGhnsfk95R%ttf|mh
zBwg{cyM2B3%O|&%e0-?L!JZ`YqGRc#SR*-kIi@?cS;yPgm+Mb-pDo6JpZ%*euY2RY
zyBntYn7mNbdbx7`D>?g%=|80WB({5WJ?LfaXf1M{5U?uLPi6JJ2$QE0A9}U4ER$^a
zwo4VCi8y_Ur<h~M?yq?>x+EU$o3A|erofbyEt{NFzUx-DtdQef$$lU@UV2it%-W`o
zj^c=*NU0?06pk*%cke$vHZE%mVcs`A+&O2?lC~UyS24zGir&9Enz~uh>{^0AaF%G1
zRAJJKCrT$c#os@(bbs|XVo9XfQh~-5ekUg=KRPyj375ccjWYr79IjMsZz;OLSEap}
zL#6H6gvS~ec1K$zb)0;^Yxa%_)9Ye2K7RFLt3Tawy7i*f^`8Y>J{&JByKu3oO;A3B
zvA53i?5YEqVLD9fbT8;Qo%wOVIQqyhL)VQ99_~^(t8_JXM;C+m!^H0&r-+7jbhjr3
zJ~-_o_G6tuhpWGssoCMc_4dLCZ~t6$EBd*3^kRYF&Gw%|Om>8paF<N9v5<dsIm{(A
z_IB3_jd}hTb6rIarYb}Wx_;0yo43sJO~~w=jtOmtH8u7G=WaT%RMJjE>`KYT_O+b%
z{2ayKeymDS(%!LaUBSG`$3k~6eEV}*U%0+z%`G(vfpzLEw^z<@T|N7E#)@~W`O^<v
ztF?4zf6!SSY3Ram?!w8V0(^#LOlx@zpMEJa{9@7h=FcUAgyM`3pN&~o%>k7y4qKEP
zOYan!B+WRmCTRw*=gEZSF2+35^tC^hYAZVJ)Z~vB=+<5%zfVCZdxreHTYh_gXQg&1
zI4K_eDVdpIU-0<FC4u=8-s<9qcZF3wS-S9eY|imJMg<o+4)yU&eSFkFrGG(Xv*NT)
zuVdQ^WCd5-{^)snEPYM6r~J%0tClL}O@8xKNumAVWOhsL7p50hUto!_-JV=}bn>lh
zb?c`u<UU?uK8MAq_}g9!^-nu52M1ig)y*q*X4bAH@f*#KmGE?aOe+vQC3AzHN#C`h
zaEk56%QJqZUTD2}A!zgYh*QbV@qLFqO#`|uUuj<1ofyQkTbFObV`fFW&HimJn+s+8
z<3e&K9jUo;(pBJ9>y<7B<E%HVJgvL)H{Nw!P!KpbKY&yGKv|LD5!u(O&r>BgA2pp-
zsmEnjZyDO~S-P^OI3nGNqj^U~@s7%0cTO5eOVwDrY>$x;lJ_Z%k?Ts@=(#K}RI0e-
z25U#)hiS=T&i&botty2pEcVQ5xWTthY(C4ALv#3UMYMU;IUaOxy{+ASc7sAq%ADdO
zX&+`c6#G0p@N)6f;M92M<g;xiE)Sy~r?QIAS`suTy8me2UgJ+ovO4+`e-;!gFTAJ{
z8LCjYT)mNH=bKXkeUS_Lf>^_y<^2m;UT27Wdigx&)ucXw+qG8T<&G$FM@*jnr+N3I
zts$09EmQsUm}(r#_bzzWA-tWl{o&qu%3&v8NalXpywJO}|60O~BNvq41gMKUS_qtR
z5q`i_>D%CJ;3w+xI>d4By(rNMPr|h7WRiYM%$)YMAy{hX<joB>HM7`jXBKT?&ocXN
zDxLX+BPk=ZVN>Oro4Z0y6l9jgZ7$7Zu<kk5u3dV6!cI;Lcb3?ryiBhSPn8nbD3e&j
z#<AiAN8=U~m9BiNof2)kwwvkjcK)0ar`IGQ?6>)B(~~<t1@nbkT0GVkOA0-klr#OS
z$9v<WetK<BJJ@FPhqvnAye|FR%~`6>Yh`n1-i@}tiv=PX$y`dgi+1M!ovzLBc<DU}
zzR+ElS=g-ks}5RRGEJ#EP~rMD&~(R@*bUaqZc>j|U9p%UeP)fF%o$z|MbFkXA2apm
zZl1#yr`=X~yXWDJ&&*DKoAX~hIV%vzUYPmetU-rj6SxsE`<sd5S^;M#mi=ntj7dk1
z#~rW~ivILMV6{y0H<u%ab7o|1c#`~+XUCi!)4LVRk{^9Iz_oEl%Yw|!iJTGlw6$G6
z`7-}G`SRh%(s^uejGlJzSI_(Rw)jlDZ_<km_g7BtR{UtvT{`QiaRY;r#gCj9g7t@c
zuil;4c<l7-7@m#CMQ8Jbb+|k(xR+q&^Q8J>%0`zp-&5q0OQVl&_<cs~)x9Ge*KDLO
zb+12u>FT0yfx7I6JukQ|-WNZAc9C4tPRF|f&OPahezj}|T~|(-o-LWk&wJgSSJh+v
zg2~+rl}|m-UjByn=|-LhRXZh)IV~=$U7j@Kj-<%8Qy-6RYcY^knj$Gy5$39U^v;t{
zY!25mZp2F7+VynL<ZcG-h)B^RLH63d0eq|XEnJgzH0fafvTFw~WVWp>y}I|^5trtq
z_6M<SiEFo}H``oza{c7&#6z==M_fvqVW3t1N$o&)uUBBu!Bny2;7>U(PPDSWoWt|-
zX>fgMW$2W3$~<k09o{O6m51znKD8_2`O^!pjXB=UUQnMqeIob4Q^_-Toqn-lv*Oh&
zfz=1j2FP(I=4R~5D-smY{%q>;V}^2`$B7QDeHvao54NQltVusn_)P0Xo2iA8optNY
z32j<$Y_88|{4FP|<SsK=@#_RB^}N=O=*HfcPm(&g<rkm#KHM;OU0sd8snQ}>mtU!Y
z8+q526bT-%KjwHu^SBK2w{u@CFSTe`mKDBv-!|DHclvLM?*ZxZAxf>`=h~A$x)*IX
z_`W}$=}n=>EZ10tt2#1HSF^=TzDtQV*Q{L>^<!7ks)!3K>iryIj}+V7m-!^~I{Aib
z!LyYa1+ml0kGrgYV|MnH^6u8``5WF`IXds(k*1)zzoIw1(%NuCW|9cEOyxPxjS6Bh
z`l2&*Pi*d*#cF1?s_DU^-l#CelpLV|osRw$O&OEtg&tv85h-B0)k4ZDa)N&)i+OZJ
zOqqxXx6H(K4}H|RS-eYUwHCjVdpJ+G;Cpl6J%w)zrZ3pzxZ#Y+{?AfZwcCEqef~=B
zK5LGk@jH$X9icL&Ofk;D1{3b8hwr{U$xmNA|L}sx)0_{#Td?TE!>&pDIN#rG^{ik1
z?Doo^G8(c{SxdfDU7b3mR95S*pk#skzr%AEUb0<xcazy3>yTf*<vdgQ77A(o^?B#C
zG@eslCB#bTp0w89>$N;n|E;KSjkxtHX5poL);ld;?~h-y4Ey!vWAx=~`)bcur9akt
zd)a(>{Hsq-XJ3v#dg!T3Sn8$^ZOi@!sj=`oNjxt(l5jk^_os^d>wB9W=f~+hb1;6T
zJSqAvqtz?vABR%?mb1GpnP6$_%98eeam9Tr!|MfyR3^W@ax&WYYTfN?1qTF9?2ps?
z`KNA`c+B@JE5jQqYK~mBsx@0~C$@p<*Ug*;OC^cr5p(W0iE<}ptW!DKRP%jzgYF8k
zwU>2jjy-ccs&t_I+PvlyiW4o*Dm{GBoFw>idzNF}q^r7*c7~a88oa1}%UJyP#hOT!
zn#18bCv^MTlNtkJvckkZE;KFJQo26+LGl7M1@ogKOT7fv{wz2(`SFvA0NoSUzwKgu
zCwP&iF|P6w%aNY*7ix7XtZ!F|PyYEzdPm6geDBL5JEARht~{(-{7LoQ+(Xx&?b<rC
z?eC{ltD*yzb~^XvvTNVmJ}kFw_pke5uX?A46&~n&sPJg>5rGNu&z;p1x|2St-aR9B
z^moYNCz~FmDz5lFy>J%m={FX|we<&<)g`ENoZB<8zyEaDio^9Y1%8=qyQCtsPJ2;}
ztQpIF{dEZ~Sx<jnZ)LD{et2Tu)6T6nn)9CSTpj%Un59FYeE$BcSFZmQ`N5L7Z}sJC
z+S}dUeq85waI(~n5BJnH+=Xj43jL|$64-kDS%Mn3kb=;f`37<<9k-uYAABA4Ws^XS
z&W^WdU+Eu^6a3zkdEtE10-Jjp54aZA#cZgtj1-uDfPI-{vhIPUHkMhUi#q<TNv(LD
zH#gyay$0)b#~=It@7XrTg=5vT)9y0nN3TCIZi!m_aBIyB9(~t3whp6Z&epxkI|>`M
z3{4v!Y&*bq$MI@+`u`c<-oKG3kZ4(GliQK^^x-ZK+24v5kE~yI{+(du8T9hX`I(F4
z`j?&3*!VO#=+Wn}jd5(P?=Sf3HGR%oWbr&ByQXOW8Nu*htk2V(`%j7}9u{jmIO|om
zPn*j+8K?ESyeB)~K2_>q&s%TvOh(!FzU8yjz9Rv$hqn5({p{$NzRk#Hz3JKFwTe19
z2j;DqsyNHxO!3;QcOBhhu1VQ7J)Ceo=Y_H1zs2rn6jQX@OjM)FdpaCVpQzS!1fTNT
z>dkuGS6r31R8putB+a>q-K(ejdpGmV(#=1A)H&a6^FMs`N1dX=p{U(2l-&2Fq@UV&
zv|p}BhINxj)$7%gQK^^1SNccI(GjV2TfXqnRaYg!JsTB%?lN7aI3d2m#ZYCjz~cG5
z8w2kicpWPd#F$@XsN&TkeQjDBWBXgHN@0P-t+N_#Wge=#$*HBprE#cSZ^0!0i*DA^
z%Od#hd@VPhGCi~4ak0Mm;W>f-HaN8$Z?rYMY@8sqOi{<jGU^lWWcK!$Cmq3_KMvVT
zK3c5dm$9B_@plPEw!;zqCtc>ahwvufUDxDY+n&C{y5Q_Xk;dl#Ya(|nj<a~Z%;>~Z
zqgcrklDtVbtj;D_a9z3gL|N~d`R$qf()(vyHP5bkvQvD|#sj;PocSG$Rrm`8&6^{_
zZLeGun9p7CzAS%6_Z8tei$HZN*8}#$au+WvA6X=kG>t1YSK`CP-R3EbQnQ0uIS*=?
zGJdnjPW4!4b}@{tYT6B3Q_JV~%0FE;&}_SV>~Tc8X!Ydo#A8Nf`8VuMr#%f`u<2ae
zm3;pGT(MW&t4@D&d0<^B{2(a6H^J*bsi(2XsXXt9sTVI<w3Jy&2gx2`{^GIvT*&&I
z1t(AQw?#}Uzp?2}sf*5m#lOF`DHYsESo35C)4iRSS8G4MGiSR+ua)Gr^S741cf9yP
z{gl>m^G!zIPTFm{KH;%S0DH@WkEti$vavjB+G~~k;09yfip-l6$|h}+oN!*~bc*|A
zeWlB?-p)DZTpwrfcHVf9w)NnJF2!>(yHnDgb4vI)j_-3=^PMx*T>6rXxATU0sUT_3
zrIWiCT=3{yeQmi+;q7VV&!#O-KNRAuGrgwd)8!9);v~e?Ub-IiY20w(9-r&V+kUp^
zEYDe5y|SFL<&5C-m)XT~ytdz#$#zFszUR@~8^dC;AT;y(4CRT(Bb)=X^S50oHdN^>
z?%N^uN$r8m=GEcC`lln->^^yP!uC{Mp6K&ZJnD_No+_=gThl)6*0wcz1!~4oYZ$Me
zcst#$Sz^xaBTK7wm1CYOEnU3w+OfEMES-1G#~rY2vYP!W?X~5uqB~ELUOePfKJn_1
z!Gp)i>f(nRqRTEQh_?xb^OP1Ds{B87?ZfA!j{N0k4IZ=Ps;_V3m|!PaR{bT&c2-wK
zL096rmtTaZEOPSeRlV(}*Y;umt4(Y2GWgf9logpRnK?Nv#$pe*bCvwE>D>!CO)q@A
zB(U6}dZ)xC7x77Fy`B4QLoCm?J=8eKx>q-B=l8EYf7a?cP2kb1(JJm+Iq&<m+euT?
zWmemzIZGKOcNRzgNm5+zeR9=8v8HWWkB&6Gm3k}CwC&ZE;;2~B{brw8&*`$ftxRY;
zR#|-d@%gug$IE-t-pn>Ucj|`C_QzG*r7b^XJ12SW*ppNf8X<T>?fly>F%dSqru$#H
z9Cv%8!usj1yY!ChhcRt@@Ugf>iuKolF4+?+<F74VmQ>j*Y{F(;YVCV$=}YT7m+WI-
zYE~_NAzj0u)y24@ykHh9Z`ry!hSY<%BbU58x$ctmtiOwQZ_CM$`t#(i^uB{;rczzu
zj(_ioy*h5BEHKF{Zc0LGl$+O=&EH?lJ$Qaw*8Y3jbxNvMUr1j$Z^<$Bu<KVcJNkD-
zr1Mp*UHSiF&9qly2N(W5vF87RU+<?|IXP6{p8DzQE%w0H8_#++Hn!?$yo;)ko4=N`
z;Ki#GrzgaPS{@6U?y8?EmY}ZhTe6HZZZ^mC$H}6-6YV!P$h2E6<w@Q8By)<?vnr7Z
z#+{8BRULi>wk=|pR%^LQ6@C1ep{FipRv=ZTrEa$(^naNS-&fP51A&4UxR3tb9c(!}
zA=po8f!IX0DMdorMx}-|I?E3;Bu{;0ac6r=zxiTT-ds7xb86iEwvI2a9orYtz3w3E
z5xMKGUz0tK9K65mlABQ&=Lf$26Q(BGE0~W}i%169>1<4r{~j0`ajZ6EtGM$0xWXRo
zeUiUTj<z4n{~7U_eQVU*KaRN>T*0>9caA^Rww>~l)BJ<v|93AtuRed-srr7-Je9>~
zzihcAy=?i^TNbvadzZiDJY867FsXgh54P$jNB@|-`v0(J+OPA%SFEpAPCBrB^RK|Z
z?wkGrrWui$p-1wW=6_ji@53BuS+U}FWaf{}wW{|mElM)lblhKcf7o<zXYmKCvP7j_
zPd`3aJG0}$PSK|J5EuKydoHjT87KGYcnU6g;~lPWQY(48!8Y9<u_M;a+FWi2kFuHh
zM>ZNhX8xQK_+5Y6BhhY`zqfwgJe1J?O>mib$9s7TudTI>9FHCpx_&s!?J{MuL~nT9
z1EKVqMlr>skM_#`+v)p?@w?pF(hOa`-8X)oeH2~P;kZ(;JM>-3^1Pdz0+mOTw=Mt3
zIOD5`i}uRH&pb+&cyFBl);8~uuJNkFt=AkYum8|!n%$$uz3S@|pE<fUOICgGdhMVS
zoAu)JWK%}_nagj+S8hs(<>gvs6UnjTPmt#F3mxC??ThHPTkCq6=csO)r<L6D#_t+_
zOPWQeFKHIN=Wb>8`DR?9itKDj-{2bYmlAT>&Q@(|23J4NDlu7BAiC(S)^_)@D^KLl
z2dKU=bGP{A_n+n9bWfR?&N8OwICgKp{L|3ls{Z61GHXt{KFF#NwtxOYAYan)k(lMB
zGak0jX7Da{6lpP$P%}JYelzYKPv)j>!?LN3(URQ~L75pQy_*x)ee`&{YQ+v&y{UfZ
z+AR74?OF7ByIm)2xVhop;uq7d=DyaI%Ul=Qt$*4*;@YaOH!3GTi`sf);j2HJ!V1++
zwEF2az2JWI|BU4%Z|}u(qQz8MWt_@3E55Ta<PcdVEp)Ts$0Qp`tC;Mz#m?R0cOEUg
z!*f|DVE2U1uVzQf%NKgjcPw~0Z{^~yl$1+_xzn5OD021Lra8Cw`LblEz9^JhJGomi
zbpQDZW^-rdwjIKsUp(=BkUdA=bwcvKNCT0N7ZL<)(*xZW&ARc(N?J`mn3r*@!5N7#
ztDO>QIRTD2Dt9MHbeZp+!z;L2%iU#Pv_ulWy`4oLe|}-r&F@U-E~=io-1GHL(HGY4
zr^Ra{=j`E>F#ReXl6>H6kzvm{ww%5w#Y@Uo0lQvG7JOhil77li{Z9Y9aLa9aMaE|~
zJG`~tVQ|KN{szUbO%)1rf6bhiePmL^;jYaOE~_3$ESWCCE#v4ptD*mfPvl3z*(VQO
zT|Bj`_3%28wL2^}<(fJk_$m|?#(4jKNcW^yCtsaZ654-emg}KxjxN@`N#7hdYOsCO
z7wK;Dw(L%uxROyz%q4$QXBVs9bgM0E3Zi$Pjtcwo;#!v24hg@l2P(_2F4|Xk_Rv*_
z-CeFr(w1&@nKQ>^sra6`zS~Qg^Ipk)^nLU7p;O?FD$hJ|wM0YVz}w4&TaQNtTl=oi
zxc2G!Vp(<2kl=Gp(2!t9X-9GJWL`VJsO1X+KJInwdE(hH*L?<C#D_AjsJ9;`KMX6#
z`qOt%jd$JtvfK?v9|%5v{B3TJ>}!rQw_nb0HTZhqUf{`zDIy#DKbss;V|i2z8gjpS
z#P@*ZHEAt@pC6_z7IcpJ(ONxS%~|T;>xXTjfd`Iysf#xrH{|neIC0QX*rg`<1#1kO
zO!?1x&EK13&IYNx{(i^R`=5Z~Q+-4JjZ=ec-M#iTPKw(5{eE8|<L(&`<)+>Zjr=Fe
zS0Kr|;o!o}dZii`7dUDdMPF}XN$U%k*j99Etz}e7eekRk?~=WDhb^7FAh`QokOrq{
zpK^w9=K6AFt;ZjEIrIbfaH`yx`eL8k3>BLd_w4wLc2EDowxA)O>FV;JuP+Yl>IiVT
zzJ5{Rok$<+Vx0g!u3hUr7p&;$sy-{&=pS`8mg}zljWzN6cWsuM_U_UJLA~AayGzc0
zZ(h-$T5w`%gPqCc9sklaUzi+O?O}I{W4~4Jayb{X4a>eh{&us$z3hWvtK8v|`3Lw}
zKg`_l_f_BAT`oJW=$=;%O#c7#!p+s%4~x&GYh2QC`0(Xxu3X(QGttDD!UcAA$DBF0
zDXG0`J(1{DP#550b?~6yW49g^#Vr|ABr>~|Pd@Z(N&YWVVx60?EjWGtl=Y`gRD4+V
z_-E%V?`Pe(bm2SMD5X!_Gp;U;H7jHZyLmS+TwKdH^g*-4%|GpbtKPitG1)WkCEK3s
z;`=%_tUbSok<Cz7Y3-WFZVy#1om4$OZM|w)#m+3Z(8LL|Zf{+cGx5Rfby}wS@A<=(
z-sX4q2dfL7`}{$xRQb^MNZ}t$Tz_P|6P|gr*WFO*kP&3l&rQ<aJFPfwQ};TNxC3W4
zK6<qy?l<Ek{@OY3+Aj#5`Md6~!|u?Uhut>{d!McUyCHmg^9qLQo7ojlE^VuE`myk*
zpz9^Y_=DBrZ@+~y6?-`97)eHW=em8ho82Q<wOyh_h%Zg@LWA+?1)|F~D_A$4|Jb-_
z?!0XZE1B1;^ylO(skpU~d*e<erHp;IA`gn}O`ZFvVDgnuAEvRry*V?D*>a2c2TMkY
z)n9iN_vXyn-LZw!>DG0Z6FMaub_gYY38=aldUD54;UiO%&k1&YyDr21Xb)G7p!cz>
z(Ka2qf(t*WeRN$D;$E?A=hPdS76I)UO1X)$(J$2w-7xl5x_7us|GD|2Ra+0opL#0&
z^Vp(E6=ikG4Se-sFTH#$t!Ef&B`I0Xao!c*vBfi0{R8U-_8*hZg*~>8V3GP#RxHkE
z7$<lySTM0ADl_K(s!M{^aSysVY!@_~xNc_X#J-oaM#ylsc02cef$L9fI@LE^v$xED
zm^GR0LU>Yq`|eLxe&78+Meb<-$)~eR?1LraEt{7%DqJTrt#)Mpv2pU=bilm9T7>&R
zcVJPVxah+JOqXtHb#2>w{LQ+JN5hW%sux)8C}MT@K=8u+%^f@5^xnu{+yB@*{)e0Y
zEDOKBzg}xBt2_0RjyCXo7m8kz8u>u_g~d6^(3d%Kh3mci_a09OX=ORhvUnM{pk0Hu
zYM{%S8pY>j0+*GRP0If8JmS&q1S`9?(-Dt8uo@KDy0gW<I#lser%+h%&)wF|N74kI
zp2(<iTkLyW;nElPH#xhH9BW(`-TnN9+X~-TeW1wt;oCPof5P^Y>K|FoyzFnCJnNmd
z{QepL3iS0Soj>&Q!<E&4{(k=<`|QeDX_gp{y^SXo8ka@5R<O)4*nG%0+q6-vDN=h<
z@ZOoBjhmUe8#Qdy79Y~^GfYTuN-sM5z@o8W`C`c(FH+aLb~)ZI))8YCteboE!3s6C
zfQ<WFH#PnKlV->@rMico=SSY%z{9osSBFVj+^AaJ)3xFK-GmD<tM_KRm9TcXGX0QY
zF5&-Xxgat4yT=AGyJbvkwX7GkJD+&{X8#2vlgYcY-6}ep8@t06Z7{wRC0Re^-P+U&
z-?9wJt`hO7JR;|=-w-rxP5;!A@ky{T`hn8R_vaqYwAWkt|8&kj<6!q6XL{VsxL5SL
zy#3PM_by`DQnoK19n&>i4p#`}EeK<YxX19Cfw!Y&PSXvk%~wvo{P5QMrhbCa17@wC
zt0Wks@;<QF7zylMeEE!##1@9aY7Mu=H-i_YRjlFv)A`;_=)h%<V`nART@t+R1axit
zVY%Drz(;@2MR(>Gvpwk3E@bGxI#aZ~AW{A1MZK^|F%RPM!-CWe+`i6No#X2Fbm7zh
z4d0ubd0xR~uTFpYWA|{O$=ACqTZQTjo!8G_YWC^koc>E!Ea!w+doNw-?Jkk6F>kfg
z|Hq~!YS*)0xcn>Njg_q3+;;DhZ1xM?n>*XymBg=IxJA@-hhXeU;j)D>Z%x1W{EbiB
zEVgUHM~_9DZ#uXdy#3OB-r;0~^Tr)tHwkqu-E^5#WTH;kv+R{i(iXlk+aMu&@#Wm4
z2V$n~M<i?{IOaZ45X)rSZRE|?d@VmCOQY@hy!hrUZbqBj#F%;gR}Bs<cblB6IL)hK
z+KELm$tz=O-5xLYT|Djko?D)J-cQAwzn>RcwX{fWkKR<{gY$K#-am8bz3@Emr{<q8
zc>Qqqe)=);zRuL+1wn6X;<dj2S~lHl$G^9(NBSD7t7jckJzU!trIlW^H^eVRck26|
zyp#K*wenx~E&Vj@O^jCguJzMSamXid+}mcSrFMkV>$rPu%%%U=CC|2Mo4Hu8v|h})
zBud(S+PniX7lnA{O}@<265q?QtitF;gY+crU7OSo%<7N$_h#Llm&|KeGHxb0%l@w@
zKe9nrSxtEPvG!7zg6bf9zhm(iv~C>yn0RV>Q+e1F!QQQN_bF)Y{o<XqY=8O`LCqEI
z%JW}xgsPg$EbOZhyl|(J>Au751IKxP6f)MS-cndO(OCA>LU)eCU4P=2{d+!b*8Vih
zzUL|ih6giK)HqqW%C|oX&$8OOTq-^5&IfgMv(h_$DlVNhLR~wzf9l}-rdvPZ_~Z%C
zKiIEg_?p?TdR-u`#;am#z}Y&cnz@HRUhzvdv93I_`RUB6sa*^wET*3ga&7Gp6MPvG
zn!#8Q{PytIGm(Y1y$<XA59xaRWa{nX?RdQP`HDOB5w%i*B~G=W@hMv!D!vqPES;6m
zwRRVOqMmfhO!bGaIebiWlZ@Ud8*t{^y{x>-y@k6wZ=3Le*^*l-_5QAyRDV;z<V)<7
z*Qd_w${u<iaQ$;6gTH;;lemie?ZuLdcY7TAQqcH0eQV3gsFhdW=`q&bjlD2WY2}lv
zvD{8iX5YBFXj$X^`;1@Ww{Vt3Uf2HenCXv~DJzd-v9Uu+h)~IzP08Q*qTl?K<N}4@
z!uUBAyZ=9KS<M$<G{IH(<oqMkl^RbjSlmz@>Zg;xA^LQrUpMQ4@&z+voflLrX3~75
zyC{RL$u2E@%0#Oz`<v4){4cx5dbS~!bDpsYv(#l*eU1;?t~SN&x6eE9KEJWcjPu$B
zV+B>mBQb(r+1*N~ly}VhH}9f|YtH;PT0gfhI-wKLsU#e*sAJV5Mu);ix4??XwSBfL
zChT~2_gvEYw;fB_;#;-83pZp)PcoeSPvPk;51Ayr&O_Hu$yzuqUGu=oBfCIu@%2rn
z+{=O<7JID^e6`zj$+Yz|U&ib^!?<Po`o;F&rHa2SXS=d$i{0|ajxSe#eLX8kH^IG|
zoyCUva8@C2-Mr1ErKW2{T#DDMTp4|*VOovGf#)YaPUF9BWTfx+EYdS&y<+Kyc{AhR
z2YoBNV)HVBQ@>nOu{XMD=7;}*-b>Z=gU^ZhH{H%XHS<r^>`$?WDrbL+-Bmh!k#Jq*
z?4sZ6^4A6TecqJy>UZg>eaw|v8^8WY;wy-Mkk5bf`ja-xj;RG#%yNq-u-dew@@;CE
z-`#wpNmo+FjHT2~^8*vx_g7tvYnKSjNm4Kqnfvk+n;rXx=={2(bm=t~n?pF$9(Q@m
zMXV7Mf4bFfUVF<Vfl1Xu{jq{C*(bQi<f}KHXKzq9mq>ai6t!MgS82~;tHykWb&pjH
zig{!<?(3Gxu9KNy%onSm|G~9KvP|`<m&+YB@oqJxX>rFGKf300b3AnxpQN_U<7~J2
ze(%nLwNF|1b$k(D-4fHeL$QCCyufLd_7%Sw^&8hsdQ);zu<D$CjbQV6mACEM6Qk5V
zb-q+N_U!oHTNktB#cQ6<@Mv0k`7&Fb27^}Ex*O_RDm|@yUs6@)7>f$X7XO^-l)8_>
zX6Kc(R>y}eUwHXeB^ob0VWV7-COotLPQ%d!j{lg_ULSnUc4txSGv1^r&tuLRvU`6#
zzIfHm_%-)t2=KmN!F5Y$UEOa>2}Ti?le>A`7PeLhiEfx)y75y8OMQRjTAN23SO05z
z+Q(nJRBorp$7+{`p0xfBrmxFd99)g>zA<(ZIKJ3??&n{3Rd>j4Z)d)uuu<VsWQE$D
z$m;2WCgD&17BY)5pBESUA#;EK>>|_Y+E=<C-aOYMvU%n0yjOf*zv#%sJvpM)+97}8
zj;&>lWk9x*)iSf1t}C3!!#AAI=Uca{uKrT;caMU<8ye<Me#9x!CFUN-(H_CH>=UQU
zj-W%%PdHPeijvEBRh(Krv!^R}ue3uyhxH^L25YAa^Ev#zF35-R=uBRkG;_{@=L}{0
z&pun1b15Wkn%2R~8|%6aOlCaT`9s^B$HT9)Sm31l-3R(oZij?^)G)Z*aQLt(mZ4}x
zx5O-W3ohRyzjgCw-9NIaV}sW8A4+O}LT_z7;`3U`TF<(3C+~Ik*&N?5)CqDc{o|@(
zZjJI}GCqE3!Jp!~KmXd?E;;EPJHFlR_#&}&_YeI0&$_R}py{E+;psw#e^u-lCH{O#
z`=T?|>(Snen{z56-`PsvXbb%Ih9#(_B8Ra<IkSg#R*9;T*^RX;q^x((4>{8HtUO8J
zVpwEQ{E@yFeh(#F<odc29c11*K51R`z%%5)tqo67oWHD#+V|=9fyr+JSIj+`{xEo9
z+24Ot&Ke$0__ys-`|ouRwPzN#Y@G5#X;ZJaX1LPH$gMjTbzYgH!o5R#<Aq7Awv#>!
z*DTdPE<5Fvpt$%I=S96TI)dUGFRE#NbbaFBWhxtba&pHB@r}QhbbQFTWU02}FK>a)
zg@?Bu`O36=+-lK3d-mCp9l4yxk3Y8Xd_MEpxjKdk3yf-BvWLAoCi>wff6h!E+r!@W
z8`d(5{o5>`kbdSO_qjTThSx{x%$}bUT*q9<yS&51BJ%Kew<QauE${sZ6t&nTC3wm|
z!FT0i4b~gQym?Qne>+vyo-vJbarqR<c6G1iJV|3|mWR2U^Gc@pO6t$-HfOwbqlxo?
z#V1x9)yjxBCRg%BTRluxKYTFZf2+RI-v*6M*R2lCQ?dA)8?o1T59_^-sb(|poL}`x
zR)1@?mziO~9OhU3OFGvc?@PFrpEUPK1H)FK`7SelPr7qGU$y9oy7~uJ1qb0?*15`a
z-#>_bG%Gocb<?WOnaxk0Xixn1R)lq5$A``bl|Q%I?|Zz{<3ab0!sdH-*SgHI6jf{$
zF|?{M>YYCE;Pu>do;A$bX|k5{8Z4haC~AoMK3kK0KBsNh7oBxUQ!I9Dn07!WT<-M#
zqaSum-X!rR<wVkg`pri>-W)r{U^K@!GBWiDgRx}p3XXk}1_|Fwjs);XY&iVx08^AV
z-!@6D)qI~nuaPY1n)hI?JLA0OOI#0%zZ`#e`)0k|tQUs1t&*Da_K9o7a4y=e9p2xu
z<KcI=Pun~7Cmq=7+>-a)XEWoE>PZKlvpnbuV0ba>O<7;T^EYc`nxDV;X65c;_x9_&
z<W(g<zOqeBd-LKU_e8$dWR>|YR&zJh-tLXqRR6F$!mIQvchcf_6``e!A8uzqz44&o
zYq!iz?lo8W4W#_O*EK}{yVO(1kz<_sgk$+H+q#L$SF#_b`3gF_+}Wewq2n9nV&(Q#
zzr*54MYqRu-WjaiNe8=+D=j)%(wWot=I>UQ2PI4oPcHAc@$=DKkIO64x;dPKzO!!J
z`9<#|<BJ1v&6^vxI>@+cKA66>Or_=1%lLba0Yxoe-YNamS#18zdfR44mzPu0?poa1
zD*l6MMQZd`293}?67z*ME}Yl6zQ`#0qKNO2;H+aCpS!&|TG^<dbntDMUwBe$vO%N1
zlJCWHL0?;MWJDZY7cCqvpmO3zv&8iWA3FbK#tA;$u;JK*eAQ2HQ^bELgw3{aSH9!O
zc0*s<CdMkb{|4(JBa3U|`#MVYybEaCD`>3Z-l(7SQS|zn{6~v_9I`lTE`P3(d4cnS
zeLONZl*&6^JwMPWX!J$vQ|f~a%%?<D_A#(%Wvg8<x~3H>vgp{a>m8f{Q8|-$EdS(b
z!#MBp|FF$6QWiT;MfPbN3SRi|d{ABAlmZ=lvD-66#J+wAvJ~%rAn-M2$&4$p(XM|_
zUj6qy{=abI-Cx)LFWvv|`0oAxrvJUL`7NvGRYvt4q4u|`mG5M$+&U06W8I7R%;Wp(
zcP`z3x{c%g{Q5KV?|we~{_Ek-YyJuB&rqDM#GYK9eyeHz(?`E-Zm&;T&l&i~zJ3B*
zsEziDX(dtTg|!)0yvy4nvh&Z~SNx3Y9@IVbv~!<dzV&**>vL>Hk7iBUvvnD-zSQrf
zOO4;Pwt1|rJlyTZ%zRHXZ%d15>EUiSp~=mPm%E>d>mF`&yRh_W-}2?znJS&(jPLJn
z^iz%HKEq-2=jP3aYt@t`jyoRamC`C&dQfQ1QFC57cfq7<tdp-rJWH;1c5VLu=Rv+n
z)W;vszI{E*d&+A^#aAus9g7ceUs1JQq41PfU+U50M{y6Gw3nJQuD>sRoYl1M_{_*Z
zcHJ}cn%*W|iz>Zv?!NBARfm0Ret%juGj-Lewm<%_A`P6*ns)s7{C#<X$0}ZaY3uS?
zaiteMiX1kte3P-CGx2g**%qFnJ7>bnaxV(#?#`{a@L|uPWvq@Dv`SAbU_92Carkw)
zRo1qwzw<Jui|#+4B$fM?W0PX{%DhVt0=FNUdDC(6EaiY=^V=NfmERm$sx9@ETV~x|
zFXt_M+aG?lX4=`dX!B`4z4z;H9$cKdW)|D^6urBd8{YWL3cI=V_|!IyU3ask?p-e4
zeJMk;HSfJ=^rTZuT(?=y-C}C3qHFPWw`sOO_B@yU`uV+vxlCJ%%RWW2+*@e*>eZQJ
z*QGwa_<evaWUk+?$d3iRy$Y=C8+DZ4RjKal_>&TQYpctxum@II!s-s}n`Y=X@IA^u
zrnAc82Y1h+6>P`9bw_9yW?yl6<#cV!j@lS!jqFDKhL$}%`=@KU@6jo!u=%|@@lE&T
z9ZE@+OXu-!U&V6geuCzOBZoddTc_&uZ;|7|&Vrm7zbsYCIxE}?{>li=Q}(#9^3R%A
z!AkajkBIMMoMmP=|Gq)ezU@!WZ446IsG<=%*STr#B`4)CGD3eMTD+H>u1K#<k$Qjj
zhsB!JCd=|e8xJdMlxir2u-!QOcIgq>y-!u<HCX;$sNlg`WB&W$E#>!5HuKynelWqZ
zqlQc8So%{N_e!B3YL__0)x7hQ;#`g_T*(ygGV6}yJ*RxtM~X3zxEmJVOJUscBSUD0
ztE$ukR_3okB454BnBrYB`pRx)<+)5susy!eYPHkan8hq<eWLHqC3Mzj>fM^Q_=x$&
zttYZ?FV!-5H{plUB#%>F9Og=Q=7~10mwfOzpz(@BV>6qr7!!L`@AZug>>Ibtd$my@
zXf@~Tmr6=vw-&n{nLM?w?dFHs9qrmyD-PZ`t0Q<mV4k1p#~i=9`ANP$yF-sGzUUd!
zU@7_1=26yftz(z6wd*FGH`;KqE!?d0iHiB_XUAW!d{!Ct^5&<<zF)dIE@yY@D>yw@
zkzx?}wudDx@WZ0h%zuL1t!8XV5nLIs%x<y!%Ekk)=N>ShaPyciGw<(C&Jq^c@?Cr~
zS^}HSt#UqQ60x{#{#RDJj*AL;-zyIYE|km9>*9F2HYj`JeyLy2cZ7a)6@J*WR`ZeG
z#Ilw!-6So>e}~trrdh4=su8q|@U!XMeT1u>SxoSm+6ILkQ#q<dZ0|hexViIph4{Zd
z|3yr1c6NA+{eR2*SGXWeZGNlp;<Cr(HupD~-)B8z$Q1sdBKtn8@}{6zmlt!&8}*YM
zz6c+AwOiohI`xmPN0>bvU!35ccr1*YDgH<cgW%yi2UVuAY;IcAxx@K^ZL(ly+>%Wl
z0WOn&D172A@LU<YYL<f8;kDl*uO2bn#+`TR{t=_j9YHk@Crb$YQJ?0$`q8zfC5s=F
zgl4W?;wZX4wDp(Uv>!|Y6IRY-*wVk~-wuZO?+fF8DIR1}SY~*VKdH+weNMKX%cS@h
z2Lw$gs(f#lP#vChc)PXlk!b%0i*m(7&hA1#m{vJ+L~wW5?v>cAvFD1?se@}Zc4(I|
z#UHs===xy&k$Eo-v_H7EZ1m`T>n8HLS0#=2Pf@(%d8yEEQmyO}uM$PyrMJs$n;h*H
z=XU5LW2$te?gK>~<@Kz8Vq_|2<y}3|^XgO~i-^F+DXz>O9icOH6&!O<Gi1y$J97O3
z1Lvu8((z8rBER;}3gj+14(<z8XP9Z{#R`7Od$uy@jNF~Xvn%Xmn0}Q0v5HX-D4LO3
zF|p>#!hegd_Es5n<`|rxceR)I0@F!;&yNdSZWNsTqV~*{=flj$yVN!*7p$2+T`2iL
z*JRU)X3|y%epqk3C?WhqX%X+otish<ZPMJ0`bx6$8(+kDFPR*>mMPxh^Nx)?R_->!
zhp(R0b&qnmQM*a0EM>;JzaklDTcY|_c^wc<(%Z${{Jr)_Zk%P<^!e^V#}qGd*D%Z8
zYS`6h5G7T3Qol5X*J`!a#3w}(sdqa{DykoL&sY$2=ln*KH+4ESPdgM$^|&8AW;?Tp
zORxQP>6eEAO~sqklwL*qfAv!F?C3lHRpHR4u5;Q8=PrIPxve1CH>r&0xkB>)YqdI3
zVV#c@T?G9T-b*Cy)$FX=Su1*#<K*7v=N)@4=Q9W;+BXX7O{^8yZdm-*^TBtP4F8W}
z&2{B>lTz4EUQSTh(-Fz`=*O(o1L?~n*?g7rrv(anpJS4GTXOSMmrFz5Hqo~}cXj5d
z^rTHaSXZ=mjY3=1>YJWCYfr8c<qWo+5&1Cb^VN>|i_d>QFspg_ftnW=r*09ld8~KL
z_T7UUE0+~a4haY;vHB@7am{?r|J+Qs7;?22y6`?oy<~c@g6pHnu8b$Hfh%7fO13*_
zac;-G6BC!Yv@Wlos=Op=p6hy<(@J7Y2{+etnDBg*+1Yuarug@2?YWm1yRO;7tsHV#
zZ=xUPR^6o2Z(H@1-fnzz>6P!B$sOKSH(a!m9Hxo3TkUo^F@?iyd1s-^<o(kmGJD@L
z#k)jwmQP>jBGaw1uj9r3wyocTt{w_2b`%y|D6{Wsp6WEY#Ye<16tstx*gN)jEBoGG
z<@Eci#TQx2N4<A;uCNxE_2=f#Z1#62D}?+L-tw=n^kOg3-<tDcMn^`G+{7L87-j1f
zCFc0pomODGeei9Lz}B_v0y|?Dan>+%p5kE>Sa@;TX04Nt=QTW?5gVe_-@{-N?0&T*
zOtAd(PD>U6)7K{g^@1n;V7lOccW&sz-IZEA(LYt)_vPpvRCsi!BfW`xqOJt1UFQ{1
zQN?+AM;K%!rB<?Sbl$F~_2@Wjyrt5#rQD0O{#!NrtyXa2p1{Ky>-A>ZPWx5<a|B|0
zcF%RY>*OppS?ys^<S(&jEd{-A9(h@~zZ7qktW;?i;5Js&&Z*TA*vB|GPgcY4YuNg;
zUX$cXu9d!4c_HhS@T^03M(#0v%Vlymw$D>4O8EMOFDcSx(!*fyW9AAO9CH%xd*y6>
zHsk!NLn-b1?q2l{{rG9(%HF?`p$s49pQxT<xQwUfnT6Ay6JfuvbDqg-6J+VEs1Ki%
zTRo?_tM=W6N}XM{D>9C4NH@^nY}qgE$&)v={etFFE7J{Ygw8e|)tkKe^^C}@goO+l
zTaGN-U!uQv)7wRC^SBpqf4MT9S!?53wL1z5FR~t{u1(4c`QhAJaW!k*_b<ASCvB5G
z`G2SC{byPe7n>dYSrzv|D~(ySiha6eU(1dU%85y8HSc;E6yNasZl3$|J*UgPdFC4=
zLcY7aUY}&5(KBtq>q@5m78^u8SvFh#P_aC=*rRX7)4Ptp+m_t#GyC{u@6(Sle@eaV
z-o9na=&+ty?sRec?jn;Ni+|ho&%AJ^+3dW`Kb8K81uG5Z9~ft4B)62No?A1s`J$cP
zDJ799&Tc<u-MuxRf5E0oww<9)-}83)G2c@@u71(Bf@#Bp4#U2W{H#ANHm4W8`1JIJ
zhm;bdd~#+*hgzoMQriUrOj{ltd*rDrRpwOv$n^%F`{CZzGiA(QJoWiIg}Yqh1OJx&
z-=4P#xZmzR_IEmy)|9%#F*~_LdS2aMtyM8+jf}yxHmjbVykcSY<4(NWgx;;+FP8SC
zk#*VHmZAt&Ax7DDo<ED-J{lNsu6MgBdMjZ;;oQsmJEYu?9C>(A?eg>`bA?SBD;xTb
z7|B~Tf6zWWzo)+;*xXC>aWZeDRlNC%_|>Ugi3;u~-freL|FGrNt#>bUV*k8xHhZX*
zBeMV3hh2A5>ts)v{902NqI&O_VB6xk&zHYA9+^K!IN0yLes}zm8h!U0B@0~hb-K0t
z-%mR_wLMPERW4q?TZw<8&bt~h9(7yEY0KJ_RsA^pc~lObZz=kq*WOsIYbeY1Z~Dpk
zi>B8fES7n9A->3|H%e8IlRvF(>kY=7`Jwh3@8-PNaANk$<Cpkqvs}{Kc?^xa<btlP
zV0#_?cw)t4?uO>M;s(WEYIZ+aXL)F8slX4VLzbLZ|9ScJYwlB0o3lv3<+szBiC1@;
z8j9bl-`Ez{(J}KD%f1ekzXyCid*xh__I)6|;Hj-=!ZQy4(hsr4rv+E}c|H*4c=K^_
z+Eity0?QxW*2RBzJkWN3b+9A(5|f=+LwHrXfl|q=lIe%eu7AE`(rP|IDfjM<;>PY>
zje?RZ4*vYJ)bc^elUDsCrIi-fvaJtYlr7zLF=nROq%4!`Dq<E)S+2r@Oub7!Wn0hx
zaY``j>y8H@Z`U*&ZSZR{pS8NoO0%_UOL5c@HhVoL`6GD(+m8jO)Rx^U=zg~LIsfLZ
zM`AZC%{ySFf6|qA+V_JuFV;R?^y~$T_N9D=X*0zH9=ufLdhmUPSeTgj<AVtclmyl@
z2Gmxqbqg~oNR(bF`5`c1&q0rs4|DyDjl?9oCsuo$O>$UzIb}-7+>;p}A~FpV+7hpE
z?M^qAG;wWWvCBI!S+xD)qu%cc0u1fd2NMDw?`t@JacgzL*@KTCemrJx_k4{=@dH-F
z4+2}1kKNua&3EtQ>nH8&Im%x11>f6qIcLEaLB9&7{pt?wT9X-lk7pS^m~$+;=Y{tE
zK25gXlx=&%dRRpFW*9tBF?4BmJiOAfJJ6D8@ll6AeBBp6Sfv<7`JQC4+T$JRd+DLl
zp$s9PKLRQrEO*8AbS*c2*v)d?N7-NbsEqmT`|2?pAI7~~UA}or$*1%kOaA7WE#$R%
zpT;%geHwQKSEKS@j>89IHLU{dZe8mMzPjgt_=Ezt#mzmZ3@`TGs@e0*!`)JT%_@a;
zv40n7P5m`Jh08aGFZRy5BW(8X-HKU{Y%8*`lCflqGAR;hs5z7@6V@sw*!78H@vhZE
z4|^*FJ+0b|t$dHjGA32-?aUN>_(Pw&hPlL~meKe)%X}}@*ws#d-B<7V$g8q_iNLL`
zS|%$zZ471!*R7e&+43dr%%T?tKJ2$XuP&E;>2WXF%#P1&0>|sB)yh6w7tE;*Yvqgi
z&^SM|FWPP6>P^qTdfGJVF7D9m-za-{x*Nk3nLNYPPo_<_?(0Pl$o!hIUsEj5p=J9=
z-<GP$2gD~T7bQ>I*HNl3VZbByBhG+ni}>HIE>`monJ!YBbmLJZ%dI0eciS0{m-?)K
zZl2bxA@Wvux6G%jDo%kaPrM)ZoIYEqT`QDW!stDbdt#qZ$u;30DvJUOEA|Q5E}L^e
zd}5iO#)KPp57sr@;*NKTNlQI(XS&eOZ7LzYIxAWB)ZFXn$YK=EbX~)%X7T*QO_v?=
z&Re)$a}1ac?tK5L_roXUkFIYjbY8v<do-_+J&^I)m6qPpzqj(4m#N9T>wJ>DUw{9K
z&Y-FL|3ClvccZ99eY@DS*KTg7=gvv;kuT^ntUaK~c6N!mfuzZu*^$~px0`q`tiNz9
zG;-m@EHjA@$+LXjlvf^2I-p&$UBV>1W{bpz^X*Dgl1ygB?~U&1>*ivt>8rb&oYKcU
zYw?zEJKYx<2iYWRY*zNnm~$~=dFgz<V>$JK-c8*NJkuFEgxsWm+uGWMI>i2-`)7Xi
zr`oI&Id53ny=xEFbpB@YV9;new>rV*+qO@4Y>S<uWCS87sOjn*jp${&eN;OxMsDLX
zOO^9J8n+&V-FSVk@=4<Y(OlIhzpvjH&XGx~s6U;em{j9#aDvmv?RfDn@dN$b2fT&8
z*uJ%kJo$3P;~V`pBKxizH*%PqTKO=XH*n>=E9aFRlU(gx<ayo8D|ip=cRP1cN@eBg
zCz8MF5>?%|Fn{kln5w$}`Qw%T&E@WP9X*%#PQ1hQ>*&vOYBN~>DGHc>C}jR;%wUrr
zvTyI)1N%h+yq4!y@aE3?RcECq#mVjDtxyy3vh{20*9*^Dz7*=UPA$k2j2HPPb!*NB
zHx2)FE#A!u4Jseg@9LB@<f-j=sQ%$I-`^b!&f?}VZoG4Dg=<`Ty=gyNiF#JTHm)-|
zQJ>sm#RC#7rmwGMUTRinRv~0}aI?_v{Nr1TuYTRbd}Vgc)>YA08|vmv7EiqG(IU9{
zW6y$VbN%c-88R43pSK9Tt95Nw@0|B@N;V%j&&c9#U3lDTo0gxnulM914@!mY^A6Oj
zO_0)UJDV`)z^cPC52stLakTEVe}Cb!B9{R3-4_#V=bhj6P+R-l2krSDP8$`B=Jl`t
z%JyMC=a#si2FoPWKm26KUbF9&!8;Gh`Hw$k$V>nF&URg<;(f35kI85G?zv}X_ZMyc
zy|et^--?|}=D&`9UO(}VX3hRmIiZ8oj;kqTsW#2J7|AosBmU&q3Ex&&F7mOzB_Lj1
z@LRF*zYT*<&+eliG<#;4sVh5ME|lu&nc;mkVM>JMoYo`}q3Y&Px6+LdCj}cm2tShA
zeDQ_%Bu<B&S5I**oILwz!-O>Eko)0b^B3PN_n3auS59l|-<=*?gU;w3+o^ELt|!29
z#@#JikN#XL2;6zaH$wWuym{YTDlS+~`d{p=cO<XOldI80uR?q?!-sC&qJl$S%1n;u
z=e6|v1*Fw4YxR8<_H4iU1pyC#hRKZ6=jer=J+O5_cIfrbEOkd`+;F*_XFK<gn82)H
z^E&qXOV{Ne-m<V?!@YGA%e=PTD-S3b-brxgk21OU`RJCGK-=WNT#<zHvn--M?C!l`
z*T<YPzvtsJnUKev4_^E6RYW(3R|lS->Rz|($^0!D2ab9^t+=+@wf^0ivW`=xlJ8c3
zn6F;Xbze}opY7J=;Ond29FL6n^lZ}pFZaV+j-B+ezs4D{+f8SCX?n}<{l|@(K5}ti
z&Jyrkl`j!2uH<uX;g{7N9e18ud|Bn&lOw(JBkzR;zCtrBAN87lEjcUrka_L_aYOMN
z`p2~=9^(mB%Tk(Cvs7lC%dc<Z`#N~_j&CrMJ<`v;uPA5Z<7I`+-4j22xY4_)tNY;A
zY+3812Cf<=#&2pHPS_Un{Lp!SPA|V(V!^LzCDSjneBGe7H<VTCfq|NFhiqkBwV6xV
z$0gNfE_?EJWuL#)HL>{!`^MOg^ChX@7jBqjP+|FP-mO#@lWn#Y54$5aXo%V>scpQJ
zANZg<LV9h|$=J@01CLqub=<xBsCK{5PpcdAmAS&U%@Fu&v?xVl=i~~e*YhIQrEvN^
zj{cpdI@{mE_@~aCBPWmWf8+jP%V_oTXO2OQri}WdvkwwVx0W7#A@lv}#yOQtoy<Z~
zk*PV$#gxNmtdHio(G$VL(tTQtxzK9&(T4t;4|v@cA6>b^O-4#VQ<5j+e_NW-1LtEb
zzdC*_-}Fg9RL8AFCZCZrZtvPPK?jnzA8gQ*ogyuwyxAntaMtUCNg~I&j?4<Is$rfS
zD7fTs(gcRf%@>;+pE>Bd@hfSCAD{Y;$?mw$4dbk{Qc+vvUMF$S|D2nB{esS^0O3Dg
zyO&kW{c~ZR=9}{do2!@2Ok<YpTfy?7nu$X`%`m|z(`W<ZES?=pKZ_|}NYsk%33+iP
z#ZX~kX*XlFrcJwsTjSE2?Gif<ZfW2OHPl``%j={Vb7N|y&itNv^EcKQ6hyzOw2<YQ
zHF?7hV+k3xn@K#fWzB*fKHO>n(Z-Co7*<DWTiq7h99F<`U&rmx;;y3_CO_j2KQHE~
z5}f}>@|elB>`K4GVNI5a3(TGWU(oqseW{MIaOTwwOgvM*R-W^TSGcTb)oaB&`{dCl
zUVGlOp9tK{ZqwDN&mdivHh+$$OYJJ>S8Xq5%5YULsq5=i?MqnL!MoAx$6t|NhRGMc
z#2;7_-0mLFSNtzcK`eQpY@A`n{|*CR`+bjid)9Bz$+1wJ%AtMxGxLp-O@~{jt>aVq
zFSU7{UqQjbXQs^Nk4kb3B{r&;?EJ;RXd|C6C)`re^T3u5k@5l$SJ_>k`%|jsx5ZAj
z`(MBOj901Wy0`rN<6_sCx1ozmf8DWLuf&w`eEZ(RFTGFu<o&#4B-HncBR-0|g5&h`
zYfN=|=e{gmYSio;Dltz(p>Tpb^8!)EW#4xFXo@H~n(*M2#I7>#A2J8>Zrl{RAldM`
zb>?!fk0#Z3^TY&|C#vmSJMr%qJ=NvPTI@$>ophIdwLUI#rBjOYmv2{O*-N7CEJ&;S
z^nxe+VZsmJnv(rozc((5)sa3j!{XkTtw%iAPb+-bXeQMVBdvYBf=~aRj={qdl8ZGA
z4sU&~bZNbQjiB*V3Fkd^N?*%9FvT-;_IJKlJ1>)YM=9g{*V~yLyKXeAm34&fSh=Nh
zOVOc|^TR_Mldt?^nkU07SN7n{&rgLPHr-I!*Rf^$r4L2dS6v9`^?Sg5Vn&P549m15
zPhY-^619?Bdc$9d{m}{z=In6R<w-j@g?=a{aWAV(o8A$u@2eNp*O#AgKS;E_WNLDW
zD3{9Hu&ErMO*``wTBGfYY#K}b#3swX+w0-6H|yy6ll;+~6KkejR6bcO(_NFs{Jw5=
zUO>nBxCfKjb1SqC$RF9z@nMPY-nE?@50nSpJL2+uqIzC#;`vYms}t;k>WOdswj|C{
zE!%c4-}QlXMu34)gOHP%<cEp>lg?OOki6E*@L)4vtCXUylIIo<@%5dearsFbZtvXO
zmCR?Up%j<I)N@rYo_FyT@qHa~=SxlFy?Hk56ZyfEp%8vVE6DQDV&gj}@2_%N#KO15
z%00>@%Y^aQ@w6vWaXpdjx4!?bzOmPeL2<pM(}C`Yhvzx+9&WzNI8}6`)|B_A6HAxt
z$ui98<IQ=qtm8)5?CsVJ7H9k4{kh1<V0BOV9A5&%y-<DG0NLtK1@ChF*o>-ohFZG0
zryKX3$+#ZavfREyJwea+!=AT$N~SEAi^-CUoB7k`%aZx64xe6>n2AfO%J8PY{b2Ip
zkhtNZhuJ%Xgk{@y9T1;5?c5B@Kbw7ZIL!iMg}LA5TKar%J<)!5QRj|{-6e;12sA5S
zWO19JKJm%<SwAoQRO)MI;J$Au)-wCjeF1^n>f%3nBWlY+1B9(!WhvRuv8Y#llzT2K
z&qJa@=#I;+utUjV2P#%qOuuoYU)n&@<jQ028LqA^|2zH6#NYPk3JP9Z#$6*I|J_-I
z?UpQy=ca8wpZ2O<3R$Y>AFd?&{gC*?rycLsyI6RCVTxy1%P$z$bWY~u%gUCAX2l|j
zyHpJ`4$OO2aDK`wbD@rQ=?1+^=bdhJs6O3c{7L3;nt<gqCibltUCw)N7I$%ZlGW{z
z-uQ@hUq^`HovzMR;j5w|jx=4Lk})Mh$Y;vyz^hw2r&fhLnC;=~n*I5!wC5AWipSgv
zmLeP9l=f};r1<WquKS%M*W*e<Z<KPxe7@Il<qpT5C7mAbn?GO6V!U^K_5pE0se1(}
zW!i?1_U$P5?WvIJd+FtJ<Wo$qkTK`ug16N#mkYi*@p5BFg1g`~k?lg-CaNs^7_3?k
zG<-T?xM^mq|Gzb-CMQn`e&ZX`VEJ93XU4w?#rZ!)g)Z6OPkHmCW~W2ygR8qv-JkEZ
zu`$P#!=%&m&L)Wf&68rv4>o!*$(tvni55KWve?yC$h4Zr%2=H9%o>lRw?~r{I%aN`
zxN;#s!RUj}1Rb|l&8bIMaNJzCPg(Lny;{JF4RL=bhDx1gHd!p%{LJW(d!}1*_?A%P
zUG0_O7q$i+IJ4^V$=luusjRPAm>ZT)OGstyRm@LijlX@9&FbBRo;4hjPDf8Zh?u0d
z_|Sn{2}}ASzOyl(|9w`v=S=?xHiq|K6{R8{rbH|{*r4dPQ9@Vsht~z385vgH7ZsmL
z^OUi^)jd$H5zhUfSVyAzV<b0Er%K+8*U>*Vo1Bc;_d(p5wdU)Bh;F|+8;!7-??q3}
z%}ryJkvhwA>hqBzrV<a`3Yqu=&skphTw1)QOzmXJbw=N(izg~41@3E@sa$j9c$jOS
z=H-CsBWLU~R;xX8d0ljdePgcDA05sbLGGMw8`)z!3iAD*XZ_`!5cR;s_vsB8y+eOY
zkF)h^Hs&jROMP|h_VMpr-cid}F=g+~VdhL+%X8pzm#oSMOU7T<uH0JtsbZ$a!k2oj
z+LxTtUFIfhO^ls&x9CW5q4*D_v>557o4vz}Sz7jJslHz2aDzkbf|o(#vj;v$m~6g!
zTt3_;HtT>{$@GQt58}6~G~X!nzvilbI6d>!>>J#F-M{;ksI;_Iyp^nw{CaLiPW8=+
zmSyW3Rdx0*?sl(W{{L!$)5-LL$1`iL?Q%XWnEmgRT6k3ccP&?D6V4juH--u;cmxG)
zoEqOvQ_g*~lB-7G<EKNfe9x&pQatigd|!tO`=(cqduL>EdOql$q4>;U&J33yHM7lq
zDmV_h&Rah#;svvn%5?8eQN>N0uDiUN)RXZfT<NdsM^=*;8W9YhO?-*2p@A0`K8u#!
ztsznPK+!|c^PGdu*9z4`oI-1UiB8-my@O?k@XL~SEc+N-Bp%G(W9-h8D1YwaO!0}+
z)_OdT@^x7fx#!~jRg*ln@kR1G-P$X#?vWKo<;zt}@eH1A9~{>fxA3xEvCg+V#O+#M
zRnj)CebbrV8?r6GmaT3IICzvniK&0~fvAi=D~$)!qxr0#N`)-QQJ8yJJ%{(*#wC9?
zPdUHnxpmE=@QGKH?Uw3iYc~IOyS8tp=9j9KE9`gP`v32BeZlSc|G)PCx&FW6`}O~u
zR{P%at5=LlI^g?kRs6xG&eg@YjD^iY{!I(N_3{1lo!?HLkhT9m!+!Vk_WQ5fkC#4i
z{<Ekx<3#Ea<s#55_->D15#QIsX2G9*eD!lx!XfEyACBXz*3>WDwR`KNyVvssH<%wR
z{^n;}zpV7w=EaO(t#u@O?h9V=o3bm+$wTqR<FMR<6SuPU-u?RA_Py@$!*dEN-ehnr
z?7nyNEvsalBdbk@@8y5-ZJRDF;5|O!iqWh#gGUieu9-gz_wh++UAJX%)t;#$6MrV3
z?ao5^2oc_cjvN2PX7I{AGT)Q2_E`_N%4*LWlb5__y0?FMNY{_rwCfu`T>N=|9qX4_
zRrfyplbyZwqxIYsi+)yn-u*R~CHhACoU4cOSkx7^XC3_Id7xYDXOw-cRQtA7Gg$Z3
zo#%+i{X6fWwd;RB_q{XL-q$|M^|-v{cJH<K9ILhJ=Fe|D@y7Ao%kS48@8Qv1ZM=J)
zfbaDmd&9mhE&L<*F!#LV{_|V^uDJGdx2n=*kL9j0Gx%+<y?Jz$Z}o-6CI6SqWBq>R
zVMW>BKU2CV_;+}3`s7!#=+5Oy`<j-luSshwP}?W5|M4`-j{DDj8u~a6P2Ss8Iq&eU
zCik)*dnYq6q>G+^|KF-UpJTW94RsNlo%>|u6%<9BY+|}p`gfRZSo`S0-Tp)IuP-|$
z$%-*oyq?i{{rv|a?xPQX{ysnTZzTU|)k7y{ww34_-~H5KP^2Fbc;C0}{=;{sWt-F6
zoLt2|EP5)o_(kL9rTi7C;TC$6!gcr7-PiSHKJ-6Uc3!!wxAV2O=@u6+N&Y*(Kz#b`
zi<equ>)Eef65V`1b@9^kRd=GK1lu+mpPm-Cv%D;I`@WBlKmE=*#rAkr(c8v*N^_rv
z@*nWiwod=XFz1wvLHhCi%b5g!Uu9l@fB!2+zZu2l@A#`2Iz2TSSG`!x{^Prkvi5x2
zgsX>NG5WQ87p<>mh)76Z^<Hj6-TyiJ4~w0hZF``g`SS90853m#SINyVDZ3rJdC^6#
z{spVHUsAZpRq@x)DO~H?d(+MPuWpub`P{Ph{?anmx`(mBTP|fX^F8z8ozZtyC~gbe
z?RiVW?s;av*!$%CDR*}9m~-=QChBag?2qNPV!D(hHv3fGyF4T7%1bkEO751c`E{`R
z#`Z(y$;T6ne@@$!?RYu&!A}t>=8`{75!*r;=3c!0ODyKYhqJe|-5E+^zRNhgX89m@
zigAmd!p^YOoDUd%m^K$l{ube#7yY!L@iwbnhw`p)PL7qSf|e)3>mGJTJPcVjMO$!T
z%IX8+7i60biOo%JKObIkX+v>~`R{kE`xyF`=r*3`Jn)ZU*2n2G3lBuI>|?mmyT4(k
z^8O%YrE9A0LLv`}1BH{1Xh-c5685d_)K7YpkonK+%v`?xOz|!^PJhu^eaonKzUz`p
z5z8F}v)x73Rfn#$DciZeqj&N3nAKdT3)a+ib%Z9d?Aj*~{$ly$3Z`dG4vUqK)|j@<
z=5}hi`P*+_{siS*>0jkGtHXs8yyxmPSRVK|;gVol;nj|?9(QLhi<akFA6S<dd~p+D
z;616(Xu6g=Y0|aDEA}ie_53hxVJB;0{I31iHXi!E_5iz~#F5+>-W`X`Zali$7Cj+H
zoa3s*uL}JSu5XqqJ^S0sA^S`1qi0KsQ~R})?Y;@@$CQtKQTbQQ*m9KV@XDX!`C=X4
ztEJ}8c3%`!J?9exe@B<d`Ewm_R$cyhXPcd1Mf+!s`kwBNlnc{0F|=f6vrYK;E1j`m
z-~XgDr!Jm*yLoqs%<E4|W--?+iykBhH`umX@0Qa0AG37xpQWo8PIK1G$i3|H!}QzN
zOIIh#Zxs;q6uiFp+R`I?Kg>BIY!I#zbuT72epmRRQ^w6*b|=#%_a4@d5V$#k;YHZp
zj6|iK#<?}jGg`zRJd{7jl)>Jv?-0r=@jxl)ePH|54JG&5bBnGXVG%D}b2%m4?(p31
z1MGrw_luSsF5cGJ$;-U!h<LyPZtcdI%AGr}9+dewDY>!OqA`Dg@{Adb3EsXJ8Km-_
z_%=*^%)8*Q-~^U=QIBmrCfnWAJzsZIP+vjv$gxDmy!qV)8@Iflf4KK*rPib7*v^8J
z!jCOI7?vCo@7lgfs6(Us)#HaN7C+eM%9ykH6)(f~=Cku3^Exbj9Jr&$yzE3@gKO0u
zN6}-OchoB$GKqcE9g%oIX5C?~*);`@<(9f(lGUrv3HELD+EZ59@+!7#*Xil;-@HS=
zC6x;KABa2ZQL`lQ^I5HJH6>@hWdF0gvr~McV9l)R?aLTa*_wNrXYekn2xjP$_MPm(
z<oGbOHdNN@!|V=)`9k*@RGw!%k+_k2&eq-H!^wjRO8>;%=k6DH=xrPsn&^3xB`WPR
zKkI?DSsS$c_wP1r36~X^S1zbsbAY=>&@-i3_vY45vhU{Xa(r|2q0$exmft@5A6XCF
zJ7>;(pmViZtcaLuOMRegZOn(M%5rOBgwB2~WKIiIdDH&Ar=nhT%?Z_g4I*t~d)X3v
z^O*Lg2rqc6zi-o{Q;yp?6c68CTGV>qzoY!w2`|qA@nnVz6VIO2=vwmj$)~+5x)wCt
zJTZ}Pj>)_pnT3(hPMf;BEXjyH`$Z|-ZuSoG9nBR?&rZ3|?-%^{wsTU;uN{-u-+%dp
zDO~0G`wz2bZf2S1Rmrivz;YY+vd{(Vzcq*Z&XCzxoU*|A;TZ-2Srv~2G0}zdXTAyy
zi96yEwDO3!VA@SS@jcV6)Uy2c9k*CL>7mb3Nro6DRn9YuZfvbRdwr3D?BQ1-Pdiw3
zqZnfRXEW?cWSJi-yFuT~rFhR3M#nj`{r@Ul6O=pYShrbf$EKC)I+~_}&reItj#c{5
zv!n0$hNJ}#Yk$au$(#`hOP!v0G|TO6tA5g>A9~XrnR1nObaOvfNW5HdtKo3!gblL-
zIfUYm99rJwJ>B^>$F0??<};|=VTk+1dCP4_vEUE3f;k0l?3>y-%ilZ9y1RAPX6D(B
zQ<Avt8Lcb)LyvS=H$2d{)xXyy`jO?#Q61Ne<+auEani@#=b!w(s5P6P`@;`~zyoWh
z9zSavfBoE~hbB2@3Uc)eS#>_Jx^VnAd?lmYr07^w_cX%HaN-V)54<LGKJzLZJf6F$
zA#N9E$_@)-#vRW$HZ(<?6q+&LS-!s__BvbBYK!}m9M@cEEW2KovEvkvUwEstog~9t
zGvjNy%pM#Y9)`$f^tRWpQF_&I_~a_*hCa(H>q7hfT+3nN{g}Yh(3`1xp!9{#go96K
z-{q@ySw86plTfGkNv0PPl0SKB#8}_gbO@$=6SX;cabonN?ug7yhow)h?JHOoaoCbu
zKw!(2u*;U*zv_H;hor7&18w|DRdNnJU0>a8_kPX1CppPZsb?nGz5c#DD2G3ahsnl5
zEZs08TeqNlt;7ejtD6os%r)<xuCDBuzD1g6MPlmeo=5H*JdZAzI(zPI%>|WNw~bf#
zz5eLpTW%!b&>h{=$5AQ9to71taZoNV+nv)D<!06LdjG4fX3uS$Cp+KTpCRtyB-R6(
zb2wFQcuHP9`n69xtTZ!K_h`}+hOg?)jQoNx-xTxZzqrxfkrpDAXB)+HOJ&hlS>9{W
zY8Mu!=rw%)TXkM7%I&wX{z)$b^+(%;j&|$(;ja;8-0VL0&&t?4f(Gha8r7MWF{QDb
zVYO*>nC5#y@$S@Ds<zjk^n~;DEhs*cUUldCT!t#CU3<73_8Dk}lxm13W_${4-_c=u
z{F2u-%SUzn^QA=^+#7QkN`91uifn!5(C%xc^DWw1p-gt(UQxlgH$_?HO1c4}d@Scz
zIm~QZ5&PVOHPBPZU9fKR=W0H?TMACqyZ5q5G^KoTU9+@!4pXRT%bqeZhV>^^Unepj
zoUmATf0x$kzSAi$&J_ChhxbJ??_V>MxjO&Vs_ER54;RLrx4!Y!XMfeqFh&<!QOVMl
zirB-44~s?>&+52-p5g3i?uoH!tqVFcqWky$bN!Meb<iXGv2;gkTOXr{#Pew@x|?)u
ze9q>Ts;tbj`99Y&>{WU`<BpBSjeXLuCzQ%oExXu%nsqndVb;{uT^(O<s>)o`bGajH
z*2te^)S+aT_B>&$;*28=(a&DI75e#hv1MmIL*G;tgJPGM@``gio^}{qUpUW}eL-r>
z+MCTR`jQ3j)IYfD$P_P)@owqrKO)Ycd{f+@SY_kx4HF7Z3f6npFhw&zVYzn1t}Cd)
z^073J-s1mh$IkzlV!Sghw9HN}jq`k6?h=X84nD2$J{8RzF_mo>ADwT^<jPb1e{PFb
zQAvPI$$pRXjj~>rm;M)f@82TG=CfR3Uw`$3*mF#a++UdXwcmTV<Xb?|vnvs9Oxy0N
ze=Rt4QsB%68$R#NE%$|Al$i7|&ET=nPkH$>Wy>MPoRU=k2jXiN^BojPpY33rCc&|H
zlDS2B@s?x-7fvZQHK&s=YeJo5J|D_E=C}6DqVtmjN<OTcy;#@mkE5Lbp-k_xhV$Z=
z7U~|Jee&C1!TCF5j&I)Z=8Iv->WRGGO=X;0Vtxz$Ono48_rS|z_KY!`Enjf@T#q-g
zi2bW%*=e@rs)l=_$JtvoTf*K1g&)@HC}q2O{FwIg>`&`Yw<>07ZMws%s8c5J_**<z
z$CkxcMVAR@F)aM2yXunmpZEWJy<=K}x7x@RJ6(%7a`ousfV#g+4V3$t+@-Z2hRl^q
zD8I2FWVzOZ*Vme?4P3;9)^5$-b+E<aRG+Vb;6$OQpd{U<xU#i3KF@10>TikO{BQZy
zg}R+z15--t{3qO+HH~%a8x|JFvqxWC=e6<WjqQo}msZSd|MpkGWf$w{yhZWeOO&q^
z9sm1A#lK^s)ZDA<S8a&i|LEha(5GwamOh@=zw~8(<N<T<`{JDUPm7%tHT~?`9repa
zcVFDEGP$Cc!asE^Ok>`}xC^|S<<+mfP^SH~;kP*byt*y_XFu`3c)I_a<(hBz^w}Q=
zuhwmTuxR43{@;)G_+9Gv`xnyCFRSV5;#0rC^I#Ou)<<U>n?FCSY%HAgE@S_SSr$%<
zrZ?XZpICMI@cExgehhJCdllBn6dr3^ba$;*YuaAtnopBG+>7`8ja$uRZt+F3OCsTl
zEQ`Xqoy_?GvtPcF7C0to7+ca8u<eX*9rM{I)66$MTIKnjSxM6M*S_WmF+sg4s{1;w
z{AVqHYOcf-bC|VLNr|H~`(IS(t!dr@KiHC-eZ-kpeE9UbG_d4>)`c&-uWno>_26W<
zpl86z9p3w|ZhZRZkod+>m*C9pLJyZTCU2N?e?xP$oTb)->Bi4A_wZi(Gc`zUlK<`#
zGi${Bl=5F5d%r=!=O)X8Ku4zi>K}fDh49Q5ig(d!(>IuICSekA??B3dJ6EH7Tvjih
z8G0x#o$*8bNyFFYjUM=~NpEJ<-@Q?~=hj2ZI|*CvMYO&=+b~OIkJ5^$LJ!UzFD~^k
z992y>tns+VQlKeyrToDWzUj`dP78N)-%AOYYO$a<=|H;YHVKuTzjbCmDegIJyX^W7
z*E7=u)lT>rwEro~6j0Lrd@k16rXVm>y<W{(H2N~LFV`0NjNVU+IA%P%>iT8JH@B2u
zlR5tDOgwkOJjq8zVoB^w-UEFL+<BkyG5=iFt+gXZZQ;8xkvn|{pKm_3@zZ=i=Cg^q
zCK7X(#LVBc&Uv{j^FOxxr5TeuE^~cp2<`juUH+rZipHkZR?G*!Itsd;wK||`xnC;&
z7UR3rhidV{nU<&a#{cFj+%E9kDV+7VM_+HvvxtRH6&tQEi?gh$;5?_G)V8holk^LX
zYvrLoa<o2p9tkaZ^z*CII=+bTi_gv9y!?7<V`f6WS<*Ar9XEX9U4J?h_4H{>>fae#
zuh{21b^rRGH~vWfuzfCF+q_+ZabN1@g9jciN$+O7D&NgGxhCIGXo|V6Tavtrm~wiZ
zNvOjzwylgW8lzI5$gGZB&DDKQgW+o9=E*zeowfB|Ju#`Q;J)mf!ZYuDb=SU|cZp+8
zvZ{>yh4Ke;SZ!KFEz%k7#o6^&+DXiGjdF<YvofCX<UsqXG=)2n<_$g08+0BQGwi<k
zO#OG$bcOwPp-U^IuD!qTq@(6xyXp7RX91u1(vK<q{4uxr>9H)PgFi232>+PFz~_DQ
z^d!%cuI>~2j;+4#GO3PBrfqMBrjF8E+bxN%v7$oVb2%r>5RW^c)8$fi{PxS$D`JmN
zyHVpNoY>Ql{wZ2Ek>l2`i&`55TeFXA3;y1JK;7YNOc7|KN>cmjm(hI%=D!b#U)=2c
zt3>sXvT2i*M$($K2NG8)lnLDx6O`LfW8?khjqcj^D$R*|k18uvTiM;?&pje_eiehp
zg;$o=1<yJ3^<5uuFHmILe!}W_-}V_5FC!Ob76^%M__qGKPEJ9}=ckD$54R{kOf6qN
zf9d192TUhk)Va%UrdzO^MTfamSh+g60MuvuJL!1Enw2Kq9zvE|*Vub~>E_T+;pkY<
zv1O5S=jnA?zo)A=u6Fm;kxXp-JlA7Uj`$BXCzFGF&n#Uvmo4zMtFZMR+bLz*f_YDB
z_0r2(zWsi9JZEd?hUeN$@eUfwP8&~6Y%6NvKY7}G!``$nyLK|~Y5Y}|`;KAp*E=P}
zmvi2hu<SQ8&x`b!aQ2t<gNchH7-X+1Fuz=s#rxr1;olu@%*(iI7*)0&{Md4?&_8+e
zr=)HBI=Kv%7di)Q_%fCA`ix_`o9&;@ocH~;;mfREp@_+BW=p#cUgwzjwc~!z3C1Yz
zZ4w>Nuj#t^sovo6QRsH$UhsJK(#e6I%idf~I1pqRnfk!yVvkYA;+HEWd9t+5E5?d8
zSM8hS;1!@Ie&G3w{=3^Z|KDKX(D>}T>cPuj6WgD(B?)eA-I7>&x9;)Oo9T1^yuB#x
zd82AZzV$ql#j_X$?6o<K<QjgfInCcK(k#I&Vm4RhkWj9m@S)vYHH<q=Gp1)Om~v@%
z%9%wE*7Y2{9UfRHnBDTz<%(t4k^EDE&u=71G_CzLDcL>2Fy3V2@k3=&)7SIu2y%+}
zIQfL5-H&<of|+`}vRucQON3eWbu@D6?BLozMM5?vuFSV*jgxHNeUC|^YZaK{9h#Qb
zaatXpQowWey3ETvPSx?(ES=icfu^xoJ{ElaRj4}2VZy3&f(KRN4xAC(7#nTd{&Zck
zyUV*(?2>+GOeU^t);T1a^R7zgphS1?J^lL*!Yi&mJKvwa{PtAQ+%rP0GiR&G9k^w7
z<QAjj9;@ql*~jbMie|}Abk4IsnJ&3SR+R6D)#k?h@0ypKWK}<8hI}k&pBVpC-sP9N
zSB;?Uy3F5mJGAxmJGmS37Eet+qHN_Py<TRebX3$44*S<k@h&fBU!M6oYAVlsJ*N8(
zN3X7!n0zewp15V$ofquQ5ryGT_9=+X`Kznc!|r*hO8BqRx26{ofx?-e7yK+13hz94
z@xNycvt<81EB7Pz&MaTE`#OZ1UZ=P&VQoLFo#(<5^ZA(hg+t;At`(}63fIgGJ?i@`
zJalR7mR)Ir4-2kbH#c0j(TzJ-*YQDjL}1F)&sz_jJ*{-fp=9N}#j|@K8QJH|2u&5X
zcr*KX&B5GN>9Rb`3rZDNY-MmrSMS@tsO-iS(D;f|tGk)izMAa;7ZYW#PcZ(ev-oge
zPOr5z|Iwc|ui3uu>K8jP`+4lS!&4u%a&YU3mo#p;p2~YrdSYAZ%99#`ZBJD1d%K8y
zN~uxGJ6!bVk@U)i4{}R|)dRR^o4=OPKIvT`Q+HbM-n<15mUY;E)V|*<@gwT;j|!3L
zul_!MSl{0pdoKR~vs<Ct>IEyK_HXCf%5f(B+^PbO<e22xRfmKxluB&TRyvv3nEt<&
zV>$m)Nmak{pW;d<#dsTw`ue9ccJ|ANCY;yNT6*=v*)yLk_I`}}w`6{6g~j}aj{Qc5
z*naJ)W_rHh&BaWmvob9bwjG6nh1Wofs)cR@_x+4gnv>$vsIPR=aOKuAZNr3X*Ou%z
zJm4W~{%g9>Li^*#rsgZnOa53AqJRI!&C?5%GmC}Q51h07`|~41(!&`hX`u<Z9GkBd
z)!BU6Ui++jmv`uqgi2x2ggzy!hAAJ9{oAVGxjOFN$>WCGFGrS0oLYN-zL%rnq+}n>
zhI0bzydM-#*^q6W?V|3sBUjozOZ(`bS+ZZdzNHAoKf0>R(s$+H>nF!2T5VYFU~%hS
zrkib{ZP)Hob6g`uf8SSH=Fl$JsIOE~n6a^1xSfAt<6^_PmyhrWUyoU@nzmvdM~$%b
zA^!QHx!n;)GUqy1=`C>dGGwq>w_jrOidi=of8W}tvY}1k18d2O1kZ$LH!QWH_dn%e
z_glGaT}Ou!v+^-*!FiIZ`xvZtUg*5VP;h#xib1#68&=J`QWB51c-IIBiW@tg`cNjz
zJimDJ5pf6GSAxx<%pWeOH%4CJxmKi^b$(UziiW*49h}nzG#1x9-NkUSUDox^%k-BM
zW(nnmh<&hZoEErFW8wLTV?D{nd`$93PJExYrLW4-rQuqk=wXYw3@ZB=q{N=Go{?Fp
zZpHI9-*TFwRff`*6IE}+m1?RFYzYvI_IBR2z0*0>dj8sDT$8rcKT;@CJT~oEP+^UY
z&+G!vwZ$#A=J(>x)HTSZwBPH`Gp%6MUmFwMd-hZC#kFk}XH_=GMDvzy(614En4o;U
zdUdH)_Rl&#rxnKAPCaB2*|6+D;1s4eI~j9}zdyCMRGoiOKJC-T>ZGSlpP1~_8zgSt
z?Pf~&DJNdoa{bdRiNYl<9UqmJxh~mxLh-GL;I@T(X2*N2=}?;3yXsLU*T3vM)k`M|
zh2}dfc$T`|Grf<oD%+$zweLb=tPB5lL8kjI63id280=@{TP`RSDlE89|M=#e*Ued6
z)^r4#n{Q$K$W*Rt`1sWliO|*)vmW2Pv)jc=s#Wgm1kMlT@r&QJGhDv(Y`rs^`B7d)
zu8_Wf+G<8)cd3LA_sZ5LukK^}U^&ew`dRxE{bbG4E5E8~9hg(B^5MeDr>DaU-?&%&
zd8_nS=kDVzs>V`FyQ6Q0Hm#TCn=b$HiictL_R@1N3@!=22s_g3DHF)f$2EJmdi#F;
zN&d!iOD`{;o}wZXfAPVq#h(pk?6-fpaL%+Jd>Ksk>a6d|7TjKAsq%P2k65VUK8LSc
zLU=bc%6vO)tR1oU`XdqM+d-!{^_*vXV>Z{fabElC<@cwv_%C)ZJhX7yQrSPE%Ys(j
zh?^XJD#6X^U&o7WMmLz`4h6AAA2@&X;E|U2z@wZudaExjy>O@f<BGHcrxP^U79Wx=
zd?~fy|J(;}vl!<y-{`fveQ0y*6#vZzQy*o16DiwZ)~;|^v3sLjvQ(d{e6g3x{J6}t
zPl4=ZS)%SL@22)Q|Gl<ikNm73t`E97mhxNNtrwIRZatxQZ{;bbc!sw#Ll#U_cKO<5
zux0wH1EH)r8$<g#ZI??kBrW+GQxeF!t{{7#Sg7os<}}|m7j)g0T;!g3j#p)ss;|mL
zcJ;ceG4cnRkGc0XI<H=;&?wLK;lsPDKHWxs9+S;3a^|Tmar|Pr@J^w}&8<ypfl*f;
zyl`RCU;6%h;`Gn!l&{^L8X<LP!s;k}g-d%@U%gpYFlWQztR-t&LSFZ?PMjff&W+DG
z<KW(vH?0q3zHPca-Q2KfhU}f>+ea+^uzS@AdVX6`VQG}kc=~q%SDL^>SJt}M`KoEx
zK7E`uLpZPL&eV>pk&n7L(k1Th%nlWta-6-q=fH_`^+CLDeIHC5-SsCb{}n0^ec{m~
zSSFD8s?ni(>+R4)^9vuk(*<{@pWpxN_~D&QOs_a=7_|#tOkB(~ZOiAVWY4-~Tm9B=
zyqzYV{igWPjFagPFHgw&`)`Ub^X<Zl-&1X4be4O5E@+EjwX2->#QxX+B2^^`o;{j#
zL>(u%-D2TUIIzZ_Y4eH$&1Yk~o6ZFY{!qG9)7-w(dLrLip?HSAX(ySCzIYa2a!qw{
z)%mNT)&KO+f$}~9h1G$TlP(Ip^?q_=nxp*V4ga2(K2Zs4$$kaeOBwek=%!?U>POZK
zMlUv+Ts}2B@^I7jqdgCJwP%YdeTfNsrTJ2&FJb;}Vbz*D4Uy0J)*9EF-Phu|wc2FS
zFUJ)Bs~OK$bjXX>JehIRFsH5P`|dum4PA%s2COQRHICkO$#Gql(po;voyC1mU3)6z
z%Ad<5`(IZ{|8-jC^qZ8O-ZhMpdE$R8r$*GW*LCRyYZg~1TOGEZo9uW%j(f$~y^@<X
zB9x~tQNIt`|8glqHB#&4yubrVB|COlr>mMYW@NSASU3OnM-}<=SA`hX{yWMrZCO9t
zHK~8=nwicVo$LDd+tl?sad#F@)Sh(y(8}~ZpVclrcpS^%zxKt9Chz)4qjl<clpb|l
z-0YgOW8FUCi|d8rU0&IQo!BFo`Ek9b^nC{Xg)*z687~|)Y~<puSj=~GVu2dNiU6Or
zr4Lw7?^ZfwS$5{^Z||p#<+JivF>~F%ktVDVxjXc#aqHamM=D-RUOTw*&9}cQY&Kh`
zMxWnM<j3Rs)#stNewg+?!IuTc41bACRN>vXE6!z~{f#3}tXD7G(|J`P@BW#d<sxxE
zl$0t`chxGJuzI*n`@vT5Hi2=2so$zlh9^hzUv6K-rE)ssiHA1d?UL0po;zAUJu!6`
zJ9?$!*uS@4+ZZ(pqvBc3cidxIQNQS@!pf=BY!=HZ=}o$|SN7YlWgYAZdNqvsKOep|
zdh@}hxt0Idf2E&)WLL}m&bWHu@tt_aeJxK^KZJ-sd=%8aWW%bE2en0Y%hhMz^Q>Xq
zsPL$Zafw$`pm{?~p}0h;EZ5p=B^G<HEqr|Ioat2MdydhizgFM4Z}#Q+IhjiTTq$|W
zO|w|%WXvf|G3`F~tI+y5Pw;Zzmf*`1OecOz`lef?ob<>1Jx@~hj`({n@2_nZDfp$o
zFDvFqzw`!)oxj8lx)(XRKbo(>b*#Nse5z7T<K%M_{f_kMJNYrJn(525dBvoUD%alb
z%Zu4C`G-;%i$&?nTT9jV6|XTlt@^>4k@MfTNwxA#EhXRH-f2~SIOV6MQFW4g_$px$
z1IaDsN5l>6C%9Se-V`rC<HpoqDsDd(X+F<7;BahHI>Y5PG0erilS(}tnV&rp_4Haa
z_o?;D-XpX0CcQW1isDxbNLnlOU|J)u(dq{!fksMa?dD&$YzyvYy3f#;AvD8sl12Nf
zZW+O<OyQM_GetS9+$-K`nZA%&xtZ$`@4ccUlA7E#f*&2uNxyOg?G`!S^x%46&7I@C
zGh9U{{aNVyQ%~!yOty^N2NA)C@rADof9^Q-k*jN!@|2UA|24GSkFfUJev9s7yglia
z<+Y8iYkw?#E^$1xl%H*572nb_<zqr|KbSJATgqkUDmVFUR;W8ESordbL;L#tBQtH-
zs~+vR(U*MvUXe@2M~x4@Pp<z>;Zx#{w=7#R$>TvXqow$2S;1P(d$$cAJu(!#8zZ=I
z?ZT!4<#k)1tITWIt5JF*`{{eJrE#Zb_$XWM|E99-M!u%^gOyW{7ivfI#8{MeH)<@u
zn{+@+Gm6KgH?pGT;S^RCor<qI&G(aEY>D+}n-|OUWf!lT=Z;;b5?dAG)-Z0k-lE5_
zwff9ChmfL}Pd$fvL{58V-tynek@-HOQ9M>MVfUActv@zTnXjy>qai!LGd<|Yi6#50
z-B?^4Z*1)lnY`=uD%gq%503MH*Z<e9|Jz?)|2MyNwu?}0{lqB@_Rkm9ZAqWd;JW$b
z;XC`ce$-vR<?;Rg`n&4N<$wMp|Fc=l^gqtt#*Sb9k+|-YgsgXm^-`9(p4tA;=9eee
z^ghEkuw@gV!vkh8$(?XH)Dd2Fr+W1}w>^H-*Owi+P~#i8)J`N`*xFV4qv<@A-`_7q
z9#8-G&$9mgj(6R=nRJ(1%HK$iI%epZ%AOv7^q1|l@L!QUai_9hyiYo{$kk=vy$_3A
zC7LI%s9h=RdE52C>+f?G&YB%kwq;Got=aiEMXznUzEz{Z*yHx0rJpvuFOZHiaj{db
z{16sZ-tqW#$kUe}!k)f2-W|7+y?S4Y`y-Ctmn*Uw3!FN4y$-4ra(i&_uy$0#Eh|s+
z>6Z#72!2@fkdfQ*jQ$oD)nDtp4+rmVf1R^?(w4>pm%=V;Y-VHL<DJQ2=2&$8=AkVb
zZe}m6>+>s0a~(yQUHw;_is^d!#x(r;y2slzkKcCxIxG5o)+!hGY?f<jySHpDnZM=n
zcU_M+u59;8g0$oBo!JuqW6qA?{`r@KzFO3M+p*`%vG)Zvfot#EvTXkQ`}rSRCu5U$
zUWY<oSuja|IJfSAX?y(s{}%P@JHvM5{gi%IvgN}Tp;JEJW$GmxtF5iB&aqs7fBu}c
zlTDX9uZj7U`rO7|G_0=Ry`BBnoqv85HZz~Cm3q2ivA*w=hRHeonO6&@Pe>@8eLM1y
zl9-LD*w@V0-=AN$Y5M8p`9EhX&)tmhquXnBTG$fKuB!gX;C}knyL(e&@7#?rR9akr
z*^MQ3(vsJnzc)ObD7(ciV~0aqP3?j|e^>8wwz6vfm{I**b^_DgX)4cys-|pWIBd1-
z{k~`ui_*T`k$h1NlO=Z8T4q?Z1a7w6EYEmZviZqt*WWw-?7L(>|LOb960`bM-z@yc
zZTq$2Rq_sn9cL~s=eT(Dc=Db%b3Bu|A6{bFQ+Hf(wd>>W7ZUZCcQsy&6zWxI=R1CX
zX=>)-?l1w}LsO;KR<&?ytP(4|b7R#TExAj<J5tz{qv}4|W@z`lYc&ghJGtyn-r8qx
z{%`xO-)mmr<KPm&H~HHVd3Ld$rC(TVXCJ6nbC~3^onh8pWvN@7EgjMY+zN_@QLU37
zy!T}*5!!v!BSKM!ZO+8o4r{+n51xM`{+@-?vV#sSGoJ9W=|=sT_9^W_lKpW(uD?eQ
z{H^uMfAF1!t5Z<y@b<VfYd9nsANeU1xhO8~VPUoS`t;8?(I2L{jL!oLdCjd3F0nbk
z*R3gi$+WfE-KRCJX2$wz{wTRz`ss7U<?kQUmfbv1yf5;=a~7*ZJnDg*J2G{;CAdYH
zCaY~yu5%Hr5PYrlXp8no*CqMIyn@>Ls+<06HtH+6WxHmq<lY$eNAl}&^QhqX17`&D
zI2Oz)|J`=2YQhgDt8>?cW>{W&xg<DpyVauh#YfZ)16&_md=)18L#N_lcgGG68TTJS
zNo|{J8}*eqH5sSRHdm58BFz5As#EvNfs04<LS1VF)eF?p_C@Ff@;OB&9WzyY=kVIF
zN^-&9ThRw*#kdD@MOe4YDd*S}dwcpbk)v-XEcX8t$)+bFoqg+k&Wd`u$<J;6R0$P6
zmOfyo*QoB?@9pQYX}gT@m2lR59bc;3C*A9vv5||rM)2pN>1Cg#H%_@w@OyoS%CWSH
zp#6f{+iV*37dTEaZsaPrW4jQW{M(fGf#9y!eIIY|#hqpJU9#tx<Q%o>i)I~`c3HS|
zV&Y0CrOB>K)OfDmy>)SOSFHBC9Cx$pYm*P|6G;4c^{ROlU*+Ye3PDHOSpUn^ZeVV^
zv{kB>VME+~xB2PHr-Dvf{<`5OF@5p$i|y=BJ?twMU-kIWvF=WE@3}Dj8o`YRRO)lL
z+WzKW#PlY0VcCjK?!C#sSo5Nk_f)P=RlL;R`DAlXoQ?ImyEjelEIYGn;vK=bA5t|t
z44QgB&we2;SoJOLLAOUVL-m>+Q#+pVGsU}D<Q@$CtMX{h6i`$D&CDt1Zf%uxSS{$r
z|9%k@d)Y$eNjX#b^tW|;ICH1XU=v)poyDNzanp}pXSc<2t*2D}zWui>|J(Va0z#K~
zRDUY0X?c9?53g&*fu?V|YlF5lUSw+f-K^NS_w#|fqDfy4v=rPsUqAD@HkYvanF?1O
zZN>PB=hy2ky|U5EE?)PYL(ZHkzKJm<EXKx`*KbRU$IOx1r@s1y%f%pe7x#x}qAUar
z&6j<>tTWBbZ%5Akm3Mu1a4RqD<Mne%wBM)sX6FmRWnps!W$O23|9#JDW|99riR;e}
zhWPD1r#GDS+tf3E_4z1H&C0v!lkYtA(B}AboHv5!RySz;SW0cHS`=G;eQIxM%)9;-
z`}LLBbr)@XcHZ<^q}GpnQg(IcP22R>d8WObZraBCa$!f|I>Q~!%SyG=_a5_6(#u!f
z*B~Wbn|{qQOz!N{6BqTB?lgJS2rkqz7OUT^WitPEheKV6>l>-}GNK82>JnRBy=Jy<
zE8!QPy3r<V(b11ua(g}Oxj%l0m~OBk-Ayntt9@7CIVt(8Z9y9ruWW0pc*>!0X{SVD
zUU*-J=}YsC53?7kJ!3d~tVZDQ3}5{@wokUiFFhPDq&q>S_{j0E4C*cgVrPD-Ka5F=
z3vjPk^<%XupJU8I>#5JZetXTxSi1gc_!8fiX|KO~am%Kku!(4z-%{N9bCJP|s3+la
zTiirlBx;1-U7c0C=h38^?boxnZu`K}tgGSm;_5B0y7<Wj$E6=|8ofRDYp24Vn4%2_
zIRDOTSl-LK=#FKI)Y_dgr-BWmlCn*XDkz$K<b0TN;5Ppp=6O7mG-PT*HQX9BBf4CT
zZQONkJTBcfg=t@o=B)X==U7v`|IXR$(cB&CRmJGPUU|-J_bXdNE#@}PRk$R%)4h>D
z$*|+ol!NOO3$?QZgk{tf6rOJs@<}RV?JA$uVcjtA@Z1{$9WP|~cc`?T59T~0!~M?f
z@65;l*jge!-&2@$X8yy^7h=w?I_BQTASH6(k0D1KL(bX-RgZ4`d;M4Ea9Cn*tn&IP
z#h=&Jm|nD$dAD(suU7TG{;xmg3I14q==Ou1)Bf#vSP|6B{qnoshj_LB&!^21HD4yj
zImzY7+Ydz-4ont3GvN$Z$CEAhw<mr-aq^+{q6cyY7uOlxZf(ik;lEP*CzH)NrW^az
zKU~&eI>?q4>1v~0evr>zx`HKuD|QLr1>aky9uwF<9V#~zZaB}qLP0TzU#VU(WA5$4
zO><?$=lITRsgCGaKcO`|?(hG=%n<oCtZXNpB&J_He&C+d5yLGa30~qVFCKpQdv&qt
z5^kZKAC*<h<h%9$sO+*yn(Y6;UU&h|s*?%&v24l-MUg!h+T&A?dgxYe4%;%xa&y>@
z4X?x){6D0HsZ2c{9wu*|klMOfq;HCr_K}reU5y`HS-EV1r0Jm^RSBL+HUi(180|#@
z1om!^3p2J*O7xyFw<zyV!ve0!J^5h=Qc75u{M<g5&Uh!?)6ft<i}CM0rrWKP8IRt3
zbN@iffkPXjdRX@JpG|P^)iH0LsC*|=%At411EWo=X7c4e%+cnKh`ea`NS8tJL6nx2
zHmeR>{06QE#b>VDet-U_ZS%@I?Hf{5XLuj}_P>MCFa32m&yLHcJu~kV@g}RtWOv_R
zmnil@U|RMJ(4i&~yIHl3@3f`txjKhoUT>1I*F%M_lP9>e&3ZnHFslil)Y@}-Mv<eq
z+y<|W2G)(|8Q<j1Sj)bhdE*+lV9t4UtE|7Ue$~0x`#Ai(z?3=XWFOal_q1CjQ1{jB
zklwqT7cLWy$2v6rnP4>Kq9{M3$OEzW3e#LwB5!%u2zowRzE?HY`^dhDEa$A3vi`Z%
zKfPh$j}MQ|GG)#^c6p+PKy<);mkI^3A50!5r}Pt^&3Jh1)cyUk;+K6Na4T3UvI?(w
zd3J{D!6O&1R%aj7??1vW_-kT?GJm?PeA1Jtl8k+(8`Cw`ru}|gz{&D{AJcpnu`Lg_
zd<aq!iT%)1SYwmz-1dnnt?$pJcjs5Vky+TT{L!`Lt6|f<yZaO;PB<zasXoy;<MG)C
zK}nq#4rtBduno{?y4NB4{8Pddj%pQ+^n0sry*Q!v(e;R;eAKn+LJMD>U~^Y5)I6)B
zq|`b!^pVlcdf~~ABI@Ur?rhR{#HkY)vM!mIY3i247yd<M$*tlDTr$7)!KEdK{vSWb
zA?-bPYqQcx?s%6LyH^(9_jRNS3Z^aNs$u?Mkk2SNFJ#em*N0-<-&Sq6nieA%6e-MY
zb7R@>;|FitQ-Az8;|EK|-FqE-4;-`2NIGuz{QN3D-5rxm?TS+Pm0l>8KRLnJl=b-Y
z=Tj5ijwbgUx7fvQKC#OqY5C{B3cFl+EaF^0ezX^PAk+D8+kGuRk3)ho+t0KFUtu`n
z<q&wCEAI|>UVqx!BdxWG`l?qZGsPd7A$xr8uC2^UY?XJk=DBDXUV2ocy6j==eT8o!
ziMPsDXZh{i_w34X-iRKjts$EQ99C~gpLUq7@2&X8l3!aT&UUhHvRclj6}~j1=1GTv
zVg%o<n=uSRcizOzTD@TrXW@CvV2c%%PZ#euz1NVwCg7h$zWxKr{P1=M)>GY*hiy+e
ze&4v@T9Ku=0K*5REBf3W7ji<52pdd)@Gc|Z_piAcmZnkjo^0l+xOPUswahH<m9I$H
z7Bv;Mqs?M^H8HYBz6Pqa9~5lA?y{%xTF83UG!7%Cco&w(dhgb}(wn&Lr^-jx2^YE<
z-m^J8p0)J+<`r(-tlT$Nui!iXy!*xvUtPH)r^IwVC@0m+6j-hFsu7BGSj@KBzVGqG
zfXbyZ_YZ8mnQh2uB|h0Dv?S1E*UF`b*7nJSoZzfs+>)>68DshB?!DDJJ=U#x+;sg=
zcwdQ2o@U3hA3GQ~YjC{$@S<k5jh^U(qv67d{kP7ozZd$FqxyDFf3vN@>jk$|-+5LE
zh$fuB*A|>)p8o#xrL#;SO&2y@UeEYEOQ%M4vyqmC-+IRO-jnLh9Qv(m&KD}Gc{u-7
zdBmjux%h@-O;|?Ebw|zM2i+XGAEx;)iax@0IHWP3p?y)-lL+QRX?Kd3$f<5Trf}%6
z^ZsyFu9I8Sd|R$?vdeGpU;e8_d|yX|QItjJZWk-b2g?F$ZQdSP`uXXDnabZhZ!p{`
zIucTP^@QMi&$UvPX%$lC-(`yZ6|I{iZXEdUw`QVQcZR^j$2*cw?=eYV`ZVZK^9|ld
zd}m^QahQdv<}<0NDyS?ww_);$v&Wkr3)|`aIJeQ{%|z)R3mIngKTVj;C%WT#)8v@E
z>l2Gki8MTr-#%yahWyV}n@{eJso{IX8L?XEUGdA3_xmSm+LSD^5cxj2POOPtIm&eP
znG^o@J_i=Eg@TU$)NIgCc05uO<ub`C{)f^rw*HW}3cp-i{wc2$5;eU3YN2z9@+BQ7
zpKkMwR?Qks&Ea9~x|U_l9@ZfrJEXIxoTzAD*mwB|+wzwO<2yO-Ub=M5++lXS5ra<p
zPgWb(LKUNk>bHwtJovJw*T}D^R^SI)RfS-9Uxx<w%Qrzk8@9WhNb2fX?&a~vJZX_*
z1k1jT5V@E&v7IKDHQq1kEHIz^$uq{*Tbo<yj^q(8`@Jt^_U?9hldKu)`$lC_;f}P~
zJCs+*xv<XIEE#<McfS7Yk52Q-KSi=liB?{;t~+O0ks+J-lxWp`ZL6E-=ki<^FYNca
z(V?s|LCI+|SD{J1s@e^nDJwcJq`7spNl!F0c+R@7q3NVf<ILnnvkY;0dCx}`e#dN7
zWql@|>;Ilpf9Si~v*X26G>)`b+TZK%Xze(hR@a>F{_slo^W()oG+bEr)!5uK&e%Eq
zhti{b4VTzeQc8gf<5qVVDo#k=J&mKBW8Hk^uC2$plP<(}s&wpD`oJ0@{+WA*<)LVs
zIW_a|e<(ay-dEr*$NHg=IV_NO+V}5#S%QY^dik0X^SZzDHARJPuv+oFP5pN^``3A!
zj;K4NhvYczdVX!`hoxH8k(Qn63G2)cUY`^E&#$WB@rn(X)@wc}*esChR>57A{VqZM
z<VTfFx1DXc(>zrwOXqxSIK0Z7t42^Wwk5vFe4}nsl6^>^uwY!rwJFvcH?I1p=Eq>Q
z$(PCa_!;Fr@x@0rlrY5~39?r5h_|1|r(nlfBWV36v86<JVhX#|r;`ege3+FvXG=Kw
zb<AGWp{VdE(0+em=+tdb{~Zz+RNP?vXnnlbl1Eaf=c;d1SP*FIeoQUQCH`&XS7E*5
z34e1K0uFwy($P&9U9I6|c6dqnLy?!hJyIK<i{&2QVqIsweL;ujrSncUJ)4Y=teGlU
zEhKq*USq$E^6Tu-J>PX7JZ4+7=z_SeyzA4c%G<Jqm`ns`ZU3@$Ro`R}B@vS!riL4D
z2JW23p)Pk++;@pG>z$8r-e*d5%0T6rSLV{#&KdtY?yjD-S+T;!z=}g|_3@yTdghoP
zsg3$dXOA6Y7u~JJ$nEzwR*>0;)7zr`h}Og<yT2V07vx{P<#UX8%c-5hKbVA~4@oeb
z+qGj>fa_ES;dz_W%LBKhY?5v_7Yy7R^GrSF^J9xw;gt`&Z#+<D*t9ED$(mnx<MvgZ
zdzBX4wwxB$xkXdGr7`@-Ud`L8U0)w6%xl<LaNw}|(qQiP3Plf5xw+}5BK11u433E&
zc&_lKDEywm?Il~=O%vCMERNd}@U}{oWxId={S${K%YX66x_FY`xgzZHk)68lOcu{u
zv!7EvCvHmUtrAnFIc01vTduiq?AYN`Cwy5c?Z*|(Na2-_i;CVxDVYd09S~<IRdgu~
zx4blS^YW^{Y%88Q@_GtBbZTU2er?WjWXXxZdS;Uzts3roUM=qSF#_63dn!Me9%<!x
zA9Xe(&nHPjFK)G$wC^dV`wSvpO&@vB9(H>7i+7?FyWcHQ!Ms1*K0nL^^(@-T;@3*a
zTXuQ>XRW!@aNbZ*#322B_Ot_vkt^0K*L*v?;&r8(!zaGGv-eEyKfiK+##$#1>zTZ=
z`%kSYS>ItYUF7WJId3=0+_sq!dg$duwMQSVk}UTLZ1!f=6BH5jZ|0SL+v~ypPU(Yd
z%R7VkwR<`$&GsJ(?_=E+Ynb=oF`Eus&o$KzuN*FE=9q@b3VeQ2sKK;Hsbbv$_KlJ*
z3l|4lo~fyM*v&Ejr``PcSTVtUKFN0bcWsp2yI!p!<B-q{*RMf>x=+GH*2!1trLX=F
z&2>_BX?$nNzXs>TP*DlBNenkj`ve`^6wbsKE%~)v=Ywy~jT7fS&Jh>PZagAxc%094
zM|S52-E-l+>Knh^dAQ?^+mY19Bjy(t97<xaeRL?8+2T#{lbf6QqStMBy+M2dXqmyO
zkQWRNPS?cQg;c&5=rA33HvTIWUecwMc0+RE?dOa5FEigtZaN@7QB3WWiTn}UNgsC~
z5uZ5s?bbS7!^82LU(bqIFrDGzZ>J-_3&nn@9olO;?XY*KphWPa<_>q=Ntq7~&g%%S
zOP}<3!sRXx+j|SIZ0fLl_{F$$N6+);YbJZR`zxfcUMIBi(f$vvDYmn!GD9<7hObyK
zXKh!xww3y~6268V9Tl#MmNyhGrFFjewq0mp&6TFS(2lQs$12Q~LVA7#eOD=K&v^Wt
z;YR4uN17jb1K87<J9gM?Z*-ECIKS}-e|<?*chV!peajTqc~%SgADDNRqgwE_uhje^
zw(1x6PhQ_pT)@zL`O2yG!w1)W?79%``k-4P%2DTi^A2_^Ssukddpmi>zgR5YnKtc)
zMOaSF!)}lLkAA*(<KZ(@*c9%P;q$mBFHF?pctGc_RR!|Vg0o(PDe+XP?CU6q>~()F
zZRj-H@d392C!66qlYoNd<=>bYR{T&{^G!?Z;JpjFN_z^d>V@_?imYFFK#`f{>YN>W
zmWA%RKTA0L>W7l2=by<;zb!d$@tLrR;a5S6!#e{C7YF3*l`$0j#bIDJ`MlAM!wCl^
zGoCs#l|@he%%{KStn`s<?Gj&=+FXzH7K#5*I<#4*XH&lFrN|SWHG+vIoT@XWC#D_b
zj(4e0_WJkdSZt`(qL5B~2E7A^|F3@&RrO_8;hTH=lcZL-N}kyAwXVW?_06+&7dVVE
z51$JWVy|OhWcz!+z5RPvc(}-FtwM&w_b&>n#@cFhDs5+Yl=#zk^#mbTZXcu5C-VNO
z$8=0t=**GQ&7nWfSkL92`LnH|>rQ<=koVD4F!prv&RgCt9zUn4$FMQ!Hs5?`a8Mzs
z)mOMq;BcD-zwI~2i3x9)c6JCKbdT9>^=OOjru8DeJu|(USWCjM6x`W!euqHj!>=7m
zse%thTGz6NC7tDKTa^}Qoh$WIBw6v%L&M$cO;qA0AM}c8e5-RY!1w!{xjg5EmcM=L
zVV4r1Ch9+RT~1K$bJ4>O0}nmq`}ByHAwTsmj}7mFw5V&ZCM63cHN+ln;TBZ8w~}qM
zM#xHOy(2e_&Yky3I>>xs$Ha&X^8=5MC>)yYkiYs!M{G&Ynrm-gbugF6F!}8eh<-V5
z{gZN`$BC+k!#{CPbhApG8Q$sCBB)f;nxXWpgTb{(z;pV^z%Ho|O~>7rcP<Hcb9rF&
zs)O-H`X8l7Cl|d>3lx_3EBEy=VANQBq}$`E&%Im~u{z-#Zyg!$9OaFh<o9g-?k)S!
z?#B5a3UR-0?md$IWZe<b8+<SQK6`Y1F9`pB{Oj>Lv15$ERWDQd!d+)Pa&wz_t+V2*
z(fkB85pkt?R-t#Yx7tpeyXLvHp3A<%1CdX9XSB?CV3U2Qb;b%|%Q;^qgnp_O9AaHC
z?W1|ZlL(KieYLu$rY1MWo^Ro9Sey8Mw$UUu$6M{O$J)Z#5`#r7QWorO^L(=*NiQm?
zfJ64GZzm&PvtXs8;LX*NA$R_kFL2~u|20lnnaO=ul9$hh%=rb1NjINQE^CfBkS*QG
z>L*disD9*$tKi|a68B>Le>k3zezYb#WuLo#bW&~y*Q{^7%`c9b6mAqe<n`u;zoTIE
ztB&Mb*G%f3oGASCY2mzkMJyKtepI}Z?0Ea8Rpaszmp${Z@IOlX*N`oJOXQ5cQf4(@
zdtQfY>5rJq+*x@>naU^g_of9}-Fe9}Cv@&hzvYp_P1Ap?KJ3bQZ2Wqf^U|pn-`Aej
zS<-C2V2<kD%GMt}OJ*NlQzrBDVM&}&*I^wt&)DXROH3|2G05&#=F)p>YsR;E+eu&Z
zfH}Jk23JkJ@;vz9F+2YU?2msH)RdoOsNt+AXKWT!;<??G_F$DfzpE(o>>IZxr@3r<
zp)1X%r1f+|q6z!{-?JtPv@P^IT5HnqJX)*R!rXrQmD`5bOf+<U6whh=c-8aZ+I45=
zbN>6Gr?fV+!)%9urA1<Pfmu!Oa+c(-<_>1Rnv0zBE_==%-1ySzOLK>?;47P0VcWCk
zx6IzI5|q!~;k>AG1N*VpYTXq!75%e34!0k3FzS|)zSE`VyX3Eo=GCK9IvSj9*WF#U
z`Q+yHf#&9G(mtFjJGb$aCeOL3htrR)ZEo~W&wMzeaia2^-9eUTje^wQ8SA<HswjAn
zE9AL<*F&c_&kxSNIEUlko3t7MWp)kUP|q5Jf|G?h985M52X?h|tavNLWM5Sq<-}EU
z^2o-Po>)~Gu4CGk;meCV8s6-vbu-(-YQ4C!<apxSqFEofJr+NFFX?2=J2CxGbss-l
z9`hvSbK9z8i)?aERbBZJ=;mVY9pWUnx43Vj`k8C5?^Jy8e&OWvN2qeGjP&H4KF%S6
z@}hkgCY0_EQdaCuy%nP3S)q5;oP$4k)nri-_A=YK*<Wq>ZB{z@FB07#%)uV>H73h4
zQHfPI#Is`Ewey_2b+6CaaG7mEnWx5S(*sPw^Iok_n>p>ZZl3=2+fSY;9a*`s_tUHL
zx;5LGLU%lUef{~P)`^WSbFEVDre>VxH4mBPDD1mdH_J_%@42tE+u02Zukx_CJM1w&
z`ha`aJ<;a-#}8QqHMlcZY+L%li)G)RXVa>z_a!#SU9Z}9%;f+Z|8~RIGaBaS-wB)H
z!Xj=vW&P3*Ob+&oIs0@EeTaHk^ZD9?V9!mSCKHN2Px^JmM8fIe<z;t;a^)YVF>(BP
zbms0dk)X?|6-q9Zwr*#9j>KtPzIWuj@Bx$ExgV5|ANiOlV-s^HI*~0dk5xjdOloey
zwjEoX9xdfd>?xfYXncRR*5{eex171t$#r9$eSl!b^-rgQ&rYm4@nY|VV<tW~56twG
zN_F;#pVia+=-_1zrGS}7c-AhT+Bzfhch3fcox=Td6YOpNIi0<J<k8Ql8hydKve=yu
zoz_g$7t>X`bIa_;(={$qcV)t^sVObE+`=t*&^1#0&UL|qn)y2f1a;JQr+M`ltnh!G
z{={6o@7C2HeHSJQl|J85=gzP+u-$N<@-8hgx%K;%zh>UzE&Xgg$?N7r<~K@w4IyX6
z_WnCi;lVaNExhl_#9xvoOcm~5&h9cRPgK6wwnF~)q62mU_a3VKVamv_V4la;F!_2$
zP5a5~?Mmwol${7lTloBT>CzkQ=bXj%HLZW*%y#Zx!LIt$$%RLaPqlfcoHEmp+g0Rl
zv(P$l7AJq+gPwOvd<usoGT7Yu4BPs`H-`l#Y%_Z7bY!lQTKH;>ofoq9uV$Vn<>F)A
zcBIQ<wXoh1uV{G-Uz1K={h~SRY8Fcxyk~fK&)C4_Yg@YH#Z@vZ89%mp+qdQR9$vLW
zU%AKsR1dcxd)bza!9wypF-1K)k{frKHn4LGxV7XxE|p9=I4@<L>7M1Rikm(L$7jcy
zA9*=N$Ra5zzjNh+{ZeO3cew3*=%n&?&f<uCdjXpTEiY#M+QbmF_>xL+(o)%+`2~yx
zuOFo+JmFaXmSbk(Q;%P6=kn&V++gO?lsWp|{wLdX8Nn{m=`X(f?_+LZY~HczwxQJw
z%_A#6d|Bvzq{S{WQ2P;APP*ruBS-#SD%F+QTl8Y%#5#_~*Oe?0^NgGX4w-qm@8S8r
zj(g(ypC4AJ>mS){D`l^|L~e?y;l=4KSKo#yoxA?veD0xEj`hoS^la$h?MvKy-R0WB
z3&G!ApPrB_2-zgWoWnXNdz#CoZ-VBvxuFc5c1|Wyq84-1T<@;>vb6ZI?)<<jPSPtS
z#g*=<9zJtmQiQikuGe-gwY|?K-CR|XaY)>#>qbJC#M`j9J6`wA4tv|7`0Q-h(KVMM
z)=C^<JkbzQ6mp<!i9_ZRro9E+x3qs3PJVKH+xGbL{H#Advlv`@)z|p*R=(u&*M+PK
zUe5PYkH&?S^*Cu+=S&b~o`3r}@8U;E8OK)?IGHl@iy3Unsz}*!deza0pG%?*wWL?&
zNo@JF$!(KS!qw@uS9|(AqF+qsR^HJtXVt29wid^(YrFyOvlqXwV5xi8&i^d8YxDh|
zW?y%=WzWs|y4(N6$=6T5Ur+F0TI|R-%leYc)0TxYNsL7W&5GQ8C0zm^ZPxqk5MY*4
z`O-S0Rbt`MDeF2lEh^R;s$QDLs2F2@q)*v8-D?TwzHgl3N)xs8UD}Sc^@(<=DJdl%
z+?3$)Ci!MWr|i7Uf~4IZH3lChDobDA@yN`fv3=7bMwz;xw|Wl_GR<RixVzYFb69~w
z^Y#<7PJCQDcimNmOKavP_%H3)5Oz%2-&?82G(D!n<Vo<mvr|sw%~7vmxcp$(^A!v;
z-#;&OkK)x0{JQh!J@a|jg=Hr7e`yye%VqtZT6${5gM;q^t+qud&n-FB+Ogvk<NY%V
zmr~}X$8>DzcziBU5R}B1>=l>!^it+wg<`^0dCNGyaQ;1sk9@6;v)t!4`OEPkfzdg{
ztE2GJ*{F1O_ng@7L)%oR`aaBF{#4b>_;_1-Y~kmpQeVw0_H6B#E9;lDFDCu}k7v`l
z`<@*(c*wLN`@&guUOBt)Q<IWQotE6Uj!V=`N~y2AJbm%SJ9ktKA8J$_;#X?laGKN2
z>9&>2KC!(Iopd$`b=^}@+TlC5Krw7avqid)^d8Ult*04YaO_PinW;P}_U)=@=8g}C
zbH4PP)bbMyPp~c&vCF8s=67#%At(DZ$&>9oJ{mHiA)gwXr#*6en4uqWswdvTa?StJ
zzTUR-H{N}59THB)dM>xp*zIafx+W>jxsluPriOj~l?f37Wr`NQIu|$3R`ynsQ(m@B
z=w_5&!uS2tXWUr-mRCIKu-LV=F6u6q%oA2G>Xg+>HWc_Kv@s%BowG~gMezl${X(uv
zYd2J^-KqF!F7sK%WiGcwCa#k;6<qebrd%ghxHwrzX<o`TPWz6CjE|kgcg029kLuko
zQ2fT=y>P4WZ^tL@Nj1Usua7Wjy%l|QtMl{IyB9T1nVN(@;>tOmb2QGzzMAI||7LxA
zRry1LEPB5z82y<W<ZI?E>t>Mn;HJ3g>5~?2!9EwReP4SeS|kK#Cm(8+&_484ELiD_
zaYUN7Qj^ueUo}dHE-n^$cpsFWJ?)#HZqgKti%XB`*pQ}gVP*2_hIZ4`FyAK!*3XFh
zCRC_C?W0?X>LFDHyH3@K%T%PU#$GpMd2=LR_USbXM&XA&@<$HwJ=Buhk>4G4<HVjP
zoZ<}sjB4Vl*%&P1SCz(#^m$5r>~Iy{82s3Fx<KLFt1TS$QpS2NJf2Zrp{s2rc09RZ
zW1qLDft~Ti;cdMdm(~RD-2Qp(POBuB)q)oBoVu1;3D$oS9dFz&ey33RWBxuBw@-@9
zft&(WFHf=c3*OO~y?m`+Qhe+l#vc-Yc`KwCm>M4&m7d#Js(7i+_}mVGM2-i}rrk{o
zSSt^)E|{uw*5%~HF9-W94uu649oK%fsFO9#eBBIJ#ifhS?GTu~cz@Qe4#R`@oI6Zh
zEJH5L<?#PBg^S;8o6y66dC%5M${%64U3>4@n^zsDg@5f^=;qtgAsoF()3C7N3$LJ~
zq_mopbJEFm3OY-bf)2|pV`)3m_Mur-M}CHL^|1%1)sFiqAHG|ipPyWPmQjT{q|UXc
zVgo1tTDQOihNz&J-G6HgH$L0J^n0V17iaGi@#9)zOSOLr_<6g3oPA$#@moKMy{|af
zr>Y-hty|dQaVUR>falECsyza;1y)819(EF5dHjIzB27WI!<C2lm7<*{|2p1W;hd73
zI_rb_AEp(b?>0<K&g<aY7q*Xc;+Ip>dM>vv9*mt4IfX6v9IJ26lI};At%?&D7w=r7
z-On9=Y0hPr7WHc?E>WuaI|ORoH45@YMfs0dy=MqZdiBBM(%D5yCgHiU!kHF|Et51i
zCPmNhRtxIayt+2_l~T~`Uy|ZU{4b2NW!En%+h%;Rv}cX}(KOE<zDBFZR`Z@&Pc=O*
zdV}wi-)?uUOWnULLS||IRNNC^7V-G|^3UJzaeogxxi8R~n>SzSN8;a8pEn%IjbO+-
zqIRSqqCr^Ch3{OWw~n*Y`v1apjFtz=qMv&dE9cHxHB-5_>5SJ`FO{!-QpIckgtD`U
zapVR6Y!hsldU%3|)~`aPE!P;omoH?Us%$2;<anvJyTp^^;su=@oR|MZRjzbiAbCf1
zy>|bLi>6NL1}bj1mY&@qARM>eJzwbI`Fr8(J7<;%%3rgJb8USa%s1OgDMeV`gGVV>
zFp9U?W49ecx6Av2Raco-FQ2{W*UxpCs_PEqxg6RtE38A@e{06i&frgq%|*v<8K*LD
zudAKHyYaQuy;v@PhFft{bs2OE*ygca*l>2Xt7$|zhvB1|%efs_Y8XGZtuZ<@^;HkI
zVX?rnH68qHdX|$Oy%At^Wk_`SC8n9@A{zA2drvo4_*1SstUGuG)z{3umb|)1blxTP
zKT4DI*z7k<I}-MnS3Id%dBP*z&Vzy3*E#n$ya~R~xFe#y@Qaq#fps&Jze+87uzJ_|
zw>BLGek~1YZchs&-lhLh_{AHzW~GGMv~p{?wZa^U+x1tbPY=jF#;U==7i;d&&su&e
zO2kS)$6<SEa=KxouY33+8#VJ&8kbu^jX1fFZ!UaZI@zqkt1Xz>)4t_^(8*wFKgq;v
zlP)Q8M86c)bJ-TDQu<rzlH2Dy&kgPs-l}}al#t4A&9LuvevhJ7d(oHevsY*xxnr!<
z^-^Zx*Sif9mA&rG-e2UiweNGt`HgcPvYgj<xs!Tv*Y()D*QLV4uKtu1PdfhU?&W=a
zJ5Fc)ZR1aRuwiv^p#P)hM(;km$$V1F7uiHKbS%=9j^mC><&pij*erEPZ)C%3)ou^z
zI-6Nnj<oE!vvKB;E0=l2m2z0-XsxPYza{h}OzjVo)}r_vhB=d!t$Kv6O38elJ@s(%
znmOiEyE*1Odvoey+dQ#}JByfl8ux?ptR&+p$6eB4x_sCABpI{+O^vJ4GK-w}+S(}T
z|GrB{S90&LddP0*^pfL`LxML;-}1e}dPh9YRA^gucy{dIow2%%aihYawdV}QS-zXS
zIv}2AQvK6cmg`Zn#cn>+W72vq6_s3jXSvvX&=l4?(pP@_Zsd^$1@kMxA`>6GmV}06
zn$9pivLiF^(m~G^=G{^^LNs14y7Y;+I(GL84uL73m#t`J>wKT66gJEKkn5VQ$2jdf
zGM)c?_cXMqS-)F%qE&|C+qC$Q2QLl_>p2|W`j2nH`;d%Dmls*B%=Y^lr|9PL)pynR
zP3C34VyquXJu467y3tpEgZ1gGc!~eX{`QmjC8uz{JH0$-lJ?&IO_ddkON8wzOnwP^
z?4IGGv3!R{uuF;itzEH4W;~n{(($3ETSC5T#!bTs=Bi<LI{kMDXvf%Y+b1wvK>EsB
zPH`o<o6E21bS}wq*O=Djaog~ce$&lWTV@=LtIfK~sKDmuwQHxPnex0%k(Np-CH~pP
z#TU|V*(J`s9XfBm$4_a!Bac3GslHP!TJo&Te^F=1X9jx<F+sDtOYE|f9v_mDpCP;b
ziL{=}p8JijZ5H<x)N&n8aqU@m@Y>xU2QEL|4obTzN-PtKe+TcleDs%%(fKFNZtZ!J
z&vUrurS)%0bj;r{NBADYhO%#KjK6%~;^7w8c9#kHxl1vrs?~9$Yme&P0>w%1WF~Fz
zoLO6w*KtK#(EgRuq=qm(r87rXYh~RO&_DjXCzw0uRRv21Uxit*sAz9sO9%G?N%5ri
zor%7y`uN%Eo<=<M(2j2~c$K(+t?R{ghjPvxn&;sZ5I@h^DB*v$aPo<qnF~7v*QS;_
z#dIBB_;{J+&)&^9Q@QpBW$m__v~0q!;!>8iN2W%YABik~&}|h{u;y{<F0<(35C;BF
z^)iR|#2=n>g=M<na@V%Xf-nCcwmh7wIlpg;!P$a4weCT6cV4@nw?FeD^LE)%i7TtO
zbp4vv{kPw|-h1bif6wB-p1r@P`g1++J(ZxWEs}i&W(HH&i%5NpSX}$aLp?qA*_Pw?
z-}4LqG*;gJ=Z{5Q*>isRr|f!{Zada2YfX^jxgVA1%U$ob(BD&AW=pI0nwbKR?Ds11
zcI^-|VEr*`uF$2Hx`@j=O8@1rO_@G<*1zSpl1Uyeo|QGHUiP^c6`Y-zRkP*3+QFUQ
zTC_GjET8o4_%*|e%d3yeteo!7|6+okOux@LmFw?iq(1$sElCLf=yb(<np|Dk;tLP<
zDaCF0(>MFx&+iju=g04^Ij_gbTetbci}IxhZ;Jj&lU&*my;q{-q2T7;WotXxE>|wR
zSZ4Q~dtY6@#oD!6yWJ+MzkR+Y=)n5QoevzFm$%<YGJ3_6Tx%0`b&Ho)>bf?QIXACN
z2vtnvZ!x_w$xS({t##Ui?<ZBgr506u<=$7P-~0V?b{Xrr7^lr%fr76b>o*uYnlG_5
z<3r5k(udN1Z&zJi&6K-Y@LS>1hp$#VW=PlfWqaxsT_+w|D79{0+D@-ucb+WhRBL~6
zJe%{3)4`Wdmc$44P5N;`TmJl!g6A$=+;Krm_(Z3QZHl_}as#{PhQK42zfVjNIWuiZ
zGfSbF%o#tS&qpegEIw<=tgLO|7gOLla%o26az>S?=@~{lqPn+5K7Ynpk#c@s<ntL!
zX6=#BXDFEl&02M`@!BGR%=+NW{so-{#{@G%cL`4xD17il?GMum?J2Sjuh%ShT<W@&
zXZ^XGTFC`FRM+n+Iw-3szs6{i#qnp)yDE;jL}{0Mx_Hc&6mO9KFCNQ&=jh{o*UlI&
zl}L~2Sg9c3IIDx#@kq;zk2y()_?7OnJd}L>EA{*-`M}*53T8zlo^&Zbwr#}@y+*^>
zuij68%CRcu?>)ECd<Rdww!W+54?8~heL_EVc&u#}YZz_Rc*K>nT&5ze`{v8y#jn*g
zH~gK(ZD1<@vRz<~ltSIvDS<gAcJ42Kq?<o<YT2k_ex)~}#pABn!|Nu3-dB0{^v@LY
zR(ILanAz2F+`qTv|E+JXyfTw#_g)v-xG8p5;PC@o%vGn`I&N^>U7@^x;whDq;1HJV
z1KIK3Ny}qboS(g@%;pY%S|IZskLkXFnOqC(a>b{L6vc%3y2?7JY&Ca}ZEtw(w}*dI
zm(wa8Y1fr9+;18};vYxLteSQ8`hzp_??gl5xoemoFS>fY;jwMR-7AeI+4C30w#(hf
z@Vu(1^zQMxqU#G{Tr?A`qcUfyv+CQFzxO_AZOyiKlKlS1dTIsXR~?$x9smuFABs(%
zsbc=(kCV<Hkwq_Lq-$fclIAL(xg)qZw8*EzdcL00otHj89DSr8l`Iqfp(&WzUh4d2
ziI8&4pKW|MX0$%G`V_~`V8ZfOOyl_PS)m~ZzLxLne05Y*Q<-<#oUHp#IJz%M8x;9i
zsPP_Se-Q53`E5<MwfeTw6(3Ae1+_IzjrCk~L@N#@305~v{<WZU?}Nnt%^h0~J+$+w
zSJ*gpLx+(`*dwkt$9cYq#N{8jF3MLX_tQ)N?<vKqGdw+Ytj_M&-nlrnaEB;XRj|z|
zP)zD{dN9S>kV`O;BR!_0;t^-Iu(y(?@t64PE@g?4*B8YJ2{I%c<5%)a$h=j4XRn#i
zPsNZu51m?Gb(^<|Z4|k+)qe+r!O0cpUdjlXi1~fqR{EgbulGct;Ks>%JF@3?aD*Fn
zJhWJQLFnN$OQp1(f$T?C_N|$wSK83Xe9!cijPSO7`=Ux6Las>bxw!moJ#4vJW9uWO
zTiHpje?&vuy&rv?;42==bVovH`Nr)6;R)6nA3yb7n>t-=(~;#`ljivEbDDNq=x6O0
zM)AF$y8`-}waz}+ZqpHL!|31sVzt!b6%m&Tj+H;z>1nvCb3@Te_e+{}4+LH;ahB1q
znWb<4VA0lZ@*BJh&iVOwwH~j0Zu?VR`)6s?af6qRSCm=A8uSl*I%>U&siCV~y7cIZ
z4F4^+Pp#N;H-)z(^};gSM`C`4ySytdRx$RoeXtX^G5+ip?fL0(qj%kWDY=G!4bz#v
zWFK3-K<VhqnaNrnuU;y1nmk#?#oP46O+xJ-gZ9N~|Fb^%hZWh)m{wfm7jz@?`xNC6
znOhkWtP`FvuG_I$Mc&TzN5I<`2j<*Kb}m-^zC%)yw^>(s(G^acBR&jFeIJvX-_*!8
z%1S9siQReNBSYG2<Btyme>P+t@jRgV;4wqg(V}9;W=3U4i_Sov^Jcn%#s!5<68pOZ
zKbT$m$-DTA*z&NQ5*$ls?M}N8#+`Si#5wkWwp7;)KE_IOUe{jV<YTc+^H@%Fs{j2h
zUbDKI<y!BSmx9x$i~9Ac?~izT{z<qUQvpx#Do=+k2cmWQKNpwpcr&GC_jy~R@cGpY
zuZq|6{Jf*>Z1?@tg!5}99v5pL`*BCxdEcu`9>O1-lwEC}_7q<C_~h#T%tHC^61(lQ
z4DZFs&wXaK=F7{{&+>YoSDIe7`R_aP;g!zy&g)xGiSIkUYc~JiqfeF>RH*M!-QTdW
zgzte?=$<<TKbvmc|Ni33<-3tbK29$GAg=7m-{9Z*dE-^t1IHOfBCh31EMX3_OOKYc
z$XZ!>JmbbY-vgHeSFNsE%yeA!!b<BmK|QC;`{q4;z|mX9VamIoKj(&M@bLv-pIDq~
z)w?)9v4XwbFVN5~vd6oTVUFw}wbaJSqq~?puDe*X-*PF7S}9Py>Br|!#+w!|JXbzz
z-z65;Lz;;R>CfAje+mvs_`cInf$iwbf-DYIp4~H^yl3tcK2$H2CwH!;=rh9xhm;TD
zv37h4U%SMGn0VOCBA14qUGak_kx7pCf$h4}nayi&{ofz%)OlsGbH#j*^hX(oBn~%D
z393J5qrbe3`$9?9mN~mFs4=sjOn<e~b$!vZj^8)K(@K^-OMAM_;*si>dDr!VOh4>9
z_;lZD_vjCiHX>Ixf4t;!U}?g^wU<2?Y~{JvlWEsFzop-;$XcGqsAa;Q=bw*$4&CRc
zw~TqUL+1J52ilEAjQnCBG8o=JTrB9gxxi8<b}s+Hn5NRjPd<b#;ET6h7k`2C!9s<$
z2CY6eyL}uAK2E%wD}<{|8onDIb~ApnU;m}x(uA%FHS_!!(tLCC7SAZk_UvGfD>W4b
z89LiKw|N<Nkl&4m^HuYsY%eg~eyHTL)k=5QLihFEiyHzDdN@goeT!yY9Afa%((RV%
zz9u<d1}&9!>w1p4AK+NEN>94IWX^1@2aFFww$;RRt-hs|u!Vo>;t!G2lGYs1aBf?f
z$(<%?@hbFY**V@Lx>MeN4lS^>G5?!0>Gsb(MZY9ZZolk5Fa2TggUJjVCi_oz$a$|W
z_n`B80%Jeh26?^$OPANV4^4lcdAQc$%i7q2e@%W3-#Q|;OxEgSo5yCLws2=%?v?km
z!qz#>xUiVf#$5Dirk2#tJwhF`qt+eB5VzQ%vGw(ug2x_fS88u$`n{Fu_+*RuEmf=R
zf)m#BE!n>E(FvI?VGfM)@k}YNF3Nj2_OpGsQ!;h=%dEH7MzOs$&sHk=Z@v`e%i7a6
zG1Aj8EMbb{GVR4YM(QuW-E`<*U3E1>YN7pk-*8uT`%gC+*3Vt%_UUa&=(3kt95q&r
zVY0jbPn0Q0cD~$g(9iNR$u8o+eDw>3&uqir9b`J^6jOX^uRy8Dqgje<pV#u*N*yTP
z>@`!Ze`^6FzsRK+3l^&vely&gR=ir>XwNR-S<Jc1*VKSZ@$gNp7M{SnPFz;jYnkRr
zUrUv`raV8KDcgUA^n>%l6E5yF68Z4aHKFI)QrB-6>`U5C>s1Gp#BH>$QT)1TCHDsY
zho=p;TF*K4x$Ex3sTcQH*HovL&lQbbE_ChUrFf6JuKj(}rrrHry2+?v`|_v1llcEN
z9sKt?$ZqcC$Di4Luaso_y>joVg!`A-mhAr-Uj2Fg{{J8U-mZRS{obzj-`m5x`{(cf
z_wna^``U-~t*__rulxUZ{`-GFK3$%_zh>!vyZ`Uo=kKqr{r>lKe|-JVxBc<<e|~&^
zet&=M&p)qs^Vk1tsjsj7{@Fi%-`^j{zsJ}Aefqus{l3~CKQF)E|L4!;_4ai?KOBFq
zfB)X!zit2jE`MJi)VV_W&-Lf)@7Mi$TVMD0!@sljHUIwo-u}I2!O!ghl0Ubvx3B;C
Xv_JoTef9rm{~2xl9<MYoVPOCO_>goo

diff --git a/examples/ros/myumi_cart_pulling.py b/examples/ros/myumi_cart_pulling.py
deleted file mode 100644
index 073bc7b..0000000
--- a/examples/ros/myumi_cart_pulling.py
+++ /dev/null
@@ -1,119 +0,0 @@
-#!/usr/bin/env python3
-
-import rclpy
-from rclpy.executors import MultiThreadedExecutor
-from smc_yumi_node import get_args, SMCMobileYuMiNode
-
-import numpy as np
-import argparse
-from smc.robots.implementations.mobile_yumi import RealMobileYumiRobotManager
-from smc import getMinimalArgParser
-from smc.control.control_loop_manager import ControlLoopManager
-from smc.control.cartesian_space import getClikArgs, getIKSolver
-from smc.control.joint_space.joint_space_point_to_point import moveJP
-from smc.control.cartesian_space.cartesian_space_point_to_point import (
-    controlLoopClik,
-    moveL,
-    moveLDualArm,
-    moveL,
-)
-from smc.control.optimal_control.croco_point_to_point.mpc.base_reference_mpc import (
-    CrocoBaseP2PMPC,
-)
-from smc.control.optimal_control.croco_path_following.mpc.base_reference_mpc import (
-    CrocoBasePathFollowingMPC,
-)
-from smc.util.draw_path import drawPath
-from smc.control.cartesian_space.cartesian_space_trajectory_following import (
-    cartesianPathFollowingWithPlanner,
-)
-
-import pinocchio as pin
-import matplotlib
-from functools import partial
-
-import numpy as np
-
-
-def fixedPathPlanner(
-    path_parameter: list[int], path2D: np.ndarray, p_base: np.ndarray
-) -> np.ndarray:
-    """
-    fixedPathPlanner
-    ----------------
-    we can assume robot is following this path and that it started the following controller at the first point.
-    to make the controller make sense (without a sense of timing), we need to find the closest point on the path,
-    and delete the already traversed portion of the path.
-    the assumption is that the controller constructs a trajectory from the path, starting with the first point.
-
-    the cleanest way to get this done is associate robot's current position with the path parameter s,
-    but i'll just implement it as quickly as possible, not in the most correct or the most efficient manner.
-
-    NOTE: path is (N,3) in shape, last column is 0, because subotimal code structure
-    """
-
-    p_base_3 = np.array([p_base[0], p_base[1], 0.0])
-    distances = np.linalg.norm(p_base_3 - path2D, axis=1)
-    index = np.argmin(distances)
-    if (index - path_parameter[0]) > 0 and (index - path_parameter[0]) < 10:
-        path_parameter[0] += 1
-    path2D = path2D[path_parameter[0] :]
-    return path2D
-
-
-# def main(args=None):
-def main(args=None):
-    # evil and makes args unusable but what can you do
-    args_smc = get_args()
-    assert args_smc.robot == "myumi"
-    robot = RealMobileYumiRobotManager(args_smc)
-    # you can't do terminal input with ros
-    # goal = robot.defineGoalPointCLI()
-    T_w_absgoal = pin.SE3.Identity()
-    T_w_absgoal.translation = np.array([0.5, 0.0, 0.5])
-    T_absgoal_l = pin.SE3.Identity()
-    T_absgoal_l.translation = np.array([0.0, 0.2, 0.0])
-    T_absgoal_r = pin.SE3.Identity()
-    T_absgoal_r.translation = np.array([0.0, -0.2, 0.0])
-    # loop_manager = CrocoIKMPC(args, robot, goal, run=False)
-    # robot._mode = robot.control_mode.upper_body
-    # loop_manager = moveJP(robot._comfy_configuration, args_smc, robot, run=False)
-    # loop_manager = moveLDualArm(
-    #    args_smc, robot, T_w_absgoal, T_absgoal_l, T_absgoal_r, run=False
-    # )
-    # loop_manager = moveL(args_smc, robot, T_w_absgoal, run=False)
-    robot._mode = robot.control_mode.whole_body
-    robot.setInitialPose()
-    robot._step()
-    if not args_smc.draw_new:
-        pixel_path_file_path = "./parameters/path_in_pixels.csv"
-        path2D = np.genfromtxt(pixel_path_file_path, delimiter=",")
-    else:
-        matplotlib.use("tkagg")
-        path2D = drawPath(args_smc)
-        matplotlib.use("qtagg")
-    path2D[:, 0] = path2D[:, 0] * args_smc.map_width
-    path2D[:, 1] = path2D[:, 1] * args_smc.map_height
-    path2D = np.hstack((path2D, np.zeros((len(path2D), 1))))
-    robot.updateViz({"fixed_path": path2D})
-    path_planner = partial(fixedPathPlanner, [0], path2D)
-
-    # x0 = np.concatenate([robot.q, robot.v])
-    # loop_manager = CrocoBasePathFollowingMPC(
-    #    args_smc, robot, x0, path_planner, run=False
-    # )
-    robot._mode = robot.control_mode.base_only
-    loop_manager = cartesianPathFollowingWithPlanner(
-        args_smc, robot, path_planner, 0.0, run=False
-    )
-
-    rclpy.init(args=args)
-
-    executor = MultiThreadedExecutor()
-    node = SMCMobileYuMiNode(args_smc, robot, loop_manager)
-    executor.add_node(node)
-    executor.spin()
-
-
-if __name__ == "__main__":
-    main()
diff --git a/examples/ros/navigation_example.py b/examples/ros/navigation_example.py
index c7439db..60ea6c2 100644
--- a/examples/ros/navigation_example.py
+++ b/examples/ros/navigation_example.py
@@ -3,7 +3,7 @@
 
 import rclpy
 from rclpy.executors import MultiThreadedExecutor
-from smc_yumi_node import get_args, SMCMobileYuMiNode
+from smc.multiprocessing.smc_yumi_node import get_args, SMCMobileYuMiNode
 
 import numpy as np
 import argparse
diff --git a/python/smc/control/cartesian_space/cartesian_space_point_to_point.py b/python/smc/control/cartesian_space/cartesian_space_point_to_point.py
index 6a26983..1a923c9 100644
--- a/python/smc/control/cartesian_space/cartesian_space_point_to_point.py
+++ b/python/smc/control/cartesian_space/cartesian_space_point_to_point.py
@@ -15,6 +15,7 @@ import numpy as np
 from argparse import Namespace
 from collections import deque
 from typing import Callable
+from IPython import embed
 
 from smc.control.cartesian_space.ik_solvers import QPManipMax
 
@@ -38,6 +39,8 @@ def controlLoopClik(
     T_w_e = robot.T_w_e
     SEerror = T_w_e.actInv(T_w_goal)
     err_vector = pin.log6(SEerror).vector
+    if (robot.robot_name == "myumi") and (robot.mode == robot.control_mode.base_only):
+        err_vector[5] = err_vector[5] * 10
     J = robot.getJacobian()
     # compute the joint velocities based on controller you passed
     # qd = ik_solver(J, err_vector, past_qd=past_data['dqs_cmd'][-1])
diff --git a/python/smc/control/cartesian_space/ik_solvers.py b/python/smc/control/cartesian_space/ik_solvers.py
index d4e3880..c07ff73 100644
--- a/python/smc/control/cartesian_space/ik_solvers.py
+++ b/python/smc/control/cartesian_space/ik_solvers.py
@@ -137,8 +137,8 @@ def QPquadprog(
         b = (V_e_e / V_e_e_norm) * max_V_e_e_norm
     A = J
     # TODO: you probably want limits here
-    # lb = None
-    # ub = None
+    lb = None
+    ub = None
     # lb *= 20
     # ub *= 20
     h = None
diff --git a/python/smc/control/controller_templates/point_to_point.py b/python/smc/control/controller_templates/point_to_point.py
index 1cc63d1..b6140ac 100644
--- a/python/smc/control/controller_templates/point_to_point.py
+++ b/python/smc/control/controller_templates/point_to_point.py
@@ -14,6 +14,7 @@ from smc.robots.interfaces.whole_body_dual_arm_interface import (
 from smc.robots.interfaces.whole_body_single_arm_interface import (
     SingleArmWholeBodyInterface,
 )
+
 global control_loop_return
 control_loop_return = tuple[bool, dict[str, np.ndarray], dict[str, np.ndarray]]
 
@@ -103,9 +104,9 @@ def EEP2PCtrlLoopTemplate(
     if err_vector_norm < robot.args.goal_error:
         breakFlag = True
     log_item["qs"] = robot.q
-    log_item["err_norm"] = err_vector_norm.reshape((1,))
     log_item["dqs"] = robot.v
-    log_item["dqs_cmd"] = v_cmd.reshape((robot.nv,))
+    log_item["dqs_cmd"] = v_cmd
+    log_item["err_norm"] = err_vector_norm.reshape((1,))
     return breakFlag, save_past_item, log_item
 
 
diff --git a/examples/ros/smc_yumi_node.py b/python/smc/multiprocessing/smc_yumi_node.py
similarity index 83%
rename from examples/ros/smc_yumi_node.py
rename to python/smc/multiprocessing/smc_yumi_node.py
index dfa1958..b569578 100644
--- a/examples/ros/smc_yumi_node.py
+++ b/python/smc/multiprocessing/smc_yumi_node.py
@@ -1,6 +1,7 @@
 from smc.robots.implementations.mobile_yumi import RealMobileYumiRobotManager
 from smc.control.control_loop_manager import ControlLoopManager
 from smc import getMinimalArgParser
+from smc.robots.abstract_robotmanager import AbstractRobotManager
 
 import rclpy
 from rclpy.time import Time
@@ -13,6 +14,7 @@ from abb_python_utilities.names import get_rosified_name
 from rclpy.callback_groups import ReentrantCallbackGroup
 from smc.control.cartesian_space import getClikArgs
 from smc.control.optimal_control.util import get_OCP_args
+from smc.path_generation.planner import getPlanningArgs
 
 import numpy as np
 import argparse
@@ -24,6 +26,7 @@ def get_args():
     of various kinds. Make sure you know what the goal is before you run!"
     parser = getClikArgs(parser)
     parser = get_OCP_args(parser)
+    parser = getPlanningArgs(parser)
     parser.add_argument(
         "--ros-namespace",
         type=str,
@@ -60,6 +63,25 @@ def get_args():
         help="if in sim you need to set sim time, otherwise not",
         default=True,
     )
+    # TODO: move elsewhere
+    parser.add_argument(
+        "--handlebar-height",
+        type=float,
+        default=0.5,
+        help="heigh of handlebar of the cart to be pulled",
+    )
+    parser.add_argument(
+        "--base-to-handlebar-preferred-distance",
+        type=float,
+        default=0.5,
+        help="prefered path arclength from mobile base position to handlebar",
+    )
+    parser.add_argument(
+        "--planner",
+        action=argparse.BooleanOptionalAction,
+        help="if on, you're in a pre-set map and a planner produce a plan to navigate. if off, you draw the path to be followed",
+        default=True,
+    )
     # parser.add_argument('--ros-args', action='extend', nargs="+")
     # parser.add_argument('-r',  action='extend', nargs="+")
     parser.add_argument("--ros-args", action="append", nargs="*")
@@ -80,7 +102,12 @@ def get_args():
 
 class SMCMobileYuMiNode(Node):
     def __init__(
-        self, args, robot: RealMobileYumiRobotManager, loop_manager: ControlLoopManager
+        self,
+        args,
+        robot: RealMobileYumiRobotManager,
+        modes_and_loops: list[
+            tuple[AbstractRobotManager.control_mode, ControlLoopManager]
+        ],
     ):
         super().__init__("SMCMobileYuMiNode")
         if args.sim:
@@ -93,7 +120,9 @@ class SMCMobileYuMiNode(Node):
             )
             self.wait_for_sim_time()
         self.robot = robot
-        self.loop_manager = loop_manager
+        mode, self.loop_manager = modes_and_loops.pop(0)
+        self.robot.mode = mode
+        self.modes_and_loops = modes_and_loops
         self.args = args
         # give me the latest thing even if there wasn't an update
         # qos_prof = rclpy.qos.QoSProfile(
@@ -165,6 +194,15 @@ class SMCMobileYuMiNode(Node):
         # self.get_logger().info("TIMER_CMD")
         self.current_iteration += 1
         breakFlag = self.loop_manager.run_one_iter(self.loop_manager.current_iteration)
+        if breakFlag:
+            if len(self.modes_and_loops) > 0:
+                mode, self.loop_manager = self.modes_and_loops.pop(0)
+                self.robot.mode = mode
+                self.get_logger().info(
+                    "about to run: " + str(self.loop_manager.controlLoop.func.__name__)
+                )
+            else:
+                self.robot._v_cmd[:] = 0.0
 
         if not self.odom_initialized:
             self.get_logger().info(
@@ -172,7 +210,7 @@ class SMCMobileYuMiNode(Node):
             )
 
         # self.get_logger().info("current iteration: " + str(self.current_iteration))
-        self.get_logger().info(str(self.robot._v_cmd))
+        # self.get_logger().info(str(self.robot._v_cmd))
         if self.args.unreal:
             msg = self.empty_msg
             msg.header.stamp = Time().to_msg()
@@ -196,6 +234,9 @@ class SMCMobileYuMiNode(Node):
             # REAL
             for i in range(3):
                 msg.velocity[i] = self.robot._v_cmd[i]
+                if self.robot._v_cmd[2] < 0.01:
+                    self.robot._v_cmd[2] = 0.0
+                    # self.get_logger().info("this velocity is too small for anything!!")
             for i in range(15, 29):
                 msg.velocity[i] = self.robot._v_cmd[i - 12]
             # self.get_logger().info(str(self.robot._q))
@@ -223,7 +264,7 @@ class SMCMobileYuMiNode(Node):
             self.init_odom[2] = th
             self.odom_initialized = True
             self.get_logger().info(str(self.init_odom))
-        if self.args.unreal and self.odom_initialized:
+        if (self.args.unreal and self.odom_initialized) or self.current_iteration < 50:
             T_odom = np.zeros((3, 3))
             T_odom[0, 0] = np.cos(self.init_odom[2])
             T_odom[0, 1] = -1 * np.sin(self.init_odom[2])
@@ -249,6 +290,9 @@ class SMCMobileYuMiNode(Node):
             self.robot._q[1] = p_ctrl[1]
             self.robot._q[2] = np.cos(self.init_odom[2] - th)
             self.robot._q[3] = np.sin(self.init_odom[2] - th)
+            # self.get_logger().info(str(self.robot._q))
+            # self.get_logger().info(str(th))
+            # self.get_logger().info(str(self.init_odom))
         # self.get_logger().info("CALLBACK_ODOM")
         # self.get_logger().info(str(self.robot._q[:4]))
         # self.get_logger().info(str(self.init_odom))
@@ -257,7 +301,6 @@ class SMCMobileYuMiNode(Node):
         if self.current_iteration < 200 or self.args.unreal:
             self.robot._q[-14:-7] = msg.position[-14:-7]
             self.robot._q[-7:] = msg.position[-7:]
-        # self.get_logger().info("CALLBACK_JOINT_STATE")
 
     def wait_for_sim_time(self):
         """Wait for the /clock topic to start publishing."""
diff --git a/python/smc/path_generation/maps/premade_maps.py b/python/smc/path_generation/maps/premade_maps.py
index 7037857..511984b 100644
--- a/python/smc/path_generation/maps/premade_maps.py
+++ b/python/smc/path_generation/maps/premade_maps.py
@@ -8,11 +8,18 @@ def createSampleStaticMap():
     return obstacles that define the 2D map
     """
     # [lower_left, lower_right, top_right, top_left]
+    # map_as_list = [
+    #    [[2, 2], [8, 2], [8, 3], [2, 3]],
+    #    [[2, 3], [3, 3], [3, 4.25], [2, 4.25]],
+    #    [[2, 5], [8, 5], [8, 6], [2, 6]],
+    #    [[2, 8], [8, 8], [8, 9], [2, 9]],
+    # ]
     map_as_list = [
-        [[2, 2], [8, 2], [8, 3], [2, 3]],
-        [[2, 3], [3, 3], [3, 4.25], [2, 4.25]],
-        [[2, 5], [8, 5], [8, 6], [2, 6]],
-        [[2, 8], [8, 8], [8, 9], [2, 9]],
+        [[0.5, -1.0], [3.5, -1.0], [3.5, -0.5], [0.5, -0.5]],
+        [[3.5, -0.5], [4.0, -0.5], [4.0, 3.5], [3.5, 3.5]],
+        [[-1.0, 1.0], [2.5, 1.0], [2.5, 2.0], [-1.0, 2.0]],
+        [[0.0, 3.5], [4.0, 3.5], [4.0, 4.0], [0.0, 4.0]],
+        # [[-1.5, -1.0], [-1.0, -1.0], [-1.0, 5.0], [-1.5, 5.0]],
     ]
 
     obstacles = []
diff --git a/python/smc/robots/implementations/heron.py b/python/smc/robots/implementations/heron.py
index a409401..2153703 100644
--- a/python/smc/robots/implementations/heron.py
+++ b/python/smc/robots/implementations/heron.py
@@ -6,7 +6,9 @@ from smc.robots.interfaces.force_torque_sensor_interface import (
 from smc.robots.interfaces.mobile_base_interface import (
     get_mobile_base_model,
 )
-from smc.robots.interfaces.whole_body_single_arm_interface import SingleArmWholeBodyInterface
+from smc.robots.interfaces.whole_body_single_arm_interface import (
+    SingleArmWholeBodyInterface,
+)
 from smc.robots.implementations.ur5e import get_model
 from smc.robots.grippers.robotiq.robotiq_gripper import RobotiqGripper
 from smc.robots.grippers.rs485_robotiq.rs485_robotiq import RobotiqHand
@@ -38,6 +40,20 @@ class AbstractHeronRobotManager(
         # TODO: CHANGE THIS TO REAL VALUES
         self._MAX_ACCELERATION = 1.7  # const
         self._MAX_QD = 3.14  # const
+        self._comfy_configuration = np.array(
+            [
+                0.0,
+                0.0,
+                1.0,
+                0.0,
+                1.54027569e00,
+                -1.95702042e00,
+                1.46127540e00,
+                -1.07315435e00,
+                -1.61189968e00,
+                -1.65158907e-03,
+            ]
+        )
         super().__init__(args)
 
 
diff --git a/python/smc/robots/implementations/ur5e.py b/python/smc/robots/implementations/ur5e.py
index 25d3ccf..4cd1070 100644
--- a/python/smc/robots/implementations/ur5e.py
+++ b/python/smc/robots/implementations/ur5e.py
@@ -30,6 +30,16 @@ class AbstractUR5eRobotManager(ForceTorqueOnSingleArmWrist):
         self._ee_frame_id = self.model.getFrameId("tool0")
         self._MAX_ACCELERATION = 1.7  # const
         self._MAX_QD = 3.14  # const
+        self._comfy_configuration = np.array(
+            [
+                1.54027569e00,
+                -1.95702042e00,
+                1.46127540e00,
+                -1.07315435e00,
+                -1.61189968e00,
+                -1.65158907e-03,
+            ]
+        )
         super().__init__(args)
 
 
diff --git a/python/smc/robots/utils.py b/python/smc/robots/utils.py
index 4d53987..488c05f 100644
--- a/python/smc/robots/utils.py
+++ b/python/smc/robots/utils.py
@@ -85,7 +85,7 @@ def getMinimalArgParser():
         type=str,
         help="gripper you're using (no gripper is the default)",
         default="none",
-        choices=["none", "robotiq", "onrobot"],
+        choices=["none", "robotiq", "onrobot", "rs485"],
     )
     # TODO: make controlloop manager run in a while True loop and remove this
     # ==> max-iterations actually needs to be an option. sometimes you want to simulate and exit
-- 
GitLab