diff --git a/README.md b/README.md index 83ad8a62185f13252135de78006fa801a0c98d0c..43e2b1a5250097ac9d1938af14bc7267ea98626c 100644 --- a/README.md +++ b/README.md @@ -14,41 +14,36 @@ git clone -b noetic-devel https://github.com/ROBOTIS-GIT/open_manipulator_simula git clone https://github.com/ROBOTIS-GIT/open_manipulator_dependencies.git ``` +To run MediaPipe's models, the model has to be downloaded from their website. + ## Getting started -In order to run the project run the following commands (*in the future, once the pipeline is complete, the roslaunch files will be all run from one file*): +In order to run the project run the following commands: ``` cd catkin_ws catkin_make source devel/setup.bash roscore -roslaunch open_manipulator_gazebo open_manipulator_gazebo.launch -roslaunch open_manipulator_controller open_manipulator_controller.launch use_platform:=false ``` -It is important to run the two roslaunch commands as the former runs Gazebo simulation with the robotic arm, and the latter allows for control of the arm. -**IMPORTANT**: Before running the following scripts, it is important to press play at the bottom of Gazebo, otherwise the arm will not move. -## Roslaunch -There is two `roslaunch` files to run currently. The first one `keypoint_collection.launch` runs the collection of data points from pose estimation. This data is being used to train the data. It outputs a pickle file. The second one is `training_data.launch` which uses the output of the first launch file, and converts the keypoints into a training dataset. The labels are obtained by calculating the inverse kinematics of the end-effector. This is also used to visualize and test the data in RVIZ and Gazebo. -## Files -At the moment, there are currently three files that can be run - in the future the functionality will be combined. The first one (1) runs the video capture of the keypoints in real time and moving the robotic arm in Gazebo [*It is currently being debugged due to new functionality being added*]. The second one (2) is a keypoint capture program which saves the keypoints into a pickle file. Finally, (3) loads the saved keypoints (hence 2 and 3 have to be run in order for 3 to work) and visualizes them in RVIZ and calculates the manipulator keypoints. Currently, 1 and 3 use different approaches. The accuracy is currently being tested. +## Roslaunch +The following roslaunch files can be run: -1. Arm Keypoint Capture + Pose Estimation Control +1. Arm Keypoint Capture + Control ``` -roslaunch pose_estimation pose_estimation.launch +roslaunch open_manipulator_cv_controller keypoint_collection_control.launch ``` -2. Capture Keypoints +2. Convert and Visualize Keypoints ``` -roscd pose_estimation -python3 capture_keypoints.py +roslaunch open_manipulator_cv_controller training_data.launch ``` -3. Visualize Keypoints +3. Training and Evaluation ``` -rviz -roscd pose_estimation -python3 visualize_keypoints.py +roslaunch open_manipulator_cv_controller train_evaluate.launch ``` +Global variables for each can be viewed with `--ros-args`. + diff --git a/pose_estimation/CMakeLists.txt b/open_manipulator_cv_controller/CMakeLists.txt similarity index 79% rename from pose_estimation/CMakeLists.txt rename to open_manipulator_cv_controller/CMakeLists.txt index 8a75491b941b34c959fac7ba1f0f6213074816ff..b36094501a90ee1624edb9f59ff64b51b44abfe4 100644 --- a/pose_estimation/CMakeLists.txt +++ b/open_manipulator_cv_controller/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.0.2) -project(pose_estimation) +project(open_manipulator_cv_controller) find_package(catkin REQUIRED COMPONENTS roscpp @@ -19,13 +19,14 @@ find_package(catkin REQUIRED COMPONENTS ## Generate messages in the 'msg' folder add_message_files( FILES - # Keypoint.msg - # Keypoints.msg - SphericalCoordinates.msg JointAngle.msg JointPositions.msg + Joints.msg + ManipulatorPoses.msg ) +catkin_python_setup() + ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES @@ -65,11 +66,11 @@ include_directories( ## Mark executable scripts (Python etc.) for installation ## in contrast to setup.py, you can choose the destination catkin_install_python(PROGRAMS - scripts/pose_estimation_control.py scripts/arm_keypoint_capture.py - scripts/data_collection.py scripts/training_data.py + scripts/keypoint_collection_control.py + scripts/training_data.py + scripts/training.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) - -add_executable(inverse_kinematics_solver src/inverse_kinematics_solver.cpp) -target_link_libraries(inverse_kinematics_solver ${catkin_LIBRARIES}) +add_executable(kinematics_solver src/kinematics_solver.cpp) +target_link_libraries(kinematics_solver ${catkin_LIBRARIES}) diff --git a/open_manipulator_cv_controller/data/models/joint_predict_demo.pt b/open_manipulator_cv_controller/data/models/joint_predict_demo.pt new file mode 100644 index 0000000000000000000000000000000000000000..6601b23b78ef8da975437e68825cbf26984ddc1b Binary files /dev/null and b/open_manipulator_cv_controller/data/models/joint_predict_demo.pt differ diff --git a/pose_estimation/include/pose_estimation/kinematics_solver.h b/open_manipulator_cv_controller/include/open_manipulator_cv_controller/kinematics_solver.h similarity index 66% rename from pose_estimation/include/pose_estimation/kinematics_solver.h rename to open_manipulator_cv_controller/include/open_manipulator_cv_controller/kinematics_solver.h index c62bdc490462ebd12ae4e9e2f9372a614cd6a27d..b53c0710fa8d2b0ab1aa7c42708f11b31dec2f63 100644 --- a/pose_estimation/include/pose_estimation/kinematics_solver.h +++ b/open_manipulator_cv_controller/include/open_manipulator_cv_controller/kinematics_solver.h @@ -4,8 +4,9 @@ #include "open_manipulator_libs/open_manipulator.h" #include "open_manipulator_msgs/GetKinematicsPose.h" #include "open_manipulator_msgs/SetKinematicsPose.h" -#include "pose_estimation/JointPositions.h" -#include "pose_estimation/Joints.h" +#include "open_manipulator_cv_controller/JointPositions.h" +#include "open_manipulator_cv_controller/Joints.h" +#include "open_manipulator_cv_controller/ManipulatorPoses.h" #include <robotis_manipulator/robotis_manipulator.h> #include "ros/ros.h" @@ -14,8 +15,8 @@ class KinematicsSolver public: KinematicsSolver(bool using_platform, std::string usb_port, std::string baud_rate, double control_period); - void keypointsInverseCallback(const open_manipulator_msgs::KinematicsPose &msg); - void keypointsForwardCallback(const pose_estimation::Joints &msg); + void keypointsInverseCallback(const open_manipulator_cv_controller::ManipulatorPoses &msg); + void keypointsForwardCallback(const open_manipulator_cv_controller::Joints &msg); ros::NodeHandle getNodeHandle() const { return n_; } @@ -29,5 +30,5 @@ private: robotis_manipulator::Kinematics *kinematics_; void solveIK(Pose target_pose, const open_manipulator_msgs::KinematicsPose& manipulator_pose); - void solveFK(const pose_estimation::Joints &msg); + void solveFK(const open_manipulator_cv_controller::Joints &msg); }; \ No newline at end of file diff --git a/pose_estimation/launch/keypoint_collection.launch b/open_manipulator_cv_controller/launch/keypoint_collection_control.launch similarity index 87% rename from pose_estimation/launch/keypoint_collection.launch rename to open_manipulator_cv_controller/launch/keypoint_collection_control.launch index 4bd9a1c312f3086e82b03834879196a9cdb485ba..5c82400e951542f236a7897601f0cca2fbb4daf5 100644 --- a/pose_estimation/launch/keypoint_collection.launch +++ b/open_manipulator_cv_controller/launch/keypoint_collection_control.launch @@ -6,8 +6,8 @@ <arg name="manipulator_control" doc="Control or Collection?" default="false" /> <arg name="ik_model" doc="Name trained model. Located in `data/models`" default="joint_predict.pt" /> + <!-- Running Gazebo Simulation with Open Manipulator-X if control is on --> <group if="$(eval arg('manipulator_control') == true)"> - <!-- Running Gazebo Simulation with Open Manipulator-X if control is on --> <include file="$(find open_manipulator_gazebo)/launch/open_manipulator_gazebo.launch"> <arg name="paused" value="false"/> </include> @@ -17,7 +17,6 @@ <arg name="control_period" default="0.010"/> <arg name="use_platform" default="false"/> - <!-- Running the Manipulator Controller if control is on --> <node name="open_manipulator_controller" pkg="open_manipulator_controller" type="open_manipulator_controller" output="log" args="$(arg usb_port) $(arg baud_rate)"> <param name="control_period" value="$(arg control_period)"/> @@ -25,7 +24,7 @@ </node> </group> - <node name="keypoint_collection" pkg="pose_estimation" type="data_collection.py" output="screen"> + <node name="keypoint_collection_control" pkg="open_manipulator_cv_controller" type="keypoint_collection_control.py" output="screen"> <param name="gesture_model" value="$(arg gesture_model)"/> <param name="filename" value="$(arg output_file)"/> <param name="video_save" value="$(arg video_save)"/> diff --git a/pose_estimation/launch/train_evaluate.launch b/open_manipulator_cv_controller/launch/train_evaluate.launch similarity index 80% rename from pose_estimation/launch/train_evaluate.launch rename to open_manipulator_cv_controller/launch/train_evaluate.launch index 00ebce37d729809bc53b138f6a05e76e87eb3463..bd775406aaee70091188215c11f780cb17c978fe 100644 --- a/pose_estimation/launch/train_evaluate.launch +++ b/open_manipulator_cv_controller/launch/train_evaluate.launch @@ -3,21 +3,20 @@ <arg name = "plot" doc = "Plot training loss {boolean}" default = "false" /> <arg name = "model" doc = "The name of the model to be saved in data/models/ {string}" default = "joint_predict.pt" /> - <arg name = "dataset" doc = "The name of the dataset saved in data/ {string}" default = "keypoint_dataset.pickle" /> + <arg name = "dataset" doc = "The name of the dataset saved in data/ {string}" default = "training_data.pickle" /> <arg name = "loss" doc = "[huber (default), mse] {string}" default = "huber" /> <arg name = "scheduler" doc = "[None (default)] {string}" default = "None" /> <arg name = "initial_lr" doc = "Initial learning rate for training the model {float}" default = "1e-1" /> <arg name = "epochs" doc = "Number of epochs the model will be trained for {integer}" default = "100" /> - <arg name = "validate" doc = "Run validation with positional loss {boolean}" default = "false" /> - + <arg name = "NAS" doc = "Run Neural Architecture Search {boolean}" default = "false" /> <arg name = "NAS_iter" doc = "Number of variations to run NAS [10] {int}" default = "10"/> <!-- Running Kinematics Solver Node --> - <node name="kinematics_solver" pkg="pose_estimation" type="kinematics_solver" output="screen" /> + <node name="kinematics_solver" pkg="open_manipulator_cv_controller" type="kinematics_solver" output="screen" /> <!-- Running the training loop --> - <node name="training" pkg="pose_estimation" type="training.py" output="screen"> + <node name="training" pkg="open_manipulator_cv_controller" type="training.py" output="screen"> <param name = "model" value = "$(arg model)"/> <param name = "dataset" value = "$(arg dataset)"/> <param name = "loss" value = "$(arg loss)"/> @@ -27,7 +26,6 @@ <param name = "plot" value = "$(arg plot)"/> <param name = "evaluate" value = "$(arg evaluate)"/> <param name = "epochs" value = "$(arg epochs)"/> - <param name = "validate" value = "$(arg validate)"/> <param name = "NAS" value = "$(arg NAS)"/> <param name = "NAS_iter" value = "$(arg NAS_iter)"/> </node> diff --git a/pose_estimation/launch/training_data.launch b/open_manipulator_cv_controller/launch/training_data.launch similarity index 80% rename from pose_estimation/launch/training_data.launch rename to open_manipulator_cv_controller/launch/training_data.launch index 28dac4b2ded3a9790890220d5636e2436eb25298..994ef2c0e820dac0ed0d88e80c0441883a4f3fc5 100644 --- a/pose_estimation/launch/training_data.launch +++ b/open_manipulator_cv_controller/launch/training_data.launch @@ -1,6 +1,6 @@ <launch> <arg name="input_keypoint_file" doc="Name of the input file with keypoints (from data_collection)" default="collected_data.pickle" /> - <arg name="training_file" doc="Name of the file where the training data will be saved" default="keypoint_dataset.pickle" /> + <arg name="training_file" doc="Name of the file where the training data will be saved" default="training_data.pickle" /> <arg name="simulate" doc="Simulate the motion in Gazebo?" default="false"/> <arg name="show_video" doc="Show the input video" default="false" /> @@ -22,12 +22,12 @@ <!-- Running rviz with the TF graph setup --> - <node type="rviz" name="rviz" pkg="rviz" args="-d $(find pose_estimation)/rviz/keypoint_tf_frame.rviz" /> + <node type="rviz" name="rviz" pkg="rviz" args="-d $(find open_manipulator_cv_controller)/rviz/keypoint_tf_frame.rviz" /> <!-- Running Inverse Kinematics Solver Node --> - <node name="kinematics_solver" pkg="pose_estimation" type="kinematics_solver" output="screen" /> + <node name="kinematics_solver" pkg="open_manipulator_cv_controller" type="kinematics_solver" output="screen" /> - <node name="training_data" pkg="pose_estimation" type="training_data.py" output="screen"> + <node name="training_data" pkg="open_manipulator_cv_controller" type="training_data.py" output="screen"> <param name="input_keypoint_file" value="$(arg input_keypoint_file)"/> <param name="training_file" value="$(arg training_file)"/> <param name="simulate" value="$(arg simulate)"/> diff --git a/pose_estimation/msg/JointAngle.msg b/open_manipulator_cv_controller/msg/JointAngle.msg similarity index 100% rename from pose_estimation/msg/JointAngle.msg rename to open_manipulator_cv_controller/msg/JointAngle.msg diff --git a/pose_estimation/msg/JointPositions.msg b/open_manipulator_cv_controller/msg/JointPositions.msg similarity index 100% rename from pose_estimation/msg/JointPositions.msg rename to open_manipulator_cv_controller/msg/JointPositions.msg diff --git a/pose_estimation/msg/Joints.msg b/open_manipulator_cv_controller/msg/Joints.msg similarity index 100% rename from pose_estimation/msg/Joints.msg rename to open_manipulator_cv_controller/msg/Joints.msg diff --git a/open_manipulator_cv_controller/msg/ManipulatorPoses.msg b/open_manipulator_cv_controller/msg/ManipulatorPoses.msg new file mode 100644 index 0000000000000000000000000000000000000000..17bde958e7c5ccbdf339475466f65926b97805da --- /dev/null +++ b/open_manipulator_cv_controller/msg/ManipulatorPoses.msg @@ -0,0 +1,2 @@ +open_manipulator_msgs/KinematicsPose originalManipulatorPose +open_manipulator_msgs/KinematicsPose processedManipulatorPose \ No newline at end of file diff --git a/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-Copy1-checkpoint.ipynb b/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-Copy1-checkpoint.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..f1aae3e81f0c3909eede2fefbf489bc09dd4faa4 --- /dev/null +++ b/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-Copy1-checkpoint.ipynb @@ -0,0 +1,603 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "%matplotlib inline\n", + "\n", + "import os\n", + "import math\n", + "import json\n", + "import torch\n", + "import random\n", + "\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "from matplotlib import cm, colors\n", + "from mpl_toolkits.mplot3d import Axes3D" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "## TODO:\n", + "# FILENAME = \"_test_metrics.json\"\n", + "FILENAME = \"metrics.json\"" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "with open(FILENAME, \"rb\") as handle:\n", + " metrics = json.load(handle)\n", + " metrics = json.loads(metrics)\n", + " MAX_DIST = metrics['max_dist']" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "0.2586145463665413" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "MAX_DIST" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "def workspace_surface():\n", + " \n", + " half_pi = math.pi / 2.\n", + " u, v = np.mgrid[-half_pi:half_pi:100j, 0.0:math.pi:100j]\n", + " \n", + " xline = MAX_DIST * np.cos(u) * np.sin(v)\n", + " yline = MAX_DIST * np.sin(u) * np.sin(v)\n", + " zline = MAX_DIST * np.cos(v)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "def plane():\n", + " u, v = np.mgrid[-0.6:0.6:100j, 0:0.7:100j]\n", + " \n", + " xline = u\n", + " yline = v\n", + " zline = np.zeros_like(u)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "class Visualizer():\n", + " def __init__(self, angle1 = 20, angle2 = 90):\n", + " self.angle1 = angle1\n", + " self.angle2 = angle2\n", + " \n", + " self.title = None\n", + " self.x_axis = \"x-axis\"\n", + " self.y_axis = \"y-axis\"\n", + " self.z_axis = \"z-axis\"\n", + " \n", + " def set_axis(self, title = None, x = 'x-axis', y = 'y-axis', z = 'z-axis'):\n", + " self.title = title\n", + " self.x_axis = x\n", + " self.y_axis = y\n", + " self.z_axis = z\n", + " \n", + " def get_axis(self, dim = 3):\n", + " plt.clf()\n", + " \n", + " if dim == 3:\n", + " ax = plt.axes(projection='3d')\n", + " ax.set_zlabel(self.z_axis)\n", + " ax.view_init(self.angle1, self.angle2)\n", + "\n", + " else:\n", + " fig, ax = plt.subplots()\n", + " \n", + " if self.title is not None:\n", + " ax.set_title(self.title)\n", + " \n", + " ax.set_xlabel(self.x_axis)\n", + " ax.set_ylabel(self.y_axis)\n", + " \n", + " return ax\n", + " \n", + " def plot_test_spread(self, actual, pred):\n", + " ax = self.get_axis()\n", + " \n", + " # Data for three-dimensional scattered points\n", + " ax.scatter3D(actual[:,0], actual[:,1], actual[:,2], color = 'red', label = \"Test Values\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'blue', alpha = 0.5, label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_trajectory(self, traj, pred):\n", + " ax = self.get_axis()\n", + "\n", + " ax.plot3D(traj[:,0], traj[:,1], traj[:,2], color = 'blue', label = \"Actual Trajectory [frame 1]\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'red', label = \"Predicted Values [frame 2]\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_orientation_trajectory(self, traj, pred):\n", + " ax = self.get_axis(2)\n", + "\n", + " ax.plot(traj, color = 'blue', label = \"Actual Trajectory\")\n", + " ax.scatter(range(len(pred)), pred, color = 'red', label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_workspace(self, predictions):\n", + " ax = self.get_axis()\n", + "\n", + " pl = plane()\n", + " sphere = workspace_surface()\n", + " \n", + " ax.plot_surface(pl[0], pl[1], pl[2], rstride = 1, cstride = 1, color = 'w', alpha = 0.1, linewidth = 0)\n", + " ax.plot_surface(sphere[0], sphere[1], sphere[2], rstride = 1, cstride = 1, color = 'c', alpha = 0.2, linewidth = 0)\n", + " ax.plot_wireframe(sphere[0], sphere[1], sphere[2], rstride = 5, cstride = 5, color = 'black', alpha = 0.2, linewidth = 0.5)\n", + " \n", + " within_range = []\n", + " outside_range = []\n", + " for point in predictions:\n", + " dist = np.linalg.norm(np.array(point))\n", + " if dist <= MAX_DIST:\n", + " within_range.append(point)\n", + " else:\n", + " outside_range.append(point)\n", + " \n", + " within_range, outside_range = np.array(within_range), np.array(outside_range)\n", + " \n", + " if outside_range.shape[0] != 0:\n", + " ax.scatter(outside_range[:,0], outside_range[:,1], outside_range[:,2],color=\"red\", s = 20, label = \"Predictions out of Workspace\") \n", + " \n", + " if within_range.shape[0] != 0:\n", + " ax.scatter(within_range[:,0], within_range[:,1], within_range[:,2], color=\"black\", s = 20, label = \"Predictions within Workspace\")\n", + " \n", + " ax.set_xlim([0,0.6])\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + "visualizer = Visualizer()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Test Set" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "test_outputs, test_set = metrics['test_set'][0], metrics['test_set'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_test_spread(np.array(test_set), np.array(test_outputs))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "g3fRbkqaNHup" + }, + "source": [ + "## Position" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "traj_pred, traj_actual = metrics['pos_traj'][0], metrics['pos_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 0\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_trajectory(np.array(traj_actual), np.array(traj_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "zV1tmbQ1NJyk" + }, + "source": [ + "## Orientation" + ] + }, + { + "cell_type": "code", + "execution_count": 934, + "metadata": {}, + "outputs": [], + "source": [ + "or_pred, or_traj = metrics['or_traj'][0], metrics['or_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 935, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<Figure size 640x480 with 0 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(title = \"End-Effector Orientation Predictions\", x = \"Trajectory Samples\", y = \"Orientation [rad]\")\n", + "visualizer.plot_orientation_trajectory(np.sin(or_traj), np.sin(or_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "BTJFV6jTY_kd" + }, + "source": [ + "## Workspace" + ] + }, + { + "cell_type": "code", + "execution_count": 936, + "metadata": {}, + "outputs": [], + "source": [ + "### TODO distance of each point to origin. \n", + "# If smaller than max range then within " + ] + }, + { + "cell_type": "code", + "execution_count": 937, + "metadata": {}, + "outputs": [], + "source": [ + "ws_pred, ws_traj = metrics['workspace'][0], metrics['workspace'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 938, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAaMAAAGFCAYAAABQYJzfAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOz9eZglZ3XniX9iufu+5r7UrlJpl9C+gWVk++dusHHbbbsHGffY/Rh4sBvsBqanGYYej8GAR7aHxt09DbgxBuw2tmkwkoWs0oZYJCSVSrVXZVZV7vfm3fLuS8Tvj4g3MvLWzVpzKaXi+zz5ZGbce+N9I27E+41zzvecI+m6ruPAgQMHDhxsIuTNnoADBw4cOHDgkJEDBw4cONh0OGTkwIEDBw42HQ4ZOXDgwIGDTYdDRg4cOHDgYNPhkJEDBw4cONh0OGTkwIEDBw42HQ4ZOXDgwIGDTYdDRg4cOHDgYNPhkJEDBw4cONh0OGTkwIEDBw42HQ4ZOXDgwIGDTYdDRg4cOHDgYNPhkJEDBw4cONh0qJs9AQdvXGiaRrPZ3OxpOHDgYB3hcrlQFGXdx3HIyMFlodlsMjExgaZpmz0VBw4crDOi0Sj9/f1IkrRuYzhk5OCSoes6s7OzKIrCyMgIsux4ex042IrQdZ1qtcrCwgIAAwMD6zaWQ0YOLhntdptqtcrg4CB+v3+zp+PAgYN1hM/nA2BhYYF0Or1uLjvnkdbBJaPT6QDgdrs3eSYOHDjYCIiHzlartW5jOGTk4LKxnv5jBw4cXD3YiHvdISMHDhw4cLDpcMjIgYN1wK/92q/xzne+0/r/wQcf5Hd+53euaJ9rsY+NxMXM90tf+hLRaPS87+k+l1c7LuaYHJwLh4wcvGnwa7/2a0iShCRJuN1udu7cySc+8Qna7fa6j/2Nb3yD//gf/+NFvXf//v1IkkShULjsfVwN6J7v+Pg4jz766CXv54//+I/50pe+dNnzeOyxx5Akibm5uRXbBwYGGB8fX7FtcnISSZJ48sknL3s8B5cHh4wcvKnwUz/1U8zOznL8+HE+9KEP8fGPf5xPf/rTPd+7lgm98XicUCi06fvYSKzVfCORyBVZGvfeey+qqrJ//35r2+HDh6nVauTzeSYnJ63tTz31FB6Ph3vuueeyxlrPAP9Wh0NGDjYVx44d4zvf+Q7Hjx/fkPE8Hg/9/f2MjY3xW7/1Wzz00EN885vfBJbdQb//+7/P4OAge/bsAeDs2bP84i/+ItFolHg8zjve8Y4VC1in0+GDH/wg0WiURCLBv/t3/w5d11eM2+2yajQafPjDH2ZkZASPx8POnTv5b//tvzE5Oclb3/pWAGKxGJIk8Wu/9ms995HP53n3u99NLBbD7/fz0z/90yvOo3AXPf744+zdu5dgMGiRscD+/fu5/fbbCQQCRKNR7rnnHk6fPt3z3P3CL/wC73//+63/f+d3fgdJkjhy5AhgkHcgEOC73/3uOfN98MEHOX36NP/23/5byzq143xz7OXy/MAHPsC/+3f/jng8Tn9/Px//+Md7zhkgGAzylre8ZQUZ7d+/n3vvvZd77rnnnO133nknXq8XTdP4xCc+wfDwMB6Ph5tuuonHHnvMeq+wor7+9a/zwAMP4PV6+cpXvnLO+JlMhttuu42f+7mfo9FokM/n+dVf/VVSqRQ+n49du3bxxS9+ccU+v/a1r3H33Xfj9Xq57rrrePrpp639dTod/vW//tds27YNn8/Hnj17+OM//uNzxv3CF77Avn378Hg8DAwMrPjuCoUC/+v/+r+SSqUIh8O87W1v49VXX131HG4EHDJysCnI5XL81E/9FHv27OFnfuZn2L17Nz/1Uz9FPp/f0Hn4fL4VFtCTTz7J0aNHeeKJJ/jWt75Fq9Xi4YcfJhQK8eyzz/L8889bC6b43Gc/+1m+9KUv8YUvfIHnnnuOXC7H3/7t35533He/+9189atf5U/+5E84fPgw//k//2eCwSAjIyP8zd/8DQBHjx5ldna250IDxiL94osv8s1vfpMXXngBXdf5mZ/5mRVP59Vqlc985jN8+ctf5plnnuHMmTP87u/+LmDki73zne/kgQce4MCBA7zwwgv85m/+5qrKqQceeGDFwv3000+TTCatbT/60Y9otVrcfffd53z2G9/4BsPDw3ziE59gdnZ2Bdmcb46r4c///M8JBAL84Ac/4A//8A/5xCc+wRNPPLHq+9/61rfy1FNPWf8/9dRTPPjggzzwwAMrtu/fv996GPjjP/5jPvvZz/KZz3yGAwcO8PDDD/PP//k/P+fB6SMf+Qi//du/zeHDh3n44YdXvHb27Fnuu+8+rrvuOv7H//gfeDwe/sN/+A8cOnSI73znOxw+fJjPf/7zJJPJFZ/7vd/7PT70oQ/x8ssvc9ddd/HP/tk/Y3FxETDKcA0PD/PXf/3XHDp0iI997GP8b//b/8Zf/dVfWZ///Oc/z/ve9z5+8zd/k9dee41vfvOb7Ny503r9X/yLf8HCwgLf+c53eOmll7jlllv4iZ/4CXK53HnP+7pCd+DgElGr1fRDhw7ptVrtsvfx8MMP64qi6ID1oyiK/vDDD6/hTFfikUce0d/xjnfouq7rmqbpTzzxhO7xePTf/d3ftV7v6+vTG42G9Zkvf/nL+p49e3RN06xtjUZD9/l8+uOPP67ruq4PDAzof/iHf2i93mq19OHhYWssXdf1Bx54QP/t3/5tXdd1/ejRozqgP/HEEz3n+dRTT+mAns/nV2y37+PYsWM6oD///PPW69lsVvf5fPpf/dVf6bqu61/84hd1QD9x4oT1ns997nN6X1+fruu6vri4qAP6/v37L3TqdF3X9QMHDuiSJOkLCwt6LpfT3W63/h//43/Uf+mXfknXdV3/v/6v/0u/++67e85X13V9bGxM/3/+n/9nxT4vNEddX/m9if3ee++9K/bzlre8Rf/whz+86tyfeOIJHdBnZmZ0Xdf1dDqt//CHP9S/973v6WNjY7qu6/rJkyd1QH/66ad1Xdf1wcFB/fd///fPGee9732vruu6PjExoQP6o48+es4xRSIR/ciRI/rIyIj+gQ98YMX188/+2T/T3/Oe9/Scp9jnJz/5SWubuJ4+9alPrXp873vf+/R3vetd1v+Dg4P6v//3/77ne5999lk9HA7r9Xp9xfYdO3bo//k//+een1mLe/5CcCowONhwHDt2jMcff/yc7Z1Oh8cff5zjx4+za9eudRn7W9/6FsFgkFarhaZp/Mqv/MoKF8/111+/Ipn31Vdf5cSJE+fEPur1OidPnqRYLDI7O8sdd9xhvaaqKrfddts5rjqBV155BUVReOCBBy77OA4fPoyqqivGTSQS7Nmzh8OHD1vb/H4/O3bssP4fGBiwSrvE43F+7dd+jYcffpif/Mmf5KGHHuIXf/EXVy35ct111xGPx3n66adxu93cfPPN/OzP/iyf+9znAMNSevDBBy/5WM43x9Vwww03rPj/Qp+5++67cbvd7N+/nxtvvJFarcYtt9yCpmlkMhkmJibYv38/Pp+PO++8k1KpxMzMzDmxo3vuueccd9Ztt912zni1Wo377ruPX/mVXzlHtPFbv/VbvOtd7+LHP/4xb3/723nnO995jjV51113WX+L68n+vX7uc5/jC1/4AmfOnKFWq9FsNrnpppsAo1LCzMwMP/ETP9HzXLz66quUy2USicQ5cz558mTvE7gBcMjIwYbjQhf8iRMn1o2M3vrWt/L5z38et9vN4OAgqrryFggEAiv+L5fL3HrrrT1jAalU6rLmIMqrbARcLteK/yVJWkGSX/ziF/nABz7AY489xte//nX+9//9f+eJJ57gzjvvPGdfkiRx//33s3//fjweDw8++CA33HADjUaDgwcP8r3vfe+C7rXLmePFfuZ8RXv9fj+33347Tz31FLlcjnvvvRdFUVAUhbvvvpunnnqKp556invuuQe32029Xr/o+XdfM2DEJh966CG+9a1v8Xu/93sMDQ1Zr/30T/80p0+f5h/+4R944okn+Imf+Ane97738ZnPfOaixvva177G7/7u7/LZz36Wu+66i1AoxKc//Wl+8IMfABe+vsrlMgMDAytcrgKbKUl3YkYONhz2p+BesPu21xqBQICdO3cyOjp6DhH1wi233MLx48dJp9Ps3LlzxU8kEiESiTAwMGAtBGDEYl566aVV93n99dejadqKoLQdwjITZZd6Ye/evbTb7RXjLi4ucvToUa699toLHpcdN998Mx/96Ef53ve+x3XXXcdf/uVfrvpeETfav38/Dz74ILIsc//99/PpT3+aRqNxXhWa2+0+7zGtN9761reumLuAINinn37aiheFw2EGBwd5/vnnV+zj+eefv6jzK8syX/7yl7n11lt561vfyszMzIrXU6kUjzzyCH/xF3/Bo48+yn/5L/9lxevf//73rb/F9bR3715rDnfffTfvfe97ufnmm9m5c+eKB7xQKMT4+Piq8vRbbrmFubk5VFU955rujl1tJBwycrDh2L17Nw8//PA5BRcVReHhhx9eN6vocvCrv/qrJJNJ3vGOd/Dss89a7pwPfOADTE1NAfDbv/3bfPKTn+Tv/u7vOHLkCO9973vPyRGyY3x8nEceeYRf//Vf5+/+7u+sfYoA9NjYGJIk8a1vfYtMJkO5XD5nH7t27eId73gHv/Ebv8Fzzz3Hq6++yr/6V/+KoaEh3vGOd1zUsU1MTPDRj36UF154gdOnT/OP//iPHD9+3Fr0euHBBx/k0KFDvP7669x7773Wtq985SvcdtttPa0E+3E/88wzTE9Pk81mL2qOa4m3vvWtHD9+nMcff3yFi/SBBx7g7/7u7zh79qxFRmCICD71qU/x9a9/naNHj/KRj3yEV155hd/+7d++qPEUReErX/kKN954I29729usPKePfexj/P3f/z0nTpzg9ddf51vf+tY55/xzn/scf/u3f8uRI0d43/veRz6f59d//dcB47t/8cUXefzxxzl27Bj/4T/8B370ox+t+PzHP/5xPvvZz/Inf/InHD9+nB//+Mf86Z/+KQAPPfQQd911F+985zv5x3/8RyYnJ/ne977Hv//3/54XX3zx0k/sGsEhIwebgq9+9as89NBDK7Y99NBDfPWrX92kGfWG3+/nmWeeYXR0lJ//+Z9n7969/Ot//a+p1+uEw2EAPvShD/G//C//C4888ojlNvm5n/u58+7385//PL/wC7/Ae9/7Xq655hp+4zd+g0qlAsDQ0BD/5//5f/KRj3yEvr6+FZJcO774xS9y66238rM/+7Pcdddd6LrOP/zDP5zjwjrfsR05coR3vetd7N69m9/8zd/kfe97H//m3/ybVT9z/fXXE41GuemmmwgGg4BBRp1O54Lxok984hNMTk6yY8eOy3ZxXgnuuusuPB4Puq5z6623WtvvuOMOWq2WJQEX+MAHPsAHP/hBPvShD3H99dfz2GOP8c1vfvOSHpZUVeWrX/0q+/bt421vexsLCwu43W4++tGPcsMNN3D//fejKApf+9rXVnzuk5/8JJ/85Ce58cYbee655/jmN79pWS3/5t/8G37+53+eX/qlX+KOO+5gcXGR9773vSs+/8gjj/Doo4/yn/7Tf2Lfvn387M/+rKUClCSJf/iHf+D+++/nPe95D7t37+Zf/st/yenTp+nr67vk87pWkPQLOWcdOOhCvV5nYmKCbdu24fV6r2hfx48f58SJE+zcufOqsogcONgMTE5Osm3bNl5++WVLkHA1YC3v+dXgCBgcbCp27drlkJADBw4cN50DBw4cONh8OJaRAwcOHFwlGB8fv6CsfavCsYwcOHDgwMGmwyEjBw4cOHCw6XDIyMFl483qTnDg4M2G81W3WCs4MSMHlwyXy4UkSWQyGVKp1KpVnh04cPDGhq7rNJtNMpkMsiyvqNu41nDyjBxcFsrlMlNTU4515MDBmwB+v5+BgQGHjBxcneh0Ok5nSwcOtjgURUFV1XX3gDhk5MCBAwcONh2OgMGBAwcOHGw6HDJy4MCBAwebDoeMHDhw4MDBpsMhIwcOHDhwsOlwyMiBAwcOHGw6HDJy4MCBAwebDoeMHDhw4MDBpsMhIwcOHDhwsOlwyMiBAwcOHGw6HDJy4MCBAwebDoeMHDhw4MDBpsMhIwcONhC6rtNut9E0zal47sCBDU4/IwcO1hmaptFut2m327RaLXRdx+12I8syiqIgyzKyLDt9oRy8qeGQkQMHawxd1+l0OhYBtdttDh8+zMDAANFoFEmSkCTJspJ0XUeSpHOIySEnB28mOGTkwMEVQtd1NE2zCKjValluOEmSkGWZSqUCGL1hxDb75+0EJojIbjk5xORgq8MhIwcOLgPCqhE/nU4HTdMALBK5WAKxW0EijiT23+l0VuzTsZocbFU4ZOTAwUVAWD92Auq2ftaiG6b4fDc5Ccur22oS/zvk5OCNDoeMHDhYBYIAWq3WCisFsGI8696K2UZO3VZTu93mzJkzjIyM4PF4LJJyiMnBGxEOGTlwYELEbewEJOI59oV+sxb7bqup0+lw9OhR+vv7rRiUmKcjhHDwRoNDRg7etBBEY5dd211vG2X9XC7EvATx2I/HTlyOfNzBGwEOGTl4U0FYP8LyWVhYoNVqkU6n3/DWxGpCiFarZW135OMOrlY4ZORgS8MuuxYEJFRvAEtLSzSbTYaGhjZxlmuPXkIIRz7u4GqGQ0YOthx65fysJru25/tsZTjycQdXOxwycvCGRy/hgSCfi5Fdv1FrxIl5XyppXIp83HHpOdgoOGTk4A2JC8mu1yLn582C88nHu0USjhDCwXrBISMHbwj0qvdmtwwu9+ndWVRX4nxWk1Aair/9fr9jNTlYMzhk5OCqxMXUe1urJ/SNctOt9TgbMe9e5LSwsMDExAR33HHHCgm8YzU5uBI4ZOTgqoE95yefz+NyuVAUBVgOroNjzWwm7OWHhPjDkY87WAs4ZORg03C+em+HDx9mbGyMdDq9rovZVlgoN/oYuoUTlyIf34z5OnhjwCEjBxuKbtdbp9OxFrdexT83YuF6o6rpNgvCVdoNRz7u4ErgkJGDdcXFyK57LUrOInV140LfjyMfd3CpcMjIwZqju812d723i5Fd22XG64k38uJ3uXlGazXupWA1l54jH3cg4JCRgyvGesmu36gqtzcD1qJv0/nk472IySGnrQ2HjBxcMjZCdu0sPFcvVosZXS6cOnoOwCEjBxeJi2mzDWtLIo6b7urEen8v5xNCnDhxgkQiQTQadYQQWwwOGTnoiV6y65MnTxKNRonFYmvWZns1bFTMCN64pLeZ7sWNWvy7rab5+XkCgYDThn0LwiEjBxZWk12Lm3tpaYlgMIiqrv9l4ywmF4/LPVeNRoNsNst0JkMmnyebzVKuVEim00iahqwoBFSVVCxGOBxm9+7dwNq76S4F9njSheTj9nilg6sfDhm9iXGpbbY30lrZymo6e3xtozE3N8fz3/seR7JZvKrKElBpNgFQFQUZOHHsGAv5PJmFBSanpjgzNQVzc7z/gx/k5+6/n3g4vOHzFrCftwvV0ROvOUKINwYcMnqT4UKy6/O12d5IMoKtpabTNM2wQqanyefzKIpCMpkklUqRTCZxu93rNnaxWGT/c8/x9KFD1NptoqkUaZ+PxVoNDQhIEi6g0ulQbrXQ2m08qspQfz+jw8MkYzFGUiki8TiHMxlKhw8TVlXGxsdJxOMburifj8QvRj7u1NG7euGQ0RaHvc22cMGJm/RSnxY32jJ6I0PTNIrFItlslsXFRarVKrIs09/fz65duwDIZDJMTk7y2muvEYlESKVSpFIpQqHQRR3/+fKMNE3j9ddf569eeIFjCwtEAgG2JxKEo1E6nQ61SgV3p0MoHKZeLKIEAkQ0jYCmIYfD+Pr78fr9BINBvD4fituNLEkMDgwwoSgUcjmeP3GCEHDrNdcQiUTW9Pyd75gv9to4nxBC7Mepo3f1wCGjLYbV2myvhex6K1pGa7n4NBoNFhcXWVxcJJfLoSgKiUSC7du3MzExwfbt20kmk0iShMvlIhqNsmvXLur1Otlslkwmw6lTp1BV1SKmRCJxSTG6RqPBP/7TP/H1H/2IxXabiM/HjUNDpOJxVJ+PTrWKFAggqSqNahVvIEAoHkdrNlHcbhRZxut2o7pcyLKMx+0mGA5TLJVQFYV6vU4xn6fVapHP56l6PLx45gz9Xi97tm1b93ji5bo3Hfn41Q+HjLYALkZ2vRY31la1jC73mHRdZ2lpybJ+yuUyoVCIRCLB2NjYCgtncnJy1f14vV6Gh4cZHh5G0zTy+TwLCwscPXqUWq1GPB63yCkQCPTcR7FY5K+//W0eO3qUiq6zbXCQUY+HHQMDuBTFECTIMgQCaLKMJxol6PeztLREs15HcblQ2m1UlwtN1+mUy0SjUWamp4k1GlTKZeLxOI1mk9HRUc5MTXHDDTdQLJVoNBoUVZUXXn+dG8bH19VKWqtYm1NH7+qDQ0ZvQNhl18L91m39rIfseisKGC4VrVaLXC5nWUC6rhOPxxkeHiaRSFxx7EeWZRKJBIlEgr1791KpVMhkMmQyGY4ePYrP51tBTIVCgc9+8Yu8tLBAU1UZGB4mFo8T1jSGIhHcfj8apgoNkCUJCaPNg+7zEY3HkQCXqtJut/H5/TSqVaKRCKVajaHhYRrNJqlEgnAkwtT0NJIkEQqFyC0ukkqnKRYKFAsF+vr6eOn0aXbE44wND6/B2T4X6yH8uJQ6eo58fP3gkNEbBL3abM/Pz7OwsMANN9ywZtbP+fBmdNPpuk6lUrHIp1gs4vf7SSQSXHfddUQiEas1wnogEAgQCAQYHx+n3W6Ty+VYWFjg2Wef5X9+//ucWFpiYNcuBvr7kSSJeDKJp1pl5/CwMS9dRxP1AE3XlMvlotVs4gsEqFUqRGMxlsplYtEorVYLr9+P1+cjVyjg8/molMsEg0FkSQJdB0kiEgpRbzRot1qEolE6uk42myWZSnF2aYml48e5dseONT83G6FC7KUe1XWd6elpcrkc1157rSMfXwc4ZHSV4nyya7tUVdd1q/rBemOrWkbd43Q6HfL5vEVAzWaTWCxGX18fe/fuxefzbci8uqGqKj6fj2d/9COeW1jAPz5OLJcj7HIxXyxSXlri+kaD7Tt3orhceFwuWq0Wfo+HWq1GwO+n3m6DJBGNxSgWiwwMDjI/P08sGkVRVYqlEiPDw2QzGUsp12y18Ho86IDL5aJaq6ED8USCTDbLQH8/8WiU+UyGmelpXKrKzNIS5WqVt1x33ZpenxstibcTU7vdpl6vI0mSIx9fBzhkdJXALkO9WNm1LMvWDbER2KoxI4BarWaRTz6fx+12k0wm2bNnj1V6ZjOhaRqPffe7/NUrr+AJBtmxZw+LuRwet5tUfz99ikJhcpJEKMT09DTNkyfp6+/H5/MRDodJJJPkczniiQSNWo1yuczgwABz8/NEo1ECfj+nz55leGgITdOoVCrEk0kA9E4HWZLQAY/HQ7FYBElCVRQK+Ty6abXrQKlUYmBggD27d1Or1fjxkSPcvGfPmgkbroaE2+54k7hvgRX3qiMfvzQ4ZLSJuJDw4EJPWRvtNttKbjohvV5YWKBYLPL973+fSCRCMplk586d+P3+q2YRmZyc5HOPPcZcp8PQyAjNVotcNks8kaDVbpNKJumUStz3kz/JmclJfB4Pbo+HzMICHU1jemYGRVHYsWMH2bk5AsEgQ4ODTE9PEwoGCQaDzM3NkYjHUVSVUrFIMBhEwiCiVrtNqVKh1WxSLBQ4e/q0QXKhENFIhFanw/DwMBKg6TpTU1OEw2G8Xi814KXDh7l17941IaTNJCNN084ZezUhhNOG/dLhkNEG4mJk15ciPLCXRNkIbIZ7ZC3RbDZZXFwkm81a0mufz4fX6+W2227bkDJHl4Jms8lffec7fOvYMQI+H+l43HC/qSrj27YhyTLzCwvIrRY7+vpo1evccP31zM7N0Ww2GRkZYX5ujlQyiUtVOfjaa7TbbUvtFo/HcblcTE1PU8jlkIDS0hJT09P0p9OUKxUkSaJYKBAOhfB4PAwMDpJZXCQaiTDQ3w+SxJkzZ4zr0BRHpNNpZufmGB0exufx0ABePXqUm/fuveIY0tVgGa0GRz5+Zbi67r4tiItts305EL7rjcIbzTLqll4vLS0ZLiub9Hpubo7Z2dmrjogmJib4L9/5DsdKJVLRKKPj46iyzFKlwti2bVSWllAlCUXXiUoS8UQCSddZmJujL5VCVRRm5+a4/oYbcLndnDlzhrvvvhuv18vU1BQLCwuUKxVePXCAVqPBzl278Hq9uD0etE6HoeFh0HXarRYuVSWVTFqEg5CJA7qmEQmFKBaLxKJRkCS8Hg9en4/FXI54PI7H66Xa6XDw+HGu3737ihbgzSajSxnbkY9fGq6uO3AL4HLbbF8OtrKb7nLHEoozQUAXkl5fbTd/q9XiK3//9zw7N0dH0xgdGGD3NdeQz+fpaBp9fX3UKxUSiQTzs7OopRLX791LNpej024zNDJCtVolu7jI4OAgsqIwPT1NOpUiGAxSrVbx+/3cd999AExPTxu5Rs0mrx86RK1epz+dJhgMEg6HabZaqKpKR1jvQkQDlrIuHIkwNTVFNBpF0nUkWSaVSHD27FmCoRBulwu/309xaYlTp0+zY3z8ss/PZrvpLteyuxT5+JvVpeeQ0RpA5Pw0Gg3L8rELD9ar1cJmuOk2yhK72POl67qx+JrkcznS66sln2l2dpZPfuMbVDWNVDKJqqpE4nE0c34er5eg30+92eTUiRMojQbbR0aYnpkhEg4TMUUK1XqdwaEhZGBqaopEPI4vEKDZapHJZBg0RQriwWnPNdcYEvBOh0OHDuFxuzl+/DgdU7gQTyQImm66DoAk0W61AAxSMitK1Gs1vD4faBqartOXTrMwN8fg4CC1Wo1avc6LZ88SCgRIp1KXfH7OV/5oI7CWRLiafPzN3IbdIaPLgN0PbG+zffDgQespfCOearaym+58Y60mvU6n05sqvb5caJrGt//xH/mbw4cZHhkhqqqGVdJo4HK7WZifJxgM4lFVTp85g6yqxGIxBiSJg6++Sl86jdvjYX5hAcAim6mpKZKJBF6/H3Sd+bk5+vr6UBUFHZifmzPKEwFIEp1Oh2QqxUB/v1G/rl7n1MmTLOZyZObn8fr9xGIx0HVanQ6asJAkiWg0SqFQwOf1ogP1RoNquUw+l6NSqZBIJgmHw6RSKV6fmiIYCOD3+y/pPG02GfUSMKwFzmc1vZnasDtkdBGwCw/O12ZbyH/XMwnSjq3spoOVFksv6XUikbhi6fVm39DlcpnP/cVfcKzZZPc116DIMu1Oh3A4DLLM955/nnQqRSqRoFyrMTA0RNDvZ/H0adRQiFQ6jcvlYmZ6Gr/PRzQaBV1ndnqaaCyG1+dD1zTyi4uEgkE8brdBJs0mnXbbIg90nUKxSCgcRgejl1EgQDKdJplIAFAoFMjn8yyVSlTKZVRVJRqNEgyFaDebzM7O0m420QGvz4fP72fvtdcyMzNDIh435OG6TiiZ5NUTJ7jjuusu6V7ZbDK6kIBhrbCaEKJer/PSSy9x++23oyjKlpOPO2S0Ci6m3husvDE2erHeDDfdRo5Xr9c5ceKEVfV6vaTXm+Wmm56e5tFvfIOaqrLvhhto1Gq02m2SiQTzc3MsLS1x3XXXIUuSoU4bGSEUCHD29Gl2RyL09/czOzPD7PQ0wVCISCSCDszNzhIMBgkFAiBJ1Go1Gs3mct4QkF1cJJVKWYIECWjW6yQTCWSWXVKddhvVFNnE43ECgQC5fJ5iPk8hl+PM5CTNdptoJILH60X1eEinUkaujSTR0XXC4TA5M8dJ0nVcikIzEODYxATX7Nhx0efrzUJG3RBWkK7rlEol677favJxh4xM2Ou9iZ9LlV1v5STUjRhPSK8XFxfJZDJIkkQ6nWbbtm3E4/F1Ubxt5E1rP3evHjjAf9m/H1ckwr5du8guLlKuVEin04YKLZEgFArh9nrptNvsvfZayuUyr732GoFWi+DAAOWlJeYXFrj+hhuIhMNouk4+l0NRVUu+rbXbZDMZhoaHDXEBxnnWdX1ZzCFJtFotdAwBRdUU3rRaLRYWFqwyQrIs4/J48LjdhMJhbr/jDiRJotFoWMVdX/rRj0ilUsQTCaLRKJFIhEg4bAgczPidDvj9fmYyGdL5PPFY7JLO32a66Vwu16aMLcYXa5HAxcjHYfM9ABeDNzUZrbXsejPI6I1MfkJ6LXJ/lpaWCIVCVpsFRVG45ppr1my8qwXPfP/7fPWll4jG42zbto3jp07hdrnYsWMH5UqFkdFRcouLhvtMkkgkk2iaRqPRoD+V4pahIWRJ4tixY6BpLJVKlAoFlioVatWqkeczMwNAJpslGAySMeNJaBozc3NEo1GmzpwxcoMkiXyhgEtVyefzuFwuVJfLqEAejzM8MoKOIeOWZJmlUolmo4FkXgsut5t0Xx/9/f1EIhFCwSClUonTExM0Gw1C0Shut5vp6WlGR0aMZFpdJxKP8/rp09wdDl+Um3WzyWgzlXzQW813KfJxu5r3asSbiozOV+9tLWTXW81SWY/x7NLrXC5Hp9MhkUicI70+efKkVWJlvbGRNfD+5/79PHHoEOFIhHAsxvz8PH3pNPFolGqtxkB/P/lSiUKxyLaxMdxeL+12m8VMhmg8jqtSIej3c3ZmhuGRESrVqlFZu16HTIZrdu82rHyT6KPRKOm+PuP6BlrtNm1NY2hoyJqXIIfB/n4k82la5BQpimJZVB37udJ1NDBeEzEOXcfn8+H2ehmLxxnfto1qtWrFmg6//jpz8/MkEwni8TjhSARXKMTxycmLctdtNhmtl4DhYnEhMryQEEK8drUKIbY8GV1Jm+1LxUZbRlbi4QY9sV0OGQnptbB+7NLrffv2nVd6fTVU7V4raJrG3z75JKdaLSrtNqPpND6fDz0QwOV209Y00qkUjWaT6clJ9lx7LW5VpW3KsROJBOVSietSKaZnZ4mY+TuKJKF3OszNzzM8NLRMJLpOuVRiZHTUqLataSBJLJqxIsk2LySzrYTpBhXXsCZq0om4kiQZ1pAgBYz4k2SeR03XCYdCFEslQn4/uq7j9XoZHBxkcHCQoaEhMpkMaBrHjh2j3ekQj0Zp1uvEQyHS6fR5z+Fmk9FmxYwELjXPaTUhxNXahn3LkdFqsmtY+6TTbsiyvGFP87B8kWmatiGFPC+WjDqdDoVCwcr9uRzp9UZbfeuJdrvNN3/8YxY1jXAsxuDAAKlUilq9Tr1WIxQKEQmHqdVqnJqcZNv27bhVlXqjwdmzZwn4/RSKRdRKhZrPh8/nIxQKUTerZ0/PzNCXThuSbfOcLSwsEI3F0IGOpiFLEq12m1a7jcfjsQgFSaJSreLz+SwLSbSKaHU6VhsK3fw+dEwCMv+XZNkgNk1DB9weD81Gw+ihBMvJsUA0EmGpVKKvv594MsmiaEpYrfKXf/d3vGXfPqtXUzQaPecevRrI6Gpz010KzufSuxrk41uGjF544QWmpqZ4+9vfjqZpHDx4kHQ6TX9//4Yx/mbEcGDj3EznI4jVpNe7d+8mFotdMllulrBgrdFqtfj8X/0Vx0olto+M0DcwgKZpNDWNfC7H6NgYHq+Xcq1GLpu1hAhT09OUSiUGh4YsogpoGoopp8Z0xZVKJQKBAB6zQ6uk69RN2XYoGASWz2XBFAtonY6VWyRLEpVKhVAoZFVZEBZPu902RCMmQQlCQjd7IrXbuF0uMLeLhVJRFFpmGSEkiXanQ71ep1Ius7S0RGlpicGBAUZGR9m2fTuyabEFdN2o9P3jHwOQTCZJpVIkk0ncbvcbngyupvFXs5p6CSFUVd2Q494yZPTcc8/x7LPP8pM/+ZNGF0ubEGGjsJluuo2AnYxE1WtBQEJ6nUgk1kx6/UZ30zUaDT7753/OoqIw3NeHx+MhlU6jtVq88vLL3Hbnnfi8XsqVCpmFBSrVKvF43LB0ZZk9u3cjm2RQymToi8WMGnGm26xaqdBqtYyacCZ0SSKzsECfWcRUM+M9uq5Tq9dJpVKGEEGSLCun2WjgM+XYgCVMaLfbKKpqvM+0ioSbTpFlOu02mK49kaskSRJut5uZ2Vm8Ho8hPwZ8Xi+hcJhkKsX01BSRaNQiRHSdaDzOUibD3TfcgCRJFItFMpkMExMTvPbaa0QiEYOE2TwLZbNjRutJhuezmjaqfcqWISOfz0ej0bBOnKIoG0oMsHlVtDdqzI75hHvw4EFyuRySJJFIJNi2bRuxWGxNZa9vdDddtVrlj/78z6lEo4wND3P40CGuGRxEBk6dPs31N95IdmGBarVKu92mr78ffzBIIhYjm82SSqeNGI6mUa3VUGo1BvftAwxC6AC5XM6oiMCye61YKOD1evGYJKGahFQoFgkGAhZhiM/Y66LpmoZuCh10DFm4y+wQK8kyms1Np5iWkavTod5oUKvVaNbrBmHJMtWlJQbSaVwejzGesLp0Hb/fT9ksWiv2qQBKIMCZ6Wm2jY4Si8WIxWLs3r2ber1OJpNhdnYWXdd5+umnSSaTpNPpdZP898IbLWZ0ubAT7kbeg1uGjNxuN/V63fp/o60U2Dw33XqNaZdeLy4uUiqVUBSFdDrN6OgooVBo3Z4U38huumq1yp/+xV+wFAyya8cOpqemGB4aQpJlps6exW/WiQODLMLxOMV8nv6BAbKLiySTSVymdd/WNGZnZrhn584VgoHZmRkSiQSLuZylfOtoGsVSieHhYSNmY3uSLy8tMTA4aL0XQJYkqrUaQbNckCANzVx0250OLo8HJKPba6PRoNlosLiwQLPdhk7HmKvHY1RrSCQsS0czY1NivqK+ng5EolHm5uaIhMMrxA8+v58zmQzDAwMrHmy8Xi8jIyNEo1G+//3vc91115HJZDhy5Ai1Wo14PE4qlSKdTl9yiaFLwWa7CTdj/I2MG20ZMvJ6vTQaDev/zSCjzbCM1tqCENJrQUCdTod4PM7Q0BD9/f3Mz8+zffv2NRvvfHgjuuna7Tb/7X/8D7JuN9dcey2TExNcu3cvh48e5ezZswBs37YNyUygHhkeptnpoLXbTJ89iz8YJJfP4/V4cLndFPJ5ksGgkcRqno98sYjH48Hn9yOzLM1ezOWIhsOWFFs8HNUbDVSXy6pJp5uvI+JF4bCVZ9doNmm3WrTabWZnZohEIhRcLhRFweV24/F4CEUiuD0eIuEw6XTacAWasSbzpOLxeqnV63i9XouIZAw3oktRUCSJerNpxYIwj8MdCnF6epqdPSp7C8skmUySTCbZu3cvlUqFTCZDJpPh6NGj+Hw+i5hisdiaWhJbKWa0FhBVIFqtFoFA4Ir3t2XIyOfzveksIzHmlSzavaTXPp+PZDJ5jvR6YWFhQ+NTbzTous7Xv/MdjpfL3HzHHZyZmmL72BiL+Twz09OMj48zODxMp9WiVioxPDICus5SLocuy4xv22ZUXOh0aDQazMzMIEsSrnqdqakpa7HPZrMMDQ2Rz+VYKpcpFItouk52YYHh4WGWKhVj4TKtpdnZWcLhMPPz82idDh1besPMzAwDAwMG2agqqsuF2+MhGAzSabVI9/dbbjDdLBukqiouVaXd6Syr8mwuPFmS8Pv9VKtVfF4vsGwdCUIJRyKUCgWDzFi+dzxeL1OZDGNDQ+e4fXtZBoFAgEAgwPj4uJGPZVbvOHDgAO12e4UIwmvO5Uq+360aM7pY2AlIuHjXCluGjDweD81m0/p/syyjNwIBCum1IKCLlV5vZBxnI8daq3Gef/VV9p86xZ133MHC/DxuVSVfKNDudBgZHqa8tMSZiQkW83li8TjlapVwMEgmk2HX9u24fT70TgdFktDabWKxGG5VZbfZW0jXdU6fPs34tm2oqoqm66iKgixJZDIZw8Jpt1FMObaGQQKyLBOPxZBkGUWWUVTVIipd1xkeHl6RLyQsJ93cv2ScJKsihI6Rk9RptxFnzr4oSRgPh8VicVn4YLrvhNTb7/eTW1ykI1yJ5kIvSxKuQICzMzNsHxs753s63+Knqip9fX309fVZLuZMJsPU1BSvv/46oVDIko5HIpFLXki3soDhQuPaq9RAb8HDlWLLkJEQMNirKWx1Nx1c/KJdr9ct8hElX5LJ5CVLrzfy+N5IbrrDJ0/yrZdeYueuXcwtLrJULJLu6yO7sIDqdlOuVAgFg7jcbu6+6y4URaFUKnHs5Elq1SqTZ88SDoeJhsO4PR4KxSL+QIDS/DyB/n7DgjJl3NFwGN10i3nNvCOvx8Pw4OAK60TXNArFIulUCr/fb7V8EIt/tV7H4/UigyUkECQkzrxQyZkny0qQFRW47a+J/WssP5hJXfsU8SFZkgxvhtnsTxCnhiE+OnL2LGPDwyuuy0uxTCRJIhwOEw6H2bFjB81mk2w2SyaT4aWXXgKwiCmZTF6U+ObNImCAZQuo2WyetxPtWlqLW4aMvF7vOW66jUxAhc1x061GgOeTXu/YsYNAIHDJF9FGW0ZvFMzNzfHV738fTzTKiYkJ/D4fbpeLqbNnDaFHOGw0rfN42LZ9O6osI6kqXq+XkN/P9tFRJqemWMxmkSSJfD7P8MgI/apKPBAwrBjTmh2x1YkTpJPNZonH4xaZAJabrlwuMzAwYEm8NZNAhHjB7/OhgSU8wFS82UUOYl/CYtLMsWFZUCH2Kdkk4C5Vpd5s4vV4jIW8630hs5q31+ejUq1SLZdpmvlJit/P7Pw8w4OD1nm+koXP7XZblSDEvZHJZDh16hQHDhwgGo1a5BQMBnuOczW46dZzfFGrs7tOp8vlWraYzeuhO09pLbBlyMjj8VwVAobNjBnZq17bpdfj4+PE4/Erll47brpzP5fJZPjjv/kbpms10HUi0SiJeBy/309/fz9ur5dMNku73SYSiRhP+rqO1moxt7DAkaNH+c53vkO1WkWVZSKJBG998EHi0SiZTIZqqYTaaKBpGkPmwmxXUbbMKiMB0/Kxv95stZAlyXLbwbJFo+s6jVqNRCxmkY/d0hHvEdezlV9m/IOMUavO7toT8nKxaPm8Xpr1Ol6PxxpD1LOrNRpUKxWmpqbotFp4/X7CZhsKYSGdnp9naGBghTtoLRY/WZZXSMdrtZplNZ08eRKXy2URk106vtkxm/WwzOzl0uyl0mDlPWj/3atq+Fpgy5DRm1FNJy6E6elpjh8/TqlUMiotJxLrIr3e6Nyfq9FNp2ka+XyebDbL/Pw833zpJeY1jeHBQXbt3s3ZqSncHg+pVAq3243W6bA4P08sFjPK8GgaLV3n0IEDPLV/PxOTkwSDQQaHhvB4vczPzfGDH/yAX/2VXyHg8zHq8XDg1Vc5fPgwXq+X0dFR9uzZQzKRQMJozhePxZYtD/PJVZFllpaWCJrXgN31BliqOkEQ4rOW0s48N6I0kFVlgZVuPE3XUYT7zq6q03W8Ph/5fJ5gKESj0aBeq1GpVNB1o31FIBhk27ZteNxuK+dILHMK0FQUCoXCilyq9bAMfD4fIyMjjIyM0Ol0rEK+R44coV6vW9LxrRIzEgQkYuz2+8xuAV2IgNa6ZNCWIqM3g5quW3rdbDap1WoMDg5y/fXXGwveOmGruukudEzC4hSVxlVVJZVKcTafRw8GuXZggFRfnxG4N3Nr2q0WmtfL2bNnicfjlIpFGvU6mUaD4ydO8KOXXuLEqVMgGc3vThw/TjKZZHR4mLn5eU5PTpLy+3nmhRd48aWXrNbhc7OzLC0tGW0dNI1mo0Gj0cDj9RpFf8GK31QrFaMFub4s9Ra/W62WIX5YPgnGL/N1EagWAgOp6xwpkoQky+hmoVUrn0jTaHc6NOp1KrUaU2fO0Gm1cLvdeP1++gcGUGXZiA3JMh6Ph4WFBcKhkJVHJdyPwXCYU9PT3LrOZLTiuBTFsoquueYaKpUK2WyWhYUFms0mr7zyCv39/aRSqTWXjl8IV0JGdhFCtzUjzqvdIrKK5doI2P6+brfdWmBLkZHo4SFqKW0FN51der24uEihUMDn81lVr48ePcr4+DgJszX0emIrWkaroVqtWq6bUqlEMBgkmUwyPj5OMBjkwOuv8+O5OaJ9fURjMUKBAKdOnSISi5FIJCgVi5yZmKBYLhPfvp3TU1O4zJI4ZycnKRUKuFUVt5m7U65WyefzDA4MgK5TqdWoz83xyoEDDA8PG9YPsJjNcnpigrvvvptSsUitWmXi1ClarRbhSIR4IrFsKcmy4TZbPqGGFSRJVGo1PF7vCuGBiPeIhFlVlhHyAQno6GbBVPNvVVGsB8BarWZ4Jkwryuf3EwwE6O/vZ2BoCMWs4GDVxDPHUBQFXdPomC4+ANl0FyqKQtFMtvWYcaeNfEiRJIlgMEgwGGR8fJwnnniC8fFxyuXyukjHL4RLJSO7C86uguu2hHqVAZJl2ZJu2y2hXlaTYxl1QciR6/W6FYB8o7rpekmvRYD1mmuuWSG93kjS3YoxI/uNWCwWyWazZLNZ6vU6sViM/v5+rrvuuhUWZy6X4yv799O3cyeqLBOLRCjk8yBJJGMxJMDj9ZIvFtE1jez8PB63G5/XS7VcJpPNGoVJWy1KS0vIimJUEKlUyC4u4nK5CAaDnDpwABkMN5VpnSSTSY6fOMGZs2eJR6MEQiFuuuUWGvU6ucVF5ufnOWX2gkqn09SqVTzm9SIsI13XjaZ3oZAlKLAvMjLQaLeRFMUqjipyn1qmldhsNFBlmWA4TCQcxuf3k4jHwaziLVR4bo+HVrOJ6vGsqLYg2awpr89HrVolGAgYrwnikiQ8gQDTc3NsHxvbdAEBYD2Q2KXjZ8+e5eDBg4TD4SuSjl8IF9NptjsGZCew7ljQ+X7DMil1W0KCnNa6OsOWISPxVNJoNAgGg5tSm+5KCFBIr4X44GKl11uRIMRY6412u00+n6fZbPLcc88BxmKzY8cOYrFYz5pnmqbxX7/xDQZ276ZYLnPNnj3omsbU9DTX7N1Lu9OhsLhotHCIRhkbG0MGnty/n1d//GOCkQhL5TISkEilqNRqVKtVPF4v7U6HpXKZt7zlLaQTCY7X6/hM9xxg/ZaAytISo8PDFPJ5FEnC7/PhGx5meHiYRqPBoUOH0DodXnn1VdwuF7F4nGQiQSAYRJZlKxYilHmapqGZFRg67TaFYpFyuUyr0bCqe7u9XqMCQzDIQH8/Lrcbl8tFOBSySgjZY05IEh6Ph1qttlwayGYBiespGAySz+etUj66GfPSdaMf0mwux7bR0U0no+6FvZd0fGFhgdOnTyNJ0iVLxy9m/F7Hb3fBCRGCfZ6W+MSc/4Xca+L93UTU/ZoQuDiWURcEGQm3wdUuYNA0jVKpZFk/dun19u3bL1p6vZGiia3gpqvX65b1k8/n8ZiFPG+44QbC4fAFz/l39u+nEY9TLZXYMTaGIsucnJykr6+PYqFgPY0KUtB1ne888QTPPP00mm60XqjXarQ1jWuiUeLRKMVCgVq1iupy8ZZbb+W+e++lVioxNDTEwYMHjRpxZjuGglkKKBwKEbBJkO0uMEmWSaVS9PX10Wy1KBYKZLJZzpw5Q7vVIhgKUa1U6LTbqOZDji5JeFQVxeUyxAWBAH6/36gSjinxNhcx1ZT6ulTViBnZyFKIIsSC5/F6KeTzVr6Rfa5iv263m1azaYklNGzycUmiZYoxNpOM7NZAL/SSji8sLHDy5MmLlo5fCHYy7HbB9bJiutFNRN1V/3sJGeyEY7eYulV3a4EtQ0aKoqCqqqWo20w33WoX7XpIrzfyON+IVpiu65TLZYuAyuUykUjEsjpbrRYHDx40ar9dAEtLS/zT668ztGcPGuD1+1nM562YUjgcptNuU2000HSdQCjEsaNH+f7zzyPLMulUCpeqkltcZGFxkdmZGVSPh0gsRr/Hw30PPMC+fftot9sszM+zd+9eMgsLvP7aa4blZEq19157LS5VZX52lmw2a9W8E9dcsVhEVVUjb0mWcblcjAwPMzY6alyDuRxLpRLT09OEIxES8TjRWMzoPGteu21NQxbqOZMkJLBaSEiAJMu0Go3lnCObGk7Mxe1y0Wm3VxCQgGjcJ2HkstTNWnaC3AQ5+QIBzszNEb/MRXwtIK7Fi31AFNLxPXv2UKvVrPp53dLxRCJx0QnnnU4HTdOoVqvnVEKwz6vb5SbIpBeBdL/WTTii0d5q58Fx060Cu6Jus9R0sNx51b4QLi4uGlLbYJBEIsHIyMhFPYlfzJhbyXW2FmPZ5ddZM8dHnPNEIrGC9EXJmovB1/7pn0iMj5PL5bj++utZLBQ4MzlJ38AAqWQSTdfJ5XIMDAwwMztLNBzm8JEjNFot4pGIZbkEQiHC9bpR/+/66/EHAuzYto1QKESlUqHdahFQVa6//nrGx8c5fPgwp0+fxu3xsHvXLkLBIKl0mmajQbFYZGh42LJcwFjwB/r7V/b1kiSrBpzP57OqMhQKBRZzOU5PTuLz+YjGYiTicbR2G8XtNsQMtrgSLC9IiqKgi/pk5uKlS8uJr7L9Kd0ULYg7UteNRoDC2goEAlQqFbxu9wpFoAS02m1Oz88THh/fdDK6HDWbz+djdHSU0dFRSzqeyWQ4fPgwjUbDko6nzO/EDrsF1Gg08Jq1C4FzCEj8tntL7K45+z67CchuCQl0b+8moLVed7YMGUmmf1qQ0Wb1MwLIZDLk8/kVVa8HBwdJJBJrLr123HQGWq2WRT5Cfp1MJrnmmmvWRIL72vHjzLXblGs1RkdGmJ2fp1ou0z8wQDqdBlkmMz9PPJEwqlGbMZJ8Po/icoGZ7CrrOnQ6KKpKLJHg7jvvpFKrGW27NY10MslcJsPI8DCSrhMOBhkaGqJaqVDI58ksLNBptRgZGqLZaCw/zeo6CobKDV233G/2hzJh1YhFzef14unrY6C/33DnFYss5nK8fugQ5XKZdF8fw4ODhCMR5C4ZuGTGkdqaZlV1wLY4yqZYQsK4F9utFrLLtUxsXe/zBwLMzswQi8fRNY3y0pJBzO02Xq8X1e9naWlp08noSse3S8d1Xbeqjs/Pz3PkyBH8fj+JRIJYLGYITFi2dDqdjiHf70EGlvjEth7YY0f2fXTfC9376d4GK11862UdbRkygpVVGDbKfWWXXmezWQAmJiZIJpNce+21RKPRdc1FeCO6ztZqrAvJry/mJrmY97RaLb794ovEBgeZN4UBbkUh2N9vNHSUZcpLS3g9HjwuF4uFAn4z1WBocJDJiQk6rRa4XLR1nWa7Ta1Woy+dpqNpJBMJ6xppt9u0ajXig4N0dJ1jR4/y3e9+l3Klgtfj4cevvEI6lSIajeL1+5mfn+fY0aMEgkEG+/spm7XeRFKr3TUmfjebTaslhTh6IZgRFt4pUy4+MTFBwyykG4vFlssOSUZlB63TWU6YZbm+nG4jKLfbTaNex+1yLSfRmhB16pqNBrlcznhN1/EHg6SSSRQzPtVqtZg5c4aY2Up9oyHWkrW8l+3S8bGxsRXuvDNnzlgPsolEgmQy2ZMMurd1y797kYp9ey+3nf2z3eo6+9zFNoeMesBehWE93XR26fXi4iKNRsMKUBYKBW655ZZ1TT61YzNiRhsRSO61/0uRX68lHvvBD/DG48xMT5My80laZg2vcCBgqOAqFfr7+tCAVqNBNBwms7DAnXfeycTkJBMTE9RqNTRNo9ZqsWPbNu67/35Cfr9VNQFJolgqEfD78ZvX8vdeeIG2+X5dkvCaRVSffOopPC4Xhw4f5uzp0yguF+NjY+zatYuhoSGDZGTZUK+JckCmq048YQvZNvrK6gxgtGaIx+O4XS6qtZoR5zJl45Isk81mcXs8aKarzXLjmWQjm+Pruo7H66VpxtEEGo0GlUqFRr1Op9PB4/USjUSIxeMETDK1VHeAS1Up1eubTkZred13y7ABq1eTkI7ncjlmZmY4cuSIFRf3+/1EIpEVFlD3vKzvuIt0epGQECkIdMe+7ce+nmvAliEjSZJ6xozW6qStJr3etWvXCun1iRMnNrzb61aMGYFx44iKEyLuBljFXleTX1/OOKuhUCjw8tmztCWJSCjEyPg4Rw4fZueuXRTzedyxGJlMhlQ8DpJEu9UypNflslUV4eGHHuK7//RPZHM5FFnmxu3b+f/99E/j9/vpmEVIwQxQt1r4zL5Cc7OzLGazDA4NGaqyVguP10va7eaVl1+mL50mkUgwNj5OvdHg2PHj1Ot1xsbHl2M4YOUWWU/SPY7fih1gWFCaplntI0S5nKHhYdrtNgcOHKDRaHDw4EEKhQLNZpN4LGbEQM3PC4KVJQmXy8Wi6TWoVSpokoRbVfH5/UT6+qzKEZVqlXqtZihJbfMXllRTklZUWdlIrJWbrrsUT/f+7WOEw2FCoRDj4+M0Gg1eeuklms0mBw4csMRP4kdV1RXfcbe7zk4+q1k6vbb3ikHZz8FaPvRvGTKClW66bl/ppcIuvV5cXKRSqRAOhy8ovd5oFd9Gx4xg/cuyNBoNFhcXqdfrPPvss1azv+uvv37NkwkvtK+/f/55au02ff39BPx+yktLjI2OsjA3h6qqVCsVXC4XqssFus6JEyf4/ve/z9TZs8RiMXbu2kV2YYHp2VncqkooHObOO+4w6gZiKNIkDHfV0tIS/mAQuVYzSFaSVny/9WqVQDDI/Pw8lUqFVDptLM6mKCESiTAzM0O9Xsfv9a50iUkSiiTRaLWs+I/lxpOkFZUYNEDrdFbEgIRLz+1y4VJVhoaGiEajHDlyhE6nw/ETJwy3UixGIBjE7/PRNFsQSEAxnycejxMbGjIsNhsximRYv99P3myjvkL9pRuJsF6vl8VCYc2++0tBt9rsUtDpdKw8oF777PVbvC4We4/Hg6IojI6OEovFLKvp9OnTHDp0iFAoZFlVouuqnUC799t9TN3iBTvsIojzxY6uFFuOjOyWEVxaCY1ms2k9hdul12NjYxctvd6M1uMb6aaDtVfR9JJf+/1+ZFnmLW95yzkKo43C5NQUr549y/D4OIqq4vF6KS4tkU6laJo1viZOnWKb2Yb90KFDfOlLX6Jer+Nyu8ktLnLg4EG8Ph/xaNSKxXzjG9/gPb/+68SiUSsnp6PrNOp1opEIjWoVGehPp0mmUszNzDAyOmp9z5lMhoDfTzgcpl6rGefQzG8CaDWbaKJPEcuWUUfXqdXrRgFX8xitxd7mqhMWkmJzkwErrCxZlpFkGb/fTzyRIBwMUigUyOfznD17Fq3TIZFK0W+WS9KBYDC4ohWF2Leo5I19/8ZElsfVdVxuN4vV6tp9wZeASy3Fcz4CEjif/LrbRWZPZlVVlWg0SjQaZdu2bdTrdate5cTEhOW1icfjxOPxFWKu81k13cTUTcCrWU4OGfVAt5sOOO9CbV8E10p6vdGW0Wa46dZivAvJr5eWljh69OiGEFGv49E0ja9997skBgaIxmLUajUKxSKpRAJJNxqPeT0exsbHKVcqTJ4+zd994xuGVDeZxGN2edWqVdrNJrVqlWqthtbpcPz4cR77h3/gl3/5l42CoUClUjGqLUgSqvmdut1u7r/vPv7xH/+Rw4cPI8syi4uLjI2NoZuJlSJGgySxmM0yvm0bQTOuYh2XubjrQLvZxGe2aRBEhPhb04w4j5lwKqp5a7pOp92m3mjQajRYzGZRVZVKpULJrKodiUZJptNGl1qg2WiQNV3ak5OTljIumUjgN3s0rYgxSRK6JOHyeGjU68s5T8tfEug6HVm2atVtJC5m0e10OlY/oF7X1PksoW6Lo9fr9lpx9rn4/X68Xi+Dg4Pouk6hUCCbzXLixAkrnp1Op4nH49Z5vVDsyC757hY3dHudHDddD/Ry03WfKFECRhDQWkuvNzq/abPcdJeDS5FfbxTJrrbAvHTgAEVgJBIxXE2Kgs/lQlFVms0mqixTrlRwu1yoqkoiHmepUjGeQtttmpJEw6wq0Gw0KLTbVvmcWqPBD3/4Q66/7jquveEGNF2nUi7Tl06jt9u4bfLdbWNj/OIv/AI/+MEPcHs8JGIxduzcyfETJ3j2mWcoFIvEolGWSiUkSeLGG24wSumARTQihqPrOvVGg6ApGbbcL2ah0mazaeWzCGWoODuqquLyePD6fESiUQYHB4madfgi0ajVhE+SZWRNw+vxMDQ4yNDQEK1WixMnT7K0tMT83JzRBj0eJ55IEAmHQZLomON4vV5qtRper3el8ELXjQriLheFYpG+dHodrobVsVrZG7sF1Evl1t2I7nyWEKxc4Lvvbcsi7XKX28lJnNtEImElyC6a5amOHTtmFVmOx+PEYrGe97S91I/9tV5KPDGntcCWIiO7mk4wuvhCBPnYq16vh/R6M9x0VzMZiXOfzWYpFouXJb/eaLTbbb77yiuE4nEisRjZbBYJiKfT6EChWGR+ft7IB0kkUBWFYrGIpuuobjdeUz3WbDbRTDdNB3Cb+1dlGV2SeO7559m3bx8Ns8WCLMs0Wi0CLteKRnmhcJh911/P0NCQleNz/Q03oGsaz33ve0jA0PAwAwMDbNu27ZxqB612G63dptVuUzAfAjrtNu1Ox7CGJEOmragqLlXFZfYXGhwcXK62LRYeM44FrKzAbQtwW+48DPeaqigM9vUhKwrBYJBiqUQul+PUyZM0Wy2i0ahBTrEYAZ+PhaUly0XX7cILBALMLi5uOBnZF11BQHYVnJ1wRC5Pt8VjJ6BuUYBAr5iMfQ5CKNXtRutlpciyTCAQIBgMMjIygqZplgDr0KFDaJpGLBYjmUySSCRwu90riLC7vFA3CdnntRbYkmTUarUolUoAvPzyy7TMCz6ZTLJnz551df1shptOZGRvxFhw/otP11fKr2u1GvF4nL6+Pq699tqLLrO/kSTbPc6R48cpaBrj4TCdVotWs0k8kUCSJEqlErPT0/QNDNDf12epxiKRCMl4nJmZGZZkmUI+T6vdXk4GFU+aplggFokYtctOnaLVbhMIBMgtLlIuldgVieDSl3sQLZVKhpw6k1mxoAVDIXbv2sV1115LoVRCVVWmp6dXquUkCVVRDGWcoqAoCoFAwMj5UZRV3UPFYtH425yDPVHVEj6Y561tFjYFVsSC7NeLapb7QZKIRiJEIhG2b9tGtVoll88zPz/PxMmT+INBms0m4WiUoN+PxHJdPN20vMqboKgTpXjK5bJ1THYCslsyQlLdS4zQi2hETKd7e/d30m1l9XLZdVsv9rElSSKdTpNOp60QRS6XY3p6mqNHjxIIBKycppCtKWMvabd9nXNiRl2YmppienqaY8eO8ad/+qd86UtfQpIkQ5I6NHTR9Z+uFBvtptvIRVuge7zV5Nfbt29f0bb5UrBRFlP3OLqu8+zrr+P2eonF4ywuLqIqCoosMz87SyAUwu3xkE4mjQXZJJh6vc59993Hd77zHWampw2LQxCR+dOoVgmGwwyNjOAye275AwEKuRx+v9/ILxkcZExViUWjdMygdbVaJd3XZ1VVEFaHrCjEYzH6TYVaMpkkn8tRqVbxe70k02ncppUlHlpqtRo+n2/ZrdZl9UhmzMeKJYGVSyRyf4TbT8R6MBdiTTxBm/Ozx6NcbrdBqqwkLJ/fz0ggwNDQEJ12m8VcjqNHjnDglVeM3KNYjHgsRigcptlqsbS0BO32ch27dYTdAiqXy5aIQBzTaqIDu8XT7aIT23tVz+7e3uv9q1VY6EV8YrvY1r1dSMdHR0dptVrkcjlyuRyvvPIKslls99prr+2ZRNtNrmuBNzwZffWrX+VTn/oUBw8eJJlMcsstt/DpT3+a2267jRdeeIFwOLxhRAQb76bb6JiRuOhFXEFUv/Z6vWsqv94MkgUMa6VUYthMHM3lcgSDQarVKn39/WSzWSPmoijWoivpOqVSiUg4bFhDgKQoyKpqWK2dDsgysqoyODyMYlpOt956K7KiMDI+TjAQAN3ozupxu5FNK6ajabhUFb/PZwkOhLXiqtVQFAVZkqiWy3zv6FHOTk0ZCY+yzODgIHfccQfhcBhdN0QIblW12oIjSVbiq2RaH7KIzYhFzHyvJOI3GM3vJPPzkiTR0TQU/dzEWWEd6bqOS1Vpt9vGWGIRM/ctFjZFVUmn08iyjM/no9FoMDs7y8njx2k0Gvj9fkKRCPFUilKptC5k1CsGhHkcvVxu4jXxv327eDBdbbv9tzgHq20XlbnFeN3v7xY7dG8X4/YSLkiSUUqtv7+fgYEBq+p4rVZbcR/3Ip61vE/f8GQ0ODjIhz/8YR5++GE+/vGP02w2uf3224Gt23p8M8YTZj3AgQMHrJYXIvF3PVyfm+Gm+/Hp08iSkfNSLJUo5POMjo7iM7ui5nI5xsbHDdWYpiEBtUYDWZI4cuQItaUlZFVFlWWLUFpmgqOmaeQWFwkGg+y7/np++md+hlKxSMh0R1kdVhXFsliq5TIBm/pMEJJ9IW+325w4eZLZuTmGhoaslgxTU1O4XC7uu/9+JKDeaKC63VapICTJsuzEPiXJlHXLsiGv1o3ip7BMvJqw+DCss46mLVf3NiHeI5rlYV+89eXq3sYGyapv1+50aDabZDIZQqEQ6XSa7du30+l0OHXqFI1Gg9cPHSJ76hR33nZbz+Kilwq7BWSPjUBvlRmcG9uxK88udvtq+1nNpafr+qrJrRf6fPfvbjdetygiGo0SDAatYz+f+2+tcMVk9LnPfY5Pf/rTzM3NceONN/Knf/qnFhl047/+1//Kf//v/52DBw8CcOutt/J//9//96rvvxg88MAD1t9er9cw401sVk+jreKm6yW/1nWdvr4+hoaG1qRh2GrYDDdduVzm4MwM6b4+FhcXyRcK7Nm715JcV82meG7RAtv8fLlYxBsIUCgUUF0uPBg5a8gymnnOkCTSySTbd+wgl8+zmMnwxHe/y769ey2lG5KEZJKDIIylcplkMgksWymCFJAkK5aUyWTw+/3MzMwY3V29XoKBADOzsxQLBeKxGJ1mE4/PtzKHx+ZaA4MQ22bCq6jyjUkUwpoSi6tsvq5rmqGGs7n2rPMLxjHZzrUOlutQCIxE23JFlnF7PITDYaOskTk/RZYJh0LIkQjpvj7mJiZYWFjgyJEjBINBKxZysekYog+QuKZ7udTscmpRiV+8vpoazm4J9fJarFY7rtd2u2ut2yrq5aK7lO3dQgf7/AR6Ha99v93brxRXREZf//rX+eAHP8if/dmfcccdd/Doo4/y8MMPc/ToUaOScRf279/PL//yL3P33Xfj9Xr51Kc+xdvf/nZef/11Qyl0hRCmvcBmkdEb2U3XarWsoq+Li4vnyK+fe+65NetceSFstJvu9YkJStUqA+EwdcmIA4WDQas0TalYJBSJGDevpll16GQM11UikUDHkEHXKhU6rRayqoJu1GcLhsOcPX0aTZapVCrMz80xPTVFKp0mFg5bZKMIFROgtdt43IYOT1hHgkxE/KVSLlOpVDhz+jTNVstQy3U6qKpKLBYzOoDquqHUM8cRZNp9hnXdEArIpvuP7vfZXVJiToJszNdl05rSNc1oKWFbvJrNJk0z76rZaiFJRvWIcDiMx+OxWl1MT00tx5fMeWi6jiIZZb/i6TS33HQTmqZZHVZ/9KMfWVWx02apJLuLvlsFt5olIdYMuyoOlhfqXjEf+37s51L8FgRu324c2rkxJfG//f32Bnr2tJVud5t9fuJ3t9WzWgJv9/bVCMsO+7hXiisioz/6oz/iN37jN3jPe94DwJ/92Z/x7W9/my984Qt85CMfOef9X/nKV1b8///9f/8ff/M3f8OTTz7Ju9/97iuZCrAyzwgcN93FYjX59djY2Dny642K5WxkzEi4uo7Oz1M3W2TLqko6mSS7uEgyHqfZ6aADPrcbzKdl2XRdBiIRqpUK9XqdYi5nWR10OmiyjNfj4Zrduzlx6tRy7ob5u9Zs8uwzz/C2t74Vr2i7DVatNrfHs8JFJF4T0m9N11FUlXK5TL5QYNzW82dqagrJdDmCYQ2IenOwUvEmxtU0zbAGzL8tsYS8XDxT05dlxYotliSsNmH5yLJMo16nUa9TqVZZmJ+nXq8TiUQM8rHFfCz3o2T0Q7II0NynEEcIywxFoVqtEgqFGBgYsGId+XyehYUFDh8+TNOsNp5IJIhGo7jMFhbiO7er3y4kIuh0OrjMCuK9XGL2a6nXdvvr3dt1/dxqB93bxed6WUZi3qsRqz12ZY8p9XIZivd3N+/rPm/itavCMmo2m7z00kt89KMftbbJssxDDz3ECy+8cFH7qFartFot4vH45U5jBex5RmI+W90yupxFW9d7y6/T6fQF5dcbSUYbATHO/MICr589SzKdxh8OM3nqFAPDw3jcbjLZLLV6nVA4jMuMHekY7qxmq4Vaq/Haa6/xzLPPItkqJSNJYCZV15tNqtUq4VAIt8uFDtRqNWrlMhMTE0yMj4Ms49Z1Rrxe3MmkES8ya9hZQgLxJCwOQDfEJMFgEL/XSy6Xw+vx0Gw2cSkKwUCAerVK0Cw+aneVSZK0IodInI8VCw5YVRmEpWIJE0yXYttUDjZbLWr1upFj1WiAbpTw8fl8JJJJPF4vLpfLeMCxzUEci2g9oes6sqLQbrcN1aFJVHaXk+p2U1xasnr+GNOUSSQSRCIRtm3bRrFYJJPJMDk5SblcJhQKWd1VA4GAtRD3yguC5QW+e0G+GJdVLzFC9/bumJI9ybR7/3ZLTuxntRjUpRKQ/X7unmf3+3qJJdZqPbhsMspms3Q6Hfr6+lZs7+vr48iRIxe1jw9/+MMMDg7y0EMPXe40VsBeDgjeHJbRxV4MovJEJpO5Yvn1RlosG4XvHzlCo15nbHSUWrWKLBntGtwuF4lkkjNnzpCZmyPd3290I5Ukpmdm0DSNcCBgBdcRuUWKYkm6Z6anyefzyBjWO5KE1m4T8PuN7YrCvn37WCqXmTt9mlOnTjFx6hTNZpNrrrkGn8djLApdT+S6ZlSAdrtc1gJbKpWoVipEolESsRjIskEmqxy3BFZSqRAh2BcrTNIRuT7CYmo0GkbX0sVFms0mS8EgLlXF7fUSCoeNJF6bJadjtIHQ2u1lebjYn65blcuFfNzjctFsNFAFuZuEJMtGWwyf18tiscjw4CCA5X4T7ixd1/H7/YyOjlpVr0UlgomJCTwej5VTE41GVzz5G4e9kiBapksRzu0I0L3d/nmxvXvf3UTSa+Hvfr07htOtlhP7txOKfbv1nXdZOr3eIyyjbsvHvrat9QPjpqnpPvnJT/K1r32N/fv3r5lEs5ebbqPjDpshYFhtvPWQX281ywiM9iAH5+dJ9/UhyzKVchmfz2cshMBSuczg0BBFkzgmJidpNhp02m3SAwPMLSwwOztrSbgBg5BsSrV6o4GsKFQrFbw+H5qmWQtKMpEAMAL0AwPcODxMuVzm2LFjnDl7lpMnThjkYnM3gbFwN5tNK6l4cmKCvXv3AsZ1ODU1RV8iQSwaNawYUyFnP7PCOtF13bJMOp0Osmkx1FstGvU6rWaTRqsFuk5ucZH+dJpoPE4kGkWSJKOck0lY1lM1y1aUpmkoqkq9XrdITUAs3DKG+1KTzBp1ppzbrhwUlpqk65RrNepmP6ReZGJfyN1uN/39/QwODtJutykUCmQyGV5//XUA4vG4VVxUuPPsVossy9YD22quNjFuN+yW0WpEsFpCbLeLvPv9Yv+r3Ze9rKfVLLvVLK9e59W+ba1w2WSUTCZRFIX5+fkV2+fn5+nv7z/vZz/zmc/wyU9+ku9+97vccMMNlzuFc+Dz+c6xjDaqOoF9zM1y0+n6udWvw+EwqVSKnTt3WqXl12q89cRGjjM5NUXD46EvkTCC6uaiLcsyHU2jUasRi0SYrVZpNBpG64hqlXw+T7vdxhcILC9O4sFAli3LSCykLlU1xA1mwVSXy0UoGGTf3r1W4F4sAC6Xi107dxKLx6nXamSzWeZmZzl14gQhs5WJbMrGfT4f1193HeVymTOnTxty606HRDzODTfeiCzL1BsNIwEWLFm1pmk0Wy067TaNZpN2q0Wr1aJQKCDLMpFaDdXlwu12E4pESLjdKLLM9MwMiVSKQCBApVKx2kToYtG1XY/CAgIsYYVkzsGeJCuSasX58ng81CoVw2Kyu7A0jXazSafdplqrGWNL5wblV8uzEfMQJXAAlpaWLHfeoUOHrGotqVQKr9drEbSwuMSx9SKO7u3dqjp72+/u+FD3++37tltG3XPoPs5u8rO/t3tbtzVl34f4vxfBrsfD4mWTkdvt5tZbb+XJJ5/kne98J2AcwJNPPsn73//+VT/3h3/4h/z+7/8+jz/+OLfddtvlDt8Tb0YBAxguhKNHj1ry63g8zvDwsFVvai2xkWS7UeOcnJ8numcPgUCApXIZr9tt+enLS0tWQ7NcLkc6nSYQCBDw+dh9551WPa9mrbYcyF8+AMs6UhXF6ODq8y13MZVldu3cybYdO1jM52nW67TNbrDlctmwXgGP12s1t2s1m2SyWbKLixSLRSqVCguZDMlEggcffJDp6WmWSiVcbjd96TQ+n498Pk+pVKJuyqcFZElCVhQ8bjeKy4XPjOl4fb6esZ0V7jLxeeGyAiRZXuFys4+j6zpuW+Kr5Q7sep+Aqqo0222DpMxq2O1GA93tptNqoUkSmmSo80Svn15P+N1P9r1eC4VChMNhduzYYbX+FlWvA4EAyWSSdru9InZkFxHYLTCx39WECPbuq6sF/+3vF+OJh+pe8xcuQ0EoYoxu114vXOz2XlbchfZxqbgiN90HP/hBHnnkEW677TZuv/12Hn30USqViqWue/e7383Q0BB/8Ad/AMCnPvUpPvaxj/GXf/mXjI+PMzc3B2D1gb9S9BIwbEU3nV1+nc1mrWO85ppriEaj615xYiPddCviF+uAdrvNYrtNyu3G5XbTzudRfT6ajQal2VkOHT5M0OdjYGCAcDjMyOgo6DrZXA6/12uU7BEuMFU1mtIJa1x8D7qRzLnv2mtRXC4mJybweb0Mjoywe8cOps6exe/34/Z4aLVazM/NsbCwgKZpFMyF20o2NeXS0UgErd1m8tQpTp08ySs//jFuj8fqYRMKBlHMBEm3243H4yESiVgVtrsXbivIbS6EinBRwQo3mWX1SD3ED4KsxPcnFt0eVgTYyMducYDlrtPbbVqmp0OUJNLM42+1WpSWlqwK36stjt1xnW6y6rZkvCbxDw8Po2lGYdGMmccFRs+qdDpt3We9gvndFo1dXt0tl7YTmZ1Qul1q4rVeOUfCOhLHI17rJTNf8X1dgKjPJ6joZdVdKa6IjH7pl36JTCbDxz72Mebm5rjpppt47LHHLFHDmTNnVpyQz3/+8zSbTX7hF35hxX7+j//j/+DjH//4lUwFWM4zsn9Bm6Gma5slYdYSq8mvI5EIU1NT7NmzZ83H7IWtFjNayGapaRpuVSWzsGBYEadP4/Z4QNMYHxlh586dtFotqtUqsiyzVCwS8PmMygOyTKvdZsf27UzPzCCpqiXbRizekgSaxjPPPssjjzzCTTfcQCqdJhyJEPD70TF6GrU1jZqiEIvH6XQ6RmBd03CZ1peEYX2AsZC7PR4y2Sz333+/JWsWi2chnyeWSJAwe9icPn2acqUCupEPNTQ0ZNWow9y3rhtlfgS5iuMQlpGAICUZswGfzcIR1k73FSLEEZacvMuDoJvjivJJOixXxZYMwUO90bCaCKqqijcQoFqvE11lceyO7XS7wqB3fo+dwPr6+kin00xMTFAsFlFVlWPHjlmy8VQqZeXddbu9dF1fYaXYSal7nnZ3W/e87QKHbvLsRardxNHtihOwqwW7t/WSilvfZQ9rcC1wxQKG97///au65fbv37/i/8nJySsd7rzopaZbD2I4H9bqC9J1o96ZcBnUajVisdg58utcLnfFY10KNoqMBNbTMmq1Wrx4+DCSojA1O4sMDA4N0e50SCaTeMx2EJIk0Wq3kRUFdJ1arUYylVqeH3DnPfdw+NgxMgsLRjUCYR2JGIp5TXz5y1/mDz/1KULhMIcPH2ZyYgJJltm+bRu7r7kGXVFYXFzk5ZdfZmJigk6nw/i2bdx5xx0rEsN1XTfUZqpquH9k2YpzaJpRWyyzsMDhQ4eYnpnh5PHjRONxwuEwx48fZ2BwkDtuv51AILDcXVWyxa3McQQJir+x/a2ZVpuI91jWkCRZzfyEm1LsV8zdWiRNAtJMebiGUYqobX7vxVKJZqNBq92mUq0SNuunAXQ0jUq1et5F105Aghi6q2Sv9rTfbfl4vV527tzJzp07qVQqLC4uMj09zZEjR4hEIpY6z+/3n3OsYl+WBdqDCFa71u3k2MtysR+zfbsgv9WsMvv7u+Nq9gf57nNkl453XxdXgjd8bTo73G73pseMrsQ12Ol0rOrXornZheTXb4S8pssdZz3QaDQst0uhUOC148fxqCpjo6PGzaYo+H0+Bvr7mZmdJRaLGTXXbMmAspn7oum61ZU1Fg7zvt/6LX7/93+fTrNpuOjsLSSENdBuc/ToUWbn5jhx8qQlJjjy+uucnJjgvttv55uPPcbps2eJx2KoqsqLP/whZ8+c4Vd++ZcNr4M5ZqPRWJHIKdxi9Xqds2fOcGpigkq5zGnTQ+F2u6mUy3h9Pk4cP07SFDigL8d5RE6PleXf5d6xehfZ3i+k34BFbOIKkaRleTeY7rdOh46IB4l9mQtds1ajasa28vk8kiwTjcVwu90US6VldZ1kxF9qZoytOyG0O+bSHavpJiz7Z8S8uy034SbTNM0KLYyOjtJsNi23+cTEhKVaTaVShMPhcwQGsDKJuJtE7feYGLfdbqOq6gqBQy/S7bZkelVpsI+5mguum9C6338+Bd/lYkuR0dVQDuhSLaNu+bXH4yGVSnH99ddbF/Jajnel2GgyWouxKpWKZWEuLS0RiURIpVJs27aN7y8sEARKpRKKLBv10HSj66nH5TKIyHSzqC4X1UoFv9cLsowCVpsHgLNnz6LpOoFgkIqokSiISHxHmsbk6dNMnT1L2mzxIOk6tXqdo0eP4lEUJk+eZNfu3fg8HnRJIh6Pc+LkSV5++WUe/qmfshb2drttVQUQc2i32/zgBz/gxPHjhMJhKuUyc3NzRCMR+vv6UFWVpaUl8rkcTz/zjKUsi8ZieD2e5Y6qXQ8DggCE9WOXiNvdUCsWN1aSULPZROt0qJrVxsGwTuv1OtVKxSig6nIRDAQIR6P4fD4kU2AByy5BodCTJImWtjLB037tdC+83UTTbekZX89KolotrmJfuD0eD0NDQwwODqJpGrlcjsXFRV577TUAK6E8Zj5ciP0I4ugeezVXm51o7Nu7j7tXcmv3ubCje5vdZWh/vdcD4lo+NG4pMhJuus2OGZ1vTF3vLb9OJpOXJb/eaLfZZrjpLuczQq6byWSo1+vEYjEGBwdJJpOWwnBmbg5cLpAkSoUCg4ODljquUqkY8RzdiKN0Oh08Xi+lYpH+vr7lhcAcr95oMD01BbpRnsdyz9mtFmEdmYuFR1UN95Vk1FvTOx1OnzlDp93G5/VayajoOsFAgImJiWULRJKMhFe3e7litq4zNTvL5OSkUb3b4wFdJxqNUqlUmJufZ+eOHXhM16OsKESiUavJXygYJJ5I0Go2jardtsVfZ9nisf+ssMxNC0kCOuY5Ez/CBajpOvnFRcPN2Grh8Xjw+XxW3MXu+nGrKo122yByWaZlk0WL303Txdcdx+jlejvfIt3r/d2fVWzt4O3XZbfFI2Tje/bsoVQqsbi4yKlTp6hWq0SjUasKhHC1d8eZehGNruuWZdQdM+p+IO0VlxJ/97Km7OcTWJG3Zd/navfiWq0HW4qMfD4fuq4v36RXiZtO0zQKhQLZbJZMJrOm8mvHTWfAipOYBNRut0kkEmzbto1EItHTxXl0agq/10t5aYnxbdsIR6PMzc7i9nqp1WpGS3pdt5rNtUXcSFquRlCr1SgWCtTrdbZv347L7aZiCgXQ9eUkWBs5PfPMMyQTCQYGBw1rw74oqKrlhrNcXbJMo9EgHImsVKaJJ2aWqxiUSiUjydPjASAYCuHz+SiVSuTzeTBJorS0xG233srI8DDDQ0OWW2xxcZGJyUkWczlSqRTxeBy/37+CBHXdUNtZOUBCdgxGO3NTeKCZ1lCtWqVZr6ObJB+JRonF47gUBU0y4ktWkqxYXNttJEWhXa9b504RcxDiCkFwNgLrzuvpRRq9hADne4/9tW4XoH2MXkQmGtht376darVqVYE4fvy41Vk1lUoRCoVWJRrd/M5WizHZrSb7a9Y1dQGxhl2JJ/4X4/WyvOzkt1qc63KwpchIPGnUarVNIyPxRZ2v+vVayq+3qmV0MW66TqdjlTgSMbZUKmVVGL+Qi/NsJkOj1UJ1uQh4vYSCQTqaxtz0NC6fz1i4Wc6TaTUahqABqFerLJVKeH0+kqkU2WyWSDTKbbfcwtP79y9bRJq2XIlBkown/Hqd2elpVJeLPbt2oUuS4bpSVXbu3MlMocDZs2cZHBxEURRLpHLtvn3LcmnTWhBEJpYDj2kNoRktun1eL8PDw0Y79KUlzk5Noek642NjjG/bZsWE3B4P/QMD9PX3EwoG8Zj5SbMzM7hcLuKxGPFEwmgCCJaVI37q9TrNep1arUaz0aCt68iahsfrxevzEY/H0YFSsYgky1bXWkUsiGZfJCQjBiUpCqopmxcuwrathpwiSXTMhbBpJv6K6+Z81kWvhbX7OusmJHG+7YKAbrddrxiN2Id43efzMTQ0xPDwsJFSYCofX375ZRRFseJMEVEZvgvd8Rv7XO2ijNWOr9vN1702drsfxZi94kXd468FtiQZibjRRpNRtVoll8uxtLTEc889ZyXM9ap+vVbYqjEjge6x2u225eJcXFzE5XJZMbZLLXF0dmEBXyqFqihGzyJdRwWCkQiKJDE7N4ff5zM6u0oStUaDoKpa1lMyncYlG1Ua6rUa0UiEf/nLv8wPf/hDatWqoahTFKs+HKZiTFhMZ8+cwefxWE34rr/uOvbs2sWecJhXf/xjTk9Oous6wWCQ++69lxuuv96ymprNJi5VpWWmMgiRQF9fH9FolNm5OfrM8kYul4vR0VFuvukmKx1AuCQxP6eDpYCTZZl0KkXaVOYVCgXy+TyHjxxBNt2DszMzeDweWo0Gc3NzaKY3wuXxEA8Gl1tQmOQi5icUiZKug1hATUtHkgyxgyLLhqrO5bI6rkqyjCIWUpal47o5H+gdF7Evrr2smdVUbeKzvWJG51vUe11/vcrvKIpCf38/fX19llWfzWY5cuQI7XabWCxGMpm03Moi6bYXoXbPqXtM+7Gs5pK0z1XsczV33/kswivBliIjj+maEPLu9SYjXT9Xfh0IBFBVlVtvvXVd2iJ3Y6tbRoDV+TOTyZDP5/H7/aRSqSsi+UajQa5S4bqdO+l0Org9HjqmS67dbNJntgevVqvkFhfJ5nIslUqMjY2RTKetkkFC1tyo1y0Z+A379vGDH/1oOU4kZN7if/HUq+uMjo7SPzDA2NgY28xE8PEdO7j9ttsMaXe7zcDAAH19fctFR01rwGXKugV0IOD3c8ftt/Piiy8yZcawVJeL22+/nfvuvXdFwquwisS3uUJ+bZ6HRqtltM7w+ejv66OYzzM/N8dEo4EsyyRSKdxeL6lUarlcjXlsOqDoy51hdd3o1dRoNo2cI+Ga01cmjLaFDFtcByZ5Wfeyvtx9FvNcwLmLY7cbCs5NIu22mlaLM3VbRueLP9nRvd/uOUmSEduOxWJEo1F27txp5RROT09z9OhRQqEQqqouKxx7CEx6Kfa60e26tJ8v8VkxhnDT2c+nGPtixrocbCkykiRpRUmg9SCjbvm1ruskk0lLfl0oFDh58uSGEBGsrMy7HpZXNzZiDDBcrWC0OF8yWwWkUil27969Ji3OT50+TSgcpm0+mdsrDqDruBSFjq4TCASMatCtFlHTYlpYWMDjcuHxevG43Uaiq7ngarrOz7/rXfzgxReXVXT2uJH9epQkDh85wj333EO6r498Pk++UCCiacQDAfZde60hCDBjJmJ+GoYKzW2KL4QbUMRchoeHiScSZDMZWqbizmq1YCejToeWWY+u1WrRajZptdvMzc0hSUYJI9nlQlUUouEwsqKQTqUolErceOONtFot8vk8EydPUq1UCEcixCMRQpGIMTeM+nOY1hCm5SPIR8JQI0pgueAwXXa6bsTAJH05ZmcnJzCIWVUUmqbVYLzt3K6m59sOqzfL636fwGpWw2qurfO9LrbbLZtAIEAgEGBsbIx6vU4+n2dycpJGo8ELL7xgJdraPQG9iEa8JpKEu+cr5tJ9XN1k1/3+1eJtV4otSUZrbRn1kl8nk0muu+66c/y7myEogJWFFNd7vPU4Pl3XLQl2JpMxRABgVRkXVu9a4djp08SiUVpmfFEDJE2zcnc0DGunkM8TNhfYcDBILBYDoNlq0ajVKJZKVKtVyktLZLNZ3C4XXr+f6667joMHDqwkINM9Z1lIus70mTP8wR/8AR/+8IdJJJOcPXOGF15/Hb957Pfdey833Xyz4bqyPY23mk0mJid56aWXePFHP2JgcJAbrr+eoaEhY3FVFFLpNM1mk5xZx04UaNXBEhd4XC4CoZBRDNV0r2maZrQ614xutsByCwnTzajKMh6/n6DfjyrLRKJRo7FdJsOp06eJhMMGOUWjuG0dXFVFoWpLcrW7rQSh66L6ua6j2R4QdDG+SWoAkqIYltYqrji7BbQaMfXK+elGt7igm5B6JZ1eyPrqXvy7LRUwLFKPx2P1fksmk2QyGQ4ePIiu65YAQlQb7+UytDcPtJOeLJ/b40gQs73HU685r7WLDrYYGcHK+nSXS0b2hfFS5debEcOBtZNXXsx4azWWcHMuLCyQyWRoNpskEglGR0dJJBI8++yz9Pf3rzkRAcwuLuIfGKBYKuEyW4MjSdSbTVSXi1wuh2b265IVhfm5OTwej/XE7na5UFWVoCShuFx0Oh2S8TiNRoN2u834tm0cfPVVI/FVkizyEU/1FkGpKs1Gg/1PP00wEODo0aOEJYmg38/k5CRnz5xhqVzmun37EPXLNF3nn558kgOvvcbS0hIDAwOcOHGCl196iYceeojR0VFk2Wh5sJjLcfToUSRJYnBwkJ07dlCr13n94EHmFxaQJYmh4WH27duHW1VpmWo4IRwQ1opQD3ZMQu2YhCcIxO/zGfeFTZlXKBaZnprC7/MRjkaJRaMopmtR0o0EY03TDHen6Cwqy5b1BCwr7AQZmfGkRq1GqVSi2WziTyZX3Hf2B8JeVkgva6LXdgF7aZ/u/XTHasRr3du7rbJesZ1eMS87SQiRQzKZBIzcOJFo+/rrr6+QjQtlsX1OvZSG3fGy1Y6lG+ux7mw5Mrpcy8guv85ms1YH2kuVX2+0aMLuptsIXCnZihpqgujFU/iuXbuIx+Pn3PDrdVz5SoVRr5dMNovXRjK1Wg0JGOjvN0QNYATgxdO46TaSJaMEj97p0KrXDXedLOP1+dA1jbHRUVweDy0znoH52V5Sbzodnt2/n2Q6zc6dO/F0OkQ9HqKRCGfPnuXlH/+Y2265BVlRUBWF0tISExMTVjKlKI8zMTHB5OnT3HHHHejAqZMneeGFF5ibmyMSiTA5OclrBw8abRhaLRKJBJqmcfTwYUr5PPfed5+RRGser9bpLIsapGU5u97pICsKkp2QWJZnu8zeQem+PrROh2wuR6lYZG52FpfLRafdxuPxEDIf6nRp5dO1YlpRwApXXq1aZSGToWz2mxJ9oCQzL6Z7Ie1ladhbOHTHceykYF9sNU1b0Ya7e//dVsVqpYbsv7vHNi6J3j2ExLkVfazEZ0T79h07dvSUjQviCoVCKywh+3HYrUS7mKPb4ullFXWfjyvFliIjSZIuyTLqll8rikIqlWLPnj2XLb/eLDfdRpLRpaLdbpPL5awus+I8X3vttUYuz3kk2Ot1XE1No4MRpJfN4qb1Wo1CLmdUP/D5jBwjc5FxmRW5RbFP3SQSDcNaUF0uo4upoiDLMnuvuYZUKsXMzMxKabctxoOmLXeElWWy8/PEEwnG0mkUcz+JZJJCoYAG+E2BRC6Xo1KpsK2vjyVR6cF02czOzrK0tITb7eaHP/whWqfD8PCwVXT1Rz/8IZqmcd9991kVEgJeL9Ozs8zMzjI2NmZZQ4otdgPLDyKSLBvFTEV5GpOoZfGgIiwDRUERyrxEgo6uUygWOXXyJMePHzdiUdEo0WiUUDhsfEZfltM3mk2WKhWaU1O4zfMfj8eJR6Mriq62zZ5G3dZGt9hAHIP43YuE7NednSREcL9bACHQyw0m/u9GNwn1mksvIrW75LutLLtsvNVqWffb2bNnV8jG7dXGuy2jXlZT9xy63ZO9xBSXiy1FRnBhy6i7+rV4ghgdHSUUCl3xid0sN91GjXmx1kqr1bKSfHO5HF5TcXXTTTdd9Hley6eubihuN5VSyVJ6VWo1mvU6UZt1Jha8arVqVUiwlF82lZUiGcH+VruNT1Wp1uuUSyV+5qd/mr//n/+TzPz8MvnY847AygkCQNM4dvQoI/39VsXsWrVKOBzG5/VaSjhFllHMBnrYnnRF/TJZlplfWKBQKDA8MkKpVLKUa16vl2KxSLvVstR4iqqiyEaHW6tbq1gUzXlLphWoi9wf2WgeKAsXnvk+WVGWz43ZqluXDBGGAqSSSVqtFv19fUYibqHAqVOn0IBIOIzf60VxuWibAg2Py0VfOo3b7WZ2YcE4PnOfxikzzmcvd1cv0riYhdW+XSzQ3S7A1UhO7Me+sPdyC9pJq3vN6I4/SZLRdVdcl70eeO2k4nK5LNm4ruuWx6eXbNxe27B7Tt3nqVe8qJcVdbnYkmRkt4zElyEsoGq12rP69Vpho9103U9ZGzHeamPV63VLgCDaXKRSKXbs2HHZXWbX47h0M17RwZCNN5tNmrUaoWjUKi8Dy8qtZquF1+ulbS6uHVvwvdVs4nK7URSFpaUlioUCqstFLBrl9jvvZO/evXzn8cd55umnDQmyUNfZyUjkIZnjZfJ5osEg5XqdarXK2972NiMIbZ6LVDpNX18fs7OzlkquaVr5d9xxBz6/Hy2bXbZoxOKqG91mre7HtkWybcrbLVecIEzTOpRNS0cTsRPzNSE3RzcreJs5P4qirFApIlx/JvlKkkQ4HMbtdhMMBCgUCkYFjfl5JNMidHk8httT7E83hBOir5Elde7xFN9tba8WB1ktpiNgD+SLBwC78KHXvroX7F5Wkt3Ksh+Lnfjsc+nl1rsYktN13ZKN79q1i0qlskI2LjpBJxIJq9q43nV+VzvGtcaWIyOv10upVOKf/umfrL5KBw4cIJlMsm3btlWrX68V7Mqc9Xyyt2MzyciugBPdSYUL7kqJfr2Oq9VqgSwTCYU4XirRbLeJJRLUazWjNbdJNuIJv2XKurOLiwYJGZMzKjE0GnTabYqFAsgyI0NDyzJrXScSDvPWBx/kphtv5B++/W2OHjtGp9Vazj0S14jNYjp69CitYJDhdJr77ruP+++9l3arxTPPPsuJ48dRVZX+gQGazSbTU1M06nUkWWb3zp3cdsstNOt1/B4PWqfDkcOHiUWjBMNhiwRisRjzc3M02m1q1SqtZpPBoSEG+vuX20UImbUpVpCADsbCL1qHS5K0IqdIBkOgYFpLwIpyPZpmtHAvFIvWveHxegmaNfEEYdbqdQq5HJmFBTJzc8RTKcOiMpWA9h5MkiTR6no6717AxbbzxTy6LR0Bu2UkSdIK1333fd7Lmuhe1MVrwtIR7xMk121prGbFifPZ/d7VEl8F+QUCAfx+P2NjYzSbTStEcfLkSXxmpQxRnqib1M6Xr7UW2DJkNDMzw7e+9S1OnjzJhz70IXbu3MmXv/xlAO4020NvBHrdCBsx5kZaY/V6nZMnT1pFSOPxOENDQyuKkK4F1uv8NZtNdFmmWi4TCAbRKxUKuRyyquLxeNBarRXyYXR9RZUA8f/S0hLzMzOk+/sZHBqikM+vaKNttzwkoFgsEgmHyeXzK+XepqtQiBsatRqHZ2YoZbMcOnyYL37hC1SqVUNxJhlJnhIQi8e57ZZbuP/++0nG4wyPjKAqCj/44Q957rnnyGYyhvS8XMbv9xMIBhkeGWFkeJgDr71mNQt0u90Ew2GjOGwgANKyWEEQkbCAZEHG2K5x24Il3Isypvy90aBWrxv9oDAeFv1+P339/RaZWQuaabH6fT78Q0P0Dw4Si8Wo12rkCgUkXWdycpJkIkE4FjMIF1bU9rsQAXW71uxWsJ0IesWSVru37W657jhM9xgC9nbgwuqyo5swu8URsFK8tBrR2ufc7a50u90MDg7S39+PruuWsOjgwYMA3HPPPZYbr9s12N0Tai2wJcjod37nd/h//9//lzvvvJNoNMp73vMePvzhDwMwNTW1YVYDLF8g9iei9cZ6W0b2IqRzc3NomkY6nT5vn6W1wnocV92sSp3NZkmlUkYdNLebmZkZRoaHjad6kyA084lVfJNtTaPZaFAsFPB4vURjMWKxmLFwmzJua9Exn4BlRaHZatHqdHC7XEQjEQq53LJVJK4Tcay6DqrK9MxM98lAxHhcqkqjWuW5Z56hWCrxe7/7u3Q0jW9/61s8+dRT1KtVZFWlWi5bhUs9Hg8nT57k9YMH8fp8jAwPMzIyQigUYnZ2lldeeYWffPvbjTwf0524ok+RphkuStOlKInFUZZpNZs0mk1D2t5sGvEkRcHn8RCNRq1Yj2ZaPrputKGwuyt13VAWamAVYg14vUQiEXw+Hy/++MdEYzGKZo09r8dDPJHA16UEWz5dq8unxd+9iovar7nuffR6yOzlahPbe82pF6l1j91t4QjXavd2sW3lZdK7Np94rduFKPYpqo1LksTS0hKq6dLtVXGh+xjXAmuyWn7uc59jfHwcr9fLHXfcwQ9/+MNV3/v666/zrne9i/HxcSRJ4tFHH73i8X/rt36L2dlZnnvuOa699lpDCSXLltm7laXWYsy1Hq/T6ZDJZDh06BDPP/88r7/+OpqmEY/HGRwcZN++faTT6XUlovW0jMqmKMHldqO12wT9fuLxOFqnw+zsLOVyGU3TaLXbVoxE0zQWMxmq1SqpdNpIeDYtA01YT2BZOzqGdeBSFFyKQsDvp1Au4wsErOrclnuu01mZh6Qo1jap0zHq57ndBPx+vG63VadN03UOHjjAn/7Jn/DMs8/ywx/9iHazieJykVlYoLi0RK1ep1qrMTM7iyLL1Gs1XJJkCHkyGRRVJRGPMz8/T6lYNMQB5nGJNt86WLEtrdGgZD6cLMzOMjc3R7FYpNNuEwgESPX10d/fTzKZJBwOG0RknhfhwpMkQ4Sgm6RvX9ysuJC+rGaUTPJKxuPs2b2bG2+8kYGhIaq1GseOHeP73/8+J0+eJJ/PL3eOtV1H9oVZrA129BIEdH/+fHEd8Z5uJV8vgoOV6rvucYUF1B2fsTcINL4O+aKUe91j2edmPyfit67rVoy3l4tR/O7edqW44pXk61//Oh/84Af5sz/7M+644w4effRRHn74YY4ePUo6nT7n/dVqle3bt/Mv/sW/4N/+2397pcMDsGfPHutvu7QbNkdQABunbhNjrsUFIYqQCgVcryKkJ0+e3LBW7utl8TU7HZqNhlHORwTtzSfxWDRKvdFAkiSyCws0mk3cbje5xUVq5TKp/n7CZt5GR6jKMOIYqqLQabWQXS46uk6tWmV2dpbK0hIut5tbb72Vf3rySRq1GrFolEVhHcnysrDBJCRJVVFdLlSTeAR0SVoWJIBVMeFHP/whS6USgVCISrVKsVQyLBxzUW9oGoppwUiyjKQo+Hw+FubnGRweNs43RlkeXdfROh3anY5h6bRaxjnBIPJavY6iKPj9fiMvCaMjsfmlrWhjDhjiBbGQSxKKOZb4AdBl2ZLOd5fnESWR2mbMCF3H5XaTjMVIJBIMxuNsGxwkm83y2muvoSiKFfuIxWLnuMSsc2mzQrphX2yFZdLtfrNbKHaRQy9xRLdbrxfsxNEdn+klKDifSKLborN/RsxzNatttYfA7vhRL/fjleCKyeiP/uiP+I3f+A3e8573APBnf/ZnfPvb3+YLX/gCH/nIR855/1ve8hbe8pa3APR8/UohGuwJbLRltFlkdLnjiVJHogipkLqPj4/3LEK63i7BbqzHWOVKxWq1IGTa1tM6hrsgGAwSDASYmZ0ll8sR8PtRXC5KhYJRCsfrtTqtghFTUd1uFnM5w61pyql1SWJ0bIxCocAdb3kL0UiE5597jkKxSCKZpFIuUzf7H0m60UBNVVUUnw+9WjXmZAobZNscRYKpbrrSdF3n2IkTjI+NUa1W0TQN1SQqS2Sg61QrFYOUWi08bjf5SoViPk+1XCY9MEC9Xie3sICiKKiqisvlwhcIEEskjHJJrRZzCwsEg0HrfGqY1bhNF5vd2pFgudKCIBbbgme5RFl+Yhf5SoLUOkK6jU25Z1oOkiShqirpdJqUrcp4Npvl2LFjVu8wUc1ctRWX7V7Uu6+37sW5O0bTq6yOQLc78EICBfG3fZG3f76XWKGXhdM9rt1i6y5/1CumJv5vmx6BXvuCla7Pq8IyajabvPTSS3z0ox+1tsmyzEMPPcQLL7xwxZO7HNil3WI+G00MG534eqnjiVyrTCZDqVSy5J179uyx+sKsho0ko/Vy0zVM1ZxuLmQdTaMj3HG6jqyqtExXXqVSYfv27YbsudNhYWGBdqdDJZejWq3SabUolUo06nWWymWazSbDIyMMDw4SCAZZzOUIh0JGHx9J4vbbb2fbtm243G6ajQaVpSX+6I/+CBmjbptYyNF1JJcLqdOxcnpEfEaUhrEWElPY0O50mDx9Gs18irerAoUFValWjQrbLhezMzN0NI1sLsfgwAB333UXfX19KJJEXzpt5QwBlnQbXUdVFEvJJsjOimkIQrcTCkZbCFHJomOSP8JikCSrP5FwPUqYVqBpaUmybLhBTXcouk6n1aJYKCA3m9ZiK8syiUSCWCzG7t27rZI5J0+epNFoWGrPVCpltWwXWC22ZHeZ9Yrp2ImpW0Ag9mmXgXeTiyAr+3fafe13V4DoJsBeRNXt0usV/7LP1W7B2eNp3QTXvW2tcEVklM1m6Zj1u+zo6+vjyJEjVzSxy4XX613OSmfjyQg2xxo734Wh60arc1GCp1KpEIvF6O/v57rrrrvk2m9vdMtI15fbZ7tU1Sjp025bxTxlWWZmdtbIz4hE8LrdxgJr9h0KBIPIkmS47hoNXI0GAZ+PQbPWndvlolqpUK1UWMzl0Dsd8oUCmiRZZXFGRkfx+3ws1moMpNNkczl0UccO0wJwuazEUXTd6ohqLfSahiYZcmO93UZWVToi0VQzGtTpgKSqRrVvTUN1u7nxxhtRFIXJ06cZ6O/nzrvuYtv4OOFIxBhHkqyYlDhfwoKE5cXZKqJqWmeCeACDIBXFkquLmJpmzkuSDIFDu922at5pupHLJFyWQh6vY9auM91lmWyWRqOBKssEw2FcZiNNuxtKLJqi0+q2bduo1WpkMhlmZ2c5fvw4kUjEcueJOHM3Wdj/7yV2ON8Dk52kxP92N1f3vnu53exj2NuOi/Pey8KxE4b9/eIhpnuM7mPrJdY4X/zrqnHTXW3weDwsLi5a/28GGW1GSaDuY9R1fUUbblFrb3R0lGQyednCg422jNZjLL/PZyxu5lN+R1+uBt1oNlkqFPCFQoTDYRaqVautd6VcZn5uzippBDA+OkokGjViMxiElUomLWm4Lkn4AwE6rRbNep1IMslgfz9enw9ZknCZ8ZuBwUHmZ2Ysa0aTJCSzQZ1mngutezHDvNYEidm22917kq6jqCper5ddO3YYSbySxIMPPMDdd92Fz0x2lMDI5TGtF9EIT5CJgCzL51bZNt1pspmcKuJgujkP2RQlyCI2pGlWp1bxo+j6inYY4ry3Gw2q1Sr5QoFCsUg8kSAWjy+7WMvl8z65i/2L/JrR0VGazSYLCwtGm/WJCUN4YbZm8Pv955DIakmg4vVugulFjL3cguJ82sfqRVarqem615peLjcx/gprugcxin2e776zH89VZRklk0kURWF+fn7F9vn5efr7+69oYpcLn8+3Imb0ZrKMNK13EdLdu3evCOReCTaSaNfLTRcNh41EUXEcuiHBbjWb1Ot1BoeGDEum06FcLtNst1kqlZBloxBqIpEgEYuxmMvhCwQsl5Ks60Y5KrM9eaVcJp/JoEoSkVCIWDxOKBBABjzmvrbv2kV/Xx9TU1P0DQwwOzW1vBh4POhLS5ZIQlhIEoalIIGRyCr6KZnbkZfbkSOsJFnmZ37mZ3jnO9/JUrlMwO8nKiTpXQuQcJ3p7bYRkzIXfTEPJMnoAyUZDfIsAhQxFLH4CmvKdENh7lcWbiuWCUdYQJIs02m1qNXrRkWLYpFAMEgiHicWjdLf17e8qGIsiKISeDcRrBbjkGUZr9fLyMgIIyMjNJtNq0LL6dOncbvdpNNpEomE1SJmtTiPgN1tdiGraTU5eS+yE+47u2u2+z3dxynGWM3KE7/t1STs87UfX7eYxE6yvSpWXAmuiIzcpkLoySef5J3vfCdgTP7JJ5/k/e9//1rM75Kx2TGjjR6z3W7T6XQ4e/Yshw8fRlVVUqkU+/btO6fX0lpgK1hGAb8f1eWiWq1abqlKtUqj0WBsbIxKpcLMzAzZxUWru+vY2Bg+n49Gs0m9VrMWZLeoY2ferC63m8z8PG5Fwe31Eg+HCYZCLBWLRkVrwOf1Uq5U8Pp8KJLETz/8MH/9139NrlCwhAbCUkOSrARZsQCLcyOsIV1YFIpi5EyZLS1ERYRINIrX7eaeu+8mHIkQiUSWhQOmi03GqLCA3V1kWkbWYiZEAyznhAjXm6jurXcTgDFZK1dLA4tELJeeplFpNKhVq0bJJFnG7/PRl07j9XpxezyoooaanRhM1567x2LYKy5j3w7LloLH42FgYICBgYEVzTMPHDiAoihWdfPVxhB/98ozsl8bvWI5Ar3Uad3xZ7uVs9q+ehGK3fq0v6Z0Xbu99tVr/eiOaa3VPXrFbroPfvCDPPLII9x2223cfvvtPProo1QqFUtd9+53v5uhoSH+4A/+ADBED4cOHbL+np6e5pVXXiEYDLJz584rnY6xYFwFZLSeC7Yo45HNZsnlcoBx3DfffPOaFHu9EN7oMSNFUYhHoyxks4yOjKBpGjPT04TDYY4eOYLL7cbj9TI8PEy5VGKgr89aZN1uN4VCwZiXvpxbpLfbFEslGtUqrXqdvtFRJEki32yiiIUcaEuGaAJbW+e+gQHe9a53MTU7y9//zd/Q0XVarRayLNN2u5EaDcN1ZV+IAK3dxi361uhG5fB2q2WRhuxyMTAwQDgSodloWJXAdW250ra5w2WSMCXgwj0HRtxGiAjsLcQlzLbrpisR8ZTPcosNCSwryorV6TrVep1apUKr1ULvdHCb/ZASyaRlXeliPiLOYc5LB4t8dc2oqN7tNoOVT+zdFtNqFoN4mLMr8zKZDJIk8eKLL5JIJEin00SjUUsAcT7xQPfvXtUa7HPqdunZ591dbdvuYuu2sHq5B3v9Fuege17C02KPMdn3ZT+va4UrJqNf+qVfIpPJ8LGPfYy5uTluuukmHnvsMUvUcObMmRXsOjMzw80332z9/5nPfIbPfOYzPPDAA+zfv/9Kp4Pb7d6SbrrzFSE9duwYqVSKcDi8pmP2wkZbRusBVVUJejzMA6+8+qrV1tzr9dLf14fL7Tbk0boZUAdroRU5P51OB73Tod1osFQu06hUcPn9xNNpFBGz7HRQMK0AyciVEW0pMNtle1QVDfD6fNx+22006nUef/xxOp2OEVMxlXQ6BikIAQOSIVxIp1JWhYelpSXaZp06RZKIx2KEIxEWFhboS6fRdZ1ioUAgEDAWHtMi0sCybCSTNIVLENvrlqrMRlSY85JM95sgK6GyE+RXqddpNBo063UWMhlcHg9+v5+4Wb9Qlo0aeJhjCaITd5FFsGJe5kNAu9PB5fOtWEzPF9jvjrP0+i0WYWEVRSIRZmZmuPbaa8nn85YyT4gfRJdVAbsbrJd10U2W3fPt9V6R29eL/OzEcyHZNqxeV068LtZMtYvke5Fbt+T8SrAmAob3v//9q7rluglmfHx8XRezzU56FWOuxTF2FyGNRqM9q41vdBznjWoZiaTeubk5Jk+epFit0j84iMfjwev1Ek8kcJn5R16vl7xZa04HK39GardxqyrlYpFWuUy23cbt9ZJMp+noRj8et9tNpVLB7/WC2dNHNsmrpeuWq65Rq+EKBg0Bgkk6991/P6FAgO9973vMLyygKQoVM44k1HztTsdqo9DRNG6++WZOnDiBrOu4ZJlGq0UgECAUDLJUKpFOp/m5d70Lt9vNyZMnkSSjWGo0FiNiVv0W7b01G6kIObaAIBxJvFcIFuTl6tmarlslgaq1mkUiXp8Pv89niD0kiUQigWzOXxC2FUcS15huyNKF5H0FmbDs7vN5POckm/ayLMQxdC+k3STVHegXf8fMJNudO3dSLpfJZrOcOXOGI0eO9JSM2+XcYl72mm7dMabV5gjGPS7IoZsE7PGqXgKEbitJ/H0+16P9nPSao/h7LdeeLaemuxrcdJdrGem6ztLSkkVAogjp8PCw1XtktfG2IhmtxVjdfZV8Ph/pdJq9u3ZxaHraqBIiSTQbDbILC5BM4g+HUSSJdquFIstoZlxOWDgeVWXq7FkUSSI5OIjLdB8ppnDAFwxSXFxEM4vGdjQN3czNUTFiM26Ph+LiIpJJBuKJXwZuvvlmbr7lFjRdZ3FhgS999rNMT01ZSjtBkNFQiE6nw7ve9S4qS0vMZ7OGqysa5eChQ2QWFgiGQuzbt48dO3YgA4PDw1TKZXK5HKdOnkSSZSLhMIl43Cgaa8Z5ROsHyTwmMaYonCpQN4UGllWk66huNx6Ph1gsZlS4WOXp2bKc7CQiy9BuI6mq1acIsCwtRV7ON9LN71cU8+y1iIvrqBfEwtzt7upeZO1JqOK1UChEKBRifHzckoxnMhlOnDhBOBwmkUiQTCZXlYx3V0awu2C7RQPtdnvFe8Tr3TGxXq601QQIq71/tfPTPU9xDGu5Fmw5MnqjCRjsfmmRt5VIJNi+fTuJROKiFHDr4RY831hXu5tOENDCwoJRPSEQIJ1Or+irdGh2lsaxY4Z826woEIvFAMjOzqK63ci6TrNWM6TIGE/ixVKJZr1O0O83mtKZLrMOoAh3nM3nLplP+5gLStt0NQnnSEfTjKZ9LLf2rtVq1KpV6HRweTz86iOP8J/++I+p12pGEVFZJplK0Wo2iUWjxONxkskkY9u2GedM0xgcHrYebkScRlg/4VCIcDDI2NgYS6US+XyeyclJWu02oVAIVVWt4q86RqXutq7TrNcpFYsUczlmZ2dBN8rySEA0HselKJZlZXfzySZZd0yytb5fzei2KwqmWsIGu9Ku07FibOJ9Qn0HoIBVKb7bpbQixma7bs/nwuqOJ9nf06sWnCStlIyLiia5XI5Tp07h9/stZZ69okm32MGO1ciq1zF1E0+3lddtLfUiGPFZpcsCFdu73Z9XbczoaoNw04mTejW66YRiRxCQLMskk0muueYaYrHYJSvg3mjWyqXgYscSoo6FhQXy+TzBYJB0Os2uXbvw+/3nvD/i8SApCu1WC1lR8JiutXQyic/tptFoUGi3mV9YwOv3G3GZahVfMEjE7FK6VChYCZuKeVMquk4bcHm91MzK2cByDTuwXFEev9/oIut20+l0jARZU5QQjcdxybIRT9I03va2t/HC975nNPKTZZpmxYg777rLIkShXFuhiMOmyjJzVSyXIxCORAiFQoyOjlIql5mdnWVicpKps2fxB4OEgkGCwSCqLOP2eHCpKsFIhP6BAfEFGcVgXS5ksFxtVszIJBxJHDfLKjvNNmfLHQXLZK0oVr2+lq5bxyjJZg6TrtNut3tKjLuf5O3bey3aAvZKDvbrb7UYVDeJeb1ehoaGGBoaot1us7i4yOLiImfOnMHtdpNIJEilUlatRwH7ON3HIyyQXrGlXvGfbjKzE5j4jH2sbkvwfDEo+7m173MtsOXI6GrNM2qZnTgzmQyLi4t4PB5SqRQ33ngj4XD4ip4wtmrM6EJjNZtNo3K02WI7FAqRTqcvqqxRJBDA7/NRWVqCeh1fLGaRi24+8SdTKUqm3DqfzeLx+WhWKrRM+XGlVgPZaKctFti2+T0GfD7mSyV8JhHqYLiwzA6zLkWh4/EwPz1tdBDVdfr6+/G6XMZ7xWIA6IrCr/zyL5NOpXj22WcpVyoMDQ1xzz33MDY2ZpCPpi0nmpqf04TrDKxgeqfTod1u02q3aTabdNptOmYVBF2SCJuup0gkQrlUolQuU56bIxKJkPB68Xi9VtdVyfwtKnLbSUWQoPhbF/Jv080mvl90Hd3WUhtMhR7LLcXBsKLEI5quGeWbypUKxULBaAm/ioXRyz3VK2gv0KvQqT0fp5d11b1/AZfLRV9fH319fXQ6HSsH8GKKua7mHoNzKyZ0u++63XBi3nYLT2yzk1b3e7stoF5W5Fpiy5FRLzed1WZ5gyAIsFcR0lQqxbZt2wgEAmv2Zb6Z3HSNRsMioGKxaNXVu+aaay5IQGDcsO12m4DbjVdVqVQqVu5Ks9lcvmExFs5qvU6n1WJ4bMwik3qjQbPVolIus2gmfKuKAqpqiBUUBcUMNutmUzkwnuhbZumhYj5vubGiiQStVssKUGsmwXV0U0TgdlNtNPjn73gHP/n2t5NdXGRkeJhsNks+lzPk0brROlzrdGi2WmD+XyoUkBSFarlsfHeShFuWUdxu/H4/qqIYsUjTxdio11FVlWQiQer/z96bh8dRXWnjb/W+75taki3vGxgbGxuzJ0AMJMxAEuIJBoPBJoaQIUMmvyErmfBlIcPkIysG25AAcSCQhEAgDHwmZAI4NmBWW94XSb2pW73vS9Xvj6p7XSp1y1q7JdHv8/iR1eque6u66p57znnPe+x2cAAvaxSLoaurC2ylggrLoi8Wg9lk4hdv4dz67ag5nglHlRuEsemzKBgxFqBEBoaEOAUPiOSHKkKIsSTQ57PZLOQyGVQaDeyChyFeIMX1OtJdfrXaI3JfVPOWpGGuWvI+0uNJDYRcLqcKDxzHIR6Po6+vj4q5Wq1WuFwuyswTP2NixXCx4ahWtCo1imLDJTZCtUJ/YtRSnCCvMQwDpVJZM5c9XEw5YyRV7ZbJeIXieiGbzSKXyyGZTOLIkSPDEiEdKSaStzLW4DiuqgGqxiqsBWKASJM5ADAajdCyLLLZLBiWhVposJfP56HValHhOCQiERgNBsjVahqGq7AsfQAdDgdUOh2Mej2fTC8W+Z+VCkr5PCrlMgKxGCoch3gshkIuh7BcDjnDwGA2QymEgwI+H5QqFe+hMCeJAGAYKo9zJBYDWywiXywik04jGAwiFovxOZ++PsiF/kgquRwqpRJKhQIyuRwqlQoyhoHRYKB6b/TaklonkccgE2qRyPgcy0IntKpua21FJBxGV3c3An4/Thw/DrPJhEKpRDu3Cl8aFVVlZLz8D/WGAEpNp+FCYnwEg8WI8hX5fB6JZBLxvj5kMxkwDMPT2RkGnEyGSjrNH1e0oIr/L46MSFUMqi3U4mNIPQepIaoWkZBuDAl7TvwZALAKTRlnzZqFdDqN3t5eHD9+HJ2dnbDZbDScRxZ6MatN6uFJjaPYKEqZdtIQYDVDJB5H/B4ClUoFpVI5JoouYkxJY1RPAgPHnRQhDQuN15RKJYxGIxYsWFCXdudTMUyXz+dRLBZx7NgxdHZ2wmw2w+VyYdGiRUMSdq1mgMjrDMNAq9VCI5cjzfK6XxzDQKNQIJ/LQa3RIN7XxyecAVTyebDCYi4Xci8sALVKhVIuB0YwRhqNBhwAdaUCRqGAVqNBuVSCTvi7Vq+Hy+3mm83J+FqgCssiGAhAYzDAbDLRBUXO8AoPcrmcJzXIZHC43WDLZSRTKdiFDrsyhQJOoaavn2fBnSxklclk1AAQeR6A92aI8gIDQRla/KyQz4i+b7VOB7VajUWLFiGXyyEWj8N36BD2ZLOwWCywWCywms1ghHAjI5A4wPI9jUrlcr8wHc1zQSBzMAzyAoEjl88jm8nA6XDA5XYjnkzCZDTSnBhbLkMt0Khr5XJq5VrI+NJ7RupNkdBmrWNXy6VUC6lVy7EQw0GYebNmzUI2mx0g5irNeVY7H7GhI+NKX5fmkgikz7PUABMjrlKp+rXgGGtMSWNEwi3iizmW4LiBIqR2ux3Tp0+Hw+HA4cOHoVQq62KIgPqH6cYLhCLb29uLVCoFuVwOh8OBZcuWDelakg6fpVJpgLQKgTjG397aiuChQygKdTtKQcEgHg5DbzJBo9UinUpBKejNaTUaMCyLshA+U8hkkKlUVIuOhKSIZ5HL5ZBKp2FMpWAxmWA0m6ES2GdgBIUBmQwKIUymkJ0sRAUAhWAMZAwDpUaDZCoFg1YLTmhlThr6EcUEoobQz6sCv8hXOA4KCHI83Mk2DazICyJsNZlMRg0XIR1QnTkhTAcAOp0OOr0ecoaB1WZDn1DDdezYMVjMZlgsFtisVsgE1XCZEJojrTogeIHlYhHpTAaFfB7gOKi1WugNBugNBmiFMXK5HM09ceC9q1KpBJvBMGChlxoHaeiqlkGpZbTI305170vDXwTVQn/ieYrvTb3ghU6fPh2FQgF9fX3w+/2oVCp488034XQ6YbfbKStUPD/xWNIQ3GDEjGpzI+8nBmisZcWqYcoZIxIKy+fzVH13LBZqluVFSHt7exGJRACgpghpPT0VYHLnjHK5HHp7e9Hb24t0Og2r1YqWlhYsXrwYe/fuhcViGdQQVSoVmpQXX4NqiwqZP9npLezowK6DB5FKp6khyReLfGtvtZrK5ugMBsT7+qDTalGGqDcPx0Gn0yGbSvHemuCRpHI55FMpKJRKtLa10ZYInEDjrjAMVEolWI6DkmWh1emQSCTAWiz9eggxOCkiKlOr0ZdKwaDXg5HLad0T+ckKYzAcXyjKKBS0jgeicJVMMDIKganHMCeliliWpf84weCWxV6BYKSUZEEDgHKZ14dTqdDq9cLb1oZsJoN4PI5Qby+6enpg0Otht9lgMptRrlRQFnpA5fJ5sJUKlEolNDodLBbLyYWVYZDNZk/SwglrjiyoHM/iMwqLcjXvSEpLrib/I75fyE8pLbqWB0TeL/U+Bkv+Sz8jDSuKX9doNPB6vdBqtejs7ER7ezsN52k0GjgcDjidThiFzsPAQK9JvCmvlfeRgoThdDrduG4+pZhyxojkEMbCGBFqJmHAEd2q0047bVAR0noaB4C/AevZCny055bNZtHb20uVJWw2G1pbW/vFyMlY1QyfNAQnDY2Qz1abO3lvpVLhVaAtFgRDIWSTSZQqFeiEYkuaS1Eq+cVbqaQUZpZlaXJdIZeDE0gDMgDpeBxytRo2pxMcgFQsBigUPAVZyIkoANpiu8Iw0Gi1CIdCdExa1IiToSwVwyBZKoEtl8EKCzMH0FwWWcDBCSw30d9I0zrSwI4RVBxoiEzwikgzO7rQAtRoAXyOiROF/wCgwggyRySkV6nwHpNOB6/Xi3yhgFAohCNHjyKVTkMGPl83a/Zs2O12KITrSLwd0nKC4zgUCwV6P1BqOHeyyysqFWi12qo5DqlBqnZPVMsLic+/1melNUC1Np9SAyY9Xq2wYLX7WaFQwOPxwO12o1wuIxaLoa+vD++99x4UCgVsNhtcLhdMJlO/9jDi9U+aVxOfh1KppF2Gq4Xy6oEpZ4yIZ0TyRsM1RqRehTDgtFotHA7HsERI62kcgMnhGWUyGWqAMpnMkJUlCAYzQNKHrNrDLV2sSMjCajTCaDIhFo8jl8+jvaODGheVUDtTLBahNxqRSSb5tgvEyxB+6oxGBAMBmPR6GG02vqUBx1EZIYPBAF93N1i7nTc2MhlPXhDCVCzD8HVO2SxPNBAazJF24qRYlFMqEU0k+P+zLPVoOFFYTuxNceTacDwhguUvJBjmpIgpJ7q+INeHXHSOQ1m0kJECXkYIHRICgkx0zVmOQz6dRr5QQL5QgIxhoNfpcNqiRZDJZPD19CCRTuPIkSN8czuhgaFMLgejUIAVQqYAb0TVgtwQC1CjxzAMLcZVqVT9vtfB8kLiBVhKXpAu2OLFmNQyST0gcs+JQ3PVvCepNyb2Vk5e6oFkAfJaWSC2kN/lcjlcLhccDgfmzZuHeDyO3t5edHZ2gmXZfpp5JMQmNrBkDNJWfjzzQMPBlDNG5OITRt1QjFEul6MGKJFIwGg0wul01iyYPBXq7RmNdehsrMYixI7e3l7kcrlhN/fjOF69OpPJVI37AwMZUWTBILTXarte8bEWTJ+Of+zbB5bj0NrSgr7eXljNZiTicTjtdihVKpQrFajlcqQrFRSKRT7vw/Dq2+lkEsViEUqGgcli4Q0RQBvJEVVpluPraWQyXhCUk8lQZFnKXtPq9chnMjAZDEClAk4mo5/JZrMo5nKAXI5IPg+3UMlPF0bupNoDvQ4sX5czIB9CwoDCgt7v78RbAqjRIUaLFTwSwvQjOnTZbBbJRIKG9xQKBVRKJbR6PcwWC9WVI3N1ulzwtrVBIZcjGo2iNxzGiRMnoDMY4LDZYLZaefFYjm+qp7ZYIOdvhn56eCzHQSPq8FrrPpX+PFXyX5p3Isci11vszZBrLb5fa81DDCnRoFYuS/yauN2DNLxns9lgtVrBcRySySTC4TCOHj2Kzs5OqmdJnjnxv8HyQI0wTlPOGAH9GXXVblZOeIhI/kcsQjpUttZgqHehbb3ZdLXAcRz1gHp7e5HP5/sRO4ZigEgOqFQqoVgs9qv9ERsgskBIJUyq7XqrxfDJz2keD+SVCiqFArQGAzgAOqMRPcePQ8YwUGm1qBQK4AwG6I1GZDMZqFQqsBzHF8TK5WhpaUGpXEYqHofFbuclboRFn+zgdXo9f58JsjkywdPgACoXpNRokMnloFWrkclmkctkAABanQ42txvgOGQSCeQLBT6PIkjksPyJ8teG/yJOsuqEf6zgXYmbtcmEEKN4SeL4C0PJBRzH8bVFHIdCPo9ELIZ4NAp/IEC7uqo1Gj7EqlLxzf34L4kfR1jEybUoVSpQMQxUajU8LS3wtrQgXyggGo8j0teHE93dMOr1sFityBUKkMv4OqMyScwLebFyqQSDRK271j1QLYxH7ldpuEx6j5C8nPh1EuaVFshKF3exxyS+b8nfxPcneY0cR/w+8Voi9a6k52qxWGA2myllPBKJwOfz4dChQ7Db7WhpaYHL5aoLIWG4mHLGiGEYvtumxDMS7xoikciQRUhHgkYQGBrlGXEcR+skiLirw+HAjBkz+JzAMA0QOSYZq9rv1arkqxUzVvOkxOA4DlqtFkalEoxCgVwqBQaARq3G9BkzkEilUBEkgcBxUAntynO5HDLJJPQmE20op5LLkQVQKZf5mh9ReK0sk9GFmixs/XbqDAPI5VBrNPB1d8NsMkEtqIiD4etuCJlCqdEgFg5jOvH0yHkJxkcmk/UjTBDCAukFJL4KxJvicJJhl8/nkU4m+RCdEBIlRl+pVEKt08Fss6HV6+XzOqUSEokEzZ3JhBAjq1DwBkS8WArnQTxFhuOlk9RqNdwuF7xuN/LFImLRKOLxOLp7eniP2mo9adw5DqVKBdFYDO0zZ/YzJkD1eiEqNSTamEhDe2KQz4g9EnG9EPld/H4yHiHHSMeThuXE8xN7O9LPSM+rmncnDe2JPSan0wmFQkGJQoFAAJ2dnTCZTFQdQszMaySmnDECTnpGLMsinU4jn8/j9ddfB8uywxYhHQkaEaarZ86IZVkkk0lqgIrF4rCvK2HAEUXiamNUywWIH1Txgyd+iKU7ZfFxpeNwHIeZLhf2x2JghFxPTqBqyxIJmPR6lO12PmeUzyOVzeLosWOYJYiSFnI5MCYTKgAMZjMSsRhsdjsqDF8rBI6DrFIBw3EwGo1IxWIwms20CysHnmwTi0bByGQwGgwwWq3QkFwIxwuHyhieqadSq9EntGYgxoXmhQDeEBCjI+ywSe+lCsez0iqFAkrlMkqlEsqC50k9NIYBW6lAq9PxZCCOo4YMMhm4WIwnHQC01QPNGcn4AldiDIlmnkz03ZXLZV6hgoQJcZKUwMrlUKpU8LS0wOF0wmgyQalQIBaPIxaLoVIqYe/evTAZjXzhsBCulHo+YkjDXdXyPtU2WOLjivNJ1XI64mNIW4OTe7PasaUhRDHExkeqwCD16MRzkcvlNBcknqtOp0NHRwc6OjpoEXkoFMKhQ4eg1+vhdrspAaLas1IPTDljlM1mYTAY8L3vfQ8qlQp33HEHAGDhwoWwWCx1cU+nomdEPEtS8/DOO+/A4XBg9uzZsNlswzJApVJpQHxcalzIbpx4EtJwTK2doTQsVy1nIE1WT/N6sc/ng06nQywSASOX8x6T1YpEPM57OuAlgswGA8xGIy+AyvFhSUU4zIejAKRzObB9fbR1ABhBZohlUSgWEQmHIQsG+VCdSgWFXA6rzQaT0QiH1YpCuYxkPA6lw8Gz5YTrpmB45h3DMKio1UhmMnyHVZZFUejuWq5UqG5bsVwGW6mgUCggk07zxaYcB7mQL5ArFNDr9VCZzTwxQMhllUslxOVyXipIuFasYGiIZ1IRvg+QaymT0fblEM6Z6MuhUqHXhjDi5II3RhTIOZbla5EEI1pheSktlVIJlVoNo8mEUrHIt25nGPRGImBKJYTDYdqmQQzpAi2+D6oVoNbKGYk7q4pzNtJ8UbXNlPi+Hqoxk35G/JpcLh+wuRIbVWKAhrK+qdVqtLW1oa2tDeVymRqm3bt3Q6lUUoHhetVJEkwZY/T0009j+/btePHFFwEAixYtwk033YQlS5bgnXfegc1mq9tcpkrOiBggkgOqVCqwWCxgGAbnn3/+kG58cR0Q2WWK49y1aKTSXWs141UtBFfLSEmPKf6bXC5Hi92ObDoNjV6PXCYDo9EIuULBF4vK5Yj29UGtUsFss4GrVNDX1weX241SoQCbw0E7nOoKBUTCYV5UNZ9Hb28vMoKmm0qthkGvRzqTgUyhQD6TQQVAOBoFymWkczmYDAYkk0mUymWqGQcSehM8oEwmg30HD8KgUiEn5HFI4z2ZQgGFULcjF1hosb4+miegoTnB6yJ0aggLsoyw/FgWJcE4cMK5cQxDc0wcf7H5YlbwRoa22hAt/OLvkCPvEb4bhSiXhEoFkMl4oyMQX1RKJWx2Oxx2O08akcuxaMEC5AsFZIX+VEePHqWaj06nE3q9vqoHJF7kxUZE6lmJPyMmwQADDZrUAwL69xoSH6ualy7NJVX7jNgzE9/THMdRSZ6hhMJrQaFQoKWlBS0tLWBZFn19fQiFQuMWNRp0LnUfcZzw7rvvYunSpfjud7+La6+9Ftdccw0uuugivn10HQ0DMLnDdBzHq0uQEFylUqFCpFarlVaFD2aIiPEhigjVcjfSn+KdoPh3qXERLw5S4yQ+B+lOU7rjlM7p/CVL8PSuXVi0aBH6wmEAfJ2O2WyG3+dDuVKBx+vl8xxyOTQ6HWKJBOQyXvtQoVJBznFgBbFUX1cXZHI5FEolXCYTuFIJap0OMo6DXqeD2WKhYaZcLoeenh7ks1kU8nloBX1Fl9MJCDVDHMdBwTCUrKCSy2ECX8rgcLshI54IBEMhGJ2KwJCjRA+BNQemP7mBXHNSk8QwPJOOXj+Aki6IJ8VyHC2KBUDrmziRh8MwDPV4GJmMp60L7yHjEj3HYrEIhUIBvcEAk9A5VSmX80ZY8JA5hldemD9vHlxOJ1XDJ8WgpHmiy+WiHpP4XiX/r3YfiO8tKYlAfO9UY8ARI1UtxyO9v8UbK7FRkm4qxXMk3x/J3Y0HHVsmk1FK+KQ2Rr/4xS/wX//1XwgGgzjjjDPws5/9DCtWrKj5/qeeegrf+ta3cPz4ccyZMwf33nsvrrjiihGP/3/+z/+h/xe3kRATGOoVB51sYTqO42itQjgcBsdxNfsriR8+8fWUKiHUqn6XPtTS91TbrYrnWa1wUJr0reVJAei3ayWf4TgOHo8HDpUK6UQCeoMB8UgEdrebHxN8ywewLCrCZ01GI6KRCGRKJa/8nckgnUwim89Do1ZDpVbD5fFAq9GgLxxGKBqFXa2G0+OBjGEQj0Sg12rByWTQajRwezx04U0lk+jx+ZCMx+FwufieQ3r9SakfABqtFr3BIOx6Pa0pAgRKOfF2hGtUFkJ4NE8jIgMQHTu50MBOTr5rluXriETfOyu8BsGrIrI+VCpInIQHH2IUvgBwHEcJDblcDrl8HoV8HgwAtVYLi8kEuSDqyrEskokE7zmR75Bh+OsDgC2XYRJUB0gxqMfjoW3lw+Ewurq6oNFoKK3ZYDD0W9xrhdikXpPY0FTbgElDduLXxONI/yaG9JmSrlMcx9dT6fX6urHgJm3O6Mknn8Sdd96JzZs3Y+XKlbj//vuxevVqHDhwgG/rLMEbb7yBz3/+8/jBD36AT33qU9i+fTuuuuoq7NmzB6eddtqo5yNW7pbeXPXAZAjTsezJDrO9vb0AAKfTecrcWi0DRGRpyFwI+2iwvI7U4IiNkHQsqTGpZnRqeV0EtY5Lfr/q4ovx0PPPY+7cuejp7obJZkMyGoXX60X3iRMo5vNQCLI/ZUHws+vECZSKRThsNhjNZjg9HiiVSr6BYl8fCkSfzmSCTq+nhaZ6sxnRRAIOmw0VloVKLkdB6LSq02phczoR7OmBjOPg9/mASgVmiwV6g4EPv7EsMuUyjKUSVWKokOtOvAjhdxnZWZNw08mT5+cjeFAcTgpsgnhBQogOguEi+nUQPkPakBOaNzGCnBBeLJdKKJVKyOXzSKdSSCWTUAhSM1arlb/2gkEjRbRlofCVCrlyJ+uawHHQyOXQaDQnDaRwPygUCrjdbng8HpRKJdrA8sSJE9AI9HO32w2tVlv1niFMOGlrBvJ3aSiv2u/V7sta+U7xZ8S/k/GILpxKaL44EenYY4kxMUY//vGPsXHjRqxfvx4AsHnzZjz//PN4+OGHcddddw14/09+8hNcdtll+OpXvwoAuOeee/Dyyy/j5z//OTZv3jzq+UjrjICBDanGE40I0w3FGLEsSxt8hcNhMAxD5Y1ILmgox6hUKrw3gP7CjGIjXC0XJDY80jBZtQe1mncj9ZyqoVrYDhhY0yG+fgzDwOvxYIbdjlQsBrZSQSgY5MVNFQo4XC70BAKwO53IJpNIp9NQKBR8C4VcDq0dHbznIRw3XyyikM9DaTDAYjbzPXiIQWX48oNMNsu3rNBowKnVSOdyVJVBzjAwWa2QMQxaWlqQKxSQjMcR8PmQyuWgFhryKQoFzBdySgzDUCYb+Z14M6xgNEjIjYTnCKONhuJkfF2PmO5Nwm7AydAboY0TQ0RyP+VKBcVCAdlcDqVymafEq1R8DkuhgMlk4lUs+C/hpLisMB4j49VLZKRQmHxHwhwLhQJsRmPV75ks2MRjItRlIuvV29uLt956i+q6uVwuGAwGem9Ic0JkDPFxpV6+1IhUIxhIN4vVyBLkWCQERwgL5JiN8FTqjVEbo2KxiLfffhtf+9rX6GsymQyXXHIJdu7cWfUzO3fuxJ133tnvtdWrV+OZZ54Z7XQA9G+wJzZG9UIjwnS1zo8YIBKCk8lkcLlcOP300we0Pq4FMQ27WCxST0guJM2lY0srzIGBIQupAapWuCg1TOLzrPUZMaSLlfQ94vHJcS9duRJPv/YaWlpb8c4772Dp4sXIZDLIJpPo6u5GPpeD0+lES3s7tEolFEolDh0+jEIuR1tIJPr6oNBo0DZtGuLRKACgIHgwFY6DXDgfm8WCaDgMpcvFM9GEEKdCYLaZDQaEQyGoNRpoNBpUTCbIFQrI43HkBdWHUDqNo4cPw+Px0K6yEBZxIp0jFzwahmH4glzRIk8YcVQ+SPhHtOYYhgFTqfC5K47rZ7gq5TISqRTkDIN0Ok09NK1WC4PRCLVaTQ2kjGEQjcV4+R5CWhCOL8PJhblSLiOXzcKg01FZIADUAyvmcnC3tQ0I38pksn6MN/E9IZPJ+hmmWCyGUCiEPXv20I7LRHBUDPGmp5onI33GpZuoWkZLHG4m8xssD0Q83HqhWqiwHhi1MYpEIqhUKnALPVUI3G439u/fX/UzwWCw6vuDweBopwOgv2ck3l3UC/UO00kfDJZleakVQWGCaFkNp8W5lIRAQGLn4oepmgcknhv5KU3iio2JePdJFQKqGHXp8cSvVzNg4utTK6Qnnn+LxwObVotcoQCVQoG9+/ZBo9XCarVi9syZkDEMrBYL5CoVGGHX7HC50BsMosXrRTKRgNlqpUw4q80Gf3c3yoUCX/Apl6PEcVAJYxqtVsT6+uBwOvmaHIi6o8pk0BgM6OnuhlGrhVKrhd1uh9VqRTKRQIVlEVMqEY5GkUgkIJPJ6N91hFUmsPBILgmcSOiU4wtPiUdHCA8QGXxCwa7k88gVCohGo4iFwwiZzfz5F4vQW61811eFAhzL0voikO+IYVAWwm9alYo20SPHr7AsGLmcN5hyObL5PExmM50DA95rkglhOxJmkxaKknuiGiONfO9E7NjhcKBcLlOyzrvvvksbJrpcLp5NKdloVXtuqt33UiMkNZxSD+hUhoZl2TEtyp+omDJsOjHEOSNp+KgeqHeYjpwfyf9EIhFaLzASA1StM67UgyDjSh9AKcQPpjgUQsarFsqQVsxLjwVU36HWYiyR38U/yf/FnlY8HkckEoFLo8ELb78Nu8vFi3k6HFAplUjG44jHYsjlcmhta+N3/jIZ9BoNYgB6TpxAx6xZdFGWMQxYhoHF4cCJri54WltRERZr0pZbIVCWU+k03xpCWEwLhQLSqRQAQKfRQGc0Qq/T0VxMRTg3nVYLrV6P+W1tyGQyiPT1IdjZCbVKBZvNBpvdftIQMUIXVeZkrojDSd05juV7QaWzWSiiUboZYcAv4mqNBlqdDpzTiRa3G+VKBbG+PpgMBiiUSloIywK86gNzMh8kZxiUikUoFQreEEFQ6QaoEeTIJkQYj4QKc6USn9/s7cXc9vYBoTExarHlxEZLbBAcDgfsdjvmzZuHaDSKSCRClbAJ+UFcdCpFNSMo/bv4viNdgofj6dQzxdBIjNoYORwOyOVyhEKhfq+HQiF4PJ6qn/F4PMN6/3AhDtMBk4NQMBJUhHoXn8+HQqGAQ4cOweVyDUthvJoSQq2wFwAqMU9i6WJtOGlMHTgZiycPlNQAAf0fWGmeiCSoxQWI4jGkY4kXIXLMajtT8tl0Oo1CoYCDBw+CYRjY7XasWL4crFqNvd3d0KvVKGYyUJrNcLndAMP3IgoFgzDodIBMxncmzeXQ0tKCVDrN7+rJOcvl0Gk0UKpUSCeTMJtMAMczyxRCoafdakUkHAYjlyMWjwOVCpSCMZExDIosi0QkArVaTZv60dwQAIXBgEBvLzra2mA1m8FyHGKxGOLxOD748EOUBcUFp6APWCqXwZZKyAstKUgIjAO/WLKVCnRaLdQazcnWEIKHks/lkM/nwTB8nRDLnSQqkIZ/DPkuSN0RCQEKnyE1SpzgESsUCjACMy9fKEClViOXyyGdyaCUz0MphClNJhM62tsHhHylecBqpAIxpHVCxBsn/YHmzp2LWCyGSCSCDz/8ECzLQqvVIhqNUkFS8f0qvc+kRlAsTjqS8Fe9jVE9UwxijNoYqVQqLFu2DDt27MBVV10FgL94O3bswO233171M6tWrcKOHTvw5S9/mb728ssvY9WqVaOdDgD006YDGhM2G6/xiAEiHpBarYbZbIZCocCqVauGdLOTHa80BCf1LKRhL6D/g16L2TYY1bpaoWstD6tamI3ModoiUM0AVXuwMpkMQqEQIpEIPX+v14t2YdfNcRw+tmIF3j1wADK7HXKlEplEgioCyBQKmIVGeAz4PIfdauXVtfN5JFMpGHU6Wo8jVyig0miQz+WQTqdhNBqhlMtRLJdpLY9ao8Hx48dhsVjQ0trKM+YE70ktl8NgMiEej8NGFkOGz8UQDymUyUDf1weVQkFJBkaDARq1Gj3d3eg6ehQHDhyATmCVOZxOGAwGKBUKXk+OXDuBQKDT6fjXmJN0ckofFzYIAF/EqhTUKDjh/mT4L4EaJvI8sDjZ4pwRxiKtKFiWRTabRcDv570ngO966nBABqC7WIRGUIYg3yu5n6SeUq3NiHSDVS2ETDZLNpuNNs/88MMPkc/n8eGHH9JaHKfT2a+nmXQOpBh1LLqkNgkMw8Cdd96JG264AcuXL8eKFStw//33I5PJUHbdunXr0Nraih/84AcAgDvuuAMXXngh/vu//xuf/OQn8cQTT+Ctt97CQw89NBbTgVarRV9fH/19sntGYjZQX18frZ9Yvnw59Ho9H56JRAa9YaUGSGooyLzFD2at94jptOJzJsclIQjpfMhxyN+lXoz4M1L2Ua3rKTVSwEllavFrRE2c5DitVivmzJkDk8mE999/nxagkjkolUpcuGQJXt+7Fya7HVabDfG+PtjsdkT7+mB3ueD3+VDhOHiF6vVEIoGWlhbEolEolEpoNRqeUSZ4HpVKBb1+PzI6HTQCi6tYKCAjdIU1m0wIBoN8sSY5X2IMOA6JTAa5bBYarRbxeJyXGapUeNUBhQLdwSBmt7dDrVRCLhgZhVwOvdEIpUARTiSTiEQiOHzkCIxGI+xWK6w2Gx9mEwwcOI6G9qjOHbkXhO9P3IqCFUKSwMmW4oSGTVq0F4tFvuWD8H2XOQ5sPo9sLserkzMMVIIH1Nbaysst8TcJWJkMmUwGTouln5dQi34t3TxJjRZ5r9SrFv8Ub55Ijc+MGTOox7Rv3z5wHEdDeaTbszgXNFaot2dUKyQ53hgTY7RmzRqEw2F8+9vfRjAYxJIlS/Diiy9SkkJXV1e/i3nOOedg+/bt+OY3v4mvf/3rmDNnDp555pkxqTECeM+oWCzS3xtljKqFCIYKUsDX29uLaDRKK8tnzJhB6agE0gWdQEpCkD580pBVtb+JwxlkrGqFfOK8ELnW0oefjEPeLzYy0t2s+FhiL0fssUkNkZQQQQQhI5EICoUCrFYrZs6cST3JWiDHWrF0KQ4eO4ZoOg21SgWVRoN4PA6ZQoFMJsMnnxlee06j0fD5GABWux2xvj6+dbNWCwaAxWQCy3FonzYNiWgUWp0OuUwGKrUabo+HhrjAcYBcDpfNhmKlAoXQu4cBYK5UkIhEeFVvlQqJRAJgGDisVpQ5Dtl0GuVKBRaTiVcMF4yJSug0q9Dp4BRyJGylgkgkgmgshmMnTsBsNlPDxAheDfG+IDvZRZYV6NqcyAAR1l5FEEEl1HQwDFQAykIuSqZUIplMopjPo1AqQaFQQKvR0EJgDkC5WKSK44zwGlepAOUy7DZbP/LMYKFY8X1U7fkQ38fVvGjxvStm5dntdtjtdsyZM4dKZR08eBAAaPGt3W6veW+NBNKw5FTFmBEYbr/99pphuVdffXXAa9dccw2uueaasRq+H8RsOqAxYToANNcxVJRKpX4GiGhuzZo1a1CZd3FYsBYLDkC/vIs0sSpVJBA/wNK6C2kYUmqAxDurarRvaby+mgdFfop3ttK/S0OJJNRDaqlyuRysViva29thsVhozL6aNyY9Z/Lzqk98AtueeQZ9kQhmzJqFJH9S8Hd3o72jAxqNBr2hEGQANAYDEkJeyGy3IxaJQC6T8cw7spizLJRaLXxdXWhtb4dOpztZ0wPAYrWiWCggnkjAZDLx7Dbh+ihlMphsNiTicRhNJhQLBag1Gp6QIHikB3t6YCL5QiIho1AgJ6gdQBhLIZfD09ICj9uNYrmMWDSKvmgUx7u7UcnnIVcoYBGaBRKvCMxJijjAs+A4Yd4y4ZgQGbFiuYxSsYhsLodwKAS90QiTyQS90QiHRkPJGmRe8WQSep1uwPdaLJVg1ev75SfF926tzU8tanW18LL4cwRioydm1slkMlrH1Nrays89HkcwGMTevXtRLpfhcrl4VQ+HY0zCdPUyRtLNZz0x5dl0QGM8I2BoicCSoD4cFoQfDQbDsLrMkiR/uVymHVHFRlBsOMQPn/RBJg9cNW+pWh6HfEb8/mqfqeXJVKsRkobbZLKT7dtJLF96LJZlUSwW0dfXR1uam0wmtLS0wG6396PESo2gdFGSGmmZTAaTyYSrP/5xbH/5Zezfvx+nnXYaIuEwSpUKUKlAxnFwOJ3oC4VgttuRSaX447EsbHY7+sJhmM1mcBwHrUbDtyc3mTBj5kwkolGoVSooyBw5Dmqhs2yxWEQ6k+EXZ/D1SRBCZDq9Hql0GhXB4+iLRsGWSpArldDZbAhGImhraQGEc1QoFHyrCPCGCAKJgGNZQKANu10utLjdyBUK2L9/PyKRCI4dPQqL1cq3BhfIFEQiiEoOCYYQMhnyhQIKhQLyuRxKgvyQRqg5KhUK8Hi9vMKBEN6D+F4CkM1k4PZ4eC09huGNHcOgkMnALVrUq22GxPdNtc0Keb3WRkT6f2nuE8CgXVKtViusVivmz5+PRCKBYDCIffv2UcPkdrsp2Wu4aLLpJjGknpH05h1v1PIKCIrFIjVAsVgMBoOByrYP1wCRcJQ4nCU9X+nOT0ooEC/sYi9EbIBqeTK1/lYtNFKNqCCeg/iY4r9JFxWGYagXGYlEkEwmYTabafxeRXoBSSBeXMQblGo7a/HnO9rasPqss/CXN9/E/n37+F47RiN6QyFM6+iATCaDw+lEuLcXSqUSyVSKeic2hwPxWAzpdBrFYhE6rZaXW2IYGs4zWq28h8OyUKvVSCWTsLlciAoyTQadjoqkymUy6LRaJOJxBAIBOOx2eL1eyJVKuoD3JhKwpFK8Ny0YVRaoqtbNSeRvlCoV3C4X3B4PSoUCeqNRBEIhHDtxAlaRTFSxVEIul0MiHqffu0KphE6thsls5lUlBAMKADFxPhK8IZQLDfkYmYwXXAWgZHhZowrHU8KLxSJsRiNkkg2LePMj3szUCmlVy4NIN2bkfVJDJxfkh4bybDIMA4vFAovFgnnz5iGZTCIYDGL//v0oFovUMDmdziEbpqYxmsRoNJtOXOtAQAxQb28v4vE4jEYjXC4X5s2bN6AfSzUQA1QqlXhdNJFRIYssWVSqxdOreSXkuNUMULVwnTSEIT6+eJ7k9Wo1HwTVPCGpoZR6dURvrLe3F8lkEkajkTKe1Gr1AEMn9brE34f0eog/J71uAHDG/PmIp1J489AhxGIxqIUW4X6/Hx6PBwzDwOF2IxqJIC1sMMiCq9PpEIvF0NHRAZ1ej0IuB7VOB7lcDovTiVhfH/QsCx1ZwAUD4XS5eNUM8MKoHMchm8uhkErBYDDwPYfElfsMr7ZgNJtxrLcXCzs6eLFSkRfCQChiZYXusXI5lAwDTiY7aaSEvkgqjQYetxt2qxWpdBqhYBC94TBfXxSNwuFwQKPToaWl5aSXyV9QWkvEACgUClAS7TrwRpHlODCsoCzOcUgmEjCazWAZnoGXzWSQzWaRjEbxiQsuQHd3d1WPplr4VnpPSe/Xavey+Jkg3iRhxJHfhwuG4VXfzWYz5s6di1QqhWAwiIMHD+KDDz6A0+mkobzBjl9vNl01w10PTEljJPWMqknWjCfIl1koFGgOKCHkAFwuFxYsWMB30RwCOI5DSRCbJL8DGOD5VFvIxQ9nNYNca9En49SKpQ8WhhQv7NKcU7X8kPjYYhUGstBUKhXaTymRSECn01EvkohlischY4sNkXQe0tBjteshDVcqFAqcv2wZktks3jl4EHPnzYPT6cS+zk7kczlY7XZotFqYbTZkAwHEIhE4XC5kMhnks1m0trXxdTeVCrLZLLQGA8pCi3Kr1Yp4PA6OZaHTaqHTapHNZqEwGGCxWnnPKpUCI5NBq9XCLhCDHDYb+qJRFEslqNVq/voxgtqCTocunw8z29p475ITGHIAJR6QIlMoFLygabGIUrGIaCIBkL8xfF2VRq3GnLlzYbHbkUunodVo0BuJICV4RjaLBUaT6aQIq8gw5XM5qARDy4i+A3IPyRkG+WwWer0e4UgE5WIRckEkdN7MmdBoNP1Cz9Xye7VyisTQiI1StWcDqN0ltZa3NRwwDAOTyQSTyYQ5c+YgnU4jGAzi0KFDeP/996lhIm3CxWh6RpMYjQzTFQoF9Pb2guM4vP3227BYLHA6nVi0aBHUavWwj8cwvHqvXC5HqVSi6tjS0JXUOElfl+ZvgIHsoWox92phNPIeqXdTy/hJvaxq3pfUkyJU9pxQUOp0OjF79myqdyb1gqTHq8YOFO+Apeck3UlXyzMolUpcds456EulcOT4ccyfOxenLVyIHr8f5VIJeYYBWypBo1Si2+9HMpmERquF2+1GNpeDwWCATKFAOBiExWaDUsjRKRQKOG02hONxsJUKDAYDspEIOIMBhXyeJwMUCrDYbDAYjZR1p9FooFYqkYrFILNaoVKrqQqCWqVCPJ9HVCBUMDIZUoJkUKlYRIXlO8TKZDIqw6NSKCAXaMxOl4uncJNrJIwpA6BQKtE2bRpPc4/FwLIsjp84AZbjYLVYYLPbYRDaHTAcX8hqtVqpIZIJyuIceEHZvkiEbxmhVkNvMEBrt0MmkyEVi2Hm9On97jvxPSW+P8XkAqnXK81fSjchRBWh1oJfaxM1UjAMA6PRCKPRiNmzZ1PDdOTIEXzwwQdwOBzweDxwuVy8EsUYGMPJgI+EMRrvMF1e6OgZDodp/kImk2Hx4sVj1mGWaFhxHEcVE8SU02o5EGnNBPlbtQdLesNLF3TxAk48FunxquWPxLvTwYoOS6US1QmLx+O80rNQd7Jo0aIB86rl6YnnUS3MKDaa1XJSUq9ICo1GgzUXX4wHnnoKge5uuLxe2BwOFPJ5VPJ52J1OMHI5lFotjh05AjPDINbXh1g8jnKlAqPBAIVajQ8//BDt06ZBLngekMlg1OuRSqWQzWRQKpfh7+qCwWKB0WaDlWEQjUSQLxR45QeGQb5YRL5UglKjgb+7GwazuX+hKsNgz/79mO3x8AKkhQJsFgu0Oh31AMh7OYD2O8qk05TlVhE8F9oniSzs4CnbJpMJJqMR7e3tSKfTiMdiOHr4MMDwahZmiwVlQVGCYxiUSyXk0mnkcjmUKxWolUqUy2XMnTuXb3ch3OPZdBrTXC4olcp+njJ5Bsj3R75Xqfct/ozYkyffqZiMcCqMp2ciNkzEYwqFQjh27Bg1TKVSqa6RnUZhShojrVaLQqHQL6cy1l9mLpejOaBUKgWLxQKPx4PTTz8dKpUKr7322qjaAdcCwzB0J0dIDEB/z6Ta7l78eWkuRQxxiItA6m2IPycN60nzZdLWzWKUy2Ukk0nKJCSCru3t7dBqtQgEArRVBTk+0QmT7oSlc5eGWcRzlYYnidckvkbi40l3xkajEeuuuAIPP/ss4pEITDYb5BwHjcGASCgEi80GVCo8ocJuRzqVglajgcVigdlkgtVmQ28ohJzgOcmExn2lSgUyuRzRWAzxWAwOux3lcpkP0bEs5BoNckITP6vdDkbI+TAMA6fXi0QsBpvVCoVQXMrIZDCZzejt68PCGTOQz+dhMploTQ/I/cGfNFUVJ94QA0BBGJbC/UUYdADAlctQimjrRpMJRpMJ7dOmIZVKIRqNorOzE0mh0Fan08FoNPKhRqHQlnhpSpWKFsuyLAs5x6HF46mZQyQQ16JJDYa05GCksjxj7RkNBoPBAIPBgFmzZiGTySAYDCIcDuOtt96C3W6nHpNKparLfOqJKWmMxovanc1mqQFKp9OwWq3wer2UwSVGPUKDpDpcpVLVFF+UhsWk9FjxAl3NayKxemloS7rAk/dKjZR0gahUKkin07SWimEYGsbUC7UkYqMiDQ9KcwO1Qm/V8kTS70Q6V6nhkYYpxSGhlpYW3PDJT+LR55+HTC6HWq1GNpWCxWZDPJFALpOBp70dyUgE9pYWhATShVnIqzhdLqRSKShVKhRzOdjtdpRYFoloFK2trZg9cyYOHToEtVIJk6A3xwBgTSYU83mk02modTpYhHnptVqoVSrEolGYzGYUyuWTygZaLbpCIZi12pOtyTleGaFSqQCCF8QwDORCXqdSLoMRNlNE1od+B8KmoFypQKtQUMYew/K1RcVSCYViESq1GlahvbpSoaDXxWq38wQBhQJ9sRgsZjN/nwkkilQigSVz5gwI9Uo3UtL7oloOczA69lBRbwIBgV6vx6xZs3DkyBGceeaZSCaT6Orqwt69e2Gz2eDxeOB2u8fFMDXifKekMVKpVGMWpstmszSBnslkYLPZ0NbWBofDMaise70ZfHK5HCqVClqttl8YD6he1EnmKJ2zeNEVL74cd1LmpxYtWlwHJAbL8oKk4XAYfX194Di+rfmCBQuoorg0sSweTzxmtTCfdMEi75X+JJ8h41QznlJPr1qYj/y9tbUVX/jsZ/HQ009Da7VCpVQiEg7DbLejVKkgFY9DrtUikUjw7DeNBn2RCMxmMzSC9ptGo4FWrYbP50OFZdHW1ka14pweD7LpNAq5HKw2Gx/qAt+mW65U4vCRI1AL5ANOWMxlcjmOHTkCh8MBm91OO7Dm83l09fTA43bTWiGWO9m9lWNZnsnGMFRFgZHJqIgqIT8QD0khl6NQLEJbqaCQSCBfKPD0bI7j+xkZDFCrVGAAuD0eGg5MJJOI9fWh88ABgOOgVCj4vlrgw36ZVArtDgeMQlvxWkxH6fchvSfGUpankTkbcp/q9Xo4HA7MnDkT2WwWoVAIPT092LdvH2w2G+3XNJK89ETBlDRGJExHIJPJqrZFqAWiY0aKKO12O9rb209pgMSotVMbL4gXdGkYT6zILX6v+PfB/i5dEKrtSqUGAQBSqRStBWJZFlarFfPmzYNZ1KtG+lMaApQmqqWkA2nCWjqHWqG5WjmhWjmuajkzuVwOm82Gf7vhBjzy1FOI53JQKBRIJpNonz4dMrkcmVQKuWwW5VIJSrMZJpMJiWQSmUwGRrMZqUQCer0eGrUacrUa0UgEZpsNSqUSVrMZfcUijCYTYrEYlGo1TAYDwDBQKhSwWiyIRaNIRKO8bI9cDp1Wi7nz5yMaifBj6PXgZDJoNBrEBGLFtNZWqtJNfnIyGW1rIZPJaOty4q2A41AolZBMpVAoFKBWqxEJh+kGyGK18qKrDENrmirChojkmiCTwWwywWa1oqNSwcGDB8ExDN577z0AfEiw3elE+2mn9bsnqm0MpN8ZgKpdUscC9QzTVRsb6O+p6HQ6zJgxAzNmzEAul0MoFILf70dnZyesVisN5Q2VsTtRMCWN0XDDdBzH9TNAuVwONpsN06ZNO2UNQC3UI0wnHa9aSIuE8cStIsTvr7XQS6vPyWtioyN+jfwku7a+vj5UKhXYbDYqSCo2ANIFRhpiqxY+FD+Y1UgM0mOKw33ina3U0IiPQ3JS0gWIGKBq81Wr1bjl2mvxwiuv4GAwiHyphHfffRennXYazBYL5EolPnjvPRj0ejAmE4wGA2QMg0Q0ilQ2i0wyiekzZ/LegV7P07zlcliNRqjUalRYFg67HZlsFn3RKEwmE1RKJWTgjQXpojpt2jS+3gqA3W5HIpVCJBqF3WZDheOgNZkQSCYhl8vRKnSX5cj3R3JBwgYmmUohnU7zslLkPFUqgGFgNJngdrvBcRycDgf1elj+ywHD8jVM2UwGesF4QvD2SH4slU5DqVZDq9HAbDIhn88j2dcHrlTCnj174HK56IJKvkvphol8DyqBBj5eBqOR1GopGUkKrVaLjo4OdHR0IJ/PIxQKIRAIoLOzk+ax3W73sEpJGoUpa4zI4ksom1LDwHEcDR319vYin8/Dbrejo6MDdiGmPRrU2zM61XiEjUfqUcTFs1JIH3rxa2KSAnmdkDnC4TDK5TKsVitmzZoFs9k8IEwizcGIQ4FSL0caSpPOo9aOVer5SAkP0iJHaU2U1ACKFz5xLkscvpHL5fjUJZdgzwcf4H/few+MxYLjXV2wGAzQarUwmkw4dPQof33sdl6JwW5HKp9HOpXiteiMRsgVCthsNhQKBb63EcPX4KidTt6D0moRTyRQLBQQCYeh1ekwffZsREIhpLNZ5HI5/rrLZDAbDCiUSugLh2G12aDTapEslRDMZJA9fhxugSBRrlRQLpX4awaebq1QKuGw2/mFnnjGDIN0LseH9fiLxV8b8J4QEYqFcJxUKgWny8VfW4avu8tkMsjmcoj19WH6jBl8PoxlkYnFcOnZZ0Mul1Na/xFBWdztdg/og0W8oHoYiYngGQ3lPDUaDaZPn47p06dThi9RfzCbzdQwDaXIvhGYksaIXOx8Pt/PGBEDRHJAxWIRdrsdM2fOhN1uH1PZ94ngGdWCmCZOapeqJfalxycgBqi7uxvhcBiFQgEWiwUdHR28uGaNFhLkNakxEDPuxCFBsbDrYKE6AAM8n1qhP7F3Q+ZD6L9S5pb4uko9OvH5ieezbPFitHs8ePTPfwYrKCmUSyWYBEWGbp8PfdEoDFotrQdyulzoPnECBoMBRqMROoMBSrkcJpMJpUIB4XgcxVIJbo+HD0EJY8vlcr7ZnWAgZPzJo6urC2q1mq/JAsBVKjh8+DBUSiWKlQrsFguOJxJIpFJYMGcOTCoVX/Mk45v25fJ55HI5qDUaKuDKCLklhuNQAVAulahEEUOuiyikV65UUGFZ5LNZpHM5cOUyVBoNDHo9KpUKZs2eDZ3BAAZAvK8PS+fOhUajgUwmQ0tLC1paWlAqlRAKhWjBc7FYhFarhdfrrSubrFEEBjI2MDRjJIZGo8G0adMwbdo0FAoFhEIhhEIhHDhwACaTiRqmahJHjTrXKWmMiEtaKBRgMBj4Fs7pNHbu3IlSqQSHw4HZs2fDZrONqQESo94EhpEYP4Zh6ENN8ksktybNlzAMg3w+j76+PuRyOXR1dcFisaCtrQ02m62fJ0kW8GrxbvHficGpVg9Va/EXGyfp+8ReVrUkt5hkIQ39VVtwqo0t/ps0REnOyWKx4NY1a/D088/jWDgMu9MJm90OrVaLYqGAaDyOfKmEZCKB9vZ2qHU6tLjdyBcKKOXzCCQSUCuVtOeRwWikEkjZXA4Omw0GwfvhKhWEgkG+0R7Lwu3xwO1yIZPNIpfPw2AwwG6xwNXSgnAkgmPHjsGo16Nt2jRwAHzhMDpaWgClkq8hEkJp/fJxEg9VLhgbhVJJ65kYnNSry+fz6ItEoBYMrtvp5PsTVSrI5HJgZDIYDAa+I21fH86YPRsmk6mfx8lxfDFwR0cHZs+ejbfffhtqtRrBYBAHDhyAzWZDS0sL3G73kPO4I0UjCQxi4s1IoVarqWEqFovUMB08eBBGo5G2vhAbpkYYpClpjFQqFZxOJ772ta/B5XLh0ksvhVwux/z588fVAIkx0cJ0Q/k8yS8RAdZyuUwljcLhMNLpNMxmM5RKJbxeL1pbWwfklYD+Wl8k11KtoFYs0zTYoi99vda5io2M+DUxxMc7lTcpzXHVGkvcsJD8Ta1WY9011+C9Dz7AS//4B+KJBKZNnw69kO/J5nIwmc28px4OUxKD1mqFu6UF2Xwe+VwO4DjoDQbMMBpx4sQJLFiwAIViEWVBAshkNMLT0gKW49Dd1YVkIgGz2Qyr1QqFTIZUOg2/z4dioQCr3Y5Zs2Yhm8nQ2jhOLkfniROY4/VCS1QTCBNT8HJICI5heCFWuVyOQjYLTiZDMplEPp9HWXhdo1LBaDKhXCrBK7RXAMMre5c4DtF4HB6PB+FIBOlEAucvW0ZVzamxq9IlVSaTweFwoK2tDblcDsFgkNKcHQ4HWlpaqGLBWKORYTryLI3V+CqVCu3t7Whvb0exWERvby9CoRAOHTpE9TLb2toaQn6YMsaI4zi88cYbePrpp/H0008jFoshGo3i6quvxrx58+Dz+eB0Ous2n4kcpjsVWJZFJBJBMBikquJutxsLFiyASqXC3r17B/R3GUyJQeqNVGPekd/Fr4vzU7XGIu8Xj1PN8xFfJ3HeR+phiY8p9Xyk5yVOrJOxiadHxjlzyRLMmzMHL/3tb3j7wAFo9HrMnDUL2nweBw8exJy5c8HI5chlswgFgzhx4gQcDgc6ZsyA1Wrla3aExLRSLkcunYbDbgcnk+FEOo1YPA6lRgO9RoPW9nYkYjFwAGKxGDiWb6+h0ethtlhQyGYBju9vpBcYenKFAnq9HgeCQTh0OngF1QPCpmPAt1XP5/MolkqIxWJ8aE2hgMfthk6rhdFo5IkJ4MN48WQSOoOBek0cx1PLjx47BqPRCL/fD4NSiY+ffTbdjTMMMygdW/xdabVayiYjhaFHjx7Fhx9+CKfTiZaWlmGpYp8KjSYwjJchVKlUaGtrQ1tbG0qlEs0xeTyecRnvVJgyxohhGHzta1/D3Llz8eCDD2LNmjX47ne/i0WLFiEcDtfVMACNo3aPFKSvUm9vL2KxGBV1Pe2006BWq/vRxMVjAgNbZUgT/8DA3A1BNYMgXvyl9UEk5yOdg9TwiD0f6bWpNQ+pARJ7dORYRBtQfD5kJ18rlKfX63H1FVfgwmgUf9qxA+++9RYMFgusFgvfRFGng1arxdy5c1EulXDsxAm8u2cPtAYD7HY7jHo97DYb9AYDAn4/soUCdFotWIaB0WCAzWJBLp9HIpFAMpOBgeOg1miQTaf51hSlEgqVCjQ6HRi5HHGfDzKGb/OtUCiQTCQAAIFKBV1dXWhvbUU6meS/W/BFrkq1mi/ANRqh1migENQyxHkiDkCpUkEmnYbH40GhUEAyk0E2k0E8HkdbezvkAFwmE2YJrTeGKstTyzshhaGzZs1COp1GIBDAoUOH8MEHH9AGd06nc1TGZCJ4RuMNpVKJ1tZWqsDeCIybMYpGo/jSl76E5557DjKZDJ/5zGfwk5/8ZEDLbDEeeughbN++HXv27EEqlUIsFoPFYhnymP/7v/8LgL95xPp09c7fAJPDMyKtzUOhEG3s53a7MX/+/AFuujiMp1Kp+i3SYqNUzUsiEC/41XJDZBxpaIIYIUI0kHpZ1fJH1Qwh+b80NChlB4rPmbxfXKtFDE81OrF4LuI8kkwmg81mw02f+xzC4TD+8ve/42BPD7K5HC8OqtPxzLJSCW6nE0WjkW/DXSjgg2PHYDAaYbdYYDKbkU2lkMvlkE4modZoEIlGIWMYKDQatOh08Pv9SCWTMJnNAMtCplTyzevSaZTKZb6dSW8vdDod8rkcWI5DvlRCKZ+HzmBAtqcHsmIR7dOmwSCQDMj1CPf1nTxHwRBxQs6oXCrhRHc3GACBUAgarZaG2lq9XmjlcsydNg02oY5qOHTsoRgEg8GAOXPmYPbs2UilUggEAti/fz81TKTh4nAX20Z6Ro3MV9Ub42aM1q5di0AggJdffhmlUgnr16/HLbfcgu3bt9f8TDabxWWXXYbLLrsMX/va10Y1vrinUSOMUb3HHKonVqlU0NfXR2uBxC0ZhtI8DOBj+kqlEnq9vl9+SeyJ1AqRAf0LGaV/k7aRkBow6RhinCqnJCU4iI8n/hsAqmAhPqZMJqNhOOnxxcZVSi0niwl5j8PhwPVXX42+vj68/MYb+FCgfPfFYjDodFDL5VBrNIhGo8gUCrx+nUwGfzCIUk8PyqUSMuk0XB4PVEJhLSOTgUsmUalUEAwGoVSpUCgW+T5CSiVQKoFRKMByHLQ6HRKJBORyOYxmM0KRCLRKJXRKJcoAIokEYj4fjnV1oZLLQaNQ4JrPf56/P9iTCuLZXA6FXA7ZQgGs0J1WqVSi1esFI5Oh69gxBHt74TCZsLC9HbNnzx5UHXswDMc7YZiT7Rrmzp1LO69++OGHYFkWbrcbLS0tsNlspzxmLRJOvdAIQ9iocx0XY9TZ2YkXX3wRb775JpYvXw4A+NnPfoYrrrgC9913H7xeb9XPffnLXwYAvPrqq6OeQ6M9o4kUpmPZky0ZIpEI1Go1XC4XZs6cyXcDHcFYZHEgag8cx1E2ntgbqEbNrqVwUI3tJs7tDJZfIvMir9VavMQ5Hun5iCWUyOtiAwQMpNhWM77SGqZqbEGAb1X9L1deiXQ6jZdfeQUfnjiBuEDVNuj1cHs8yGQy6OnqQjabhcVshlmpBAMgbTLx6t56PSxqNRRCp9h4IoG2tjZwDAO2XIbZbEapWIRMrQbLcbSVt1wmQyadRiqbhVqjQaFUQqFQQKlQQDQcRqxSwQGfD/loFEwmg0K5jI7Zs2mjvGltbXC4XDDodHCbTMjncgiGQihXKtj91lsoplKYPWMGPnvZZfB4PKMmFow0VMYw/TuvxoUOue+99x4YhqGGyWKx1LxfgOFTq8cKjfTK6o1xMUY7d+6ExWKhhggALrnkEshkMuzatQtXX331eAxLQdhMjfSMGh2mY1kWsVgMoVAI4XAYSqUSbrcbZ555Jh96GcXup5bXQwxTNbUH8edqeVDi/I7YMEnHI69LDVE1j6dWfkn83bBCol/slZEQEpGWEZMuxEan1nWpVcgrnQ/L8rpjV115JT5ZKmFfZyf+9tZbOPT++0jk87DY7XC73Uglk5DJZLBaLFDrdHCzLPL5PLq7u9EXjUKr0cBoNAIcB5VeD7Vajd5UChWWhVqppArZcrkc5UoFcoYvYM0mk5ALbRxKuRzyQrsCPcNgqdkM16xZMNls0KrVyHMcAn19KObzKMrl6M1kUM7nEertRSIahcfhwMz2dlx+7rmYMWMGVETRewwwFnkbhmFgtVphtVqxYMECRKNRBAIB7NmzB3K5HB6PBy0tLVQthIxLPtsINI3RKBEMBuFyufoPJFSWB4PB8RhyANRqdcM9I9Lzp17jsSxL23KHw2HIZDK4XC4sXboURqNxzB6oU+WnpGoP4vol8nlxoavU6xGH7KRUbHEtSjUjJ52jNGwm/jy5J2w2G06cOIFwOEwT3iRnVs3LIvOuRksnn6lG6hDPQ2rQSFPGcqmEM+fOxYXLliGdyWDfsWPoCgTAchwi4TBiQm7ParXyuZiWFmQzGSSzWaSE+qWe7m60tLZCp9EgKzQnVKtUqABgy2UwAHL5PEr5PLKlErLd3QDHQSF0OLW53VArlSiVy/B4veBKJchIvrCvDyzL8tTzdBpWnQ4fX7YM565YAavVOqBL6lhhrEkEDMP3W7Lb7Vi4cCH6+voQCATw5ptvQqlUoqWlBR6PhwqPflSMUT2jOVIMyxjddddduPfeewd9T2dn56gmNFYQ69M1yhiJmWfjBY7jkEgkkBEYSzKZDG63G6effjqvhjwOD9FwyBLEMJH6JZJjktZOSPM5xDMSG6NqHka1h1XqyZCfUiVzkgdqbW1Fa2srotEoQqEQurq6YDAYBrSBruVxiXNO4rlV89bEcy4UCjR8mkgkYLVaqSI8mdu555wDgKdq7zt4EIeOH8eRnh4c8vvBMgxMZjN0ej3USiXSQohUoVDg2OHDKJZK0JtM0CqVYORy6AwGaIXF1Ww0oqTTQW82o1wowKDX80QEhuHp3wBiiQSvYiKTQQOglEjArlRi6ZlnYtXy5TCbzVCr1SPOAw0H48lok8lkcDqdcDqdqFQqiEQiCAQC2LVrFzVG2WwWJpNpXMYfDI1Qf5gUOaOvfOUruPHGGwd9z8yZM+HxeNDb29vv9XK5jGg0WjcOuzRnBNR3lzGeYTqO45BKpahUSqVSgUKhgNvtxrx588b9ZhqOMRJ/RhzGIx5TtTAIWdzFskLVFvNq36c0/EfGIschxyQ7eLGH4nQ6aWfNcDhMiwEdDgdcLteAgmkx60+a+5L+Tfx6X18fwuEwIpEI9Ho9XC4X5s+fT9UwxPMix7VarTh/1Sqcd/bZvGeSzSIQCGDfoUPwhUJIJBJQAVAqFChxHCpaLVRaLfK5HFKxGMrFIjiOg9ZohEaj4RmRwjjFUgm9gQAMej10KhWsFgscNhtOnzEDJr0eC2fPhlarhVqtxt69e2GxWNDS0jIuBaa1UC96tVwup+0YyuUy/H4/9u3bh3/84x/Q6/U0lDdUss9o0QzT1QDZPZwKq1atQjwex9tvv41ly5YBAF555RWwLIuVK1eObKbDhDRMB9T3ix1rb4zjTurqhUIhlEolOJ1OzJ8/H1arFZ2dndBqtXXb1YzGnZd6S8RgSHeB4pCaeEzxYk9eF4fgxB4p8VjEbDgxqoXcSM1Fa2srstksLao8ePAgnE4n3G43X+hZhaJOfkpZe8lksmr4dLBSB+kCLE6mGwwGzJ07F3Pnzu1HlsgJYblisYhsNotUJoNsPo90JoNkIoGkEMozm0xo83rhcbtpAzzCkqxGuSa1QITaX09DBDSm1kehUMDhcIBhGHz84x9Hb28vAoEADh8+DKPRSEN54yk82qR2jxILFizAZZddho0bN2Lz5s0olUq4/fbb8S//8i+USefz+XDxxRfj0UcfxYoVKwDwuaZgMIjDhw8DAD744AMYjUZME2oThgNpmA4YWJw5nhgrNl0mk6EeUKFQgMPhwJw5cwbs0utJmBhLpiBZ5IgXQ4RbSRgNGLiJqMaaqybJA5z0gKSGazCSg/g4Op2OSvSn02mEQiHs3bsXDMNQCRqdTtfveOQ4RNI/FAqhUqnQjraknxOBNG8mNq7kdyIaS45N8lLkb+QaGQwG6PX6qiww8vlMJoNAIIC+vj7EolEo5HK+yZ+wqBKavkKhoN6s9F6rNxphjMTjKhQKeL1eeL1eKuAaCARw8OBBmM3mATmmsUK9PSNp/raeGLftzW9+8xvcfvvtuPjii2nR609/+lP691KphAMHDiCbzdLXNm/ejP/8z/+kv19wwQUAgEceeeSU4UEpqoXpJgrV+lQQd5fNZrNDUhYfSehspBiPscgDr1AoaJGpuLOseEyxsZAaIOL9kP9LPydlt0mNF9mJSkkOAF9UaTKZMGPGDMpUfOutt2AwGOByuWiPHyKrks1m+4nySkN2Ug+PjE/eI85BVbuXxEW51c5HahzJP1IcOmvWLCQSCfT29uLDDz+kjEuPxwOj0dgvV1Yul+teriBGo4xRtZyNUqmkMjpEEZsU2JLmdh6PZ0yUxZthujGAzWYbtMC1o6NjwI39ne98B9/5znfGZHwxtZs8hI1gtw0VpP9IKBRCOp0ednO/ei4U4234iNqDRqOhoSPy3RGGnbT+SKoJJw7viUNn0vlLz0VKIZd6PCzLC4I6HA6aXwoGg/D7/Th69Cg4joNer6eK0tXaaYhzX+RntQVHfH7SvJP4b9L3iyE1StLzI1TnefPm0VDiu+++2+8cVCoVzXWl02lYrdaqLMjxRCM9o8GMgVgRO5/P03uhs7MTdrudtmoYqbJ4k003BTDcbq9jjaEs2ITOS9oDWK1WtLa2wul0DvvmradnBNTnpiWLHWFrlYQGcOQBFf+rlruRhtzEeRzyf+l5SEOA4nMVj8NxHKLRKFU012g0aBVUqvv6+nDs2DGk02m4XC5eHXuQsKA0PCf2jMSGRxyWrPZ9VzMOtTwv8n5xl1SDwUDDUCQ/cvDgQWg0Ghq6I6FJ4imJQ6DjaSwaHaYbCjQaDQ3pSpXFnU4nbQc+nHxbI9h0jcKUNUZizwhoTEuHasavWCxSplZCkPv3eDw4/fTTR+XW1zNnVI+xCKmgUqkgn8/T5DkxPmJGHpmT1BsSh9yA/jTvarkj8jnpT7FXJG7OyDB8rcrixYv5glPh/TNnzkQqlUIwGMS+ffv6MbRIfkk8N6lBIqjWeqOW5yb1mMixpIa6WnsGKcQsRBI+JTmwfD6PZDIJu91OPVRpkbL4+o0VGhmmG4lnMlbK4s0w3RSARqNBUlAeBhqrFVcqlaggaSwWo62UFy1aNGYJz3obo/Ew7GQxJT8JBXn37t1wuVzwer0090IeYqnag3jREl8PQgCoFraqFW4iC0E2m0UkEunXnn7evHmwWq0DvBoCs9kMk8mE2bNn0/olcX7J6XT2++7FC7p0TtJcl5TcIJVWIiDvl8lOqmPXWvxYlqX1NeFwGCaTCa2trf1CTOl0GsFgEAcPHkSpVKKq2FarlRowAP0M01gZkMngGdWCWFmcbFIOHjzYT8CV1JZJ0SQwTAFotVpKYADqr4hAJGbef/999PX10UVo3rx540IFrVeRLTD2xqgaE45Qv88++2xkMhn4/X58+OGHkMlOtqXW6/X91B6I0oNUf05KRKjlFZGxgZMbiGAwiFQqBZvNhvb2djgcDrqgSxlrUmNBFmW73U7zS0Sk9ujRo7BardQwiZmD0nCe1Kuvxr6Tjg+AsuBqqSJwHE85DwQCCAaDkMvlaGlpqSmaazAYMHv2bEp8CAaD+OCDDyCTyWhuxGg0UsIDmctYGKaJRGAYDYxGI4xGYz9l8X379qFcLlPyiFhZnLAlPwqYssaoEWE6sSJ2JBIBALo7Hu8iucnmGZHwjlQRgYSExLtBo9GIefPmYc6cOejr64Pf78fOnTthMpkopZbUxxCauFTtQTrfaotbuVxGLBZDb28v+vr6aOfLRYsWUTFYsYdCFlmpLJD4/+JxxTIzhPbd1dWFQ4cOwel0wuVy9VPNqGWQap2L2AgNFobL5/MIBAIIBALI5/Nwu91YvHhxP09vMDDMSfHRuXPnIhqNIhgM4u2334ZGo6GGSavVDggdjtQwTVQCw0jBMAOVxQOBAFUWJ4y8SqUy7m3VCcRh7kZgyhojMbUbGL8wHWEZSRWxHQ4Hjh07ho6OjjEfsxrqSWAY6VjVDBBhwZF/g0Es2yJmsZFiVHG/GlIfw7IsSqVSP2086ZwSiQQNwymVSrhcLsyYMQN6vb6q11SNcCCGlCQgHY9hGGg0GsrCInmozs5OKufkcrkGjE+OLfXEyPkSL7EaKpUKent74ff7EYvFYLPZMGPGDLhcrlHtvGUyGWUWkjFIfoRsFlxC91hxrg5AVaZhLUzmMN2pIDbu8+fPRywWQzAYxHvvvYdyuQyj0QiHw1FTWXyqYMoao2qe0ViF6Vj2pCJ2JBKBQqGAy+Xqp4idSCQmZZHtUDAcY1TLAyL1QCPddSqVSrS3t6O9vZ12+Ozs7ATHcTSMR1QS1Gp1P9HWcrmMTCZDiQgsy8Jut+O0006rqtgsJTeIr4O0xkeck6pmrMR/I+curl+Kx+MIhUJ4++23odfrqWFSqVQDwnFib7AaOI5DLBZDIBBAKBSCRqOB1+vFokWLBjRPHAuQMF9LSwuKxSJCoRCCwSAOHDgAm81GcyMkfye+PoMx8mpd/3qgETkbm80Gm82G+fPn48033wTLsoMqi08VTFljVM0zGs1izXEcXSjC4TAYhu+FcsYZZ1S9MerN3ptInhEJzYiN/1gYoFoQd/iMRqPw+/3YvXs39Ho9vF4vLUAsl8vUmyL1MrNnz6YK2AzTv625eLEkf5MW0kpJBuLzFbPwxJ6SuKhWXLgqk/HdYK1WK+bOnUtZl0eOHIHdbqf0YDEduxqIwkIgEEClUoHH48Hy5cvHVLn9VFCpVHSzQGjOx44dw759+yjxgaiqnIqR10hj1CiPDDhZb2e1WjFt2jSqLL57926o1WpqmEbbEkaMJoFhHFCNwDBcT4UkeIkcD8dxcLlcQ1LEbkRdUyNzRlImHHkfyQPVY3fJMCfbApTLZYRCIfh8Phw4cABKpRKlUok+2CR0RNQeiKJ3Ldkh8e5dGluvFmIUe4LSB1xMsJAuduR3hUJB8wbFYpHmIk+cOEEZWOJOpUSixu/3I5lMwul0Yt68eTVZWvUEoTkTSaVgMIjOzk6wLEuT9mazuSYj76PkGdUaXxyiFiuL/+Mf/4BGo6G5yMG0Dic6pqwxEgulAkM3Dhw3UBHb6XRi4cKFsFgsQ74x62kcyHiN8IxqMeHEkjz1BgmjRqNRpFIp6HQ6aDQaZLNZpNNppFIpGhoju0+VStUvjCcNI4lrfqQ5IeJNiVlwYo+pWnivGklB+j4ShjMYDLDZbJg9ezbS6TRlFgI8hbxSqSAej9Oi1SVLloyJFM1Yg2GYfmwykht59913oVAoqOKDwWDox8irF0u0GhrpGQHVjaFUWTwcDtM8HVHO8Hg8dVMWHytMWWM0HAUGjuP6CZIWi0W6s7TZbCNaUMWhmHrczPUOCxLqOjA4E65ekNKUCQV8xYoVtCCVhFr9fj9lfpEwHpEeEtPExfVLtTwm8d+qFZyK/1YtPCc2YCzLUgNEjLkYZDH3er3gOI6KnbIsC51OB7fbDafTOSENkRTS3Aih0e/evRs6nY6Gn/r6+hAMBqHX6wGgn/JDPZ6rieIZ1QIx4i0tLTQaEAwGcejQIZhMJhrKG48c4VhjyhojEqYTh1ikxogksUOhEPL5fD9Ry9Fy+6stUOOJ8fbExEQElUqFeDyOzs5OWkle75YCBKTFQyAQQLFYhMvlqklTZpiTbafnz59P2WWHDx+GzWaD1+ulVfFimnipVOrnLYmPJ851SMcSe0zScJOUUVirdQNBoVCgeaBsNkvp2DabjbLYSHsDq9VKWWyN+l6GA5mMb6nhcrmQy+Vw5MgRHD16FJVKBSqVCh6PBx0dHfS6jZSRNxJMRM+oFhQKBW19UiwW+0k6WSwWGvYda2XxscLEv1NHiFphulwuRz0goog9Y8aMfsWMY4Faie3xwniE6Wox4RwOB1atWkXbfRw4cAAtLS1obW2tS8yaMLUCgQCSySTdRAznOxQzv0jdzZEjR9DZ2Qm32w2v10vzgiSMR2ji4qaA0gJYoL8wa7VNAjFAxAMajI4dDofh9/sRjUZhtVoxffr0AUZG3N6AiHWeOHECnZ2d/fJLjc4d1QLHcZR40tvbC6PRiLlz58JqtdKk/d///nc4HI5+9H3x5kDshY6l8Wi0NtxI1w+VSjWosrhYBFeKJoFhjCGmdufzeWQyGWSzWXR1ddFq+vHc0Ys9o3pgrMJ0Q2XCKZVKzJo1CzNnzkQsFoPf78euXbto3oIUoo4VxEnbSCRCa1jGIj+i0Whogp0UH77zzjtQKpXwer1oaWmBVqsdQBMnvZeklG6gP4VbnBMiXlAtA0RCiYSOrVKp4PV6sWDBgiEpd4jFOsUV/hzH0ZBNPVl1gyGbzcLv9yMQCIBlWbS0tGDlypX9NjR6vR7Tpk2j+m6HDx/G3r17KfHBarUCOJm7rMXIGynGq+h1OOOP9hyqKYv39PRg3759sNvtE8aLZrhGltyOI/73f/8XN998M7RaLT72sY/hiiuugEajwemnn16XimaWZfHqq6/i3HPPrYtbHIlEcPToUdqocDgYKyacmNGVSqUG6MkNF+I6md7eXqhUqrolZ4nx8/v96Ovrg8VigdfrHfDQStUeqp0DCfkNFobL5XJ0YS6VSvB4PPB6vWNST0I8D3IdCfuqEbmESqVC75F4PA6Hw4HW1tZ+EjiDgeQGSSNOAFTxwWQy0feIjdJo8ktHjhxBJpPB4sWLR/T50eJ///d/sWjRItjt9jE/NglxB4NBpNNpOBwOzJgxA263uyGblSnlGRUKBTz22GN44okn8Le//Q06nQ7/+q//irVr16JYLCKfz9dNWkMcpqvXeMMdi6hijxUTTtx0TMz6kslkNIw0lN092dEHg0EqjXLmmWfWtdBPzFgqFAo09LV//35qZEleSqz2ICY9nEodmySc/X4/EokE7eIr1qobC4gp7+L80pEjR2gzOLfbPW47Y47jkEgk4PP5EAqFoNVq4fV6sXjx4mF7tQzDwGw2w2w295Mi2rNnD629IZsVad+nkRAfJjqBYTTQ6XSYOXMmZs6cSfUfG4kp5RmVy2X80z/9Ey699FJccMEFWL58OcLhMNRqNY4fP45MJoNFixbVbT6vvvoqVqxYUReKZTQaxYEDB7Bq1apB31ctD0TqWsaDCUfkknw+HyKRCPUwxI3nANDwAUnQT8RcB6H9EyKBOO9E2F5DOQbJg/T29g4ozK0niJENBALIZDIDJJVGC5KL8/v9KBaLY+rtSSEN4xqNRhp+IuoVYkM0VMNEFMrruW6I8corr2DZsmUDWtWPB8iaoNFopqZnFI1G8aUvfQnPPfccZDK+/fhPfvKTmonuaDSKu+++Gy+99BK6urrgdDpx1VVX4Z577jnlF6JQKPDCCy8AAGKxGAA+/KFWqyGXy+ta9wPUt9ZosJxRLSKCWBduPOdFivWKxSICgQCOHz9OPQy1Wo1EIoF4PA6bzVY1QT9RwDAnxS3nzJlDFz8i2kqMbDXvm3iKgUAAAKrmR+oNtVqN6dOnY/r06QMkldxu94hkZ1iWRTgchs/nQzQahc1mw6xZs4bUu2c0EHuyJFxMWjWQhD2Zw3A08iYrgWGkmNIKDGvXrkUgEMDLL7+MUqmE9evX45ZbbqnZktzv98Pv9+O+++7DwoULceLECWzatAl+vx9PP/30kMcleRrCqKu3IgIZs56FqOLzGy9NuNGASMRotVp0d3fThVmlUqGjowPt7e0TlnYqhZiOTNh9RO3B6XTC6/XCYDBQ+ngmk6EK4BPJ2yMQSyqRPB2pxSJ5usFCrMlkEn6/H8FgkLL7Fi5c2JD6FnG4WMouJJJK4hwMCauKa7uk9WKNQqONYT0xrmG6zs5OLFy4EG+++SaWL18OAHjxxRdxxRVXoKenB16vd0jHeeqpp3Ddddchk8kMecdcqVSgUCjwwQcfYPr06fD7/QiFQli6dOmIz2e4eO2116h00HgjmUzivffewznnnFM3TbihguQMCEOMhLfIAidWk7bb7WhtbZ0QMjYjQTKZxNGjR2kxqlqtRmtrK6ZPnz4hvb3BQKjlpLjWYrH0U+EuFosIBoPw+XzI5XKUEj9R1aWJFFEgEOjXP8hisQBA1fzSvn37oFAoMG/evIbM+cUXX8QFF1xQl1C/WFG+ERjXp2Pnzp2wWCzUEAHAJZdcAplMhl27duHqq68e0nESiQRMJtOwHmZyURvtGY33mGImHElO2+12WsfSyAWd0HEJQ4wIy0oXK5J3IYyygwcPYt++fWhpaYHX66UKChMVhOFFPAOlUomOjg5oNBpEo1EcP34c4XC4YbmhkYKoRHs8Hlqr0tXVhc7OTqhUKhSLRZjNZkybNm1cCRBjBWlzwEAggPfff5+ep7Q5IKlLNJlMDSl+lSp81AON3ESM690TDAbhcrn6D6hQwGazUVrmqRCJRHDPPffglltuGdbYDMP0K3xtRM5oPMN0UiacTqfDtGnTcPToURw5cgRerxetra1116ciu+VAIIBUKgWn04m5c+cOydPRarUDapd27949brVLowVRoyYJerfbjaVLl/YT0W1tbaU5DFIN73A44PV6J5X3Vy6XUSgUUCwWoVQqodFoqIyWWOtvInpEUjDMyf5B8+bNo5JDb775JrRaLaxWK9V8I3VbJNpQbykiMuZHASMyRnfddRfuvffeQd/T2dk5ogmJkUwm8clPfhILFy7Ed77znWF/XqxPV08yAcFYj1mrOR2JdZOYP2GvvfHGG7BYLGhtbR11E7XBIG6q1tfXB7PZjNbW1prJ/FNBrFs2b948Sn8+ePDgqGuXRotyuUzDioR0caoEvTiHQQo9Dxw4gH379lGG2UQpRBVD3HKDbCxIzQsp6iX5pT179tA6MFIkPBlACDYWiwVGoxHd3d3o6ekBwHtSZENHSA9iD2m8DVMjjNGk84y+8pWv4MYbbxz0PTNnzoTH40Fvb2+/18vlMqLRKDwez6CfT6VSuOyyy2A0GvHHP/5xRIuaWIVhshIYhsuEYxiGdt4kemZHjx7F/v37qWTPWIS9ahVSzp8/f0wXosFql0gYb7y9P/G5hkIhKuR5+umnD5twodPpaKiILORvvfUWtFotXcgbSeIgBobkWPV6PVpbW7F06dIBz6BU7JTkl44ePQqz2UwlZyaSNyuG9FyNRiNmzpwJt9sNlmX7ebN2ux0ej4fWgIl7UIlLIsZaighoekaDglB1T4VVq1YhHo/j7bffxrJlywDwvHmWZbFy5cqan0smk1i9ejXUajWeffbZESXUpDmjRoXpRjKmVJJnpEw4tVqNjo4OTJ8+HfF4HD6fj4a9Wltb4fF4hhXnF9fZiKvf69W4zWAwYO7cuVW9v2q1S6MFKQQMBAJUTkesAj4aSBdysvBVE22tB8QKEOVyeYDi+akgzi+JiQ0HDhygmnITJSxZKBQoa7dUKtWk2ZPmgESp4NixY1Tvj0gREW9pPKSIxBvQjwLGvej18ssvRygUwubNmym1e/ny5ZTa7fP5cPHFF+PRRx/FihUrkEwm8YlPfALZbBZ//OMf+xUTDvfhPP300/H1r38dn/rUpyjb7Pzzzx/zc6yFPXv20N3uqVCv7qilUokuFJlMBh6PB62trYM2CyS5kUAggHw+X7W5W6NAapf8fj9yuRwNe52q+eFgxyNhwXQ6PeaFoKdCLpejRbUkDzWa8xkMJLw6nkxGaddZUr80HuczGDiOo/JO4XAYVquVhq+Heq5kM0YkdIg6iMfjGSBFNBaGKZPJ4LXXXsPq1auH/dmRgGVZyOXyhhFsxp3+8pvf/Aa33347Lr74Ylr0+tOf/pT+vVQq4cCBA8hmswD4BXzXrl0AgNmzZ/c71rFjx9DR0THksScCm24wW9+I7qhKpZLu+AgD7J133qEU5JaWFqhUqn5J90QiQdXNxzP3NBKoVCpMnz4d06ZNG3A+ROT0VGEvlmVpAWs4HIbJZBpVzms00Gq1mDlzJmbMmIFEIkHPZ6zyMYRmT0JT5Dqddtpp4xIe1Ov1NCxJBGCJCC05n/EMs+ZyOfh8Pip14/V6MXfu3BFdQ2nRMwmzkvMhhkmv1/drDjhSjbx6F7w2WoxnSskBSXH++edj7dq1WLt2LbLZLHbt2oWPfexjdRv//fffh81mQ1tbW7/Xq2nCEQ9oPCR5TgWyQ+7p6UE8HodarUaxWKSSKm63e9IUowJD2/GTXS6hY49E2qdekNb7iFsADHVjQPKHfr8fhUIBbrcbra2tDWHA1VJgHyu2JMuy6O3thc/nQywWG7YY60jGE5+PXq+nVHHCOhQXzw6V+JBMJvHmm2/i4osvHvM5V0OlUqE6i43AxC4MGCXE1O56d14F+rPpTsWEa2RBajKZRCwWQzqdhlqthkajoZ1cS6VSw3dMw4XYsJCwF6ldIm1D+vr6kM/naZO6as34Jgqk9T6BQICKtpKwV7X5k0XS5/NRIzYRvFuxdI+4N5U4vzQSsdh0Og2fz4dAIEAbzY2XxyeGWI2jVCpRZilpdEiID9XaigxmmBot0lpvTGljJA3TASfjovUAw/DdPqXtueuhCXcqiKvRSSxfXCMjXsiOHTsGm82G1tbWMVeUHm9otVpMnz4dGo0G3d3dNFxDapq8Xu+EZXtVg5iUQjw7UrhJ2IWVSoWSEUhb6rFmOY4ViEQUIQoEAgEcOnQI+/btG1K+jCif+3w+pFKphm8ulEol7baaz+cRCoXQ3d2N/fv3w+FwUCmioTDyPkq6dMBHwBiJqd3A+BsjMRFBoVAgEAhAJpPRdr+NXMirqTTPmzevasJavNvL5/O0zkdMEZ9o4SwxxDUwoVCIUs/POOMMyOVySlI4fPgwnE4nWltbJwQhY6gQ5y/mzp1L9deOHTsGADCbzVi4cCHdkU8G6HQ6WvQsbXJIwngkH5NMJuHz+RAMBqHVatHW1laVft5IaDQaKkRL1EiIoSUkIIvFUpORV6lUJtXGb7SY0jmjtWvXoqOjA3fddde4NrurxoQjCwBh8KRSqSEx18YapEgzGAwiGo0O0BcbDki9jc/nQ29vb7/i1olCahB3D61UKrS7aa3ciFhNu561S2MB0o6CMMSMRmO/GhkizkrYgJPFKIkhzseQejZCDhDXzU2WcyOGlGySGIahoVZCLSdhvEAggK6uLpx77rkAxp/izbIslEplw2SdprxnRMJ0Y93sbqhMOFKwmUql0NPTgz179tCd3HjJ27As268glRRpjlZFWdykTdwO4sCBA9TQEoprPSHuMJtMJgf1+KSQ1i75/f5xrV0aCxC6tN/vB8dx8Hq9OPvss/t5qjNmzKCGdu/evWAYhubRGtm2YrggvbbEuRWZTIZCoYBCoYBcLge9Xj/hvqNaqNUc8K233oJGo6FU83A4jHQ6jRkzZqBcLo9J19pTodF+yZT2jG677TbIZDL84Ac/AMA3uzvrrLNGFV4aTBFhKESESqVCe9Cn02l4PB60tbWNmtVUbcdFvILxFBqVdvHU6XS0oHY8QyakaR+hYxP9OrfbPeo6ibGuXRoLSLvCkjYVQ2GIkc0J8aAMBgMNe01U0VbSmM/n86FcLlOtRfLskvySWISXhL0mi5ckRiKRwOHDhxGLxcBxHDQaDdra2uD1emlzwNF2rT0VKpUKVCpVwzyjKW2MvvKVryCZTOLHP/4xAL6f/NKlS4e9OI/WANUC8ZYCgcCIvSVSHR4IBChltxa7arwh1TIj9OGxXCDEdOzx3u1L1bhVKhWtxaoH1Z3jOMTjcVoTpNPpRq38Xc2LnCjqCFL231BIM7Xak0xEir4UlUoFoVAIPT09/cL4Wq2WUvkTiQRsNhv9jkhzQLEhGivD1Ogw3ZQ2Rl//+tfR09ODX/ziFwCG11+oVnvu8egNRBZxn883JG9JTIdNJpOw2+39OllOBBCjEQgEKMNopIs4IV74/X5ks1lqcOtJOKhWu0Qke8Z6ESeEEb/fj3K5TBepsfZwpeoIZBGvdw6G5Pl8Ph9kMhm8Xi+8Xu+w2X/Sep+J6gGm02m6CVWr1Whra0NLS0vVTShRPwkGg8hms3TzQO59cZuJ0WrksSwLlUrVsDVkShuje+65Bx988AG2bdsGAHjjjTewYMECWK3Wqu+vpgk3XgaoFpLJJHp6ehAMBmnIq6WlBQzDVC0UHIuw1HiCFGySAkQSXnI4HIM+MNUau3m93gnRkpzULhFjMRZ9l8j5+v1+RKPRcTV2UogFQ3t7e6HVaqkHNl4eoNS4E0bjWBEtqimINHLDJi4sTyaTI4oaiKWISDmGx+MZsLkeiRQRyX+r1eqmMRoP/OhHP8Lrr7+Oxx9/HADwj3/8A3PmzOnXcrgWEYEUpDYqdFEulymbJpfLAUC/MNFkYHtJQXbAYmkWEpYABkrVTPSWBLUUrocaaq0WBiQSRo3qtiltkUGMIgkRjRapVIoWppL7meRFxgtSvT/CMKxHKDuTyVAviCjQE8mtkYKEbwlBiRRFk9DkSPJLTWM0zvjpT3+KF154AU899RQAYPfu3ZgxYwbsdntNJhwxQo0E2QEFAgGwLAubzUYT9nq9nuaWGu0hjBTkXHw+H/Xy1Go1UqkUSqUSfbAaSRgYLqr1/qlVuzQRCRLVIPYAR/O9SMPQ45FLHArEJB8iAUXOaSxzjkSOqKenB4lEAi6XC62treNi/KREHsKclUoRnUojr2mMxhkPPvggfvvb3+K5554DALz11ls0FAA0XhNOjHw+Tw1QNpulMvVithR5qHt6epDNZvvlliYbxJXziUSCPiherxdtbW2Tin4sBWk94ff76Tl5PB7qGUYikQlNHZeimsd6Kg+uUSzLoUK6iOv1eppfGmloMpvNoqenB36/n+ZJx9vrE0NaU0h6SpGawsE8JvK3RhbmT2lj9Otf/xqbN2/GCy+8AJZl0dnZiWw2S28SpVLZUANEFuRgMIhYLEYFMIeSF5HmliaDt0SKNEl4Qa/X92snHovFaEGt0WikBbUT+ZwGA8uy6OnpoaFWmUwGu92O2bNnT1pjK81tWa1WmsuTy+XU6/P5fCgUCjSfNpE3TERPLhAI0O695Dk81UaBZVmEw2H09PQgFovB5XKhra2t4VqHhUKBri3JZJJKERHWZDVGHoCmMRovfPvb38b//b//Fz/96U/xyU9+EgqFglJHM5kMWlpa0NbWNq51OFLU2pERt3q4mAzeUjqdpjF7juP6sbaqoVQq0QWNhLEapTA9EpCeUaQnEpFVImGvXC5HQ1UTLTQ3HBBv3ufzIZ/PQ6VSoVAowGw2o62treGCrCOBtHcXIQlIw63ZbJa2ppDL5VSPbiKSiUhNVjAYRKFQgMvlgtFopJvAeDyOJ554Atu3b8dLL70Eh8PRkHlOaWP0wQcf4P7778eOHTtQKBRw4403Yv369Whtbe3nWZhMJrS1tcHtdo/LrqBaLcR4xKpJWCQYDPZLpjfCsyDdPv1+fz9ZGpvNNqxmZlINMkLgmAihHjGIVBJhpJEiXGlYaiKSFkYKQkH3+XyoVCrQaDTI5XJ161U0npB2NSZF5Gq1Gn19fYhGo3A6nWhra5s0mobic7rvvvvwwgsvYO7cuXj//fexaNEibNq0Cdddd13D7sMpbYwIyuUyXnjhBTzwwAN45ZVXsHr1atxyyy246KKLqMJxT08PSqUSWltb0dbWNibsLSKOWO8qccLE8/l8dfWWSMiC0M9JzHosmtSRAkGfz4dkMjmuSeHhQKyFx7IsDUsNZZPRSDr3SCEtTJX2iiJ/J7kxs9lMc2OTNdyayWRw5MgRhMNhWotDZL4mU58vgN9A/OEPf8C2bdsQjUahUChw4sQJtLS0YO3atfj2t7/dDNPVAxzH4ciRI3jwwQfxyCOPwGaz4eabb8Z1110Hi8WCaDSKnp4ehMNh2O12tLW1nbIeRgriEQQCAcqqIrHaeocsyC6ceIAGg2HMvSXxTj8UCtGWBeO5Kyaaa36/n/atqadnQQwjoT+PRfO28ahdGkuISRkymYzmXQe75tW8Y6/XOyk8CWJUe3p6EI1G4XA40NbWBrPZTDdcsVhsWPmlRoHjOBw/fhzbtm3DY489BqvViltuuQXr16+H3W5HPp/H888/jz179uB73/tew+b5kTJGYuRyOTz11FPYvHkz3n33XVxzzTXYuHEjli5dikKhAJ/PB5/PB4Zh0NbWNmg8mBS0BYNB9PX1jalHMFYg3lJPTw9yudyo82VEO8zv96NYLDZEG4x4Yj6fj3oW0o6uYwUpO4wUho62ZqTaOKOpXRpLkPva5/MhHo9Tb3QkxkSsjk5knLxe74ST7Mnn8/2efVILV83oihmwuVyuXyh6IhjbcrmMl156Cdu2bcOOHTtwxRVX4LbbbsMll1wyIT3vj6wxIuA4Dnv27MHmzZvx29/+FgsWLMDNN9+Mz372s9BoNAOYMu3t7bBYLADQTxmb9MvxeDwTskCToJq3RJh4p9rZEeqoeFdIwkqN3hXmcjm6c2dZli4io/XOpEaX1ATVg0xRrXaJiKOO59jiwlS1Wk09z7EwurUEbhtJ+eY4jnpBJPQ4nKgIx3HU2IrzS+MtUlwL4XAYjz76KB5++GHk83ncdNNNuOWWWzBt2rQJYSRr4SNvjMSIxWJ49NFHsXnzZoRCIVx33XXYsGEDZs2ahWw2i66uLhqmAECb5jVCz2ssQFhfg3lLJDFPjK5Wq6VhuIkYLyf0cZ/Ph3A4DIvFgtbW1mGFUaQe10QwutVql8ay7xK5FwjTtB69t6qJtg5ViXwsQLwg0oqDMOJGE+6t1b7F4/GMaxiZZVns2rULW7ZswTPPPIOVK1fi1ltvxac//ekJyfCrhqYxqgLSiO+Xv/wlnnvuOSxfvhwdHR14/fXX8cUvfhFnnXUWSqUS8vk8Wlpa0N7ePmFi+yOB1FsyGo1wOBy0DqqRIpqjQbFYpGyvYrHYrxlbNYhZyRtGhQAALL5JREFUbgqFgi74E4nlRjwL0g5iNA0OiawMCT2OR05xqBCLtrIsSz3QsX6uyGalp6cHkUgENpuNekFjbQClkYTh1BEOFalUCk8++SS2bt2KEydO4LrrrsOtt96KRYsWTZrnlKBpjGognU7jt7/9LbZt24Y333yTekCf+MQnsGHDBrjd7gELeHt7+4ROZJ4KpVIJPp8P3d3dyOfzYBgGNpsNs2bNGpLS+UTFYIsuy7LUIyD1P16vd1L0xZHKCg21dmm4RrqekObMSNuM0YYJxXlglmWpF1SvkHo1hZXhljoQcByHzs5ObN26Fb/97W/R0dFBadkT4TscKZrGqAYCgQCuvvpqXHvttVizZg1sNhueffZZPPDAA/j73/+OK6+8Ehs3bsS5556LSqWCQCCA7u5uSg8fi3xFPSCW3Q+Hw/3UwElhHzG2ZAGfrMYWOBmOOnHiBBWgNRgMmDZt2qSlH5P6EUIQqFa7JA1fSpUTJiJqibYOlfpOQsyEITuU/kj1gLh+ieO4IYf6i8Uinn32WWzduhW7d+/GZz7zGdx6660455xzJiQhYbhoGqNhguM4HDhwAA888AAee+wxeDwebNiwAZ///OdhMpkQi8XQ3d1Nb/729vZh08PHG+LFiwhGDtaQTKyIQEKTE2UnPRxI8y52u50a47FO1DcK0toli8UCpVKJRCJBW5RPlo2SGNVEW2sRSYrFIvWCKpXKhD1naT6WkKCkm4ienh488sgj+PWvfw2NRoNbbrkFN998M1wuV4PPYGzRNEajQCaTwRNPPIEHHngABw4cwOc+9znccsstOO2006rSw71eb0OT/iRU4Pf7qdTJcKT0Cb25p6cHoVAIRqORKldM5N31qRhpUgrzZKusl4IQMLq7uxGLxfqJ0E7GTYQY4vYJoVAIarWaEgRyuRx6enrQ29sLq9WKtra2hntBQwW5BwOBAHbs2IFnn30W5513Hg4ePIgdO3bgkksuwa233oorrrhiwj5ro0XTGI0BOI7Drl27sHnzZvzud7/DkiVLsGHDBlx11VVQqVSIRCJ0YRDTw+ux0Ilv8mrCliMF8ZZ6enqoIOZEUdseTa2OtLhzsDqTiYZMJkPZYeJiYLVaPeB6kDDeRKmDGwmIekpXVxey2Sz1dmfPnj1pDW40GsWWLVvwl7/8BYcOHUI6ncZll12GTZs2YfXq1ZMyjDxUNI3RGCMSieCRRx7BQw89hHg8jnXr1uHmm2/G9OnT+0nMq9VqtLe3o6WlZcxvMLJ7JItPNfd/LMeaKN4SqTUKBAKjVjGQyt5MlHyDFMOVSWpU7dJYgmw2iMK72WyGy+Wi50a8/slCROE4Dm+//Ta2bNmC3//+91i6dCm+8IUv4JprrsGRI0fw+OOP46mnnsLu3bv7NQadamgao3FCpVLByy+/jAceeAB/+ctfcPHFF2Pjxo249NJLAQChUAjd3d20pmMs6OFEnZcsxiQxWi+160Z4S9L21eOhwkAEQf1+P6W5t7a2Nkw9gOT8CLlEo9FQz284+a7xrl0aa5RKpQEswLa2tn7fg7SBHpGn8nq9E64YPZvN4umnn8aWLVtw8OBBfP7zn8emTZuwdOnSqs3vJrpRHS2axmicwXEcurq68NBDD2Hbtm3QarW4+eabcf3118PpdCKZTKK7u3vE9HBSOBgIBJBIJOBwOGib6Ebt4KXekslkGnEtzGDHJ56fWq2mYafxzMmRhDNhpI31eZ0K4sJUIoA7Fq01atUujWU9zEghpeUThf3h9Boiwr0Wi4UyRRt1XhzH4dChQ9i2bRsef/xxtLS0YNOmTVi3bh1VdvmoommM6ohisYjf//732Lx5M3bv3o2rrroKGzduxIoVK4ZFD68mqUKSuBONCSb1lkgOZiTeUqFQoIyqQqFA62oa0eeIiICS8xIbhrGENP813k0HyXmJ664a0XdprL1sqWgrIe/Ui6RSKpXwwgsvYOvWrXjttdfwz//8z7j11ltx4YUXTqiwbyPRNEYNAMdx+PDDD/HAAw/gN7/5DTo6OrBhwwasWbMGer2+Jj1cqn9F8kATgTRwKlTb4Q7Fq5DmbiZafYy059JYtdcuFAo0hFYqlWhosF7f9VBql8ZjzHrkH8VlDeMp2spxHILBIH71q1/hkUceAcMw2LBhAzZs2ACv1zvlw27DRdMYNRjJZBKPP/44Nm/ejK6uLnz+85/Hhg0bMH/+fBQKBXR2diIWi4FlWQCY9LRjAANaU1fzlsQLoVwup/mMiRb3F4PIJ/l8PqRSKZpEHyp1nni8Pp8PkUgEVquVhssauXse775LYo3EetaxSSMMRqORRhhGs5FgWRavvfYaHnroITz//PO44IILsGnTJvzTP/3TpGYvjjeaxmiCgGVZvP7663jggQfw+9//HnPmzIFarcb+/fvx+9//Hi6XC+l0mkr5t7W1Nbyx3GhBvCVSG2IwGKDX65FOp2koZTiL+URCOp2mytdKpZIa02o5rVwuRynZAKhxnoiGV0zmICSZkRiO0ajHjweIQRT3IWtpaRmWaGsikcD27duxdetWhEIhrFu3Drfeeivmzp076e7fRqBpjCYQ9u7di5/97Gd44oknoFAo0NbWhkwmg8985jNYv3492traBtDD29raJnW9iFS4kmEYGjqZNm3ahOt3M1ywLEsLamOxGG3EZ7VaafhR/Hq9FKtHC2nYldQunSpvSejXPT09yGazo+6rNR4gLMNAIEDlemqVCHAch/fffx9btmzB7373OyxYsACbNm3Cv/zLv0z6e7feaBqjCYS//OUvePbZZ7Fu3TqcffbZqFQqeOGFF7B582bs2LGjX7t0juPGhR5eLxCVZiLfL6YVi2tIhsOemujIZrM4fvw4gsEgKpUK3XBMmzZtQrbjGCpIeLJaKwjiEYi9IJ1OR72gRrP1BoNYrocYXJ/Ph7PPPht2u522737vvfewZs0abNq0CStWrGh6QSNE0xhNAnAch6NHj2Lz5s20XfpNN92E6667DjabbQA9fKJK9IgXrUQiccr+NSS31NPTQ5P40rqSyQBpLsnlcsFgMCAej1NSxkTIDY0FxLVLAGAymZDP55HL5fr1SJpsIN/hhg0b8MYbb8BgMECr1eJf//VfsXHjxilZjPqLX/wC//Vf/4VgMIgzzjgDP/vZz7BixYqa73/qqafwrW99C8ePH8ecOXNw77334oorrhjyeE1jNMlQrV36hg0bcOaZZ9LW4oQe7vV60dbW1tAiRqkaBGkJMBwaerWKe8LEm6iLt5Rlp9VqqTcgDqkS1pzP56OqEfVkzY0HUqkUuru7EQgEIJPJUC6XYTabqYc7kb2haiDtu7du3YpXXnkFV1xxBYxGI9544w3E43F885vfxL/92781eppjiieffBLr1q3D5s2bsXLlStx///146qmncODAgaoCrW+88QYuuOAC/OAHP8CnPvUpbN++Hffeey/27NmD0047bUhjNo3RJIW0Xfr8+fOxYcMGfPazn4VWqx1ADyeikfUKIVRLdBOV5dFA3IuHGNxGqiFIIVY4J91zSYJ/sGtf73qisUalUqH1SalUCh6PB21tbTCZTP2KdSdTz6je3l48+uijeOSRR5DP53HzzTfjlltuQXt7OxiGAcdxeO2111AqlfDxj3+80dMdU6xcuRJnnXUWfv7znwPgc5/t7e340pe+hLvuumvA+9esWYNMJoM///nP9LWzzz4bS5YswebNm4c0ZtMYTQHE43H8+te/pu3S165diw0bNmD27NlUTr+npwcMw9Bi2vHIUYw3BVgMsngTJp7FYqE773p7S1LPbbTKDNJ28GOltDAeSKfT6OnpQSAQoLJEtQg1jahdGi6mQvvu0aJYLEKn0+Hpp5/GVVddRV+/4YYbEI/H8ac//WnAZ6ZNm4Y777wTX/7yl+lrd999N5555hm89957Qxp34m+5mjglLBYL7rjjDnzpS1/C3/72N/zyl7/EihUrcP7552PDhg24/PLL0dHRgUgkgp6eHhw9enTM6OEkHEWKCMkCs3DhwnFdYEgXWpvNRr2lw4cPY//+/XXzlvL5PPWCyuUyvF4vzj777FGPq1Qq0d7ejra2NqpBt2fPnhFr0I01iDhrT08PradaunTpKVUaGIaByWSCyWTCnDlz6MblyJEjDReirda++6233pqU7btHi0gkgkqlArfb3e91t9uN/fv3V/1MMBis+v5gMDjkcZvGaApBJpPhYx/7GC666CL4/X5s2bIFX/3qV/HVr34V69evx4033oilS5fSDq7vvffeiOnh1VpeD2VBGg+oVCp0dHRg+vTp1FvauXPnuHhL1dS858yZMy6LqHjxnjt3LiVBHDp0CE6nE62trXUtfia1U+KygqVLl46orEAul8Pj8cDj8dCQ7qFDh9DZ2Tni2qXholr77ttuuw1r166dNKzUqYSmMZqCIOG473znO/jGN75B26Xfe++9uPLKK7Fhwwacd955mDVrFt3hHj58+JT0cLIQ+/1+Kjw5ffr0CcPcO5W3NBoyBzHg4j5H8+fPr1thqliFgvQt+uCDD6BQKOjr4+GJsixL7xHSomLJkiVjmu/RaDSYOXMmZsyYQckuu3fvHnLt0nBRrX33888/P2Xad48WDocDcrkcoVCo3+uhUAgej6fqZzwez7DeXw1TOmcUjUbxpS99Cc899xxkMhk+85nP4Cc/+UlNplI0GsXdd9+Nl156CV1dXXA6nbjqqqtwzz33TEo6qhikXfrmzZvx6KOP9muXbjabaR1IIBAYQA8nmniEHUW0vCZqqwExxErbpAPoUGnU1TrAksLUiRC6IarUPp+P5ujGqn2GuFGfUqmk3nO9woNDqV0aDkj77ocffhi//vWvodVqp2z77rHAypUrsWLFCvzsZz8DwN9r06ZNw+23316TwJDNZvHcc8/R18455xwsXry4SWAAgMsvvxyBQAAPPvggSqUS1q9fj7POOgvbt2+v+v4PP/wQd999N2688UYsXLgQJ06cwKZNm7B48WI8/fTTdZ79+KFau/SNGzfi9NNP70cPz+fzUCgUKJfLcLlc8Hq9k1oTT0qjrqWMTvI0JMne2toKr9c7oRPYpLGg3+8Hy7I0bzacDQNRi+jp6ZlQslPSvkvDETatVCp49dVX8dBDD+F//ud/cOmll2LTpk1Tun33WODJJ5/EDTfcgAcffBArVqzA/fffj9/97nfYv38/3G431q1bh9bWVvzgBz8AwFO7L7zwQvzwhz/EJz/5STzxxBP4/ve/36R2A0BnZycWLlyIN998E8uXLwcAvPjii7jiiivQ09MDr9c7pOM89dRTuO6665DJZCYFxXY4kLZLX7x4Mc4//3y89957sNvtuOmmmyCXy5FKpWC32+tODx8vVPOWWlpaaBvrdDpNWydMdPqxFEReifRcslgs1BOstfiSEKTP56OqEBPR+Fbru+T1eqvS36PRKB577DFs27YNiUQC69evxxe+8AXMnDlzUn2fjcTPf/5zWvS6ZMkS/PSnP8XKlSsBABdddBE6Ojrwq1/9ir7/qaeewje/+U1a9PqjH/2oWfQKAA8//DC+8pWvIBaL0dfK5TI0Gg2eeuopXH311UM6ztatW/G1r30N4XB4vKbacBw5cgQPPPAAtm3bhlwuh/nz52PVqlW4/fbb0dHRUVd6eD3BcRwikQiOHDmCVCoFhmFgtVoxZ86cMe9L1AiQvBnp/ySueSIhvp6eHsRisUmnBi/tu/SXv/wFH//4x2G327Ft2zbavnvTpk209q6JiY0pm60LBoMDYsEKhQI2m23IdMNIJIJ77rkHt9xyy3hMccLgc5/7HI4ePYpHH30U8XgcP/zhDxEIBLB06VJ89rOfxV//+ldMnz4d5513HubNm4d4PI6///3veP/99xGNRjHZ9jPFYhEnTpzAzp078eGHH8JisWDFihVYunQpFAoFdu/ejbfffhuhUIi27piMICzDVatWYenSpahUKti1axf+9re/4dVXX8XBgwdhs9lw/vnn44wzzpgwubChQKVSYdq0aVi1ahUWLFiAI0eO4MYbb8Sll16KAwcO4I9//CNee+01XH/99VPSEP3iF79AR0cHNBoNVq5cid27d9d87969e/GZz3wGHR0dYBgG999/f/0mOgxMurjTXXfdhXvvvXfQ93R2do56nGQyiU9+8pNYuHAhvvOd74z6eBMZu3bt6hfmuOyyy7B69WraLv22227r1y79zDPPpAnu999/HyqVasKrh0tDcxaLBTNmzBgQvrLb7TS3dOjQoX51S5OBsFENHMehWCyiUCgAANRqNSqVCnK5HLLZLHK5HFQq1aQxRED19t3/+Z//CZvNhieffBJXXnklfvSjH/UrwpwqePLJJ3HnnXf2k+pZvXp1TamebDaLmTNn4pprrpnQskWTLkwXDofR19c36HtmzpyJxx9/fMRhulQqhdWrV0On0+HPf/7zhKkObxTE7dJ37dqFq6++mrZLJ+rhpACSiJlOlDAXqWHx+Xw0sT/U5DcxYD09PVRWqZGFmcMF6ZPk8/kgk8koEYPcz2KihlqtptdmouWKxBhq+25CUpk+fXoDZzs+GK5UjxgdHR348pe/PCGN9KQzRkMFITC89dZbWLZsGQDgpZdewmWXXTYogSGZTGL16tVQq9V44YUXJu1ueDwgbZc+ffp0bNy4EWvWrIHBYBiUHl5PSAtTx4LyTLylnp4eatTa2tomXAiIJPl7enrQ19dH+yQ5HI6ans9Ep7A323efxEikesRoGqMG4fLLL0coFMLmzZsptXv58uWU2u3z+XDxxRfj0UcfxYoVK5BMJvGJT3wC2WwWf/zjH/vtnp1OZ5MKKkIymcRvfvMbbN68GcePH6ft0hcsWEDp4T09PSgWi3VTDxdTgKt5AmMBKVttonhL+XyeekEAKMlkuOcuvYaNbPderX33rbfeiiuvvHLChoPHG36/H62trXjjjTewatUq+vr/9//9f/jb3/6GXbt2Dfr5iWyMJl3OaDj4zW9+g9tvvx0XX3wxLXr96U9/Sv9eKpVw4MABZLNZAMCePXvolzl79ux+xzp27Bg6OjrqNveJDpPJhFtvvRVf+MIX8Prrr2Pz5s0477zzsGLFCmzcuBFXXnkl2tvbqTzPG2+8QdXDx6Iok4DopPl8PiQSCbhcLpx22mnjxgpjGAYOhwMOhwOFQgE+nw8HDx7E/v37qQGo18JN2IA+nw+RSAR2ux0LFiwYVbdYvV6POXPmYNasWfTYx44dq6vRjcfj2L59O7Zt24ZQKIQbbrgB77//frN99xTHlPaMmqgvQqEQtm3bhi1btiCfz+OGG26g7dIJPdzn84HjOLS1tY2KHi7uFaRWq6ladCPyHdLW6eNhdMWQ5sHG2whK24GMhxCttH33woUL8YUvfKHZvluCZpiuiSaGAdIu/YEHHqDt0jdu3IiPfexjAEDVw6PR6LCq/MV9cUirddI5dKLsmMfLUFQLD46nwas1B8JIDIfDo26VAfDX6w9/+AO2bt2K999/v9m+ewgYrlSPGE1jNIVR79a8kwnidum/+tWvYLFYcPPNN9N26dlsFj09PfD7/TXp4aRTrM/nQygUgsFgoG0UJrIixlh5S2IJo0qlMmGIE+Ki03w+309p+1RGhOM4HD9+HNu2bcOjjz4Km82GW265BevXr5+S7bvHGsOV6ikWi9i3bx8A4IorrsDatWuxdu1aGAyGAemIRqJpjEaBRrTmnayQtkv/7Gc/i40bN+LMM8/spwxN6OFut5tSj4vFYj/1gMkGsbfEcRwNc9UyKFJKudVqpVJME41SLm2vrtPp6GZBSjIQt+/+61//issvvxy33XYbLrnkkgl3XhMdw5HqOX78OGbMmDHgGBdeeCFeffXVOs56cDSN0SjQiNa8kx0cx+Gdd97B5s2bsX379n7t0lUqFZ577jk4HA7k83nI5XK0tLRg1qxZE7r2ZaioRjgQU86JfE9PT8+gQq4TFURpm7QeJ6SDZcuW4fHHH6/ZvruJJoCmMRoxGtWadyqBtEv/+c9/Dp/PB51OB47j8Ic//IHKDtWbHl4viKnYLMtCpVIhm802tH36WCKZTOLf//3f8ac//QnlchktLS34j//4D6xfv35KbCwGw3BC91u2bMGjjz6KDz/8EACwbNkyfP/73x801D9VMXnv9gZjsNa8tbTvxqI171TC4cOH8Ze//AUnTpzA0qVLsXz5cmQyGdxzzz149dVX0dLSglWrVmHx4sXI5/N44403sGfPHvT29k5qzTiA78qrUCggl8vBsixYlgXHcZDL5ZO6ni2VSmHr1q34xCc+gT//+c+47rrr8N3vfhezZ88ekkLAZAeR6rn77ruxZ88enHHGGVi9ejV6e3urvv/VV1/F5z//efz1r3/Fzp070d7ejk984hO0XuyjhImbAW5iykMul+PCCy/Eww8/DK/XC47j4Pf7sXXr1gHt0k8//XRKDz9w4AD2798/anp4vUHIGD09Pejt7YXJZMLMmTOpPh7xloi24kgLV+sN0r57y5YteOKJJ6q27/7qV7+KY8eOwe/3N3i244sf//jH2LhxI9avXw8A2Lx5M55//nk8/PDDVQ3xb37zm36/b926Fb///e+xY8cOrFu3ri5znihoGqMRolGteacSli5diqVLl9LfSXuKu+++G1//+tf7tUv/1Kc+hY0bN+K8885DR0cHpYcfPXp0wjSBq4VSqUQVKQqFArxeL1auXDmg47BGo8GsWbMwY8YMysQ7duwY7SU1mKRPIzDc9t0zZsyomkifKigWi3j77bfxta99jb4mk8lwySWXYOfOnUM6RjabRalUgs1mG69pTlg0jdEIoVKpsGzZMuzYsYPmjFiWxY4dO3D77bdX/cyqVauwY8eOfjmjl19+uZ+sRxM8lEolPvOZz+DTn/40bZd+7bXXwuPx4Oabb8a1116LM888k9LDJ5p6OMdxSCQS6OnpQSgUgslkQkdHx5BqcmQyGZxOJ5xO54Tzlmq173766ac/8u27Bwvd79+/f0jH+I//+A94vV5ccskl4zHFCY2mMRoF7rzzTtxwww1Yvnw55ftnMhnqokv5/nfccQcuvPBC/Pd//zdtzfvWW2/hoYceauRpTGgwDIP58+fj/vvvx/e+9z088cQT2Lx5M+6++26sWbOGtkufNWsWpYcfOnSoYerhxAsi9TctLS1VvaChQuwtieV56u0tVSoV/PWvf8WWLVto++6tW7fi8ssvn9Q5romEH/7wh3jiiSfw6quvTvjQ7HigaYxGgTVr1iAcDuPb3/425fu/+OKLdGfU1dXVL1xxzjnnYPv27fjmN7+Jr3/965gzZw6eeeaZKV9jNFbQ6/W4+eabcdNNN9F26R//+MdxxhlnYMOGDbj66qvh9XqRSqXQ3d2NN998sy7q4aTWpqenB8FgEEajEdOmTYPH4xmzMWUyGVwuF1wuF3K5HPx+Pzo7O8EwDK1bGo8FTNq++6abbsJPfvITzJgxY0KFDCcCRhK6J7jvvvvwwx/+EP/v//0/LF68eDynOWHRpHY3ManR19eHRx55BA899BBisRjWrVuHm266CR0dHeOuHi4+fi6Xo95YvQpzpa0yhtIuYijgOA5vv/02tmzZ0mzfPUyMRKrnRz/6Eb73ve/hf/7nf3D22WfXc7oTCk1j1MSUAMuyePnll/HAAw/ghRdewMUXX4yNGzfi0ksvhUwmo+rhvb29sFqtaG9vH7GuWyKRoIoDer1+QsgTkUZ6fr+fEkGG2z4jm83iqaeewtatW3Hw4EFce+212LRpE5YsWdL0goaI4Ur13Hvvvfj2t7+N7du349xzz6XHMRgMIw7tTlY0jVETUwocx9F26du2bYNWq8VNN92EdevWwel00rYPw1UPL5fLCAaD6OnpQTabhcfjmVAdbQmIt0SEaB0OB9ra2mo2yqvWvnvTpk1Yt24dLBZL/U9gCmA4Uj0dHR04ceLEgGPcfffd+M53vlPHWTceTWM0SdGs8j41isUi/vCHP+CBBx7Arl27cNVVV2Hjxo1YuXIlGIZBOBw+pXq4OBek0+nQ1tbWcC9oqJC2HXe5XFCpVJgxYwZt371lyxa8/vrr+Od//mfcdtttuOCCCya18kMTkxfNu24SolnlPTSoVCr8y7/8C1599VW89dZbsNvt+PSnP41zzjkHDz/8MHQ6Hc4880ycc8450Gg0eP/997Fz504cP34cXV1d2LVrF958801wHIdly5Zh5cqVaGtrmxSGCAC0Wi1mz56N888/H/PmzcPOnTuxZMkSnHvuuZg1axa++tWv4qKLLsKxY8fw5JNP4qKLLprShugXv/gFOjo6oNFosHLlSuzevbvme//whz9g+fLlsFgs0Ov1WLJkCR577LE6zvajh6ZnNAkxXIFWKSqVCqxWK37+859/5Kq8U6kUHn/88art0nft2oVwOEzzLGazGbNnz570BYji9t1vvPEGPB4PTpw4AYvFgo0bN2LTpk2T/hxPheEq7L/66quIxWKYP38+VCoV/vznP+MrX/kKnn/+eaxevboBZzD1MXW3QVMUpMpbXBTXrPIeOoxGI2699Va88847eP755xGLxbBq1SrMmzcPl19+Ofbu3YuzzjqL1ga9++672LVrF/x+PyqVSqOnPyzE43H88pe/xFlnnYVrr70W06dPx9/+9je888476O3txX//93/j73//O3K5XKOnOu4Qy/QsXLgQmzdvhk6nw8MPP1z1/RdddBGuvvpqLFiwALNmzcIdd9yBxYsX47XXXqvzzD86mBzxhiYomlXeY4NSqYSnnnoKL730EmbOnIkFCxZQfbVisYj169djwYIFmDNnDgKBAI4fP44DBw5QevhEbYVdrX33v//7vw9o361UKvHpT38an/70pxs42/pgtDI9HMfhlVdewYEDB3DvvfeO51Q/0mgao48YPupV3gQqlQo6nQ7PPfcczj33XDAM069d+umnn47Vq1fjlltuwUUXXYT29nbE43F0d3dj586do6aHjzWqte/esWNHs303Rr6BSyQSaG1tRaFQgFwuxy9/+Utceuml4z3djyyaxmiSoVnlPTZgGIbWehDI5XJceeWV+NSnPoWjR4/iwQcfxE033QSLxYKbbroJ119/PRYvXkxbgRP18EbpxXEch2PHjmHbtm147LHHYLPZ8IUvfAHPP/98s333GMBoNOLdd99FOp3Gjh07cOedd2LmzJm46KKLGj21KYnGb+maGBbEAq0ERKB1MMHVH/3oR7jnnnvw4osvYvny5fWY6qQFwzCYNWsWfvSjH6Grqwvf+ta38Oc//xlz587Fpk2b8OGHH6KjowPnnXceFixYgEQigddeew3vvfceotEoxpsTVC6X8fzzz+Mzn/kMli1bhuPHj2P79u3Yv38/vvKVrzQNkQQj3cDJZDLMnj0bS5YswVe+8hV89rOfHbCBaWLs0DRGkxB33nkntmzZgl//+tfo7OzErbfeOkCgVRwfv/fee/Gtb30LDz/8MDo6OhAMBhEMBpFOpxt1CpMGWq0W69atw2uvvYbXXnsNGo0GV1xxBS644AI89thj0Ov1lB6u0+koPbyrqwulUmlM59Lb24v77rsPixcvxh133IHly5fj0KFD+MMf/oBPfOITEyJcOBEx0g2cFCzLolAojMcUmwAArolJiZ/97GfctGnTOJVKxa1YsYL7xz/+Qf924YUXcjfccAP9ffr06RyAAf/uvvvu+k98CiAWi3E/+clPuAULFnAWi4W7/fbbuXfffZdLp9NcMpnkDh8+zP31r3/lnn32WW737t1cIBDgMpnMiP6lUinu5Zdf5j73uc9xarWau/DCC7knnniCKxQKjb4MkwpPPPEEp1aruV/96lfcvn37uFtuuYWzWCxcMBjkOI7jrr/+eu6uu+6i7//+97/PvfTSS9yRI0e4ffv2cffddx+nUCi4LVu2NOoUpjyadUZNNDFCsCyLv/3tb/jlL3+JZ599Fueddx42btyIyy+/HEqlkqqHEw279vb2IauHp1IpPPnkk9i6dSu6urqwdu1a3HrrrVi0aNFHnpAwUgxHpueb3/wmnnzySfT09ECr1WL+/Pm44447sGbNmgaewdRG0xg10cQowYnapW/duhUAcOONN2L9+vVwu91U1667u5t2eq1GD+ck7btnzJiBTZs29Wvf3UQTUxXNIHMTw8JwJFXEeOKJJ8AwDO2KO5Ugbpd+9OhR3H///fjHP/6BBQsWYN26ddi5cydaW1uxatUqLFmyBIVCATt37sSvfvUrPPbYY0in03jqqadw+eWX47zzzkMmk8ELL7yAPXv2YNOmTVPaEDXvpyYoGhkjbGJy4YknnuBUKhX38MMPc3v37uU2btzIWSwWLhQKDfq5Y8eOca2trdz555/P/fM//3N9JttgsCzL7d+/n7vjjjs4q9XKzZ8/n7vvvvs4v9/PZTIZrq+vj/vP//xPzuFwcHq9nrNYLNxdd911yms5ldC8n5oQoxmma2LIGIkmXqVSwQUXXICbbroJf//73xGPx/HMM8/UcdaNRyaToe3SOzs7cf755yOfz+P111/HpZdeijPPPBNvvvkm/vrXv+Kqq67C9u3bPxKtvJv3UxNiNMN0TQwJI9XE++53vwuXy4Wbb765HtOckCDt0nfv3o0dO3YgEAjAZDJh//79+POf/0zrvzo7O7F69eqPhCFq3k9NSNFUYGhiSBiJpMprr72Gbdu24d13363DDCc+GIbBypUra16PmTNnYubMmfWdVIPQvJ+akKLpGTUxLkilUrj++uuxZcsWOByORk+niUmO5v009dH0jJoYEoYrqXLkyBEcP34cV155JX2NZVkAgEKhwIEDBzBr1qzxnXQTExbN+6kJKZqe0QTDo48+CrvdPkB25KqrrsL111/foFkNX1Jl/vz5+OCDD/Duu+/Sf//0T/+Ej33sY3j33XfR3t5ez+k3McEwle6ncDgMj8eD73//+/S1N954AyqVqt/5NXEKNJrO10R/ZLNZzmw2c7/73e/oa6FQiFMoFNwrr7zSwJkNX1JFihtuuKFJxW2CYirdT88//zynVCq5N998k0smk9zMmTO5f/u3f2v0tCYVmmG6CQatVotrr70WjzzyCK655hoAwOOPP45p06Y1XLp+zZo1CIfD+Pa3v00lVV588UWahO7q6mqKdTYxZEyl++mKK67Axo0bsXbtWixfvhx6vb6p8D1MNOuMJiDeeecdnHXWWThx4gRaW1uxePFiXHPNNfjWt77V6Kk10UQTNZDL5XDaaaehu7sbb7/9Nk4//fRGT2lSYXJsOz5iWLp0Kc444ww8+uijePvtt7F3717ceOONjZ5WE000MQiOHDkCv98PlmVx/PjxRk9n0qFpjCYoNmzYgF/96ld45JFHcMkllzQT/k3UDcPRi/vVr34FhmH6/fsotrMvFou47rrrsGbNGtxzzz3YsGEDent7Gz2tSYWmMZqguPbaa9HT04MtW7bgpptuavR0mviI4Mknn8Sdd96Ju+++G3v27MEZZ5yB1atXD7qwmkwmBAIB+u/EiRN1nPHEwDe+8Q0kEgn89Kc/xX/8x39g7ty5zed2uGg0g6KJ2rj++us5m83G5fP5Rk9lQuDnP/85N336dE6tVnMrVqzgdu3aNej7Y7EYd9ttt3Eej4dTqVTcnDlzuOeff75Os52cWLFiBffFL36R/l6pVDiv18v94Ac/qPr+Rx55hDObzXWa3cTEX//6V06hUHB///vf6WvHjh3jTCYT98tf/rKBM5tcaLLpJjB8Ph/Wrl0LtVrd6Kk0HGTHvnnzZqxcuRL3338/Vq9ejQMHDsDlcg14f7FYxKWXXgqXy4Wnn34ara2tOHHiBCwWS/0nP0lA9OLELeuHoheXTqcxffp0sCyLM888E9///vexaNGiekx5QuCiiy4a0GK+o6MDiUSiQTOanGiG6SYgYrEY/vjHP+LVV1/FF7/4xUZPZ0Lgxz/+MTZu3Ij169dj4cKF2Lx5M3Q6HR5++OGq73/44YcRjUbxzDPP4Nxzz0VHRwcuvPBCnHHGGXWe+eTBYHpxwWCw6mfmzZuHhx9+GH/605/w+OOPg2VZnHPOOejp6anHlJuYQmgaowmIpUuX4sYbb8S9996LefPmNXo6DcdIFJ6fffZZrFq1Cl/84hfhdrtx2mmn4fvf/z4qlUq9pv2RwKpVq7Bu3TosWbIEF154If7whz/A6XTiwQcfbPTUmphkaIbpJiCatND+GInC89GjR/HKK69g7dq1eOGFF3D48GHcdtttKJVKuPvuu+sx7UmH4erFVYNSqcTSpUtx+PDh8ZhiE1MYTc+oiSkJlmXhcrnw0EMPYdmyZVizZg2+8Y1vYPPmzY2e2oTFcPXiqqFSqeCDDz5AS0vLeE2ziSmKpmfUxITHSHbsLS0tUCqV/RrVLViwAMFgEMViESqValznPFlx55134oYbbsDy5cuxYsUK3H///chkMli/fj0AYN26dWhtbaVSN9/97ndx9tlnY/bs2YjH4/iv//ovnDhxAhs2bGjkaTQxCdH0jJqY8BjJjv3cc8/F4cOHaZsBADh48CBaWlqahmgQrFmzBvfddx++/e1vY8mSJXj33XcH6MUFAgH6/lgsho0bN2LBggW44oorkEwm8cYbb2DhwoWNOoUmJima2nRNTAo8+eSTuOGGG/Dggw/SHfvvfvc77N+/H263e8COvbu7G4sWLcINN9yAL33pSzh06BBuuukm/Ou//iu+8Y1vNPhsmmiiCSmaYbomJgWGq/Dc3t6O//mf/8G//dv/394do6gORQEYPiCuQsQdaCHqHtxJCgljo2Bvk0ZQQbByA3auRbEXrIJLeMVrBoYZGAbm3vfyfXWKpPq5Nzcnb9Hv96PT6URZlrFYLFI9AvAFKyPI2H6/j6qq4vl8xmAwiO12G+Px+NPrX69XrFarOJ/PUdd19Hq92Gw2MZ1Of/Gu4fusjCBTpk7QJFZGkKnJZBKj0Sh2u11E/D200e12YzabxXK5/HD94XCIqqridrtFu93+7duFH3GaDjJk6gRNY5sOMmTqBE0jRvCfeD91otVqxXA4jMfjEVVViRHZEyPIkKkTNI13RpAhUydoGjGCTM3n8zgej3E6neJ6vUZRFB/mxL3/EV5RFFHXdZRlGff7PS6XS6zXa//E4p9gmw4yZeoETeI7IwCSs00HQHJiBEByYgRAcmIEQHJiBEByYgRAcmIEQHJiBEByYgRAcmIEQHJiBEByYgRAcmIEQHJiBEByYgRAcmIEQHJiBEByfwC44Z9LrEnaIQAAAABJRU5ErkJggg==", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 45\n", + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.plot_workspace(np.array(ws_pred))" + ] + } + ], + "metadata": { + "colab": { + "collapsed_sections": [ + "3_mYGXhmjnhg" + ], + "provenance": [] + }, + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + }, + "widgets": { + "application/vnd.jupyter.widget-state+json": { + "1c0f293c6f03438bb4f19276ec49a419": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "ad8026a2dd49407fb30677e5cf96d004": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "MPLCanvasModel", + "state": { + "_cursor": "default", + "_data_url": "data:image/png;base64,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", + "_dom_classes": [], + "_figure_label": "Figure 17", + "_image_mode": "diff", + "_message": "", + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "MPLCanvasModel", + "_rubberband_height": 0, + "_rubberband_width": 0, + "_rubberband_x": 0, + "_rubberband_y": 0, + "_size": [ + 640, + 480 + ], + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "MPLCanvasView", + "capture_scroll": false, + "footer_visible": true, + "header_visible": true, + "layout": "IPY_MODEL_1c0f293c6f03438bb4f19276ec49a419", + "pan_zoom_throttle": 33, + "resizable": true, + "toolbar": "IPY_MODEL_eb0420e848554f6592e94d4423567f9c", + "toolbar_position": "left", + "toolbar_visible": "fade-in-fade-out" + } + }, + "e37f9f52ff7349cc974e863821254ee7": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "eb0420e848554f6592e94d4423567f9c": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "ToolbarModel", + "state": { + "_current_action": "", + "_dom_classes": [], + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "ToolbarModel", + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "ToolbarView", + "button_style": "", + "collapsed": true, + "layout": "IPY_MODEL_e37f9f52ff7349cc974e863821254ee7", + "orientation": "vertical", + "toolitems": [ + [ + "Home", + "Reset original view", + "home", + "home" + ], + [ + "Back", + "Back to previous view", + "arrow-left", + "back" + ], + [ + "Forward", + "Forward to next view", + "arrow-right", + "forward" + ], + [ + "Pan", + "Left button pans, Right button zooms\nx/y fixes axis, CTRL fixes aspect", + "arrows", + "pan" + ], + [ + "Zoom", + "Zoom to rectangle\nx/y fixes axis", + "square-o", + "zoom" + ], + [ + "Download", + "Download plot", + "floppy-o", + "save_figure" + ] + ] + } + } + } + } + }, + "nbformat": 4, + "nbformat_minor": 1 +} diff --git a/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-checkpoint.ipynb b/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-checkpoint.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..f1aae3e81f0c3909eede2fefbf489bc09dd4faa4 --- /dev/null +++ b/open_manipulator_cv_controller/notebooks/.ipynb_checkpoints/evaluation_metrics-checkpoint.ipynb @@ -0,0 +1,603 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "%matplotlib inline\n", + "\n", + "import os\n", + "import math\n", + "import json\n", + "import torch\n", + "import random\n", + "\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "from matplotlib import cm, colors\n", + "from mpl_toolkits.mplot3d import Axes3D" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "## TODO:\n", + "# FILENAME = \"_test_metrics.json\"\n", + "FILENAME = \"metrics.json\"" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "with open(FILENAME, \"rb\") as handle:\n", + " metrics = json.load(handle)\n", + " metrics = json.loads(metrics)\n", + " MAX_DIST = metrics['max_dist']" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "0.2586145463665413" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "MAX_DIST" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "def workspace_surface():\n", + " \n", + " half_pi = math.pi / 2.\n", + " u, v = np.mgrid[-half_pi:half_pi:100j, 0.0:math.pi:100j]\n", + " \n", + " xline = MAX_DIST * np.cos(u) * np.sin(v)\n", + " yline = MAX_DIST * np.sin(u) * np.sin(v)\n", + " zline = MAX_DIST * np.cos(v)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "def plane():\n", + " u, v = np.mgrid[-0.6:0.6:100j, 0:0.7:100j]\n", + " \n", + " xline = u\n", + " yline = v\n", + " zline = np.zeros_like(u)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "class Visualizer():\n", + " def __init__(self, angle1 = 20, angle2 = 90):\n", + " self.angle1 = angle1\n", + " self.angle2 = angle2\n", + " \n", + " self.title = None\n", + " self.x_axis = \"x-axis\"\n", + " self.y_axis = \"y-axis\"\n", + " self.z_axis = \"z-axis\"\n", + " \n", + " def set_axis(self, title = None, x = 'x-axis', y = 'y-axis', z = 'z-axis'):\n", + " self.title = title\n", + " self.x_axis = x\n", + " self.y_axis = y\n", + " self.z_axis = z\n", + " \n", + " def get_axis(self, dim = 3):\n", + " plt.clf()\n", + " \n", + " if dim == 3:\n", + " ax = plt.axes(projection='3d')\n", + " ax.set_zlabel(self.z_axis)\n", + " ax.view_init(self.angle1, self.angle2)\n", + "\n", + " else:\n", + " fig, ax = plt.subplots()\n", + " \n", + " if self.title is not None:\n", + " ax.set_title(self.title)\n", + " \n", + " ax.set_xlabel(self.x_axis)\n", + " ax.set_ylabel(self.y_axis)\n", + " \n", + " return ax\n", + " \n", + " def plot_test_spread(self, actual, pred):\n", + " ax = self.get_axis()\n", + " \n", + " # Data for three-dimensional scattered points\n", + " ax.scatter3D(actual[:,0], actual[:,1], actual[:,2], color = 'red', label = \"Test Values\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'blue', alpha = 0.5, label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_trajectory(self, traj, pred):\n", + " ax = self.get_axis()\n", + "\n", + " ax.plot3D(traj[:,0], traj[:,1], traj[:,2], color = 'blue', label = \"Actual Trajectory [frame 1]\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'red', label = \"Predicted Values [frame 2]\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_orientation_trajectory(self, traj, pred):\n", + " ax = self.get_axis(2)\n", + "\n", + " ax.plot(traj, color = 'blue', label = \"Actual Trajectory\")\n", + " ax.scatter(range(len(pred)), pred, color = 'red', label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_workspace(self, predictions):\n", + " ax = self.get_axis()\n", + "\n", + " pl = plane()\n", + " sphere = workspace_surface()\n", + " \n", + " ax.plot_surface(pl[0], pl[1], pl[2], rstride = 1, cstride = 1, color = 'w', alpha = 0.1, linewidth = 0)\n", + " ax.plot_surface(sphere[0], sphere[1], sphere[2], rstride = 1, cstride = 1, color = 'c', alpha = 0.2, linewidth = 0)\n", + " ax.plot_wireframe(sphere[0], sphere[1], sphere[2], rstride = 5, cstride = 5, color = 'black', alpha = 0.2, linewidth = 0.5)\n", + " \n", + " within_range = []\n", + " outside_range = []\n", + " for point in predictions:\n", + " dist = np.linalg.norm(np.array(point))\n", + " if dist <= MAX_DIST:\n", + " within_range.append(point)\n", + " else:\n", + " outside_range.append(point)\n", + " \n", + " within_range, outside_range = np.array(within_range), np.array(outside_range)\n", + " \n", + " if outside_range.shape[0] != 0:\n", + " ax.scatter(outside_range[:,0], outside_range[:,1], outside_range[:,2],color=\"red\", s = 20, label = \"Predictions out of Workspace\") \n", + " \n", + " if within_range.shape[0] != 0:\n", + " ax.scatter(within_range[:,0], within_range[:,1], within_range[:,2], color=\"black\", s = 20, label = \"Predictions within Workspace\")\n", + " \n", + " ax.set_xlim([0,0.6])\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + "visualizer = Visualizer()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Test Set" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "test_outputs, test_set = metrics['test_set'][0], metrics['test_set'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_test_spread(np.array(test_set), np.array(test_outputs))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "g3fRbkqaNHup" + }, + "source": [ + "## Position" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "traj_pred, traj_actual = metrics['pos_traj'][0], metrics['pos_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 0\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_trajectory(np.array(traj_actual), np.array(traj_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "zV1tmbQ1NJyk" + }, + "source": [ + "## Orientation" + ] + }, + { + "cell_type": "code", + "execution_count": 934, + "metadata": {}, + "outputs": [], + "source": [ + "or_pred, or_traj = metrics['or_traj'][0], metrics['or_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 935, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<Figure size 640x480 with 0 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(title = \"End-Effector Orientation Predictions\", x = \"Trajectory Samples\", y = \"Orientation [rad]\")\n", + "visualizer.plot_orientation_trajectory(np.sin(or_traj), np.sin(or_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "BTJFV6jTY_kd" + }, + "source": [ + "## Workspace" + ] + }, + { + "cell_type": "code", + "execution_count": 936, + "metadata": {}, + "outputs": [], + "source": [ + "### TODO distance of each point to origin. \n", + "# If smaller than max range then within " + ] + }, + { + "cell_type": "code", + "execution_count": 937, + "metadata": {}, + "outputs": [], + "source": [ + "ws_pred, ws_traj = metrics['workspace'][0], metrics['workspace'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 938, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 45\n", + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.plot_workspace(np.array(ws_pred))" + ] + } + ], + "metadata": { + "colab": { + "collapsed_sections": [ + "3_mYGXhmjnhg" + ], + "provenance": [] + }, + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + }, + "widgets": { + "application/vnd.jupyter.widget-state+json": { + "1c0f293c6f03438bb4f19276ec49a419": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "ad8026a2dd49407fb30677e5cf96d004": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "MPLCanvasModel", + "state": { + "_cursor": "default", + "_data_url": "data:image/png;base64,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", + "_dom_classes": [], + "_figure_label": "Figure 17", + "_image_mode": "diff", + "_message": "", + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "MPLCanvasModel", + "_rubberband_height": 0, + "_rubberband_width": 0, + "_rubberband_x": 0, + "_rubberband_y": 0, + "_size": [ + 640, + 480 + ], + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "MPLCanvasView", + "capture_scroll": false, + "footer_visible": true, + "header_visible": true, + "layout": "IPY_MODEL_1c0f293c6f03438bb4f19276ec49a419", + "pan_zoom_throttle": 33, + "resizable": true, + "toolbar": "IPY_MODEL_eb0420e848554f6592e94d4423567f9c", + "toolbar_position": "left", + "toolbar_visible": "fade-in-fade-out" + } + }, + "e37f9f52ff7349cc974e863821254ee7": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "eb0420e848554f6592e94d4423567f9c": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "ToolbarModel", + "state": { + "_current_action": "", + "_dom_classes": [], + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "ToolbarModel", + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "ToolbarView", + "button_style": "", + "collapsed": true, + "layout": "IPY_MODEL_e37f9f52ff7349cc974e863821254ee7", + "orientation": "vertical", + "toolitems": [ + [ + "Home", + "Reset original view", + "home", + "home" + ], + [ + "Back", + "Back to previous view", + "arrow-left", + "back" + ], + [ + "Forward", + "Forward to next view", + "arrow-right", + "forward" + ], + [ + "Pan", + "Left button pans, Right button zooms\nx/y fixes axis, CTRL fixes aspect", + "arrows", + "pan" + ], + [ + "Zoom", + "Zoom to rectangle\nx/y fixes axis", + "square-o", + "zoom" + ], + [ + "Download", + "Download plot", + "floppy-o", + "save_figure" + ] + ] + } + } + } + } + }, + "nbformat": 4, + "nbformat_minor": 1 +} diff --git a/open_manipulator_cv_controller/notebooks/evaluation_metrics.ipynb b/open_manipulator_cv_controller/notebooks/evaluation_metrics.ipynb new file mode 100644 index 0000000000000000000000000000000000000000..f1aae3e81f0c3909eede2fefbf489bc09dd4faa4 --- /dev/null +++ b/open_manipulator_cv_controller/notebooks/evaluation_metrics.ipynb @@ -0,0 +1,603 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "%matplotlib inline\n", + "\n", + "import os\n", + "import math\n", + "import json\n", + "import torch\n", + "import random\n", + "\n", + "import numpy as np\n", + "import matplotlib.pyplot as plt\n", + "\n", + "from matplotlib import cm, colors\n", + "from mpl_toolkits.mplot3d import Axes3D" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "## TODO:\n", + "# FILENAME = \"_test_metrics.json\"\n", + "FILENAME = \"metrics.json\"" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "with open(FILENAME, \"rb\") as handle:\n", + " metrics = json.load(handle)\n", + " metrics = json.loads(metrics)\n", + " MAX_DIST = metrics['max_dist']" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "0.2586145463665413" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "MAX_DIST" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [], + "source": [ + "def workspace_surface():\n", + " \n", + " half_pi = math.pi / 2.\n", + " u, v = np.mgrid[-half_pi:half_pi:100j, 0.0:math.pi:100j]\n", + " \n", + " xline = MAX_DIST * np.cos(u) * np.sin(v)\n", + " yline = MAX_DIST * np.sin(u) * np.sin(v)\n", + " zline = MAX_DIST * np.cos(v)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "def plane():\n", + " u, v = np.mgrid[-0.6:0.6:100j, 0:0.7:100j]\n", + " \n", + " xline = u\n", + " yline = v\n", + " zline = np.zeros_like(u)\n", + " \n", + " return xline, yline, zline\n", + "\n", + "class Visualizer():\n", + " def __init__(self, angle1 = 20, angle2 = 90):\n", + " self.angle1 = angle1\n", + " self.angle2 = angle2\n", + " \n", + " self.title = None\n", + " self.x_axis = \"x-axis\"\n", + " self.y_axis = \"y-axis\"\n", + " self.z_axis = \"z-axis\"\n", + " \n", + " def set_axis(self, title = None, x = 'x-axis', y = 'y-axis', z = 'z-axis'):\n", + " self.title = title\n", + " self.x_axis = x\n", + " self.y_axis = y\n", + " self.z_axis = z\n", + " \n", + " def get_axis(self, dim = 3):\n", + " plt.clf()\n", + " \n", + " if dim == 3:\n", + " ax = plt.axes(projection='3d')\n", + " ax.set_zlabel(self.z_axis)\n", + " ax.view_init(self.angle1, self.angle2)\n", + "\n", + " else:\n", + " fig, ax = plt.subplots()\n", + " \n", + " if self.title is not None:\n", + " ax.set_title(self.title)\n", + " \n", + " ax.set_xlabel(self.x_axis)\n", + " ax.set_ylabel(self.y_axis)\n", + " \n", + " return ax\n", + " \n", + " def plot_test_spread(self, actual, pred):\n", + " ax = self.get_axis()\n", + " \n", + " # Data for three-dimensional scattered points\n", + " ax.scatter3D(actual[:,0], actual[:,1], actual[:,2], color = 'red', label = \"Test Values\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'blue', alpha = 0.5, label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_trajectory(self, traj, pred):\n", + " ax = self.get_axis()\n", + "\n", + " ax.plot3D(traj[:,0], traj[:,1], traj[:,2], color = 'blue', label = \"Actual Trajectory [frame 1]\")\n", + " ax.scatter3D(pred[:,0], pred[:,1], pred[:,2], color = 'red', label = \"Predicted Values [frame 2]\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_orientation_trajectory(self, traj, pred):\n", + " ax = self.get_axis(2)\n", + "\n", + " ax.plot(traj, color = 'blue', label = \"Actual Trajectory\")\n", + " ax.scatter(range(len(pred)), pred, color = 'red', label = \"Predicted Values\")\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + " def plot_workspace(self, predictions):\n", + " ax = self.get_axis()\n", + "\n", + " pl = plane()\n", + " sphere = workspace_surface()\n", + " \n", + " ax.plot_surface(pl[0], pl[1], pl[2], rstride = 1, cstride = 1, color = 'w', alpha = 0.1, linewidth = 0)\n", + " ax.plot_surface(sphere[0], sphere[1], sphere[2], rstride = 1, cstride = 1, color = 'c', alpha = 0.2, linewidth = 0)\n", + " ax.plot_wireframe(sphere[0], sphere[1], sphere[2], rstride = 5, cstride = 5, color = 'black', alpha = 0.2, linewidth = 0.5)\n", + " \n", + " within_range = []\n", + " outside_range = []\n", + " for point in predictions:\n", + " dist = np.linalg.norm(np.array(point))\n", + " if dist <= MAX_DIST:\n", + " within_range.append(point)\n", + " else:\n", + " outside_range.append(point)\n", + " \n", + " within_range, outside_range = np.array(within_range), np.array(outside_range)\n", + " \n", + " if outside_range.shape[0] != 0:\n", + " ax.scatter(outside_range[:,0], outside_range[:,1], outside_range[:,2],color=\"red\", s = 20, label = \"Predictions out of Workspace\") \n", + " \n", + " if within_range.shape[0] != 0:\n", + " ax.scatter(within_range[:,0], within_range[:,1], within_range[:,2], color=\"black\", s = 20, label = \"Predictions within Workspace\")\n", + " \n", + " ax.set_xlim([0,0.6])\n", + " \n", + " ax.legend()\n", + " plt.show()\n", + " \n", + "visualizer = Visualizer()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Test Set" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [], + "source": [ + "test_outputs, test_set = metrics['test_set'][0], metrics['test_set'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 13, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_test_spread(np.array(test_set), np.array(test_outputs))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "g3fRbkqaNHup" + }, + "source": [ + "## Position" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [], + "source": [ + "traj_pred, traj_actual = metrics['pos_traj'][0], metrics['pos_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.angle1 = 0\n", + "visualizer.angle2 = 90\n", + "visualizer.plot_trajectory(np.array(traj_actual), np.array(traj_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "zV1tmbQ1NJyk" + }, + "source": [ + "## Orientation" + ] + }, + { + "cell_type": "code", + "execution_count": 934, + "metadata": {}, + "outputs": [], + "source": [ + "or_pred, or_traj = metrics['or_traj'][0], metrics['or_traj'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 935, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "<Figure size 640x480 with 0 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.set_axis(title = \"End-Effector Orientation Predictions\", x = \"Trajectory Samples\", y = \"Orientation [rad]\")\n", + "visualizer.plot_orientation_trajectory(np.sin(or_traj), np.sin(or_pred))" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "id": "BTJFV6jTY_kd" + }, + "source": [ + "## Workspace" + ] + }, + { + "cell_type": "code", + "execution_count": 936, + "metadata": {}, + "outputs": [], + "source": [ + "### TODO distance of each point to origin. \n", + "# If smaller than max range then within " + ] + }, + { + "cell_type": "code", + "execution_count": 937, + "metadata": {}, + "outputs": [], + "source": [ + "ws_pred, ws_traj = metrics['workspace'][0], metrics['workspace'][1]" + ] + }, + { + "cell_type": "code", + "execution_count": 938, + "metadata": { + "scrolled": false + }, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "<Figure size 640x480 with 1 Axes>" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualizer.angle1 = 20\n", + "visualizer.angle2 = 45\n", + "visualizer.set_axis(x = \"x\", y = \"y\", z = \"z\")\n", + "visualizer.plot_workspace(np.array(ws_pred))" + ] + } + ], + "metadata": { + "colab": { + "collapsed_sections": [ + "3_mYGXhmjnhg" + ], + "provenance": [] + }, + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + }, + "widgets": { + "application/vnd.jupyter.widget-state+json": { + "1c0f293c6f03438bb4f19276ec49a419": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "ad8026a2dd49407fb30677e5cf96d004": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "MPLCanvasModel", + "state": { + "_cursor": "default", + "_data_url": "data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAoAAAAHgCAYAAAA10dzkAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/bCgiHAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOy9d5icZ3nv/3nf6X1mey9aSatqdclauWIHgwnBkPAjkFBCCsmB5BCfiwQSckIgJ0A4BEhILpPCARMChARCQokxNgYbCdsqu5JW2t57md7nLb8/prCrtm0k7Wqfz3XpsrU7877PFM37nft+7u9X0nVdRyAQCAQCgUCwaZBv9wIEAoFAIBAIBLcWIQAFAoFAIBAINhlCAAoEAoFAIBBsMoQAFAgEAoFAINhkCAEoEAgEAoFAsMkQAlAgEAgEAoFgkyEEoEAgEAgEAsEmQwhAgUAgEAgEgk2GEIACgUAgEAgEmwwhAAUCgUAgEAg2GUIACgQCgUAgEGwyhAAUCAQCgUAg2GQIASgQCAQCgUCwyRACUCAQCAQCgWCTIQSgQCAQCAQCwSZDCECBQCAQCASCTYYQgAKBQCAQCASbDCEABQKBQCAQCDYZQgAKBAKBQCAQbDKEABQIBAKBQCDYZAgBKBAIBAKBQLDJEAJQIBAIBAKBYJMhBKBAIBAIBALBJkMIQIFAIBAIBIJNhhCAAoFAIBAIBJsMIQAFAoFAIBAINhlCAAoEAoFAIBBsMoQAFAgEAoFAINhkCAEoEAgEAoFAsMkQAlAgEAgEAoFgkyEEoEAgEAgEAsEmQwhAgUAgEAgEgk2GEIACgUAgEAgEmwwhAAUCgUAgEAg2GUIACgQCwRoZGhpCkiS+8IUv3O6lCAQCwbIQAlAgEGwIOjs7eeMb38iWLVuw2+2UlZVx33338V//9V9X3faBBx5AkiQkSUKWZdxuN62trbz1rW/l6aefvg2rvz4nT57kQx/6EMFg8HYvRSAQbCKEABQIBBuC4eFhIpEIb3/72/nMZz7Dn/zJnwDwC7/wC/z93//9Vbevq6vjS1/6Ek8++SSf+MQn+IVf+AVOnjzJK1/5St70pjeRyWRu9UO4JidPnuTP/uzPhAAUCAS3FOPtXoBAIBAsh0cffZRHH3100c/e8573cOjQIf7qr/6K3/qt31r0O4/Hw6/+6q8u+tnHPvYxfu/3fo+/+7u/o6mpiY9//OM3fd0CgUCwHhEVQIFAsGExGAzU19cvu3pmMBj467/+a3bt2sVnP/tZQqHQDW//wAMPsGfPHs6cOUNbWxs2m43m5maeeOKJZZ3v2Wef5d5778XhcOD1ennd617H5cuXC7//0Ic+xPve9z4AmpubC23roaGhZR1fIBAIVosQgAKBYEMRi8WYm5ujv7+fT33qU3zve9/joYceWvb9DQYDb37zm4nH47zwwgtL3j4QCPDoo49y6NAh/vIv/5K6ujp+53d+h89//vM3vN8PfvADHnnkEWZmZvjQhz7E448/zsmTJzlx4kRB4L3hDW/gzW9+MwCf+tSn+NKXvsSXvvQlysvLl/14BAKBYDWIFrBAINhQ/K//9b/43Oc+B4Asy7zhDW/gs5/97IqOsWfPHgD6+/uXvO3ExASf/OQnefzxxwF417vexbFjx/jABz7AW9/6Vkwm0zXv9773vY+SkhJOnTpFSUkJAI899hgHDhzgT//0T/niF7/IXXfdxcGDB/nKV77CY489RlNT04oeh0AgEKwWUQEUCAQbive+9708/fTTfPGLX+TVr341qqqSTqdXdAyn0wlAJBJZ8rZGo5F3vetdhb+bzWbe9a53MTMzw5kzZ655n8nJSdrb23nHO95REH8Ad911Fz/3cz/Hd7/73RWtVyAQCIqNEIACgWBDsWPHDh5++GHe9ra38e1vf5toNMprX/tadF1f9jGi0SgALpdrydvW1NTgcDgW/Wz79u0A192rNzw8DEBra+tVv9u5cydzc3PEYrFlr1cgEAiKjRCAAoFgQ/NLv/RLvPzyy/T09Cz7PhcvXgRg69atN2tZAoFAsK4RAlAgEGxoEokEwJITvXlUVeVf/uVfsNvt3HPPPUvefmJi4qpqXV5sXm/PXmNjIwDd3d1X/a6rq4uysrJCVVGSpGWtWyAQCIqJEIACgWBDMDMzc9XPMpkMTz75JDabjV27di15DFVV+b3f+z0uX77M7/3e7+F2u5e8j6IohaETgHQ6zec+9znKy8s5dOjQNe9TXV3N/v37+eIXv7jIoubixYt8//vfX+RnmBeCwghaIBDcSsQUsEAg2BC8613vIhwOc99991FbW8vU1BRf/vKX6erq4pOf/GRhsCNPKBTin//5nwGIx+P09fXxjW98g/7+fn75l3+Zj3zkI8s6b01NDR//+McZGhpi+/btfO1rX6O9vZ2///u/v+4EMMAnPvEJXv3qV3P8+HF+/dd/nUQiwd/8zd/g8Xj40Ic+VLhdXkT+8R//Mb/8y7+MyWTita997VX7DgUCgaCo6AKBQLAB+MpXvqI//PDDemVlpW40GnWfz6c//PDD+re+9a2rbnv//ffrQOGP0+nUt23bpv/qr/6q/v3vf3/Z57z//vv13bt366dPn9aPHz+uW61WvbGxUf/sZz+76HaDg4M6oP+///f/Fv38Bz/4gX7ixAndZrPpbrdbf+1rX6tfunTpqvN85CMf0Wtra3VZlnVAHxwcXPYaBQKBYDVIur6C0TmBQCDYRDzwwAPMzc0VhkYEAoHgTkHsARQIBAKBQCDYZAgBKBAIBAKBQLDJEAJQIBAIBAKBYJMh9gAKBAKBQCAQbDJEBVAgEAgEAoFgkyEEoEAgEAgEAsEmQwhAgUAgEAgEgk2GEIACgUAgEAgEmwwhAAUCgUAgEAg2GUIACgQCgUAgEGwyhAAUCAQCgUAg2GQIASgQCAQCgUCwyRACUCAQCAQCgWCTIQSgQCAQCAQCwSZDCECBQCAQCASCTYYQgAKBQCAQCASbDCEABQKBQCAQCDYZQgAKBAKBQCAQbDKEABQIBAKBQCDYZAgBKBAIBAKBQLDJEAJQIBAIBAKBYJMhBKBAIBAIBALBJkMIQIFAIBAIBIJNhhCAAoFAIBAIBJsMIQAFAoFAIBAINhlCAAoEAoFAIBBsMoQAFAgEAoFAINhkCAEoEAgEAoFAsMkQAlAgEAgEAoFgkyEEoEAgEAgEAsEmQwhAgUAgEAgEgk2GEIACgUAgEAgEmwwhAAUCgUAgEAg2GUIACgQCgUAgEGwyhAAUCAQCgUAg2GQYb/cCBAKBQNd1VFUFwGAwIEnSbV6RQCAQ3NkIASgQCG4rmqaRyWRIJBLouo4sy5hMJgwGA0ajEVmWhSAUCASCIiPpuq7f7kUIBILNh67rpNNpMpkMsiyTyWTIfxxpmgaAJEkFQWg0GjEYDEIQCgQCQREQAlAgENxydF0nk8kwMDBAIBDgwIEDpNNpgIK403W98EcIQoFAICguogUsEAhuKZqmkU6n0TQNWZa53ndQSZIKws5gMCwShMlkkvHxcex2O+Xl5RiNRiEIBQKBYAUIASgQCG4J+UGPfKv3SqEmSdJ1xWD+9wsFYTgcRpZlNE0jlUqRTCaRZRlZloUgFAgEgiUQAlAgENx0NE1DUZTCpG9elC0l+m7EQjEIP2sZq6qKqqqkUqlCy1gIQoFAIFiMEIACgeCmkd+/l6/6LaziwdJVvxtxpYjLH1uW5cK584JQUZTC7/PTxfn/XrkmgUAg2AwIASgQCG4Kuq6jKAqKogBcU2itRQDmz3E9ricIFUUhk8lcJQjzolAIQoFAsBkQAlAgEBSdfNVPVdVFIuxKilkBXM7tlysI8z6E+ZaxQCAQ3GkIASgQCIrGwpZrfsr3RkItLwAzmQyDg4NYrVZ8Ph9Wq3XZ51stSwlC4Kr9g0IQCgSCOwUhAAUCQVHIC7krBz1uhCRJZDIZTp06hdlsRtM0Ll++jM1mw+fzFf6YzeZr3reYXE8QZjKZgkehEIQCgeBOQQhAgUCwZq709luOONN1nZmZGWKxGNu3b6e2thYAVVUJBoMEAgGGh4fp7OzE4XAUxKDX68VkMhWOcbO4liDMt7bzFUJJkoQgFAgEGxKRBCIQCFbNUt5+1yOdTnPhwgVCoRBGo5F777130aTwlbfNC8JAIEA8HsfpdKLrOk6nk9bWVozGW/9dNi8IF36EXikI81PGAoFAsN4QAlAgEKwKXdcJBoPIsozZbF729Oz8/Dznz5/H6/VSWVnJ4OAgbW1tZDKZQgXxRqRSKQKBAIODg4WWs8vlKlQIPR5PwRvwVrJQEOaFrCzL15wyFggEgtuNaAELBIIVk6/6dXZ2UllZSUNDw5L30XWdvr4+hoaGaG1tpb6+nrm5uRW3cS0WC1VVVQSDQUwmE7W1tYXq4OXLl0mn07jd7kWC8Fa0ZfMTxHkWtoxHR0fRNI26urqrWsZCEAoEgtuBEIACgWDZXOntt1xhlUwm6ejoIJ1Oc/fdd+NyuYDi2MBYrVaqq6uprq5G13USiQSBQIBgMMjExASKouDxeAqC0OVy3XJBmEwmURQFXddJp9PXTSkRglAgENwqhAAUCATLIl/N0jQN+NmQRP7v12NmZoYLFy5QUVHBoUOHFu3XK7YRtCRJ2O127HY7tbW16LpOPB4vVAhHRkbQdR2v11sYKHG5XLdEdC0UhPl154dnhCAUCAS3GiEABQLBDVnYyrxyyvdGAk7TNLq7uxkbG2P37t3U1NRc9/irYTnCSJIkHA4HDoeDuro6dF0nGo0WBOHg4CCSJBUEoc/nw+Fw3HTRda0cY8g+Z6lU6oa2M0IQCgSCYiAEoEAguC5LeftdTwDG43Ha29sBaGtrw+FwXPP4sizftCi4ayFJEi6XC5fLRUNDA5qmFQTh/Pw8/f39GAyGRR6ENpvtlgpCg8FQGCTRdf0qQZhPKTEajcueuhYIBIIrEQJQIBBck4VxbtcTGtcScJOTk3R2dlJbW0tra+uS++1uVRTctZBlGbfbjdvtprGxEU3TCIfDBAIBpqen6e3txWg0XiUIb/Z6F05UXykIk8lk4TZ5QZivEApBKBAIlosQgAKBYBEriXNbWAFUVZXLly8zPT3N3r17qaysXPJcaxUrxXaxkmUZr9eL1+ulubkZVVUJhUIEg0EmJyfp7u7GYrEsEoQWi+Wmr1MIQoFAUGyEABQIBAVWGueWHwKJRCJ0dHRgNBppa2tbdpUsLyCX6yF4rfveTAwGAyUlJZSUlACgKAqhUIhAIMDo6CiXLl3CbrcXBkquF1tXbJYrCK/0IBSCUCAQ5BECUCAQAD/z9ltJnJskSYRCIYaHh2lqaqKlpWVFFivFngK+2RiNRkpLSyktLQUgk8kQDAYJBoNLxtbdTK4nCPNDJclkElmWrxoqEYJQINi8CAEoEGxyFnr7rSTOLZPJMD8/TyqV4uDBgwVRtBKK4QN4OzGZTJSXl1NeXg4sjq3r7+8nHo8XPA8tFguKotyS2LorK6p5QaiqKqqqXtd2RghCgWDzIASgQLCJ0TQNRVGW3fLNEwqFaG9vR9d1qqurVyX+YONVAJfCbDZTUVFBRUUF8LPYuuHhYQKBAM8///xtia3LC8J8dfZ6gjDfMl6YYywEoUBwZyIEoECwCclf/NPpdOEiv5wLva7rDA0N0dfXR0tLC+l0ekkj6OUcczVsBGGSj60Lh8NIkkRdXV2hQpiPrVuYUuJ2u29ZSsm1BKGiKGQyGSKRCIlEgtra2qtyjDfC8y4QCJZGCECBYJORH/QYHh5menqaw4cPL+uink6nuXDhApFIhCNHjuD1eunp6SnEwq2GhRXA1QiL9VYBXAqbzYbNZrsqti4QCDA2Noaqqrcttm6hIIzFYvj9fiorK8lkMoXfGwyGgg9hvmUsEAg2JkIACgSbiCu9/WB5wmt+fp7z58/j9Xo5ceJEYbBhrS3cK/eprfa+G4Er17vS2Dqfz4fT6bxljzu/PxCurhAKQSgQbHyEABQINgHX8vaTZXnJ9q2u6/T19TE0NERrayv19fWLBMhakzzyAnK1x9goFcDlrHO5sXULLWduVmxd3ppn4dpu1DKGa8fWCUEoEKxfhAAUCO5wruftl/fwux7JZJKOjg7S6TTHjh3D7XZfdZtiVgBv5X03AteKrYtEIgQCAebm5m5qbN2VAvBaa7uWIMxkMov2lQpBKBCsX4QAFAjuYDRNKwxqXDnhe6Pq3czMDBcuXKCiooJDhw5d17qkWALwTq8AFgNZlvF4PHg8Hpqamq6Krevp6cFsNi/yIFxtbN1SAvBKriUI89sN8hXCKwVhfspYIBDcHoQAFAjuQPIt30wmc11vv2tVADVNo7u7m7GxMXbv3k1NTc0Nz3M7BeCtSAIpJsUWO9eLrQsEAoyPj9PV1bWq2DrIvg/WWp1daG+zUBBeq0K4cMpYIBDcGoQAFAjuMJbr7XdlBTAej9Pe3g5AW1sbDodjyXMt1UZezv1h9QJwo3ArhOpKYuvyFcLrxdattAK4FMsRhLIsXzVUspFeY4FgoyEEoEBwh7DworqcfN2F4m1ycpLOzk5qa2tpbW1d9l6tYgyB5Ne+GWxgbiXXi63LD5TEYjGcTmdhoGRhbF2xBeCVLBSE+dfwWoLwyj2EQhAKBMVDCECB4A5gYZwbXB0Fdi3yU8AXL15kenqavXv3UllZuaLzFqsNuxrBIcTAylhubJ3P5yMej1+3OlhsFmYYw2JBmE6nrxtbJwShQLA2hAAUCDY4C739Fm7EX4pkMkk6nSYajdLW1raqgYHbOQUMG6cCeLMraqvherF1+T+qqhKLxQoVwlsZWwfXF4TpdBq4tu3MenuOBYL1jBCAAsEG5VrefsuNcxsbG+Py5ctIksTRo0dXbc9RzD2AogJ4e8nH1lVVVRVa+263uxBbl8lkcLvdtyW2DhYLwvyfVCpVEIT5YSebzSYEoUCwDIQAFAg2INfz9luKTCZDZ2cngUCAXbt2cfny5TVdxIu5B3A1bJQK4EZD13VMJhM1NTXU1NRcN7buypSSWxlbB1lRmBeDMzMzjIyMcODAgUIl3GQyFSqEy/03IhBsFoQAFAg2GJqmMTk5STKZpLa2dtkXtVAoRHt7O3a7nba2NhRFWbOAut02MIKbw7WSQK6MrYvFYgVBODw8fNti664UhEajsSAKk8lk4TZCEAoEixECUCDYICz09gsGg8RiMerq6pZ1v6GhIXp7e9m6dSvNzc2F1u1a2rdQnCGQhcdY6bE2SgVwPe4BvBH5dur1kCQJp9OJ0+mkvr7+hrF1+T92u/2mPgcLt0Fcq0J4pSDMi0UhCAWbFSEABYINwJUtX4PBsCzxlk6nuXDhApFIhCNHjuDz+Qq/W6sFS/4YxRKAKz2OuFjfPFaTBHK92LrZ2Vn6+vowGo2LKoTFiq1buOZridbrCUJN0wqCMJ+NLQShYDMhBKBAsM7JV/0WVjiWIwD9fj8dHR14vV5OnDhR8HjLk79Yapq26unOtQ6B5I8h9gCuL9ZasbxWbF0oFCIYDF4zts7n82G1Wte05vy/j6W4niBUVRVVVUkmk0IQCjYFQgAKBOuUK739Fl6AbiS8dF2nr6+PoaEhWltbqa+vv24SSP72q6WYPoDz8/PE43FKS0uXJQbExfjmUeyWtSzLBaF3vdg6q9VaMKReSWxdntXG110rx3ihIFzoQ5hPKcnnGIv3oGAjIwSgQLAOyXv75UXelRebvInzlSSTSTo6Okin0xw7dgy3233dc+SPt5YK3lqngPMMDg4yPT2N3W6np6cHq9VKSUlJQTRcWb3Ms1EqgBtxD+DNXO+1YuvyptTXiq270Xsgz3IrgEtxI0GoKErh91fuIRSCULDREAJQIFhHLIxzu5G337UE4MzMDBcuXKCiooJDhw5hNN74n/fCFvBqWWsFMJlMomkawWCQo0ePYjab0XWdYDCI3+9ncHCQixcvFhIqSkpKCobE4mJ787jVgtVoNFJWVkZZWRlwdWzdxYsXcTqdi3KMr3x/F0sAXsn1BKGiKGQymUWCcGGO8a2wxBEI1oIQgALBOmEl3n4LK2+aptHT08Po6Ci7d++mpqZmWedbqwdf/hirvf/c3Bznz59HkiT27NmDw+Egk8lcJQbyCRV+v79gSOzxeDCZTItyjwXFY7Xt1GJxrdi6/IRxX1/foti6vCC8WQLwSoQgFNwpCAEoEKwDFsa5LWezeb4CGI/HaW9vB6CtrQ2Hw7Gi816vlbxcViMAdV2nv7+fwcFBdu7cSW9v7w0vjgsTKvKGxH6/n8nJSWKxGM8///wttRvZDKw3UW02m6msrCxkVS+Mrevu7iaVSmEymbBarQQCAdxu9y2JrYOlBSFcO7ZOCELB7UYIQIHgNrLaODdZlkmn05w8eZLa2lpaW1tXdUFZawt3pQIynU7T0dFBIpEo7FHs6+tbtuBYaEhsNpsZHh6mtbUVv99fsBsxmUyFdvFqhgluButNUC3Fel/vwi8FAIlEgkuXLqEoCp2dnSiKclti6+D6gjCTyZBOpwu/F4JQcLsRAlAguE2sNs5NVVWGhoZIp9McOHCgUBVZDbeyAhgIBGhvb8fr9dLW1lbYw7VWEep2u3G73TQ1NS2aLs0PEzgcjoIgvNbeMcHVrHcBeCU2mw2r1YrD4aCxsZF4PF7YQzg2NoamaXg8noIgdLlct+zxXUsQ5iv+eVEYCASoq6srCML8lLFAcDMRn4QCwW3gWt5+yyESidDR0YEkSZhMpjWJPyhOlNtS988nkfT19bF9+3YaGhquihkrVhTcwunSlpYWMpnMor1jiUQCl8tVqA56PB5RebkGG00AwuIkEIfDgcPhuG5sHbDIlNrhcNxSQbiwPR2NRhkaGqKysvKaFcKFU8YCQTERAlAguIUs9PbLJxcs54Nd13XGxsbo6uqisbGRqqoqXnrppTWvp1gVwOsJhkwmw4ULFwiHwxw5cgSv13vN46xWcCwlHE0mExUVFVRUVADZqWO/308gEGBiYgJFUfB6vQVBeDPzazfSBXwjCsAbJYFcGVsXiUQKk+YDAwPIsrxIEN7KfaR5I/Z8ZXphhTAvCGVZvmqoZKO9PoL1hxCAAsEtQtM0FEXh1KlT7Nu3D6vVuqwP8UwmQ2dnJ36/nwMHDlBWVkY0Gl1zAgesPcnjRnFyoVCI9vZ2nE4nbW1tmM3m6x4jL+RWGj+2UqxWKzU1NdTU1CyqDOUtZxYaFpeUlGCz2VZ8jmuxUfwK82xEAZgfoFoKSZIK2wZuFFt3ZUrJzXo+rlz3lRXC6wnC5557DlmWee1rX3tT1iW48xECUCC4ySz8ANd1nXA4vGybjbyIstvtnDhxojDQsNbKXZ61GjlfK01E13VGR0fp7u5my5YtbNmy5YaPdS0X1rW2rxdWhvJCwO/3MzU1RU9PDxaLZZEh9fVE7J3G9app65nVitYrY+tUVSUcDhMIBJicnKS7u7vosXULUVX1hhPLCwXhQuun//qv/8LtdgsBKFg1QgAKBDeRKwc9lpvju3DfXEtLC83NzVclgeRvtxYBVcwKIFCYwvT7/Rw6dKiQ9LDUMYq1B3AtLBQCzc3NKIpCKBTC7/czPDxMZ2cnTqezIAi9Xu8tsxq51WzECuBaMq0XYjAYCkIPuGFsXTG+GCwlABeyMMM4Ho9TXV296vMKBEIACgQ3iet5+8myXBCE1yKdTnPhwgUikQiHDx8uXIgWsjDFYy0XvbVWABcKwGg0yrlz57BYLLS1tS3bfmUtgyg3s7VqNBopLS2ltLQU+JkZsd/vL3jP5SdLS0pKcLlcN6yabSRBtVEF4M1Y841i6/JfDPKT5vkvBkvF1l257tX8G47FYiv2/RQIFiIEoEBQZJby9rtR+9bv99PR0YHX6+XEiRPXvZAUSwAWqwI4MTFBT08PjY2NbN26dUXtw/VSAVyKhWbEeUPq/GRp3mpkYVVo4WSp2AN487lVSSA3iq0bGBggFostGVu3kOXuXbyS/HkEgtUiBKBAUESW4+13LQG4MB2jtbWV+vr6G16Ai5Hjmz/OWsRJ/vy9vb3s37+/EN21EtZrBfBGLDSkzluNRKNR/H4/8/Pz9Pf3FwYJSkpKbljxXY8IAbh8bhRb19vbSzKZXBRbl8+yzrOSFvBChAAUrBUhAAWCIqFpGul0eklvvyv3ACaTSTo6Okin04V0jKXIH7sYAnC1x4jH45w7dw6AQ4cOXbNVvRw2SgXwRkiShMvlwuVy0djYiKZpi/aNhcNhotEo8Xi8YEi9kjbhrUYIwNVzZWxdMpksCMLLly+TTqcXpZQoirIqARiPx0ULWLAmhAAUCNZIvuWbn/Jdyttv4R7A2dlZzp8/T0VFBYcOHVp2SkXeCmKtAnC14mtqaoqLFy9SW1tLJBJZc9zaRqsALsVCO5ktW7bQ3t5esBLp7+8nHo9fZUi9ngZKhAAsHlarlerqaqqrq9F1fZEgnJiYIJ1OY7VaCxGGS+0lBQoWRqICKFgLQgAKBGsg7+23kjg3WZZRFIWuri5GR0fZvXs3NTU1Kz53MQTgSo+haRrd3d2Mj4+zZ88eqqqqGB0dvelpIte730YhbzlTV1cHQCqVKhhSX758mUwmc9VAye18fEIA3hwkScJms2Gz2QpelOfPn0eSJCKRCKOjo2iahtfrLRhTX++9EI1Gcblct+FRCO4UhAAUCFbBld5++fim5d53YGAAo9FIW1vbqts4ax3gyB9jueIrkUjQ0dGBqqocP368sO5ixMmt9n7rtQK4FBaLZVFVKB6PFyaMR0ZGAK4ypL6VgmwjCsCN6F2Y/9zw+XyFlJLlxNZBtgW81grgj3/8Yz7xiU9w5swZJicn+eY3v8ljjz12w/s899xzPP7443R2dlJfX88HP/hB3vGOd6xpHYLbgxCAAsEKWRjnBqxI/E1OThIMBvF6vRw5cmRNF6xbWQHMt6orKyvZuXPnonZlseLkNisLs2vr6urQNK0wUDIzM0Nvby9ms3mRIfVaW+5LsdEEoKZpG1IAwuIhkOvF1gUCAebn5xkYGOCv//qvUVUVn8/H9PT0ml6rWCzGvn37eOc738kb3vCGJW8/ODjIa17zGn77t3+bL3/5yzzzzDP8xm/8BtXV1TzyyCOrWoPg9iEEoECwAhZ6++X34S0HVVW5fPky09PTeL1eysvL13yxuhV7AHVdp6+vj6GhIXbt2kVtbe2Kj7HWNRT7freL5V6kZVkuRJXlkynyhtSjo6NcunQJh8OxyJB6uXtHl8ONsp3XK/n3wUYUgDeycloYW5cfLtJ1ne9+97ucPn2a173udZSUlPCKV7yCd7zjHTz88MMrOverX/1qXv3qVy/79k888QTNzc188pOfBGDnzp288MILfOpTnxICcAMiBKBAsAyW8va7EZFIhI6OjkLLt6+vr2gxbjezAphKpejo6CCVSnH33Xdfd7/R7RKAsH6HQK5kLeu80og4k8lcZTOSnyotKSnB7XavSQitJpf5dpN/D29EAbgSGxhZlnnggQfYtWsXTzzxBLOzs1y4cIEf/vCHBIPBm7tQ4NSpU1eJzEceeYT3vve9N/3cguIjBKBAsAR5b7/29nZaWloWGfwudb+xsTG6uroWGSSvlxxfuP4+wrwhtc/n4+DBgzesMN3OCuBmxGQyUVFRQUVFBcAiQ+oLFy4UhgjygnC579c8G1kAbqQ151mNEXQsFitMmj/44IM8+OCDN2l1i5mamirY2+SprKwkHA6TSCSw2Wy3ZB2C4iAEoEBwAxZ6+83Pz9PY2Lisi4yiKFy8eBG/38+BAwcKqQGwdBTccilWBXCh+NJ1ncHBQfr7+5dlSA3FSRO50yuAN5Mrp0pjsVhhwnhwcLAgFPIt46Uu0huxnbpZKoB58jFwG1HwCtYPQgAKBNfgWt5+BoNhWcItFArR3t6O3W7nxIkTV23YNxgMZDKZNa+xWHsA88fIZxBHo1GOHj2Kx+NZ9jHWKsTu9ArgrdpTt3CIoKGhAU3TCIfD+P1+Jicn6e7uxmq1FgSh1+vFbDZftdb8sTYKG8EC5nqsJs4xGo3eFgFYVVXF9PT0op9NT0/jdrtF9W8DIgSgQHAF14tzuzLB41r3Gxoaoq+vj5aWFpqbm6/5AV3MFnAxKoD5IYNz587hdrtpa2tbUUrFWlvRogJ485BlueApB9nKdD63dnBwsGAmvHCgRAjAW8tqKoC3KwXk+PHjfPe73130s6effprjx4/f8rUI1o4QgALBAvJVv2sNetyodZuvnkUiEQ4fPnzDWLT1JAABwuEwL730Elu3bqWpqWnFF/7b6QMoWBlGo5GysrLCloR0Ol1oF3d1dZFOpwvDPuFweM0DJbeKjSoAV2tfE4vFsNvta/43EI1G6evrK/x9cHCQ9vZ2SkpKaGho4AMf+ADj4+M8+eSTAPz2b/82n/3sZ/mDP/gD3vnOd/Lss8/yr//6r3znO99Z0zoEtwchAAUCrvb2u9aU7/UqgPmBCa/Xy4kTJ5asnq0XAagoCjMzM8TjcQ4fPlyYMl0pYgp442I2m6mqqqKqqgpd10kkEszMzBAOhzl//jy6ri8ypC6G6LgZbFQBmP9CuZoWcDFi4E6fPr1ogOTxxx8H4O1vfztf+MIXmJycLBiTAzQ3N/Od73yH3//93+czn/kMdXV1/OM//qOwgNmgCAEo2PTkvf0WThJe6yJ35R5AXdfp7+9ncHBw2QMT1zrOalnL8EUkEuHcuXMAlJaWrlr85dchpoBvzEbw1ZMkCbvdTmVlJYODg9x7770FE+K5uTn6+/sxGo2FdnFJSclNN6ReLhtVAOb//a5mCKQYAvCBBx644b+9L3zhC9e8T/6zQ7CxEQJQsGlZGOe2HG+/hS3gZDLJ+fPnSaVSHDt2DLfbvezz3m4bmLGxMS5fvkxTUxNGo3HN/mFiCvjOYmG04UITYlVVCwMl4+PjXL58GbvdviihpJiG1CthowrAvAXMSr8c5KeABYK1IASgYFNyvUGPG5FvAedj0SoqKpb0yLsWt6sFrKoqly5dYmZmpmBNMzIyUnQrmZWyUACu5EK43itqG5XrVSsNBkNB6EHWkDo/UNLf308ikcDlchWqgx6P55aJso0cA7eadQsBKCgGQgAKNh0L49xW8u1blmWmp6fp7+9n9+7d1NTUrOr8S00TL5eVCMBYLMa5c+cwGo2cOHECq9UKFMfCpdg2MCtpl4oKYPFZ7vNvMpkoLy+nvLwcyFbF84bUnZ2dKIqCx+MppJg4nc6bJto3cgVwpe1fKF4LWLC5EQJQsGlYS5xbPB5ndnYWgLa2tjV9+77VRtBTU1NcvHiRuro6tm/fvuhCeSvyhFdy/5VcyDdSBXAj7AHMs9q1Wq1Wqqurqa6uRtd14vF4YcJ4aGgISZKuMqQu1nOiadqGeX4XsloBGI1G17RvVyAAIQAFm4TVtHzzTE5O0tnZid1ux+PxrLn1UswW8I0MpTVNo6uri4mJCfbu3XtVhBOsjwqgJEmoqkpPTw8jIyPLrhrlf76RxNVGoBjPpyRJOBwOHA4H9fX1aJpGJBLB7/czPT1NT08PFotl0YTxlYbUK2GjVgBXYwIN2fg/UQEUrBUhAAV3PDfy9lvqfpcvX2Z6epq9e/cSDodJJpNrXs+t2AOYSCRob29H13Xa2tqw2+03bS1rPYamaczMzGA0Gtm7dy/xeLxQNZJluSAG19PU6Z3MzRDUsizj8XjweDw0Nzejqmph/+DIyAiXLl3C6XQWBKHX613R3tqNKgBXuwcwGo1e99+0QLBchAAU3LHkc1Gj0WjB0Ha5F7ZIJEJHRwdGo5G2tjZsNhuxWKwordubvQdwZmaGCxcuUFVVxY4dO25YYVjrAAesrQIYCoUYHx/HbDZz7NgxNE2jpKSkUDW6curU4XAUxGD+AigqgMXlVrRTDQYDpaWllJaWAllD6mAwiN/vp6enh1QqhdvtLrSLlzKk3sgCUOwBFNwuhAAU3JFomoaiKMzPz9Pf309bW9uyLmq6rjM2NkZXVxeNjY1s3bq1cGEpZuXuZvgAappGX18fw8PDyx5SWauFS/4YqxGAo6OjdHV14fV6sVqtGI1G0ul04fcLY8y2bNlCJpMhEAjg9/vp7u4mlUoBMDw8TFlZ2U0dMlgrG0mk3o6JWrPZTEVFBRUVFUC2gp1/rcfGxtA0Da/XWxCEV+bgbjYBGI/HhQAUrBkhAAV3FAu9/XRdx2g0oqrqsi6+iqJw8eJF/H5/wSZlIcUycM4LybWKgoWCNJlM0tHRQSaT4fjx48u+ONyOIZB8a31mZoaDBw8SCARIJBJLPhcmk6kgEnRdJxKJcPr0acLhMCMjI6JdXCTWg1i12WzYbDZqamrQdZ1oNFoQhHlD6oX7BzebABQ2MIJiIASg4I7hykEPSZKWLdpCoRDt7e3Y7XZOnDhxTfFQzNZtfr3FEIDz8/N0dHRQVlbGoUOHVrR3qlhDIMt9XhKJBOfOnUOSJI4fP47NZiMYDK7YB1CSJGw2GwC7d+9GluUbtou9Xu+qLrSbkfUgABciSRIulwuXy0VDQwOaphEKhQgEAkxOTtLd3Y3BYMBisTAzM4PP51syjnG9sJohkPzWlnxms0CwWoQAFNwRXM/bL18BvB66rjM8PExvby8tLS00Nzdf9+JXrNZt/gN/rVULSZKIxWKcPXuWHTt2UFdXt+IL962sAM7NzdHR0UFVVRU7d+5c9NjXGgW3nHZxfrq4tLT0trSL15OouhHrTQBeiSzLiwyp85X7TCbD4OAgFy9evMqQer2K/7UYQYsWsGCtCAEo2NAs5e13owpgOp3mwoULRCIRDh8+XLigXI9itoAh++G/2uisdDrN8PAw6XSaY8eO4fF4VnWcYlQAlxok0XWdwcFB+vv72blzJ3V1dUVdw7Xue2W7OJFI4Pf78fv9DA8PF0REvkKYN8a+WWwkw+r1LgCvxGg0YjabCxPGqVSqYEh9+fJlMpkMHo+n8Hq7XK518/hUVV3VVgWxB1BQDIQAFGxYluPtlxcnV1bb/H4/HR0deL1eTpw4sayWUbFawPk1rvZYwWCQ9vZ2LBYLDodj1eIPbn4FUFEULly4QCgU4ujRo9dc62oF4EraxXa7HbvdTl1d3aLp4omJCbq6unA4HItMitdrxehWsNEEICweXLFYLFRVVVFVVbVI/OctZ4BFAyV2u/22Pd7V7AHUNE3sARQUBSEABRsSTdNIp9NLevvlK2z5Vouu6/T39zM4OEhrayv19fUrioIr1vTuaoRXvl3d09PDtm3bcDgc9PT0rHktN8sGJhqNcu7cOaxWK21tbdc1+l3rxXel679RuzhvQbLQjHo9VYxuBRtRAF5vO8WV4j8/POT3+5mdnaWvrw+TybRI/N/K4aHV7AGMx+Poui72AArWjBCAgg1FvuWbn/Jdytsv/+GqqiqqqnL+/HlSqRTHjh3D7Xav6NzFagHnj7USAZjJZLh48SKhUIgjR47g8/mYn5+/7SbOcO0hkKmpKS5cuEBjYyPbtm274Wt0syuAS3Gr2sUbRVRtVAG4nDVLkoTb7cbtdtPU1ISqqoWBktHRUS5dulSoBuf/rHabxnJYzR7AeDwOIFrAgjUjBKBgw5D39ltJnFu+2jY7O0tPTw/l5eUcPHhwVR/qxWoBw8qqieFwuDChvLCSVsz27Vou+gsj6TRNo7e3l9HRUe66665rxs9dbw2rpZj765ZqF3d3d2Oz2RZNFy/nvST2AN5cVjtQZTAYCq9lS0tLoRocCATo7+8nkUjgcrkK1UGPx1NUu5nVtIBjsRhGo1HYHAnWjBCAgnXPld5+kiQt+wKVF0hdXV3s2rWL2traVa/jevsJV3uspcTbQlPq5uZmWlparpp8LUYFMH+u1V708wIulUrR0dFBOp3m+PHjy96jdLsrgDfieu3iQCBwx7aLN5MAvJKF1WDI+mvmtwdMTEygKMqi/YNrnSZfjQDMx8BtRN9DwfpCCEDBukbXdRRFQVEUgBWJv3g8TkdHB7qus2fPnmUlY9yIYtm3wNLiTVEULl26xNzcHAcPHixEZq3kGMth4UDKah+TJEmkUilOnTqF1+tdcYV1PVUAl+JKgRCPxwsDBrdjuvhmsJkF4JVYrVaqq6uprq4u+O/lvwAMDg4usqQpKSkpeFOuZN2rEYCi/SsoBkIACtYt+apfXuSs5AN+cnKSzs5OampqyGQy1x1AWAkL9xOudV/QjfYTRqNR2tvbMZlMtLW1XVdEFCPGbWEFcDXouk4oFGJ+fp7t27fT1NS0KvGwXiuAS3FluzgSiTA/P39VuzhvU7QREALw2kiShNPpxOl0FrKq8wMl09PT9PT0YLFYFg2ULPW5s5oKYDweFxPAgqIgBKBg3bGUt9+NyMeMTU9Ps3fvXiorKzl58mTRpnfz51gr16veTUxM0NnZSUNDA9u2bbvhRW0p/73lrgNWZ0mjqiqXLl1ifn4er9dLc3PzqtawlgpgMaaYi4Usy3g8HjweT6FdHAwG8fv9pFIpLl26xPj4+LpvFy93oGI9cTui4Ba+3s3NzaiqWni9h4eH6ezsxOl0FgThtdJoVjMEEovFbqt1jeDOQQhAwboin/s5OjpKc3PzisRfvnJmNBppa2srtGOKNb2bj5YrVhzcwuNomsbly5eZmppi3759hRbjUsdY6wBH/n4rFVHxeJz29nYkSaKpqYlIJLKq8y9cQ/7/14ugWysmk4ny8nLKy8sJBoMFA2y/31/wo1uYXbxe2sWiArg6DAYDpaWlhe0a6XS60C5emEaTF4ROp1O0gAW3FSEABeuGvLdfMpmkv7+flpaWZd1P1/VC/mtjYyNbt25ddDEopn1LsbwAFx4nL6YAjh8/jt1uX/YxYHX7iPLk91SuRNReGek2NjZGOBxe1fnza1itqN5IgtFisVBWVkZtbe2i9mE+z3Y108U3AyEAi4PZbKaysrIwCb/QkHpsbAxN09B1nampKcrLy3E4HMt63kULWFAshAAUrBtUVUXTNEwmU+HDcakPxHwOqN/v58CBA5SVlV11m9vp37fUcWZmZjh//jw1NTXs2LFjRRexYghAWL6I0nWdgYEBBgYGFk1Ur1WEbTSxsVqunOBe2D5UFKUwbdrb20symbxt08UbUQAuTAJZr9hsNmpra6mtrUXXdYLBIOfOnSMYDDI8PIzRaFy0f/B6FWFRARQUCyEABeuGvGffwvSOG1VBQqEQHR0d2Gw2Tpw4cV1frGILwGK1k6enpwmHw+zZs4fq6uoVH2Mt+/euPM5Sx8hkMoXc5CtNtIshAO+EPYA3Yqk1Go3GQrsYWGRGfavbxRtBTF3JeqwA3ghJkgpbVPbv318YpgoEAoyPj9PV1YXNZltkSJ2PqyxmDNzf/u3f8olPfKKw9eRv/uZvOHr06DVv+4UvfIFf+7VfW/Qzi8VCMpksyloEtx4hAAXrhnw7Ml/NUhTlmgIwH4nW29tLS0sLzc3NS6aBrKcWcDKZxO/3A9mW72q/za81U3jhcW4kUCKRCOfOncNut3P8+PGrJhvXOo28kWxgbhULq0W3ul280SqAeW/OjbRm+NkASP5zLy/0tmzZUqgI5+1m8ilAzz33HJlMZsV2M9fia1/7Go8//jhPPPEEx44d49Of/jSPPPII3d3d192D7Ha76e7uLvx9oz3ngsUIAShYN+Q/TGRZvq7QSqfThUrU4cOH8fl8Sx53PbWA5+bmOH/+fKHis5ZWzmozha/kRseYnJzk4sWLNDU1sXXr1mt+4K91GnmtFcA7neW2i30+H6WlpWtuF29EAQisaRvE7eBGWzeurAinUilefvllpqenOXXqFJFIhIGBAR5++GEeeughDh8+vOLX7K/+6q/4zd/8zUJV74knnuA73/kOn//853n/+99/zftIkkRVVdWKziNYvwgBKFiXGI3GgvlzHr/fT0dHB16vlxMnThRaIkthMBhIpVJFWddqxaSu6/T39zM4OMjOnTvXNDW7kGJ4AV5LgGmaRk9PD2NjY0tOJRejDbsZKoDFElU3ahePjo4CFPaRrcaceKO1gPPv/40kWmFlHoAWi4V77rmHe+65h3e+851UV1fT2trKM888w5NPPklnZ+eKzp1Opzlz5gwf+MAHCj+TZZmHH36YU6dOXfd+0WiUxsZGNE3j4MGD/MVf/AW7d+9e0bkF6wchAAXrkoVCa6F4am1tpb6+fkUf9re7BZxOp+no6CCRSBT2z/X09BTyc9e6nmJXAFOpFO3t7WQymWVFut3uPYAbgZspUq/XLp6amqKnp6fQLs63GJdqF2+0CuBqjOLXA6vxAISs4G9oaODd73437373u1f1es3NzaGq6lVZ3ZWVlXR1dV3zPq2trXz+85/nrrvuIhQK8X//7/+lra2Nzs7OgsWRYGMhBKBg3bDwQ8xgMKAoCslkkvPnz5NKpa4aPlgut7MFHAgEaG9vx+v10tbWVrj4FkO4Fes4C6uI+cnEkpISDh06tKy9ZcWcAs5kMoTDYQKBAH19fYyMjRHPZDBaLGhAIpVCUVUUTUPVNIZHR3H+4AdEQyHi4fDPqkGADsiShNvno6KqCofVis1mw+lw4HW5KHG7KfN4cLtcuFwuHA4HNpttwwmJhdyoXdzX10cymcTtdhf2D7rd7qvEgxCAt4bVpIDA1VPAt+q1On78OMePHy/8va2tjZ07d/K5z32Oj3zkI7dkDYLiIgSgYF1iNBoJBAJcuHCB8vLyFefLLuR2VAB1XWdoaIi+vj62bdtGY2PjVTYgNzNRZDXHGBkZobu7+5rrvRErEYC6rhfi0ianphicnKRvaIjB0VH+86c/JRqPMzk6SjyRwO71YrbZSKfThObm0NJpShsaQFVJp9OEZ2eZGh3F5XbjLi3F4XZjNJuRDQZMJhOywYCm6/hDIQZPn0bSdUwOB8lIBCWdRs0nzQBoWvZ+sozTbqe0vJx9e/fy8488wvZl+lGuR5bTLl6YXWyz2TakAFxJRvh6YbUCMB6P43K51nTusrIyDAYD09PTi34+PT297D1+JpOJAwcO0NfXt6a1CG4fQgAK1h2appFMJhkeHmb37t0Fv7nVcqttYPKWKeFwmCNHjuD1eq+6TTErgMVoLw4NDRGLxTh06BAlJSUrXsO1HksymWR6eprT7e08++MfoxgM2LxeYuk0KVVFJftahwMB/LOz9A4OEpyZweXzYXW5iIbDmNNpLDYbFQ0NKOk08+PjeMrLScfj1LW2Ut7aSll5OUajEU1VyaRSaJkM6WQSVVGI+f1EAwEkWcZoMqEkk+x/+GEqcwI3X2lW8/dJJomEw4Smp/nvkyf58r/+K5qqUl5VRUNDAzu2b+fgvn3sbWmhrKxs2aJjvYiqK73owuHwonax1WotVISvN4W/3thoFjB5VuvfmY+CWwtms5lDhw7xzDPP8NhjjxXW88wzz/Ce97xnWcdQVZULFy7w6KOPrmktgtvH+v/XLdhUxONxOjo6UBSFpqamNYs/KH4F8EbCLRQK0d7ejtPppK2t7bph8DcrUm6lxONx4vE4FouFtra2VfnLSZJEJpNhZGSEroEBzvf2MhMIMB8O4w8GmRwepqKxkfnxcYxmM06fD13XMZpMWB0OSmtqiEajVG3dygO/+quYHQ6MCy7oqqYhSxKzY2NkUikyqRT3/n//H7LBwPDQEJWVlVhzlSs0jXgsxkRvL5lgkJrt26moq8NgMpGIRAjPznLpJz9hemAAg8WC1WbD7vVSUlmJzeEgmskgSRIWu53KxkaqmppIJxLMjIzQ3dND3+Ag//pv/4amqthtNkp9Pprq6jiyfz9td9+9osrp7UaSpGu2i/v6+vD7/Tz//PNLtovXAxtVAK5mD6Cu68RisTVXAAEef/xx3v72t3P48GGOHj3Kpz/9aWKxWGEq+G1vexu1tbV89KMfBeDDH/4wd999N1u3biUYDPKJT3yC4eFhfuM3fmPNaxHcHoQAFKwbMpkMp06dorq6GrvdXjRbh2JXANPp9FU/13Wd0dFRuru72bJlC1u2bLnhxXI97AGcnZ0tWNI0NzevSPzF43EGBgc529XF+e5uOvv68JaXk1YUkGXUTAZ0nbG+PupaW3F6vVRt2cJ4Tw/7Hn4Yp9sNuerlpRdeoKShgQMPPEAqk0GWJFRdR9J1NEkinUwy1N6OyWLh0KtexURfH3NjY5TV1aGqKololHQ8TnB6moneXnRdx1tdjaeqCjSNmZGR7Ouv66Dr1La2MtHbS/2OHUQDAYYvXiQWDqMqCk6Ph4qGBipbWqjbuhWjxYLBbEbWdWYnJ5ns62P7kSOg6wQmJ5mbmmIkEGD4uef416eeQs5kaG5o4PWPPsqRI0eua06+Hsm3i6empvB4PJSXly/ZLl4PbLSp5TxraQEXIwnkTW96E7Ozs/zv//2/mZqaYv/+/fz3f/93YTBkZGRk0fMaCAT4zd/8TaampvD5fBw6dIiTJ0+ya9euNa9FcHsQAlCwbjCbzdx99904HA4uXbp0lQ3MarnZQyCKotDZ2Ynf7+fgwYOFMPgbcTv3AF4Z6TYxMbFkZSeVSjE4OMhXv/Ut/IkEkXSaaCaDqutk0mliqootk8FoNmOx23GWlBANBjm6YwcN27ejAZIso8symVQK3WBA0nV6X3wRm8cDQHB+HiWTQUmnyaTTKIkE06OjzAwNUVpTg8lspuPZZ5Ekicm+Pup37yYcDjNvNBKZn8fuclHR3Izd6YTcPkCjwQCShJR9skgnEvgnJzGazfSfPUvTvn3suuceLHY7SjpNPFcl7H7xRXRdx+F2Y8/56um6jqooPP9v/0bjnj14y8tp3LULs82WFYNjY1isVmIWC5/+yldQnniCPbt28cj995NKJFb3At8G8u3qK9vF+b2bC9vFeTG4nOnim8Vqp2lvN6sVgLFYrGhRcO95z3uu2/J97rnnFv39U5/6FJ/61KeKct6l2CjbDzY64hkWrCucTie6rq/L+Da4WrhFo1HOnTtXaKEut+Jzu1rAmUyG8+fPE41GC1PVU1NTVx1D13Wmp6c509nJSxcvMj47SyiVovfsWZw+HxVNTUiShMlqxVVairWykj0HDmC22QoVwPPPPkvLoUOEAwGiwSDxaJTw9DT9p09T1dzM5MAAssGAxeHAPz/PnNOJrmlogMloJBIIgCRRt2MHZqsVg8GAJEmo6TTu0lICExPMTEzgKS2lafdunCUl2L1enLlWpa7r6NkHzfTICPOTk5jNZsrq6mjZt4/es2epbGrCW1aGTvaiUy7L6JKEDKTicWbHxghOTWFzufCWl6OqKha7ne4XX8zuRcy1pPWcCJENBtLJJJqm4ams5ExXFy9fvIjZZGL3qVO8/pFH2L9v37quDF5rv6IkSbjdbtxud6FdHAwG8fv99Pf3k0gkFrWLXS7XLRNlG7UCuJo9gKqqEo/HixYFd7sJhUKcOXOGbdu2UV9fTyKR4Hvf+x4vv/wyr3nNa7jnnntu9xLvaIQAFKxL1oN581LHmpiYoLOzk8bGRrZu3bqii9DtaAHnI90cDgdtbW0FI+28WFIUhf7+fn587hydg4PMRqMkk8ls9S43GOD0+bA4HLQcOYKntBTJYEBJpxkaHUVVFKaGhogFAkz29qJkMvS9/DJWtxsZUBUFq9tNOpEgMDWF0WSicc8eZIsFdyzGrr170WUZJZWi7+WXaT54kMotW0DXs3sGcy3jTCqFqqpMdnez/zWvobKmBjIZYqEQ8yMjjITDkJsMTcbjWO12Suvr2Xn33ci5qoIO1O/axVB7O+6yMnRdx2QyoWsaqUSC6Pw80WCQRCiEJEkEZ2YY6+nBbLHQsGsXh1/1KqaHhtjR1obJaESWJBRFIR4OE/b7ic7PMzU0RDQQwOpyMTU9jdnt5qP/8A/IqRS7tm3jV9/4Rnbs2LHm90CxWc7AitFopKysjLKyMiA7XZy3m7nV7eKNvAdwpVWuWCwGUJQ9gLeT/Hvs7NmzvPvd7+af/umfqK+v5+tf/zrveMc7aG5u5qtf/Sr/9E//xCte8Yrbvdw7FiEABeuKvBgxGo1FFW35vNC1XijyAvDixYtMT0+zf//+gsXGSrjVAvB6kW7pdJq+/n6+8cwzBNJpAokE6XSadCoFkoTZYsFXXo6nuhqH283opUtkkkncZWVE/X78U1OEZ2aYmplBb2nB7vPhLCtD6+qieutWUokE8UAAk82G0+fD4fUSnJzEVVLCnnvvRcsJuvTICPFUitH+fia6umjetw9XRQXk9hRKQEZVmR4YwD86St2ePeiahslsxmgw4HC78ZSUkFEUZoaGmBkZwWA04q6oIBEOE5iYQJZlvJWV2CwWFE3DbLNhslqZn5ggnUgQnp1FSaezVU2fj7KaGuw7dxYqj5qmEY9GGe/qyraHvV5mR0epaWpCJyuKXLnHKG3ZwvbDh1EVhYHz5wm9+CKjly9T39pKbWsrM8kkH/jEJzArCq9/9FFe/9hj66YquJqJZZvNhs1mo6amptAu9vv9TE9P3/R28UbMAYbVtYDj8ThA0VrAt4v8e2xycrIwMDc6Osr3vvc93v/+9/MXf/EXvOc97+ELX/iCEIA3ESEABeuSYlftoDh7hTKZDKFQCE3TaGtrW3Vlo1gCcKkoOE3T6O7uZnx8vBDplslkeOr73+c/n36ayUCAsKZhdjiwGI0gy9kWb0sLpXV12D0eNE1D1zTmRkbwT0wQnZ8nnUhQUV+Pq6wMq9tNRFFIxeOkIhE0WcZks1Hb2ord7UZaIOBSySRRv5/tx46h6joGWcaQq+wNdneTmJnhwCtegS5JhEMhZmdmkE0mDIrCVG8vlQ0N7LrvPiRZJub345+bo6KyknQyyURfH8HZWSoaGth7333Z112SUDUNNZlkZmSEnp/+FLvTic3jIRYKEZyeZmpggG1Hj9K8fz92mw1N19E1rbDu/PMI4HC5aD10iGAwyPCFC4x2dVFWXY3FZkNTVbTca6tkMhgMBgxGI1sPHsTs85Hw+xk+fx53aSmywYCjrAyr3c6/Pf88X/7mN3nVgw/yzre97bYPV6zVsmZhu7ipqemmt4s3cgVwpQIwFothNpuv6y6w0YhEIoX3WldXF9PT0/zWb/0WAB6Ph6Ghodu4ujsfIQAF65K8P1uxjgXZD9zl5gdfi6mpKXp7ezEYDBw7dmxNF51iCdwb+QDmI90UReH48eNMT0/zb9//Pk/94AekTCZMNhsJWSYyP48hHObQI49Q3dqKNVch01SVmeFh5sfGSEWjSEYjdpcLV0kJmqoSmJ0lMDuLzePB7vGw68gRjEYjA+3t1O/cid3jyYqo3F48WZIYeOklGg8cIBmPZ/dTahoTMzNE5+eRYjHuesUrMBmNaICvtDRbQWtvxz89TVlLC6rZzNzsLEazGavLhf/iRTqDQdKxGKXV1XgrK0lGowyeP4+iKOiKgqqqaJkM0WCQSCBAKh4nk0xiczqpbG4mGggwNzLC/OgouqahSxLG3ACJwWhEMpkwm80YTSZMFgsmiwWL2UzT3r1k0mme+ed/ZsexY5gsFtScp6AkSYUvHLIkMTU7S2VlJVsPHuTC88+z9cABth88SCKRwGA0ErFa+d6pU/zn97/Pr7zxjbz1TW+6bVWtYnsWXtkuTiaTRZ0u3kwCMBqNYrfbN2TFcyH59ee7ER//+Me5cOECJpOJBx98EFVVmZ6epqam5jav9M5GCEDBuqSYLWBJktY0dbuwitbU1MTk5OSaLzg3uwWcj6AzGAzMRSJ8+IknCOg6Pe3tpOJx3BUVeKqq2HHPPSQBAzB9+TI2rxddVZkfHkbVNDwVFfhqakiGQkz295OKRvHW1GBzubItTklCUxT6Bweza9F1IrOzNOzdS0bTMOSqfEZJYqS3F09lJa6yMkKTkySTSSYmJ4nOzhIcHeUVv/RLqICkaaiKwvzkJD0//SkOj4eKqipS8/NEEwlm0mmS8Tjzk5MEx8fZ1tZGZXMzLo8Ho8WCyWTCYDJhkGWCs7P4JybAYKBhzx5Ka2sxWSzIQCwSYbizE1dZGRVbtlBaXZ21ismZICuZDPFgkODcHKGZGVKRCMlEAjWTQVNVpJxAjASDXHz+ecrq6qjesgWnz4fN6czuKcwdLwGY7XYsZjMHHnyQ888/z+TAAJX19RhMJqx2O9a6OiLBIH//5JN86atf5f986EMc3b9/ze+RlXKzhyqsVis1NTVFaxdvVAG4miGQWCy24QdAFn5hvffee3n961/PRz/6UbZs2cJf/MVfAHDu3Dnm5uZ4zWtec7uWuSkQAlCwrsh/MyxmC3gtx0skEnR0dKCqKsePHyedTjM2Nrbm9eSF21qrLVcKwLzFy/effprBQICExUIwmWRqcJBUNIqu69z75jfjqaxENhpRNQ1lZobQ9DQYjZz+1reo270bT0UFMb+fwMQEjtJSfNXV2Hw+lFgMR0UFc4OD2ag1TQNJQtZ1kCRiwSA2jwejLKOpKtFwmGQsRmx+npELF6jfuZPJ7m6GOjvp6+oiE4mQDIWQzGZ+9JWvZKsiRiPpRIJMOs3WI0coqajAaLVizU2IT/f1EZqZYe/dd3P+pZdoOXCAtKKQUBSsuk4qFiM8NYUSj+OprKTl4EHMuf11+YuPLEnYXC52HDvGeG8v5595huZ9+5DNZpLBIEo6jWwwYHe7cfl8VDU0YHO5MJpMWZFI1qBaAsb6+9EUhdDMDHMTE5SoKv7x8YIwsXs8KKkUroYGPG43ZdXVOH0+pkdGUFMpGnbuxGyxEI9EsDocmMxmpoeHeevb3sbd99/PX3zwg9TmvNluBbcytaQY7eKNKgBXsyUlbwGzUSuAC99bmqZhNpt5//vfz/vf//5Ft2tsbORDH/oQzc3Nt2OZmwYhAAXrEqPRWLQWMKxOAOaNkisrK9mZGwZQVbVolTtY+8V2oQCcnZ3l81/7Gmd6e7HV1RGan8c/Po63spKd999PcGKChj17sOZsUmLhMJM9PUwMDGCy2ykrLaWmtZXxS5dwlJay9cgRTDZbVqgCgdFRkGUsdjvJWAw9l7+q6zrJWIypvj76z57FYDSSjEQwmEzYHA4MNhtjly9Ts2MHiqoSCAQIzMxQabNhkiS2P/gg/nCYlu3byWQyDJw9i83lwldVRSoSYTIUwmixoGQyJGMxGvfsoXbHDiRJwup0Ius6VZWVTA0NMdrTA0YjrrIyXLmEEDUntI2yjA7Z/YjpNMHZWYIzMyQiETLpNDNDQ9hdLnYfP47RZitMH+fvI+WMpJVcfrAMZDSNyvp6+s6cYe+99zI5MEA8EGDHsWNIskwmmSQaCjE7N8fwxYvZPGKzGUdJCelkki179zJ6+TIVTU2U19Tgq6igUZJQ0mlmR0Z47pvf5OFHH+XVr3kNH3z8cUquEStYbG5nbN1K2sU+nw+73b6hBeBqKoBrjYG7nUiSxMmTJ3G73ezZs4f+/n5mZmbw+XyYzWasVitWqxWn08mePXuEF+BNRjy7gnXJ7awA6rpOX18fQ0ND7Nq1a1EcXbEMnIs5mPLiiy/yyc99jktDQ6R1nWQohH7uHDXbtrHt+HFK6utxlZQwNziI3e1meniYmYEB0slkdo+bJGG0WPA2NtJSUcG2tjZ6Tp5E2r0bA6BBYYoaWc569M3NMXDuHBG/H11VCcXjVO3di8XpZM999xGPRIjOzRELBpm/fBmDLGM2m4krCqVbt6LGYpTV1rLzxInssfv6MFutDJ0/T8v+/XgqKwtDGOGZGfrOnMFss2FzOpkdGMgOoTQ2YjAa6Tt9GlcuwePQQw8hGQyouk4qkSCVTDI7N0cmnUZLJEgEg6ipFBa7nZKKCqq2bMHmcoEk0Xr33cyNjdF19izbDh/GYDAgSxKyJGUHQ3L+lOg6Wk5QGnQdyWpFkmXUdJrqlhZmh4fpPn2arYcOYbJa8ZrNlCUS1FZVIZvNpBMJQnNzGE0mfvqd79CwYweDFy6QSSapb2khrSgYzGaqt2zh/3vvezn73HP89MUXec2b3sSrXvEK3ve7v3tTRcB6yS2GpdvFFosFo9GIyWQik8msaY/vrWa1ewA3+gTwV7/6VXbu3MmePXt48skn+drXvkZ5eXnh35fRaMRiseD3+/noRz/Kgw8+eLuXfMciBKBgXZG/8OT3ABbrYrRcAZhKpejo6CCVSnH33Xdf5beVN3AuRuUOWHU1MZ1O841vfYt//OpXybhcKJpGUlGo2bKFXa94RbZ6lk6TCAYJjI9z/vvfJx4IMDc+jsliweF246upoayhAVXXSWYyeMrLkSQJl9NJVWsrA2fPsuPoUWRZJhOLMT04SHBqivnRUZLRKCU1NdTs3k0qFuPyuXPMjY4yPzxM/9mzOEtKcJaUUFJXRyaVYuc99zA1PY3bYMCiaQwEAhz/xV9Eyz0Hwelp4mNj7Gprw2i1gq6TjMcZ6ujAZLGw9xWvwJT7uZbJMNDezvkf/pB4IkFDayt35S8SuSqdJEloBgOxUIj45CSZTAaz04mrogLJZMq2re12VEkioyjYXS6SsRhVjY1YLBZ6X3qJ7ceOYTAasxfpXOU3EYuRzgnLTCqFpiikkkkioRDtP/oRLq8XHfBPTjLzzW9SkcsGnp2ZITE7i9VqRTYaMVss1G3diqYolNbU4PT5uPziiwxfvkxDayulNTXZ6hZw6BWvwJzbT3imt5fXv+1t/OrrX89bfvmXixaXuJD1JAAXcr128cDAAJFIhBdeeAGXy0VJSQmlpaW31Ix6NaxmD+CdYAL9lre8hZKSEgDuu+8+3G43siyTSCRIJpMkk0kURWFiYgJPLiVIcHMQAlCwLllYIStGG2A5AtDv99PR0YHP5+PgwYPXPG9+Xav58F7Iwn0wKyEej/PUD3/Ik//+72Q8HlIuF/7xcbbffTcHfuM3MFutKKqKLstYzGZUq5XQ7CzTfX14amqQJAm7283Wu+/G6fWiAJFAAKMsgySRX01NUxOzAwN0vvACmUQim8RhMtG4fz+lNTUEJiYY7+khk0xistvRdB2bx8Puhx6ifvt2JFkGTaPr5EkqW1sZHR/H6XRikSSGc3sBDbnnYKijg0QgwL5XvxpZkshkMkz39xOamqJ5/34cPl+2HatpWY+/oSEcJSU88Cu/QndnJ2NnzzKa9x2MxZgbHSU0O4vJaqWspoatR45gNpuz+/9yLd1UKkU6kSAaiTA3N0cslUIbHkbNVXsNRiM/+fd/p6y2NtvmztnCmCwWzFYrZosFOdeycpeU4Pb5mB0ZoWXfvuztDxxgoL0dZ1kZpRUV4HBQ4vNhNhjQVJVkTjRKBgOXTp2irKaGysZGJvr7GenpYWJwELPZTHl9PWV1dew6doxLL71E7ZYtpJJJvvPTn/LUM8/wpx/4ANu2bVv1+/BarFcBeCX5drHf70eWZerq6grt4vHcHsyF08XrqXWq6/qa9gBuZO6++24g+xw89NBDPPTQQ7d5RZsXIQAF65K8uCpWJuSNBKCu6wwODtLf309rayv19fXXvQDmP7BXm+OZZ6WTyeFwmG8/+yw/uXyZzsuX0TSN2NAQVbt3s/c1r6GuoaGwH082GJgfHeXSD39IdH6emt27aT54kCOvfz2appEMhxk+fx6j2UzDvn3oZAcaLLJMUlGYHx7GPzKCJEn4R0fZ86pXEff7GenoIDA6SjIcxuRw0LBnD3aPBxno6+sjMTlJ85YthUneyOwssUQCKZmkorwcE9Dz4ovsvOcehjo6iMViDHV0UFpVRY3Hg9FgIDQ/z+C5c1Q2NbHzvvuQACWdZmpggLmREcobGthz//1Iuf2HpTU1xCcnmRke5sJzz9G0dy+Vzc3UbN+OIZfQkd+3qZPdt4euIwNaKoUaDpMIBAhNTzMaCDA9MYHRasVXUkJJfT02l4uWvXsL4lHLTchquo6k68iShA64dZ2pwUEksxlZ05AMBpr37+fyyZOUlJdjtlrxer0YTCZUXccDqLpO7datXPrJT9jT1oam6zTddRedP/oRJVVVpKJRBi9coPPkSZw+H5X19SiZDJ6cIK7cu5fH//RPed3DD/POd7yjaNWujSIA82iahtFovG67eGZmht7eXiwWy6Lp4tvZLs5/8VtNC3ijVwDz20kMBgOf+cxnOHHiBIcPHwYWf65+73vf4+jRo8vKVhesDiEABeuK/IVHluWi7beD6wvAdDrNhQsXiEajHD16dMmWw8IKYDHWtNRxgsEg33r6aU6PjOBXVTp/+EMcJSWU33UXe3fswO5wkIjHITc4MHzxIn0nTyIbjbTefz/1ra0kUimGX3wxKxABh8/HjnvuITA1Rddzz+GorsZgt9Nz+jTxQABPTQ1lLS1EZ2YITUzQ8b3v0XLkCJVbt2J1Oqlqbmbw7Nns85CrqGVUlXQigd3lyv5dUTj/wguU79xJbV0dRkni8o9/zM4TJ7DZ7aDrdD73HK3Hj+MuLaWvu5uel19GzWTY0daGzW5HURSm+vqYGxujoqGBPQ88UBA5yUSCqYEBei9cID4zw5777sNbXs5IZycA87loOlVRshW3WIxEOEwqHs9efIxGLHY7VocDm82Gx+slGQ7jcTqzE71TU6RSKXpefpmhy5dxeb3YnU4cDgcGsxmD2YzVZsNitSKbTFis1mzbWVVBljHqOkaDgS379jHY2Ym5rIykquLMTRHrsozZYEAHPGVlzE9P4ykrw+ZwsOf++xns6KD12DFMskwqmWRqaIihzk4mBwdp3LWL2i1bmBge5sQb3sCPf/ITzrz3vfzl//k/RYkI22jJGtda742miwcGBkgkEoV2cUlJSaENeSvXDCsXgHeCDUz+yxvAU089xVe/+lU++tGP8sADD2AwGAgGg3zqU5/iIx/5CO3t7UIA3kSEABSsW25Whm+eUCjEuXPncLvdi7Jxb8RaPQUXciMvwFAoxNefeopTXV1Mh0IExsYIjI/jqa/HUlkJ8TiB3l5mMhkioRD9ySShqSmc5eUc/aVfwldRQTonzpLz89i83uy3a1kutEG9VVVIus6pb36TZDzO7nvuwWixEJmaQlUUShsbaT5wgIvPPktFXR2zExNomkZG0zBarWTicVw+X1bwJZNYnE4UTctG5f30pzh8Pra3tKACl37846wdi82Gf2qK8Z4e9t5/PyWVlfgnJhg6e5b9992Hr6oKVVEYvXiRiaEhfBUVlNbXk4rH6XvpJQJTU0Tm50GS8FZW4i4tRUomsTqdmC0Wdt13H4PnzlHR2Iim62ipFAaTiYrGRjwVFXh8PrTccImUfUGzlT1NQzp5kp1tbdnWdK7tG49E6Hr5ZWp37SISDhNPpTAqCrKqkk4mkVSVZCKBkk4zNzpKMpHA7fNhdTqx2O3Y3G5MZjPRQIDqqipkWcaUFxq5iqKvpoaZoSF8lZUYJAmLzUZpbS0TPT007tyJyWajats2mnfuJBaJ8OP/+A8ifj9KOk1kfp6DDz3E1MAA7/jt3+b//vmfr9k6YyNWAJcSbzeaLr5Wu9hms93U5yD/+bFS0RmPx6m8hZZAN4v8437yySd597vfzW//9m/zsY99jJKSEh5//HHm5uZ46qmnuOuuu27zSu9shAAUrFuKnQaS/9DVdZ2RkRF6enrYunUrTU1NK/qwv5kCMBwO88STT/LMyy8TjsWQjUaMZjOlW7bgqq+net8+qmtqsJrNjPX0MNbZSWBqCo/Hw9bc3pqR8+cZNxhwlpXhrq4mFgjgKi3NxpTlpln9ExMMnztHKpHAXVmJKRxmqqeH/a9+Nc7SUgy5b+kZRaF2717629vxVlRkEzIkCaPNRiKRQNE0DJJEcn6e8sZG0qkUoyMjRKanueexx9CA/pdeom7HDjzl5cwODzPR18fWI0fQdZ1LJ0+SiERwVVYSnpqi5+RJgtPT+CorKauvx2yzZYVOMEgqkaBu1y4qm5owms0gSUyMjzOZ2yYQnJ4mGY3i9HqZ6Ovj4Ctfic3pRJLlbMs359uXf6XzCSUARklCJvs+kQBd09BycW4Wi4VMKITP5SJlNJKMxYjGYqRSKQyShMlsxuJ04qmsxGg2Y7RaScRiRPx+0skkqViMwa4u5EQCX0UFnpIS7D5fdt+lruN0uxmORNA0DUXXMUgSVY2NdL30EpFwGLvLhUmW0SUJi8NB68GDuEtKSMbjnHn2Wb7/pS+x89gx6o8c4Xc/8AH+5H/9L44dObLq9+WdKACv5Mp2cTQaZX5+/pa1i/OtzpU+z3fCHsCFlJWV8bWvfY23vvWtvOENbwDg137t13jiiSc21ET3RkUIQMG6YuEHYjHTQPICUFEULl68SCAQ4NChQ4VptJUeq1hegPnHFwwG+Zu//3ueefllZI+HkuZmPLlc3pq9e3npP/+T+sOHKfV4mLh4kXQ8jmSxYDSbabz7bu66+25kXUeTJNA00DSCU1PMDQ4y+PLL1La2oksSqViM7uefR1MUqrdto2HvXmSHg0QySZnHQ8/Jk1Tv2IGvthZZkjAZDJRXVTHZ3U08136SJAmHw0FoZia7x07XCc/Nkaqr49LZsyQmJ/F6PIx0dDA5MIBsMGBxOhlsbyfq91OzfXu2mjcxQcPevZQ1NDDU389MJELD7t0cft3rMMoys6OjzAwOYrXbadq9G2dJCVJONIdmZwlOTjLS309sZobKpiZqtm3D6nRiMBiY7O9ndmyM+h07shvuc21CCUglEiRjMdLxOIl4nFQ8jpJMMtrdjarrhcqg0WTKxr/ZbIxevkzDnj1IBgOekpJC5TOVTpNJpbITjIqClkhg9/mwud0YJYl0Oo2mKExPThIJBIiFQvRHoyQTCWRJwu714i0vJxIOk4xGsTmdGHPvr4bduxm8cIEdx45hNBhQNQ2DLFPV0kL/uXPsPHqUR9/xDn76ve8xfOkSdocDd20tH/7MZ/gfb3sbj/7cz61KyG0GAbgQSZJwuVy4XC6amppQVbXQLh4cHOTixYuLzKiL0S5erf3TndACXkg0GuUb3/gGAwMD3HPPPYyOjmI2mwkEAlRUVNzu5d3xCAEoWLcUuwUcjUY5efIkNpuNtrY2LLl0iNu1LoPBQCqV4rNPPME3f/ADDGVlNBw7hsFiIRWLseXwYXSLhe7Tp5GMRuJDQ+guF776eqZ7erC7XNTu3Us4HM4KHFnGIElkAJPJhKe2Fl9dHdHZWTTg2c99Dk1V2XLkCNvb2igpL0fVdQKBQHYjvd3OnoceoucnPyEdj1O1bVtWUOo6LXfdRccPfkDjwYOouo6q60z29RELhcgkEsz19mK226mqqiKhqlS2tDA7NEQsGMRbUUHX888jAaX19QycO0ciGKRx/34a9+xhsrcXi8PBofvvR1IURi9dIub3462pYceJExhMJvR0mumhIQJTU2SSSZwlJfiqqjCUlBAcHKSioQGbw5EVL0BZXR0d3/8+RqORVDyeNa5WVXTI5gjb7VjsdpxeL2XV1VhsNlBVWtvaCoMd+cQPXddRk0kqGxuzSSB5kQ0FUaZqGqH5eSb7+7H5fCQTCbSc8HXYbLRKEno8zs5cZU5VVVKpFMHZWeZGR5kbHeW5r30NRy55xF1ejrOkBIMsE/H78ZWVQe55t+QmslPxOFaHg6OvfCWXf/pTrB4PwZkZVE3jb/7pn4hEIrzpDW9YsZjbbALwSgwGA6WlpYW9Z8lkkkAggN/v58KFC0VpF692iOxOqwD+zu/8Ds8++yy/8iu/wl/+5V/S3d3NL/3SL/HQQw/x5S9/WbSAbzJCAArWLcVMA4lGo8zMzLBly5ZCAPlqKVYLuOPiRf7o4x9H8vmob2vDW1PDbF8fJY2NlDQ1EZqfp/vUKabOnGH/o49Sv3MnY11dzPT2suXoUewuF8FoFACTLKPkplJNBgPxaJT5kRHmh4bo++lPqb/rLh7+3d/FW1pKbH6e0a4uhtvbqdm2DYvPVzBdNhoMbG1rY+jcOUbOn6d53z4UTcPk8ZBOpxlpb2duYADZaETJZKjZs4fJiQm8DQ1UVVczfvEiNpeL2eFhApOTHP2FX2Cqv5+qrVspr6uj+6WXOPDKV6IpCueffZbg5CRNe/eiqio9P/0pkixT3dJC8969pBIJZoaGCE1NIckyvspKtuzfj8VqzU4u6zrRiQkyqRRTg4OoikIiHM6+RgYDstlMYGaGhl27sokhBgOGnKkzZFvBsiQVqrlyTtjrObNnSZbRFAUkCVd5OcG5OXxVVdnYO362kV/P/XG43ZhkmdrqanQgnUgQi8cJhkJYbDaG+/oom53N2uGYzVisVqrq66mur6eqqYl0PI7D4yEwOYl/epr5yUlkYOjSJZp27cJXUYGrtBSr3U5lQwMzo6PUbN+OyWKhfvduZoaHuev4cXo6Opjo7+cfvvxl/OEw/+PXfm1F78vNLgCvxGq1Ul1dTXV1daFd7Pf7mZ2dXXW7eLU2UrFYrCiDPusBTdMYHh7mW9/6FocPH0bTNFpbW+no6OCd73wn9957L6FQ6HYv845GCEDBumLhhacYewBVVeXSpUvMzc3hdruL4pm21hZwIBDgj/7yL/nRqVNsvecedt53H1OXLxPx+2lpayMWCPDjL3+Z8OwsvspKyhsaCM/O8swLL+CrqcFVWcnEpUtIBgOKrhOKRnFIErLRSDwUIpQb1jBYLCiKQt3u3Rx/4xuzkWiAvayMXSdOoKTTjHV303fuHGavl5rqavTckMuWQ4cY6eyk58UXcVdUMDswgCRJRIJBDrzmNUTm5pjo7ub0975HOhxGsliwO534amrY88ADXHzuOe5+7DEG2tvxVVQgGY10v/QSzfv3MzsywtzoKI179+KrqaH3pZeYGB7m4be8BafXy9TQEOOXLyMbjZTW1bH16FEsOX/DdCTC5NQUsVw7NRQKocRieEtKqNyyBUdO6EE27q3v5Zdx+nw/2/dHzgoGCqbReaScADTkIuPk7IuNrut4ysrwT05SlhN3RllGgYI9jAGQjEZURSnEx1nsdsxWKx6vl+HhYUorKwn7/USjUVRNw2a343Y4MFut2JxOwvPz1G/bhqu0lIbdu0nF4wSnpgjNz5NMJAiHQvhnZlDTaZxeL7Pj49S3tiIDTq+XwMQEiXicfSdOUFZZyZkf/pBvfPvbxOJx3vfudy/7/SkE4PVZ2C5ubGxcdbt4LS3g9eRnuBZkWeZHP/rRIueH/H+/8IUv8NrXvvZ2Lm9TIASgYN2y1j2AsViM9vZ2DAYDW7duZW5urijrWm0FUFEUvvif/8nnv/QlDE4nB375l4nPzPDiV76Cp7oao8HA0JkzxFMpyrdtY/f99zN16VLWc07TuPtXfgWHw4GS28soqSqRUIiA30/fiy8Sm5/H7HBgcToJjI5itFio2bOHdCxGLBzORp7lhkAUXQeTiea9e/E1NNDT3s7573+f6pYWKrZsycYySRITXV3MjIyw48QJVFVl9vRpLv7gB1h8PtKSxLGHH2aurw/N4SDi97Nl/376XnqJ+l276D97Fm9lJcHZWYwWC5VbtjB47hy127ejZjKMdnbi9Ho5+OijaM8+y/Nf/zpb9+2jtKGBnffeC7pO1O9nemCAaCCAmk5jdTpxlpRQ1dKC2elkbnqa4NgYvro67B5PQdCpqopkMJBRFHRVJZPJoGQyoCik02mUvEWMoqBpGpqqMjc5iWQ0YsptDTDk9htKBgNoGhO9vZhsNoxGI0ajEdloxGAyYc7txZRz7XI5JxolspXB/FeFkupqlGSS+sZGEskkqUSCWDTK7OwsOjA3PU1lNIrFasVsMGByu3E4HBgdDoKTk5hMJlKRCJ6yMqwuF0OXLtHx4x/jraykqqGBxh076HzxRbylpVS3tHBYlrn00kt875lnSCWT/PHjjy8p7PTc87eeEzSuRM95M94OrmwXp1KpwnTxjdrFq2kB67p+R1UA4Wdf+AvbUHKxfgaDgV/8xV+8zau78xECULDuyBsar2Wv3dTUFBcvXqSuro7t27czPT190z0Fb8RL58/zsSeeYHhkBFdFBRVNTfS/8AIldXUceO1rmRkayrZUT5ygoqYGX1kZqViM8QsXOPDYY1Rt3Yoky+iahlWSSGcyTPX3M93XRzqVYv/992MrLSU6O8vomTMc/sVfxOnzEZqZITAywvCFC6SjUYxGI86yMjyVlTh8PjSzGdlgoLyhgYaGBiZ6evjRl74Euk55UxMVzc3MjYxw6Yc/pGbbNnY//DDhYBBLRQVVtbWUl5Ux0d6O2eUiHokQnp/H4nQy0d1NaV0dM0NDlNTUEJyexmgw4KqoYKynB1dJCZ6KCvyzswRnZ3F4vdQ/9BCJQIB4MMjM4CC6ruP0+XBXVFC/fXvWvkXXs1VKsh6O8VCIeDDIrK4TmZkhmRvoyAuZie7ubGvbbM6KtdzjlXIRbyajEXLTmHanE1dJCdbcJnuJnCDStELLzmg0omYyZJJJNEUhk06jptMo6TSapjHe25utHhoMWO12DBYLFrudeCxGSU0N07OzyJKEzWbDlvMOTKZSpFMppru7Cfj9qIqCxWrFYrHgcDgoKS9ndmCA1gMHUBQF/8wMs6OjWO12POXluL1ehi9dQlUUjCYTc1NTlNXUUNXczNzkJAaTiaeeeQYJ+MDv//4NxVL+edtIFcBi5GkXC4vFsqx28WqrrPF4/I7aAzg5OclXv/pVOjo6iEajWZskkwmTyURDQwMf/vCHb/cS72iEABSsW1bTAtY0ja6uLiYmJti7d2/BM6vYAyXLbQGHQiEe/9jHOHvmDPayMmp276bp4EFm+vtpOn6cxOwsgclJfM3NxBWF8spK3E4n00NDjJ4+TdPRo1Ru25adYNV1osEgk11dJMJhSuvr2XriBLNzc7jKyxk+f56Y38/OV7wCo8WCpqpYnU4qW1rYevgwqqahZDJE5+YITE4ydvFiNt7M5SJjMjHe20vPCy8gG41IskxgfJzdDzzAznvvze49HBjA4HIRCwTYWVpKwm4nnUwiGwzMDgxQ19BAcHISHbC6XMwMDWG22QhOT2PKRdK5KyqyexcnJ1EzGWpbWrKP6eJF9Hic0OQk+175Sup370aXJDLxOKlolKmhIRKRCIloNGu2TLblGk8mUZJJDKWluCsrKbfZssM9spwVM7JM65EjSEZj9qKr62TS6ULrVsoNVkC2ZWtzOrHmrGOMOaPmfIXJ4fNRkpuOhqyNDJL0s0ohWeG058QJ0qkUqWSSZCxGKhYjNDlJxu9nuq8PJZ3ODqB4PNjcbuweDxaLBY/bTW1tLZlUilgymW37BgKFx+kPBHC63VTU1lJaXc3c2Bi9Z8+SqKyktqUFq8PBxMAALz31FIcefpjK2loaWluZm5hg3/33819PPYXVYuH3/8f/uK5g2ogC8HZWAG/EjdrF09PTpNNpTp8+vaLp4jtpCCQUCvFnf/ZnfOtb3+LQoUM89dRTPPLII5w7d45oNMpb3vKW273EOx4hAAXrFqPRSCKRWPbtE4kE7e3t6LpOW1vbor0yxRSAy2kB67rOX/3jP/L/nnySmt27OfHOdzI/MpIVRoODGEwmEoEAjYcPo0oS8WgUj91ObGqK4Z4ewlNTSIANGHrmGSJzc4SnpzGazZTX1FDl9aLPzRGcmGB+chLj4CDh2Vk8lZVMnDqFkmtdJmIxEvE4ow4HJqsVp8uFu7QUd1UVuqIQnJig9+WX6f7pT7FaLLQeP07jwYN4yspQ0mmGzpzBPzZG5c6ddLe3I4VC3HXPPcyPjGA2mwlNTWFxOEiNjzPV14cpX9WKxZABRZbRVRVNVVE1jWQ0isVux2C14p+cJDg9jbeqitqdOylxuYjm9haOaxq6rhdEmd3txllais3pBElCTadJJhKMj4wQjMdJRKPMj42hpFKo6TQa2Qre2OXL6KqazSbOvXZSLvfYkBt8ye8CnBsdRVNVjCZTdh/fggg5CZjo6clWpmUZo8WCyWzGbLUW9voZrVZ0XSejqkhGI3aXC5vLhQRkDAZqa2sxG420Hj1KLBwmEYkwPzHByOXLoGnMjI5SVleHt7wcn8cDHg+6phGLx4n5fIwNDGArKcGWyyB2lZXhLS+nZd8+Jvr7iQaDNLa2svPIEfxTU0wNDVG9ZQuJSITGnTs59OCD/Md3v4vL5eI33/a2a4q8jSgAb+UewLWwsF1sNBqJRqOFLOPlTBeruQzpjW4Dk69+dnZ28t3vfpfTp08Ti8V41atexbe//W0GBwd5/PHHxR7AW4AQgIJ1x2pawDMzM1y4cIGqqip27Nhx1f6aW1kBfP7kSf7wIx9Bczr5hQ9/GJvbzbn/+A+UTIZYIIDN48FdXk5qfJz+H/4Ql8VCbV0dlZKEx+PBev/9uDweTj39NOU1NcxPTrL32DEaWlux22xA1qhY1XWUTIbOCxfYd+AAuq5jyhkZZ1QVTdcZ6ekhODdHdXU1wXCYyMQE/YODzE5MkEylcJeXEwuF2HL8OEde+UqUZJL50VFGOzqwl5RQs2MHgWCQk9/8JmXV1WRycWqB6Wkcssz86dMkDAaUdJq0rqOl0wVBJclytlpnMIDRiCHXPkXXcft8hKamiIZCxIJBAtEo5uZmHD4fdbt3Y7NaiUWj2fi2WIyZwUGSiQR6bs+ewWTCYDIRi8VIRCLY7HYMuUg2g9EIOZEXnJmhork5O+Wcj1/LDcwYDAbMFktBEOq6TsPOnZhttmxVSZJQFiQ26JrGzhMn0DUNJZ0mk0ySTiZRUikCwSDJeJyxnh7ImWjbHA6sTicOlwslk0HJtZKRZexuNx6fDxlQyV7c0z/8IRlFYejSJdKJBBabDW9FBc7SUmobGwlMTVFTU0MylSIajRIKh5mbm6MsHKaiqYkKXWd6YIBwMIgM7D1+nLG+vmy+8qVLbNu7l4jfz7/+539S5vHwhsceu+q9u1EF4EZaL2Rfb7PZfN12cV9fHyaTiZKSEkpLS3E6naTTaYCi7AH827/9Wz7xiU8wNTXFvn37+Ju/+RuOHj163dt//etf50/+5E8YGhpi27ZtfPzjH+fRRx9d1bnzAnB2dhZ3rur9rW99C5vNRjwep7m5mVe84hV8+tOfXvU5BMtDCEDBumU5NjCaptHX18fw8DC7d++mpqbmmre72bFyAH6/n/f92Z9x+uJF2t7+dhoPHEDVdZ7//OcZv3CBiro6mltbqaurw2WzUV5fj/fAAfbs3Imiaci5vW2BQIBLZ87Qf/EiW/fuZdfhw5gNhuzwR/52+Qgz+NlUqqYVkjkMsoxRkjAYjbh8vqxZ88wMqWSS/fv2UfO612F3OlGSSabGxjh//jzp7u7shKqu4ysvRzMY6Hr5ZYJzczRs3050fp5UIoF/YADr2bOkR0aIpdPEFIW0zUayuRmT3Y7BbMZoNGJ1OMik01mPPUUBWUbVdTRVRTYasblceCsqCPv9xObmGJiZYWZoiOn+fkxWK6ZcqobZasXhcuHwejEajUgGQ9aPT5aR/P5spdThyFYWcwJY03U0Rcnm8y4Y9IjnsoE1Vc0OgeSGQyRgvK+PRCSS3YRuNmM2mzHabJit1uxzajQiSxKS0YjRYMiuKzfxK+Vei0wqxa62NnRNI51IEA0ECM3NMd7XR3RigtnhYVw+Hw6vF5fPh8liyQ75ABabjfqWFgAUVSUeiRCZn2fo/HkyqRRhv5+yujocDgdutxt0nfDoKDoQmJ8nrShYSkup8Pm48MMfYrLbad23j7LaWk59+9sYjUa2HThALBLhH/7lX2huauLA/v2L3sMbVQBuhArgQq4cAllquvh/5Nr21dXVnDt3jnvvvRez2byqc3/ta1/j8ccf54knnuDYsWN8+tOf5pFHHqG7u/ua5ssnT57kzW9+Mx/96Ef5+Z//ef7lX/6Fxx57jLNnz7Jnz55VPwe6rmOz2Uin07jdbmw2Gx0dHRw7doyhoaFVH1ewfIQAFKxblhJtyWSSjo4O0uk0x48fv+HemPyximFxIcvyImGq6zrf+K//4mOf/SylO3bwSx/7GLFQiL4f/YjRl18mODHBr//u79J6113oksTY2BiB+Xlq6uqye9UkCaMsMzUxQf/588gGAzVbtnDw3ntp3rqVdK4dKuf2tWm5P4Zcrqyu66QVBZPBUIiXU1SV2clJLrz0EulEgl2HDrHr8GHcHg+qpmVjyACj3U5ZbS21sRgH9u/HlIt/m5me5nxHB+FkksaqKhKzs0RmZsik04Tb21FmZlAVhbCmEU0mUcJhDLEY1u3bcbjdyHY7qqKA0YhGVtAo8TjJSITpgQFURSHq92ej0EpKKG1upn7LFqZ6etjzwAOFxyppGpokZS+Wmoasaej5rF5dxzgxgclopKy2Fl9lZaFFq+k68+Pj1O3cSUVTU8HY2ZCr6umwKPNXyr2uLYcPI8syqXQaLZUiFo2SSSSYnZoiNDtL5wsvFJJCzHZ7tsLn8eB0uTBbrciyjFGWUQG7w4HJZqMEUCwWamtrMUgSJVVVBObnmRsfz2Yo22x4S0tRMhnSOdEqAU6PB4/XS2VjI4qqcu4HP2C8r49MIoGnrIyS2lrsDgelXi9mi4VEbt9gOpmkdMsW5v1+Tj79NDVbtlDd1ITV4aD7zBkq6upIlZTwwT//c/75H/4Bn8+36L2cfXgbQwDquan2jSgAbyTgrpwu/sY3vsFXvvIV/vZv/5a3vOUtxGIxHnzwQT74wQ9y7NixFZ37r/7qr/jN3/xNfi3nD/nEE0/wne98h89//vO8//3vv+r2n/nMZ3jVq17F+973PgA+8pGP8PTTT/PZz36WJ554YkXnhp9NmLe0tPDQQw/R1dXFvn37aGho4L3vfS+tra38+Mc/5vd///dXfGzByhACULDuyF98blQBnJ+fp6Ojg9LSUg4dOoTReOO3siFnzVEMAWgwGArtmFgsxnv+6I/o6O7m8JvfjEHXGf3RjzCl0zgkidbt27n/fe/D7nKRSaXoGxjAoOtsa20lGAiQSaUYGxyk/+JF3F4ve44fx+1yMZ6rFCmahjnXfszHlBlz8WuqphX2uklkjZGD8/OM9vYyPz2Nr6KC+q1b8ZWUULdlC8acwTG6jpJrYZtkGZPRmI2Ry0XJJdJppufnaWpp4eGf+zlko5FwKETX+fNcPnWK6Ogo05kMk4kE/kwGA+A0GnFHo0ipFHpuvYlIBGVuLivUzGasTidmux1neTlSzm/Q6nKhKArRuTm6RkcxWSzZ1JDc/jzJYEAyGDCbTNlMX5MJY646JxmNJKNRUslkoepXsF7RNOZzXoNSrmKan+rNV17ywk+S5awhtKpm7V0kCdlmQ7NasebabWo6Te327XjKyrJVRVUlGg6TiEaJzM8zOzREMh5nZngYs82G3ePBnZsoNuQMqA0GA7LRiMPnw+bxYJBlDLJMLBIhODvLzOgo0smTODweyqqrcXi9aDkxazKZcHu9bDtwAFVRiPj9jF6+zNTgIGabjeqtW7FaLNjMZnSvF6fDweClS5Q3NTFy+TIzo6NkDAaqmpsZ7+0lFgjQdPAg//MP/5AvPPFE4aKc39qwUQRgwcR7gwnAlRpBNzY28spXvpInnniCiYkJLl68yPe///0VewKm02nOnDnDBz7wgcLPZFnm4Ycf5tSpU9e8z6lTp3j88ccX/eyRRx7hP/7jP1Z07ivZu3cvf/AHfwBASUkJH/vYx/jwhz/MyMgIf/Inf8I73/nONR1fsDRCAArWLdeqAOq6zsDAAAMDA+zYsYO6urplXazyH7bFsIzIr+ulc+f4n3/0R8glJex94AFKNY0yj4eZSITGvXvxlJQwePkyDrebcCjE0OAgTreb5sZGdF1ncniY/gsX2HHXXRx+8EFcDgeKpqECEb+fkoqKbKKEqmKWJIySREZVQZazwwy6nt0/pij0dXYyPTqKzeGgeccOdh46hCRJDF66hMlkQidbhTPk7ivnEjHyObn5FJFwKET/wAC+khJqamuz6RiahsPlYsu2bbhHR9ljszFvtfJ1ReHbmQwOwJZrvabCYXSzGbvXi8PrxVddjdXlwmS1YrPZCi1Vo9GIQZbZ88ADGAwGenp7CXR1se/nfg7IDdpkMtlWraqCqhZyddVMBiWdRonFCE5P4x8ZQYlEsNrthf2HOjA7MoKrrAyLzYbV6SzsE9RyVUQpJ3olQMs9HxrZi7Oe+/98WkjU78/mKeeOLxsMOD0e3Ll9fADJ3L696uZmgoEA04ODxCORrIF2MpkV7jnBYjQYsm17VcVktVLZ2Ih/YoKdx44RD4eZn5piuKsLi9VKaVUV3srKbPqJpmEymSitrMRTVobJbCaVSNDz8su4vV4qGhuxORzYnU5QVcrLy6muqGCor4/OkydxezyUNTbin5+nq6MDm9XKp//u73j8Pe/JPm8b0AQaNp4AXM3nUD4HWJZl9u3bx759+1Z83rm5OVRVLbgj5KmsrKSrq+ua95mamrrm7aemplZ8/ivJZ7EHAgFqa2v553/+5zUfU7B8hAAUrFuuFIDpdJrz588Ti8U4evQoHo9nRceC7AfvcqKaboSu63z+3/+dp55+mqbdu/m5176W6ro6Lp8+jQY88Au/gG4w8NJTT7Hj6FFmZmYYHx2lrr6ekpISRnp7Gbh0CZPDwV333MPOnTuzxsxk25I6EI1EqG1pwZhr6WpkK1wmoxE0jYyq4p+eZqiri67OTo7efz93/9zPYTSZMOYu4Iqmoeb+yLk2s6ZphRYyZM2OzUYjMjA+McH89DS1uXXmq2ZGWc4OlQCKz0dKlokrCsccDnZarUiAAvglCf+RI2ilpcgWS3YdkoTd7cacFyWSRCqRIOj345+Y4NILL6CpKj1nz1JZX89wRwdmhwOny4XV5cLmcGQFL1khXDBbzj0fBp8Po8lEY2srdrc7m4csy/SeOUPLwYMYc8MkwelpkrFYdt+krmfTN1wu7DkbFqvNlvVZXNAClfKDIKlU1honJxLz8XH5iqJGVpgl4nFMViv23HENTU1ZK5tMhssXLhCansY/MUHXqVNYXC58FRV4SkuzE8m5wRFJkrB7PNg9HhpaW0knEkyPjTHx4ovMjoxQ3dKCu7QUY+62FrudEo8Hh89H3O9n8OJFLDYbVU1NGE0mlEwG2WymoaWFwOQkiVAIp8fD/Y8+yo//8z/RZJmv/9d/Ueb1cvfRoxsuZWIjC8CVGkHnLWA2kkBfCkVRMBqNfP7zn0dRFP7wD/9ww30J2cgIAShYtyxsAQeDQdrb2/F4PLS1ta1YxOVbjmuNlpucmuL3/vzP6evu5k2/9Vscuu8+Lr38Mr3t7Ry8/37sTicyEA6HURSF+UCAaCTCtm3bmJuc5OILL1DV0EDbq19NNBxmdn6ejKZhyk3Mqrm1JqJRbHY7Sk70SAC6TiKRYKS3l4nBQTxlZWzfvx+j201jrgWoLtgjCGAgW23K25PkrU+M+QogkFYUVF1nfm6OHTt2YLPbs+3lXHUsnTMf7u/sZKi/n0h5OaUTEzRaLHgkKSucJInMjh3wu7/L7OQkPT09zIXDGEtLsbjdZOJx5sbGSESjyAYDDo8Hb0UFu+65h5mhIWKpFLuPH0dSFGKRCPFwmLmJCZLRaHa62WjEmhdsXi9Olws9JwzzrVuD0Qg5n790JMLW/fsh10KV+dmwgKqqZOJxwsFgtto2Pk4mHme8tzdbqfR6cXm92N1uZKOR2bExSmprswbPuT1+5C5QeU9CXdfJpFKYrVbIPbeFmDlJwunxYNI0SquqKK+rIxoKEZmZYWpgAB3wlZeTSqVQdB1jrkqraRomm42alhbqt22jPZ0mMD3NSFcXpZWVVDQ0oOasakxGI76qKpwlJSQiEUa6ugjOzOCZnqamvp6MpmEwGtlx+DATfX0MXrpEy113ZU2s43GePnmS3Tt3ZlNJdJ1z585RWlpKSUkJDodj3V6QN1rLOs9qBeBaBXpZWRkGg4Hp6elFP5+enqaqquqa96mqqlrR7VdC/vU7c+ZMoRq40V7LjYwQgIJ1R/4DIF8BHBoaore3l61bt9LU1LTqD4i1ZPjqus6Xv/ENvvj1r+PwePj1P/5jPFYrJ7/7XXYcPkxFXV22vZqrCPV3dqKYTGRSKTxWKy8/8wwVdXXc95rXYDKZspYgZPNmJShM7xolCSXXgjTl9jVmVJWA389AZyeJaJSGbdtoe9WrsnvLcu1cNTcBTG5DvCF3zPxeQYkF+yA1jUzucSnpNEMDAxiA7du2YbPZshOo0SiTo6PMTUygZDJ4y8uprK/H5nSy761vRf7Up5Db2zGqajaSbscOQr/+65TKMhW1tVTU1oKmMTYyQtfly6QyGcobG/FUV6MqCvMTE4x2dnLyG98gMjeHd+tWosEg5TU1WFyuxXm8uo6qqsTCYaKBANMDAwxFo+iaRjKdJjY3R6ypCbPdDgYDA2fPUrtnD5okIecGSZSc+JMlCV2SMDsclNpsUFNTaOFKkkTVtm0kQiH84+OMXrqEpmnMDA2x6557SMRi2YokLBLIam7wREmnMZvN2Z/nKrlGSYLc6xKam6Nx504kWcbl8+H0eKgGlEwm28oeH6fr1Ck8paWU1tVhttkKlVtd17HYbDTs3IkMBGdm6Dl3jtDsLFv27EFb0N73lJRgO3iQ0e5uBtrbSUWjVLe0YLZYSCYSNLa2Mjk2xkQumWLv8eOc/sEPeP6ll/i1t7yF9vZ2ysvLmZ+fZ2BgYJEdic/nW3MFvZjkRf1GEw0r3QMIxTGBNpvNHDp0iGeeeYbHcjZAmqbxzDPP8J7cNoArOX78OM888wzvfe97Cz97+umnOX78+JrWkl8PZFvT9fX1az6eYGUIAShYt+TbcYODgxw+fHjRtOJqWK0VzPz8PB/4P/+HlNnMniNHaD10iFM/+AH7Dx/mgccey158cq1JRdcJBYN0/PSn7Lr7bqZ7eiirrOT4q16F3WrNiq/cFG6+tZqfRlVVFXIVICk32TsxNMRQVxd2p5OWXbvwlJZiJDu4kG/xSrnbGyUJFQp7++QFZsdaztjYkLtYGmSZcDhMf18fbq+XSDxOyO+nf3yc+ZkZrA4HlXV1HLnvPuTcBT8SDBIJBDB5PGh/+qdkxsdRJyfRq6oYTiRw2e2FKVxZlpEMBuqbm6ltbCSdSjHS30/XT36C7nTirq3FYrfjKivj+OteR/fFi4QmJ5nv60OXZUpranBXVmLNVTwMRmN2X6HHA83NhYGeydFR+gMB/JOTTC3IDPbV1KC5XFmbFch68+UNoHP7GvN7KeWcn6JsNOLweHB7PFBfjyxJzE1OYrZYQNeZ6OoinUhkDbVLS/GUl2dbcoAuSaQTCVw+X7Y1TVZQ5l8jRddREglcHk82jSQ3kS7LMsacVU/9rl007dlDbH6e8a4uUqkUJVVVlNTUYDKbs8M0BgOarlNSXY23spKes2eZGRsjMDNDw7Zt2L3ebHVJlimtqEDXdeweD5dffDHbrs5k0HWd8upqrFYrJ7/9bZr37KG8tpYfnjrFob17kWWZuro66urqUFWVUCjE/Pw8g4ODdHZ24na7C4LQ5XLdVvG1ESeAYW17ANfK448/ztvf/nYOHz7M0aNH+fSnP00sFitMBb/tbW+jtraWj370owD8z//5P7n//vv55Cc/yWte8xq++tWvcvr0af7+7/9+Tevo6OhAVVUOHjzIrl272LZtW+F36dyXKcHNRQhAwbokHA7T3t4OwOHDh4tifrqaaLlnnn2Wv/vSl7jnDW9genAQd3k5XWfPsnX/frYfPJg9pqqS/y4/NTHBxbNnSYRCSOk0Rx5+GKfdTiYn/Ey5vWWZXAsoH0Um6zqmnKiLJxJMjIzwwre/TVVDA8ceegij2VyoBJEbBpEkCaPBkE3cyIkMckJQzw0Y6Pl9a7m9cflq2PTMDGOjo9iNRuaGh7l84QKGAwdo3ratMEAC2SlhHQr5tlpu/yGAVF0N1dUYJAnTwEDBvkTLef3lW8+SJGG2WNi5dy879uwhMDfH2ZdfZqanh+YDB9BlGXtpKV63G6fbTSIWIzY3x+jFiyTjcVw+H+UNDdh9PiSDAVnXUSUJSdOw2mzYXC62HDhAJp2m99Qpmu66i9D8PL1nzqCmUpjsdtzl5fgqKrA7HKiqmn3Oc8+HCiTicYxWa+HvBlkmpSiM9/TQfPBgtvXW3FwQev6ZGca7ulCSSSx2O57KSpKxGBW5tI98gki+FZ+Jx7O+iIpS2PNHbjpZlSSSiQQmsxmDwYC3vBxnaSmaqhKZm2OoowMdSEQiZBSlIOIBDCYTLfv2YTAYmOzrI9nbS8OOHdmtCGYzuqpSWlWFr7yc9uee4/LLL3PXiROYLRa8JSVs37+fs889R9OuXUwNDfHEF7/Ib/7Kryz6N5NPpoCs9ZLf72d+fp7R0VEkSSr8vqSkJBvDdwvZiB6AsLY9gGvlTW96E7Ozs/zv//2/mZqaYv/+/fz3f/93YdBjZGRk0XPa1tbGv/zLv/DBD36QP/qjP2Lbtm38x3/8x6o9APOP/U//9E85e/Ysn/rUp/j0pz8N/Oz1fNOb3sTjjz/Ovffeu+bHK7g+QgAK1h2zs7OcPn2a5uZm+vr6VvxBeT1WUgHMZDJ84tOfpndmhrf98R/zk+9+l0goRPPu3Wzdv5+RwcFsRSm3jy6jqlw6f57uc+cgmeT+172Onfv2oeXEnjF37oymZe1YNC1b9cvv/9M0QuEwfR0dBObmsLtc3PPzP1+wClFyUWqQHRQxyTLpvK9hTgQaZbnQmsy3Jw25fXK6rmePoSicffFFhnt78Xk8OJub2bZ3Lzgc7NqzB0cuzkyWpMJgSj4NQwK0nADJTxEruTWo5PbD5YSJlKuI5kVrXgipmoa7pIRj996LzWTCZTLR85OfMJ/J4Nq3j6DfTzKVwuFy0XzwILIsEw0GmRsfJ9zejtXhoKyxEU9ZWXafXO5cOtB76hR1O3ciyzJ2jweb3Y6mKESDQab6++l76SWUVCobL+fx4PJ4snsDJYloMEgiEslWX3N/wsEgqViM6OwsCZMJg9GIwWzGZLFQWV9PdUMDuq5nbVymphi+cIFULIa3spLSmhqsdnuhAhuZnWXLjh0/a2tDoT1vyA3G2J3ObIsaQJYxGQyU19TgqawkMDvL4NmzdL/4Iu7ycqoaGpCNRrRMBovZjJQTgvFolNHubnRdp2bLFpRMplD1rNm6lUwySfeZM9Rs2UJFbS3ljY0k4nHmx8YwGI1EEwme+dGPeOCBB67578JqtVJTU0NNTQ2aphGJRJifn2dsbIzLly/jdDoLewc9Hs9NF2cbMQUEVi8AixUD9573vOe6Ld/nnnvuqp+98Y1v5I1vfGNRzp2nr6+P0tJSPvjBDxL4/9n78yDJ7ju7D/3ce3PfK5eqrH3fet8bjcZCEABBAhxyVpmSIzSSPTMOR4z9JCvi2XohW0+O8B/W84uQJb9nRejJIY01E/JoZHFmNBzOcAASIAE00Oi9a9/3Lfd9ucv74/7urWyQQwLNBtmQ80QgulBL5s2bWXVPnu/3nJPN8hu/8Rv26+XGjRs0m82fcAtt/LRoE8A2njpEIhEuXLhALBZjY2PjpzZuWPikO4BHR0f8P/7BP6D34kV+7a/+Vd76gz/gaHeXX/7N38Tl9VKtVm1yhCRRKhT43p/+KY1ikedef521e/cYnpykaRg4JQldKHYu+bitQ8Ikcpquk0qlWL5zB1VVGTl9mrGzZ1m8dcts/zAM+5gdwtBgYCp+ktgPkyQz3NgKOHZKZqOIahgYkkSt0WBvc5PNpSU219cJJxK88rWvEenoQBFEzhpJS8Ioo7U8Pmtk7HI6bVexRaMtImi1kzjEeNUQ922RVosYWgHMiiyb+2fnzjF9+jQ/+O53Wf7+96k7nfSdOkXZMDjKZFAcDjweD+GuLoKxGMVUiqUPP6R4dGTm97ndFA4PKeztEYzFyO7uojidSE4nTqcTl8tFIJEgnEyaNXmKQimfp3B0RCmbRVIUQp2dBKJRol1dxHp7TYVQ09hbXmb47FnTlFMuY2iaWelWr9Oo1x8xlrh9Ptx+P9H+fhqVCluzszRqNUKJBLHeXoqZjDm+F2TfIoLW+L5WLhOOx+3nwtA08/bFOabZpH96mnhfH5n9fZZu3cIr1FJDROogSTg9HsbPn6eUy7F8/z6VQoHRs2dxyLJZnwf0XLnCxtwcxUyG/slJ0HVGz5zh+3/8x1z+0pd489/9O/7vxeJPVN1lWSYcDhMOhxkZGaHRaJDJZMhkMjx8+NDutrUIoVfUGD5JPM4u3c8bhvid/nkSwKcBR0dH/OEf/iF37tzh7/7dv0utVuO3fuu3cLlc1Ov1T5Xy0MbjoU0A23jq4HK57AT8J13h9pPI5NHREf+/3/99Lv/qrxKORvmLf/NvKKbT/Npv/zZORTFHh5hKlmwY3Lpxg3vvvce5a9c4c/kySBKLH36Ix+Mxg5uFsUPDvJiDOVZtahqpw0Nmb9ygPjrKiUuX8AaDOGWZfDaL7HDY2XyKZAYPW+HNslAAm+JzttqmKLbxQ9d1MkdHLNy7RymfZ+TECSSfjysvv0x/f//xSBjRpoDp9nUL4mcRS2vXThUxMAhy5xC5f4ivI0k0RQOJDXH8EsfGHmtE3FRVmyA2Gg384TCnT5/GLcvcu3WLdKGANxpFcjppNptmG4jLRSAcpv/0aYLRKIamsfLwITuzs/SMjDB1/TqBSMQ2vcjC+d1oNu3mE80w8EYidA8NIQPlapXs/j5rt27hcLtBlon19VHY2WH4zBli4lzpum6O+cUxW+dcFrub9XKZ9O4ukmGY50iQvP21NRY//JDU0RGrDx8yODWFx+OxiXBTqKb1cpnQ6Kj9psAi0Jb6W8rnSfT341AUkv39xJJJc2fz7l02wmF6RkfxiYw4WZbxhkJMXb7Mg3feYebGDYanp22lVFEURs+c4Wh7m7mbNzF0HU8wSP/EBPMffUTnyAj/7//lf+H/2RIW/EngcrlIJpMkk0m72zadTnNwcMDi4iJer9feHYxEIk+EuH0eFUDrDd3jEMDe3t7P4pB+prCeL01ke/7n//l/js/n42//7b9NJpPh7/ydv0Oz2TTrDtv4TNEmgG08dWj9g/5J+oA/KX4Smdza2uJfffvbTH7pS2zMz7O9vEwwHOb888/bjlxDZOrl02n+3f/2vyF7vfzCX//rxKNRVMOgWijgC4VQDbN2zGgJWZYls8FjZ2uLZVH5NnjyJBevXcMlmz25qiBHDkUxg5+FWQFDNFiIPb9miyooC7OBqmmUi0W2l5Y42N0lEo8zOD5OuVxG8vkY6u6mp6vLJmvW+NE65w5BCAGbbFrESQJcTqf9+C1lz/p+u2XDctoKYtiquDrFTmCtUmFvc5OtlRWK+TzbW1tIskxffz/h3l6+8OqruFwu5ubnOSwWiY2PE47HqVSrZr9upcJROo2sKKjNJtG+PkavXmV/ZYV6sUisv5/EwIC5A2cYuBXFrI8TRNcipZph4PZ46B4eppbNkhgepl4us3LrFntLS5x44QW0RgOHx2Mqm+LnJYuUY74RQNxetLub5NCQaQJpiYJ58L3v4RMq4A/+7b8FwyDe30/v+DgREeasNhoY4j4USbKbbSyCXykU8AYCpkIovh6Nx+kdGyPe28vGzIz5WMbG8InRc0PT6EgmGZicZH1mhkq5TGdfn12Ll+jtxRcI8OGf/zmpvT16RkYoZLM43G4+vH2bo6MjEonEY/2utXbbDg0Noaoq2WyWdDrNwsICjUaDSCRiq4M+n++xiNzncQfQ+hv0OCaQJ7ED+POG9TxnMhlbZf71X/91kskk3/jGN9jb26NcLrcVwJ8B2gSwjacaT1oB/MtGwOvr6/zrN99k9No1bv7FXzAwPs701assfPQR8e5umzwYzSYfvfMOu8vLnLxyhVNnzoBwZiqSxJGoYFME2XNgjmQbuk56b4+5O3fwC1IpyTKLCwtm7y1inCXL5n6gLNsk0iFJNOC4RYLjfT8rMmZ7dZX5dBqnw8HgxATjZ8+CJHHv5k0ODg74wpe+hC8QQOO4As0ipRYaqopHfGyrfGIEbAUeq0LZguOWDEmoTsbHxsMOWaZSKpFJpcgdHVHIZjEMA4/Xa5paXC680SivXrpEPpcjEokQFZ24ToeDaGcnlXKZB3fvsr64SGxyko5olHAkgmEYzL//PhgGvkSCbKlEoL+fhNtt1srduIHD5TKVsY4OW7GzquJU8bEk/q2Wy7gCAbyBALtLSzz7q79KuVBg5e5d0DQiPT3Eentxu1y2cmmAOXaVJIrC5IEk4ZbNLmBdVank8/jDYdPl29+P0+GgWiqxubDA/I0bYBj4OzrIp1L0iJBnXawKyJg7nKqqIgu1yIrHUTUNXYTohqNRQtEo+VSK1Xv3CMdidA4OojabuD0enG43ExcvMn/zJuszM4TjcQLBILph4A+HzZWD27c5c/06Pr+fcrVKR08P/99//s/5+z+iG/Zx4HA4SCQSJBIJDMOgUqnYZpKVlRWz3UR033Z0dPzEakcLbQL4+YNFAH/5l3/ZzhLUNI3XXnuN733ve3z9618H+A/isT7taBPANp5qPI5z99Pe1vb2Nv/6zTcJDQ5y+/vf5/IXv4gvGOTGt7/NmWvXbEPF6vw8C7dv447FmL56lekTJ5AdDjO7T9OQgHImQ6K/3yR/kkRTVUkfHLB4+zahSIQLL76Ix+czyVG1asaBWBcxQSysEaM1DrRIl1MYKqxKsHwmw/rcHIvz8wxPTnLpxRdxud0okoSqqqwuL1Op1ejr7cXn99vBxA5BIjSRT6cbht29K2P272rCdCLLx+0YslAiHcJ8oYnxpSF2D3VNI31wQOrggNzREc1mE6/XSySRoHd4mDOXL6Njksv5mRkaus7k9DTBYJBCLmebW6zmDw3w+f1cvX6darnM3Vu3WFlcJDExwe7CAqFYjI5AgO3ZWbp7eqhXKpQqFWqyTHhkBFSV3dVVGqUS8YEBOgcHURwOjJZRumSpmYaB2+lk+fZtukZG8IZCBMJhOnt7UTWNo81NFj/8ELfHQ2JgAH80arp9VdV8LrJZQtEokmFQb3nDsr+8TP/UFHuHh/bI3Ov3M37uHGPnz1M4OmJzbo5mrcbu6irbS0soDgex7m7CiQQOl4vU3h7Rri6T/ElmC4kiSZQLBVxiJ8wpy4RjMYIdHeT291n86CO8gQAe0RwhSxKBjg7C8TirDx7QMzxMNJlEURRC0Sj9o6NszM1RLpXom5zkaH2dWw8e/FQq4F8GSZLw+/34/X76+/vRNI1cLkcmk2FlZYVqtUooFLIJ4Y9rv/g8EkBr/+/TKp7/oe0A/sEf/IH9sZVRevbsWT788EPef//9z10rzecRbQLYxlOHj4+An6QC+PHbSqfT/Is//mNUtxsln+f5r30NhyyTEyNGfyRCOZfj9ttvYzidJCYmGBgcZHNjA4fDYV/UHSIOppDLMXX+PJJhcHR4yMKtW7h9Ps6/+CKhYNAe31rRLA5xQTcE0XJaI1SOFT+LhFku3r31ddYXF/EFgwxPTRHq6iIQCuHxeFBkmXKpxMLSEj6/n6nJSfY3N+38OCvG5ZFzLHppNeHotca/5kMzHiWMHI+HNU0jtbvL0d4eK4uLGMDoxASxri6GJyfxiVDp1vOvNhpsbGxQLBYZGR4mEg7bwcmqiMpRf8RF3evzce355ykVCrz//e9Tz+UYPHuWzMEBDqeTgNeLz+0m3NGBoetUSiXKlQrezk6UWIx0JsPe8jLBeJzeqSm8Xq99TiUASWJ/bc3MyOvrs0fEkhi39o6M0D06Sr1UYm9lhe25OaI9PSQHBsDhoF4q4Rsawrwpk1iWs1kzDNrrRRfn23JDS7KMU5KIJBLUajWz61dVKWazBGMxNFVl5d49FEkil05z9vnn7ZG9JJlh1pVSCW8waO9gArgcDjNDMZHg/jvvwOEhsWQSt9cLmoa/o4NEby/rDx9SLhbpHx1FEV3RJy5d4k//1b+ic3iYkRMnuPFnf8Y3v/UtfvPXf/0xf+M+GRRFscne+Pg41WrVNpNsbGwgy7I9Ko5Go4/kw30eCeDjOIABKpXKE4nDelph/U3q7Oy0VcA2Plu0CWAbTzWe9Ai4NVqgUqnw//md3yGj65y/eJHOgQFTATMMFu7cYfzsWWY+/JDUzg6RgQEURaFvaIhIIMDWxgb1ZpOAqB9TNQ2HLKM2m5QrFeZu3kSWZU4/+yx+Ye7QhUEDhNImmVErlqqnCBJkiGNwyMdhz6VCgbXZWXKpFL0jI1x99VWzkcEwyBcKJmHRdVKZDNsbG3R2dtLb00OxUKDZaDxCxGyDB+YF1DJ4GBwTPgnMPUOhbiK+t5DLMXvrFtlUCkmWiYuGkGBnJ7phMDgwcHzCrdsSI+Rqtcri8jJOp5PBwUHS+/vHI3nxPXC8o2ftH9q7hLKMPxjkK1/7GqnDQz788EO2jo7whEJomoZqGLgUBU2S8Pr9BMTOXLVep9nRQbm7m6O9Pe5897t43G4GT52io7MTtVql2WiQ2tzkxPXr5utEVc0ROdi7mYq43cHTp82A5P195j74AJfPRymXw+nxIEkSTsxYoM3ZWUYvXDDH+pikT8dsB7Gigwygls/TPTiIOxhEazbZX1/naHubzv5+/B0dHL39NusPHyK7XCQHB/FFIjgkiWqxSNfw8CMO66YgRC63m45EglA8zurdu0R7e6lWq8Q9HhwiMmZ3ZYWV+/fpn5hAU1UUp5POgQG2Fhbof+UVIokEb33/+/z1b3zjZ5rv5/V66e3tpbe314xHyufJZDJsbW0xOztLMBi0CeHjBCr/vPG4x1wqldqqWBtPFG0C2MZTCYs0fFYmEF3X+X/9k39CRpL4wq/8Cn6/34xcAbRGg/TeHpVCge7BQWKjozidTkZHRnAKd64iHTd/ODBVunK5zPrsLA5FYeryZTpiMdsx3NR1c3lfECpD7M45OHYF6sJE4XI4UDWNpqZxtLfH2uwssiQxODXFyStXzIBly4wh7lvVNHZ2d8mkUoyOjBAIBk3HssOBZpGZlkw+Q390F9Ipy7YhpFUBLBWL7G5scLS3R7PZJJ/JkHj+eSZF+LDlkK3v7mKoqk0eNXEurcdWLJXYWFsjFA7T19dHan8fh8Nhu4ktZctuLfnYcVhNK9b3RGIxXv3yl/nOv//3LC4tcdDTQ2J4GEn8rFOEMUuSRMjvR/N46IhG6enuplIukzk6YvH2bfRmE28oRHZzkxe+8Q1kMYpyiuOyI3us3TtrHK8oxHt66OjuppBOszU3x/x779EpRqtHW1sEYzFcXq9JJhHET4ycLUc5QLlQwClaVFxuNwMTE3SPjHC4scGdN98kmkwydumSuU+5ucnG3Bzx3l4qxSI+v99Wdq3nuNlsmmSwViOaTBLr7mZrYYGtuTkGJibs36ue0VFSOzss3rljk1e310skmWTp3j2mLl3iB3/4h9y4eZMXn3vuifwOflrIskxHRwcdHR2Mjo7SaDRIp9NkMhkePHiApmk4nU52d3eJRqN4PJ6ffKM/ZzyOAmjtTf6HrAC28bNHmwC28VTjSSuA1m39yZ//OUWnky//1b+KIhy4EuYe21/8wR9Qq1Y589JLpqkjHGaor89W4xyShC7IlCJJNBoNlu7d43B7m2h3N1dee83cZRPjVAnslg+rGcMyYKgIRcCKFBEq4f7mJrlUikgsxulnnsHn99vEQwYaHI8TDSCXTqMbBuMTEwR9Pps8eT0e1EbDDogG7BGzFdKsCuNGU+z9pQ4O2N/cJJtK4Q8EiPf2cu7ZZ3F7PLz3539OQixuWzEyklD5dDG+tc+3UDmOUil2trcZ7O83TQDiPEuCuFqPQdd1UyUVqqS9Cyluv7Vyzzr2cDjMs88/j9fjYe4HPyB+4gRBoQzpmH/gGqpqkitFAUnC5/cTCgbpHRzkaG+Pd373d/FFo8zNzNDR1UU4EMDtduNwOm0iaZE1O85GqLcOhwOX08n4+fN0Dg+zt7LCztwcpXyey6+/DtZ5Fm5wQ+yGYp0nMda1WlY0XUcyDGRFoXNwkNT2Nh2JBLPvv0/X0BD9p06hNZscbW2xtbhIMBYjOTiI7HLZncRWFqP12nMoCn0TExxtb7N4+zaD09OERAxLQsSKPHjvPSbOnkVSFNx+Px0dHaT39ghGo/zrf/fvfm4E8ONwuVx0d3fT3d1t7pLOz1MsFtnb22NhYQGfz2dHzYTD4acyI/Bxswv/Q9sBbOPnjzYBbOOphqIo1Gq1J3Zbmqaxs7PD3NERL//Vv2qOHoV6kkuluPPOO1QKBS5+6UvsHxwwMjRER0eHaeoQe36aIBONZpO1+XnWZ2YYmp7m8quv8vDdd+1qNkVEq9gKICZZaraQMacwPOhAvV5ndXaWzaUl6vU6L/3iL+JwOs09NEznqqppdsyKQ5ap1Wrk83lkRWFqasrcSxT3a2XM2bl1YKuHrbt+mqqS3tvjcG0NpywTicfpGRri5KVLNpkAfmjf0dpJs0OjLRjHOYHbOzscplKMjI4SjURswmcZTCxYty1LEi5h1JAQRhNrLC72I60eZIB6rUaoo4PpU6cYHh3l9s2bbKyv0zU9TcDnM9tSwB6nI+5XNwwa9TqHS0ucfPZZkmNjpLe3OZqdpdHbi+zzoQB+vx+Px4Pb48HtdNIU599yfauqSu7oCG84jNvjoW9qikqhQCIYZPHGDToHBujs78cQ42SLHjcNM0+ykM3iE3uQTkEKmsKUUjg6IhSN0jM2RmJggNTmJgs3btAzMUE4FmPy8mX8wSDLd+7gj0ToGxszR/eaRq1QIBAKHY/1FQVPIMD4uXOsPXhAOR4nOTSErCgEo1E6urpYuHPHHMMbBl19fRQzGTxeL0vLy9Tr9Z95zdtPgiRJuFwuwuEwk5OTNJtNO2pmbm6OZrNJR0eHTQi9Xu9TkRn4uDuA5XK5rQC28UTRJoBtPJVoHQE/SQWw0Wjw+9/+NtOvvGJfDAzDYObmTbIHB5x49lne+eM/Jl8uc3p6GlksnCuYpM4hlL1CPs/27Cz9w8Nc/+pXcTqdlPN5FJfLJhw/pAAKk4WVRaeLkWCpVGLx7l3y6TSDU1M8/9Wv8uC993C73UhizNy0FKiWn01ns6yvr+PzePD7/XhdLntEqbaQPmuEaWUFOkS0yN76Onubm2jNJjVVZfrMGfr7++1dPOtnrQYSXZgNHgl7FsTG6XDQqNXMmBXJbB/Z3NigWq0yOTmJx+OxswIdIurG6XTaFXmyLHOUSqHpOuFwGJ/HY9flKcJNrWuaGWMjjschyzTrdbw+Hw5FIRAI8MJLL3G4v8/7N25Q7u0l2t+PU5BgWbidVV1HV1WWbtxg8MwZtmZnicTjdHR20qzX2ZqdNXMBR0ZQFIVCoUD96Ai3x0PA68UrYmwss0o5myXa04NmGKR3d/EFAvSfOIGu6xysrXHvnXdouFw0envxuN3ma1u8kShls4TicdONLBRCWaieBxsbDJw8ae70uVx0DQ8T7etje36e9O4uvVNTdCSTdPb2sr+9zeyHHxJLJukZGqKQShGMxczoI8OgUizi8Xpxi0iYjfl51h8+ZHB6GknXCcVihDo6uPvOO4S7utA0jeHpadbn5gh0dPC7f/AH/CctHcFPC1pNIE6nk87OTjo7O82KvnKZTCZjNu0sL+N2u+3dwU8TNfOk8Tg7gM1mk0aj0Y5GaeOJok0A23iq8aRHwLfv3ydw6hRujwdN16kVi3z41lv0jYxw4Qtf4PtvvUW8r4/pqSl7D6ypaeaOHJgGjw8+YHd1lWdeeYXevj5kyWx0qNZqZi8rgiwKJc5ytzrECNM2duTzrN67R2Z9nTNXrnDq6lWTAABNMba1j12MjJvCxbu/v8/B/j4jQ0NUKhUaqmqHQz9i5BAKmKbraM0me1tb7K2vozabdPX3c/bZZ/H5fMzPz+MVC+YOsQen6foje3wWrF0z6750w7CNEoZhUG80WF5exud2m+fR6bRVS4voNJtNZGG20HWdnp4e3NksxWKRw8NDHLJMOBIhFAoRDgZxuN3m/WiaPSpu6Dr1Wg3J4aAh9hwNwyCaSPCV119nYWaGufffJ3n6NL5g0HRbGwaNapXlmzcZPHuWQEeHuTcoxswej4ehc+eoVypsz85i6Dr9J08iO50063WKpRKpTAZFUfB6PHg9Huq1Gl6/n0a1Snpzk8lnngFZxu1w0DMyQnxggPs3bjD/wQf0jY4S6e42z6MsU0qlSA4NmSNqWaYujrGYy+FwuXALt7IsSRiCCI6ePUshkyGzvY0iSXQNDBBLJuns6WF7bY0H771Ho1Lh3EsvYehmtmStWMQfCqHqOm5FYWBykqPtbZbu3qWzvx+P202sqwun2016e5uRkRE0YHBykt31dd783vf4m3/trz0VClor/rJxqiRJBAIBAoEAAwMDaJpGNpslk8mwvLxMrVYjHA7bhPDHRc08aTyOAlgqlYB2Nl4bTxZtAtjGU40naQKp1WrM7O3xi7/8yxjA+uIiGw8fcu6ll9A0jdnFRahW7eYPGUH+xNh0eWaG7aUlTl+5grerC7/ff0z2hOKHopgKoDArNMUF3XIB6+Livnj7Nqqq0jU0xKlz54iKcGNdkCgLSksOX1PX0TSNzY0NyqUSExMT+Hw+ypUKcKzWtTaF6IZB9uiIj773PerVKl2Dg1y4ft2sPROQxc/J4vuNjxNuMUK0PtYNA118j/V5a4RbKpVYX10lGovR19trt2VoHLt6wRw7O1wus+FEMmvekp2ddCYSaJpGqVQiXyiwtb3NerOJ1+cjFAoRCoVwu1zIikKxWKRcLuN2u6lWqzRFR6+qqqjNJn6fj7Hubu595zuoXi/h7m4alQo78/Mkx8dJbWywv7zM0fY2vgcPzEYPRTE7jV0uwokE9VqNuXffxRsMMnTqFJ2JhBm1U61Sr1Q4ODggXyyyubnJ/twc01evIn0sO9HrcpEYGKCvp4ed5WUONjbomZggZK0WOJ2mE1vs8EmSxM7CAoOnTtkjXEvRlSQJyTBwut1MX7nC4cYG8x98wNCpUwRCIXqHh+lIJLj57W+zcv8+Y6dOYTgcFPJ5c3dTvDZcDgeJvj4cLheLt2/TOzaG4nDgi0TQNY3D3V06e3tJ9Payt7FBKptld3f3qasi04WS/JOgKArxeJx4PA5AtVq1zSTr6+soimKPiqPR6Ce6zcfF4xDAcrkM0N4BbOOJok0A23gqYb0bf5IK4Hffe4/YiRPoqsrNt9/G43Zz/WtfY2d3l2w6zfjoKOWNDSLhsDneE6pb+uiIh+++S6K/n+u/8Au4ZJmjYpGGRYKEIUBVVZxCebNbPMS4UjUMKvk8s7dvo6sqk+fPE47FmJmZQcGMfbH22iSOK9YsFVABtGaT5eVlkGWmpqdxOBy2OiQJJ2jTMPMFc+k0m4uL5DMZyuUykxcuEBTdms6WsasuxqxWy4flsgVsp7MuVEvxxDzyHMni9hRJolarsby8TG9fH4l4/Pj2W2AZR3ThjLXMN9aI3boPq0ZM6+qimM+zt7vL/MYG2XQaXdMwNI16rUZmb4+1hw9xOJ24XC4UlwvF4cDpcpmd0p2dvPrGG+xsbvJgfp5ao8GF11/H4/OZsTbpNIosExMqkUOSaDYaNFUVSVTyxXt7yR8c8O4f/AG+cJhwImGSVoeDcqmEz+Nh5949/J2dHKbTyLkcAZ8Pv9+PwyISYvzcPz2NWq+zMzfH2r17+Ds6zF1KYUTSDYPs4SFevx+/iLGRDNELLBTTYiZjmzi6R0YId3Wx/vAhkXic5MgIhVSKqcuX8fj9zN26RXJggEqhgGdiAqfDYZ67ZhOnotDR2UkoFmNvddU0kwB9k5Psr6/jD4dxejzEu7tZffiQP//e9/ibT9kY+HFzAL1eL319ffT19dlRM+l0mo2NDTtqxiKEoVDoiaqDj2MCKZfLZsXfU2hqaePzizYBbOOpxpNSAPP5PFvFIlIoxPf/6I8Yv3CBzp4e5hcXcQIT09M4DQOXx4MqFLtavc7czZuUi0UuffGLePx+20EryTKyUHkssqeIWBYr008Wu3vlYpH5W7fQGw0mLlwgHIuZu3xC8WmKUaul4FljW/scyDK5XI6V1VWi0Si9vb24hFKk6jq6GA036nU2l5c52NzEHw4zND7O6atXufX227iEmcQmdS0qntwSr+JUFDRVNQmh+LwN8XgVK85E09BlmUazSTqbpV6vMz4+TjAQsFs2nGIHzapOU8UIt95sEmwZDRfzebLZLMVcjnI+T7VaNY9NZP95/H5GR0fxnD7NUTptf33p3j26x8YIhUJEIxG7N1nTddPsIg69q7ubsakpfvDOO9RLJYLxOA5JIre/T6i7m4BQYC0VVGo5Tw7AOHmSpqqyv7JC8fCQnqkpPIEAyzdv0qzXcblceB0O6nt71BoN0roOTiduv59gLGaaTlQVn9MJTidDZ88y98EHFI6O2F9eJjk2ZpJEw2B/eZnxixdRNc0kbGKPtKmq5jEfHhIS7RwOWcbr8zF15Qp7a2vMf/ghWrPJxOXLuFwuQpcvsz4/z/7aGhPnz6MLlzDidepUFBwOBwMnT7J8+zaapuFyOhk6eZLVBw+YOH8eJAmP18vtBw/4Gx9/Tfyc8SSCoFujZsA0Y1k1ddvb2wB2CHUsFvupzTCPqwA+bl9yG238ZWgTwDaeajwpBfCtH/wAPRBg9c4dfvU//U/RgIezs0QjEQb6+pBlme3NTaKdnaZ7dX2dhY8+YuTsWU5du4YTaLTEeCiS9IgC2EriLGdstVJh9qOPqJbLTF24QKKry4yRaSV9IhLEUsOarYHNguDt7O1xuLdHT28v3WLB3RoLGoZBZn+flZkZDuJx+kZHufbaa8fhw5KE2+Oh2Wjg8ngwJOl4nIs5wpXBjqBpatpxHzGmMmndlipUw4aq2lVWqqqysrJCo14nHAgQDoVsw4gkiJgNw6BWqZBNp9lcWuJod5clpxMJ8AeD+EMhwrEY/aOjpmmkxblsEced7W00XWdqaopGrYZWqeD3+chmMuzt7OB0u4mEw6aCGAjYAdkIc8lX3niD2QcPWPzwQ3rPnqWSy9HZ32++1ix1Uj+uirMc3bJkNoL0jY/TGBxk/f59FEUhd3RErLubyStX7PtSJAm10SCXTpNPp8msrFDI59mZnyccjRLv6SESj6OrKmdffpnM9jZz771H9/g4tWKReF8fbo/HHgtr1nMC6JJEKZdjYHLyOCtRKM1dQ0O4fT7uvPkm3WNjxLu6QNTKVYtF5m7eZPzMGdx+PxZl0nQdtV6nM5lEBla+8x0GT50ilkgQ6ezkcGsLXdNI9PezvbfH3t4ePT09P+2v4xPDZ9EE4na7H4maKRQKZDIZdnd3mZ+fJxAIPBI182nvX9O0R9pMPgnaETBtfBZoE8A2nko8yRFwtVrlT958k6GrVzn17LPkSiUO9/bo7usjmUjYI9pyJoPb7+fWd7+LLElce/11M1hWKHmOFtewJHbmLBXOii/RNI1avc7inTvkj46YOH+euFj6t0KKLZKnCDKmapq9s2cFIjtdLoqlEgeHhxSLRaYmJ01SYEW31OuszM9zsLWF7HIxeuoUJ8+csR+z0rKD6PR6qZTLBMJhO+bDIUaOlitYEuNay6hhfV3TdVspBMy8OqES1cXI1+ly0ZVMkslkHhn5NlWV1P4+maMjcuk0zUYDh8NBJBbD7fNx8uJFk6TQEtOCScRan3NDmD7WVlfBMDgxNYXL6WQ7m6UjGiWZTNIpiHs2lzMv2KkUqq4TDAYJh8OEgkFksd935vx5unt7+f4PfkA6nab//HkUXUc1X3jI4jnWOQ7ntmNrBKGeuHKFjQcP2JqZYfzCBfv7LPKvuN1Ek0niySTa9DRrGxskEwnye3vsr66ycPMmhVQKJRiks6eHoXPn2Lx/n721Na7/8i+j6Toup/P4PIjnpFKt4nA6cTgcJjlUVSRxfA5ZppTJcP6LXySzu0u9UCA5OkoulaJnbAyPz8fq/fskh4aIJpNm3qBhmPuZioIvECAYjXKwtkZnVxc9Q0PMffghjUaDYChEKZfjvQ8+4Fd/6Zd+qt/HJ4nPugpOkiTC4TDhcJjh4WGazaatDs7MzKBp2g9FzfwkPK4JxO/3txXANp4o2gSwjaca1gjYIiaPg7v37zN2/Tonr17l7t27pI+OmJqcxCcCkxVAA9bn5tA1jbMvvEC3cPc2RO6bpfJJkoSCecFsiNG0U5Jo6GZY8NbSEqm9PcZOn+b0lSt2XIkmlBpadgt1XccQI1CL+Fk9vYrLxcyDB0SiUSanpsxAZ00je3TE6swMjVqN/okJrn/lK6QzGQq5nB0f0hTKkSH269weD81azQ6jtpojLFiqpSw+bo16sUahiMfsFM9HNp9nbXWVzkSCZHc32WyWWrnM+tIS2aMjs93C6SQcjxOOxRgcH8ftcpkNKEClVMLf4mi04m3sMbVwIhu6TqVaZWV1Fa/Px+jwsN1nXMrn8fr9j5BWa5SnSBKFUol8Pk/q6IjNzU18Ph+hYJBIOEy8q4vX33iD3/tn/4zD2Vk6p6ZsAm/lPFoGDE2cH8sZjSTRKBbZWVri2i/9EqV8nvTuLqNnz+Jwu03TkHAWNzUN61Lv9vnoHh2ld3yc7aUlGo0GjWaTpVu3qNXrVPN5+icmmHn3XQamp+nq7TWPRYyBm5pGemeHaHf3cbyQw2HmMOo6TVU11cGpKTq6ujja3GTx1i2ajQZ9o6MoDgfTly+zdP8+tVKJ5PAw1WIRfyBgrhBUKiT6+6mVSqR2duju76d/cpIb3/42UaEuv/Pee/+XIoAfh9PppKuri66uLjtqJp1Oc3h4yNLSEh6P55GomR9F9B53B7CtALbxpNEmgG081bD+UD5uej7Azbk5Rp97joWFBQBGRkfx+nz2rl+5UuHBe++xv7nJX/m//d/MrDbhlnS0VIBZJM3u7hW339B1dtfWmL1xA90weO6NN5Bl2XTw6sftGIZQiVRNQxeExTKNWGYISZKolsscHBzQ2dPDiNgN21hcZG1hAX8oxMS5c3R0dNi36xIj20f2+oSip4gdsVKxaKuMFo12KAqIx2JYRo8WlVMRwcut7RzIMocHB2TzeaIdHTTLZW698w7pVIpao8GZ8+cZP3UKfzCIoyXmBbDdsbIkoakqHpcLpcUdbY9eW1TfQrHI+toa8USC7mTSPB5x/JVymVgyabtj7fxFQTIjoRCRUMhUcFWVXC5HoVhkeXnZfm5OnT1LV08Pt27fJnnmDC6Px3xDIMbYirhdKw7HqSgU83lW79wh1t1NYnAQt89HLZ9n/oMP6BoeNoOfxbm3RvsK4BJmIU3XKaRSTF68CIqCfPYsW4uLHG5sUC2VqJRK3HnnHcLxOKPnzhEIBvE6nciyTCGdZvLCBXOEaxxH7zgVhd2NDeLCpSsBnQMDSA4H97/3PUbPnDGjThSFsbNn2VlcZHNhAcXhICh2UnOZDKFwmFhPD6m1NfyhkGk2kWVKxSJ9o6PMzs7+zEnXj4MhTE8/D7RGzQwODpqh4Lkc6XSaxcVF6vU6kUjEJoSWgvc4OYDlcrkdAdPGE0ebALbxVMLe/xJhrarYO/u0yGQyZFSVyvIyiXicZr2OJP74ysD+9jYzN24weeUKtVIJr9tt9/taY0kZU+WzCJRLmBvqzSbZoyMefPABoViMZ7/6VeY+/NBUkgTxs9SpVgXJUqskMWZUW0bCh6kUm1tb9A4O4lQUlu7f52Bri57BQa6+8gpOsTtkLfCrVjiycWwbsUirNdJ1ezykDw5somD1ANv3a+2XWSQX7LYMvYWY1mo1lubnaT54QGdXF1qpRLKnh5OXL1Ov19nb32d4ctI8PsOMk5HEfVoVblbUTbPRQLeUUY5r7azHBmaF3N7ODgMDA8RjMfs1YXUaV8RYzNqJbFWJlZbbtu4/0tFBNBZD1TTKpRIP79yhqapkSyVGh4aYff99opOTRHt6zBFrC3m1lMBaPs/6nTuMX7zI8u3beP1+c/Tb0cHkc8+xOzfH8kcfMXjmDIYIuq4LpVfHVDmbjYZJDp1ODKBaKlE4POTsF76Ay+GgVq1yuL3Nyv37vPtv/y0Dp04R7euzDTqGIKVgvgkxJLOOMLO9zYlr18zn3Omkqaqg60xcuMDKvXuMnjmDNxDApSj0T06ys7rKyt27XPvqV0Echz8axeFwMHLyJMv37zNx4QLx3l6OdnbM59bhYGdnh36xN/nzxtNERh0Ohx01YxjGI1Ezq6urOJ1OotHoYzUbtRXANj4LtAlgG081LHXncfYADcPg3//Zn1F1OBgbHCTe0cFBOo2kaTRUlZkbN1CrVa698QYej4eV27dN8idIhK36GcdNHJYxo16vM/vBB3TG45x7/nl8wnDQqNdtZU4WTmBLpVFk+TgWRjeDoa0oFQnY3NzkKJ2mO5lk6fZttldXee7113nu9ddN0iOOBzEabYrHKQvnqzVqVnXdVBbF4/AHAjSqVTuz8GMnCVkQWqsLWLJGmIZBLp3mYGuLw7090pkM1WqVF159leGJCfN8CJLcaDZt1UsC28Cgi+cBQSRbnxtFKJBWN7JFzCXDYHdnh3Qmw8jYGAG//3g/UCiSYGYJWoT445EzrR8/kqsomS0qwWAQl6Jw7tIlZNH24fV6ufn++2ytrNA7PU0oEMDj8RyT1kKBldu3Gb5wgUajgcfns4OpnYqCQ5YZOHWKWjbL4gcf0Ds5SSiRMHcKxYqABGT294l0ddkEff3+fUbPnzfXHXQdt9fLwPg4PSMj5FMp7r31FpmtLbyRCIGODra3t/F4PHg8HgJ+P06Hg9TuLtHubvP3RajMmmGQOzhg4MQJksPDLN+6Rc/EBNF4HFmS6B4cZH1mht3lZQampkwyJZ57r99Poq+PzYUFAqEQxUyGYj5PMJHggw8/bBPAnwBJkvD5fPh8Pvr7+9E0zY6aqdfrzM3Nsbu7a+8OBoPBH7vi0lYA2/gs0CaAbTzVkCTpsYwgjUaDe/fucXd+nmf/+l8nEAig6TpOSSKfybDw0UcMnTzJiCAyDWv3TozpHBzn+8kI4gA0VJXNmRlm7tyha3ycy0JxUTjucAWz+s3aGZTEKBFdRxVft4wkDkWh1mwyv7hIOZulnsuxfnTEyIkTeLxe+oaHAVHHxnEuoOUetkilahiPkDtL7VN1HYcISrYz/AzDbvuwOn01QdI0VeVga4udjQ0qpRKRaJRoVxcNRaFnYoJ6LkcoHLZvRxJGFovYaroZVm2I3bVHcgCN46BjEM7jFvUO8fi2Nzep1GpMTEzg9XgeUQft3uEWpc96k2CNa63nwPopA5MgSjzqaq5XKvZF1e/10t3VxcTEBHc/+oi7Dx5QHR7GkCQCPh/NapWj1VUmn30Wl8vF1uIioa4uu+7P6mh2yDLOUIjxq1fZfPCA/OEhPePjSLKMS/QqZ3Z3GT13DkWWWXvwgHh/P06Px1QShQHGMpVEOzt57ld/le3FRe6++SaeEyeQwmFcoRClYpFUOo2iKBwtLHDy2WfRAcU6n4KcekXm4eSVK8zdvIlkGIRiMYqZDANTU2AYrNy7hzcQQBZvIgxJIt7by+7KCoFolEgiQXp/n0RPD/dmZvjVX/mVT/X7+FlB1/UfS5yeFlhB09FolMPDQ8bHx1FVlXQ6zdbWFpIkPRI183GX8GelAGYyGf6L/+K/4I//+I+RZZlf+ZVf4X/+n//nH0s2v/CFL/D2228/8rn/7D/7z/in//SfPvHja+OzRZsAtvHU49NmAebzee7cuYPP56NraAivz2eTjP31dXZKJa6/8QbBUMgkQcINKQnnq4JJsJpi/GtFgaQODpj74AP6hoe59KUvUSgWURDxMGCTEutnQewJCiIJoqZNUey9t6aqsrW2Rm53l96+Pk5duUJQZNKtz87aJM5SIy3FThakTxMqmybIpyLq6yxyB9jqodXEoWrasSIlSTTqdfY2NjjY3mY7EqGrp4eJM2cIhEIUCgU219eJRqP09PSwOjNjHkOLa9hSmwAzpNk4zhW09gytcXJrLIydt2eeGBrNJqurq7gdDqbGx3GIvTeL0Bji9nVArddxOp2PjHktd7UsScekUfycRREMcdyNeh2l5ecdQjUDuPzMM6ZL+P33SZw8SfrwkO3ZWbqmpjg4OiLg91M4OKD/+nUkRcElFGrrOVUAVZYZu3iR/fV15j/4AHdnJw1NQ2s2TTLo9XK4uYlhGMR7e01VWNNsNVg3DCRFMZ26kkSit5exM2fQALXRYHd2lsTAAD2DgyzPzOCNxUinUuiGgdfnw+N2U8lm6ejstLP9GobBicuXmb95EwNI7e4yMD6O4nLx0ZtvEu3spKmqeNxue4wc6+lhd3WVaDyOpuv4AgE2xS7t04CnVQH8cdB1Ha/XSzAYpKenxwwkF1Ez29vbzM3NEQgEbGUwHA5/Zgrgf/wf/8fs7e3xne98h2azyd/8m3+T3/qt3+L3fu/3fuzP/eZv/ib//X//39v/7xM1km18vtAmgG08lWh9V/9pFEDrD+jY2BgAns5OHLJMo17n1ne/S71a5dqXvkQ4HKYhmh8USaLabKI4HHaMh2wY9t5fvV7nwXvvoes6l195hYDfTzqVIq9pNMVYz1IIESNKW+lqUeYcsowuSTbpWJyd5f3vfpdQJMIXv/Y1wuGwGTciRqKGcAVbkAEsE4kgBpbLGPF91m3LLSqb0mJkEScXtdlkY22N/Y0Nc3Tr9TJ+5gyTU1P2/tzR0RE7OzsMDwwQi8fN50CWqTcax8aOln00rdnk4OCAUCiEx+u1g58t/Cgnt+X8rZTLrKyuEgqF6OvtBXGeWsfWdgg3UCoU8IlmE3h0h1CR5R8yw1jHqgmlN5NKERG1YB//eU3X6eru5iuvvsp3/uzPyJTLXH39dRwOB+Vy2QytzuXY2NrC7fEQDATweb1IQmW0en11XSfa24vL5+Pe979PLBymWioRSSYpZ7Okt7cZv3IFWZZtl7kmzE4y2Pt+DoeDzM4OfdPTuH0+1u/fp3NggFq1yv0f/IBGrcalV14xCXajQbVapVAosPrgAcOnTpHL5wn6fDjdbiRFYfLSJTPepVbDdfYsEhAIh2nUatSKRVxOp6mEizddwUiEXDbL2OnT5DIZiuXyT+XKf5L4PBLAj5tAZFkmEokQiUQYGRkx9zkzGTKZDN/85jf5h//wHzI+Pk5PTw8bGxsMDg4+keOYm5vj29/+Njdv3uTSpUsA/JN/8k94/fXX+Z/+p//px+Y9+nw+ksnkEzmONn5++Hz95rTxf0l8EgVQ13UePnzI4uIiFy5cYHh4mJXNTaLd3aSPjvjBH/0RA9PTjJ49a+7PiT05XahosnDAamLki2HQ0HU2l5Z4/1vfon9igktf/CJeMYbRBfmyG0CESuX2eFBrNXMUKgiMQzoOFMYwONzd5Y//1b/i3s2bXHzxRc5cu0ZAkBlFEB9VqHlqs2nv1dmkSDqOjrHInSYUTAtWuLNumOHSsizTbDTYWl3lgzff5P233kJXVc4/9xzXvvQlBsfHcXk8gLmvtru1xf7eHmNjY8TjcVM15DgHELADo2XA4/HQ09dHtVZjaXmZhw8fsr6xQTabNZ87MdJ0KoppygB7ty6TzbKwuEgsHqdXhHJb+CGSIUkgSZRLJUKhEIq4PWuP0epCthzMlnNbavkYIHt4SEJkByrWOFlRbPLldDgIRyL84i/9EsPJJIWDA5Ak/H4/Ll1n9MQJupJJvC4XxVyOtfV1tnd2yOVy1JtN8zhFLqBqGIxfusTR5iard+7gDYVYuX+fiYsXTVLaohZLkmSbdCz1tNlsks9kiMTjeP1+pq9cIXt4iKIoeAIBXB4PK/fu0Ww0cHo8hCIROmMx4okEoY4OdFVla3eXjY0Njg4OKFerdHR3Uy4UqFUqZi2fLDN5/jw7y8s0m01TgZRlauUyg9PT5A4P6UgkyB8doQPFYvGT/Op+5vi8EUDDMH5iooHL5SKZTHLixAn+1t/6W3zzm98kHA4zPz/P2NgY09PT/Hf/3X/3Ux/L+++/TyQSsckfwCuvvIIsy3zwwQc/9md/93d/l3g8zqlTp/i7f/fvUhF95G18vtBWANt46vGTFMBqtcrdu3cBuHbtmh3GurG3R6le53B9nWdffx23z0dxacncBRQ7etZ+X00QP8vkURVRHMFYjOtf+5q932VFpcjCxWu5hBE/6w0EKOTzxLxem1hY49/0wQHzN2+SK5XoO3GC6RMnKObzVMplkygIwmiNT0ORCKV8HodQqiyNyh53SpIdBKzrZp4hInvOUiYNw+Bob4+tlRVq5TL9Y2OcvXaNYCBwrC4KwqQYZuvEytoa9WaTiclJu/bKGl27nU5TmWoZWTYFgYhFo0Q7OtANg3q1SrlY5OjggK2NDTw+nxmoGwo9st90cHDA0cEBA4ODRMJhW+GzSS/C1Wwc17QBFHM5Et3dZm6fODetHcbWSNoiy4hzYyGXyTBx5ox9TvUW0qXqZnOIoiigKLz06qvcvHGD/fl5OicmSO/uMnLmDE6vl3AggKZpNFWVSqVCqVwml88jY+Yv1ut1PIpCZ08PHZEI6Z0dbv7hH3L5jTfQxeNyAbVm0w4GN3SzJUbHVIdS+/uE43E0RJSMJDF+4QJLt29zsL7O9V/8RUrZLKt37xLv6SHW28vh5ibdg4NmU4UkEYvHqdXr1CsVSoUCSzMz9E1Nce/dd+kaHCSSSKC4XMQHB9lbWiIWj+NSFBr1Om6vF18wSD6Twely0dB1SoKA/zxhkanPEwG0/o590kQDRVHsv2n/1X/1X/Hrv/7rvPXWW+zv7//Ux7K/v09nZ+cjn3M4HESj0R97+3/tr/01BgcH6enp4f79+/zX//V/zcLCAv/n//l//tTH1MbPFm0C2MZTiY+PgP8yBTCdTnP37l2SySTT09OPXAzuP3xIz/nzPPPVr9oZbNZ4sClcuKpQoRTRWdvUNFYePuRgbY3T168TikZxWKpcS6yL3GLysIiJahj4wmFKhQJd3d00NQ2HopDPZJi/eRNdlvF2dpKcmmJoaAi300mlUEBt2cdTEFEhmoYvFKKQzRKJx+14FjhuEjEMA4TyJQllTNU0JKBcLLK5uEjq4ICORILRkycZGh8nLsY2Vl+x1EKWas0mc/Pz+L1eJicmbIOJ7cTWdXMEXa8DLQv4ktmCYlWhSbqOz+8nFAyS6Oqi3mhQKBQo5PPs7e6iyGa38drqKvVajcmJCXNkLC7omvnggEd38+SWi2a5WGRkaur4hWAYNBoNmo0GTVVFU1XUZtM03mgauqhT04SSmTo85GBnB1lRcDmdZtOGw4HP6wXRjytLZrezLMtcf+457t65w+K9ezRqNWSXy3R4q6qtvnaEQoSDQTTDoFYus390hKTrlFQVPZUitbGBw+1m7MoVdhYXGTpzBp/PZ2dKWoTaei1oYpUgvb3NwOnT5jkXo39V01BrNYZPnWLt7l2Gz55l/NIl9ldWWLpzh3q5TPfYmPkmQLxuAz4fLocDj1CYunp7cSoKt7/3PU6/8ALZdBpfIEC9VCJ7cGC+7hSFarFI19AQBxsbJHp6WJubI5fL/dwr4Sxi/3kigNYbjccNgg6FQvziL/7ij/3e/+a/+W/4H//H//HHfs/c3Nynuv9W/NZv/Zb98enTp+nu7ubll19mZWWF0dHRx77dNn72aBPANp56OERDQysMw2BtbY2VlRWmp6fp6+t75Ou6rpMcGuL09et20LKjRZGzmz3Ex5osUyoUeP9P/oREfz8vfP3rdi6eKi66ljpnKTOGptkNGlbER0dHB9urq6aKWC4z99FH6JpGz9QU6UyG7q4uerq7bbImC0OIhNgRFONpJIlgRwcHm5uPEFUL1ojTMlhoulmXtrW6ypaoZxuamGDqwgUkSWJtYYFKqWQbSBDHbBGtRrNJqVQimUwy0Ntr7wyqmmaPbAEUh4Omqh63h4j/1BY1sdUMA2Kk1dlJd1cXmqaxu7vL0oMHFIpFZFlmb38ffyBAKBTC7XI98jjrjQalQoFKqUSjVqNcKlGrVHjw0Uc06nV7NA7gcDpxulw4nE5znOtw2GRdFs0eOpDP5fD6fFQrFdPIouuojYZJ5ppNGs0muqra6qAEuL1evH4/7nKZjc1NmtUqhtdrj5xlTGIuSxL1ep39VIqg10tnZycNVaVUKrF29y59Z88iBQKEfT7mP/iA0fPnzTGtruNxOs03A+Kc67pOsVAAScLrdqMoCs2mGf5ztL5OpKeHroEBcgcHLH70ERMXL9I7McHu8jIH6+sUMxkSXV22Qqupquk8Xlmhb3yccCiE1+1mp7sbo163FWVPJMLC3bt0DQ3h8/vJ53LEu7o42tnB7fNRr9XIFAqf4jf4s4EdHP45IoDWDuqn3Z8slUoEg8FP9L1/5+/8Hf7G3/gbP/Z7RkZGSCaTHB4ePvJ5VVXJZDKfar/v6tWrACwvL7cJ4OcMbQLYxlMLe9ftYyNgVVV58OAB+XyeK1euELZiSVpQLBbxBIMmQcJ8oatijCmJHTuL1DV1nbW5OVZnZvgr/+V/STASsdU2a3yrYDZ+WIqfSxyTJm7HyuDzhcPkUikefvABhUyGqUuXqDcaHBweMjo8bDZ4aJpNvKyYGEOoj07h7nXIMuGODpbv3XvEQWyNlTVdtwlKuVRibWaG8u4uyYEBLr7wAm6Pxx4VS5JEKBQifXhot4VYJhHDMEinUqQPDvB5vfT09Ni5hbZzVvyryDJOp9MkS1Zszo+4+Fqk8BG3MObFr1arsbOzg9/v5/Tp09TrdQrZLGsrK6SPjpDEvqDLInOKgi8YxOv3EwgGCUYieHw+KqUSz77yCvCxHuGWnbpWN3DrKHjhwQNOXbpEUhBdO6NQ7N9ZF2hb4TTMUN9KqcTm2honJya4+Yd/SKS3F0lR8Hg8eEMhvOEwisdDLpOhIxQiGA6jS2aM0fqdO/RPTHD+mWeoVquUy2XCAwPc/f736R4dpau/HyUQOM5GFCsGh5ubxPv7zedbnMdasUg2nWbq8mVkIN7djSzLLH30EWMXLlDMZrn85S+zOTdHuVikZ3DQHOcaBmq9TqNaxRcMYhgGqb09hk+epJzLgaqapha3G48sM3/rFt3j4+S3thg/cwZ/NEpmbw9D18k9BQTw86gAWgaQT0MArcq5T+q0TSQSJBKJn/h9165dI5fLcevWLS5evAjAW2+9ha7rNqn7JLDWb7pF53kbnx+0CWAbTz1aR8ClUok7d+7g8Xh4VmSy/SgUi0Vkn8/ep1MFeZLE6Nba9auUStz93veIdnczdeECoY4OW9EzMPf6rKYNSZLscbAOduSHIXYBdV1nY2GB2Y8+4qt/428wffky62trNKpVTkxN4fJ4TNWRY5L0iDsXU22SMC8UDrFvB4/mClqj6K2NDTYWFsyMsWSS519+2b4dA+zGkaam4fb7qZTLx/cjzsf61hbZbJau7u5HLuqWO7eVKDZV1XzcloohPt/6WHQrAFqQ2NYcwEKhwPzcHNV8HrVW46O330ZVVXP0GgwyNjpqjtYNg1q9jizLhEIh879g0BwBGwa1ahVv68Ww5WJq5dhZj8EigDJgLRFkDw/t8bFTOo7ocSjKMeEX+3lgGkLw+XB7PPh9Pp579VXO7+/zgw8+oPvsWZPYFoscbm2xv71N0OulEYtRjUQIxeMcrK1RKxY5+8UvomMGc/s8HqKxGP39/czcuMFWtYo3GjX7kwMB3ELxqxaLjJw+bUcB6arK6oMHjJw7Z2dJarpOR2cnBjD77ru4/H48Ph+nLl9maWaGlZkZxk6exDAMdldX6R4asnMlM/v7TJ4/j9HTw9xHHxHt6yPg9xMdHmb+ww/p6++nmc+jOBzUGg1WFxepNxosr6zYpOTn5Qb+vCqAj9NoVKlUPrEC+EkxPT3Nl7/8ZX7zN3+Tf/pP/ynNZpPf/u3f5hvf+IY93t/Z2eHll1/md37nd7hy5QorKyv83u/9Hq+//jqxWIz79+/zt//23+aFF17gzJkzT/T42vjs0SaAbTz1cDgc5lhtf58HDx4wODjI+Pj4j73wVKtVXB6PGc1imMHOqlgYN1QVVdfZXl5m9f59zr7wAuFYjPTOjhmGDLZ71yIEcGwQAdOIIYOtJO5tbrJ09y59Y2OcuHiRcDzOwvw8XpeL6akpEH/0LddwU2TGIUkYmmarWM2WsazV6qCpKohKvGa9ztLcHPsbG3T29XH5hReQnU7u3rtnjg6dTnskazuRJQmv30+1VLIv/PV6nZXVVTRNY3Jyknq1SiaXs+NrdCvXDh5R8RQxmrTGwhLY+XfwqBmjWi5zsLdHLpNhd2uL1NERvf39+H0+/H19nLt6FYfD8UO1bU1x39VKhWwux+7uLuv1OsFgkGhHB/VKhWAkYvf+Wi0rhmE2pLT2BduZhLKM1JLV53A4zPNs7TginNPCuWtV7RmYO3SyLHO4t0dMLM3Hk0levH6dt955h97z5zFcLlzRKNdOnMDhdlOvVKhmMtz58z9HazbNx5PPm+Pplt1Ch9vNxRdfZOXePdyGQaijg0atxtHREQcbG/iCQcqlEoFAAEOSWH74kOTwMG6Px96XtJTBSCLBhiRRK5dBN5tihk+cIL2zw/zt24ycPEkpn6d/chIDc4/S4XLhdLnQdZ3hqSlm794ldOkSWqNBV28vO0tLBDs6TFVJkqgcHlJMpdjZ2+PmzZu4XC7i8TixWIxIJPLYfd2PA0uhfRriaD4pHrfT/LMKgv7d3/1dfvu3f5uXX37ZDoL+x//4H9tfbzabLCws2C5fl8vFX/zFX/CP/tE/olwu09/fz6/8yq/w9/7e33vix9bGZ482AWzjqUXrCDibzbK/v8+ZM2fo6ur6iT9brVbB5bLVNlUQA0WWKdXr3HrrLRwuFy98/etI4qJvqXpO0dhgRbu4hEHEMhA4ZZmGME8UhMHDEwhw7ctfxulycbCzw/2PPqJ3ZITe3l4c4vYsp6/ScsFyCiJiEUsrQ9AyggQjEQq5HC6Xi6UHDyjn8wxMTPDcG28gyzJOWabebJoRIuLnbfLDsXvXUuNUXadaq7GysoLf66V/dBSPy2UaO4zjoGZFZAsamHl0EiYhcrtcaJpm7/y1RrrkMxlS+/tkj45o1Ot4vV7CiQQOj4fukRGuvfwywWCQrbU11GbT7nm2LuC261dRQJZxh8MEg0EM3cxizObzpDIZlmdn8QcCBLa3CQaDBAIB+zZa9wf1FnJgqUW5TIZQR4f9eU2oqZZqCdhvAKxjs3Y0dzc2GJ6cNHcKZZnOri6+9NJL/Ls/+iM8g4MMDA3hdrvN15DHw14qxciZM+belyxTqVRI3b6NBoS7ukj29eF0OGjqOkNnz7L+8CH5nR36JyfpiEbJrq3R3ddHNp/n4OiIWi6HXqvRJ8wZTtEiY0XclEslnC4XiYEBFu/cYfzCBdB1M2hakrjxp3/KqWeeMUmuLJPa2qJrYMAcS0oSAUHgCuk0VYeDroEBVmdm6BM9zBIQjkZRHA5CwSDPP/882WyWdDrNwsICjUaDjo4OYrEYsVjMduN/Vvi8OYDh8RXAcrn8xBVAgGg0+mNDn4eGhh6pUuzv7/+hFpA2Pr9oE8A2nmo0Gg22t7ep1+s8++yzn/hdcL3RwO10Hu8AihFqIZfj7ltv8cIbb5AcGMAJNIWD1+V2o9frqCIPz2Wpci3k0erxlXSdjZkZqru7nL1+nUg0SlPTODo4oFit0hkK0d/XZ490rcYRwHScCtVLF6NmEKRLfI/l5tUMg+9/61t09/YycvIkie7u42BjsPfsNMxdRp8gaLLYVTRaduLAbElZW1sj2dVFb2+vTeZ0w3jkD70VxWIRSmtULSmKHQNTyOVI7e1xtLeHpmmEIhGinZ30j47i9niQDYOVtTX0apXp6WkcTqf52Op1PB6PuY9p7d2J+2gNj7aMEGAGz7rcbro6OykdHRHv6aHZbLKxsYGu68ej4lDIvl2tZVRtfXy4u0tCLLjL0nGvsNJyX86P7RQamGSjVCgQjkRs5anZbHKUzXJqeprV9XVkEdArA6t37+KLROgcGmL+3XeZeuYZHA4Hxvg4er3O4c4Oi7duAdA1MEAokWD0zBm25uZYn53FHQjQ1d9PoquLqKaRz+VYWltj4MQJ9nZ3cSgKLjGSDvj9YBhkd3ZIDg4STSbRGg0za/DsWRqqSigSwRMIcLC1RbSri2qjQTGfZ3BqCgRRloDE0BD7q6u4fT5OXrjAzuoq9XLZNCwZBm6fD73ZpFaroSgK8XiceDyOYRhUKhXS6TRHR0csLS3h9XptMhiJRJ44Wfu81MC14uMh0J8EDWFQancBt/Gk0SaAbTy1yOVy3L59G7fbjdvt/lQjkKbIh0Myo1WamsbKgweszsxw4vp1kgMDtisYsQ8XCIXI5/NEPR4cQn20qJNkGLbxYXd9neW7dwlEIlx69VU8bjcYBpvr6xRLJc5evsze0pJN8hotBMf5sVYOK1i51bygAPvb26w+fIghSXR2d3P5i18EsJ3JklAIjVb1TBBVWsil5co1DINqpcLywgLDY2NEo1FaL51WiLTV6avrunn7QmWRJIl6rcbO+jpzd+9SLZcJRiIke3oYGBvD+bFdzEajweb6OgYwPTVlunvFMTWbTfyh0LFzuPUi3kJCWwmpRXQloFapMDg4iCL6jEvlMvlczqxs29zE6/fTEQ4TECHJLjHKBcimUoxOT9uVetaupN0pLM6lU1HM5148/r2dHTtCB6BWq7G2toaiKJy9cIHRsTHeevttOk+fZuP+fRK9vST6+8ns7ZkqqNNpkmxdB6eT/tFROgcGaNTrpLa22FtZwdfRQdfQEIcbG8zfuMGzX/+66eAFth8+5NS1a7g8HjoliUatRlE87tTBAbKicLC9zfkXX0SRZZIDA2zX62wtL9M7Osra/DyTFy/SqFZZvHOHQDRKoqfHzpDUxBjd4XDQ0dXF3soKmqbhDQRo1Go06nU8bjdqs4mkKNQ/FsskSWZItt/vZ2BgAFVVbXVwbm4OVVUfUQc94k3WT4P/qyiApVIJoE0A23jiaBPANp5abG1tMTg4iNfrZXV19VP/vNWkUK3XufPd7xKKx7n82mukDw5sY4hDkmyDhTcUopLPE+/qsr/mwBwTakC9UuHeu+/iD4V47o03uPfggakwqiqLS0sYsszU1BQep5PlW7eOzR2GgVM2e4ZbPyeLZgwd7HHzzvo66zMzdHR1cfHFF3F5PLz37W8D2AqkpdZZGX6SZGYBWjtwrYqfQ3x+fWODqqoy3dVFNBq1v26THzgmfcLcous6+UyG/c1NMoeHuNxu4t3dDIyM8Nxrr9nHZN2fIYwftWqV1dVVgoEA3b29SGI/z3rsjUbjUcL4MTdna+yMZeowxF4icByULOJSPF4vHq+Xvr4+ytUq+XyeSqnEzu4uDoeDWEcHvkAAr8cDum6O3THVUWtMjjDxtO4wWo9JAnbW1pg+exZFNhtV1lZX8Xi9DA0MoAORaJSXX3iB/+P3f5/BixeJ9vSgA3tra0xcuICm67gcDtu93RC5hB6vl76JCfSxMcrpNOsPHlArFnG63eytrjIwOcnczZv0TU7i8/ns59vl8dDhcpGIxVBVlYV79wh2dbG1vW1m/Xm9dA4MsDE7y9bSEoqi4A+HCUYi1KpV5m7e5MVf+iXTbCReI5pQnXWxNnAgSK+h6xSOjvD091MtFm0l98f+7jkcthvVcrGm02kODg5YXFzE5/PZZDAcDj8Wkfs8EsDH2QEslUpIktTu223jiaNNANt4anH69Gl0XSeVSn3iLmALiiyjNpvkUinuvf02U1ev0tnbS7lQsHf5WmNgDMMgGouxtbqKlSgoGYZp1tB1Vh4+5Ghjg5PXrhGOxQBTLSuWSuzu7BDr6KC/v9/ODbTMGy6n01TpWseNwpRgZfs1VZWt5WXW5ubo7Ovj2pe+hNJykbX6di2iZTl7LaKkappJInUzP9A2MAi1bXF5GV3XmZyePnYVK4qpagpl0zI7qM0mB7u7HG1tUSwUCEejJPv7mTp3zr7Y7m9uPnJsFtFWdZ1MLsfG+jpdIu+wlRxa/zYbDXxer916YYCtOh5T1+PReSsha9TrjxCQR3b+dB2X00kiHkfp7KRPVSkWi5SKRba2tkgdHKA1m6TSaULBIE6xI9r63DgVxVYmrRBqVVVp1Ov4g0EKpRIba2uEIhH6enuPDUOKQryzk1/7tV/juz/4AZGuLurFIi6PB8XlwjAMGqpq1g+K0WVrADRAIBZjOhbjzltvEUsm2ZydNQOjT50iJIiURXeskGjNev7qdU6eP4+qaVSqVRrVKqlUCjkU4s5bb3HxtddMYu9w4PJ6CUYiZPb2iPX0mMRPvKmwyN7ImTMs3LrF1S9/GckwWH3wgK7+fqqlEl6vl4YIA/8kkCSJQCBAIBBgcHCQZrNpq4MzMzNomkY0GrUJodU+85PweSSAj6MAWgaQz9tjbePpR5sAtvHUwtrv+XFNIH8Z3C4XmzMzqPU6V77yFbyimk0T41ArCBqxKydJEr5IhHIuZxpCDIOmMDbcf/dduoeGeP4XfsEelVmEYXtri76+PnpE4K51lB2JBIVUio6WfTNrr87K+zN0nZ21NWbefZfg88+bJhKn0yZLljM4EApRyGQIC+XO6vm1iIPdcStGvtbXqtUqG6urOD0ehgYHyR8dkRbBr03hPAbzorS/vc3crVscrK7SMzDA+OnT+FqWzh8Zx1o7jII0WEaKo6Mj9vf2GBgYIBKJHD9uERNjNXGojQaSIFpyy7n8uPqmC/LX6sQtFwpEolFzz4/jRpNHwqcFKZJlmUg4TCgYpLunhzu5HIFkkkw6zd72tqmiRSJEwmG8Pp89EnYK0491e9sbG3T19ZEvFNjc2KCrq4vOzs4f6qhuahod8TjXLl3i/du30WWZ7uFhaLlNqx3GOj5LGbTaYPIHB0Q6Oxk8cQJPMMj9t9/G4XIRSyZx+3wokkRDVY+rCTWN3ZUVkkNDZmyRohDw+5EDAXRdZ3NxkfELF9icnUXVNBwOB/uLi0xducL2/DyBcBhPIGBWCFarZLNZfIEA7kCAWrlsqo0ul/kGRHQEu71emo3Gp/p9bIXT6aSzs5POzk5zhF8qkUql2N3dZWFhAb/fb5PBUCj0lxKfzysB/LTH/POO22njP1y0CWAbTy2sP3g/qgnkJ0GRZaq5HC/+2q+ZdWZC7XKIZX9VjNJkQQQlwOlyoTUa5shX01i8fZtcKsXFl17CFwjYxLGhqmxubqJpGoP9/cTicTNbsMXtG+3u5mB31yaAkjW6tYjj+jqL9+4R6+5m6upVps+ft0OlZdmsq7NGpuFEguzhIbF43CQKPKqoSbJsEzJVkKZcPs/6+jrdXV30dnej6jqeQIDC0hJgXjx3trfNjuBKhY7OTk5cvGhGsDidFEolNMDn9+N0OFAwx9SaOFf2KFuoZ9s7O+TzeSbGxszIEvE8WHuIsjg3SBJqywjYeo4ttzIcZyFa427r3GEYZFIp/OHw8f6ggMyjuXBSi5vZIpbVSoUL167Z4dupbJZCocDh0REAwWCQsHAeW2NRgL2NDUamp9lcX2dkeJiwILeGOAZJksx2FEFyu/v6OFUo8Kff+haDZ89iiNeZJsa+qlDvJMxswpqqmqsIksTuygqj58+TOzigUanw+m/8BrPvvcf9d94hMTDAwMSEbXKpN5ugaVRyOQYmJo6zH8VqQK1SoZzNcuqZZ8gcHJDZ3YVQCE8wSC6XwxGJcO/99zl17RqKopBKpajnckyfO8fBzg4D09McbW+THBzEH4mws7GBoev4w2EaPwUBbIUkSQSDQYLBIMPDwzSbTdLpNOl0mgcPHpjKfIs62Jr7+XklgI+rALbRxpNGmwC28dTDagKx9t4+CUKhEAPj47hEuK9DOu7ZtWI9FISzVXxNNwwUp5PU3h5zH37IwMQEJy9ftkONVV2nVquxuraGBHjdbmRrxCt2+lRxm7HOTlYfPDD3CzWNJiYxOdjeZvHuXaKdnTzzpS+hOBzcvXsXVdNwORw0NA1d7PRZjR3JZJKZ27dRRXixffwtSpV1DIZhkD46Ynd3l6GBAWLRqE3WPD4fqf197r33HoVcjs6eHibPncPn95txNw4H9WaTYrFIuVBgS5DcQChkmioEMWqFpqpsrq/TaDaZHB/H6XI94qC18IiCiEnqZVpGvJbppoXE6S0kzholF7JZkqL2r/XzraqsDMejZHEMtWoVt9t9HDkjy8QEsdB1nXKpRKlYZHdvj8b6OuFQiEAggENRKBSLHKRSjAwPExDmFWv8KkkSLllGt3YVxd02Gw0unDvH/uIigydOUBd1bIaum/ugH9vTRNdJHRzgDYWoVyocrq8zfukSkqJw6vp15j74AEmSmHn/ffonJ4klEkiSxPrCAv0TE8eh3YaZbYhhsPbwIcMnT5q1iD09ZPb32Vtc5NLLL+N0uahWKjgMg8V794j29prrAbqOLstUslnGLl5k8dYtegYGiHZ2Mvvhh/gDAYKRCNX9/c+EgDmdTpLJJMlk0nSaFwqk02m2t7eZm5sjGAwSi8WIx+OPpab9vKHruh1/9ElRKpXw+/1tBbCNJ442AWzjqYfD4bDJwSd99+z3+zFqteNaM8nM4JPE2MwwDHtca5E0XdfJZTLceustXvj61/EGAvZ4WNV1yuUya8vLRMJhuvv6WFxcNC+C4g+zquu2ocHj8Zj5deLCn0+nmb15E18gwOWXXsLt9ZqNI0IxVDXNjuMAzPBqcVyuQICKcAIiMt9as/gQO4XoOjtbW+TzeUbGxvD7/WjC/bu5vMzh9japgwOuvPQS4WjUPqeWciQBbocDJRymIxKhR9epCFPF4eEh6xsbBAMBCvk8arOJpuusr63hcDoZHRszXblC5QMxnhUXaIugWCqgJlzaVtgyYGcxfvxj6/ZkWaZarRIMhezblYXCZxFw21AiCKWl0u1vb9MpKtOs82vlLRqShDsSIRqJ0N/fT71WI5fPk83lmL1zh0A4TFjcpyaeb1k6boipW6N4MeI2DIPs0REvvPoqN959l/31daKCtMri9Wd1QFtRN6qus7u8TO/YGBuzs0xdvYrL5TL7miWJsfPnWb51i+HTp9lfWyO9t0f34CDNahV/R4dNzJuqim4Y7K2t0ZFI4Pb7zbzARoNwNMrO8rI5CjYMfF4vyf5+dtfWCHo8HO7tEe/tZWVuDlXXKeZyOFwuirkckViMQiaDPxgkEo9T3t21x9+WS9zqXX5SkCSJcDhMOBxmZGSERqNhq4N37961M0L39/eJxWI4P4E55ecNTdM+8Y6jhbYC2MZnhTYBbOOpResOIHy68UkoFKJeKpkL+oIkGIBbUexRpt30YBiU8nnuvv02id5ePF4v3kDA/Dmxm5VKpdjb3qanu5uoUF8URUGx3JNif8wh/lU1jXA8zu7aGgdbW2iqyvnr1/G0/CG3xraaRW4tUoNpTKFF8XQ6nWYFmyyjWvtfYvdOESPurZ0dZFnmxPQ0hiSxu7HBlhj59o2OMv7lL+N4802C4bBN/pwi1NhS7ax/LdLs9/kIBwLIfX2ULIdttcrD2VkMw8Dv9ZIQ58NyAUvCrdwaLC2Lz9m7ih+DTQKt3T7puF5Oxgxn1kQsjdVn/KN6fw3DQG/ZB9TEfR3t7XH60iVTgVGUY7L+MTUOwOV2E+noIJvLUS0Wufbii9TrdTY2NtB0nYAInw6Fw3hcrkd/XpJYnp+nf3gYwzB45tlnees736GYyRBNJEz10Opo5jjLMX94iMPlYmt+nhNXryKJgGiLIHp8PobOnGHt3j2mn3mGzOEh7//7f8/p558338yI21McDoq5HLmDAyYvXz6OtzEM9jc3Ofvcc2wvLDB69izZfJ6joyNOXb3K7sICyDIDY2OUP/yQYWHAcvh83L99m9ETJ6hVKjRqNQJiL8/hcJhvIFqUW4sEPmkyCGYLRXd3N90iC3NlZYVUKsXm5iZzc3OEQiF7VNwaDv404XF3ANsEsI3PAm0C2MZTD+uCoqrqX9r9+3G4XC4UocxYLSAOSaIp1DIH5k4bhsHa7CzbKyuce/FFPD4fH33nO3Zrh6HrbG9tkc9mGRwZoSMUQtXNLmFLfbLUD6cgIbpw0+YzGR7euMErf+WvEOvqskOPLfKmifGnIsuPGDtsFaxFPYskEhzt79PV2wuYBMlyrBbKZRr1Om6vl/6eHubu3iW9v0+it5ez168T8PlsYucLBKgUi4QiEfgY+bNpmVAZwVQorcdrOWytPLJYNIoiSexsbaHpOv5AgHA4bIcxyy0XYHsn0BrZiio9u8rLMAOxrV1PR+t4W/xspVTC13Ih1FqOu9Fs2gRRFdVrVqezruvks1ma4ntcTieyoiCL82ft7lm3pzabLC0tUchmOXHmDIlEwjRsaBqVSoVquUwqlWJnZ4eAz0fIyhwUys7e5ibPvfKK/dw994Uv8Gd/+qe43G5zlxTxRkGSbOV5/eFDFIeDE888g9PjMV/rTieNZtMOow6Hw/ROTLBy7x6dAwN0j42RFqQ/0dNjvs5VlY2ZGcbPnzfH7IIkH2xvk+jpIRSPkzk4YH1pCUNRGOjrw+VysVAo0DMwQD6TsZ9HhyQRj0apZTIYmobscpHN5VhdW6MmDCPRaNT8PRBvhHSxP2vBak2xPn5SkGUZt9tNMBjk1KlT1Ot1Wx3c2NhAURSbDEaj0U89dv2s8Lg7gO0MwDY+CzwdvxVttPFjYKltn9YI4hLqibVwb+1sWaqd2mxy9+23CUYiXHv9dRRFwSFJ6KpqXpg1jfW1NdRGg/HJSXt007o72Gg27cDnpojp2FxeZn12lsETJ9CaTWJdXfZFX5OO+4Qt04flDG6NxrVIoaUExrq7Odzepruvzx5vNnWdXD7P2uoqlWyWw7U18tvbDE1OMnX+vH3BlYRCqEgS/lCIbDqNPxw2iVfLuFYW51nVNPtctTwJ6IbB0cEBmUyGZ774RQLBoK28VSoV8vk8BwcHbG5u4vf76QiFCEUi+Lxe251cbzRwOJ32CNjq8P04NE2jUi5TLhapVSpUKxW219ft///4zygOh1mP5nTao3SHUHvz2SzVSoXV+XmToKgqarNp3kYLyZRlGWSZbDZLJBqlkssxevWqqbJKErpkZrEFAgHinZ1oqko2l6NQKHCwv48ky5TzeSKxmO3IVTWzn/nll1/mW3/2Z/RfvIgsqvlkoKHrbMzNUc7nufzlL+PyeFA1DbfTSVOMWC0VtK6qRLu6KGQyzLz7Lhdfew3F6WR7ZoZKscjA5CQr9+490hUsyzK1Wo303h4nr14FINjZycyNG1x95RVcLhd1oeoV83kq5TLDJ0/a5ihD0whHoxSPjoh3dhKJRgkHg0heL0tLS1SrVTpEV3AsFsPv99sk0FIHrVHxk1YHW5tA3G43PT099PT0mIQ/nyedTrO2tsbMzAzhcNgmhD/Pfbo2AWzjaUKbALbx1KL1j/TjRMHEQiHUWg1JdJI6xEUcReFod5eF27c5cfUq8Z4eM0pFuGjDnZ3srq9TKJdx+3ycOHHC3lezYjx0EeUCIsQZyKfTzNy4QUdXF9dffx3F4WB/dRWt0cDpdqOKkWtTqE72npr4VxOqlT2WbHn88USC5bt3jztrDYOdnR3u3byJ3GiguFxMnj/PwNAQgK38OMVuoKZpqIaBLxgkn0o90r+rWHl3um4bTKzbUA3DjqzZ2tykVC7T29eHx+u11TsJ7BaI/t5eGo0GuXyeXDbL9u4uLpeLjkiEQDCIoWm4RAuEYRhUSiWymQyFfN4kd6WSeU4Ar8+Hz+/H4/MRjkbJZ7NMnztHsrfXJt20PC9wTLpazSUPbt7kxLlzRONx++vwsRBroJDPs7SwwEBHB26nkzsrK6wtLbEg3Khen49QJEI4FiMSjeJ1u4nH4yQSCTSROfi9+/cZPnmSBw8eEAmFiAhXsdfv5/ozz3Djzh36z5wx30AYBuVcjsUPPuCFb3wDr89njl0tVVa8RizXtdPhMMmhOH+NapWo38/AyZMcrK1x6803iXR2kujpoamqNoncXV6me2gI3TBIHR1RqVaZOHWK3P4+3pERdpaWGJicZHdtjWq5jMvtNmN3JAlDlgnH42y+9x7+cBiPz4fUbDI+McH169ftgOejoyMWFxfxer12PVxHRwcg+qnFfz9KHXxcMviXmVBkWaajo4OOjg7GxsaoVqtkMhmbEDqdTpsMdnR0/EzVwccJgm6PgNv4rNAmgG18LvA4UTADySQLh4ckBwfNcaputmTsLC5SdLt55vXXcbndJvnTddsU4gmFuPXee1x5+WWSyaStGlokA0GsDEslUVXuf/AB1XKZsy+8QCgUss0Cyf5+ttfXGZyYAI7bMqwaN6cwIkhCIZNa9to0oSgiSeiybIY9axq1apX3v/tdDre3Of/MM0ycOsXmxgZu0RQgyzIK2MfX2nkb7uhgd3XVJqJgjlLt+xWxMla2nmSYTSpbGxuous7ExAT3Mxk0VcXpdJpKpSClmm7G6ygOh32B1TSNYrFINptlbWWFvc1NCqkUB7u7eH0+/H4/wY4OgsJY4w8E7Io367FYx74+P09CPB+WCQOOw6CtXTjAjuQByGcynLp40f4eOO4ctsa/6UyGzc1NRsfG6OjoYGl2lme+8AX6h4ZsglyrVinmcqQPDlidm6Opqvj9fhJdXcS6ushnMkyfPs34yZNozSbpbJajdJqNrS18Ho8ZHh2Lsb+6Ss/4ONnDQ+69+Sanv/AFvD6fed5pidgB3LJsxxQZuo7RaJDa2eH8q6+yfvcu3osXUZxOIl1drM/OotXrNJtNHA4HzWaTWqVCs1olHI9zeHCApmlmR7UkMffBB3hDIdRmk2BHB+rCAg5Fwelw2LuWDocDQzJrAOPd3TRqNerVKhfOngX4ofq3TCZDKpViZmYGVVWJRqM2IXSJQGyLDP606uAndSF7vV56e3vt7mtLHVxZWaFarRKJROzX62edt/e4O4DBlkzONtp4UmgTwDY+F3icEXB/Tw+379/HMTRk7tzV69x8802zv/Wll3C73Waun6WUaRr7u7vkq1W8DgfJZBKXLNOwlDmO69g0YcjYXVtj7eZNxs6dIzkwAIguWVmmoWl0DQ7y4L33GJyYsCvnWs0dYJKVpqbZcTOGYRyHEbcs2Lvcbr73R39ELp8nOTzMf/Qbv4Ei1Asdc0xoqUdWRIzVv2uNmmWfj2q1apO/1sBjqwdY04+7Yau1Gqurq4SDQQZ7enA5nbgcDruWrdnynNi7fIZBqVAgtb9PLp2mUiohyzLhSASpp4d4PE5nfz+1eh2/3084HCYSDtv7nXKLecNyA1uEzeV02ruFDofDDr+2g6Gtx4M5+i4VCviDQZxOJ7JQFmWrCk787OHRETs7OwwODREOBjEMg4Ptba69/LL5fRy3WXh9Pjp7emwSXyqVSO3v8/D2be598AEXn3uO1MEB8c5Oujo76U0mqTUaFAoFyqUSLp+P7Pw8h4eH1PJ5Il1d9I6M2E5mzTBwKQoNEdTdEC0tiiyjyDKrDx7QMz6Ox+uld2KCzdlZBqenWb13j0uvvUZ2f5/1hw8ZO3MGwzDYmJ2ld2LCHFFLEsnubvs11jU0xIMf/IBLr75KOZvFGwhgaBqFXI5AOIwhiGfu4AAD6B4cZG9zk0alwogIuG6Fw+H4kQHPe3t7zM/P4/f7bcU0LIxIlmv6cdTBx4mhURSFaDRKNBplfHycSqViq4Orq6u4XK5H1MFPq9b9JDzuCLi7u/uJHkcbbUCbALbxOcHjjIC7u7upf+97qIZB5vCQmR/8gOlnnuEwmzVjQCSJpiBjzWaT1dVVqvU60ydO8ODoyBwfezymk1gs7VvqTK1c5sH3v483GOTFN94wg4PBvrhaO4Jur5dmvf7Ixc0iWlYNnZWBZ40trbBgMIlken+fxfv3yRwdUa7XufDCCwwNDdkOUUWW7eBi6+cslUUBjJYdSMRIEY73/gyxx6eKc2J9vVgssryyQncySXdXl0midR0UxW6CkCQz0iWfyXC4t0f28BBNVQmEQkTicSZOn8ZnOTINg/XlZWRJYmB0lKYYFRcKBfZ3d3F7PETCYaKRCG4xYrYIXqNex+V22wQVjsfXraNgO4NQmDY21tbo7O1FVdVHxr+WqWN3Z4d0JsPo6CiRYJCGppE+PCSaSOB2uWz1VBfnShOP2VIPo+EwwUAAh8NBMByms7ubw50dFu7fxx8M0j8yQiyRIBGPE41G6e3rY7C/n3/1L/8lTbcbfzLJ9u4uHcEgisuF2+mkIdYLrFxB63lOHx7SbDSIdnbikCSCsRipvT1uf/e7TF29itvtpntggF1NY2VmhlBHB26/n1yxiNPpJCEaVKz1AE1VMcSbhbWlJUbPnqVZqZDe2yMgjDzVWo1yoWA6wkMhMAxqpRLDP4IAtuJHBTynUik7wgWw8/ysgOdWQvhJ1EFd13/q6Befz4fP56Ovrw9N0+yKusXFRRqNxg+pgz8t2kHQbTxNaBPANp5aPKKSPcYI2OVy4dQ01mdn2V1d5cqXv4zb4yGTz5sKlnDlqvU6C0tLBLxepiYn8bhcdA4OsrW6ysiJE7YL09qRW37wgNTWFhMXLuD0eFAcDrt9QW0hJ5ZSFevp4WB7m57BQdP5yvHYFbANAZbiY30+tb/Pyv37uHw++icmcEYi7C8uMjw8bO+G2e0iFlkSt49QGjUxxrWUS8MwcLvdaI0GsstljqJbFUkxhs6K8N2+vj6i0agZNC0gKwq5TIaj/X1S+/toqkqoo4N4MsnIxITd8oEgnK1mi0atRiQWw6EoODwe3B4PnZ2dYBhks1nyhQLLq6uomkYwFCIaieDz+8mmUoTETpm1O2l9bI+CW8699VpJHRwwZgVotxhHms0mm1tbNGo1Jicm7Mw9CVhbXOSE6NW1CKYkHLuKIFCGIIFWFM/a4iLXXnoJp8tFTPT2VopF1paWmLt7l85kkoGxMbNtJBLhtS99iT/9sz9jbHoavdkkXyhQrlRwOp0EfD6Cfj+K02m/sTB0nc35ecbPn7cJnGEYoKpoqoovELB3SJNDQ6zcv8/shx8ycO4cbqeTZFcXiNedVet2sLnJ1OXLLNy+TUQQnIbDwcbiIk1VxeNykd7fx+l2E0smqQrzjdZoEI/HP9XvotPptCNcDMMgn8+TSqXY2NhgZmaGUChkj4qDQoX9Uepga97gkw6iVhTFPgZDGJvS6TSpVIrl5WW8Xq9NBiORyGPd9+PsAFYqlTYBbOMzQZsAtvFUw8qXe5wRMEDY7WZtc5NnXn/dbG0QF28rHqScz7O8vk4ikWCwt9cmej3Dw9x+6y0mTp60w6SLmQz333uP7qEhrn/1q+zt7VGtVHAKcmURDBnsiBGAnuFhFu/cYWBoiKb1fYJQKWKfraGqtvM2e3DA3J07+INBTl+7Rr5U4mB/n+HRUWpHR+bOHeYI04rgkKTjhhPLBPHxYGTLOOGPRMhkMiRETZ1FDh3i+zc3N8nlcoyPjeERqkez2WRva4uj3V2WHj4k3t3NxKlTXLh+3Y4/sY0X1sfiscktCqSl5FnkSm9R7yKRCJFIBIcskysWKeTz7O3vU61WSe/u0jswQKNex+fxYEjHodlWnqPU8h9AvVbD4XDgEY5YEPEyqsrK2hoGMDExAdJxpE61UkEXkTZWLI+1J6iK8G1JPH9WVM3u1ha9/f04nE67nxcgEApx8sIFFFlmZ2uL+zdvIksSI5OT7O/u8uyzz5La3yc+OIjb68WpKJSKRYrlMrsHB6DrBHw+3F4vud1dEj09eL1ek/hJEnvLy7j8fqavXWPt4UOmLl6039g0m01qqgqqSpdQbx0iegdJYnNxkaGJCTzBoKkgXrhgnjtJwhcI0KhUcMgyqd1dJCA5OEi5WKTZaBD0+z91mHErJEmyn+uxsTHTpSyI1vr6uk3EEomEHeHSGjNj/WcphFYO55MOof74fqOlDs7NzdFsNu2Kumg0ilcYzX4cPm2YvYW2C7iNzwptAtjG5wIOh+NTj4ABnr10ifLqqk2AdESwtKaxu7/P4d4eA4ODdMZix6oK4BVOy0qthsPpZOnOHbKHh1z4whfsLDenolDSdXuvz2rvaL0dwzDoiEaplEo0WhbAXWK3TdPN6i1d10kfHLBw5w6BUIjzzz+P2+Nhc3OTSqnE9NQUfp+P/c5ODvb26OzpAbDNGrJQqJotYzNFkCQDEaQsSFAgHKaQzRJPJs3dOTHirDebbG1sUK3XmZicRDIMVufnOdrZQdd14skkoydOEIxE8Pr99AwMPBLHYoVuW4YSa3QKx+pco1azyUOrwqsLwmqpph2hEJFgEN0wqNfrfG9jAxSF2bk5/F6vWUkWCuH3++39Rkt9tUjYxtoaXb29NFvGv/VGg3XhBB0bHrYzBq0YmPWlJcYmJ83zYohQaUEEwRzJW6qf1Rm9Oj/PtS9+0VQGxUjeajsxxGNP9vbS199PPpfj+2++SblY5PrLL5O+d49KoYBXXOD9gQD+YBBVVdFV1YyY2dtja36eqYsXyWQyuL1e8gcHNKpVhs+cQZYkMru7pPb2iHZ2sre1RTqV4tyLL3K0vEyjv98k6eKN1OHenqnaxuNszs8zMDFBOZdDdjjwOBwEo1EKqRTNeh1JUXA5HEQ6Okjt7VHK55kaHPzUv4c/Dh6PxzZp6LpOLpfj6OjokZgZS5nz+XwYhumAz2QytrHDej19ViHUDoeDRCJBQqi7lvv54OCAxcVFfD6frQ6Gw+Efef/WcT6OCaRNANv4LNAmgG18LvC4CuDQ0BDV996Ds2dRhavWKUnsHx2h6zpTU1P4WoKSrfy9hqaRHBpi4c4dcoeH9I2N8exXvmISFY6zCVu7axWLDCIq3sAmDwlrDDww8IiRBKBcKLB65w6Jri7OXb+OLxCg2WyyuLiIDJyYmgKx39bZ28vexgZdvb12hp5VI1coFPB6PIRCITzigm+PpAWxMgyDaCzG8syMPSp1yDL1Wo21tTWMZhNJ17n19ts4nU66+vo4/9xzuN1um+ylDw9Rm00A23xhu4Bb7+9HuCnrtRpur9ckihznAFpjccvwYX1NNwycLhd+n4+p6Wk0TaNULJLL59lcX0c3DEKhENGODrw+n7krKo7hcHub888+C+L4qtUqqysrhMJh+vr67MxD6znSxf7f1JkzxzV7YCu89qMRJh1V01hbXqZ3aAiHw2GrhIb1OlMUMIxHXhMOl4uA388Lr77Kyvw8Tl1n49YtTn/hC7bbVzLMXmYNiEaj7C8ucvkLXzBXDBoNlh4+pJRKMXruHJVymVAgQN/kJIs3byK5XMzeusW5554jGo3iURRWHz5k8tIlNFVFNgx2lpeZunyZeqVCuVRi5PRpNmZnCcXjIEl0xOMs379PLp0GXad3ZASn00m9WiV7eMjFX/mVT/17+Ekhy7Jt0picnKRSqZBKpewxrNvtxuPxkM/nOXPmDLFY7CeGUD9pMmgZggKBAIODg7b7OZ1OMzMzg6ZptjoYi8XsNzzWsX0aBdAaRbdHwG18FmgTwDaeatgVYw4H9Xr9U/+82+3G73CgimiMRrNJrlhEURROTk/jcjjsXD6Jlho2oFapcPM73+E/+lt/C38wiA44gaal7smynQfYUFVkoSwCNsGxXLJ9o6Ms3L5Nd3+/TS4qpRJzt2+zv7vLqcuXGRwZMT9frbK+vIw/EKB/YMDsjRX3Ge3sZP7WLTtGA8wLS7SjA0WWyaZSbGxtEfD7iUYi+AMBPB6PObLEVAI9gQClQsE+R+lUihs/+AGNcplkMknP8DDjJ06gOJ32CNlyJCuyjNfjOd4Hs9RPHlX0LEVUlmVTeRVGE0PsbVkjSTuHz7oNEdcDx/t9tWrVHjMrskw4HKajowMJUx3J5/Ps7e5SbzQI+P1EIhG8Ho+Z3SfMJIVCgbW1NZKdneaOHvyQYri1vk73wIAdIq0KBa/Z8pxa+XyGYSAZBrvr6zz78su2MQSOVULr5y2FsqGqzN69y+SZM/j8fs5duUKxUOCtP/kTbnzrW5x66SU8oiPaUk8PNzboSCTwBYMoikL28BCXqnL62jVqjQbZbJb9gwP8Ph+Kz8f7f/InnHzmGTqiUZOoRCJ4/H4ye3vEkkkW79xhaHISWVFYvnOHoelpgoGAufspxqoul4tSoYDL48HldOILBlEbDVRVpVqpcO3ChU/9e/i48Pl8DAwMMDAwgKZpLCwssLu7i9Pp5P79+0SjURKJBPF43B71/yxCqFvxo9zP6XSavb09FhYW8Pv9dgA1fHoFsFQqtWNg2vhM0CaAbXwu8LgKIMDZ8XHmtrYIxGKsrq3hFRVSsiyjGmaEiNVbqwLVcpm7b79NrLubU6I9wVL9kCSboDgE4bEIZFPTcIrjtOrnwCQtgUiEaqViN1As3LlDMZNh6tIlYoODtpuxkM+zvr5OdzJJvLPT3O2z7su6D7ebRq2Gy+MxFTxJQvF68Xg89PX0UK5WyRcKZHM5tre2zLy9YJBoJGISDFlGVVU2lpZYnp0lnU4zeeYMJ86exeV0Ho+vhWHAJVQ+VVVNEid2zGxVEewIFmeLuqGKaButRe2UWi9+LWNySy2UDQNJPB8WEctnMoRjMTvuRRUXeIeimL3NPh9dyST1ep1KqUQ6m2VtcRFFltna3sahKOzu7zPQ308sGrXH96qq2juUiiyzvbrK9VdeMc+5ODZXS8i07cxWFJqqysLMDIPj48iKYqo6guBarwelhTA2VZXM0REYBvGuLvtxeP1+vvpX/gr/9l//a+bee4++sTFifX04ZJlauUx2b4/pZ54xd0OPjthZXGT6yhUUh4OIOMeGpnFweEhTVamWSjSBfC6Hx+PB7XLRPzbGzIcf0mg0UBwOwokEu2trBKNRQpEI9WaTWDLJ3uYmvSMjZnZjNkskHmfw5Em7dq1YKOB0OH6iA/izwtbWFgcHB1y+fJlQKES5XObo6OiHYmbi8TjhcBj47EKo/zK0up+HhoZoNpu2OrizswPAw4cPbXXwk1RbtkfAbXxWaBPANj4XeJwYGAsnp6b4k//9f8c/MkJfXx9qvU5dVY9JB0LVkyR21tZYuXeP09evE4nH2d/cZHthwVywF+THUsKMFjKoCHOJ1WkL2PExFnHo6u/ng7feQms2GTtzhrPPPIOm6xSrVSTDrFnb2dtjaGiIjo4O0+Uo9vusca4kScR7etjf3mZofNyMJWkxU6i6jsvppLuzk854HEM36+Ly+TyrKyvkMhlKqRTrCwsoHg8dfX1c/sIXCIVCAPao0yEujJbxAXE/GAYOpxNVVR8hfHYHcot6Z53fRwbBglhZPcfOltgcMC/MFuFSMMemqcNDkr29tkPZgt3oIZmNJW63G4/bTUc0Smpzk6HpaXK5HPV6HVmSqJTLyLJskn/ruRfK3dH+PmGhmlmjXOtxOa2IHSv7UFVp1Osc7e1x/ZVXzO8Xr02HiOSxuqvtfD9NY/buXa48/7z9fFrnT9V1vvzVr/Lt73yHWqXC4s2bDJ05w8bDhwycPIlmGDSLRXYWFpi6fNnscBYqpAGUymWT+JVKXP/qV8ns7VHz+8nl8+Y42e3GEwox/+GHvPCLv0ilXCazt8fkpUv2cxLr6mLu1i36RkeplEo4nE4MXccbCNgdy5m9PXp6e3/mNWqGYbC6usrW1hYXL160X6vWGNaKmbGMJPfu3cMwDDtm5rMIof6kcDqddHV10dXVRS6X4/79+/j9fnZ2dpifnycQCNhkMBQK/dC5tfYN2wSwjc8CbQLYxucCjxMDA+Z4dHNzk9L+PqdffpmOcJjtvT27ecMwzPw7VdOYff99NE3juTfeQHI4kIDegQEWb91i4sKF4zGxMHrIIiTaIZmNG617b1bThkOMhQ93dthaXiafTvP1/+Q/MW9DHIMiSaRzOWTDYGJyEp/Xa4dJq8I1rFgXBsOgb2CAO++/T+/IiB2LgTguGVA5VqsURcHr8XC4tUVmcxNPMMjQ9DRNw6BpGHSGQtSbTZrNJl632zQvqOqjeXotpE43DNwuF8bHVDGL2FmwMvys43N8jMBbRhnrfFr4eKuHJEmUslkip0/bXzcMwxy3t+zlKS0XzqaqYmhm17OuaUxOTpqqVqHA3t4emxsb+Px+wqGQXQW2urDA6UuXjsfaHNfKqeJ5QpJwOhyg6zycmWH85En7NQEtI2JxriThLm5oGsvz8/SLjl5H62tDPNZgKMTE0BD7tRrhri4++ta3SA4N4Q0EqBYKrD18yIkrV5AUxawOxFRk87kcxUKBWibD6JkzRGMxsjs7hAIBepJJarUaxWKRvbU1mobBxsYGmc1NJoXaW2808Lhc1BoNsze4WmVjfh7Z4SAaj5utLOIYs0dHvPTCC5/wN+/JwDAMlpeX2d3d5dKlS38pEXI6nSSTSZLJJIZhUCgUSKVSbG1tMTs7SygUIhaLkUgkfmzMDHx26qCVWzg8PMzw8DCNRoN0Ok1aRC5JkvTI7qDT6aRWq6Hr+mdCAP+H/+F/4E/+5E+4e/cuLpeLXC73E3/GMAz+/t//+/yzf/bPyOVyXL9+nf/1f/1fGR8ff+LH18ZnjzYBbOOphkVuHmcEXKvVuH37NpIk8cuvvcbi4SEh4dCThBKAJFEuFLjz1lsMnThB3/i4uXMIqIaBBiT6+tjf3KR/eNjcXRNuYstB20rCLPOCFfBcLBR4cOMGLreb66+/zt133qFereLz+1FkmXq9TloEU09OT+N2Om0XbetOoSEy3pq6jux2U69WH8nZs2JgdI6DpDOHh6zPz6M2GvSNjfHc66+jqirr6+tmn20wSEckQiGXY3d7G4/XSzgcJhoO43S7bXKjWIqTGAkjy4+MgCWwSYIVNIwhomrEebAiVtwiLqNV52ht+8ByLwtFxhAXZ5fTabqZhWlDEcqqbjl1OR7Nbq6t0ZQkiuUy01NTJmnCrC3r7u5GbTbJCeK0v7eHrqrk83nzdoXhA46X9q0OXjDjcMrFIqVCgVMi4sUi/tbP2YHTYvRbKhTIHB5y7aWX7NYXK+xYMwxcTieqpnHq7FlW//APCQ8O0pFMomka6w8eUC4WGb90CVmM5x3iOLLpNJVqFVlVCUWjRKJRdKBvfJyDtTW8J0/icrko7u8zfeECuq6zOjODNxzmMJMhnc/j9XoJB4M4XS4isRi7q6vouk6ssxNDqLO6rpNNpVBVlWeuXPlUv4M/DQzDYHFxkYODAy5duvSJjRCSJBEOhwmHw4yOjpq/Y6KveHNzE1mWbWUwGo0+EkLdOjIGbGXwSaiDHw+BdrlcdjairusUi0VSqRSbm5vMzc3xb/7Nv8Hn89nu5yeNRqPBr/3ar3Ht2jX++T//55/oZ/7hP/yH/ON//I/5l//yXzI8PMx/+9/+t7z22mvMzs6au8ZtfK7QJoBtfC7waWNgstksd+7cobOzkxMnTlCr1fjg//g/6BkbwyXLFMUFfXd1lZX797n0xS/iFcqAS1z4LFVr7ORJPvrud+kW8ReqblbHVTCz7TSOg581odZpmsbyvXuk9vY4d+0afhFi3D85yc7iImPnzpEvFtlYW8PhcOD3eEwFzni0zUMyzOiOpqqarR6CUEUSCfLpNLHOzuP7NAw0VWVzdZXN5WVCsRjTFy7gE+pBrVZjdWUFn8/HxYsXWbh/n3giQTyRMEd82SyFQoHFgwMcTifhcJhQKITX5zNjdAQhtUbA1ijcetx2NApiJG6peeI5qYm9RSvX0SaBYszd6ox2jqAyvgAA1l9JREFUin3HUqFghxxbF89HyGMLYdMNg6aqcufDD5k4e5bx8XFkkSFnGTN0Q3QVx+N0dXVRazR4Xzy3KysrJnkIheiIRAiFQuaIWKwLWGaR2Xv3mD571ia9mq7b1X2KIH1WDI9qGDz46CPOXL5sHrsY21rmI0WWaTSbSJiE4PLFi/z+7/8+V37hF6iWSjx4+226hobwuFzomN3ANVXl4PAQXVUJ+Xzs7O5y4upV8741jUBHB9tLS9RrNYrptL02UCkUKB4dcemll3C7XFQrFcrlMvsHB6biWq+zfOcOXX19TJ86xdbiIojX9aYwM5wVodqfNQzDYG5ujnQ6zaVLl34qAuR2u+np6aGnp8eOmUmlUqysrPDgwQMikYhNCP1+/yNk0CLA8NOPin9cBqAszE2tpHVpaYlvfvObZLNZJiYm+MpXvsLrr7/Oa6+9Zo/Bfxr8g3/wDwD4F//iX3yi7zcMg3/0j/4Rf+/v/T2+/vWvA/A7v/M7dHV18c1vfpNvfOMbP/UxtfGzRZsAtvG5wKdRALe2tpifn2dycpL+/n4z3Nbno9Pno1kuowtFaub992k0Gjz7xhsoDocd22K5gEHswnm9OJxOSvk84UjEJhxW3ZgMdrg0wP72NnM3bzI4Ocmzr79uZwMqkkRPfz/v3L1LdHCQzc1Nkl1dOGSZQqlkdvhaqpqlKoqLui6URstV2zM4yM7aGh2JBGDGqyw8eED24IC+0VGeefVVM0AXk4CVikU2NzZIxGJmALRhUC2X7cfpdDjojMdJJhKommbvDW6ur9PUdYLBIPFoFL/fj8ftRhcKoCZG1I+0iYjzaP1rRaKojQYej8f+PktVswKVpR9BGtOHh3TE4+Z+YaNBtVql0WigNptoqopkGNQbDQzDzAvc2Nggn8ng93g43NlBVhQcDofZ++xy2TlyhjivaqOBQ1E4ffYssiRRKBbJFwps7+5SW10lHArhDwRIxGJIikIunUZRFMJidGyRQ3tvUez/WX2+q0tLJJJJAsGgqVCK2B1DnDdJPG6noph1aQcH9Pf0kN7bo3B4yDNf+xqFgwMWxBpCVdfZ39/HKcvEEgmWb91i9Px5u9oOTMKWHBpiQ0SSnLh8GU1VWZuZYeLiRQqpFB1dXQR8Prv7tlarsTo7S6lYpNvtJpPJkM/nqdfrOBSFvc1NEsnkz6ST1jAMZmZmyOVyXL58+YkqS60xMxMTE1SrVTtmZmVlBbfbbZPBjo4O+zX542JmrI9/ErSWHNCfBLfbzf+fvfcOkuOwr/w/3ZNz2JxzXmAXi5wBEiQlUaJIyzrZls6S7ZMcZZ/lK8v2+SdX6XynU+l3tu9s+SfbJZ11Jduy0ikyiQQJEhlYbM455zBxJ3X3748OWJCURIJBhDyvigViMTvb3TOz8+Z9v++9j33sYxw/fpwHHniAf/mXf+HJJ5/k05/+NIFAgHPnzt3dBXgdmJqaYnl5+Y6f7fP5OHz4MFeuXMkSwHsQWQKYxdsaRl3aq9gBlGWZoaEhlpeX2b9/P8Fg8I5/P33wIN/r68NTUkL/889z6PRpyhsaAK2Rg9sRMCaNbOlv7NV79zLZ18ee48dVx68+7kTNDLSYTKQSCfqvXAHgxLvehag5e2VNgUrLsrq/ZbPRc+MGh44exe31srG2ZhAfWVPVJFlGUhR1v1Bz3+qVcRlZJpCXx+DNm0S2txnr6yO9s0NlUxPNWkSHvoMnCgKhzU2mZmcpLS2lQCN4uw0aZi24OCNJSKiETFcjTIJANBYjEg6zsrxMVMsk29zaIpFMYrPZjBGw/nN144q8y6iQ1vL7LNqbuQhGhVtGU/p2YjHCoRA7sRjJeJxkIsH02BgFpaUszs5itVoxW63YbDZEsxmz5r4VNXK5uLSEkkrR0NKi5u+lUqSSSRRZJplMkkqlSGs7VTq5XllcpLCkhKW5OfyBAC5tN1CSZVKpFNvb20YYs9liYby/n2P33We0piioamVGM3SkteiXlCQRi0RYnptTb7/r34xKPrPZ2CVNZzIszM4iyzLveM97+Oq//At7zp3DbLGQW1oKosjQjRu4Cgtx2u0EgkGm+vooqq1VCbksI4giNlEkmU7j9HiYHBzk7M//PJKiMD86SkF5OYG8PMa7uwkWFBh7q/pYORGJ4PV6aW5vV8l0Os3s/DzbS0skkknKtdBls/nNe9uQZZn+/n6i0SgHDx58XY0jrwYOh4OysjLKysqQJInNzU3W19cZGhoilUoRDAYNQuhwOF5XzMzd9ABHo1Hcbjdnzpzh7NmzfPazn70jfP2txPLyMgAFWq2gjoKCAuPfsri3kCWAWdwT0F3AL1OaNCSTSbq7u5EkiWPHjr1iNVNVVRXh736X8aEhSpubKW9sxISqmOzu4NVNHboaZxIE8goKGLp+nXQqhcVqVd2v2i6gLMvMTE4y2d9P04ED5BUXqwRIiyrJSJKagyfLTE9P4wkGia+t4fJ6VYVO2/kza0RC1P5UFIU0WgSNZhoxa9mD2+vrzE5MgCDQeuiQ6mDVzlMfY2cUhbn5ecJbW1RXV9/OEhMELKKIw+UiGo3icrsNVy7a+ex2HzscDhwOB8VaxEw4FCIeizE0NKSSEZ8Pr8+H3eFQ9/Q0k8bLRsA7O9jsduYmJoiFw4S2ttQaL8Dp8eDxerE7nQTz8nC6XFhtNhTg2P33G8ctgEG09LHx9vY287Oz7GlvZ6K/n/3Hj2PWdinZdXt9hKtn8yUSCS4+/TSVdXXEIxFWFheJR6OgKLi8XnLz8vDn5almilSKwd5evIEAC4uLrCwv43K7yQkEcGuRQvqHBYtG6Hpv3GDP/v13GGJ0c5BJv72iYDGbCUejRp+w1WKhubmZnXAYj/YhJqewkIX5edanpmg/fpyV2VlsDgf5miKXSqfVMbQso0gSY11dNB04wPbqKharFUmWCRYVqSN7TU0XTCbsZjPJdJrx/n4URaGsthZJkvD7fAT9fmqrqniutxdvTg45fj/PP/88gUDAyN57I3fTZFmmt7eXnZ0dDhw48KoiUt5ImEyml7V9rK+vs7KywsjIiLGPl5ubi9/vN4751cbM3A0BjMViL9t9/HEu7D/6oz/is5/97I+9z6GhIRrfolF+Fm9vZAlgFvcETBqheCUCGAqF6OrqIhAI0Nra+iN/yQqCwIl9+7i2vo7gchndp4aDF7Bqzt7d+XtpzW1a1dKiujEPHFAjWUSR5M4O159+Gk8gwKn3vOcOZU1X/RAEdhIJpiYmMIkie9rbufX88+zE49j1VgzNjQwYPcU6IdTbMgDWlpYY6enB5nRy8L77QJbx5+QAt7MC9TiW8clJEokEdfX1alOFdmyKLJNWFDyBAKGNDVz6jp22z6e3etzhPgbQHMCFBQUUFhWxp7WVcCSiumvHxzEJAh6vV1UPvV4ioRDrq6uENzeJhkLMTkxQ1dBAQVkZRRUV1La2YtmVO6grn7qimNEq3PRoFt2du9uhvLK8zOLiIuUVFTisVgRRxGK1vmKQsw6LNrqdGR+nrrWVwpISRC1Kx6ztW8YiEdZXVhju7SURi2Gx2ViYmeGd73sfdoeDSCRCOBxmfmGBRDJJwOfD5fGQGwiQASbHxsjJz8fr9xvHYtbMKMAdTuNkKkXP9eu0HzqkrjooCvs6Onji6afxBIOkUikWFxcpq64mvrXFaFcXoiCo7R4vuR9BEJjo7aWouhpfTg79ly5htlppOHjQIHs5hYWsLyxQVFkJisLG8jI78TgFZWUIQCoeR3I4kGSZzbU1FEnC6XDwkV/6JRobG1lfX2dtbc2oQNtNiu7WKCFJEj09PaTTaQ4cOGDkYv60sLvtY3ee3/r6On19fapRRouZ2Z3n9+PUwddDAF9t9M4f/MEf8JGPfOTH3qZaC5x/rSjUusNXVlbuWAVYWVmhvb39ru4zi58usgQwi7c1do+AAaOpQMfi4iIDAwPU1tZSWVn5E39RHj96lBf+/u+xaj2wu5U+FIWUHjOiLfErqIv7AOXV1TzX20vN3r2YLRZmx8eZ6Ozk3GOPUVRWhoKaXae7eNHGhLFYjJnJSTweDyVlZYiCQEVjI7NDQzQfOKC6WHeNgEVFue34FUWV6MzPM9HXh9Pjoe3ECRwOB5l0mhvPPUf9nj2qgqeo0Skpre9WEEXq6+uxWyzGSJldBNqfk8P64iIVVVXGLt/uHmOdBAuiqDpzuW16QDNTBAIBcoNBkqkUC7OzzI6NsTQ3RzqdJpiXR1FZGVUNDXh8Pqx2O3sPH8Zms6mmlV0jyJc95opCaH2dQE4OZrNZVUFv3wBZlpmfn2d9Y4Om+nrsTifjQ0OUVFSoJEQjzrtjWvTcPV2xWZ6f58QDDxjkTwEjesbn9+P2eqnRImRuXrpEcXk5PdeuoSgK+SUlVFRVUVJSojpyt7bY3t5mYX4eWZJYmpzk5EMP3XYEo5EDzfVr5DZKEv1dXZRVVeH2eo1dV7fbTXlREctzc+xkMvh9PnKCQWIOB8M3btB+4oRRn6e70RVgZnCQnPx8cgoLyaTTqgnpzBnsWnSPyWTCHQwyMzhIUUUFyWSSudFRrDYbJVVVbK2ukojHCeTlIYoio93d1O/dy5ymGu1u5shkMkb23ktJkZ6992ogSZKh3nd0dPzUyd8rYXee30tjZgYGBvB6vcZ5e73eOzIHdXUwkUgYk4xXGzPzSgrgj4OuYL4ZqKqqorCwkGeffdYgfOFwmGvXrvGbv/mbb8rPzOLNRZYAZnFPQP9lqY9ZZFlmdHSU+fl52tvbX/UvPavVSmt5OVeXl6GtTc2o00bAunpnE0XSu9y4OqnLyDLljY2M9vQQ297G4XKx59Qp/Lm5gKr47XbxSrJMeGuLqelpCouK1N0ZjYCVlJcz1t1NrWam0ImoIsukJAmr2Ywiy2ysrjLa1YVLJ35OpzHKtGpKlz5aFQQ17Hhyagq/10tFWZmRCbhbQdOJUTA3l4n+/jv2HiXt+EyaCUUnfBluR2KASqZCm5usLC6ytbyMJMsEcnOpa2ri8MmTCMC6ZiSYmpnB6XSyrvUvK4oa3WLSiKUsisZunJ4LmJEkVpeXyS0oMJRAvT4ulckwOzNDNBajtrYWh9OJJEkszc1x5MwZdXSum2Y0RdOyS4WTZJmpsTFK9Q5fQTCUGZ0A6tdKlmUi4TBSOs3hM2cwm83sxOOszM9z4+JFRFGksq6OvKIiSoqKiO3s8PwTT1DZ3Mz09DSzmioa8PtxulzYrVbSmYwxYp+fmUGSJMqqqgyyqI+Jy6uquPaNb9B84gT+QIBUKsVkdzdH3vlOpgYG8ObkYHM4DKV2ZXISs8VCTkkJiiwz3tND3b59xLe3SeXmIppMiIqCxWZTsx4lifHeXhRJoqG93Wj8iIbDyJLETixGZHub3JIStmdnXzbuNZvNr0iKZmdnjew9fVTsdrtf8cNZJpOhq6sLQRDo6Oh4U/cL3yi8NGYmlUoZRhI9Zual6uD8/Dzr6+vs3bv3Ne0ORqPRN60HeHZ2ls3NTWZnZw0SDlBbW2vkDjY2NvKZz3yGxx57DEEQ+I//8T/y53/+59TV1RkxMMXFxTz66KNvyjFm8ebi7f9qyyIL1F+U+qfnVCpFT08PiUSCo0ePvuZfkKePHePx//f/RXnwQbXHV1PadKOFntMGtwOGdVJnczp56itf4dGPfYyC0lJ6e3sRtO8zQpE1rC4vs7K8TEVVFX6fDwWwae5QCSiqqmJhaopgQYGRSyhpo+WtzU0Gb9zAarfTduwYXp/PUJJ0JSstSeSXl7MwPU11YyObW1sszM1RWFBATl4egsmEoH2PwO2MQl0pFE0mpF3ROrobVSdiLz2fVCrF0twcqwsLDPX04Pb5yCsupq6p6XZun3bdLCaTOirWCFwkHGZgZ4eJsTFMZjMerxe/34/P7TZIp7EzqP0Z2tykrqUFwIhWkTIZJicmQJZpqK/HomXoRcNhHE4nJrNZfQy1qBlJGwMb1w6V1C1MTxu1b7o5Q1AUw7Vs1mJqJFlm4NYtWrQgcCmTwWK1Ul5TQ2l1NZlkkrHhYUb6+ykuLyeZTFLX1ERlbS2iKBKJRIhGIiwtLZFIJHC63fi0MXlyZ4fpsTGOnj1rPJ76B41wKMTK0hLNDQ0o6bSa39jfT1F1NU6vl5q2NiZ6e2k5dAhJllmZnSWZSFDZ0oKsKKxNT+PyeimuqWH42jVVndaVUVnGbLMxPzHB9tYW1U1N2Ox21TRksSClUqopZWqK9mPHWJ6e5vD+/T/2NfVSUpRIJAxSNDk5idVqvSN7z6S5nm/duoXFYqGtre01j0ffLrBarXfEzIRCIdbX15mamqK/vx+Hw8HOzg7Nzc3k5OS8phDqN7MF5FOf+hRf/vKXjb/v27cPgOeee44zZ84AMDIyomZkavjDP/xDYrEYH/vYx9je3ubEiRM8+eST2QzAexRZApjF2xq7VQOz2UwkEuHWrVt4PB6OHj16V4qB1+ul1O1ma2mJoLbLInK7Fgzu7N7VA4n7r10jubPD/f/u3xHe3KSgtNQgTLvJkgkYn5wkFo9T29CA2+G4vZu3a4+xsqGBq089hS8vj2Q6zeLyMhaTienBQaR0mj2HD+PUjBv69+hqpX5diisquPn883hzc1laXKSqqgr3ruJ4BU2Z1MbZuzuKAUwWC0omg8liUZ2z+k6Z9ga0E4+zMjPD8sICApBbXExjWxvJnR32aj3JxjgXVcXTyZNJG7eazWYCwSD5hYU0t7YSiUQIbW8zNTWFSRBwud0E/H7VjKIpdPobo81qVVU8IJ1MMjk5idlsprq21ohcUWSZhclJKmtrjV5ni9aYYeQUaued0YKiiysqjL1SuN35qxN5UTuGhdlZPF4vwWDQ2J3U1URREDBZrTS1tyNnMgx0dXH94kVOnDunRgMpCl6vF7fbTUFREZlkUo2ZCYWYnZ1lvL+fA8ePk0mnyWiRPSKwsr7O6tIS1TU11NfX8/2nniK8tYXD5SJQWIigKCqRzM1laW4OURTZ3tigaf9+dW9vZYVIOExVaytmUcTmdpOOxxGcTqxmszqGtlqZ6OmhtLaWotJSUrKMzWzGYjar+26Li6STScpra7n5zDO861d+5TW9xux2O6WlpZSWliJJEltbW6yvrzM8PEwqlcLv9xvjzXZNffxZgCiKBAIBAoEAdXV1TE9PMz4+jtfrZWhoiImJiTuIsFnLqfxRIdSRSORNUwD/8R//8SdmAL7SesanP/1pPv3pT78px5TFW4ssAczinoGiKPT391NVVUVtbe2rXox+KUwmE+0tLQx2dREsKlJbLuCOwFe4PQ6MhkJ0Pfcclc3NlNXVIcsyF7/zHeqam408ObPm0pXSaYbGxjCJIo2NjcaIMaXdt6KphYIgoJjNeIJBYqEQ+Xl59F67xvriItV79lBWW6s2P6CRU7Sg411EMK0oOGw2NjY2sM/OUt/YiMflMmJG0HYJM9p+mH61dJevSRDwBgKsr66SV1SEoCkwiZ0dlqanWZqbw2yxUFpRwf6TJ7FojQm7l9pFUTSIGIoaiq2rmJJGkvQGD1H7vqDfj9fjoVwUScTjqtq1vEwikcCtuYEVScLj8xmNKNFYjOnJSVxuN2Wlpar7Wrvu6UyG9dVVGtraAO7IcVQUBVEUUbTxsaIozI6Pc+qBB1QDinasKV1h1N98BYFUJsPE8DDH7rvP2I/Ux/Q6wRMENSA6IctsbWzwSx/9KBsrK1x4+mkqamupqKkxGlIEm40Ch4P8/HwuP/cc+w4exGw2Mzo2hiAIBHw+Iz6msrraGJtaJYmNlRWajx1TiZJ2jPkVFdzUDEi6ISQeDrM8PU3DgQNYLRbSmQz5xcWsLS5S3tCgmlBkmcWpKQBq9+xB0ZTfjCQhaNeq69IlavfuVT84JJPU1tbe1WtNf73ppKehoYGtrS16e3sBNbD92rVrxqjY5/Pd9ev67YbFxUUmJyfp6OggGAzeQYRHRkZIJpPqDm1uLnl5eS+LmZFlmSeeeOKeGItncW8i+8zK4m0PvQ80lUpRVVX1unsnRVHE4XDQWFzMxsICuSUlRoUamhkig+oWnRwZYWZoiI777sPn86ktICYT1a2tDPf2Imi/tEVgOxJhcnISr9dLTUWFEeeS1AiXbi7RswNlWaaquZnnvvUt/MEgTa2tlDz8MNuhENuhEKNjY1hNJpweD36/H7/HY7RPCFoczPDUFO7cXFxWKy5tR8sqCCQ1VVL/uQK3VU1JcyanZRl/bi5bGxv4c3OZHh1laXYWk8lEWVUVh86exazl7enKqK7UWMxmlEwGtIgR3dBhvHnv/lNRkFIpbE4nFo38ZrRdQLvDgV2LmInG48SjUTa2thgbHMTt8bC0vIzdamVufp6iggJy8/ONPT5QSfr66iqBvLw7iIMR/aJHnmjq7tzUFEVlZSCKSFq+okU7J6vJhE4dM5LEcG8vtU1NmDXThn7d9eYPPacxlcnQ19lJfUsLDqeTsupqisrKmBod5dKzz9J+8CAur1dtBpEkRgYHCebkUNfcrMbBZDKkEgmmZ2ZIp1LqSHd5mYTPh5xOYzeb8Xg8qrqpPaZpSWJLi3hxeDyYzWZSiQQzg4PUtLer+YyaEcbp87EwPg6aAj3R14csSRRVVGDWDBeZTEbNJRQENldWkCWJipoalmZm6NB2Zd8IJJNJhoaGyM3Npbm5GUmSjFGxvguok0W9D/dexNLSEsPDw7S1tRl5pLuJsKIoxOPxlzmqXS4Xc3Nz3HffffzZn/0Z6+vrfOUrX/kpn00WP6vIEsAs3tbQl8QjWkitZ9d4826h7xOe2r+fL/7f/0uwuPi2uUH7T5Ikul94AVEUOfqud6njTEXrCJZlSmprufjd7xKoqkJUFJY3NpifmaGgqIiC/HzQRokKt8ORdeIjacrcxtoagzduoMgyLUeOENSMLHnBIHk5OaQyGZLxOOtbW8zOzjIjSfi9Xtw+HzabjdnpaSw2G0dOnKD74kXMe/eq+Xi7ataMvS/t7y81fKRTKW5euMDG0hKFFRUcOHUKiz521RVRbhtHZD0exmolmUrheonTU9FIh6iNShHUWrxINIrNbictq13KutlD/xmSomC323G7XARzc9mcn6e8oYFQKMTqzg4ms5l0JsNOLIbX6zVUVFlRmJ+cpGHPHqN+zqSZSnaTFr1ybXZ8nKP332+QWlEU1ZE6kNJaPURBILS1RTwapf3gQQTUKBm9E9ikkT6dhC/NzqqGiJISw2xjt9mobW6morqaW9eu4Q8GqW9pYWVpifDWFgeOHTPq6cyiyIxWx9bY1ASKwnYoxNLCAj03btB++DBbAwNEQiGcbjcysLW8zObiIm1nzzJx8yaJWIzxnh5q9uzB5XSSTqfV/VVNAdXDpjdWVliZn6euvZ3t5WXVTGQ2384xlCRmRkfZc/QoDo+H8Z4ePv6nf/q6X3MAOzs73Lx5k5ycHJqamgwleXcfrr4/Nzk5SX9/P36//47MwXtBHVxaWmJoaIi2tjZytIiml0IQBFwuFy6Xi4qKCsNRfeXKFX7nd36HRCKBIAj8P//P/0Nzc/NbfAZZ/FtBlgBm8baGIAjY7XZaW1vp6+t7TX3APw4mkwmr1cqx1lYGx8aobmggrSl08UiEzvPnqWppobK2Vs38044FQQDt780HDnDt4kVsdjuxWIzq6mqCXi8ZbVyo75NZNLVNV+MSOzsM3rhBJpVi/5kzpJJJxnt6CJw+rZImMMiJw+2mzO2msqyMSCxGNBxmaXGRZCqFw2Yj4PNhtVgQRJFYPI7NbjdGwPp9ybJ8W+EEdmIxZkZHWV9aIlhQQEFpKUcfeEC9LuLtFhJdrQPucBDrETCZdPq2uqjdNq3HybArokQQSMTj2PRw7l1v4qK2o7c7qkUA0qmUalJJp6moqsIkimxvbzM5PY0sy3i8XnL8fqw2GzuxGE632yAxukta1MinTjQXZ2cpKS/HZrUasTv642o8ViYTqXSa/s5O2g8fNvqJ9b1GAdRoHFQSHY5GmRwd5eiZM1i1nD/TrpGyxW7n4MmTzE9Ncf6JJxAUhVMPPYRZ6wIWBYEJPa+xrk59XmqP23B3N+9+3/sQBIGdaJSu7m5yy8tJhEKkw2EaDx3CYjaTV1HB9aefZs+JE2q4uHZu+uhbUBScXi8rc3NMDw5SUVdHYVkZG0tLWLVMRP0DSufly+QWFak5lmYzpkyG+vr61/16i8VidHZ2kp+fT0NDwysSuZfuz+k1bWtra4yPj2Oz2QwyGAgE3pZ7g8vLywwNDbF3794fSf5eCbqj+r3vfS89PT1861vf4p3vfCff+c53+NM//VPOnTvHk08++SYeeRb/FpElgFm8rWE2m2lpaVGVndfQB/yToN/XsUOHuP6lL7FTVYXZYmFpdpaxmzdpP30aTyCgKjSgkjqNnKCRI39BAdHtbTZWV2nv6MClmT3Qc980xVBX3RRZZnp4mOnhYRo6OigpK0NSFBwuF5lMhkQshqAtfOtqm0UjHmlJwul0kk4mSafTlBYXI4oi6xsbzM7NkQR6btxgz4EDuJ1OTLsUSF3NW5ydZXpkRDWg1NfToI32IltbpNNpI29P1MankqKgyHcW2Otv21aLBXSDDBgmCx0vLatK7OwYfbigRcpwe19QHwkDRMNh4skka6ur1NfVYbXZMIsiHo+HiooKotEo4VCIhaUlZicmsNvtrKysEAgEsFqtxs82acRP3+ebHBnhuNYqokfK6ERdd/+mMhmmxsbILy7G9RIzjdHjq5lLEqkU3deu0XboEBar1TAM6Qqzvk5gNZspLC1lqLcXk8lENBTCFAyiKApjExMoQEtjI7K2i5dIpbhx8SLN2vhQVhQ6Dh1ifmkJJZkktrlJsKKCubk5HHY7S+PjmC0W/Lm5KlkVRbWLOJPBarEgpdM4vF5uPvMMpbW1VDQ2GiP9ZDqNzWwmlU4TD4dZmp6m5fBhEtEoIz09vOvBB+/m5XUHotEonZ2dFBcXv6bd3ZfWtOmZg/39/UiSRE5ODnl5eeTk5LzplXGvBisrKwwMDNDW1kauFg31WqAoCp/97Gf50pe+xPnz59mzZw8Aa2trjIyMvNGHm0UWWQKYxb0DPQbmjbovvdf03adP8/itW4h2O5tLSxx517swaw0V1l1jSsBQSqKJBJOTk5S3tLA9O4vj2DGVIO4yaWRkrftXUYiGQvRcvEggL48TDz+sEgRBUPe0BIG6vXsZ6e6m/fhx9fgEwSBGegDz0vIym2tr1NbU4NKiIfLz8kikUmxtbnL5ySexeb1YLBaCWpCxzWZjcXycuakpgvn5dBw7ZvTx6o0b3mCQ2PY2gfx8w/msn6uk3A7GFkXxtvnBZCKRTOLj5dVUujomal3JAIl4nGBu7h2uap1YioKAhErYMpkMPbduYbHbqauvV3tudSeiNp51OZ143W6KiopYn52ltqWFnXic5aUlbHY7Xi1mxel0GuR5ZmJCdf5qrku0CA5FUdQqPk3li4XDLM3OclILiM7sGv0aDmFBICnLDPf0UFlTg9vrva0oamRbP39Blkml03RevsyB48fx+f3cuHSJorIykpkMJrOZ+poaFE2FTKbT3Lx0icq6OvILC1G0Y7RaLBTk5DCxsED7iROYzWYyqRQDN29istmwer0MdHdTWFZGwOsFQTAcpgDTAwNk0mka9u27HaitkdOMpHZZX//hD2k6eBA5ncbhcjE/PMz7/+t/fV2vs0gkQmdnJ2VlZVRXV78u41Z+fj75+fkoikIkEnlZELOuDno8nrd8VLy6ukp/fz979+69a/L3l3/5l3z+85/n2WefNcgfvLnhzln820aWAGZxz8BsNr/hCiBAQ3093//hD4l4PBx68EGDwOmBwqCOOHWlKxaLMTE+js/nw11Sws7GBoszMxRVVKCgmjB0128yk2Gyt5eVuTlajx4lkJNjtE6IYESzBPPzGe3uJhGP43a774iVkWSZ+ZkZ4js71NTX43E678i1c9hsWPLzKa2ooLqyEgnYXFnhxosvEt3epqapiebDh/H7/dg0Z6iiv/nLapXc2uoq/rw8tS1k9zXXnLOSoiBrREEQBMwWC5l0Wr3RrugXRcvUM+rsdGdxPI7d6TTIlwHtjdpsMpFJp5manGRrbY373/lOnNo4G27Xuel1ebKiEA6FcLpcFBUWGjt+8WiUre1tZqamQBDUnUmPh7nJSU4/9JD6IUIj/hmtGUNXzTKZDP2dnbR0dKg/M5NRFUuN1Ge0sHBFUVianyeRTNJUUWHsNOr9vkamn+bo7Lt5k9KKCnLy8xGAtkOHeOq736WwtJTjJ0+qu6WCmjHYc+MGhcXFFJeVGaYTq3b+e9vbWdf2IRVFYWlqCn8wSEV9PfF4nJHOTpBlZufnMQkCDs1UMNXXRzKRoLyuDpvNZgSDA0iZDGazmd6rV/Hn5+PyeAitrZFKpWhpbHxdGXShUIhbt25RWVlJVVXVXd/PSyEIAl6vF6/XS3V1Nclkko2NDdbW1piensZsNt9hJHmz8wVXV1fp6+tjz549d0XUFEXhb/7mb/gf/+N/8PTTT2dr1bJ4y5AlgFm87aGHBOvhsW8EdhNAQRD4tQ9+kL/75jfVf9OULwOKYrhn9eT8suJicnNzmZmfp2rPHsa6uykuLwdNHRIFgdDmJt2XLlFUXs7Rd77zjrBpWSOXoraorwCN7e0Md3fTfuwYoJLORCrF9OQkAlBTV6eqURqBtGq9tbJGokprahjV4jXSiQSHjx/H4fUSjkRYWl5mbm4Or8dD0O/H5fGgaJlwwfx85icntVNVdwd1V+9uoqkrhgB2m81w16LdTjdf6PezG8lEApc2mtavpaSZLiRZZieZZHpyEqu21+h0u438Pn0vUf9TH2nPjI1RXltr/Hyz2Yzb68Xj8yHLMvF4nND2NlcvX0aRZSY0h7bP58MkikYHs4xKKOdnZnC4XGq3snZeeoi0xWQCjQyHw2Emh4Y4evasEbWi9/yK2v6fSVMPRwYHsdrtVNbUgCAQiUSYmZ5m//HjrM3OMjM1RVV1NWlJYrCnB7fHQ3ltrXGOFrOZVCaDxWzG5fEgJpMgy8xNTJDJZKhtbiajKNjsduwWC36/n5zcXKRkklA0Sv/16yxNTtJ68iSRpSVi8Thel4uE1hssms2sLC6yODnJg+9/P1OjoyQTCdYXF/nM5z9/16+vra0turu7qampoby8/K7v59XAZrPdEcSsR62Mjo4aUSu6OujQ91DfIKytrRnkLz8//zV/v6Io/MM//AOf+cxneOKJJzh48OAbenxZZPHjkCWAWdwzMJvN7OzsvCH39dJ9wkAgwKH6eibGxynWYmZMmstUr2pbWVpieXWVupoanG636nYVRQSzmermZgZv3aJJa0wY7+lheW6OtmPHcPt8hjHBYjIhS2onLNr9W0VRjWTJzyfR3U08GsXhdhPf2WFsfBy3201ZWZnhGtVjS9KaImUWRTbW1pgZHWXo1i3e+5GPEMjNNX6m2+2mvKSERDLJxuYmK2trxGdncbtceDwefD4f6WTSIC0ZjZDu3unTTR6CpuAJJhPJePzlih7c7lLeZZyA2+YJSXPQ6mpaVKuvCwQC+DweNt1uFEUhlU6zs7ODLKn9xsgy6XRajUHJZJgZHye/uJjQxgYIAk6HA9FsVlUuRSHg82G32ZgQRQ6cPs1OLMbG5ibLi4tY7XZygkGcLhdup5NEMsn0yAgnzp0zxvd6OPTuEXAqnab7+nX2HT2KzWYjlU4bqqJu8jFrAdhz09NEQyE6jhxBr+mbnpoimJNDaUkJJcXF3NRMRFvr6wDUNTcb+3sWzfls1f40mUyUl5Ux1NODIIrU7tmjfjiSJKwWC65AgHgkgi8YxOJ0srq0RHRtjVPvehcWh4PNhQVmp6Zwejx4XS6SqRSJnR26X3iBjtOnMZlMxCMRouEw5cXFlJWV3dVra3Nzk+7uburr6yktLb2r+7hb6DVsOTk51GvK6Pr6OisrK4yMjOB0Ou/IHHw9RpK1tTV6e3tpbW29a/L35S9/mU996lN8//vf5+jRo3d9LFlkcTfIEsAs7hm8GSaQ3Th9/Di9//t/s1NcjEMzY5gEgWQmw/TMDDvxOK0NDZi1HTrdKZtMpymtq+Py44+ztrjIaFcXuSUlHHvoIWRtZ9AYI2oZfHpwtAhGOwiCQF1bG6Pd3VTv3cv09DTFhYXkaGMlsyAgCWq2oB7xEdrcZKSrC5PFQvP+/WpMiDY+1tVGSRslWqxWCgsLKS0uJp5IEA2HCW9vs7S0xPLKCpNTU+Tm5eFxudSaKp3MaOYXXeVDEDBbrXfsY+pjUEVTT/WRsbhLFYTb+35SJkNoa4uVxUUmxsdx2u1ElpdZWVpSTRvxOKLZrBpALBbMFouxhwiwtrqKzeFga30dRZJIZzKkk0lSqdRtggmsLi4SyMtjc20Nn99PXV0dmUyGaCTC5vY2C4uLmE0m5sbHadyzB0FTP/XdOD0+RSfHvTdvqnt/Ho9RAaiP9BVuk9yt9XXmp6c5dPIkFrOZza0t5mZnKS4pIS83V1UNzWY6jh3ju//yLxSXl3P41CnDQWzR1F19tG0xm1VVVpbZmJ/nyMMPq8qnNspPpdP48/IIra/jDQZZW1pi6No12k+dIr+4mEQqRWlZGWa7HbfXy3Y4zNbWFue//W0COTk4vV4UIBYOszo/z+f+7u/u6nW1vr5Ob28vjY2NFBcX39V9vFF4adRKOp1mc3OTtbU1enp6UBTFGBXn5ua+psxB/TxbW1vVju/XCEVR+Kd/+ic++clP8t3vfpdTp0695vvIIovXiywBzOJtD32h+80mgCaTiQ88/DBffvJJ9j3wAGlNeZocH8diNtPc0IDZajW+z6wpgHqXbbCwkO988Ys89uu/ji8YRNEUMz0GxqIpfTrZU2QZade5KYpCXmEhty5eJDkwQH1jI8Fg0HAeJ3Y1a2xvbTF86xaiyUTzwYP4/X4ykkR5bS1Tg4MUFBYiSRKSpkrppFAfzdqtVqyaizKVTiPFYqyvrBAKh7GJIh6/H7fHg8vlUjMAtT0qozrNalUr5DSipe+V6WRRhyRJbG9ssL6yQt+NG8TCYWO0mVYU4okEDc3NlJWWYrbbuXXpEq379+P2eJB27ejpUS4mUW0Y2Vxb4+SDD+J0Oo24GV1h1d260ViMy+fP09zWxo4W1xILh5EVBZ/fTzA3l9L6emampjCZzURiMfp6e3FrwdtutxubxWLU/U1PTGC2WCiprATUMG+TyaSqwLviYrY2N+m7dYtjZ89it1pZWV9nYW6OkrIyNRpE0bIKtbFzYWmpkdun34ceJ6OTUFEQGBsdJZVMUlxUZKjHNu18RVHE5fUyPzbG9toat86fp+XYMfKLi42xvsVqRZFlXC4XToeDIW0sX7NnD2tra8zNzDAzNkZRURHVd7Gzp+/CtbS0UFhY+Jq//82GxWKhoKCAgoICFEUxMgenp6cZGBjA5/MZ6qDL5fqRRpKNjQ16e3tpaWm5a/L39a9/nU984hN885vf5OzZs6/31LLI4q6QJYBZ3DMwa5llbwR+FJksKipiX3k508PD+IuLmZycJNfno6CkxCAhll2kRxYEpFSKzvPnMVutHH7wQbbW1vDn5KgjYm4bGFKyjAWQNSXQYjIZhFAURZKZDAsLC3gLC0mHQuToDQIagRQ0Zaz35k3kTIaWAweMrmB9Py83L4++SIRkMonJbFbHmZqaZ9FMCtKuyBW9s7eytpaNpSVqW1pI7OywqYVPy5KkduEGAng9HrU7WAubTqXTBvnSkUwkWNfcypHtbRRZxmK1YrPZKK+pwRcIoADrq6ssraywr6YGh9OpVrpJEqlEAofTaSiF+luw3gcsAuFoFNFkwrargF5X4XTXdEaWGRsYoKW9nQJtN6x616h2a3OTzdVVbl68yGBPD0fvu4/q8nIUk4l4NMry8jKpVAqHw0FOMEg6lWJpdpZDp08b9XPGaFgjbFazmXAkQs/16xw4fhyrzcbSygrLy8uUV1QQDATUPmjttmNjY2ysrnLszBkW5+bo7+mhff9+Q/nT915lRWFkcJDNjQ32HTlC+vJldmIxPG43yXQaiyiq18ZkYicW4+Yzz9B0+DAl5eWkJQmbtutptlqJRSIgCEwMDhLZ2uKBD3wAj8eDIsvMTEywvb7O73/841y8eBG32204UH+Ss3Z5eZmBgYG73oV7qyEIgtqu4/dTW1tLIpEwMgcnJiawWq13ZA7qRpKNjQ16enpoamq6a5L77W9/m9/+7d/mX//1X3nooYfeyNPKIovXhCwBzOKewZutAOo4d+YM/+1//k/m1tZorK/Hn5Nj7OnpBhH9rTAaCnHruec4+Y53kFdSgiLLXH78ccoqKsBuN1pA9HHxbjVOJ4SSILCTSjE/M0MilWLfwYP0X77MxtoagdxcZEUhlUox2t1NZGuLpo4O/FrUhN6Goe/spbWKr8XZWcqqq9VAX63tYrexQSezehCyLyeH8b4+RFHE7XbjdLkoLikhnUwS3t5mdWWFqakp3G43Pp8Pm9VKJpUinUqxsrLC8sIC0XAYi9VKbkEBpVVVeLWw3vXlZbyrq/iCQQRFYXZ2llg0Sl1dHW6n03gc4tEoLo/HyNCzaNVsugJnNplQZJnZiQlq6uuxmM1q04Wmnpp1IiQIhMJhYuEw+R0dqslm13WXFYVAMIjX72dzfZ1HfvEXMYsiI4ODxCIR8ouLqauvJyPLxDQyeOvyZfYePszG2hp+vx+H3W6QP115jMbjdF66RNuhQ7jdbubm59na2KCyshKfz3eH6WhibIy1hQU6jh7FarFQXF7O4swM6+vrBHNy1PsURTKKwvjQEJFQiIPHjiEIAmXl5QxMT2Oz29Vz1/YAI6EQ493dHHn4YUqqql7WhmKxWkGW2VpdZWpggOqWFjxer7rbCQxcu0ZjczO//Au/QCqVMiraZmZmDGdtXl4ewWDwDmft4uKiUXt2NxEobwfY7XZKS0spLS1VFebNTdbX1xkaGiKdThMMBnE6nczNzdHc3ExRUdFd/Zzvf//7fOxjH+MrX/kK7373u9/gs8gii9eGLAHM4p7BG60AplKpl31d7x1uqayka24On7bAn5ZlzILadCEACALTQ0OMd3dTd/Cg2p6gxaPsPXaMWxcvcujcOUBVsUQwol30UakZdWcsoWUKWsxmmurrUUSRho4O+q5c4dC5c0yPjLA4OUlNaystBw8a5gQFldxlJMkwh6QlidLqarpefJHK2lpS8u2OXr3NQ0TdJ0xxO6Raj9jRx9M6sXE6ndhsNgoKC9lJJgltbzM/M8Pc5CQTfX2sra1RUV1NZUMDwZwcwz2s6PmFQDwWw651Js9MTSFJEvX19eoYeVfMy/L8PLmFhch6XZ5GbtHcv3pO3vrKCo1796IoirGXaJgw1AeRgVu3aGhrw2I2GxEtej5fRgufXpydxWK1UqA9drmFhWQyGVYWFrhx8SIWm43qhga2V1Z48D3vwWG3s67tkKEpSG63m4Dfz04yyc2LF2nSwpunpqeJRKNU19bi1M7dJAgogsDMxATLCwscOHYMs/ZYWs1mmvfto6+zk8OnTxtB3hNDQ0SjUdoOHjT2EYuLi7nW1UVeRYVKgIFIOMzVxx+nqrmZ/JIS9XEWRZBlw8gEENnaYnFmBrvTSWltrWHiScRizE9M8GWtd9Zqtb6is3ZkZIRkMkkwGCQvL490Os3U1BTt7e1G5+29DpPJZCifiqIQjUbVKsaZGQBmZmaIx+Pk5ubi1Qj0q8GTTz7Jr/zKr/C///f/5rHHHnszTyGLLF4VsgQwi7c93qodwEwmQ09PD7FYjAcffJCKsTFe7Oqibv9+I7oFVAND98WL2G02TrznPczMztI3MIDP6cTt96sZZcEgM6Oj1DU13bH/ByoBkxWFDBCNxZibmsLn91OsdclmJAmXx0Mmk+GJf/onGjo6OP7OdxrXYbcSmd51Dhnt606nE5PZTDgcxuV2q8RVlu9o39gdc6PHq7g9HkOFE3Yda0ZRWFtZYX56mvDmJr5AgI5Dh7CaTDTs20csGmVhaYmdRAKX243X4wFBMGrjUjs7uLxexkZHMZnNVNfUGOYQWRtzSrLM+vIy7UePGuNgk6h27Ro1ccDS/DyFpaVGSLN+7BaTyRirr66sAOAPBg3SaxhiNINHMpFgcniYo/fdZ7h4TaKIyWSipKKCkooKwtvbPP3tb2O323HYbLh9PvzBIJlMhp14nI3NTZYWF5manGRubIz6lhYCwSDjExOkEglqa2vV2jnUDxaKKDIzMcHS/Dz7jx1TFUxBUNtiMhm8Ph8uj4fN1VWCeXkM9vQgCAJt+/er1XH62BmwanuBkqKGIl/+/vdpPHgQQVFIJxLYnE5QFGNEr8gyqUSChYkJcktKcGtxOPqHmQs/+AFlFRWcPnz4Za+VlzprY7GYkbm3s7OD0+lka2sLs9n8UwlhfjMhCIL6oWBlhebmZvLy8gxldHZ2FlEU78gcNJtf+S31/Pnz/PIv/zJ/93d/x/vf//63+CyyyOKVkSWAWdwzeDN3AOPxOLdu3cJms3HkyBGsVisd7e0MT0ywubhIUHM0puNxrj3zDJUtLRRVVGARBBrq6lBkmc3tbba3tlhYWMDmcDBw4waeYFBtwEDd5QNIa+Pg1Y0NZmdnKS8uNka6GVkmmUjQd+0aNqcTZypFdWOj0VcLGCqbHr9i0WJHdo+By+vqmB4dpbmjQ41k0RQl/T70UGOzKKqqmKLgzclhfWVFzQgENlZXmZ+cJLK1RSAvj4raWnzBoFGhNjc2RlVVFYIgEA6FiEYizM/OqkYDr1fNG3S72draIhSPU1hURHFJiepolSSVCOvHLMukMxkcDodhgNAr1wBj73JufJzDZ87ckVWoN6UIqFVuw729tGkE1SCSmhKGIKjNHFeu0LJ/P3atQmx39IquJq6vrlLf2kpNQwMD3d2YTSaa29uxOxxqfIzbjSTLXHvhBUqrqhDNZnr6+jCbTOTl5hrkSneAT46Nsba0xP7jx9VoFy1iRo+OSUsSTa2t3Lh0CYfbjcPppLGlRTUa6VmEqB29fq+XWCRCKpXi6ve/T+uxYxRXV7M0OalG5QCCKCJIkqrw7eww3tMDokhdWxvTg4OYbTZkSWJhcpKNxUX+03/6Tz/xdSMIAm63m7W1NdLpNPv27SOVSrG2tvYTR8X3Ira3t+nq6qK+vp4STVndrYxub2+zvr7OxMQEfX19RuZgTk4OLi1J4IUXXuAXf/EX+eu//ms++MEP/kwR5CzubWQJYBb3DHSnrKypWa/3vnQyubW1RVdXF4WFhTQ2Nhr3LQgCP/+e9/D5L38Zh9dLLBxm4No19p86hV0zXyioLRaSpgQU5OWRSaXYDIWQ9uzh6W98g72nTpEbCODz+7HabAiCwMziIlvr61RXVuLx+VSVTpKYGBhgZXaWpv37CebnM97fz/ToKLVNTUYTCdweJ+vZcxk9lFk79vzSUsZ6e1Xlh9uZfvq+oNVsNkKO0UhUTkEB/TdvEotE2FxexpeTQ1V9PR6//443LYNwCYJBSnSjSGFxMcmdHTa1eJl4IsHk2BgdJ09SVFSE2WRS6/S0mjiTKKLIMlsbG/gCAUOdNJlMSHocirZrt7mxgVXL+ktlMkZQtF7RZjGZmJ2awuvz4fP5AIzv1zP1TKLIxMQEbq+XHK2aztjj09QbkyiyurTEysICB0+dwmoycfDECTZXV7n+wgtU1tVRXl2NJMv03LhBfmEhVXV1TE5O4nK5CPj9RCMRBoeGsFuteH0+NlZWSMRidBw7hl0LjzZI4K4GEVkUmZ2aomnvXhpbW43rrfcz65mAJSUldI2NMXLjBm2nT1OkZ/Zp43fjdSIIJHd2GOvuRjCbKSgrw263Y7ZYMJlMxGIxBm/cwBcI8MGf//mf+LpRFIXJyUnm5uY4cOAAHu11sHtUrHfX7h4V5+XlvS36el8LdpO/V8ozFEWRYDBIMBi8I3NwbW2Nb3/72/zt3/4tBw4c4Omnn+azn/0sH/nIR7LkL4u3FbIEMIu3PXaPgAEjFuT1wKSpZvPz8wwNDdHQ0PCKjQU2m41//9hjfO4f/gGzz8fhhx5S3zw1c4fRU6sRK0EQsFqt5ASD5ASD2EWR8OYmCbeb1YkJQwVEUaiuqcGuNROsr6/Tf/Wq2hryjncYOXTVTU1ceuIJSquqsNpsxihZFNS6upSmbOnKlbQrwDivuJiluTlKKioMoqUranpUCkBSc7jOjY8zNjjIO97/flo6OlQioR0rqCqc/nd9v2/3/ehKl8ftxuZwEHW5mJmZwW6zIQCDAwPYHA5yAgFcbjdOh0MltILA2tIS+cXF6ihXktQQbjB21NKSxOTwMNUNDUbAtSiKSJmM0Q6SSCYZGxri6JkzKinW9hAN97bFQiwcZmF6mqP33WcYYORde4Qmk4lwOMxgTw+HT53CppE0kygSyM/n+LlzjPT1cf3iRSxWK06Xi/KaGkZHR7FardRqjR/5+fnIskwkEqG/q4uV5WVqmppYWljA5XYT9PvvCHu2mM3E43FuXrrEngMHjJo9fSdT0giqpEXo2Gw2ep57jmPvfS/5JSXqc1GSjPxDfcc0Fo8z0duLw+NBNJnIKyxkc20NbzCIlE7T9eKLWO127j916keOL3Xo+7GLi4scOHDgZTVxu0fFiqIYo2LdJOLxeAx18O0+Kg6FQnR1dVFbW/uqw6ydTifl5eWUl5dTU1PDzs4OX/3qVxFFkf/8n/8zL7zwAo8++ii/+Iu/+CYffRZZvDq8vnfRLLJ4C6ETwDdiDCyKotqfOjJCR0fHj62rysvL4xfe+U68Hg9mi8UwSUga6dMjVnSDQUojWiZBoHbPHtKJBG6rlcbGRvUcZBkZGJuYYHZqimvPPcfQzZscOH2amtZWY7/NLIqIJhO1bW0Md3cDavacRcseTGrkCdRQapO246cTtoqGBubHxw3yJ8uymhmnnVcoEqHvxg2uPvMMmWSSA6dP09DaSjA/33DOCqgqml7zpgdZ66NN0Kr60NRQjYCsayPBsvJy8vPzqauro7W1lWAwSDgSYXhkhIHBQVaWl4lFo2ytrpKbn28oi4p2PrKiYDabUTIZ4tEoOdpivk7Y9AgWBIGpsTHKKiuxOxyGi9Yg6EAqleLm5cu0HTqE3WpFNJlUYwaqsiqKIjvxOJ2XL7Pv6FFjhGdU0QmCmrvY3k4mnWaou5u8ggLGRkdxOJ1UVlaqYdWa6UYQBOYmJ/G43bzvAx+gtrYWUdtR7O3tZWZqiqXlZRRZJhaPc/WFF6htaqK1rY3w1pZBqPUaPL0FZWNjg7GBARr37SO/tNRwdSua+of2OCTicSZ6evDl5UEmQ05hoZp3uLWFPxhkuKsLFAU5leJ3f+M3fuzrRVEURkZGWFpaekXy91Loo+KqqioOHTrEqVOnKCsrIxqNcvPmTV588UWGhoZYW1t7w/Z63yjoHcY1NTV33YYyNTXF//pf/4uPfexjbG1t8cMf/pDGxkYuXLjwBh9tFlncPbIKYBb3DARBeEOMIJlMhsnJSTKZDCdOnDDe6H8UFEVh7549zC8tMT86SqVm7DDtImrpXe0cev2ZfpTtJ09y8fvfp6C2FpfXS2V9PQKwtLDAjeeeI1BQgDs/n4WVFXI0E4l5VytBUVkZM8PDxMNhnD7fHfEeZo2MGXuBqPEyAqjdu2Yz4VAIl8djjEpXV1YY6+9HEARqmptpPXDAUA39WmtGcWkpou6YFYTbfbi7rolOxHbvuaUyGVaXl1ldX6e+rk5t8NBIoWgykZeTQ2FeHrIWxBsJh5kYG2N2bo6ShQV8Ph8+r5eMNl5OyzKiojAxOkppdbV6TNqxZFDz/8yiyE4yyfLcHKceekjdf3tJnZrZZGKot5fi8nICgYDxNb3yTVEUUpkMt65coWnvXvx+v3EbXWFNZzKYRZHBvj48Xi8PPfYYT373u7QfPEhFeblK1jRXLopCz40b2Ox2WvftUwmR04nH7UaSJDLpNFvb20RCIUZHRliYmGD/sWP4NONKICeHjbU1cvLzjb5ls9nM0sICI/39HDp5kvPPPqsSPkFA0PMP02ncHg/RSITp/n5ySkvZXlqioaOD+YkJ3B4Pifl5tjc22FpZwZ+XR1NFhTEy/1HP/6GhITY2Njh48OBd9em+kqt4bW2N4eFhUqkUOTk5hjr40xwVh8Nhg/zdbYdxX18fjzzyCH/4h3/IJz7xCQRB4ODBg9me3yzedsgSwCze9tg9Knq9RhDd7GEymTCbzT+W/OkkRyec7zh3jv/zta+xsrBAbnExkqIYxAmNLFm0Y81oREBWFNLpNPacHOZHR3nwfe9DAUa7u9leX+eB970Pp9NJIpFgW2smmJ2ZweFyqW0VPh82u529R47Qe+UKh8+dIyMImLS9PUk7Rnb9v1lziKYliYqGBiaHhmg5cICFmRmmRkbwBQLsPXwYh8tljJT1Jo/C4mIW5+YoKC7GoiuKGnSypatcohalY9P2GmVZZnpmhnQiQV1dHS6Hg0g4jNPtNsblom5GMZnweL0E/H4USaKxpQWL2cz8wgJzc3O4XC78fj8+n4+ULLMyN8fR++83FMKUtkOXymQQtNiX+tZWo0pNd/TKsozdYmF5aYlYOExLe/vL8vtS2oh3oLOT4vJyCouL1bGsVsdmtViMnzfY10diZ4faxkYmp6Y49eCDTA4NsVlYSCA3V41qSafpvnYNf04OdU1NxijdpO36iSYTJtTQcVmSyMRiHL//fmRJYmhoCJvViqQozE5NEcjNVXctRZGxkRGWFxY4duYMVpvNyEsEtYIvI0nImQyJZJK10VGKa2pYGB+nbt8+lcAmEiSTSTLpNIvT0+SXlrI4Ps7nPv/5H/kakGWZwcFBQqEQBw8exL4rfPtusXtU3NDQ8IqjYn1v0O12v2Wj4nA4TGdnJ9XV1XdN/gYHB3n3u9/Nxz/+cf7oj/7obT3mziKLLAHM4p7C61EANzc36erqoqioiLKyMq5evfojb6sv0evhwYKg9tD+0s/9HH/3la9g15b9U7siSEQt503SCKEMbG9sMLuwQGNbGxuzs/RdvUp0e5viqiqOPvigYcpwOZ047HYK8vORMhk2traIhEKsLC5isloJ+P3Y3G7mJieprK1V+3IzGYMcGHuB2s6apCgogkAwN5cXf/ADNldWKKqo4PB992GxWg1yozuDZa0txBMIEOrpQTtpo8dXHy/rRFEBzBYL6XQaq9WKpPUly7JMY0MDsva9kUgEm9Np7PLpjR46MrLM2vIy1Q0N5ASDhokkFAqxsrrK3Ows8UgEk81mxJpYTCbSmvFFN4ekEgkKiovvIIZm7TgjsRh9nZ0cue8+wz2cfok6ODwwgMlioUrLxrNp96GTP5Om/O1Eo1TV1zM5OUlJSQnBYJDCggKuPPcc7YcPY3c66bx0ieKKCqprau5wIUvczoA0aYRudWGBY2fP4tTG1uXl5WyHQoS3t7nywguY7HbcHg/rWmfxoZMn1b3ETAav201Sa06RAZvZzPb6OqH1dar27GF2cJCaPXtw2O0oqC0tm8vLatSPy4XZauVAa+uPbLSQZZn+/n6i0SgHDhx4U5Q5fVSsj4v1AGo9ZsZisRjK4O5GjjcakUiEW7duUVVVRUVFxV3dx8jICO9+97v56Ec/yp/92Z+96eTv85//PJ/73OdYXl6mra2Nv/7rv+bQoUOveNszZ8684vj5Xe96Fz/4wQ/e1OPM4u2LLAHM4p7C3RLAl5o9dnZ2jODjl/6i1lU/XVnbbTix2Wx8+Od/nr//13/FcvIkNodDJVGaAijpKpcksba0xOrmJvW1tThcLqLr61x+4gnOPPYYlQ0NRm+uWWvq0HfWTGYzJQUFpHNzyUgS8UiEja0tBLudy888gyyK5Obl4fd4yGjqnV75pnCbvM6PjTEzMUFeSQlF5eXUNjcbY2Cjik6SDPJnEkVMZjOyvieojRWlXY5S/fqA2q2qZDKkUylGx8Zw2O1UVVUhmkzIGgmOR6M4nE4EUUTRHjd9R86ijV6joRB+rSbNLIrgcFDidlNQWEg6leL8449TVlfHwOAgdrtdVYhycrDa7aAoDHV1se/wYXUcLcvq6FcjuKIo0nXtGs379uF0OAwyZ7FY1LYRs5mZqSlCGxscOHHC6BtO6kRSI5nD/f3EIhHK6+qYmZ6mXBubmrQdxMOnTvHCM89gMploamujpLTUcPbqx6MTVjmToe/WLQCOnT4NokgqnTaaT3KDQXw+H7MlJVSUl3PlhRew2u3kFBQwOTFBTjCIx+PB7nQSSSSw2GzYrVaW5uZYmZ3lxCOPMN3fT1VLC24t0iedTpNOJpkeHqa0uprqlhZ6n3+e//qFL7zi60WWZXp7e0kkEhw4cACrlmf4ZuNHjYqHhoaMUbFe0fZGEdJIJEJnZycVFRVUaj3PrxUTExO8+93v5oMf/CB//ud//qaTv3/913/lE5/4BF/4whc4fPgwf/VXf8VDDz3EyMjIK1bxfetb37oj+H5jY4O2trZsJuG/cWQJYBZve7yeEbC+vL6wsEBHRwc5OTnAbUOJLMt3qAo6+dOjZl7pF7nP5+PfP/IIX/7e92g8fRqH3W64WVEU0pkM8zMzxJNJdQ/OZKLrhRcwWyz84u/9HtefeYaC0lJcLhciGG0dkja+VVDNHibNbOLx+cgJBkml07jsdsZ7e4lo+3A+rxe310tA2+HKSBLzExPMjIxQWlPD8Xe8A0WWufrDH1LT1AS6YihJZLRz08ezOhn1BYNsbGwQ0K6VJMuq+qao9Wx6DIzZamU7FGJ7dha310tFebmRtaeTxEQsRmFpqbEniTYqljTCs729jUszFOjnj+bgtYgioViM3Lw8WltbSaXTxKJRNjc3GRgexm6xEAmFMNvtON1uQ83TR6NWs5nhwUG8Ph9Fmjqo7/Tpu5sry8vMjI1x9MwZozHEiFuRJKyiyPDAALFIhNLqaubn5qiprcXtdqtEXyN30VSKZCKBzWZTK/T0TEFt3K2TwZ2dHW5dvUpBSQnVdXUqWdeIYVqSsGqqqtlsRspkuHXtGu0HD1JaWkosHicSiRDa3mZ2bo711VXCJhM2p5OFhQW2VlcprKxkZmiI0tpaPH4/kiRhFgTi4TALU1P48/LIKy5mcXKSd5w9+4rVbZIk0dPTQzqdZv/+/SpZ/ingpaPiaDTK+vo6CwsLDA0NvSGj4mg0SmdnJ+Xl5VRVVd3VcU5PT/Pud7+bn/u5n+Nzn/vc604oeDX4i7/4Cz760Y/yK7/yKwB84Qtf4Ac/+AFf+tKX+KM/+qOX3f6lLS1f/epXcTqdWQL4bxxZApjFPYXXogCm02l6enrY2dnhyJEjd+z77Y6U0f//1ZA/HYWFhfz8/ffzzQsXaD592mjZSKfTTExMYDKbaWpoIBoOc+3CBer37qWoogIF2Hv8OF3PP8/hBx/EZDZj0dQ7k0bEjOouQUBU1Cq0jEae6pqa2F5epryoCLPdTjQcZmF+npnpaTKxGGvz81Q3NnLswQcxaXE1kizjy81la3WVYEGBquQJgtG4wS5XLUAwP5+1pSWDAOqkL63FzOhj4VQ6zdjYGE2treTk5mISbrd/6Lt+sWgUm8OhjrplmcxLHsOVhQXyi4vVsOJEAjmTUd3KmuO158YNqhsa1DGw1jSRGwySTKfZ2tpiqKuLyuZmunt6CAYCON1u/D4fZpOJ9fV1VufnOfnAAygaec3IspE/uLW5yWBXF4dPnzaifZK7sgdNgkB/by/xaJSSykqWlpaor63F7nSqzmAtmmVlcZGB7m5OP/QQizMzjI2M0NDYaGQMKprSuLW1RdfVq+zZt4+8ggIjdkbUQ7y1UbHJbGZhbo656WnOvvOdlJSWIssyDrsdq9VKUUEBiVQKiyDQPTVF56VLCIpCcVUVk4ODHDp3Tg0W10h4OpOh7/JlLHY7bq+X/MJC5vv6+OhnPvOy53Umk6G7uxtFUdivNZC8HSAIAh6PB4/HY4yK19bWWF9fv+tRse5ILisro7q6+q6Oa35+nocffph3vvOd/M//+T/fEvKXSqXo7Ozkj//4j42viaLIuXPnuHLlyqu6jy9+8Yv8wi/8wk80wGXxs423x6s7iyx+AvRokFerAMbjcTo7O3E4HBw5cuRlKob+izqTyaijzF07fz+J/Omoqa7moViMpy9dovnECZKJBBPj47i9XkrLyliYnma6v5/9Z8/i8niM4OJgTg4Vzc10X7xIx+nTZMBQ5QBjTCuqB2qEPls09art6FGunT/P8Xe8A6fLhc1qpefyZUSrlZLGRuKyzNz8PG6Ph1ztzbC6qYnBGzcIFhQYFWu6mzitO4g1c0luYSFzk5PqiFaWjZo0/bpJsszmxgYrq6tUVVVRXFhoHLu+86ZHyCQTCexOJ+lUiu2tLUJbWySiUWKRCMlEgtH+fmqbm5mdmMBqsSBaLFjMZkRtLLo0N0cgJ4f15WWkdJp0KqXuZQoC89PT5BUU4Nf22WRFYX11lZmZGZwOB+N9fZx84AEjIiedTmPVHutYLEb3tWt0HD+uto8oCilN+ZN08tfTQzqZJL+0lNW1NZoaGzFbLMZY12oyMT87y/jICIfPnMHpcOBobubyM89QUl6O0+k0VMSZ2Vkmh4Y4cOwYXp+PjKZG7g6E1l3kg729hEMh9h06hN1mI51OY9GUQf25ajGb8Xi9hJaWqG5sxJufz/Wnn8YVDBKKxUgtLeFxu7GYzYz39GC12dhaX6fl4EG6n3+ej//6r79shJpOp+nq6sJkMrFv3763dYuH1WqlpKSEkpISJEkyuoqHhoZIp9NGAPWPGhXHYjE6OzspKyujpqbmro5haWmJhx9+mLNnz/L5z3/+LSF/oGaGSpJEQUHBHV8vKChgeHj4J37/9evX6e/v54tf/OKbdYhZ3CPIEsAs7im8GgVwY2OD7u5uiouLaWhoeMVfzLsjZXabPV4t+dPRtmcPO4kEz54/j5iTQ1FxMYV5efRdv04iHufIO96B1WIxMgP1rMCSqiqi29uM9/VRv3cvKW3/TdKDnTViBioh1P8fwGq3U1pTw8DNm6QTCRRZ5uDZszjdbkyCQHxnh0g4TGhri/n5eTwuF26vl3Q6TTQSIaB1wOqBy8ouNVA0mXA4HKRTKWN3Tb9eoMbbbKytsby8THlFBTabzegVNpTBRIL11VU2VlcZ6e9HkWXMFgs+vx+Hx0NRWRkObYQqiCLHzp1T9//0SjtFrUbr6ezk9DvfSVl5uXpdtL1FSZbZ3tpS43kOHmR7c5PI5iahrS21R9nlYnBggIKyMqanp3E4HHg8HnJyckiLIpl0mhsXL9J24ABej8dQJ827iFh/dzdSJoM/L49QKERzYyOC2axWxumu4b4+ItvbnDhzBkE7dpMo0rhnDyN9fbQfPIgI9HZ3E49GOXL6NFab7XYEjUY49fONxeN0X7tGMC+Pg8eOMTU2xk4iQZ7ZjCyrHcapdBqL2UwoFKL3xg2C+fnklZUxeusWgdxcKhoacLndxOJxNjc2mOjtpbC8nLGrVzn64INsLC5S4PVy//333/E8TqfT3Lp1C4vFQltb29ua/L0UJpPJ6OPVR8Vra2vGqNjr9RrqoNvtVgO3b96kpKTkrpW/lZUV3v3ud3P48GH+4R/+4Z66Xl/84hfZs2fPjzSMZPFvB1kCmMU9hZ9EAOfm5hgeHqaxsfEnhriatBgTPdribj7BK4pCQW4urnicqCgSaG7myg9/SEFxMc0HDqjxKGCYRADDpdrS0cG18+eZn56mpLJSNZBou4Ayt1VPRRsP65l8siyTyWS4cf489/3cz1FZV2eEFQuAy+HAZrNRWFDATjJJOBxWCZPVyvOPP07HyZPkBYOYtfgWATURXkAdicuKgsfnIxIKEQgGjfG2oijMzc2xsb1NfX09GysrxCIR0skkSwsLbCwtEQ2HMVut5OTlkVdYSG1DA8cfeMCon0tlMuquocnE3PQ0OQUFqglGUxp1s0QimWRrZYXmtrbbRFQjqYIgMHDrFm2HD+P1egkEg0Z/L0DnlStYrVbkZJKdcBiX3U48Hmd5eRmLxcLk4CCtHR0Ec3ONMbuwqyru1vXrWK1WPIEAsZ0dmhsbUUTRUGYF7Wc4nE4OHD8O+mOl7ZPmFhYyPjxMOBRioKuLnIICDh0/rj6WGknU1d2UJGE1mVhZWaG/q4uW9nbyCwpUJdpkQtE+oJh35Rouzc0xPDjInv376Z+aYryri8Lycpamp/EGg6pyCywOD7P/6FGGe3pUxzZw49ln+R//9b+yubmJ3+9XlVZtpOhwONi7d+9bpmS9Gdg9Kq6uriaZTN7hKtYrIPPy8owe69eK9fV13vOe97B3717+8R//8S0nf7m5uZi058xurKys/EhHt45YLMZXv/pVPv3pT7+Zh5jFPYIsAczinsDuEXBaq8naDVmWGRkZYXFxkf37979s6fml0O9rfn6e0tLSHxuE+6Mgy7IRkPurH/4w12/d4lv/5/9w8KGHKNCND5JkqHn6Oejhw2lZpv3UKa4+9RQul4uc/Pw7qtcEQcAExn6gAmytrTF44wYF5eW8/zd/k97Ll6morVVdvBpJNOuNKVr9WWFeHgW5uVRWVvLsd75DNBJhfX0dq9mMz+fD4/HgdDoRtXYTAcgtKGBjaQl/IIAkSUjA5NQUUjpNbW0tqXic6fFx5iYm2FxZIaewkPrWVuxa5p9JFIlEIjg9HpWc7moW0R4AVhcXqWtuBlRyqKt/FpOJmbExymtqsJrNt2v2UMfgUxMT+IJB/H4/kkaG9Zq0jdVVEvE4737/+5FkmVgkwuzYGJsbG5RWVjI5Pk5+aSnxnR16envx+Xz4/X48bjcCcPPyZdweDyabjUQmo5I/MMbayWSSm5cuUVpRQVVdnTHK1c1EuvnDl5PD977+dR585BEKCguRMhmV0OnPA9SMSFEQGOrvZ211lUMnTuBxu43dQL2+TtH2QkVBoK+ri2gkwtEzZ1hfWWFqaIiGAwfwBYMsTU9jEgQi4TDT/f2U1dcTDYeJbG7Sfvw4W7Oz/NqHPoTP56Ovrw9ZlgkEAoTDYbxe7z1P/l4JNpvNGBXrO39Op5Pt7W0uXLhwRwD1q3E6b25u8sgjj1BXV8dXvvKVn8qOpNVqZf/+/Tz77LM8+uijgPq76Nlnn+V3fud3fuz3fv3rXyeZTPKhD33oLTjSLN7uyBLALO4pmEwmEonEHV/TzR6JRIKjR4/idDp/7H3oZo+mpiYWFhaMvaf8/Hzy8/MNZeTHIZVK0dvbSyaT4dChQ9jtds6dOaOG+a6uUlBaqhK9XeNbXW2TFUXNDxRFMJk4cv/9XHrySfafOYPL61W/Dnc4i1PpNCO3bhGNRuk4fRqPy0VGUSgsL2eiv5/aPXvUHlgtAFrU9vn0Hl1RyzFs6eggFgrR1tZGVIuXmZudJSPLBLUWEr/PR05hIb1Xr1LV1ISiKIyOjhINhTDLMjcmJwkEg+QXFeF0udh3+LBa2aYpZHoP7U4shsvtNhQveVcsSlqSiIRCOD2e2wqfFmYsKAqzExMce+ABVZXTTCgZzT08NTLC8XPnDAcummqYSibp7+zk0JkzhuJo8vlo2b8fZJnHv/UtdmIx6puaKCkvJxaPqwRxbo50KsX8+DjFFRUIFguCyURjVZXhmpYVhe3tbbquXaNl3z4KCgtJpdNqZ7OejajtGo4MDbG1tkZBYSH5+fnGnp+iK3naGDexs0P39esEcnI4rsfB6LuB6bTRt2w2mUglEly/fJn84mKa9+41noeFFRXkFRezubREIC+PWDTKZF8fdXv3Eo/FCK2tkdzZwSQIlASD/MpHPqLWxikKa2trDAwMAKqq1dXVZbhq76bt4+0MPQC+qKiI+vp6AGNUrEdEeb1eY2/wlVzFoVCIRx99lNLSUr761a/+1NzRAJ/4xCf48Ic/zIEDBzh06BB/9Vd/RSwWM1zBv/zLv0xJSQmfeYnR54tf/CKPPvqokYaQxb9tZAlgFvcU9BGOjlgsxq1bt3A6nRw5cuQnfiLX9/109SMYDCLLMpubm6yurtLb2wuo/b/5+fnk5OS8jAzGYjG6u7txuVwvW5Z/8P77EZ57juFbt6jet480u0wdmssXNPOFomAVBLBa2X/mDJ0XLnD43DksGoFVUNW/7bU1eq9do6a1lb2HD6tECHWsXNvSwuWnniK/tBSP36+SLS0PTx85g9ZXbDJRWlnJC48/Tk1LCz6v14hgSe7ssL29zdz8PDMzM7jcbrY2N1lZWuLWlSvsRKPU1ddTVleHLycHi8lEKBxmrLfX2P2D213AiqIQDYexu93qeei5itq+2+bGBh7NrZvRCKHFZMIsisxMTpJfUoLdalUVPo3AWkwmuq9do761Va2Y08iugBpl03n5Mq379+N2OFB2EWGzyUT3rVvUNDbS0NzMyMCAGtx85AgFRUXk5OVx6ZlnKCovx2y1EovH8bjdrK+v4/Z4cLtcLM/NMTIwwMETJ3BrdW42qxVJ+/mKoiBlMnReuYLL4+H4fffRe/Mmm5ubBIJB4/z0hpGF+XlG+/tp2beP/IICVUkEFO36mc1mduJx/IEAi1r9mz4e1k05yUQCTzBIOp1mY2UFm9vN1MAAte3tZFIpliYnsTmd+IJBVqam+PL/9/8Zz+WdnR1GRkYoKCigqamJnZ0dY1Q6OjqKy+UyyKDX672nGy12dnbo7OykoKCA+vp641x+1Kh4cnISq9VKXl4ekiRRXV1NJpPhscceIycnh2984xs/1bo6gA984AOsra3xqU99iuXlZdrb23nyyScNY8js7OzLfm+NjIxw8eJFnn766Z/GIWfxNoSg6IFdWWTxNkYmk0GSJObn51laWuLgwYOG2aOkpISGhoYf+yb1Ss0er3R7RVN6VldXWV1dJZ1OG2QwNzeXUChET08PpaWl1NbW/sif+dyLL9K9sEC9tmht3WXq0JVA0HIItb2/7fV1Bq5f5/C5c5gtFgRFoe/GDXaiUTqOH8ekjahEVMKjaM0Y8ViMWy++yImHHjLIJnC77kwQ1F5i7fbTo6PIikJNQ4OxO6ifuwBEIxGGBwa49NRTBAsKqGtuprqxkdxgEEEzyZhFkfjODn1Xr3LkzBmjG1nPDDSbzfR3dpJTUEBhcTGg7heKoqiaLLq6yMnLo6ikxNhr1EfkF556iuNnz2K2Wo2v6Q7fieFhjp4+bZhCTNrx9N26hc1up6G52bguetD0QG8v6WSSfYcOGaQwEYvReeUKOYWFrCwsUFFbSzQex+/3U5CfTzgUYn1ri51YjOX5eZAkTtx/P06n09hDNUb8FgtrKyv0dXbSuGcPxaWlZCSJ9ZUVNlZXad1VP5dKpejt7ESSJPbs34/DZrvdJy3LanagpnrevHzZIJj7Dh82FCd933B0aIjp7W1yCgq4+L3vkVtSQkN7O+lkktFbt6hvb+eHX/saTreb//Rbv8VD584Btx2wLyVEOtLptEGGNjY2DJNFfn7+m9rG8WZgZ2eHmzdvkpeX9xN/R+jQXcVra2t88pOf5PLly5SUlGA2m3niiSfuOiw6iyzebsgqgFncU9BjYGZnZxkZGaGpqYnS0tIf+z0/rtnjpRAEgUAgQCAQoL6+nnA4zOrqKuPj4/T19aEoCsXFxVRWVv7YN5OzJ09iu3aNK5cv03T0KGm4o7JN0UalaOTPKor4cnKo3buXzuefp37fPgauXqWmuZkirURe0Ma6sjbW1ds0nG43lTU1DHR20nLggEH89HNNa8YFfb+uvLaWK08/TZUWUg2qchcKh5kaHGR7YwNfbi7Nmku2trmZza0tVpaWsNntBLSOYrPFQiqdVjMKteMzVE5FIR6JUFVfb5gz0AiiKIpsrKxQ19qqum5NJqM9ZXlhQVUYbTa1wUI3/CgK/bduceTUKcMUgTaanZ+ZYScWY+++fUZriVkbc44MDZGMxdh35IihFpoEAavTSduhQ3znX/6FvIICQuEwhUVF5ObmYjWbseXn4/P7ufHii2r7RFER4xMTWM1mnG43eTk52BwOrGYzQ319bKyucuT0aVxa9ItJC9SeHB5W8wBFkfW1NXpv3qS6oYHyykoUvTlGI6r66NfIDLx2jbPvfCe1jY1qn7CWryhp57cdiWC12+nUmkLq9+0jmUgwdusWNXv3Mjs6SiwS4dzZszyouX714OPi4uIf+QHGYrFQVFSkdhW/pI0jnU7f0cbxVjWE3A105U93B79aFXO3q/if//mf+dCHPsTCwgIOh4Pa2loOHjzIn/zJn/Ce97znTT6DLLJ4c5ElgFncUxBFkXg8ztjY2Ks2e7zWfD8dgiDg8/nwer0oisL8/DwFBQVEIhEuXLhAMBgkPz+fvLy8VxwJHTt8GLvNxjMvvEDT8eOgxYgktQ5fPfjXsitapKC0lOmREb735S/zvo99DJfbjaDfThtrAkaosaLt25XU1rL0/PNsLC8TzM/HZjYbocYyt/P7BEA0mcgvLWV+aory2lo219aYGBhAVhRqm5vJr6xkbXmZ9oMHmRoYIDcnh3xtHLaxuUkkHGZpaQmL1crm5iaxWAy7w6EGSgsCgkYqE4kEVrvd6OfVzQ/RWAyz1YrNYlFr6bToFVEUmRoeZt+xY2plmzYSBhjo7qasqgqH02mQTFmSiITDTAwNcercObVjWFGwanmJE6OjhDY2OHj8uLGjCOouYWhzk94bNzjz8MMM9vayOj9Pc3MzZrMZWVEIhUJ0X71KXUsLpWVlpGWZCkUhHouxsbXF1PQ0O/E4i1NTlFRUcOTUKaM7WX+GWS0W0pKEIsv09fYS3t7mwC6jx+7VAL3Cz2QyMTw4yOriIhW1tdQ3NZHRKu0kPRtSM8VsbGywsLaGlErRfuoUgiwz0dNDTWsrZpOJa+fPs3ffPj75e7+HIAiEw2Fu3bplBB+/mtfCK7VxrK2tMTc3x+DgID6fzxgVv51ChROJBJ2dnQSDQRobG+9qhJ1IJPjgBz9INBrlypUreL1elpaW+MEPfkAgEHgTjjqLLN5aZEfAWdwTkCSJnZ0dbty4QSQS4eTJk6/a7HE35G/3z+3v7ycSibBv3z7jTW5nZ8cYE4dCIXw+n2EieekC/fDICN9+4QX2nDqFYLFgEQS1/g11j093yGYyGXouXsThdmN3Ogmtr9N+4oRRj6YHGku7SKCuaimKQjKR4Mazz3L43DlsNpuxb2jSxt264mQSRRLJJE997WsEc3Nxeb3UtrTg8XqZm59na3OT6qoqvF4vLzzxBEcfeMBotNDVt2QqRSQS4YXHH6e6tRUEgZxAAK/Ph0Nryrj0wx9y4oEHjGYTkzbOHR8exmQ2U1VbayiaAJvr60yNjXHg2DHQjlXWdgl7r1/n5AMPqI+Jdu0kSeLSs89y4MQJgxjqP2N6cpKluTkOnzyJoplh9DDr5YUFhvv6qN+zh6WVFWqqqwlvbrI0N8fBkyeZm5lhaniYjmPH8Gk5gTKqEzijRcXMTE8z0tdHSXW1+qFkZ4eAz4fT7SZHG5VbTCZ++L3vYTKbqaitpVpzawOGwUO/T7PJpGb73bxJTn4+1fX1dF6+zOFTpwznu81iIZlKYbVYmJ+d5Wv/9E+0nDnDyswMTR0dDNy4QUl1NT6fjx9+4xvsRCJ88fOfp7WlhVAoxK1bt6iqqnrDRpiJRMIYFW9ubmK32w0y6Pf7f2p7g4lEgps3bxIMBmlqarqr49Cdsqurqzz99NNZwpfFzySyCmAW9wSi0SjXr1/HZrNhMpl+Ivnbbfa4W/KXSCTo7u7GZDJx6NChO8ZdDoeDiooKKioqSCaTBhkcGxvD7XYbZNDtdtPY0MAvOZ388w9+QN3x4+ByGe7gjLZ3F9nepvviRRra2ykoLVWJUn8/A1ev0nz4sEFe9N22VCZjuGd1F6rD4aB+3z66L1/mwJkzqptYEFRDiLZ/pygKywsLjGpml6KKCmqamshIEnOzs2yHwzQ1NGC2WJBkGU8gwPbGBvn5+aQ0BUoANerE5yMvP5/m1lai0SjRcJjZmRnSkoTb5SIeiwG3jSGg7i6uLizQcfw4GUlC1iJjAIZ7e2k5cIC0lhUoiiJmQaD3+nXajxwxdif10OUbFy/StGcPLpfL+DdJUZifnmZhepojZ84Y3cN6Nt7k6ChLc3M07t3LwvIydbW1eDUzQCIe5/tf+xpFZWWcuP9+0K+5Np6VZBlJkui+fh1BELj/Xe9CNJkQtfDtUCjEdijE8tISVquV1cVF5ufmeOdjj1FYVKTuC2qqnxFCrpHj4cFBlufn6Th0CK/fz9LiolHFJ6COJfXb9nV1EY1GKaurI7y1RWF5OUO3blFcWYkvEKD74kVC6+v8+q//Oq0tLWxtbdHd3U1NTQ3l5eWv+XXwo2C32yktLaW0tJRMJsPm5iZra2v09PQAGPEqOTk5b1lcSjKZpLOzk0AgcNfkL51O85GPfISFhQWeffbZLPnL4mcWP1uhT1n8zGJ7e5uCggJaWloMI8crQVep9J2/uyV/kUiE69ev43a72b9//4/ddbLZbJSVlbF//35Onz5NeXk54XCYa9eucfnyZcbHx/H7fPyHn/95Zq5cIbq5SUqPDgEWZmbouXSJA2fOkF9aajSGNOzdi9XppP/aNcPwYNbGwBZtpJqWJKxafIooiuQXF+PyepkdHVWz5jSSaTaZ2Fhd5fozz7A4O8vRM2d48Od/noXpaZKpFNOTk8Tjcerr6439O5MgkF9SwtriotEdrJNIWVfUtGvs8XioKCtj75491NfVIUkS8USC3t5eJiYnWVlbYyeZJJFOIysKDofDMBNkJInNjQ1MZjN+nw+LyaTW1SkKY0ND5BQU4PF41MdXu+b9XV3kFRRQVFKCKAgImvFjfmaG2YkJjpw5o+56anuSsqIw0NXF5toa1Y2NLK2s0NjQgM/rRZJlEjs7LC8uIisKVTU1oO0lytp5A6wtL3P5/HmKy8vZf+SIGiItqPV+ToeD3Lw8mhoaKC4oYHJwEJPZjC83l/GJCeYXFtiJx42MP/3P7c1NLp4/jyLLnLj/fnyBAGlJYnt9HV8waLikRUEgEolw+bnncLhctO3fjyQIRDY2WJ6dJae4GG8wyODNm6wtLlJbW8uvf/jDbGxs0NXVRV1d3RtK/l4Ks9lMfn4+LS0tnD59mvb2dmw2G+Pj41y4cIGuri7m5+dfFuH0RiKZTHLz5k18Ph/Nzc139brPZDL82q/9GhMTE/zwhz98y+JSPv/5z1NZWYndbufw4cNcv379x95+e3ub3/7t36aoqAibzUZ9fT2PP/74W3KsWfzsIKsAZnFPoLS0lMLCQhKJxB3K3m681Ozxo5y+Pwlra2v09fUZ47LXch8Wi4Xi4mKKi4vJZDJsbGywurrKzZs3sVgs3HfoEM9evkygsZGC8nLGe3sJb25y9KGHMJnNhmFCURQERaG+rY2R7m4Gb9yg5dAhY19M3yGTFIW0pgzpjt89+/fz4pNP4s/LI5CTQzwaZejmTRAE9hw5YkS/CIqC1+/n5uXLFJWWUlFba+zl6W7fwsJCJgcGjBgXs0amAONYRUDW/hMBp9OJ1+WiobmZqoYGIqEQW5ubzM/NEQ2FsNpsJJJJ7DYbgiiiCAIjfX20tLerTSEaqUzE4yzMzHD6oYfU22mP+9z0NIl4nL0dHSoh1I5jdWGBmfFxjp85Y+xNiqKIlMnQff06dpeLgtJSNra2qK+vx+VyoSgKK0tLanXboUPYnU6uPf88x+6/H4vVSkY7nu7OTlLJJEfPnMGijdeNejxNZZTSaXquX0fOZLj/4YdxOBz0dXXhcrtJJpNMT00hSRKBYBC3y8XC9DThUIj9hw/j8XpJafFGArC+tkZtc7Ox/zcxOsrc9DT7Dh3C7/ezMDvLjpZjWNXURG5uLoM3byIKArGtLb7+pS+xvr5OX18fjY2NFGtO7LcCgiDg9/vx+/3U1dURi8VYW1tjaWmJ4eFhPB6PMSp+pby9u4Gu/Pl8PlpaWu563eM3fuM3GBwc5Pz58+Tl5b3u43o1+Nd//Vc+8YlP8IUvfIHDhw/zV3/1Vzz00EOMjIyQn5//stunUikeeOAB8vPz+cY3vkFJSQkzMzP4/f635Hiz+NlBlgBmcU9A/4Wuj5L0SBEdr8fssfs+ZmdnmZiYoKWl5WVl668VZrOZgoICCrRqL50Mtjc08MKVK7z4+ONU79nDPm3PS9YNAdq+H6gqXGtHB/23btF79Sp7tHGwCEa2XEYjTIqiGCPlfSdPcv3ZZ8ktKiK8uUljRwd5+flGHElGkpDSaWSbjdXxcQ4dP45FOwaTICACKY18CIKg9teazSo5A3WvDtVQkkqn1X/jtkIXi0Tw+v24nE5cDgfFhYUkUinOP/EEgcpK+vv7sTsc+H0+zNp9eXe9gSmKQvfVq3Roo1+0eJntzU1mxsc5ee6capwA5EyGpfl5psfGOH7mDGj9uoIgkEmluPrii5RWVCCYzURjMepqa7FYrao5o7ubeCTCifvvR9BMJ8Xl5cxOTFDb2Mj66ioD3d3UNTZSXlWlBlPrzy1BbV4xCQIz09NMjYxQt2cPZaWlpDXVziSKeL1ecjQTTSKRYGR4mBd7e8ktLKSuoYFUJqMaZmw2Uum00QRjsVhIxON0XrtGIBjk5P33Gw0hk5OTTI2McOj++/EFgwzcuEFRdTXPf+MbfPpP/xRFUejr66O1tfV1P49fL1wuFy6Xi8rKSlKp1B3VbBaLxSCDgUDgrppI9Co7j8fzusjfxz/+cW7evMlzzz33EyvV3kj8xV/8BR/96EeNEOcvfOEL/OAHP+BLX/oSf/RHf/Sy23/pS19ic3OTy5cvG9FA2WiaLO4GWQKYxT0FfWwoaflr8MaYPWRZZnh4mLW1Nfbv339X1XA/DqIoGm90TU1NtLe3853vf5+bU1OYXC78gQB5gQAOzfVr1kagaCaJhrY2xvr66L1yhfZjx0AnZpoSqJ+zHjMT3t4mvL1NPBrloQ98QM2X0+JDAGLRKOOTkxQVFWGRZTULr7JSJZOA3rZsMpkIFhSwtbpKcWmpEbMCqEYHq5V0MqnmFgIIan1dLBwmkJdHKp1GFEWjicRmtbJ37141a007xhcuXKCmqYmZ2VkCfj9Ol4uZsTG8wSAun09V20SRZCxG740bnNCIUEYjhcsLC0yPjXHszBlEjSCJqHmG1y9doqW9nVA0ipxI0FBfr95XIsH1ixcpKS+nbd8+VcHUzquipoaLzzxDaHubTCrFsbNnseuqnza2N2kKYzQUou/WLQLBoHpcmovYpO1pSpIEoohoMhGPx+nr7MRmt/PvPvhBtY1jY4O1lRUm43G8Lhdev5/w9jYFxcWq6jc1ZQRA6+0gCALXLl2isrkZh9vNeG8v9fv28ezXvsZ9Z87Q0d5OX18fe/bseUUF6acJq9VqKOS78/YGBgaQJOmOiJlX07Shkz+3233X5E+WZT7xiU/wwgsv8Pzzz1NSUnI3p3ZX0I//j//4j42viaLIuXPnuHLlyit+z3e/+12OHj3Kb//2b/Od73yHvLw8fumXfolPfvKT91RGYxY/fWQJYBb3FARBuKMN5I0we6TTaXp7e0mlUhw6dOhNr8HSozV+9cMf5vjoKP/y+OMobjfT8/MomQxOt5tgIIDf60XSmyFMJpra2hjp6+PmCy+w78QJLGYzaHmCou4mzmS4eeUKZpOJh/7dv2NiaIip4WFqm5tVUinLbGxuMjczQ3FpKQW5ueTn5PDi009TVFamjnUFAVlTCgUgv6iI2YkJiktLkTXHsp6zZ7XZyGQyqgKruW1FQSAei+H1+dQRrCQRiceZHx8HYHxoiEw6jZTJEIvFMCsKJkWtfxtPpzGJIqsLCzz43vcaLR+ZTIYrFy6w78gRzFares7A0sICU6OjHD97ViV/GmleXl5muKeH/UePsri8jCiK1Gmhx8uzs4wMDrLv8GE8fj+KpngqGrlbX19nYXaWYF4eR06dMsbf8i6lNZ1O09/dTTQcZu/+/fj9fjW6Rvt3NFNKYmcHq9VKb2cn4a0tmtrayMnNNcbGxUVFCNq6QGh7m1AoxKXnn8dsNlNRVUXH4cN4vV51vG+xkMlkiMdiSEBOQQGLExM0HzrEzWefJcfn47f+w39geHiYtrY2cnNz39Tn8evF7ry9xsZGIpEIa2trzMzMMDAwgN/vNz40vZLpSydPLpeL1tbWu1IPZVnmk5/8JE8//TTPPffcm7on+UpYX19HkqSXqbQFBQUMDw+/4vdMTk5y/vx5PvjBD/L4448zPj7Ob/3Wb5FOp/mzP/uzt+Kws/gZQZYAZnFPYDex0wmgbvYA7pr8xeNxuru7cTgcHDx48C0vd2+or+d3c3P5yre+RV5tLZ7cXGKhEEvLy0zPzOD3eHB5veQFApgtFmpaWpgZHaXz+ec5rO26Kaju4JXZWUZ7e9lz8CD+/HwsokhjWxvXz58nkJNDbmEhi8vLbKyuUlldTa7fT0qSMNts5JeUMD85SVVdneo61VS7VCaDNyeH8M2bRoSMTm4ANQw6lQJUJTaTTrO5usrM+Lha1aapVnaHg9nJSWqbm7Ha7bi8XkyiyNKNG+w/fhyny0UmnSYei3Hp/Hk8Ph8/+MY3EESRotJSYtvb7Dt8GK/fj4y6vzg3NcX89DTHz5xB1Ma+ABMjI6wsLHDo5ElmZ2cxWyxUacHLt27cAEXh9AMPqC5fLbRa0khdz/XriCYTD7/vfUxphFVGczJr8TNTExNMj41R29RE+4EDpNNpQH0OyloWou70XZidJRIOU11fz56ODtWUo+9vamaedCaD1WLB5/czNz1NemeHs488AqLI+OQkFrMZl9tNXm4uLpeLqy++iGixkIzHaejoYGpwkNXZWT736U8zPT1Ne3v7T8zHfLtBEAS8Xi9er5eampo7qunGxsZwOp1GI4/X6yWTyRgVkK+H/P3pn/4p3/nOd3juueeorq5+E87sjYcsy+Tn5/P3f//3mEwm9u/fz8LCAp/73OeyBDCL14QsAczinoNJq9TSyd/dmj22t7fp7u42CuJ/WrllwWCQ3/zwh/nm977H8sYGFXv2kF9YSDKRYHN7m8jmJgtzc7hcLnICAYqrqrDZbFz64Q85cPYsJlGk+9IlTGYzxx96CMFsxqTFzNgsFvadOMHVZ56hpL6eVDJJXX09LrudlNYmosgyNU1NXHvmGcqqqkAU1dYSPW9QFHG4XMQjEWwulzFy1ls9FqanmZ+cJLq9jcVqJZiXh8fv58DJk1i00bAkScSiUdoOHlRNG4pCeHsbl8dDVX29EaA8MTLCkdOnadyzBwUIbW1x/vHH2VxfZ+OJJyirrKRxzx7i4TCri4scPn0a0WRSiZws03XtGmazmY6jR5mamsLlclFeVsaWFvxc19JCcVmZQcDQCPTM5CQzY2M0tbeTX1iojne7ulBQjS0KsLm2Rl93N3mFhZx64IE7jCYKmlIpSYhmMyuLi4wMDJDY2eE973+/eoxguHoV1P1JBLWreGFujlHNOfzgI49QVlmJKAiUV1QQCoWIRSJMTk0R3tzkie9+l6OPPEJ1fT3Ls7P0X77Mf/j3/55UKkVHR8fPhBnA4XBQVlZGWVkZmUzGIIO3bt0yXqdOp5Pm5ua7In+KovBf/st/4atf/SrPP/88dXV1b/QpvCrk5uZiMplYWVm54+srKys/cg+xqKgIi8Vyx7i3qamJ5eVlUqnU27qdJYu3F7IEMIt7CnpbwpKWtXa3LsKlpSUGBwepr6+nrKzsTTjS1waLxcIHHnuMzq4unnn+eeqOHMHlclFSUEAmP590KkU4HGZ7e5uFhQWsdju+wkKe/trXcDgc7DlyhNyiIqOOTa88S0kSdpuNQEkJNy9c4Oc+9CFsDodRDycCCAJOh4PCykomx8aob2pSu30FwagpyysqYmFujoaWFtKpFHNTUyzNzrI8P08gL4/2w4fxBYNqz248TmhrC7PZrJo0FIXV5WVyCgqQZFkle4LAQFcXTfv2qeotEA2HWZye5viDDwIqodpcW6Omro73fehDxKNRRgYH+e4//zOJZJL7H3mEjY0NlfAoCtcuXKCipobcwkLGx8bIycmhsKiI4f5+trSqNpvDgYCq6gFEwmF6rl/Hn5PDqYceUqODUE0uVquVZDJJKpVioKsLk8nEQU2tlLVOYT2XUTeDREIhhnp6sDsctB86hM1mQ9EeD1mSUETRULAtZjNbm5v0d3Xh9ng4cvo01154gcKSEsyiqOY8ms143G6Cfj+ZdJqLTz1FeWMjZoeDns5Ohq9f59ShQ1RVVNDR0fGG766+HWA2myksLKSwsNCIelEUhVQqxQsvvHDH3uArNfK8FIqi8N//+3/nS1/6Es899xyNjY1vwVm8MqxWK/v37+fZZ5/l0UcfBVSF79lnn+V3fud3XvF7jh8/zj//8z/fkYQwOjpKUVFRlvxl8ZqQJYBZ3BMQdHesJFFfX8/8/DzXr1/HbreTn59PgZYV95PIoKIoTExMMDc397bbkxIEgQMdHZSXlvLP3/kO/tpa8kpLsYoiWCwU5udTkJ/PTjJJJBRioLOTtbU1zBYLZdEonkQCu92uVqWhBhgjSQxPTuJyuThy5gx9N27QceIEgFFFJ2pqX1VDA5efeoqaujpMJpO6p6YoZCSJ/JISLnzve2yurJBJpykuL6f92DE2VlfZicXwBoPGYxQJh3F5PIZyJgoC89PT1DU1qbuDwPbWFggCXp9PbSiRZW5evsz+o0fV0GZZZmlxkdXFRY6cPg2Kgsvlwu1y0XHkCHn5+fR1dREJhZAyGWbHx+k4ehSnz8fY6CgFRUV4nU4uPvMMReXlHLnvPtVBK0kogoCUSjHU18f25ibthw/jcrtVBU833sgyTqeTaxcvIigKLe3t5OTmqgqfICBpjxeKgiIIxCMRBnt7kRWFPZqJaG52lmBOjrpXqUXoJDMZtdEjmaT75k1SiQTN7e3kBIPMz82Rm5eH2WJRx85ms/oYyjJXXnyRZCJBTn4+efX1CBYLQ5cuUVtaysMPPogsywwNDRnVhG9UvMrbCel0mu7ubpxOJ21tbQiCYETMLCwsMDQ0hNfrvaOa7qXXQFEU/vIv/5K//du/5dlnn6W1tfWndDa38YlPfIIPf/jDHDhwgEOHDvFXf/VXxGIxwxX8y7/8y5SUlPCZz3wGgN/8zd/kb/7mb/i93/s9Pv7xjzM2NsZ/+2//jd/93d/9aZ5GFvcgsgQwi3sCV69e5ebNmzz88MNGu4AkSayvr9+Rs1dQUEB+fj4+n+9lv/wlSWJgYIBQKMTBgwdxa3l4bzfk5+fz2x/5CN978kmGr12jbv9+7Far0f1rE0V6tY7eE7/7uywtLnL1mWdYrawkqO1I+f1+rFYrUxMTamNDWRlmk4mdaJTx/n6a2toMB3FGlhEEAZvFQlVDA8P9/bTu24cky+zE48yMjrK6sMD21hYn3/UuXG634Zi1WK1Et7cxm0yqIQUIbW/j8nqRUBVGSXPL+gIBJC2mZqiri9b9+zFpZGqkv5/SigrcPh+KorC1uclIby8nzp0zHseB7m5SqRT7jx3DJAiUVlXxw29/m831de57z3uIRKPMzc4iiiIzo6NsbW5y/OxZPFqXs55XuDA7y9jgILUNDTS3t6v1erKsBjsDUibD6MAAwwMD1Le0sP/IEbWdRBSRNfORnoG4s7PD8PXrpBIJGvbuJTc3F0kzxWyuralqnuZMVhQFRZLo7etjc32dlr17ydWW/yVZZnpsjL0HD2Ixm9VRnsViHGtLezt93d1gtWKxWOh68UWswK//6q9y9OhRrFar8VqYmprCZrPdUct2N2PStxMymQxdXV1YrVba2tqM83G73bjdbqqqqkgmk8aoeHJy0rgGbrebvLw8LBYLf/M3f8Nf/MVf8NRTT9He3v7TPSkNH/jAB1hbW+NTn/oUy8vLtLe38+STTxrGkFntOa2jrKyMp556it///d9n7969lJSU8Hu/93t88pOf/GmdQhb3KLJdwFncE3jiiSf41Kc+RXd3N8eOHePRRx/lkUceobCwUN1HkyQ2NzeNSjaTyWTUsQUCAVKplFFR1d7efs+MSoaHh/nOc89R2t5OIDeX9M4O186fp7a1lcLychTUT3GZdJorzz6Lv6AAbzDI1tYWiixjs9spKi7G5/EY7R7Xnn+eoooKKqurSWuKlgmMqreLTz1F8/79zIyOEo9GqWlooLC8nMGuLlWBKi5Wx8OCwNbGhkpcDh0CVMWv/+ZNyioryc3LQxEEVubnWV1ZoWXfPgRga32d8aEhDp44oY5519cZ7O7m6NmzapBxLMa1Cxc4ft99WO12FEWh98YNrBYLjXv3Imjhzr2dnYBaSba2uoonJ4eC/HwGurow22zk5OerLSVeLz6fD1EQ6L95E7fXS4s2etZr6DK6wWN0lJnJSSpqaw2jS01dnTGO1Q0c8ViMgd5eUjs71Le2kp+fbxBqWYvKuXT+PEfOnMFmsZBOpxkbHmZ1aYmqujrKysuNiB+zKLK2usrs1BRtBw5gNplIJBJ03biBw26ned8+Rvr6CG1vsxKNsjA1RWh5mT/+/d/n9OnTRj+1jt2vhbW1NUDdNcvPzycnJ+eeiwrRDR9ms5m2trZXdfz6NVhbW+Mf//Ef+fKXv8zevXvp7u7mO9/5DufOnXsLjjyLLN7eyBLALO4ZKIrCzMwM3/zmN/nWt77FtWvXOHz4MO9973t573vfS2lpqRGvsbW1xcrKCqurq4C6V+P1emlra3tV+WJvJ8RiMb7xve+xGI+zvbnJgVOncGoRK6Jm4hAFgWQ6Te+VK0iShNXnIxgMoqDuuSmyjNfnw+fz4bDbuX7+PC0HDhjh0LKiYDGZiEYiXHn2WVYXFnjX+9+PPy/PiNnZ3thgYWKC9qNHDcftTizGwK1b7D9xwlAFrz/3HAdPncJmtRqdvQ179uDV9tMuPvMMHUeOYHe5kDMZLj79NEe0rL10KsWL589z6PhxXD4fiiRx89IlAjk51DQ3Y0JV3a6/8AKVdXVUVFWxsrrK5QsXsFss2G022o8cwR8IqMpjJMLGxgY9N24Qj8VoO3CAwqIiAoGAmreImnk4PT7O1NgYpeXl1DY1ISsKc5OTCIJAZW2tGsNiMhEKhRju6yOdSlHX3Ex+QYER+4KmMiIIbG1vM9LXx77Dh5kYGWFpfp7K2lqqa2vVkGrtdvp1vPz88+zp6MDj8TA6PMzi3Bx7OzrIyclhc3OTgZ4epubmCIXDrC8s8Pu/8Ru8593v/omRRYqisL29zdraGqurqySTSYLBoDEqfrt/ENKVP1EUaW9vvyvymslk+MxnPsPXv/51ZFlmfn6es2fP8oEPfIBf/dVffROOOoss7g1kR8BZ3DMQBIHKykr+4A/+gE984hMsLCzwrW99i29+85v8yZ/8CR0dHTz66KO8973vpbKykpycHGZmZhBFEb/fTywW49KlS0acRE5Ozj0xGnO5XPzyBz7AtRs3+OGVK6pqJ4qIuzp59X7gquZmrly4gC0Uoqm5GbvVCopCNB5na2uLxYUF0qkU+ZWVXHn2WU684x34fD6UdJpb168TD4XYf/w4Q93dYDIhSZLaQWw2k5uby8DNm4Dq2BUEAbPVSjqVUtsxNFUwk8momXXa2DMWjeLx+VBQ+3RdbjdOlwsEga4bN2jYswe7w0E6k+HyhQu0HzyI2+cjk8lw7cIFyiorKauuRgBWlpbov3WL/UeP4vH7WVhcZG5uDrfTycbyMocefRRfIACo5GdtcZG5qSkOHz2KNxgkEgqxsrrK7OwsHo+HnWiU1YUFisrKOPXgg2q2IoAkkclksGn5c6GtLcYGBpAVhfqWFvLy8tTqNu2cJa3bV5YkBGBheprEzg6Xzp+nqq6O0w88YJg/TCaT4aAGWF5cxOlysROPc+vqVUrLyzl57pwaTyPL9Ny8icVmY3ZmBimV4tc+9CEeec97sNvtP/G5IwgCgUCAQCBwRy2bvjPn8/nu2Jl7O0GSpNdN/hRF4atf/Sp/8zd/w3e/+13Onj3LxMQE3/ve95ibm3sTjjqLLO4dZBXALO55KIrC8vIy3/72t/nmN7/JhQsXaG1tpaamhu9///v84z/+I4888giKohAKhQxlMJPJ3EEG74XRWCQS4Zvf/z4Rk4nK1lZsVqsxxl1dWmJ5dZWa6moioRAjXV0cOHUKr99POpPBopk+kskkW1tbzM3PM3j9OqWVleyEw+w/fpyisjJkWSYSCjF48yYnHnwQRXPuKkDniy9Sv2eP4byVFYUXn36akw8+aESmvPDUU5x88EEEQWBpbo6tjQ2a29qQFYUXnnqKI6dP43A4mJ+ZYWVxkX1HjiDLMlefe47qhgaKy8pIJBJcff556pubKSopQREEhnp6CG1vc+DYMcwWC9NTU4wODCDKModOnMBssdB19Sonzp1jaX6e4f5+SsrKqGlqwqQZY0RUNXhybIyB7m5sTie5hYW4tPBtn9+Pw24nI0kMaDtn6ysrWB0OGlta8OnX0mxG0mJ0QO1mtprNRKNRRoeGuHbhAuceeYTqmhq1kk6WsZpM6phYc1brePp738Nut+P2emnaswe704lJc0Z3XruGz+/n/37jGyTSaR576CF+86MffVVu15+ERCJh7A1ubm6+LGvvp2ki0ckfwL59++6a/H3961/nd37nd/jmN7/JQw899EYfZhZZ3NPIEsAsfqagKAorKyt88IMf5NKlS5SUlOB0OnnkkUd47LHHaGpqMtyq4XCY1dVVVlZWSKVSxp5Ubm7uWx4I/VqgKAqDQ0M8fuECBU1N5Bf//+3deVyVdd7/8dc57HDYd5AdFXFhEUFcsTRTUbCmKacZbZnGexq7y5qaarJmpmasaRkrndFmKutumlQ2S81yQzM1lcUNQRSRRThwgAOcw3K26/cHcP0ytVFERPk+Hw8f2fE653wPoOd9vsvnE0BlRQXalhaGDx2KlY0NtlZWaLVaCvbuJWLUKIJCQuSDED39grUNDezevJmmhgbGzZhBZ2cnzs7OuLm54eHmxtFDh/ALCsI3IECe8as5d47WlhaGjhrV1d5NoWD31q1MuuMOkCQ629o4UVDAuEmTkIADu3czOi4OR2dnKsvLaW1qYmRcHO06HQf27GHyjBlYW1lx6Ntv8fb3JywyEr1Ox4Hdu4kbNw53L6+u0h979+IXEEB4d8mOE8ePc+zwYUbHxBAdE4Oiezbtm6+/pr2tDZ/AQKLHjOkqw9K9RG6yWKgoK+NsaSm+AQEMGzECaxubruLVTU20trbS0tKCra0trVothfv2MW7SJEbFxmLv4IC5u5WeHPy6txtYK5U0NDRwpqSEzvZ23H18MLa3MyYhoavUjlLZdXoY5CBtZWWFXqcjd+tW2vR67pg7F1d3966xdte5VNfUUFNVxfEjR6jVarktMZHfLV16XZZtTSaT3Ktao9HIrQt9fHzw8PDo15lys9lMYWEhkiT1OvwBZGdns3jxYtatW8ecOXP6eJQXW7VqFa+//jq1tbXExMTw7rvvkti9N/aH1q5dK5/y7WFnZ0dHR8d1H6cg9Bi473KC0AttbW089NBD1NbWUlRUhLu7O59//jlZWVm89dZbBAcHk5aWxvz58xk9ejSurq5ERkai0+lQq9WUlZVx4sQJPD098fX1veKepP1JoVAwMjqaiPBwPv/yS7Z9+y3eQ4cyetQoFFZWXXXpTCacXV1Jnj6dwv37aa6vZ0R8fNfJXEnieF4erVotM+++mwaNhorSUsZOmoSutZX6xkaqq6qwc3bm8N69zJg3T14e9AsKomz7doaPHi23R1N017lTKpW0tLR07d1TKDAZjRg6OlC5uGC2WDh94gSTZ87EYjZzeN8+4pOTsbK25sjBg7h6eBAaHk5zYyOHu4OXi6srdbW1HMvLIzYxEXcvL0wGA7u2baOpoYFZ6em4u7khSRJtej3H8vPp7OzE3cOD+IQEuTWdxWzm9OnTVJ49S2BwcFfo7C5m3VPvz9vbGxeVCr1WS3lxMSo3NxxdXbFTqdA0NODq6oqtvT1W3XX8zBYLWCzUVldTduoUdvb2DI2Kwt3Tk+/27CFqzJiucjzdB0JsrK3pNBrlWcLSoiKaGhowm83Mv/9+uYuIJEkoJQlDezvH8vLo6OigtqGBCXFx1y38QVfJGV9fX3x9feU9tPX19Zw8eRKj0YiXl9dV9ejtrZ7wZ7FYrin8bdq0iV/96lf8+9//7pfwt27dOp588klWr15NUlISK1asYObMmZSUlFy2H7OLiwslJSXy/99qZXuEgU/MAAq3FJPJxCuvvMLSpUsvKorb0tLCpk2byMrKYuvWrfj4+MhhMD4+Xp7l0Ol08sygXq/H09NzQG6a7+zspKCggKamJk5VVmLt7U1EdLR8uKDnRKoSOFVURG1FBVGxsZw4fJiwoUPxDw/HtrtYc3lJCZraWhImT0ahUGAwGGhubqaooIDm5mYio6NxdXXFzc2N/G+/JXHyZOwdHLBYLOztXgJWACVFRV0FrIODqSwro7O9nYjoaM509zWNiIqiKD8fRycnwocP5+TRo5hMJsbEx1N7/jxFhYWMT0nBwc6OE0eP0qLVkjBxItbW1tRWV7Pz668ZEhLCxClTsLK2prOjg5NHjtDa0sKouDjcPDzYs20bU2bMwNjZyeniYtQ1NYRGRBAUHo5V9/JrTzhTAuraWspKSrCYzYQNG4Z/YCDtHR0cOXCAqNhYWlpaaGluxmix4OnmhoODA+rz56mvqcHH35+IqCgc7O0xmkwY2to4kp/PuO5ezZbuXs3WSiU6vZ6S48dpa20lIjqa6nPnCAoJISAwUC7Fo6Sr3l3Wp5/i6OxMcWkpIyMiePWPf+yTZd+rJUmS3KO3rq4OvV6Pu7u7vG+wL/tmm81mjhw5gtlsJi4urtez8Fu3bmXhwoV8+OGH3HPPPX02vh+TlJTEuHHjWLlyJdC1zSAoKIjHHnuMZ5999qLr165dyxNPPIFWq+2X8QnCpYgAKAxKer2eL7/8kszMTDZv3oy7uzvz5s0jLS2NpKQkeeahra1N3jPY2tqKu7s7vr6+eHt735A35O+PPz8/H3d3d6KjowE4nJdH7uHD+AwfTmBQEObu0iZmwFqh4Njhw3z75ZfcfvfdREZFdS1HdveulRQKio8epV2nIzYxUS6PIkkSuzZvZnhcHJ0dHTS3tFB//jwuLi6MiovD0dGRvV9/zcQZM1AqFBTs28fQ6GicXV3Zu2MHCRMnYmVtzZ6vviJl1izqa2spP3WKpClTKCsupqmpibHJyZw7c4aq8nKSpkzBaDBwaO9eAkNCiBg2jM7OTvIOHEBdW8uImBgihw9HMpspOX4cjVpN9Jgx+Pj7y+3ktm/ahIe3N7rmZiK69xTKbdu6l23NJhNlpaWcr6jAzcuLYVFRqJyd5cLYZ0pLsZjNhA8ditT1heDMqVOUFBWh0+nw8vUlPDISNzc3VM7O2NvZYTKbyd+/n4jhw3Fxd+/qH0xX0euSEycwGQyEjxhBQEAA56urqTp3jsSJEzEZjSitrFDQdap6/ccfExwWxqkzZ3BzdGTVm29e0YGP/tDe3i6HQa1WK9fY8/Hxuabi0xaLhSNHjmA0GomPj+91+Nu5cyf33Xcfa9as4Wc/+1m/zKoZDAYcHR3JyMiQu3kALFq0CK1Wy8aNGy+6z9q1a/nlL39JYGAgFouF+Ph4/vKXvzBy5MjrPl5B6CECoDDotbe38/XXX5OZmcmmTZuwt7dn3rx5pKenM2HCBPnNqL29XZ4ZbGlpwc3NTa412J9v0D09jAMDA4mMjLzgTa6jo4Ntu3ZRUl1N0KhRuHt6YjSZOHn4MAaDgVEJCRz57jvs7O0ZM24c0L0nrTsgFRcUYLFYiB47tmvfH9BQX8/p48dJTEnpqq+m0bBv505CRozA2sqK8qIiJk2fjpu7O3u//ppJM2Z0hbhvvmHS9Okcy8vDw9sbD29v9u/cyeTp06muqKCupoaxEyZQcuQIbR0dxCclUV1RwemTJ4nvPuV7triYMyUlOLm7MyQkBH9/f84UF1NTWcmwUaMIDAqSZzw1tbWcPnmS4mPHmH3PPfh2t8ZTgFzKRlNXx5mSEswmE0PCwggOCUFSKLoCvyR1/VIo2L9rFzGJiZiMRs6VltKg0eDp60vksGHYOzqi0+nQ6XQ0a7Xo9XqcXVywsbamorSUKTNmgCRRUVHBudJS7B0cGBodjXv36eSOjg72795N0pQpODk5IXWXzyktLubwvn2ERkZyrqqKjoYG3l+9uk9n2fqS0Wikvr6e+vp6GhoasLGxkWfKr6b4dE/46+ll3Nsl5j179nDPPffw7rvvsmjRon5bUj1//jyBgYHs27eP5ORk+fZnnnmG3bt389133110n/3791NaWsqYMWNobm7mjTfeYM+ePZw4cYIhQ4b0y7gFQQRAQfgeg8HA9u3byczM5PPPP0ehUJCamsr8+fOZMmWK/ObU0dFBfX09arUarVaLi4uL3JLuer5hq9VqTpw4wdChQ3+0h3FjYyObvv4adUcH2qYmAkNDCR85Up7xO1daytniYuImTkTl4iIf6DB3F122sbEhOjYWRXers/xvv2VIWBi+/v4AfPPVVySlpNDR2cnebdvwCQrC1s6O4rw84pKTqT5zBhQKnFQqTh0/Tnxyctd/J05EAVSePUvCxInkHziAu4cHEVFRFO7fj5W1NTEJCTQ2NnIsLw93b2+wssLdw4O25mZqqqqIGD6c4LAwFEolJqORirIyzpWV4ebuztCRIzl68CBjJ03C1sYGia5ZtTMlJWjUajx9fAiPjMTRxaXrtQF095e2dC/D6pqb2ZyVha+/Pw5OToRGRuLr69vV/k2S5N7FPf1/Ow0Gmhob2Z+bi7OnJ4b2dozt7QSFhRE9alTXUnn3wRsF8N2+fYSFh+MTEIBksdDU0MDxgoKuWUClkobGRmrLyvjo/fcHXGmWy/l+4eX6+nokSZL3DXp6el52Rs9isXD06FE6OzuvKfzt27ePu+66i9dff51f/epX/bqfrjcB8IeMRiMjRoxgwYIFvPzyy9dzuIIgEwFQEC7DaDSye/duMjIyyMnJwWg0MmfOHNLT05k2bZq8BGwwGOQOJI2NjahUKrklXV++gVdUVHD69GlGdXeeuNL7rMvJwcbLi8jRo7G2tsaqu/1bu15P/rff4jdkCENHjEBpZYWlu/bc8YMHsXdw6DrsoVBg7Ohg3/btTL3jDhQ2NpSeOIGjkxN+gYHs2rwZK6WSzu49d2HR0fIyb21FBdExMdRWVmI2mejo6KC8tJS48eNp0WoZMWYMDo6OFB48SFRMDO5eXhw7dAiAsOHDqaisxNDaSodeT/jw4QwJDUWhUNCm13OmuBhNXR3BoaGEDB0q1/D7Zts2kiZPprKiguqzZ7GxsyN86FC8/f27ZqW6D6/0FNFWdIe4irIyaqqq0KjV+AYEMH7yZKy6u39YWVl17c8zmbCytobuHsk9+yyPFxRwLC+PkPBwPHx8sHFwoE2vx8raGi8PD5xdXXFydKTy7FkaNBpix42jra2NoiNHMBmNhISHc/L4cTo6O6ksLuajDz7A2dm5z352+lNPuaWepeKOjg48PDzkfYM9f296wl9HRwdjx47tdfg7dOgQaWlpvPLKK/zmN7/p98MUvVkCvpR77rkHa2tr/vOf/1ynkQrChUQAFIQrYDab+eabb8jMzCQ7OxudTsesWbNIT09n+vTp8qxfz7KYWq2moaEBJycneWbwUs3pr4QkSZSWlnL+/Hni4uIuOtxyJfc/ffo0W3NzwdW166CItTVWdM1IFR87Rl11NWMnTcKpuz+yxWLhyHff4eDgwPAxY1AoFFScOUNLUxMj4+OpOHOGPV9+SeiwYXS2tzN8zBicXVyoKisjODKSo4cP4+HvT/GRI7h5e9Pa1MTw6GjUlZWMSkhgz5dfYmNtjaNKhYOTE3FJSVScPcv5ykpGxcejUCj4dvdusFiIiY8nOCwMCaitrqa8tBQUCiKjovDpbgUoSRJms5nzlZV8lZ3N8NGjCQoLIzAoCGtra5Td/X7l/yoUGNrbKT97lrrz57FSKvENDCQoNJR9u3bJnUkUdIU+a6USFIquci7ds6V1dXVUl5ejbWykpqqKO9LS8Pb2xmQ2IykUKCWJ5tZWGhsb0be0oG9ro7aigknTplFdUUGLVsuo2FjsHBzYl5uLjYMDDefO8fry5bi4uFz1z8lApdfr5bZ0LS0tuLi44O3tTWNjI0aj8ZrCX0FBAampqSxbtoylS5fesJO0SUlJJCYm8u677wJdf3+Cg4NZsmTJJQ+B/JDZbGbkyJHMnj2bt95663oPVxAAEQAF4aqZzWYOHDggh0GNRsPMmTNJT0/njjvuQNUdokwmkzwLotFocHBwkPcMOjs7X9GblcVi4fjx47S0tBAXF3dNM4qSJFFcXMz2vXvlIKi0tkZBV7u4gr178Q8OJnLkSLkP7rGDB7GysWFkXBwWi4VNn32GrbU1AcHBqGtquD01lbOnTuHg6IjRYEACdFotvoGBnCgsZFRCAof37iUgOJiio0fx8PGhqa6OmMREqs+coa2tDW8/P9p1uq4TuEOGcHj/fs6cOsW4iRMZMXIkbW1tlJeUoK6txT8wkLBhw7Dr3nNpMpmoqaqi+uxZDEYj3r6+qGtqSLnjDhRKpdx2zdy9v6+lqYmqigo0ajV29vYEBgXhHxzc1efXYkFdXU1TfT1RMTFyMWZjd5FnyWKhvr6emooKGjUa3D09CQgJQVNbi529PUFhYdjY2CB1n/xVKpUoJAlTd8mYLTk5WNnY0KTREBAWRnh4eNfs53ffobC1RQU8+9RTA+bAx/XQ2dlJXV0dZWVlGAwGHBwc5ENVrq6uVxXgjh07xuzZs3n66af53e9+d0PLqKxbt45FixaxZs0aEhMTWbFiBevXr6e4uBhfX18WLlxIYGAgy5cvB+BPf/oT48ePJzIyEq1Wy+uvv05OTg55eXnyoS5BuN5EABSEa2CxWMjLyyMjI4Ps7GyqqqqYMWMGaWlpzJ49W57JMZvNaDQa1Go1Go0GW1tbeWbwcl0XjEbjBWUx+qoEjSRJlJSUsH3vXsyOjoSNGIG9oyOSxULpiRPUVlYSN348Lu7uWCwWTuTn09zYiMlkQuXsjLahgWmpqZQeP47K1RWLyYTJZKJVqyUwLIxjBw8SOnw4+uZmNGo1weHhVJSV4enrS5NGg7WNDRXnzuHl64tGrUZbV8fsu+6iXq2mproaR3d3YuPi0LW0cO70aWysrQmOjMQvIACFUomho4PqigpqupeV/QIDGRISgqNKRVV5OXq9nmHR0UiShMlg4Pz586irq+nQ6XByc2NIcDA+vr5Yumfyelq5SXQVkh6fkoK1jQ023bOFPQWZW5qacPPwwC8oCB9fX5RKJY0NDRQVFDDxtttQ9rTk615it7GywgK0arV8kZGBSqUiYeJE/IcMQdc9M7h727auHs22tix+6CECAwMHXN3JvtTzgUav1xPbXWKnZ99gT/Fpb29vPDw8frQGYFFREbNmzWLJkiW8+OKLA6KG3sqVK+VC0LGxsbzzzjskJSUBkJKSQmhoKGvXrgVg6dKlZGVlUVtbi7u7O2PHjuWVV14hLi7uBr4CYbARAVAQ+kjPnqaeMHjmzBluv/125s2bR2pqKm5ubii6w0ZP14X6+nqsra3lmcGeazo6OsjPz8fBwYExY8ZclzZ1kiRRXl7Otj170EsSIdHRqFxd0bW0cOTAAZxdXRk+ZgwlR45w6tgxAsLCmHDbbZw+cQKLxcKQ0FCOHTpE6NChtGi11J0/T+iwYTRqNNTX1KBSqXBQqbpm22xtsXd0pLW5GU8vL/R6PRaLBRdPT/L376ehvp6EKVO6Zs86O7GYzQwJCSEkIgI7Oztam5s5X1WFuroapVKJf1AQgSEhF5TikSSJA7m5BAwZQnNzM40aTVeB44AA/IcMQaVSyTNzSBLm7vp8PcvHleXltOt0DAkPp7aqirqaGswmE14+PvgOGYKHhwd0f/9srKwwmc18s20b8RMm4OzsLB8oUSoUKBQKqiorqThzhqpz5xgSGkrylCldpWokiU6Dgd3btqFtbGTMsGHMnjkTjUaDTqeT6+z19+ny602SJI4fP05raysJCQkXfKCxWCxotVr574TRaMTT01MOhN8PxSUlJcyaNYuHH36YV155ZUCEP0G4GYkAKAjXgSRJnDx5koyMDLKysigqKmLq1Kmkp6eTmpqKl5cXiu6adI2NjajVaurr61EoFLi7u9PY2Ii3tzcjRozolzZctbW17PjmG2q0WvwiIvDy8+PMyZNsy84mcepUxk6cSFlxMRq1mvhJkziwfTvxycnk7dtHdFwcNRUVNNXXY2Nri5WNDUaDAaPRiLGzE6VSiaOjI53t7Ti4uNDZ1oaHry9NdXU4qVQEDBlC9vr1qJyd8fTxwdXTE1c3NySTCX1LC216PSqViiGhofgGBmJlZSWfTu40GNDW11NfU0NdbS1niouZePvt+AYG4uHuDlZW0L0fz2yxoFAqu9rhdZdesVYqaWtro7qigj1ff01oRAROzs74BgTgFxiIvZ0dFsDc3cu3p0yMwWTiZEEBbh4eBIaGdi0XdxdNPldWRn1tLV6+vtja26NtaGDcxIlyDUKLxcLXX3xBfW0td6emMj8tTf4+/LDOnrOzsxwGe7uHdCCQJIkTJ07Q0tLC2LFjf7SGpiRJcjH2+vp6dDodJSUlaLVakpOTWbx4MQsWLOCvf/1rv7aoE4RbjQiAgnCd9RzC6AmDhYWFTJw4kfT0dObNm4evr68cBouKiqitrUWpVKJUKuWZwf7qx9ra2sq+gwcpPHmSsnPnmDJ7NjWVlbRqtYxOSKBZq6Xi1ClGjRvHke++w8vPD5vufW3tej0GgwGT0YjJaITukGalUODg5IS5uz1du16Pm6cndra2aOrqaGltpaaqirQFC9BqNKhratDrdNg6OmLn6NgVDD08cHF1he7Z00a1Gl1rK9bW1nj6+ODt58f5qirc3NwICguTD3oAch1AhVKJZLHQotVSr1bTWF9PR1sbtg4ONGo0DI2KYlh0NArAYDJhZWWFVXdpHCu69hH2dBCprqigtqqKxIkTae/ooKK8vOswiZUVQWFh+AcG0qTRUHTsGJOmTeuqR2hlhaGzk00bNtCu1fKbxYsv2ysWuk6XajQa6urqaGhowN7eXq6zd7X75W6kqwl/l9Le3s6GDRtYs2YNR48excPDg0cffZT09HRiY2Nvmq+DIAw0IgAKQj/qWXbNzMwkKyuLgwcPMn78eNLS0mhvb+ett95i586dDB8+XF4SU6vVmM1meSbI09PzuiwJf5/JZOJEURH78vLoUChw8fKisqwMe0dH/AIDKTl2DJ/AQEydnehaWmhvb8fY2Yler8fQ0YHFYukKUNbW2NraYm1tja2dHU4qFSaTCRtbW9w8PVHX1FBbW0urRkPipEn4DhmCt48PSisrdC0tNGg01FRWUltTQ1tbG46OjvgPGUJIeDh+PYWeu/sO792+nZQ77+xaZlUoMJtMtDY3o21spKG+Hl1rKwqFAmdXV9y9vPDz9cXe0ZH6ujpKi4pInjoVZfeSsMlsxrr74Ieyu96gWaHArntce3fuZEhYGE0aDQBDgoPxDwrCzs4OiyTRqtVS8N13TEhJwdbeHkv3fsRP33sPP29vfrN4MREREVf8/ejZQ/r9/XI9Hw7c3d0H7EyYJEkUFRWh1WpJSEjodfecqqoqZs6cSUpKCrfddhuff/45W7duZebMmWRkZPTxqAVhcBABUBBuEEmSqKqqIjMzk7fffpvq6mqSk5O58847SUtLIyQkRC5x0tLSIrekMxgMeHl54evri5eX13UPg/X19Rw4fJiS8nKMSiWN9fV4+PjQ2NAAFgtGo5EWrZbWpiba9HqMJhO2dnY4ODhg7+iIo5MTdnZ22Dk44ODoCIChsxNdWxvuXl44OzrS0d6Om4cHLVotHW1tKJRKnF1dcfPwwM3DAxd3964izd3dN7RaLSajETc3N5wcHTl17Bh29vbY2dnR0tKC2WRCqVDg5OKCm6cnHj3LypKEha5ZQavunsffbN9O0tSpODg4yPsDga76f0olVkolHQYDjXV1VJ47R97evUSNGUPEsGF4BwTgYG8vF4UG0Ot0fLdnD8nTpmFnb49SoaD89Gk0FRUEeHkxY8YMAgMDe/39sFgsNDU1yUvFZrMZLy8v+cNBb9uo9bWebRCNjY0kJCT0ej9jTU0Nd955J1OmTOG9996Tf947Ojqora0lNDS0D0ctCIOHCICCcAOZzWYee+wxcnJy+OijjygtLSUzM5M9e/YwevRo0tLSSE9Pl1u+Sd37zHpmBjs6OuQ3f29v7+v65m82mzl16hQH8vM5efo0moYGDAYDHe3tNHQf/LCYzTipVF3By90dN09PHBwdsXNwwNHRsSsQKZWcPXsWa2trvL295aLRHr6+uLi64uDo2LUkbjZjsVgwdHbS3t5Ou06HXqejXa9Hp9PRptOhb2ujqamJxro6EiZOJHDIEAKHDMHOweGCPsc9i4Sm7j14Nt11/Q598w1DwsLw8vPD1soKS/e1bTodmvp6tBoNTY2NWCuVuHp5UV1RQUxCAv6BgZjNZnkGEknCJEmYOjrYn5vL2O4OK+rqaurKyxkREYGttTWjR4/Gv7ubSl/o+XDQs1+uvb0dDw8P+eehr06O92ZcfRH+1Go1s2bNYty4caxdu/a6f9gRhMFEBEBBuIEKCwt56KGHyMnJITg4GOh689RoNGzcuJHMzEx5SbinP/GIESPkMKjX6+WZwba2Njw8POS6ateznEhHRwdHjx4lZ/NmduzYwfGCAlAocPfwwDcwEHdPT7x8fXFycUHl7Iy9gwNOKhUKpZL6hgZc3dzw9/OjprqaRrWa4MhIjJ2dGI1GzGYzSJIcruzs7bHvDpAOKhVOTk44ODlhY2eHxWTim23bGD1uHEaTCa1WS5tej5NKhae7Oy6urtjZ2SFJUtdpX4ul6+QvUHbqFG2trYR1n2JuaGigpakJs9GIjb093t7eOHt64u3lhVKppOC773B2cyM0MhLr7sMlJqMRG2vrrpZzbW0c2L2buKQk2nQ66isrGT1sGNFRUZSWljJq1Ch8fX2v2/cE/n/R5bq6OlpbW3F1dZWXivurp3BPvcmGhoZrCn8ajYbZs2czcuRI/v3vf/fbzOaqVavkci4xMTG8++67P7pXs8dnn33GggULSEtLIycn5/oPVBCukQiAgnCDWbr3mV2KJElotVo+//xzMjMz2bZtGyEhIaSlpTF//nxGjRol37fnzV+tVqPT6eSZIB8fn+s6E9Tc3MzPfvYztC0tODo5YevsjJu7Oy7u7jg6OmJlZ4ezszNKpRJ1QwNeXl4MCQzEYrFQsH8/ydOnd11nY4OdjU1XT9zvvX56WrZ9b3m25zTukYMH8fD2JigsrOtai4VOg4GW5uauMNjejp2tLbbW1lhZW2MxGmnp7ilcVV7OsJEju2YsnZ1x7f56WXUXx7Z09wpWAKUnTmA0mRgZG9u1v7Fn5k+hwGA2YzEY2LtjBx4+PigNBuKio5mYnIxWq6WoqIgxY8bg7e193b4Hl9LTr7quro6mpiZUKpW8j1SlUl2XwxM9NSbr6+tJSEjodehsbGwkNTWVsLAw1q9f32+1EdetW8fChQtZvXo1SUlJrFixgg0bNlBSUvKj7RfLy8uZNGkS4eHheHh4iAAo3BREABSEm0hLSwubNm0iMzOTrVu34ufnJy8Tx8fHy2Gwvb1dnhlsaWnBzc1Nnhm8nrXlOjs7OXPmDPnHj1NRXY1ZqcTawQEUCs6ePYujvT3OKhUWi4XiY8cICgvD3dMTaxsb7LpLyNhaW4NS2dV/V6lE2V1+pee1mU0mzJLE+XPnaGpoIGL4cAxGI2ajsav8jMFAzz9rZrOZjs5OzBYLkiShcnXF1cUFdVUV01NT5c4dUndB6J59f0qFAqn7/mdKSmhtbiY+Kalr5hXkQy4WiwWNWs32jRuJGjaMO6ZNY0x3z+Xq6mpKSkqIiYnB09Pzun3Nr4TRaJRPFGs0Guzs7OQPB311oliSJE6dOkVdXd01hT+tVsvcuXPx9/cnKyurX5exk5KSGDduHCtXrgS6vs9BQUE89thjl23pZjabmTJlCg899BDffPMNWq1WBEDhpiACoCDcpHQ6HV9++SWZmZls2bIFd3d3eZk4MTHxgs3yPTODzc3N/bYsKEkSarWa7w4fZs++fTi5uOATHIyLuzulxcVEDB9OQHCwXDrG2NnZ9V+zGYvRiLl7v56le0lYplDQ3NTEudJSxk6ciJ2dHdY2Nl0nju3s5FnEnn/aembxetqQ7duxg5Dhw7tOA7u54ebqiqOjY1ef3+6QqQSUSiVlp09TW1VF3IQJ2NnYyK3hmurqqDt/Hjo7GREZScwP9vZVVlZSWlpKbGxsVwHpAaSnEHnPiWKFQiHPDPa23ND3w9/YsWNx7D7sc7VaWlpIT0/H1dWVjRs39mshbIPBgKOjIxkZGaSnp8u3L1q0CK1Wy8aNGy95v5deeomjR4+SnZ3NAw88IAKgcNMYGMfFBEG4aiqVinvuuYd77rmH9vZ2vvrqK7KysvjJT36Co6Mj8+bNIy0tjQkTJhAcHExwcLAcgurq6igtLcXZ2RlfX198fHx6/aZ9OT21DVUODjzz+ON4eXmhVqspKS2lTqmk8dw5tGo1jq6uuHp44OrujtLaGiwW6JmR6l6G7emgoVQoaGxo4Nzp08z+yU+w/UEnkB6W7j2EFklCSddMjsls5syJE8yYOxdXNzd0ra00NTVxqrQUKysr3NzccHZ27loeVSopO3OG2spKEqZMoVWrpaq+nrbGRuyUSoZHRnL7nDlyDcfvKy8v5+zZs8THx+Pm5tanX9O+YGVlJX8A+H4HjpMnT2I0GuVDRV5eXle0706SJEpLS1Gr1SQkJPT650in08k/uzk5Of3eBUWj0WA2my/ap+nr60txcfEl77N3717ef/99CgsL+2GEgtC3RAAUhFuAg4MD6enppKen09HRwY4dO8jKyuLnP/85VlZWpKamMn/+fCZPnkxQUBBBQUEYDAbq6+tRq9WcPn0alUolBwOVSnXNYzp37hxnzpwhLi5OngULCAggICCAaVOnIkkSzc3N1NTUUF5ZybmCAto6OrAoldg7O+Pg5ISzqyuOrq7yQYvGxsau+nrTpmFlayvvEQTkIs1S9+/NkiTv5TMajRzas4cRcXGoXF2xsrLq6sHr7o5kNtPaHQbPlpXR3t5Oo1pNS309I6KiOHPoEEEBAUwdPZqwsLAfnTUtKyujoqKCsWPHyn2gBzKlUomHhwceHh4MHz5cPmFeVlbG8ePHLzhRfKkafj1Fzmtra69p5q+trY2f/vSnWFlZ8fnnn/fbgZVr0drayi9+8Qv++c9/4uXldaOHIwhXTSwBC8ItzGg0snv3bjIyMsjJycFoNJKamkp6ejopKSnym7rRaJQPDDQ0NODg4ICPjw++vr5XfWBAkiTOnDlDVVUVcXFxuLq6XtWYOzo6uooeazTUqNXU1tfT1tGBwWSi5ORJwocPx8nFBRt7exTdy762NjZY2dhgY22NUqlEoVSi6B5LZ2cnB3NziYiOxtnNDbPRSEd7O5LJRGd7O2aDAbPRiK21NfY2NqicnLACbG1scHFxkWdIf6zm4vdf89ixY3F2dr6q1zwQ6fV6+WeipaUFV1dXeanY0dFRfs3V1dUkJCTg5OTUq+fp6Ojg3nvvRa/Xs3Xr1hsWnK92CbiwsJC4uLgLfiYs3S0GlUolJSUlV1XsWxD6mwiAwoD35z//mc2bN1NYWIitrS1arfa/3keSJF566SX++c9/otVqmThxIv/4xz8YOnTo9R/wAGUymdi7d68cBnU6HbNnzyY9PZ3bb79dnnUxmUzygYH6+nrs7OzkEOTi4vKjYbCn/ltDQwPx8fG9DgU/9hr0PXUA29poa2ujRaejo7OTjs5OOjs7MZnNmM1mpO5lYGN3azofHx/sbGxwcnLC2ckJp+5fzs7Ol+yz+/0ae2q1ms7OzguWR3tOpvbsf+uZBeuL2dOBprOzUw6DjY2NODk5YW1tjU6nY9y4cb1+zZ2dndx///1oNBq+/vrrG75knpSURGJiIu+++y7QFeiCg4NZsmTJRYdAOjo6OH369AW3vfDCC7S2tvL2228zbNiwG1aHURCuhAiAwoD30ksv4ebmRlVVFe+///4VBcDXXnuN5cuX89FHHxEWFsayZcs4duwYRUVF/b63aCAym80cOHBADoMajUbuQDJz5kw5uPUcGFCr1dTX12NjYyPPDP7w9KjFYuH48eO0trYSHx9/UyzjXakf1lzU6/Xy8qhWq6WpqemalkBvJkajkaKiIjTdbfBsbW3lrQNubm5XPFtsNBpZuHAhFRUV7NixY0Acllm3bh2LFi1izZo1JCYmsmLFCtavX09xcTG+vr4sXLiQwMBAli9ffsn7i0Mgws1EBEDhprF27VqeeOKJ/xoAJUkiICCAp556it/+9rdAV606X19f1q5dy3333dcPo715WCwWDh8+TEZGBtnZ2Zw/f54ZM2aQlpbGrFmz5CU5i8VCQ0ODfIjk+4cJnJ2dOXr0KCaTibi4uFt+5qOtrY26ujrKy8sxGo24uLjg7++Pt7f3LRV8L6Vnn2NPqZfGxkZ5thi44ETx5ZbMTSYTDz30ECUlJezcubPfayT+mJUrV8qFoGNjY3nnnXdISkoCICUlhdDQUNauXXvJ+4oAKNxMRAAUbhpXGgDLysqIiIigoKCA2NhY+fapU6cSGxvL22+/fX0HehOzWCwcOXKEzMxMsrKyKCsrY/r06cybN485c+bIMzw9/Wh7ZsRMJhO2trZERUXh1d0541ZmsVg4ceIEra2tjBw5Ul4qbmpqwtnZWQ7Gfb0EfqOdPXuWc+fOXXKfY0/R8p4PCEajEU9Pz4uWzM1mM4sXL6awsJBdu3Zd9+4ogiBcmjgFLNxyamtrAS5ZzqHnz4RLUyqVxMXFERcXx8svv0xRUREZGRmsWrWKJUuWkJKSQnp6OqmpqXh6etLc3MzBgweZNm0aKpWK4uJizGazHIA8PT1vuTBosVg4duwYbW1tjB07Fjs7O1xdXeWT1RqNBrVaTVlZmXyYpmeW9Hp03+gv5eXllw1/0FX2x93dHXd3d4YNG4ZOp5NnSY8ePcrKlSuZPHkyp0+f5vDhw+Tm5orwR1cgtrKywmg09lvHE0GArnqngtDvnn32WbnX6+V+Xa72ltA/FAoFI0eO5KWXXqKwsJDjx4+TkpLCBx98QEREBHfccQe33XYb+fn5jB07lhEjRjB58mTi4uKwtramuLiY3bt3c+zYMerq6rp6/N7kzGYzR44cob29XQ5/32dra0tAQABxcXFMnTqV8PBw2traOHz4MHv37qWkpAStVsvNtvBy7tw5ubbhlZxwVigUODs7ExERQXJyMuPGjWPs2LF8+umnfPrpp6hUKj755BNOnTrVD6MfuEwmE1ZWVmi1Wn7xi1+QnZ19o4ckDCJiBlC4IZ566ikeeOCBH70mPDy8V4/t5+cHgFqtvqA7g1qtvmBJWLhyCoWCYcOG8fzzz/Pcc8+xadMmFixYQGBgIJs3b2bWrFmkpaUxb948AgMDcXNzY9iwYfLS6KlTp+js7JT3h11pkeGBxGw2U1hYiNlsZuzYsf91tsba2ho/Pz/8/Pwwm83yXrnCwkIUCoU8M+ju7j6gZ0nPnTtHWVnZNdU2dHNzQ6fT0dnZyXfffceRI0fIyclh2bJlfPnll9x22219POqBTZIkJEnC2tqa1tZWxo0bR2xsLNbW1lgsFvlDsCBcT2IPoHDTuNpDIL/97W956qmngK4WUz4+PuIQSB/45ptvSE1N5fe//z1PP/00lZWVZGVlkZ2dzbfffktCQgJpaWmkpaUREhLS1T9XktDpdPKewfb2dnl/mLe394Bf+jKZTBQUFADIM5y99f3uGz0zoz3B2NPT87IHJ26EiooKzpw5Q3x8/FXXc+xhsVh44YUXyMjIYNeuXReUYmptbcXOzu6WPzTUQ6/XX7Av1Gw2k5qaioODA1lZWfLtZ8+eJSws7EYMURhEBu7HTkHoVlFRQWFhIRUVFfIsTGFhITqdTr4mKipKXj5RKBQ88cQTvPLKK3z++eccO3aMhQsXEhAQcEGBV6F3XF1defvtt3nmmWdQKBQEBwfzxBNPkJubS0VFBb/4xS/Yvn07MTExTJkyhTfeeEPuNBIZGcmECRNISkrCxcWFiooKdu/eTX5+PtXV1RgMhhv98i5iNBrJz89HqVQSHx9/zTOXPd03oqKi5CVzW1tbTp06RW5uLkeOHKGmpgaTydRHr6B3Kisrrzn8SZLEyy+/zLp169i+fftFdTidnZ0HTfg7d+4cDz/88AW1A2tra2lsbGTp0qUAZGdns3jxYkaNGsWECRM4cuTIjRquMAiIGUBhwHvggQf46KOPLrp9165dpKSkAF2h78MPP5SXlXsKQb/33ntotVomTZrE3//+d4YNG9aPIx+8JElCo9GQk5NDZmYmO3fuJCoqirS0NNLT04mKipKXuHpKqqjValpbW3F3d5eXRy/Vfqw/GQwG8vPzsbOzY8yYMdd1dq5nlrRnZlCv118wS9qfQamqqorS0lLi4uJ6XZxZkiReffVV1qxZw86dOxk1alTfDvJHrFq1Si7lEhMTw7vvvktiYuIlr83KyuIvf/kLp0+fxmg0MnToUJ566il+8Ytf9OmYvvnmGw4fPiyHvR4TJ06kvb2d4cOHU1FRQWRkJI888gg///nPue222/jggw/6dByC0EMEQEEQritJkmhqauLzzz8nMzOTbdu2ERYWRlpaGvPnz2fkyJHyHrj29nY5ADU3N+Pq6ip3IenvAt6dnZ3k5+fj6OjI6NGj+32f3g9bsbm5ucnB+Hp+Laqqqjh16hTx8fHXFP7+9re/8be//Y2dO3cSExPTt4P8EevWrWPhwoWsXr2apKQkVqxYwYYNGygpKcHHx+ei63Nzc2lqaiIqKgpbW1s2bdrEU089xebNm5k5c+Z1GePzzz9PQkICd911F3l5ebz99ts0Njby3HPPERkZia+vL88++ywGg4E33nhjQO8RFW5eIgAKgtCvmpub2bRpE1lZWWzduhV/f395ZjAuLk5+s+vo6KC+vh61Wo1Wq8XFxUXuQnK9iy13dHSQl5eHi4vLBQH1Runo6JCDsVarvW61BqurqykpKSEuLg53d/dePYYkSaxcuZLXXnuNr7/+moSEhD4b35VISkpi3LhxrFy5EujagxgUFMRjjz12UTu3y4mPj2fOnDm8/PLLfTImk8kkbx0oKirinnvuISwsjMcee+ySIXPv3r3MmzePd955h5///Od9MgZB+CERAAVBuGF0Oh1btmwhKyuLLVu24OHhwbx580hPT2fcuHHykqvBYJADUGNjIyqVSp4Z7Otiy+3t7eTl5eHu7k50dPSAO41pMBjkmcGGhgacnJzkMKhSqXo93vPnz1NcXExsbGyv27JJksR7773HH//4R7Zu3cr48eN79Ti9ZTAYcHR0JCMj44L9vosWLUKr1bJx48Yfvb8kSezcuZN58+aRk5PDjBkz+nR85eXlhIaGcvjwYX73u99ha2vLI488wl133QXAyZMnycrKYuXKlTz66KMsW7asT59fEL5PBEBBEAaEtrY2vv76azIzM9m0aRNOTk7MnTuX9PR0kpOT5RkUo9Eozwx+PwD5+vri5OR0TYGtra2NvLw8vLy8LtinOFCZTCY0Gg11dXVoNJoL+vL+sFfzj+mr8Ld27Vqee+45Nm/ezOTJk3v1ONfi/PnzBAYGsm/fPpKTk+Xbn3nmGXbv3s133313yfs1NzcTGBhIZ2cnVlZW/P3vf+ehhx7q07H99re/pbi4mE2bNgFQWFjIb3/7W6ysrFi8eDF33XWX3JIxIiKCRx55pE+fXxB+6OYqxCUIwi3L0dGR9PR00tPT6ejoYMeOHWRmZnL//fdjbW1Namoq8+fPZ9KkSQQEBBAQEIDJZJJnw8rLy7G3t5dnBq+284ZOpyMvLw9/f3+GDh064MMfXFxrsKdXc0FBAUql8opqDdbU1FBcXExMTMw1hb9PPvmEZ599li+++OKGhL9r4ezsLFcW2LFjB08++STh4eHyIbO+0tnZKf8+NjaWFStW8OSTT/Lee++hUCjkPbG3ej9pYWAQM4CC0McaGxt57LHH+OKLL1Aqldx99928/fbbqFSqy94nJSWF3bt3X3Db4sWLWb169fUe7oBnNBrJzc0lIyODnJwcuXZaeno6KSkp8ulYs9kst2G72tmw1tZW8vLyGDJkCBERETdF+PsxPb2ae5bNJUmSaw16eHjIS+u1tbUUFRURExODp6dnr55LkiTWr1/PY489RlZWFnfccUdfvpSrcq1LwD1++ctfUllZyVdffdWrcVgslosCd0+w3LFjB66urlhZWaFUKjl58iSPP/449fX1fPLJJ4wcObJXzykIV0sEQEHoY7NmzaKmpoY1a9ZgNBp58MEHGTduHJ9++ull75OSksKwYcP405/+JN/m6OjY684LtyqTycTevXvZsGEDOTk56PV65syZQ1paGtOnT5dPx35/Nqy+vh4rKyt5mdjNze2CgNfc3Ex+fj4hISG97j4zkEmSRHNzs1xqx2g04uXlhZ2dHVVVVcTExODl5dXrx8/KyuJ//ud/WLduHXPmzOnDkfdOUlISiYmJvPvuu0BXGAsODmbJkiVXfAjkoYceoqysjNzc3GsayxNPPIGPjw/BwcGcPXuW999/ny1bthAdHX3BdSdPnuTQoUMsXLjwmp5PEK6GCICC0IdOnjxJdHQ0hw4dkk8/bt26ldmzZ1NVVUVAQMAl75eSkiIvCQlXxmw2s3//fjIzM8nOzqaxsZE777yTtLQ07rjjDvlwiMVikduw1dXVXdCGTalUUlhYSHh4OCEhITf4FV1/PbUGy8rK5K/FtdQa3LRpEw8++CD//ve/B0yR9XXr1rFo0SLWrFlDYmIiK1asYP369RQXF+Pr68vChQsJDAxk+fLlACxfvpyEhAQiIiLo7Oxky5YtPPvss/zjH//gl7/8Za/HUV1dza9//Wusra05cOAAw4cPZ/fu3fj4+DB9+nQcHBxISEjAx8eH+fPn99XLF4QrJgKgIPShDz74gKeeeoqmpib5NpPJhL29PRs2bLjsP/QpKSmcOHECSZLw8/Nj7ty5LFu2DEdHx/4a+k3NYrFw6NAhOQyeP3+eO+64g7S0NGbNmoWzs7N8nVarRa1WU1tbi8lkwtXVlfDwcDw8PG54uZf+UFdXx7FjxxgzZgyOjo5yMP5+EW5vb+//Wmtw69atLFy4kA8//JB77rmnn0Z/ZVauXCkXgo6NjeWdd94hKSkJ6Pq7Fhoaytq1awF44YUXWLduHVVVVTg4OBAVFcXjjz/Ovffee1XPKUnSZbcO6PV6Ojs7mTt3Lu7u7owaNYqDBw/S2tpKYmIiq1atuqbXKwi9IQKgIPShv/zlL3z00UeUlJRccLuPjw9//OMf+fWvf33J+7333nuEhIQQEBDA0aNH+d3vfkdiYuIF/UGFK2OxWDhy5AgZGRlkZWVRXl7O7bffTlpaGnPmzMHV1ZXs7Gyqq6u58847sVgsqNXqAd2Tt6/0hL/Ro0dfVBS5vb1dPlDz/bqLPj4+F30Q2blzJ/fddx/vvfceCxYsuOn3TF4rs9ks/7x0dnai1+svOFBjNpuRJIn09HRGjhzJa6+9BnTtbx3ofbCFW5c4BSwIV+DZZ5+V/9G+nJMnT/b68X/1q1/Jvx89ejT+/v7cfvvtnDlzhoiIiF4/7mCkVCqJi4sjLi6OV155hRMnTpCRkcHKlStZsmQJiYmJHDp0iD/96U9ERkaiUCgYNmwYLS0tqNVqTp06hcFgwMvLC19fX7y8vG6JMFhfX3/Z8Afg4OBAcHAwwcHBF9RdPH36NE5OThw6dIjk5GT0ej0LFixg5cqVIvzR9YGj5+fjxRdf5MCBAxQVFfHggw/yi1/8gmHDhsl/PnPmTDIyMrBYLEiSJMKfcEOJGUBBuAL19fU0NDT86DXh4eF88sknvVoC/iG9Xo9KpWLr1q3XrR3VYCNJEu+88w5PP/00o0eP5ujRo0yePJn09HTmzp2Lj48PCoUCSZJobW2VD010dHTg5eUlL4321CO8mdTX13P06FFGjRqFr6/vVd23p+7io48+yu7du7GxsWHSpEn88Y9/JDExcdAHwB5PPvkkGRkZPPPMM/j6+vLQQw8xf/58Hn30Ubkg9oYNG/jlL39JVVWVvC1BEG6Um+9fMkG4Aby9vfH29v6v1yUnJ6PVasnLy2Ps2LFA13KZxWKR9yBdicLCQgD8/f17NV7hYv/+97/5/e9/T3Z2NrNnz+bs2bNkZmbyn//8h6eeeork5GTS0tKYN28eAQEBuLi4EBERgV6vR61WU15ezokTJ/D09MTX1xdvb++bYgZHo9Fw7NgxRo4cedXhD8DGxoaAgACef/55CgoKmD9/Pu3t7cycORNnZ2feeeedQX+IITs7m82bN/P5558TGxvLjh07aG9v56uvvqKuro4//OEPjB8/nrCwMB5++GER/oQBQcwACkIfmzVrFmq1mtWrV8tlYBISEuQyMNXV1dx+++18/PHHJCYmcubMGT799FNmz56Np6cnR48eZenSpQwZMuSi2oBC723evBk7OzumT59+we2SJFFZWUlWVhZZWVns27ePcePGyS3pgoOD5VkuvV4vzwzqdDo8PDzkfXJXe4K2PzQ0NHDkyBGio6Px8/Pr9ePk5+czd+5cXnzxRZ544gkUCgUGg4Fdu3YRGhrK8OHD+3DUNxdJkti1axfFxcU8+uijZGdn8/DDD/Pxxx8TFhZGfHw8aWlp/PrXv2batGk3eriCIBMBUBD6WGNjI0uWLLmgEPQ777wjF4IuLy8nLCyMXbt2kZKSQmVlJT//+c85fvw4er2eoKAg5s+fzwsvvCDqAPYzSZKoqakhOzubzMxMvvnmG8aMGUN6ejppaWkXFIlub29HrVZTV1dHS0sLbm5uchj8bydo+0NP+BsxYsQ1zSQfPXqUOXPm8Mwzz/DMM8+IJd9L0Gq1tLe3Y29vz9y5c7nrrrt48skn0ev1JCQkcObMGZYtWyZ6+woDigiAgiAIlyBJEhqNRg6Du3btIioqSg6D3+8V3NHRIc8MNjc34+LiIrekuxFtvRobGyksLCQqKuqytSevRFFREbNmzeKxxx5j2bJl/Rr+Vq1aJZdyiYmJ4d133yUxMfGS1/7zn//k448/5vjx4wCMHTuWv/zlL5e9vi99v/xLTU0NM2bM4MUXX+SnP/0pTU1NPP/88zz44IP9MhZBuBoiAAqCIPwXkiTR1NTExo0bycrKYtu2bYSHh5OWlsb8+fOJjo6Wawh2dnZSX1+PWq2mqakJZ2dnuQtJf9R17KvwV1JSwqxZs3j44Yd55ZVX+jX8rVu3joULF7J69WqSkpJYsWIFGzZsoKSk5JInmO+//34mTpzIhAkTsLe357XXXiM7O5sTJ04QGBjYJ2O6VJ2/npZvxcXFWFtb4+TkxIQJE5gyZQrJycmsW7cOi8UitnIIA5IIgIIgCFepubmZL774gqysLL766isCAgLkmcHY2Fg5DBoMBrm2XkNDA05OTvLM4I/1hu6tpqYmCgoKGD58+DUFn9OnTzNr1ix+9rOf8dprr/V7geykpCTGjRvHypUrga6gFRQUxGOPPXZF7dzMZjPu7u6sXLmyz9urffvtt4waNQqVSoWVlRXbtm3jgQce4N///jcpKSns3LmTRx99FJVKhY+PD1u2bOnT5xeEviICoCAIwjXQ6XRs2bKFzMxMtmzZgpeXl3yAZNy4cXJ4MhqNaDQa1Go1DQ0NODg4yDODKpXqmmfYtFot+fn5DBs2jCFDhvT6ccrLy7nzzjtJT09nxYoV/R7+DAYDjo6OZGRkXNBebtGiRWi1WjZu3PhfH6O1tRUfHx82bNhAampqn43t7NmzRERE8O2335KcnExubi4zZ87klVde4emnn5ZnBBsaGlAoFBcUgxaEgUaUgREEQbgGKpWKn/70p/z0pz+lra2Nr776iszMTO666y5UKhVz584lPT2d5ORk/P398ff3x2QyodFoqKur49ChQ9ja2sozgy4uLlcdBrVaLQUFBQwdOvSawl9lZSVz5sxh9uzZNyT8QVfZGrPZfFHJGl9fX4qLi6/oMX73u98REBBw0Ynva+Xm5ib3DIauZfIXX3yRp59+GugqQi5JEp6enn36vIJwPdz6jS8FQbjIqlWrCA0Nxd7enqSkJA4ePPij12/YsIGoqCjs7e0ZPXq0WNa6DEdHR+bPn88nn3xCTU0N//jHP+jo6GDBggUMHTqUxx9/nNzcXLnn85gxY5g6dSrDhg2jo6OD/Px89u7dS0lJCVqtlitZoGlubqagoIDIyEiCgoJ6PfaamhrmzJnDbbfdxqpVq27avsivvvoqn332GdnZ2dd8Grvn628wGABwd3cnLCyMrVu3ArB48WKef/55+dof6wcsCAONmAEUhEFm3bp1PPnkkxdssJ85c+ZlN9jv27ePBQsWsHz5clJTU/n0009JT08nPz+fUaNG3YBXcHOwt7cnNTWV1NRUjEYju3btIjMzkwcffBCz2Uxqairp6emkpKTI5WMsFgsNDQ3U1dVRWFiIQqGQZwbd3NwuCmXNzc3k5+cTERFxTeFPrVYzZ84cJkyYwHvvvXdDW9/1tN5Tq9UX3K5Wq/9rLcM33niDV199le3btzNmzJhrHotCoWDjxo188MEHuLq6EhsbS3t7O3q9ns7OTmxtbeXAJ4KfcLMRewAFYZC52g329957L3q9nk2bNsm3jR8/ntjYWFavXt1v475VmEwmvvnmGzIyMsjJyaGtrY05c+Ywb948pk+fLs9aWSwWmpqaUKvV1NfXI0mSHBQ9PDzQ6XTk5eURHh5OSEhIr8ej0WiYPXs2o0aN4pNPPhkQre6SkpJITEzk3XffBbq+FsHBwSxZsuSyh0D++te/8uc//5mvvvpKbr3WF/7zn/9QVFTEoUOHsLOzY+/evTQ1NXHnnXdSWVlJcnIyjo6OLFiw4Kq6/QjCjSYCoCAMIr3ZYB8cHMyTTz7JE088Id/20ksvkZOTw5EjR/ph1Lcus9nMvn37yMzMJDs7G61Wy5133klaWhp33HGHXDampwxNXV0ddXV1mEwmLBYLfn5+F5SguVqNjY3MmTOHiIgI1q1bN2Ba261bt45FixaxZs0aEhMTWbFiBevXr6e4uBhfX18WLlxIYGAgy5cvB+C1117jxRdf5NNPP2XixIny46hUqj4/bb1hwwYeeeQRli9fjlqt5vz58xw/fpzNmzfj7u7ep88lCNfTjf+oJwhCv+nNBvva2tpLXl9bW3vdxjlYWFlZMXnyZCZPnsxbb73FoUOHyMjI4MUXX+RXv/oVM2bMID09nTvvvBMPDw88PDxob2+nvr4ed3d3mpqayM3NxdvbGx8fH3n59EpotVrS0tIIDg7ms88+GzDhD7pmnevr63nxxRepra0lNjaWrVu3yj+HFRUVF4Tef/zjHxgMBn7yk59c8DgvvfQSf/jDH655PD17+ywWC1FRUfj5+TF79mx55lXs/RNuRiIACoIgDABKpZKkpCSSkpJ47bXXKCwsJCMjg1dffZX/+Z//Yfr06SQmJvLGG2+wbNkyHn30USRJorW1FbVaTWlpKcePH8fLywtfX1+8vLwuu5zb0tLCXXfdhbe3Nxs2bBiQfYyXLFnCkiVLLvlnubm5F/x/eXn5dR1LT7hTKpWMHj0ao9FIbm4uixYtuuDPBeFmIgKgIAwivdlg7+fn16sN+ULvKZVK4uPjiY+P589//jMnTpzg73//Oy+//DIRERFs374dlUrFnDlz8PDwwMXFhcjISHQ6HXV1dZSVlXHixAk8PT3x8fHB29tbnuHT6XT85Cc/wcnJqU9Oyg4mPTN9KpWKysrKGz0cQbgmN+c5f0EQesXW1paxY8eyY8cO+TaLxcKOHTtITk6+5H2Sk5MvuB5g27Ztl71e6FsKhQKlUklmZia///3vycnJYcqUKfzzn/8kPDycefPm8a9//Yu6ujpUKhURERFMmDCB8ePH4+LiQkVFBVlZWdx22228/vrr3HPPPVhZWbFx48Yb0qf4ZtYz0/fwww9zzz333ODRCMK1EYdABGGQudoN9vv27WPq1Km8+uqrzJkzh88++4y//OUvogxMP1q8eDF+fn788Y9/lG+TJImysjIyMzPJysoiLy+P5ORk0tLSSEtLw9/fXw4sVVVVrF69muzsbM6dO8fkyZO57777mD9/vpjJ7QWx50+4FYgAKAiD0MqVK3n99dflDfbvvPOOXMIiJSWF0NBQ1q5dK1+/YcMGXnjhBcrLyxk6dCh//etfmT179g0a/eBjNptRKpWXDR2SJFFZWSmfJt6/fz/jxo2TW9L5+vpy//33o9FoeP/999mxYweZmZns37+f/Pz8PqmZJwjCzUUEQEEQhFuIJEmcP3+e7OxssrKy2LNnD87Ozvj4+LB///4L+tPW1NTg6+t703b9EASh98TfekEQhFuIQqEgMDCQJUuWsGPHDs6fP096ejqZmZkXhD8Af3//6xb+rqbd4IkTJ7j77rsJDQ1FoVCwYsWK6zImQRD+PxEABUEQblEKhQIfHx8+/PDDft2v2dNu8KWXXiI/P5+YmBhmzpxJXV3dJa9va2sjPDycV199VexJFIR+IpaABWGAExvOhZvN1bYb/L7Q0FCeeOKJCzrPCILQ98QMoCAMUJIkUV9fj0Kh4Ief08TnNmGgMhgM5OXlMX36dPk2pVLJ9OnT2b9//w0cmSAI3ycCoCAMUAaDgenTp/Pmm29eNAM4WGcEr2Zf2dq1a1EoFBf8EkWPr78fazco2gcKwsAhAqAgDFB2dnaYzWa5t6vRaATg6NGjnDlzBhhcM4FXu68MwMXFhZqaGvnXuXPn+nHEgiAIA5cIgIIwQOn1emJiYqiurgbAxsYGi8XCfffdx69//Wvq6uouOxNoNpuxWCz9Odzr7q233uKRRx7hwQcfJDo6mtWrV+Po6MgHH3xw2fsoFAr8/PzkXz+clRL6Xm/aDQqC0P9EABSEAUiSJJycnFAoFFRUVABw/vx5nn32WXQ6Hf/3f/+Hj48PJpPpgvu1trYCYGVldUvVduvtvjKdTkdISAhBQUGkpaVx4sSJ/hjuoNabdoOCIPS/W+cdQhBuQXq9niFDhgDw5ptvsm/fPpYtWybPZFlbW8vXNjU18be//Y3ExETuv/9+9uzZc8nHvBlnBnuzr2z48OF88MEHbNy4kU8++QSLxcKECROoqqrqjyEPak8++ST//Oc/+eijjzh58iS//vWv0ev1PPjggwAsXLiQ5557Tr7eYDBQWFhIYWEhBoOB6upqCgsLOX369I16CYJwy7P+75cIgtDfFAoFZrOZ2NhY8vPz2b59OytXruQ///kPXl5ejBw5EgcHB372s5/x6KOPYm9vT2trK7GxsQwfPpxt27axaNEili5dyv/+7/9e8NiXmxm81crNJCcnXzDjNGHCBEaMGMGaNWt4+eWXb+DIbn333nsv9fX1vPjii3K7wa1bt8oBvqKi4oKfw/PnzxMXFyf//xtvvMEbb7zB1KlTyc3N7e/hC8KgIAKgIAxAFosFKysrPD09+eKLL7Czs+O+++7jrrvuQpIk1q9fT05ODp988gmjR49mxowZBAcH4+fnh62tLffeey9/+9vfWLt2LXPmzCEiIoKTJ0/y8ccfs3DhQkaMGHHR8/W8Ifv5+ZGRkcGkSZNuxEu/pL7YV2ZjY0NcXJyYVeonS5YsYcmSJZf8sx+GutDQ0EF1oEkQBgKxBCwIA1DPm2FnZyfQtdT5pz/9Sf6zkSNH8vvf/578/HxmzJhBZWUlTz/9NDNmzGDatGm88cYbJCcnU1RUJC8TjxgxguzsbD777DP5ebRaLZIkoVQq5f2E//jHPwgKCurPl/tf9cW+MrPZzLFjx/D3979ewxQEQbhpiE4ggjBAdXZ2smjRIk6ePMmuXbsu6uPaQ5Ik7r77bgoKCnj88ccxmUxs3LiRb7/9lrCwMEpLS+U6eO+88w7vv/8+R44coba2lnvvvZfGxkbWr1/PiBEjMJlMF+wrhAtnB2+kdevWsWjRItasWUNiYiIrVqxg/fr1FBcX4+vry8KFCwkMDGT58uUA/OlPf2L8+PFERkai1Wp5/fXXycnJIS8vj+jo6Bv8agRBEG4ssQQsCAPMl19+yalTpygoKODQoUOsXbsWDw+Py+7RM5lMbN26lX/961/87Gc/A+C3v/0t48ePJyoqSg5/0LUv7u233+aVV17hk08+wdPTk82bNxMcHAx01c3LyMhg1qxZ8n16wl/P4ZEbFQavdl9ZU1MTjzzyCLW1tbi7uzN27Fj27dsnwp8gCAJiBlAQBpz//Oc/vPDCC8THx7NkyRKmTp36o9e3trZy99134+Pjw6pVq9DpdHz44Yf84Q9/YN26ddx9991yeCwqKuLee++lrq6O//mf/2Hp0qW4ubkBsGXLFubPn8+BAweIi4ujubmZdevWYWtry/z583F1de2HVy8IgiD0BxEABWGAMhqN2NjYXNG1X3/9NYsXL6a1tZW0tDS++OILnJ2d2bNnD4GBgQAcP36cRYsWcebMGUJCQjh48CB2dnby89x99900NTWxY8cOjh8/znPPPcf58+eRJImSkhLmzZvHyy+/zNChQ6/nyxYEQRD6wY3f2CMIwiVdafgDuOOOOzh79ix79uzh2Wef5Sc/+QkREREEBgbS1tbGv/71L9LT04mIiGDdunWo1WoaGxsveJ6tW7eSnp6OQqHgyJEjVFdX8+GHH1JQUMD+/fsJCQkRvVwFQRBuESIACsItwGw2AxAdHc3QoUP5+9//TlZWFtBVQPqll17iN7/5Df/3f//H1KlT8fb2lv8cYNu2bVgsFrn0y5gxYygpKWH9+vVUV1cTExPDkiVLiI+P7/8XJ9wQq1atIjQ0FHt7e5KSkjh48OCPXr9hwwaioqKwt7dn9OjRbNmypZ9GKghCb4gAKAi3ACsrK/n3kiQhSRIqlQqAZcuWcfToUZYuXYqdnR329vZERUWxZ88eOTiuXbuWpKQkQkJCgK4AuH79evLy8nj55Zc5e/YsQUFBODk59f+LE/rdunXrePLJJ3nppZfIz88nJiaGmTNnUldXd8nr9+3bx4IFC3j44YcpKCggPT2d9PR0jh8/3s8jFwThSokAKAi3mO+f+oWuQOjp6XlBC7ilS5fS0tJCe3s70HXwJDU1FU9PTyoqKjAajaSmprJs2TKKi4u5++67OXv2bL+/llvBnj17mDt3LgEBASgUCnJycv7rfXJzc4mPj8fOzo7IyEjWrl173cf5fW+99RaPPPIIDz74INHR0axevRpHR0c++OCDS17/9ttvc+edd/L0008zYsQIXn75ZeLj41m5cmW/jlsQhCsnAqAg3OJ+WM4Futqiffnll6hUKs6fP8/kyZNJSUnBZDKxZs0a1q9fjyRJTJw4kTVr1nDq1KmLunAIV0av1xMTE8OqVauu6PqzZ88yZ84cpk2bRmFhIU888QS//OUv+eqrr67zSLsYDAby8vKYPn26fJtSqWT69Ons37//kvfZv3//BdcDzJw587LXC4Jw44k6gIIwCJnNZnnZOCAggN27dwNdxaf9/f157rnnePPNN7n99ts5duwY1tbWJCUl3cgh37RmzZrFrFmzrvj61atXExYWxptvvgl0dXDZu3cvf/vb35g5c+b1GqZMo9FgNpvl+oo9fH19KS4uvuR9amtrL3m9ODQkCAOXmAEUhEHo+3sGe/YBAtjZ2bFkyRKOHz/OQw89xOnTp5k6dSq5ubkoFIoLlpGF60PMpgmC0B/EDKAgDHKXOkDi4uLCkiVLWLJkyQXXDoSWcLe6y82m9ezZdHBwuK7P7+XlhZWV1UVL/mq1Gj8/v0vex8/P76quFwThxhP/mguCIFMoFHLIM5vNiDrxg4+trS1jx45lx44d8m0Wi4UdO3aQnJx8yfskJydfcD10lRa63PWCINx4YgZQEIRL+v7MoNB/Ljeb5uLict1n/3o8+eSTLFq0iISEBBITE1mxYgV6vZ4HH3wQgIULFxIYGMjy5csBePzxx5k6dSpvvvkmc+bM4bPPPuPw4cO89957/TJeQRCungiAgiAIA0hycvJFRZT7ezbt3nvvpb6+nhdffJHa2lpiY2PZunWrvDRdUVFx0anyTz/9lBdeeIHnn3+eoUOHkpOTw6hRo/ptzIIgXB3RC1gQBOE60ul0nD59GoC4uDjeeustpk2bhoeHB8HBwTz33HNUV1fz8ccfA11lYEaNGsVvfvMbHnroIXbu3Mn//u//snnz5n45BSwIwuAgAqAgCMJ1lJuby7Rp0y66fdGiRaxdu5YHHniA8vJycnNzL7jP0qVLKSoqYsiQISxbtowHHnig/wYtCMItTwRAQRAEQRCEQUacAhYEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhkRAAUBEEQBEEYZEQAFARBEARBGGREABQEQRAEQRhk/h+k4KEN2MLyAgAAAABJRU5ErkJggg==", + "_dom_classes": [], + "_figure_label": "Figure 17", + "_image_mode": "diff", + "_message": "", + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "MPLCanvasModel", + "_rubberband_height": 0, + "_rubberband_width": 0, + "_rubberband_x": 0, + "_rubberband_y": 0, + "_size": [ + 640, + 480 + ], + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "MPLCanvasView", + "capture_scroll": false, + "footer_visible": true, + "header_visible": true, + "layout": "IPY_MODEL_1c0f293c6f03438bb4f19276ec49a419", + "pan_zoom_throttle": 33, + "resizable": true, + "toolbar": "IPY_MODEL_eb0420e848554f6592e94d4423567f9c", + "toolbar_position": "left", + "toolbar_visible": "fade-in-fade-out" + } + }, + "e37f9f52ff7349cc974e863821254ee7": { + "model_module": "@jupyter-widgets/base", + "model_module_version": "1.2.0", + "model_name": "LayoutModel", + "state": { + "_model_module": "@jupyter-widgets/base", + "_model_module_version": "1.2.0", + "_model_name": "LayoutModel", + "_view_count": null, + "_view_module": "@jupyter-widgets/base", + "_view_module_version": "1.2.0", + "_view_name": "LayoutView", + "align_content": null, + "align_items": null, + "align_self": null, + "border": null, + "bottom": null, + "display": null, + "flex": null, + "flex_flow": null, + "grid_area": null, + "grid_auto_columns": null, + "grid_auto_flow": null, + "grid_auto_rows": null, + "grid_column": null, + "grid_gap": null, + "grid_row": null, + "grid_template_areas": null, + "grid_template_columns": null, + "grid_template_rows": null, + "height": null, + "justify_content": null, + "justify_items": null, + "left": null, + "margin": null, + "max_height": null, + "max_width": null, + "min_height": null, + "min_width": null, + "object_fit": null, + "object_position": null, + "order": null, + "overflow": null, + "overflow_x": null, + "overflow_y": null, + "padding": null, + "right": null, + "top": null, + "visibility": null, + "width": null + } + }, + "eb0420e848554f6592e94d4423567f9c": { + "model_module": "jupyter-matplotlib", + "model_module_version": "^0.11", + "model_name": "ToolbarModel", + "state": { + "_current_action": "", + "_dom_classes": [], + "_model_module": "jupyter-matplotlib", + "_model_module_version": "^0.11", + "_model_name": "ToolbarModel", + "_view_count": null, + "_view_module": "jupyter-matplotlib", + "_view_module_version": "^0.11", + "_view_name": "ToolbarView", + "button_style": "", + "collapsed": true, + "layout": "IPY_MODEL_e37f9f52ff7349cc974e863821254ee7", + "orientation": "vertical", + "toolitems": [ + [ + "Home", + "Reset original view", + "home", + "home" + ], + [ + "Back", + "Back to previous view", + "arrow-left", + "back" + ], + [ + "Forward", + "Forward to next view", + "arrow-right", + "forward" + ], + [ + "Pan", + "Left button pans, Right button zooms\nx/y fixes axis, CTRL fixes aspect", + "arrows", + "pan" + ], + [ + "Zoom", + "Zoom to rectangle\nx/y fixes axis", + "square-o", + "zoom" + ], + [ + "Download", + "Download plot", + "floppy-o", + "save_figure" + ] + ] + } + } + } + } + }, + "nbformat": 4, + "nbformat_minor": 1 +} diff --git a/pose_estimation/package.xml b/open_manipulator_cv_controller/package.xml similarity index 98% rename from pose_estimation/package.xml rename to open_manipulator_cv_controller/package.xml index 95a8c873710f1dfaa543326e73c7093f8223e374..b35b7bc616e1398cf3133e6f3067d6b6bcd0944a 100644 --- a/pose_estimation/package.xml +++ b/open_manipulator_cv_controller/package.xml @@ -1,6 +1,6 @@ <?xml version="1.0"?> <package format="2"> - <name>pose_estimation</name> + <name>open_manipulator_cv_controller</name> <version>0.0.0</version> <description>Package used to detect the arm keypoints with Mediapipe's pose estimation</description> diff --git a/open_manipulator_cv_controller/requirements.txt b/open_manipulator_cv_controller/requirements.txt new file mode 100644 index 0000000000000000000000000000000000000000..20fdff7aef5f0e838244d9bf5fc091f26b91a191 --- /dev/null +++ b/open_manipulator_cv_controller/requirements.txt @@ -0,0 +1,21 @@ +catkin_pkg==0.5.2 +catkin_pkg_modules==0.5.2 +matplotlib==3.7.1 +matplotlib==3.1.2 +mediapipe==0.9.1.0 +numpy==1.24.2 +numpy==1.17.4 +opencv_contrib_python==4.6.0.66 +pandas==2.0.1 +Pillow==7.0.0 +Pillow==9.5.0 +pypareto==0.3.0 +rospy==1.15.14 +scikit_learn==1.2.2 +scipy==1.10.1 +seaborn==0.12.2 +sensor_msgs==1.13.1 +tf==1.13.2 +torch==2.0.0 +tqdm==4.64.1 +vg==2.0.0 diff --git a/pose_estimation/rviz/keypoint_tf_frame.rviz b/open_manipulator_cv_controller/rviz/keypoint_tf_frame.rviz similarity index 100% rename from pose_estimation/rviz/keypoint_tf_frame.rviz rename to open_manipulator_cv_controller/rviz/keypoint_tf_frame.rviz diff --git a/open_manipulator_cv_controller/scripts/helpers/__pycache__/training_help.cpython-38.pyc b/open_manipulator_cv_controller/scripts/helpers/__pycache__/training_help.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..14f5222204ce1fabd9240a49972950ac1bf6de1a Binary files /dev/null and b/open_manipulator_cv_controller/scripts/helpers/__pycache__/training_help.cpython-38.pyc differ diff --git a/open_manipulator_cv_controller/scripts/helpers/training_help.py b/open_manipulator_cv_controller/scripts/helpers/training_help.py new file mode 100755 index 0000000000000000000000000000000000000000..4cfe7e15025e1fc0adfa7c56f090ded58f632b50 --- /dev/null +++ b/open_manipulator_cv_controller/scripts/helpers/training_help.py @@ -0,0 +1,31 @@ +import torch.nn as nn +import torch.nn.functional as F + +class Net(nn.Module): + def __init__(self, input_num, output_num): + super(Net, self).__init__() + self.l1 = nn.Linear(input_num, 16) + self.l2 = nn.Linear(16, 256) + self.l3 = nn.Linear(256, output_num) + self.drop1 = nn.Dropout(0.10, inplace = False) + self.drop2 = nn.Dropout(0.41, inplace = False) + + def forward(self, x): + x = self.drop1(self.l1(x)) + x = self.drop2(self.l2(x)) + return self.l3(x) + + +class Net2(nn.Module): + def __init__(self, input_num, output_num): + super(Net2, self).__init__() + self.l1 = nn.Linear(input_num, 128) + self.l2 = nn.Linear(128, 32) + self.l3 = nn.Linear(32, output_num) + self.drop1 = nn.Dropout(0.48, inplace = False) + self.drop2 = nn.Dropout(0.38, inplace = False) + + def forward(self, x): + x = nn.Sigmoid()(self.drop1(self.l1(x))) + x = nn.Sigmoid()(self.drop2(self.l2(x))) + return self.l3(x) diff --git a/pose_estimation/scripts/data_collection.py b/open_manipulator_cv_controller/scripts/keypoint_collection_control.py similarity index 87% rename from pose_estimation/scripts/data_collection.py rename to open_manipulator_cv_controller/scripts/keypoint_collection_control.py index 346a72c754eaab2d98b784955119d3a06f6eefae..8fbcd326bd96281bd6fd41dc88e50fde955d3025 100755 --- a/pose_estimation/scripts/data_collection.py +++ b/open_manipulator_cv_controller/scripts/keypoint_collection_control.py @@ -13,23 +13,24 @@ import tf from mediapipe.framework.formats import landmark_pb2 -from helpers.training_help import Net -CONTROL = rospy.get_param('/keypoint_collection/manipulator_control') +CONTROL = rospy.get_param('/keypoint_collection_control/manipulator_control') if not CONTROL: - FILENAME = rospy.get_param('/keypoint_collection/filename') - VIDEO_SAVE = rospy.get_param('/keypoint_collection/video_save') - save_file = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/{FILENAME}") + FILENAME = rospy.get_param('/keypoint_collection_control/filename') + VIDEO_SAVE = rospy.get_param('/keypoint_collection_control/video_save') + save_file = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/{FILENAME}") else: VIDEO_SAVE = False - ik_model = rospy.get_param('/keypoint_collection/ik_model') - CONTROL_MODEL = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/models/{ik_model}") + ik_model = rospy.get_param('/keypoint_collection_control/ik_model') + CONTROL_MODEL = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/models/{ik_model}") + +MODEL = rospy.get_param('/keypoint_collection_control/gesture_model') +model_file = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/{MODEL}") + +ANGLE = None -MODEL = rospy.get_param('/keypoint_collection/gesture_model') -model_file = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/{MODEL}") - # Dictionary of different modes/stages of data collection COLLECTION_MODES = { "Setup": 0, @@ -71,6 +72,9 @@ def create_file(): def save_dataset(data): rospy.loginfo("Saving the dataset...") + print(data['points']) + print(data['calib']) + if not os.path.exists(save_file): create_file() @@ -109,18 +113,22 @@ def gesture_recognition(recognizer, capture, frame_timestamp_ms, mode): # If the mode is set to setup, searching for a Thumbs up to start calibration if mode == COLLECTION_MODES["Setup"]: if verify_gesture(gesture, "Thumb_Up", score): + rospy.loginfo("Thumbs up detected...") rospy.loginfo("\n*** CALIBRATION MODE ***") return COLLECTION_MODES["Calibration"] # If the mode is set to collection, seraching for a Thumbs up or down to stop the collection elif mode == COLLECTION_MODES["Collection"]: if verify_gesture(gesture, "Thumb_Up", score): + rospy.loginfo("Thumbs up detected...") rospy.loginfo("\n*** Collection Over ***") return COLLECTION_MODES["Finished"] if verify_gesture(gesture, "Thumb_Down", score): + rospy.loginfo("Thumbs Down detected...") rospy.logwarn("\n***Program Terminated***") return COLLECTION_MODES["Terminate"] elif mode == COLLECTION_MODES["Control"]: if verify_gesture(gesture, "Thumb_Down", score): + rospy.loginfo("Thumbs Down detected...") rospy.logwarn("\n***Program Terminated***") return COLLECTION_MODES["Terminate"] @@ -137,13 +145,24 @@ def show_image(img, pose_landmarks = None): landmark_drawing_spec=mp_ds ) + img = cv2.flip(img, 1) + + if ANGLE is not None: + img = cv2.putText(img, f'Wrist: {round(ANGLE, 2)}', (0, 30), cv2.FONT_HERSHEY_SIMPLEX, + 0.5, (0, 0, 255), 1, cv2.LINE_AA) + + cv2.putText + # Displaying the current frame of the video - cv2.imshow("Pose Video", cv2.flip(img, 1)) + cv2.imshow("Pose Video", img) # TODO: Possibly add Visibility def get_landmarks(pose_result): + global ANGLE - if not pose_result.pose_world_landmarks or not pose_result.pose_world_landmarks.landmark: return None + verification = not pose_result.pose_world_landmarks + verification1 = not pose_result.pose_world_landmarks.landmark + if verification or verification1: return None landmarks = {} angle = None @@ -153,15 +172,18 @@ def get_landmarks(pose_result): landmarks[idx] = coordinates elbow, wrist = np.array(landmarks[elbow_keypoint]), np.array(landmarks[wrist_keypoint]) - wrist_vec = zero_out(wrist - elbow, 2) + wrist_vec = zero_out(wrist - elbow, 1) angle = vg.angle(wrist_vec, np.array([-1, 0, 0]), units="rad") - if wrist[1] < elbow[1]: + + if wrist_vec[2] < 0: angle = -angle - else: - angle = 0.0 + + angle = -angle landmarks['angle'] = angle + ANGLE = angle + return landmarks def test_path(model_path): @@ -219,9 +241,8 @@ def skeleton_estimation_pose(img, pose): except Exception as e: rospy.logerr(f"Exception: {e}") - # Displaying the video feed and the landmarks show_image(img, pose_landmarks) - + return results @@ -244,11 +265,12 @@ def calculate_calibration(pose_result): return MANIPULATOR_MAX_DIST / distance def get_model(path): - model = Net(7, 4) - model.load_state_dict(torch.load(path)['model_state_dict']) - model.eval() + model = torch.jit.load(path) return model + +GESTURE_CHECKPOINT = 15 + def video_capture(control = False): video = cv2.VideoCapture(0) video_fps = video.get(cv2.CAP_PROP_FPS) @@ -314,14 +336,14 @@ Important: Try moving the arm up and down whilst fully extended to capture most try: frame_ms = int((1000 * frame_idx) / video_fps) - MODE = gesture_recognition(recognizer, capture, frame_ms, MODE) + if frame_idx % GESTURE_CHECKPOINT == 0: + MODE = gesture_recognition(recognizer, capture, frame_ms, MODE) if MODE == COLLECTION_MODES["Setup"]: show_image(capture) - ### TODO: Max calibration rather than last elif MODE == COLLECTION_MODES['Calibration']: - counter += (1000 / video_fps) + counter += (1000 / video_fps) * 4 if counter <= threshold: results = skeleton_estimation_pose(capture, pose) if results is not None: @@ -361,9 +383,6 @@ Important: Try moving the arm up and down whilst fully extended to capture most if landmarks: data['points'].append(landmarks) - LANDMARKS += 1 - print(LANDMARKS) - elif MODE == COLLECTION_MODES["Control"]: pose_results = skeleton_estimation_pose(capture, pose) if not pose_results: continue @@ -383,7 +402,6 @@ Important: Try moving the arm up and down whilst fully extended to capture most return data -####################### TODO: CODE FROM training_data.py ######################## from open_manipulator_msgs.srv import SetJointPosition, SetJointPositionRequest PATH_TIME = 0.5 @@ -401,7 +419,7 @@ def set_wrist_angle(joint_angles): goal_request.joint_position.max_velocity_scaling_factor = 0.0 goal_request.path_time = PATH_TIME resp = set_joints(goal_request) - + rospy.sleep(PATH_TIME) if not resp.is_planned: @@ -412,29 +430,24 @@ def set_wrist_angle(joint_angles): def shift_keypoints(original, offset): return (np.array(original) - np.array(offset)) -############################################################################################################# -### TODO: Testing + def control_manipulator(landmarks, model, calib): - print("Controlling manipulator...") - ## Shifting the wrist to be relative to the shoulder at origin - wrist_point = shift_keypoints(landmarks[WRIST], landmarks[SHOULDER]) - wrist_point[2] = -wrist_point[2] + ## Shifting the wrist to be relative to the shoulder at origin and applying calibration + wrist_point = shift_keypoints(landmarks[WRIST], landmarks[SHOULDER]) * calib + wrist_point[0] = -wrist_point[0] - ## Calculating the calibrated point - wrist_point = wrist_point * calib + ## Concatenating the wrist point and angle to match the model input + model_input = np.concatenate((wrist_point, -landmarks['angle']), axis = None) - ## Converting the euler angle to a quaternion - angle = tf.transformations.quaternion_from_euler(0, landmarks['angle'], 0) - ## Concatenating the wrist point and angle to match the model input - model_input = np.concatenate((wrist_point, angle), axis = None) - ## Predicting the joints based on the wrist point and angle control_outputs = model(torch.Tensor(model_input)) + control_outputs = control_outputs.tolist() + ## Setting the manipulator's wrist angle - success = set_wrist_angle(control_outputs.tolist()) + _ = set_wrist_angle(control_outputs) def verify_params(): verified = test_path(model_file) @@ -447,8 +460,8 @@ def verify_params(): return verified if __name__ == '__main__': - rospy.init_node("keypoint_collection") - + rospy.init_node("keypoint_collection_control") + if verify_params(): rospy.loginfo("All the parameters were verified") @@ -459,4 +472,4 @@ if __name__ == '__main__': else: rospy.logfatal(f"Check if all the provided model names are correct or if they are in the correct directories") - rospy.loginfo("Finished") + rospy.loginfo("Finished") \ No newline at end of file diff --git a/open_manipulator_cv_controller/scripts/training.py b/open_manipulator_cv_controller/scripts/training.py new file mode 100644 index 0000000000000000000000000000000000000000..d39b01ee4427a08375584896dfca46194b33acdd --- /dev/null +++ b/open_manipulator_cv_controller/scripts/training.py @@ -0,0 +1,766 @@ +import os +import pickle +import rospy +import pypareto +import matplotlib +import torch +import tf +import math +import json + +import numpy as np +import pandas as pd +import seaborn as sns +import torch.nn as nn +import torch.optim as optim +import matplotlib.pyplot as plt + +from tqdm import tqdm +from random import choice, random, uniform +from open_manipulator_msgs.msg import KinematicsPose +from open_manipulator_cv_controller.msg import Joints + +from torch.utils.data import DataLoader +from sklearn.model_selection import train_test_split + + + +dataset_name = rospy.get_param('/training/dataset') +DATASET_PATH = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/{dataset_name}") + +model_name = rospy.get_param('/training/model') +MODEL_SAVE_PATH = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/models/{model_name}") + +criterion = rospy.get_param('/training/loss') +scheduler = rospy.get_param('/training/scheduler') +learning_rate = rospy.get_param('/training/initial_lr') +EPOCHS = rospy.get_param('/training/epochs') + +PLOT = rospy.get_param('/training/plot') +EVALUATE = rospy.get_param('/training/evaluate') + +RUN_NAS = rospy.get_param('/training/NAS') +NAS_iter = rospy.get_param('/training/NAS_iter') + +LEARNING_RATE = 1e-1 +CRITERION = None +SCHEDULER = None +CHECKPOINT_LOG = 0 + +INPUTS = 7 +OUTPUTS = 4 + +def validate_params(): + global CRITERION, SCHEDULER, LEARNING_RATE, CHECKPOINT_LOG, EVALUATE + + if type(EPOCHS) != int: + print(f"Epochs have to be of integer type") + return False + + if type(EVALUATE) != bool or type(PLOT) != bool: + print(f"`evaluate` and `plot` flags need to be booleans") + return False + try: + LEARNING_RATE = float(learning_rate) + except Exception as conversion_exp: + print(f"Learning rate incorrect. Exception when converting: {conversion_exp}") + return False + + if criterion == "mse": + CRITERION = nn.MSELoss() + elif criterion == "huber": + CRITERION = nn.HuberLoss() + else: + print(f"Given loss [{criterion}] not valid") + return False + + CHECKPOINT_LOG = 5 + + if scheduler == "None": + SCHEDULER = None + else: + print(f"Given scheduler [{scheduler}] not valid") + return False + + if RUN_NAS: + EVALUATE = False + + return True + + +def list_to_tensor(arr): + return torch.tensor(arr) + +def process_dataset(dataset): + inputs = [] + labels = [] + + + for data in dataset: + actual_values = [] + for joint in data['jointPositions']: + actual_values.append(joint.angle) + + labels.append(actual_values) + + man_pos = data['manipulatorPositions'] + man_angle = data['angle'] + + man_angle = tf.transformations.euler_from_quaternion([man_angle.x,man_angle.y, man_angle.z, man_angle.w]) + + x = [man_pos.x, man_pos.y, man_pos.z, man_angle[1]] + inputs.append(x) + + inputs, labels = remove_duplicates(inputs, labels) + + inputs = list_to_tensor(np.array(inputs).astype(np.float32)) + labels = list_to_tensor(np.array(labels).astype(np.float32)) + + X_train, X_test, y_train, y_test = train_test_split( + inputs, + labels, + test_size = 0.20, + shuffle = True, + random_state = 42, + ) + + train_data = [(X_train[i], y_train[i]) for i in range(len(y_train))] + test_data = [(X_test[i], y_test[i]) for i in range(len(y_test))] + + trainloader = DataLoader(train_data, shuffle=True, batch_size=5) + testloader = DataLoader(test_data, shuffle=True, batch_size=5) + + return trainloader, testloader + #return (X_train, y_train), (X_test, y_test) + +def remove_duplicates(inputs, labels): + processed_inputs, processed_labels = [], [] + + for i in range(len(inputs)): + + duplicates = [] + for j in range(i+1, len(inputs)): + duplicates.append(inputs[i] == inputs[j]) + + if np.array(duplicates).any() == False: + processed_inputs.append(inputs[i]) + processed_labels.append(labels[i]) + + print(f"{len(inputs) - len(processed_inputs)} duplicates have been removed") + return processed_inputs, processed_labels + + +def train(train_set, model, optimizer): + model.train() + + running_loss = 0.0 + for loader in train_set: + X, y = loader[0], loader[1] + + # zero the parameter gradients + optimizer.zero_grad() + + # forward pass + outputs = model(X) + + # calculate the errors + loss = CRITERION(outputs, y) + + loss.backward() + optimizer.step() + + running_loss += loss.item() + + return running_loss / len(train_set) + + +def test(test_set, model): + model.eval() + with torch.no_grad(): + + running_loss = 0.0 + for loader in test_set: + X, y = loader[0], loader[1] + + outputs = model(X) + + loss = CRITERION(outputs, y) + + running_loss += loss.item() + + return running_loss / len(test_set) + + +def save_model(model, path = MODEL_SAVE_PATH): + model_scripted = torch.jit.script(model) + model_scripted.save(path) + print(f"Best model has been saved: {path} \n") + + +def boxplots(abs_err): + df = pd.DataFrame(abs_err) + + axes = plt.figure().add_subplot(111) + sns.set_style("whitegrid") + + boxprops = dict(linestyle='-', linewidth=1.5, color='#00145A') + flierprops = dict(marker='o', markersize=1, + linestyle='none') + whiskerprops = dict(color='#00145A') + capprops = dict(color='#00145A') + medianprops = dict(linewidth=1.5, linestyle='-', color='#01FBEE') + + for row in df.transpose().iterrows(): + label = row[0] + val = row[1] + + axes.scatter([label + 1 for _ in range(val.shape[0])], val, alpha = 0.4) + + axes.boxplot(df, notch=False, boxprops=boxprops, whiskerprops=whiskerprops,capprops=capprops, flierprops=flierprops, medianprops=medianprops,showmeans=False) + + labels = [item.get_text() for item in axes.get_xticklabels()] + + for i in range(len(labels)): + labels[i] = f"joint_{i+1}" + + axes.set_xticklabels(labels) + + plt.xlabel("Joints") + plt.ylabel("Absolute Joint Error") + + plt.show() + +def per_joint_error(loader, predictions, loss_fn): + errors = {} + abs_err = {} + + labels = np.array([output.numpy() for data in loader for output in data[1]]) + predictions = np.array([prediction.numpy() for prediction in predictions]) + + joint_labels, joint_predictions = np.transpose(labels), np.transpose(predictions) + + for joint in range(joint_labels.shape[0]): + + abs_err[joint] = [] + for label, pred in zip(joint_labels[joint], joint_predictions[joint]): + abs_err[joint].append(pred - label) + + error = loss_fn(torch.Tensor(joint_labels[joint]), torch.Tensor(joint_predictions[joint])) + + print(error) + errors[f"joint{joint+1}"] = error.item() + + print("\n-------------------------------") + print(f"Per Joint Error: \n{errors}") + print("\n-------------------------------\n") + + if PLOT: + boxplots(abs_err) + +def plot_history(history): + print("Plotting the training...") + train_loss = history['train_loss'] + test_loss = history['test_loss'] + pos_loss = history['pos_test_loss'] + + axes = plt.figure().add_subplot(111) + + axes.plot(train_loss, "-b", label = "Training Joint Error") + axes.plot(test_loss, "-r", label = "Test Joint Error") + axes.plot(pos_loss, "--g", label = "Test Positional Error") + axes.legend(loc="upper left") + + plt.xlabel("Epochs") + plt.ylabel(f"{criterion.upper()} loss") + + locator = matplotlib.ticker.MultipleLocator(2) + plt.gca().xaxis.set_major_locator(locator) + formatter = matplotlib.ticker.StrMethodFormatter("{x:.0f}") + plt.gca().xaxis.set_major_formatter(formatter) + + labels = [item.get_text() for item in axes.get_xticklabels()] + + for idx, epoch in enumerate(range(0, EPOCHS, CHECKPOINT_LOG * 2)): + labels[idx+1] = epoch + + axes.set_xticklabels(labels) + + plt.show() + +def predict(model, loader): + + model.eval() + with torch.no_grad(): + inputs = [input for data in loader for input in data[0]] + return [model(input).detach() for input in inputs] + + +def positional_loss(prediction, labels): + predicted_position = solve_fk(prediction) + actual_position = solve_fk(labels) + + cost_fn = CRITERION + cost = cost_fn(actual_position, predicted_position) + + return cost + + +def dataset_pos_error(loader, model): + inputs = [input for data in loader for input in data[0]] + labels = [output for data in loader for output in data[1]] + + model.eval() + with torch.no_grad(): + + max_ = 0.0 + + counter = 0.0 + loss = 0.0 + for input, label in tqdm(zip(inputs, labels), total = len(inputs)): + prediction = model(input).detach() + + predicted_position = solve_fk(prediction) + actual_position = solve_fk(label) + + + dist = np.linalg.norm(actual_position.numpy()) + if max_ <= dist: + max_ = dist + + loss += CRITERION(actual_position, predicted_position) + counter += 1 + + return loss / counter + +MAX_DIST = 0.504 +A, B, C = (0.12, 0.277, 0.070) +DX, DY, DZ = (0.275, 0.0, -0.1) +R1, R2, R3 = MAX_DIST, MAX_DIST, MAX_DIST +SAVE_METRICS = os.path.expanduser("~/catkin_ws/src/open_manipulator_cv_controller/notebooks/") + + +def trajectory(t): + x = A * math.cos(t + math.pi) + DX + y = B * math.sin(t + math.pi) + DY + z = C * t + DZ + return (x,y,z) + +def workspace(u, v): + x = R1 * np.cos(u) * np.sin(v) + y = R2 * np.sin(u) * np.sin(v) + z = R3 * np.cos(v) + + return x,y,z + +def sample_eval_points(model, test_set, name): + + print("Sampling points for testing...") + + model.eval() + + ### Testing Trajectory Location ### + trajectory_loc = [trajectory(t) for t in np.arange(0, 2 * math.pi, 0.1)] + + trajectory_pred = [] + for (x,y,z) in tqdm(trajectory_loc): + # Input tensor to the model which will not have end-effector rotation + + input = torch.Tensor([x, y, z, 0.0]) + + # Getting the joint predictions from the model + pred = model(input).detach().numpy() + + # Using the FK to get the predicted locations + loc = solve_fk(pred).tolist() + + # Saving the locations + trajectory_pred.append(loc) + + ### Testing Predicted Orientation ### + + # Using a starting home position of the manipulator + starting_x, starting_y, starting_z = 0.286, 0.0, 0.204 + + # Getting the range of the end-effector rotation + orientation_loc = list(np.arange(-math.pi, math.pi, 0.1)) + + orientation_pred = [] + for orient in tqdm(orientation_loc): + # Getting the quaternion angle + # angle = tf.transformations.quaternion_from_euler(0.0, orient, 0.0) + + # Creating an input from the orientation and home position + input = torch.Tensor([starting_x, starting_y, starting_z, orient]) + + # Getting the prediction from the model for the end-effector joint and saving it + pred = model(input).detach().tolist()[-1] + orientation_pred.append(pred) + + ### Testing Maximum Workspace ### + + # Sampling points on the maximum range of motion + max_workspace = [workspace(u,v) + for u in np.arange(0, math.pi, 0.5) + for v in np.arange(0, math.pi, 0.25)] + + max_workspace_pred = [] + for (x,y,z) in tqdm(max_workspace): + # Input tensor to the model which will not have end-effector rotation + input = torch.Tensor([x,y,z,0.0]) + + # Getting the joint predictions from the model + pred = model(input).detach().numpy() + + # Using the FK to get the predicted locations + loc = solve_fk(pred).tolist() + + # Saving the locations + max_workspace_pred.append(loc) + + + #### Saving the points and predictions for the test set #### + predictions, ground_truth = [], [] + model.eval() + with torch.no_grad(): + test_inputs = [input for data in test_set for input in data[0]][:25] + test_labels = [output for data in test_set for output in data[1]][:25] + + for input, actual in tqdm(zip(test_inputs, test_labels), total = len(test_inputs)): + pred = model(input).detach() + ground_truth.append(solve_fk(actual).tolist()) + predictions.append(solve_fk(pred).tolist()) + + dist = max([np.linalg.norm(loc) for loc in ground_truth]) + + metrics = json.dumps({ + "pos_traj": ( + trajectory_pred, trajectory_loc + ), + "or_traj": ( + orientation_pred, orientation_loc + ), + "workspace": ( + max_workspace_pred, max_workspace + ), + "test_set": ( + predictions, ground_truth + ), + "max_dist": dist.item() + }) + + path = os.path.join(SAVE_METRICS, name) + with open(path, "w") as handle: + print(f"Saving the metrics: {path}") + json.dump(metrics, handle) + + print("Successfully saved the points") + + +def evaluate_model(model_dict, train_set, test_set, name = "metrics.json"): + print("Loading the best model...") + model = model_dict['model'] + model.eval() + + with torch.no_grad(): + predictions = predict(model, test_set) + + if not RUN_NAS: + + if PLOT: + history = model_dict['history'] + plot_history(history) + + print(f"""Best model was trained with {criterion.upper()}: + -> Average Joint Error (train): {model_dict['train_loss']} + -> Average Joint Error (test): {model_dict['test_loss']} + -> Average Positional Error (test): {model_dict['pos_err']}\n""") + + else: + print(f"""Best model was trained with {criterion.upper()}: + -> Average Joint Error (test): {model_dict['min_loss']} + -> Average Positional Error (test): {model_dict['pos_err']}\n""") + + per_joint_error(test_set, predictions, CRITERION) + + sample_eval_points(model, test_set, name = name) + + +def solve_fk(prediction: torch.Tensor): + global kinematics_pub + + msg = Joints() + joints = [val.item() for val in prediction] + + msg.angles = joints + + kinematics_pub.publish(msg) + + try: + return_msg = rospy.wait_for_message('/forward_kinematics_keypoints', KinematicsPose, timeout = rospy.Duration(5.0)) + position = return_msg.pose.position + position = torch.tensor([position.x, position.y, position.z]) + except Exception: + rospy.sleep(0.1) + return_msg = rospy.wait_for_message('/forward_kinematics_keypoints', KinematicsPose, timeout = rospy.Duration(5.0)) + position = return_msg.pose.position + position = torch.tensor([position.x, position.y, position.z]) + + + return position + +def create_model(input_size, output_size): + m_choices = [8, 16, 32, 64, 128] + n_choices = [8, 16, 32, 64, 128, 256] + l_choices = [8, 16, 32, 64, 128] + layer_prob = [0.9, 0.6, 0.6] + + activation_choices = [nn.Sigmoid(), nn.Tanh(), nn.ReLU(), None] + dropout_range = (0.0, 0.5) + + layers = [choice(m_choices), choice(n_choices), choice(l_choices)] + act_f = choice(activation_choices) + + modules = [] + prev = input_size + + for layer_num, layer in enumerate(layers): + + if random() <= layer_prob[layer_num]: + modules.append(nn.Linear(prev, layer)) + + dropout = round(uniform(dropout_range[0], dropout_range[1]), 2) + modules.append(nn.Dropout(dropout)) + + if act_f is not None: + modules.append(act_f) + + prev = layer + + modules.append(nn.Linear(prev, output_size)) + + if act_f is None and random() < 0.2: + act_f = choice([x for x in activation_choices if x is not None]) + + elif act_f is not None and random() <= 0.5: + modules.append(act_f) + + sequential = nn.Sequential(*modules) + + return sequential + +def optimal_pareto(history): + values = [] + + for idx, his in enumerate(history): + value = his['min_loss'], his['pos_err'] + values.append(value) + + chain = pypareto.Comparison(pypareto.by_value, pypareto.MaxMinList(pypareto.MaxMin.MIN, pypareto.MaxMin.MIN)).as_chain() + pareto_front = chain.split_by_pareto(values)[0] + + pareto_front_idx = [idx for idx, value in enumerate(values) if value in pareto_front] + + min_loss, min_pos = float('inf'), float('inf') + best_model_loss, best_model_pos = None, None + + for idx, model in enumerate(history): + if idx not in pareto_front_idx: continue + + if model['min_loss'] <= min_loss: + min_loss = model['min_loss'] + best_model_loss = model + + if model['pos_err'] <= min_pos: + min_pos = model['pos_err'] + best_model_pos = model + + print(f"Best Non-Dominated Positional Loss: {min_pos}") + save_model(best_model_pos['model'], path = f"{MODEL_SAVE_PATH[:-3]}_positional_pareto.pt") + + print(f"Best Non-Dominated Joint Loss: {min_loss}") + save_model(best_model_loss['model'], path = f"{MODEL_SAVE_PATH[:-3]}_joint_pareto.pt") + + if PLOT: + for idx in pareto_front_idx: + current = history[idx] + print(f"Model: {current['model']}\nJoint: {current['min_loss']}, Positional: {current['pos_err']}\n") + + plt.scatter([value[0] for value in values], + [value[1] for value in values], + c = ["red" if value in pareto_front else "blue" for value in values]) + + plt.xlabel("Joint Loss") + plt.ylabel("Positional Loss") + + plt.show() + + return best_model_loss, best_model_pos + +def run_nas(train_set, test_set): + global LEARNING_RATE + + HISTORY = [] + + lr_range = [1e-1, 5e-3, 1e-4, None] + + for iter in tqdm(range(NAS_iter)): + print(f"Iteration {iter}") + model = create_model(INPUTS, OUTPUTS) + + for initial_lr in lr_range: + # optimizer = torch.optim.SGD(model.parameters(), lr=initial_lr, momentum=0.9) + + model = reinitialize_model(model) + + lr = initial_lr if initial_lr is not None else lr_range[0] + optimizer = torch.optim.Adam(model.parameters(), lr = lr) + scheduler = None if initial_lr is not None else optim.lr_scheduler.StepLR(optimizer, step_size=20, gamma=0.1) + + best_loss = float('inf') + for _ in range(EPOCHS): + train(train_set, model, optimizer) + test_loss = test(test_set, model) + + if scheduler is not None: + scheduler.step() + + if test_loss <= best_loss: + best_loss = test_loss + + pos_err = dataset_pos_error(test_set, model) + + model_iter = { + "lr": initial_lr, + "min_loss": best_loss, + "pos_err": pos_err, + "model": model, + "model_state": model.state_dict() + } + + HISTORY.append(model_iter) + + rospy.sleep(0.5) + + model1, model2 = optimal_pareto(HISTORY) + + evaluate_model(model1, train_set, test_set, name = "metrics_joint.json") + evaluate_model(model2, train_set, test_set, name = "metrics_pos.json") + + +def reinitialize_model(model): + for layer in model.children(): + if hasattr(layer, 'reset_parameters'): + layer.reset_parameters() + + return model + + +def training_loop(train_set, test_set): + global SCHEDULER + + # if RUN_NAS: + # run_nas(train_set, test_set) + # return + + + model = nn.Sequential( + nn.Linear(4, 100), + nn.ReLU(), + nn.Linear(100, 4) + ) + + print(model) + + optimizer = torch.optim.Adam(model.parameters(), lr=1e-2) + SCHEDULER = torch.optim.lr_scheduler.StepLR(optimizer, step_size=10, gamma=0.1) + + print("\nTraining Hyperparameters:") + print(f"-> Model create with 7 inputs and 4 outputs") + print(f"-> Training Epochs: {EPOCHS}") + print(f"-> Adam Optimizer (initial learning rate of {LEARNING_RATE})") + print(f"-> Cost Function based on {criterion} loss") + print(f"-> Scheduler: {SCHEDULER}\n") + + ### Re-randomize the weights if model architecture loaded + model = reinitialize_model(model) + + best_model = None + history = { + "train_loss": [], + "test_loss": [], + "pos_test_loss": [] + } + + for epoch in range(EPOCHS): + train_loss = train(train_set, model, optimizer) + test_loss = test(test_set, model) + + if epoch % CHECKPOINT_LOG == 0: + print(f"[Epoch {epoch} of {EPOCHS}]") + print(f"LR: {optimizer.param_groups[0]['lr']}") + print(f"Training Loss: {train_loss}, Test Loss: {test_loss}") + + + pos_err = dataset_pos_error(test_set, model) + + print(f"Positional Test Loss: {pos_err}") + print("-----------------------------------------\n") + + best_model = { + 'epoch': epoch, + 'train_loss': train_loss, + 'test_loss': test_loss, + 'pos_err': pos_err, + 'model': model + } + + history['train_loss'].append(train_loss) + history['test_loss'].append(test_loss) + history['pos_test_loss'].append(pos_err) + + if SCHEDULER: + SCHEDULER.step() + + best_model['history'] = history + save_model(best_model['model']) + + return best_model + +def load_model(path): + model = torch.jit.load(path) + return model + +# takes in a module and applies the specified weight initialization +def weights_init_uniform(m): + classname = m.__class__.__name__ + # for every Linear layer in a model.. + if classname.find('Linear') != -1: + # apply a uniform distribution to the weights and a bias=0 + m.weight.data.uniform_(0.0, 1.0) + m.bias.data.fill_(0) + +if __name__ == '__main__': + rospy.init_node("training") + kinematics_pub = rospy.Publisher("evaluation", Joints, queue_size = 10) + rospy.sleep(1) + + try: + if validate_params(): + dataset = {} + with open(DATASET_PATH, "rb") as input_file: + dataset = pickle.load(input_file) + print(f"There are {len(dataset)} points in the dataset") + + train_set, test_set = process_dataset(dataset) + + + print("Training starting...") + model_dict = training_loop(train_set, test_set) + + + if EVALUATE: + print("Evaluation starting...") + evaluate_model(model_dict, train_set, test_set) + + except rospy.ROSException as e: + rospy.logwarn(f"ROS Exception thrown: {e}") diff --git a/pose_estimation/scripts/training_data.py b/open_manipulator_cv_controller/scripts/training_data.py similarity index 74% rename from pose_estimation/scripts/training_data.py rename to open_manipulator_cv_controller/scripts/training_data.py index 40f85697165cd71b7201eccd076bb913cdf87532..8805ae9ecae05ee1137027911c6cdedf0fde6fcc 100755 --- a/pose_estimation/scripts/training_data.py +++ b/open_manipulator_cv_controller/scripts/training_data.py @@ -1,5 +1,6 @@ import pickle import rospy +import random import tf import cv2 import math @@ -14,7 +15,7 @@ from tqdm import tqdm from tf.transformations import quaternion_matrix, translation_matrix from geometry_msgs.msg import Point32 from geometry_msgs.msg import Pose -from pose_estimation.msg import JointPositions +from open_manipulator_cv_controller.msg import JointPositions, ManipulatorPoses from sensor_msgs.msg import PointCloud from open_manipulator_msgs.msg import KinematicsPose from open_manipulator_msgs.srv import SetKinematicsPose, SetJointPosition, SetJointPositionRequest @@ -27,11 +28,11 @@ TRAINING_FILE = rospy.get_param('/training_data/training_file') OUT_OF_RANGE_THRESHOLD = 0.1 THRESHOLD = 2 -NOISE = 0.03 +NOISE = 0.025 -input_file = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/{FILENAME}") -training_file = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/{TRAINING_FILE}") +input_file = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/{FILENAME}") +training_file = os.path.expanduser(f"~/catkin_ws/src/open_manipulator_cv_controller/data/{TRAINING_FILE}") mp_pose = mp.solutions.pose @@ -285,23 +286,40 @@ def verify_inputs(): return verify +def create_kinematics_pose_msg(loc, angle): + pose = Pose() + pose.position.x, pose.position.y, pose.position.z = loc[0], loc[1], loc[2] + + orientation = tf.transformations.quaternion_from_euler(0, angle, 0) + pose.orientation.x, pose.orientation.y, pose.orientation.z, pose.orientation.w = orientation[0], orientation[1], orientation[2], orientation[3] + + kinematics_pose = KinematicsPose() + kinematics_pose.pose = pose + + return kinematics_pose + def data_gather(): # Reading the pickle file and saving its content as a dictionary - ### TODO: Function + ### TODO: Group Function rospy.loginfo("Reading the file...") + with open(input_file, 'rb') as handle: captured_keypoints = pickle.load(handle) + rospy.loginfo("File read successfully") - - kinematics_pub = rospy.Publisher('captured_keypoints', KinematicsPose, queue_size = 10) + + kinematics_pub = rospy.Publisher('captured_keypoints', ManipulatorPoses, queue_size = 10) for idx in captured_keypoints.keys(): rospy.loginfo(f"Processing video with {idx}") - points = captured_keypoints[idx]['points'] + if 'points' not in captured_keypoints[idx] or 'calib' not in captured_keypoints[idx]: + continue + + points = captured_keypoints[idx]['points'] + rospy.loginfo(f"There are {len(points)} points") - # TODO: Correct calibration ? Noise? - calib = 1.0 - captured_keypoints[idx]['calib'] + 0.025 + calib = captured_keypoints[idx]['calib'] for point_idx, point in enumerate(points): if VIDEO_SHOW: @@ -342,54 +360,71 @@ def data_gather(): # Getting the desired location desired_loc = point_to_np(relative_manipulator).flatten() + - pose = Pose() - pose.position.x = desired_loc[0] - pose.position.y = desired_loc[1] - pose.position.z = desired_loc[2] - + original_loc = shift_keypoints(point[WRIST], point[SHOULDER]) * calib + original_loc[0] = -original_loc[0] - orientation = tf.transformations.quaternion_from_euler(0, angle, 0) - pose.orientation.x = orientation[0] - pose.orientation.y = orientation[1] - pose.orientation.z = orientation[2] - pose.orientation.w = orientation[3] + manipualtor_data = ManipulatorPoses() + if random.random() < 0.75: + for i in range(2): + random_angle = random.uniform(-math.pi, math.pi) + manipualtor_data.originalManipulatorPose = create_kinematics_pose_msg(original_loc, random_angle) + manipualtor_data.processedManipulatorPose = create_kinematics_pose_msg(desired_loc, random_angle) - kinematics_pose = KinematicsPose() - kinematics_pose.pose = pose + lock.acquire() + kinematics_pub.publish(manipualtor_data) + + ## No angle + if random.random() < 0.5: + manipualtor_data.originalManipulatorPose = create_kinematics_pose_msg(original_loc, 0.0) + manipualtor_data.processedManipulatorPose = create_kinematics_pose_msg(desired_loc, 0.0) + lock.acquire() + kinematics_pub.publish(manipualtor_data) + + manipualtor_data.originalManipulatorPose = create_kinematics_pose_msg(original_loc, angle) + manipualtor_data.processedManipulatorPose = create_kinematics_pose_msg(desired_loc, angle) + # Won't unlock until received a message back lock.acquire() - kinematics_pub.publish(kinematics_pose) - ########################################### + kinematics_pub.publish(manipualtor_data) def vector_angle(v1, v2): - """ Angle between two 2D vectors """ - unit_v1 = v1 / np.linalg.norm(v1) - unit_v2 = v2 / np.linalg.norm(v2) - dot_product = np.dot(unit_v1, unit_v2) - angle = np.arccos(dot_product) + """ Angle between two 2D vectors """ + unit_v1 = v1 / np.linalg.norm(v1) + unit_v2 = v2 / np.linalg.norm(v2) + dot_product = np.dot(unit_v1, unit_v2) + angle = np.arccos(dot_product) + + if v2[1] > 0: + angle = -angle + + return angle - if v2[1] < 0: - angle = -angle +def process_joint_positions(joint_position): + save = True if joint_position.success and len(joint_position.jointPositions) != 0 else False - return angle + # print(f"Success: {joint_position.success}") -def process_joint_positions(joint_position): - save = True if joint_position.success or len(joint_position.jointPositions) != 0 else False - if save: position = joint_position.manipulatorPose.pose.position - position.y = vector_angle(np.array([1,0]), np.array([position.x, position.y])) - TRAINING_DATA.append({ - "jointPositions": joint_position.jointPositions, - "manipulatorPositions": position, - "angle": joint_position.manipulatorPose.pose.orientation - }) - else: - rospy.logerr(f"Point out of range: {joint_position.manipulatorPose.pose.position}") + if any([position.x, position.y, position.z]) != 0.0: + + joint_position.jointPositions[0].angle = vector_angle(np.array([1,0]), np.array([position.x, position.y])) + + orientation = joint_position.manipulatorPose.pose.orientation + joint_position.jointPositions[3].angle = tf.transformations.euler_from_quaternion([orientation.x, orientation.y, orientation.z, orientation.w])[1] + + TRAINING_DATA.append({ + "jointPositions": joint_position.jointPositions, + "manipulatorPositions": position, + "angle": orientation + }) + # else: + # rospy.logerr(f"Point out of range: {joint_position.manipulatorPose.pose.position}. DISTANCE: {dist}") lock.release() @@ -400,17 +435,21 @@ if __name__ == '__main__': rospy.init_node(node) rospy.Subscriber("inverse_kinematics_keypoints", JointPositions, process_joint_positions) - try: - # rospy.loginfo("Sleeping for 1 second") - # rospy.sleep(1) - if verify_inputs(): data_gather() - + try: + if verify_inputs(): + data_gather() except rospy.ROSInterruptException as e: rospy.logwarn(f"Exception: {e}") lock.acquire() - rospy.loginfo("Saving training dataset") - with open(training_file, 'wb') as handle: - pickle.dump(TRAINING_DATA, handle, protocol=pickle.HIGHEST_PROTOCOL) + + if len(TRAINING_DATA) != 0: + rospy.loginfo(f"Saving training dataset with {len(TRAINING_DATA)} data samples into `{training_file}`") + with open(training_file, 'wb') as handle: + pickle.dump(TRAINING_DATA, handle, protocol=pickle.HIGHEST_PROTOCOL) + + else: + rospy.logwarn(f"No training data") + lock.release() diff --git a/pose_estimation/setup.py b/open_manipulator_cv_controller/setup.py similarity index 100% rename from pose_estimation/setup.py rename to open_manipulator_cv_controller/setup.py diff --git a/pose_estimation/src/kinematics_solver.cpp b/open_manipulator_cv_controller/src/kinematics_solver.cpp similarity index 72% rename from pose_estimation/src/kinematics_solver.cpp rename to open_manipulator_cv_controller/src/kinematics_solver.cpp index b7e1a6db372c0218798a4cb633010bc6ca6e4107..0cb4f02b24658b7b6caea6b641330e0f5f8050fa 100755 --- a/pose_estimation/src/kinematics_solver.cpp +++ b/open_manipulator_cv_controller/src/kinematics_solver.cpp @@ -1,5 +1,5 @@ -#include "pose_estimation/kinematics_solver.h" +#include "open_manipulator_cv_controller/kinematics_solver.h" KinematicsSolver::KinematicsSolver(bool using_platform, std::string usb_port, std::string baud_rate, double control_period) { @@ -12,7 +12,7 @@ KinematicsSolver::KinematicsSolver(bool using_platform, std::string usb_port, st open_manipulator_.addKinematics(kinematics_); log::info("Kinematics Solver Set 'SolverUsingCRandSRPoisionOnlyJacobian'"); - ik_pub_ = n_.advertise<pose_estimation::JointPositions>("inverse_kinematics_keypoints", 1000); + ik_pub_ = n_.advertise<open_manipulator_cv_controller::JointPositions>("inverse_kinematics_keypoints", 1000); fk_pub_ = n_.advertise<open_manipulator_msgs::KinematicsPose>("forward_kinematics_keypoints", 1000); log::info("Completed setting up the Kinematics Solver"); @@ -20,52 +20,40 @@ KinematicsSolver::KinematicsSolver(bool using_platform, std::string usb_port, st void KinematicsSolver::solveIK(Pose target_pose, const open_manipulator_msgs::KinematicsPose &manipulator_pose) { - pose_estimation::JointPositions msg; + open_manipulator_cv_controller::JointPositions msg; bool solved = open_manipulator_.solveInverseKinematics("gripper", target_pose, goal_joint_value_); int idx = 0; auto names = open_manipulator_.getManipulator()->getAllActiveJointComponentName(); - std::cout << "Computed Joints:" << std::endl; - for (auto &point : *goal_joint_value_) { - pose_estimation::JointAngle joint; + open_manipulator_cv_controller::JointAngle joint; joint.angle = point.position; joint.name = names.at(idx); msg.jointPositions.push_back(joint); - std::cout << joint.angle << std::endl; + // std::cout << joint.angle << std::endl; idx++; } - - std::cout << "--------------------------" << std::endl; - - msg.success = solved; - msg.manipulatorPose = manipulator_pose; + msg.success = solved; ik_pub_.publish(msg); - log::info("Published the point"); } -void KinematicsSolver::keypointsInverseCallback(const open_manipulator_msgs::KinematicsPose &msg) +void KinematicsSolver::keypointsInverseCallback(const open_manipulator_cv_controller::ManipulatorPoses &msg) { Eigen::Vector3d position; - position[0] = msg.pose.position.x; - position[1] = 0.0; // TODO: msg.pose.position.y; ?? - position[2] = msg.pose.position.z; - - std::cout << "Received a position:" << std::endl; - std::cout << msg.pose.position.x << std::endl; - std::cout << msg.pose.position.y << std::endl; - std::cout << msg.pose.position.z << std::endl; + position[0] = msg.processedManipulatorPose.pose.position.x; + position[1] = 0.0; // TODO: msg.pose.position.y; + position[2] = msg.processedManipulatorPose.pose.position.z; Pose target_pose = {position}; - solveIK(target_pose, msg); + solveIK(target_pose, msg.originalManipulatorPose); } -void KinematicsSolver::solveFK(const pose_estimation::Joints &msg) +void KinematicsSolver::solveFK(const open_manipulator_cv_controller::Joints &msg) { open_manipulator_msgs::KinematicsPose pub_msg; @@ -80,7 +68,7 @@ void KinematicsSolver::solveFK(const pose_estimation::Joints &msg) fk_pub_.publish(pub_msg); } -void KinematicsSolver::keypointsForwardCallback(const pose_estimation::Joints &msg) +void KinematicsSolver::keypointsForwardCallback(const open_manipulator_cv_controller::Joints &msg) { ros::Duration(0.1).sleep(); solveFK(msg); diff --git a/pose_estimation/data/collected_data.pickle b/pose_estimation/data/collected_data.pickle deleted file mode 100644 index d0224b1b532ce84a296691231b5a1a718e3c725a..0000000000000000000000000000000000000000 Binary files a/pose_estimation/data/collected_data.pickle and /dev/null differ diff --git a/pose_estimation/data/gesture_recognizer.task b/pose_estimation/data/gesture_recognizer.task deleted file mode 100644 index 1c6adc8b497d3e6d6603dfc7c864136d75f66e88..0000000000000000000000000000000000000000 Binary files a/pose_estimation/data/gesture_recognizer.task and /dev/null differ diff --git a/pose_estimation/data/keypoint_dataset.pickle b/pose_estimation/data/keypoint_dataset.pickle deleted file mode 100644 index 7f5559578e526810010f2f533a970ed0b411b88c..0000000000000000000000000000000000000000 Binary files a/pose_estimation/data/keypoint_dataset.pickle and /dev/null differ diff --git a/pose_estimation/data/models/joint_predict.pt b/pose_estimation/data/models/joint_predict.pt deleted file mode 100644 index 13efa4648168af601e5153659e45ce22cafc5e7f..0000000000000000000000000000000000000000 Binary files a/pose_estimation/data/models/joint_predict.pt and /dev/null differ diff --git a/pose_estimation/include/pose_estimation/inverse_kinematics_solver.h b/pose_estimation/include/pose_estimation/inverse_kinematics_solver.h deleted file mode 100644 index ee92208e165a50c2ea2baa7e0206f5f30fdf41e8..0000000000000000000000000000000000000000 --- a/pose_estimation/include/pose_estimation/inverse_kinematics_solver.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#include "open_manipulator_libs/kinematics.h" -#include "open_manipulator_libs/open_manipulator.h" -#include "open_manipulator_msgs/GetKinematicsPose.h" -#include "open_manipulator_msgs/SetKinematicsPose.h" -#include "pose_estimation/JointPositions.h" -#include <robotis_manipulator/robotis_manipulator.h> -#include "ros/ros.h" - -class InverseKinematicsSolver -{ - public: - InverseKinematicsSolver(bool using_platform, std::string usb_port, std::string baud_rate, double control_period); - - void keypointsCallback(const open_manipulator_msgs::KinematicsPose& msg); - - ros::NodeHandle getNodeHandle() const { return n_; } - - private: - OpenManipulator open_manipulator_; - std::vector<JointValue>* goal_joint_value_; - - ros::NodeHandle n_; - ros::Publisher ik_pub_; - robotis_manipulator::Kinematics *kinematics_; - - void solveIK(Pose target_pose, const open_manipulator_msgs::KinematicsPose& manipulator_pose); -}; \ No newline at end of file diff --git a/pose_estimation/launch/pose_estimation.launch b/pose_estimation/launch/pose_estimation.launch deleted file mode 100644 index 083ab2efc072d6bae3344c18f4575adddddf7647..0000000000000000000000000000000000000000 --- a/pose_estimation/launch/pose_estimation.launch +++ /dev/null @@ -1,4 +0,0 @@ -<launch> - <node name="arm_keypoint_capture" pkg="pose_estimation" type="arm_keypoint_capture.py" output="screen"/> - <node name="pose_estimation_control" pkg="pose_estimation" type="pose_estimation_control.py" output="screen"/> -</launch> diff --git a/pose_estimation/msg/Keypoint.msg b/pose_estimation/msg/Keypoint.msg deleted file mode 100644 index a2918cdd3d9a555afe1590b321ed760e4bd5703a..0000000000000000000000000000000000000000 --- a/pose_estimation/msg/Keypoint.msg +++ /dev/null @@ -1,5 +0,0 @@ -int32 landmark -float64 x -float64 y -float64 z -float64 visibility \ No newline at end of file diff --git a/pose_estimation/msg/Keypoints.msg b/pose_estimation/msg/Keypoints.msg deleted file mode 100644 index e5f9f39c82415cd6c43c6e33b34c2aedebceff81..0000000000000000000000000000000000000000 --- a/pose_estimation/msg/Keypoints.msg +++ /dev/null @@ -1 +0,0 @@ -Keypoint[] keypoints \ No newline at end of file diff --git a/pose_estimation/msg/SphericalCoordinates.msg b/pose_estimation/msg/SphericalCoordinates.msg deleted file mode 100644 index 7e14a368a901bfbc4913ec75a16b0e1e2ac7e86e..0000000000000000000000000000000000000000 --- a/pose_estimation/msg/SphericalCoordinates.msg +++ /dev/null @@ -1,3 +0,0 @@ -float64 distance -float64 theta -float64 phi \ No newline at end of file diff --git a/pose_estimation/scripts/evaluate.py b/pose_estimation/scripts/evaluate.py deleted file mode 100644 index e3552206e20833703487661666903a16fb3d58c6..0000000000000000000000000000000000000000 --- a/pose_estimation/scripts/evaluate.py +++ /dev/null @@ -1,198 +0,0 @@ -import torch -import os -import pickle -import threading -import rospy - -import numpy as np -import matplotlib.pyplot as plt -import torch.nn as nn -import torch.nn.functional as F - -from open_manipulator_msgs.msg import KinematicsPose -from pose_estimation.msg import Joints -# from training import Net, process_dataset, list_to_tensor - - -#### TODO: Repeated code #### - -class Net(nn.Module): - - def __init__(self, input_num, output_num): - super(Net, self).__init__() - self.l1 = nn.Linear(input_num, 32) - # self.l2 = nn.Linear(32, 32) - self.output = nn.Linear(32, output_num) - # self.dropout = nn.Dropout(0.2) - - def forward(self, x): - x = F.tanh(self.l1(x)) - # x = F.tanh(self.dropout(self.l2(x))) - return self.output(x) - -def list_to_tensor(arr): - return torch.tensor(arr) - -def process_dataset(dataset): - inputs = [] - labels = [] - - for data in dataset: - actual_values = [] - for joint in data['jointPositions']: - actual_values.append(joint.angle) - - labels.append(actual_values) - - man_pos = data['manipulatorPositions'] - man_angle = data['angle'] - x = [man_pos.x, man_pos.y, man_pos.z, man_angle.x, man_angle.y, man_angle.z, man_angle.w] - - inputs.append(x) - - inputs, labels = remove_duplicates(inputs, labels) - - inputs = list_to_tensor(np.array(inputs).astype(np.float32)) - labels = list_to_tensor(labels) - - return (inputs, labels) - -def remove_duplicates(inputs, labels): - processed_inputs, processed_labels = [], [] - - for i in range(len(inputs)): - - duplicates = [] - for j in range(i+1, len(inputs)): - duplicates.append(inputs[i] == inputs[j]) - - if np.array(duplicates).any() == False: - processed_inputs.append(inputs[i]) - processed_labels.append(labels[i]) - - print(f"{len(inputs) - len(processed_inputs)} duplicates have been removed") - return processed_inputs, processed_labels - - -############################################ - - - - -model_path = os.path.expanduser("~/catkin_ws/src/pose_estimation/data/models/joint_predict_all.pt") -dataset_path = os.path.expanduser("~/catkin_ws/src/pose_estimation/data/keypoint_dataset.pickle") - -def plot_history(history): - if history: - plt.plot(history) - plt.show() - -def load_model(model_path, shape): - model_dict = torch.load(model_path) - - model = Net(shape[0], shape[1]) - model.load_state_dict(model_dict['model_state_dict']) - model.eval() - - loss = model_dict['loss'] - - print("Loading the model...") - print(f"Loaded model error: {loss}") - - history = None - if 'history' in model_dict: - history = model_dict['history'] - - return model, history - -def predict(model, inputs): - predictions = [] - - with torch.no_grad(): - for input in inputs: - pred = model(input) - predictions.append(pred.numpy()) - - return list_to_tensor(np.array(predictions).astype(np.float32)) - -def per_joint_error(labels, predictions, loss_fn = nn.MSELoss()): - errors = {} - joint_labels, joint_predictions = labels.transpose(1,0), predictions.transpose(1,0) - - for joint in range(joint_labels.shape[0]): - error = loss_fn(joint_labels[joint], joint_predictions[joint]) - errors[f"joint{joint+1}"] = error.item() - - print(f"\n-------------------------------\nPer Joint Error: \n{errors}") - print("-------------------------------\n") - - -from tqdm import tqdm - -def calcualte_fk(pub, predictions): - - for prediction in tqdm(predictions): - msg = Joints() - joints = [val.item() for val in prediction] - msg.angles = joints - - # lock.acquire() - pub.publish(msg) - rospy.sleep(0.2) - - rospy.sleep(5) - -def positional_error(actual, predicted): - print(actual, predicted) - - - - ## L2 loss between the two positions - # dist = 0.0 - # count = 0.0 - # for l_a, l_p in zip(actual, predicted): - # dist += np.linalg.norm(l_a[:3] - l_p) - # count += 1.0 - - # print(f"Average positional error (L2 loss between predicted and actual gripper position): {dist / count}") - - -def process_manipulator_positions(manipulator_pose): - position = manipulator_pose.pose.position - PREDICTED_POSITIONS.append([position.x, position.y, position.z]) - - -if __name__ == '__main__': - PREDICTED_POSITIONS = [] - # lock = threading.Lock() - rospy.init_node("evaluation") - rospy.Subscriber("forward_kinematics_keypoints", KinematicsPose, process_manipulator_positions) - - rospy.sleep(1) - - kinematics_pub = rospy.Publisher("evaluation", Joints, queue_size = 10) - - dataset = {} - with open(dataset_path, "rb") as input_file: - dataset = pickle.load(input_file) - - inputs, labels = process_dataset(dataset) - model, history = load_model(model_path, shape = (len(inputs[0]), len(labels[0]))) - predictions = predict(model, inputs) - - ## Plot Overall Loss Graph - plot_history(history) - - ## Calculate error for each joint - loss_fn = nn.HuberLoss() - per_joint_error(labels, predictions, loss_fn) - - ## Calculate error between the predicted and final position with the use of forward kinematics - calcualte_fk(kinematics_pub, predictions) - positional_error(inputs.numpy(), np.array(PREDICTED_POSITIONS)) - - - - - - \ No newline at end of file diff --git a/pose_estimation/scripts/helpers/training_help.py b/pose_estimation/scripts/helpers/training_help.py deleted file mode 100755 index b54b1e41b16f0860d5182bb5fc5b810432ef5a26..0000000000000000000000000000000000000000 --- a/pose_estimation/scripts/helpers/training_help.py +++ /dev/null @@ -1,15 +0,0 @@ -import torch.nn as nn -import torch.nn.functional as F - -class Net(nn.Module): - def __init__(self, input_num, output_num): - super(Net, self).__init__() - self.l1 = nn.Linear(input_num, 32) - # self.l2 = nn.Linear(32, 32) - self.output = nn.Linear(32, output_num) - # self.dropout = nn.Dropout(0.2) - - def forward(self, x): - x = F.tanh(self.l1(x)) - # x = F.tanh(self.dropout(self.l2(x))) - return self.output(x) \ No newline at end of file diff --git a/pose_estimation/scripts/training.py b/pose_estimation/scripts/training.py deleted file mode 100644 index 0fe00bfd28f028b7dcce7b7ebbdfe0f9a1fddc91..0000000000000000000000000000000000000000 --- a/pose_estimation/scripts/training.py +++ /dev/null @@ -1,449 +0,0 @@ -import pickle -import rospy -import os -import pypareto -import torch -import torch.nn as nn -import torch.optim as optim -import numpy as np -import matplotlib.pyplot as plt - -from tqdm import tqdm -from random import choice, random, uniform -from open_manipulator_msgs.msg import KinematicsPose -from pose_estimation.msg import Joints - -from helpers.training_help import Net - - -dataset_name = rospy.get_param('/training/dataset') -DATASET_PATH = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/{dataset_name}") - -model_name = rospy.get_param('/training/model') -MODEL_SAVE_PATH = os.path.expanduser(f"~/catkin_ws/src/pose_estimation/data/models/{model_name}") - -criterion = rospy.get_param('/training/loss') -scheduler = rospy.get_param('/training/scheduler') -learning_rate = rospy.get_param('/training/initial_lr') -EPOCHS = rospy.get_param('/training/epochs') - -PLOT = rospy.get_param('/training/plot') -EVALUATE = rospy.get_param('/training/evaluate') -VALIDATE = rospy.get_param('/training/validate') - -RUN_NAS = rospy.get_param('/training/NAS') -NAS_iter = rospy.get_param('/training/NAS_iter') - -LEARNING_RATE = 1e-1 -CRITERION = None -SCHEDULER = None -CHECKPOINT_LOG = 1 - -def validate_params(): - global CRITERION, SCHEDULER, LEARNING_RATE, CHECKPOINT_LOG - - if type(EPOCHS) != int: - print(f"Epochs have to be of integer type") - return False - - if type(EVALUATE) != bool or type(PLOT) != bool or type(VALIDATE) != bool: - print(f"`evaluate`, `validate` and `plot` flags need to be booleans") - return False - try: - LEARNING_RATE = float(learning_rate) - except Exception as conversion_exp: - print(f"Learning rate incorrect. Exception when converting: {conversion_exp}") - return False - - if criterion == "mse": - CRITERION = nn.MSELoss() - elif criterion == "huber": - CRITERION = nn.HuberLoss() - else: - print(f"Given loss [{criterion}] not valid") - return False - - if VALIDATE: - CHECKPOINT_LOG = 1 - else: - CHECKPOINT_LOG = 5 - - if scheduler == "None": - SCHEDULER = None - # scheduler = optim.lr_scheduler.StepLR(optimizer, step_size=25, gamma=9e-1) - else: - print(f"Given scheduler [{scheduler}] not valid") - return False - - return True - - -def list_to_tensor(arr): - return torch.tensor(arr) - -def process_dataset(dataset): - inputs = [] - labels = [] - - for data in dataset: - actual_values = [] - for joint in data['jointPositions']: - actual_values.append(joint.angle) - - labels.append(actual_values) - - man_pos = data['manipulatorPositions'] - man_angle = data['angle'] - x = [man_pos.x, man_pos.y, man_pos.z, man_angle.x, man_angle.y, man_angle.z, man_angle.w] - - inputs.append(x) - - inputs, labels = remove_duplicates(inputs, labels) - - inputs = list_to_tensor(np.array(inputs).astype(np.float32)) - labels = list_to_tensor(labels) - - return (inputs, labels) - -def remove_duplicates(inputs, labels): - processed_inputs, processed_labels = [], [] - - for i in range(len(inputs)): - - duplicates = [] - for j in range(i+1, len(inputs)): - duplicates.append(inputs[i] == inputs[j]) - - if np.array(duplicates).any() == False: - processed_inputs.append(inputs[i]) - processed_labels.append(labels[i]) - - print(f"{len(inputs) - len(processed_inputs)} duplicates have been removed") - return processed_inputs, processed_labels - - -def train(inputs, labels, model, optimizer): - running_loss = 0.0 - running_pos_loss = 0.0 - count = 0 - - model.train() - - for i, data in enumerate(zip(inputs, labels)): - # get the inputs; data is a bath of inputs and labels - input, label = data - - # zero the parameter gradients - optimizer.zero_grad() - - # forward + backward + optimize - outputs = model(input) - loss = CRITERION(outputs, label) - loss.backward() - optimizer.step() - - running_loss += loss.item() - - if VALIDATE: - running_pos_loss += positional_loss(outputs, input).item() - - count += 1 - - train_loss = running_loss / count - valid_loss = running_pos_loss / count - - return train_loss, valid_loss - -def save_model(model_dict): - print(f"Best model has been saved: {MODEL_SAVE_PATH} \n") - print(f" -> Best Loss: {model_dict['train_loss']}") - torch.save(model_dict, MODEL_SAVE_PATH) - -def per_joint_error(labels, predictions, loss_fn = nn.MSELoss()): - errors = {} - joint_labels, joint_predictions = labels.transpose(1,0), predictions.transpose(1,0) - - for joint in range(joint_labels.shape[0]): - error = loss_fn(joint_labels[joint], joint_predictions[joint]) - errors[f"joint{joint+1}"] = error.item() - - print(f"\n-------------------------------\nPer Joint Error: \n{errors}") - print("-------------------------------\n") - -def plot_history(history): - train_loss = history['train_loss'] - plt.plot(train_loss) - plt.show() - - if VALIDATE: - valid_loss = history['valid_loss'] - plt.plot(valid_loss) - plt.show() - -def predict(model, inputs): - predictions = [] - - with torch.no_grad(): - for input in inputs: - pred = model(input) - predictions.append(pred.numpy()) - - return list_to_tensor(np.array(predictions).astype(np.float32)) - -def dataset_pos_error(predictions, inputs): - error = 0.0 - count = 0.0 - for prediction, input in zip(predictions, inputs): - error += positional_loss(prediction, input).item() - count += 1 - - print(f"\n-------------------------------\nPositional Mean Error: {error / count}") - print("-------------------------------\n") - return(error / count) - -def evaluate_model(model_dict, dataset): - inputs, labels = process_dataset(dataset) - - print("Loading the best model...") - # model = Net(len(inputs[0]), len(labels[0])) - # model.load_state_dict(model_dict['model_state_dict']) - - model = model_dict['model'] - model.eval() - - with torch.no_grad(): - predictions = predict(model, inputs) - - valid_loss = "" - if VALIDATE: - valid_loss = f"-> {model_dict['valid_loss']} positional error" - - print(f"""Best model was trained with: - -> {model_dict['train_loss']} per joint error - {valid_loss}""") - - history = model_dict['history'] - - if PLOT: plot_history(history) - - per_joint_error(labels, predictions, CRITERION) - - if not VALIDATE: - dataset_pos_error(inputs, predictions) - -def solve_fk(prediction): - global kinematics_pub - - msg = Joints() - joints = [val.item() for val in prediction] - msg.angles = joints - - kinematics_pub.publish(msg) - return_msg = rospy.wait_for_message('/forward_kinematics_keypoints', KinematicsPose) - position = return_msg.pose.position - - return torch.tensor([position.x, position.y, position.z]) - - -def positional_loss(prediction, inputs): - predicted_position = solve_fk(prediction) - actual_position = inputs[:3] - - cost_fn = nn.HuberLoss() - cost = cost_fn(actual_position, predicted_position) - - return cost - - -def create_model(input_size, output_size): - m_choices = [8, 16, 32, 64, 128] - n_choices = [8, 16, 32, 64, 128, 256] - l_choices = [8, 16, 32, 64, 128] - layer_prob = [0.9, 0.6, 0.6] - - activation_choices = [nn.Sigmoid(), nn.Tanh(), nn.ReLU(), nn.ELU(), None] - dropout_range = (0.0, 0.5) - - layers = [choice(m_choices), choice(n_choices), choice(l_choices)] - act_f = choice(activation_choices) - - modules = [] - prev = input_size - - for layer_num, layer in enumerate(layers): - - if random() <= layer_prob[layer_num]: - modules.append(nn.Linear(prev, layer)) - - dropout = round(uniform(dropout_range[0], dropout_range[1]), 2) - modules.append(nn.Dropout(dropout)) - if act_f is not None: - modules.append(act_f) - prev = layer - - modules.append(nn.Linear(prev, output_size)) - sequential = nn.Sequential(*modules) - - return sequential - -def optimal_pareto(history): - values = [] - - for idx, his in enumerate(history): - value = his['min_loss'], his['pos_err'] - values.append(value) - - chain = pypareto.Comparison(pypareto.by_value, pypareto.MaxMinList(pypareto.MaxMin.MIN, pypareto.MaxMin.MIN)).as_chain() - pareto_front = chain.split_by_pareto(values)[0] - - pareto_front_idx = [idx for idx, value in enumerate(values) if value in pareto_front] - mid = pareto_front_idx[int(round(len(pareto_front_idx) / 2, 0))] - - for idx in pareto_front_idx: - print(history[idx]) - - best_model = history[mid] - - if PLOT: - plt.scatter([value[0] for value in values], - [value[1] for value in values], - c = ["red" if value in pareto_front else "blue" for value in values]) - - plt.xlabel("Joint Loss") - plt.ylabel("Positional Loss") - - plt.show() - - return best_model - - - -def run_nas(inputs, labels): - global LEARNING_RATE - - HISTORY = [] - - lr_range = [1e-4, 5e-3, 1e-1] - - for iter in tqdm(range(NAS_iter)): - - best_model_iter = None - for initial_lr in lr_range: - model = create_model(inputs.shape[1], labels.shape[1]) - - local_history = [] - optimizer = torch.optim.SGD(model.parameters(), lr=initial_lr, momentum=0.9) - - for epoch in range(EPOCHS): - loss, _ = train(inputs, labels, model, optimizer) - local_history.append(loss) - - - min_idx = 0 - for i in range(len(local_history)): - if local_history[i] <= local_history[min_idx]: - min_idx = i - - if best_model_iter is None or best_model_iter['min_loss'] >= local_history[min_idx]: - best_model_iter = { - "lr": initial_lr, - "min_loss": local_history[min_idx], - "best_epoch": min_idx, - "model": model - } - - ### Evaluate Positional Loss - predictions = predict(model, inputs) - pos_err = dataset_pos_error(inputs, predictions) - - best_model_iter['pos_err'] = pos_err - HISTORY.append(best_model_iter) - - best_model = optimal_pareto(HISTORY) - LEARNING_RATE = best_model['lr'] - return best_model['model'] - -def training_loop(dataset): - inputs, labels = process_dataset(dataset) - - if RUN_NAS: - model = run_nas(inputs, labels) - else: - model = Net(len(inputs[0]), len(labels[0])) - - print("\nTraining Hyperparameters:") - print(f"-> Model create with {len(inputs[0])} inputs and {len(labels[0])} outputs") - print(f"-> Training Epochs: {EPOCHS}") - print(f"-> Adam Optimizer (initial learning rate of {LEARNING_RATE})") - print(f"-> Cost Function based on {criterion} loss") - print(f"-> Scheduler: {SCHEDULER}\n") - - optimizer = optim.Adam(model.parameters(), lr = LEARNING_RATE) - - best_model = None - history = {"train_loss": []} - - if VALIDATE: - history['valid_loss'] = [] - - for epoch in range(EPOCHS): - - train_loss, val_loss = train(inputs, labels, model, optimizer) - - if epoch % CHECKPOINT_LOG == 0: - print(f'Epoch {epoch} loss: {train_loss}') - print(f"Learning Rate: {optimizer.param_groups[0]['lr']}") - if VALIDATE: - print(f"Positional Validation Loss: {val_loss}") - print("-----------------------------------------\n") - - if SCHEDULER: - SCHEDULER.step() - - loss_tag = "valid_loss" if VALIDATE else "train_loss" - loss = train_loss if not VALIDATE else val_loss - if best_model is None or loss <= best_model[loss_tag]: - best_model = { - 'epoch': epoch, - 'train_loss': train_loss, - 'model': model, - # 'model_state_dict': model.state_dict(), - 'optimizer_state_dict': optimizer.state_dict() - } - if VALIDATE: - best_model['valid_loss'] = val_loss - - history['train_loss'].append(train_loss) - - if VALIDATE: - history['valid_loss'].append(val_loss) - - best_model['history'] = history - - print('Finished Training') - save_model(best_model) - - return best_model - - -if __name__ == '__main__': - rospy.init_node("training") - kinematics_pub = rospy.Publisher("evaluation", Joints, queue_size = 10) - rospy.sleep(1) - - try: - if validate_params(): - dataset = {} - with open(DATASET_PATH, "rb") as input_file: - dataset = pickle.load(input_file) - print(f"There are {len(dataset)} points in the dataset") - - print("Training starting...") - model_dict = training_loop(dataset) - - if EVALUATE: - print("Evaluation starting...") - evaluate_model(model_dict, dataset) - - except Exception as e: - rospy.logwarn(f"Exception thrown: {e}") diff --git a/pose_estimation/src/inverse_kinematics_solver.cpp b/pose_estimation/src/inverse_kinematics_solver.cpp deleted file mode 100755 index 6e266aa06ba10cd3b0e6b4eb4bc65951e3ad1909..0000000000000000000000000000000000000000 --- a/pose_estimation/src/inverse_kinematics_solver.cpp +++ /dev/null @@ -1,72 +0,0 @@ - -#include "pose_estimation/inverse_kinematics_solver.h" - -InverseKinematicsSolver::InverseKinematicsSolver(bool using_platform, std::string usb_port, std::string baud_rate, double control_period) -{ - log::info("Setting up the IK Solver for Open Manipulator"); - - open_manipulator_.initOpenManipulator(using_platform, usb_port, baud_rate, control_period); - goal_joint_value_ = new std::vector<JointValue>(); - - kinematics_ = new kinematics::SolverUsingCRAndSRPositionOnlyJacobian(); - open_manipulator_.addKinematics(kinematics_); - log::info("Kinematics Solver Set 'SolverUsingCRandSRPoisionOnlyJacobian'"); - - ik_pub_ = n_.advertise<pose_estimation::JointPositions>("inverse_kinematics_keypoints", 1000); - - log::info("Completed setting up the IK Solver"); -} - -void InverseKinematicsSolver::solveIK(Pose target_pose, const open_manipulator_msgs::KinematicsPose& manipulator_pose) { - pose_estimation::JointPositions msg; - - // TODO: Debug Mode - // std::cout << target_pose.kinematic.position << std::endl; - bool solved = open_manipulator_.solveInverseKinematics("gripper", target_pose, goal_joint_value_); - - - // ? IF FAILED, CHECK THE CLOSEST POSITION - - - int idx = 0; - auto names = open_manipulator_.getManipulator()->getAllActiveJointComponentName(); - for(auto &point : *goal_joint_value_) { - pose_estimation::JointAngle joint; - joint.angle = point.position; - joint.name = names.at(idx); - msg.jointPositions.push_back(joint); - - idx++; - } - - msg.success = solved; - - msg.manipulatorPose = manipulator_pose; - ik_pub_.publish(msg); - log::info("Published the point"); - -} - -void InverseKinematicsSolver::keypointsCallback(const open_manipulator_msgs::KinematicsPose& msg) { - Eigen::Vector3d position; - position[0] = msg.pose.position.x; - position[1] = msg.pose.position.y; - position[2] = msg.pose.position.z; - - Pose target_pose = { position }; - solveIK(target_pose, msg); -} - - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "inverse_kinematics_solver"); - - InverseKinematicsSolver ik_solver(false, "/dev/ttyUSB0", "1000000", 0.010); - - auto n = ik_solver.getNodeHandle(); - ros::Subscriber sub = n.subscribe("captured_keypoints", 100, &InverseKinematicsSolver::keypointsCallback, &ik_solver); - - ros::spin(); - return 0; -} \ No newline at end of file diff --git a/pose_estimation/test/test_movement.mp4 b/pose_estimation/test/test_movement.mp4 deleted file mode 100644 index 7bbdb2211eb91ccf2ff725a6f3481199dd756e24..0000000000000000000000000000000000000000 Binary files a/pose_estimation/test/test_movement.mp4 and /dev/null differ diff --git a/pose_estimation/test/test_movement_2.mp4 b/pose_estimation/test/test_movement_2.mp4 deleted file mode 100644 index 8fd7d20a6dfd5adf805242292b6ce509849dcba3..0000000000000000000000000000000000000000 Binary files a/pose_estimation/test/test_movement_2.mp4 and /dev/null differ