From 20387be4c86cccf8ae55fe87f8570d9f16bbc254 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Fri, 29 Mar 2024 14:58:14 +0100 Subject: [PATCH 1/7] Fix #3 --- .../03_collision_checking-checkpoint.ipynb | 873 ++++++++++++++++++ notebooks/03_collision_checking.ipynb | 140 ++- 2 files changed, 1010 insertions(+), 3 deletions(-) create mode 100644 notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb diff --git a/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb b/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb new file mode 100644 index 0000000..73f4851 --- /dev/null +++ b/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb @@ -0,0 +1,873 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Collision checking tutorial 💥\n", + "\n", + "This notebook shows how to:\n", + "* Set up collision checking for joint configurations\n", + "* Apply collision checking to joint and TCP paths" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 1. Creating a `SceneGraphCollisionChecker` 🛡️\n", + "Drake provides a very convenient class called [`SceneGraphCollisionChecker`](https://drake.mit.edu/doxygen_cxx/group__planning__collision__checker.html) that checks for collisions between the robot's links itself and its environment.\n", + "After you set it up with a `RobotDiagram`, you can check for collisions with:\n", + "```python\n", + "collision_checker.CheckConfigCollisionFree(q)\n", + "```\n", + "Where `q` are all the joint positions of the `MultibodyPlant`.\n", + "\n", + "In the previous notebooks we showed how to quickly create a `RobotDiagram` with a UR5e and Robotiq 2F-85 gripper.\n", + "You might have noticed that gripper introduces 6 degrees of freedom.\n", + "However, in this notebook we will, for simplicity, make the gripper static and do collision checks with the gripper in a fixed open position." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from pydrake.planning import RobotDiagramBuilder\n", + "from pydrake.all import CollisionFilterDeclaration, GeometrySet\n", + "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build\n", + "\n", + "robot_diagram_builder = RobotDiagramBuilder()\n", + "\n", + "meshcat = add_meshcat(robot_diagram_builder)\n", + "arm_index, gripper_index = add_manipulator(robot_diagram_builder, \"ur5e\", \"robotiq_2f_85\", static_gripper=True)\n", + "floor_index = add_floor(robot_diagram_builder)\n", + "robot_diagram, context = finish_build(robot_diagram_builder)\n", + "\n", + "scene = SingleArmScene(robot_diagram, arm_index, gripper_index, meshcat)\n", + "scene" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plant = scene.robot_diagram.plant()\n", + "plant.num_positions(), plant.num_positions(arm_index), plant.num_positions(gripper_index)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from pydrake.planning import SceneGraphCollisionChecker\n", + "\n", + "collision_checker = SceneGraphCollisionChecker(\n", + " model=scene.robot_diagram,\n", + " robot_model_instances=[scene.arm_index, scene.gripper_index],\n", + " edge_step_size=0.125, # Arbitrary value: we don't use the CheckEdgeCollisionFree\n", + " env_collision_padding=0.005,\n", + " self_collision_padding=0.005,\n", + ")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## 2. Checking joint configurations 🤖\n", + "\n", + "Lets test some joint configurations for collisions!\n", + "\n", + "First, the default configuration. You can see in Meshcat that the robot is just barely not colliding with the table." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "collision_checker.CheckConfigCollisionFree(np.zeros(6))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "UR robots are always in self-collsion when elbow joint is at 180 degrees:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "joints_self_collision = np.deg2rad([0, 0, 180, 0, 0, 0])\n", + "collision_checker.CheckConfigCollisionFree(joints_self_collision)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Lets double-check that visually:" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plant = scene.robot_diagram.plant()\n", + "plant_context = plant.GetMyContextFromRoot(context)\n", + "\n", + "plant.SetPositions(plant_context, scene.arm_index, joints_self_collision)\n", + "scene.robot_diagram.ForcedPublish(context) # updates the meshcat visualization" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can make the robot collide with the table by make the shoulder angle slightly larger" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "joints_table_collision = np.deg2rad([0, 5, 0, 0, 0, 0])\n", + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plant.SetPositions(plant_context, scene.arm_index, joints_table_collision)\n", + "scene.robot_diagram.ForcedPublish(context)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can also check which bodies are colliding." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "contact_results = plant.get_contact_results_output_port().Eval(plant_context)\n", + "num_contacts = contact_results.num_point_pair_contacts()\n", + "for i in range(num_contacts):\n", + " contact = contact_results.point_pair_contact_info(i)\n", + " bodyA_name = plant.get_body(contact.bodyA_index()).scoped_name()\n", + " bodyB_name = plant.get_body(contact.bodyB_index()).scoped_name()\n", + " print(f\"Collision between body {bodyA_name} and {bodyB_name}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Checking joint paths 🛤️" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "start_joints = np.deg2rad([0, -90, 90, -90, -90, 0])\n", + "\n", + "print(collision_checker.CheckConfigCollisionFree(start_joints))\n", + "\n", + "plant.SetPositions(plant_context, scene.arm_index, start_joints)\n", + "scene.robot_diagram.ForcedPublish(context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "goal_joints = np.deg2rad([0, -90, 90, 180, -110, 0])\n", + "\n", + "print(collision_checker.CheckConfigCollisionFree(goal_joints))\n", + "\n", + "plant.SetPositions(plant_context, scene.arm_index, goal_joints)\n", + "scene.robot_diagram.ForcedPublish(context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import animate_joint_configurations\n", + "\n", + "joint_path = np.linspace(start_joints, goal_joints, 20)\n", + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, joint_path, context=context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "def path_collisions_as_emojis(is_collision_free: list[bool]):\n", + " \"\"\"Displays an emoji-based visualization of a path's collisions.\n", + "\n", + " Example output: \"✅✅💥✅✅✅💥✅✅✅✅\"\n", + "\n", + " Args:\n", + " is_collision_free: A list of booleans, where True indicates no collision.\n", + "\n", + " Returns:\n", + " A string of emojis representing the collision status of the path.\n", + " \"\"\"\n", + " emojis = [\"✅\" if is_free else \"💥\" for is_free in is_collision_free]\n", + " emoji_str = \"\".join(emojis)\n", + " return emoji_str\n", + "\n", + "print(collision_checker.CheckConfigsCollisionFree(joint_path))\n", + "path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(joint_path))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Checking TCP paths 📏\n", + "\n", + "### Use case 1: Grasping a hanging shirt 👕\n", + "\n", + "For the cloth competition, I've had the problem that my `pregrasp_pose` pose is collision-free, but moving linearly to the `grasp_pose` make the robot elbow collide with the table.\n", + "\n", + "Below is a recreation of this scenario, and a demonstration of how checking the TCP path can help us avoid this problem." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import visualize_frame\n", + "\n", + "\n", + "# grasp_location = np.array([0.2, 0.5, 0.5]) # This moves the robot through a singularlity for some start configurations\n", + "grasp_location = np.array([0.2, 0.4, 0.55])\n", + "\n", + "gripper_forward_direction = np.array([1, 0, 0])\n", + "\n", + "Z = gripper_forward_direction / np.linalg.norm(gripper_forward_direction)\n", + "Y = np.array([0, 0, -1]) # 0, 0, 1 is also an option\n", + "X = np.cross(Y, Z)\n", + "\n", + "grasp_orientation = np.column_stack([X, Y, Z])\n", + "grasp_pose = np.identity(4)\n", + "grasp_pose[0:3, 0:3] = grasp_orientation\n", + "grasp_pose[0:3, 3] = grasp_location\n", + "\n", + "pregrasp_pose = grasp_pose.copy()\n", + "pregrasp_pose[0:3, 3] -= 0.4 * gripper_forward_direction\n", + "\n", + "visualize_frame(scene.meshcat, \"pregrasp_pose\", pregrasp_pose)\n", + "visualize_frame(scene.meshcat, \"grasp_pose\", grasp_pose)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from ur_analytic_ik import ur5e\n", + "\n", + "tcp_transform = np.identity(4)\n", + "tcp_transform[2, 3] = 0.175 # 175 mm in z\n", + "\n", + "start_configurations = ur5e.inverse_kinematics_with_tcp(pregrasp_pose, tcp_transform)\n", + "goal_configurations = ur5e.inverse_kinematics_with_tcp(grasp_pose, tcp_transform)\n", + "\n", + "start_configurations = np.array(start_configurations).squeeze()\n", + "goal_configurations = np.array(goal_configurations).squeeze()\n", + "\n", + "len(start_configurations), len(goal_configurations)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(start_configurations)))\n", + "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(goal_configurations)))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, start_configurations, duration=len(start_configurations))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, goal_configurations, duration=len(goal_configurations))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_typing import HomogeneousMatrixType\n", + "\n", + "\n", + "def interpolate_linearly(a, b, t):\n", + " return a + t * (b - a)\n", + "\n", + "\n", + "def interpolate_pose_path_positions(pose_a: HomogeneousMatrixType, pose_b: HomogeneousMatrixType, n: int):\n", + " pose_path = []\n", + "\n", + " orientation = pose_a[0:3, 0:3]\n", + " for i in np.linspace(0, 1, n):\n", + " pose_interpolated = np.identity(4)\n", + " position = interpolate_linearly(pose_a[0:3, 3], pose_b[0:3, 3], i)\n", + " pose_interpolated[0:3, 0:3] = orientation\n", + " pose_interpolated[0:3, 3] = position\n", + " pose_path.append(pose_interpolated)\n", + " return pose_path\n", + "\n", + "\n", + "tcp_path = interpolate_pose_path_positions(pregrasp_pose, grasp_pose, n=20)\n", + "\n", + "for i, tcp_pose in enumerate(tcp_path):\n", + " visualize_frame(scene.meshcat, f\"tcp_path/pose_{i}\", tcp_pose, length=0.05, opacity=0.1)\n", + "\n", + "\n", + "path_joints_solutions = []\n", + "\n", + "for tcp_pose in tcp_path:\n", + " joint_solutions = ur5e.inverse_kinematics_with_tcp(tcp_pose, tcp_transform)\n", + " path_joints_solutions.append(np.array(joint_solutions).squeeze())\n", + "\n", + "\n", + "path_joints_solutions = np.array(\n", + " path_joints_solutions\n", + ") # note this is not always possible, because the number of solutions can change\n", + "path_joints_solutions.shape" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import create_paths_from_closest_solutions\n", + "\n", + "paths = create_paths_from_closest_solutions(path_joints_solutions)\n", + "paths = np.array(paths)\n", + "paths.shape" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "for i, path in enumerate(paths):\n", + " print(f\"path {i}: {path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path))}\")" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib\n", + "import matplotlib.pyplot as plt\n", + "from airo_drake import calculate_joint_path_outlier_threshold\n", + "\n", + "path_distances = [np.linalg.norm(np.diff(path, axis=0), axis=1) for path in paths]\n", + "thresholds = [calculate_joint_path_outlier_threshold(distances) for distances in path_distances]\n", + "\n", + "colors = matplotlib.colormaps[\"tab10\"].colors[:len(paths)]\n", + "plt.figure(figsize=(20, 8))\n", + "plt.title(\"Distances between the consecutive configurations in the paths\")\n", + "for distances, threshold, color in zip(path_distances, thresholds, colors):\n", + " plt.plot(distances, marker=\"o\", color=color)\n", + " plt.axhline(y=threshold, color=color, linestyle='--')\n", + "plt.legend([f\"path {i}\" for i in range(len(paths))] + [f\"path {i} upper bound\" for i in range(len(paths))])\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import joint_path_has_large_jumps\n", + "\n", + "for i, path in enumerate(paths):\n", + " has_jumps = joint_path_has_large_jumps(path)\n", + "\n", + " distances = np.linalg.norm(np.diff(path, axis=0), axis=1)\n", + " threshold = calculate_joint_path_outlier_threshold(distances)\n", + " jumps = np.where(distances > threshold)[0]\n", + "\n", + " emoji = \"🦘\" if has_jumps else \"✅\"\n", + " print(f\"path {i}: {emoji} {jumps}\")\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", + "\n", + "for path in paths_without_jumps:\n", + " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", + "\n", + "for path in paths_with_collisions:\n", + " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))\n", + "\n", + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_with_collisions[0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", + "\n", + "for path in paths_without_collisions:\n", + " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))\n", + "\n", + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_without_collisions[0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import time_parametrize_toppra\n", + "\n", + "\n", + "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path) for path in paths_without_collisions]\n", + "durations = [trajectory.end_time() for trajectory in trajectories]\n", + "\n", + "print(durations)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake import animate_joint_trajectory\n", + "\n", + "fastest_trajectory = trajectories[np.argmin(durations)]\n", + "animate_joint_trajectory(scene.meshcat, scene.robot_diagram, scene.arm_index, fastest_trajectory, context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "scene.meshcat.Delete(\"grasp_pose\")\n", + "scene.meshcat.Delete(\"pregrasp_pose\")\n", + "scene.meshcat.Delete(\"tcp_path\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Use case two: Closing a Nepresso machine's lever ☕" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Colors\n", + "from pydrake.geometry import Rgba\n", + "yellow = Rgba(1, 1, 0, 0.5)\n", + "cyan = Rgba(0, 1, 1, 0.5)\n", + "magenta = Rgba(1, 0, 1, 0.5)\n", + "\n", + "\n", + "lever_axis_middle = np.array([0.35, 0.0, 0.2])\n", + "lever_axis_direction = np.array([0, -1, 0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from airo_drake.visualization.arrow import visualize_arrow\n", + "from pydrake.geometry import Sphere, Rgba\n", + "from pydrake.math import RigidTransform\n", + "\n", + "\n", + "level_axis_start = lever_axis_middle - 0.1 * lever_axis_direction\n", + "level_axis_end = lever_axis_middle + 0.1 * lever_axis_direction\n", + "visualize_arrow(meshcat, \"lever\", level_axis_start, end=level_axis_end)\n", + "\n", + "\n", + "meshcat.SetTransform(f\"lever/middle\", RigidTransform(p=lever_axis_middle))\n", + "meshcat.SetObject(f\"lever/middle\", Sphere(0.02), yellow)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "lever_length = 0.15\n", + "lever_tip_opened = lever_axis_middle + lever_length * np.array([0, 0, 1])\n", + "\n", + "meshcat.SetTransform(f\"lever/tip\", RigidTransform(p=lever_tip_opened))\n", + "meshcat.SetObject(f\"lever/tip\", Sphere(0.01), cyan)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from airo_typing import Vector3DType\n", + "from scipy.spatial.transform import Rotation\n", + "\n", + "# TODO: this is temporarily copied from Linen until it's available on PyPI\n", + "def rotate_point(point: Vector3DType, center: Vector3DType, axis: Vector3DType, angle: float):\n", + " \"\"\"\n", + " Rotate a point around an axis by a given angle.\n", + "\n", + " Args:\n", + " point: The point to rotate.\n", + " center: The center of the rotation.\n", + " axis: The axis to rotate around, which will be normalized.\n", + " angle: The angle in radians to rotate by.\n", + "\n", + " Returns:\n", + " The rotated point.\n", + " \"\"\"\n", + " unit_axis = axis / np.linalg.norm(axis)\n", + " rotation = Rotation.from_rotvec(angle * unit_axis)\n", + " return center + rotation.apply(point - center)\n", + "\n", + "\n", + "lever_tip_opened, rotate_point(lever_tip_opened, lever_axis_middle, lever_axis_direction, 0.03)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "level_tip_path = []\n", + "\n", + "max_angle = np.deg2rad(90)\n", + "for angle in np.linspace(0, max_angle, 20):\n", + " tip_position_rotated = rotate_point(lever_tip_opened, lever_axis_middle, lever_axis_direction, angle)\n", + " level_tip_path.append(tip_position_rotated)\n", + "\n", + "\n", + "for i, tip_position in enumerate(level_tip_path):\n", + " meshcat.SetTransform(f\"lever/tip_position_{i}\", RigidTransform(p=tip_position))\n", + " meshcat.SetObject(f\"lever/tip_position_{i}\", Sphere(0.005), magenta)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "X = np.array([-1.0, 0.0, 0.0])\n", + "Y = np.array([0.0, 1.0, 0.0])\n", + "Z = np.array([0.0, 0.0, -1.0])\n", + "top_down_orientation = np.column_stack([X, Y, Z])\n", + "\n", + "tcp_path_lever = []\n", + "\n", + "for tip_position in level_tip_path:\n", + " pose = np.identity(4)\n", + " pose[0:3, 3] = tip_position\n", + " pose[0:3, 0:3] = top_down_orientation\n", + " tcp_path_lever.append(pose)\n", + "\n", + "for i, tcp_pose in enumerate(tcp_path_lever):\n", + " visualize_frame(scene.meshcat, f\"tcp_path_lever/pose_{i}\", tcp_pose, length=0.05, opacity=0.1)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "path_joints_solutions = []\n", + "\n", + "for tcp_pose in tcp_path_lever:\n", + " joint_solutions = ur5e.inverse_kinematics_with_tcp(tcp_pose, tcp_transform)\n", + " path_joints_solutions.append(np.array(joint_solutions).squeeze())\n", + "\n", + "paths = create_paths_from_closest_solutions(path_joints_solutions)\n", + "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", + "\n", + "for path in paths_without_jumps:\n", + " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", + "\n", + "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_with_collisions[0])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", + "\n", + "for path in paths_without_collisions:\n", + " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path, joint_acceleration_limit=1.0) for path in paths_without_collisions]\n", + "durations = [trajectory.end_time() for trajectory in trajectories]\n", + "\n", + "print(durations)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "fastest_trajectory = trajectories[np.argmin(durations)]\n", + "animate_joint_trajectory(scene.meshcat, scene.robot_diagram, scene.arm_index, fastest_trajectory, context)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Allowing collisions between bodies 🏳️\n", + "\n", + "It is possible to allow collisions between certain bodies. Just for this example, let's allow collisions between the ur5e and the floor." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "arm_body_indices = plant.GetBodyIndices(arm_index)\n", + "floor_body_indices = plant.GetBodyIndices(floor_index)\n", + "\n", + "import itertools\n", + "body_combinations = itertools.product(arm_body_indices, floor_body_indices)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Let's go to a configuration where only the arm and the floor collide." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "joints_table_collision = np.deg2rad([0, 45, 0, 0, 0, 0])\n", + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plant.SetPositions(plant_context, scene.arm_index, joints_table_collision)\n", + "scene.robot_diagram.ForcedPublish(context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "for body_index_arm, body_index_floor in body_combinations:\n", + " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, True)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We should now see no collisions." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can re-enable collisions equally as easily." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "body_combinations = itertools.product(arm_body_indices, floor_body_indices) # Repopulate the generator.\n", + "for body_index_arm, body_index_floor in body_combinations:\n", + " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, False)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Caveat\n", + "\n", + "The above collision filtering only operates on the collision checker. It will be out of sync with the plant context." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "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.10.13" + } + }, + "nbformat": 4, + "nbformat_minor": 4 +} diff --git a/notebooks/03_collision_checking.ipynb b/notebooks/03_collision_checking.ipynb index 2c30393..73f4851 100644 --- a/notebooks/03_collision_checking.ipynb +++ b/notebooks/03_collision_checking.ipynb @@ -36,13 +36,14 @@ "source": [ "import numpy as np\n", "from pydrake.planning import RobotDiagramBuilder\n", + "from pydrake.all import CollisionFilterDeclaration, GeometrySet\n", "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build\n", "\n", "robot_diagram_builder = RobotDiagramBuilder()\n", "\n", "meshcat = add_meshcat(robot_diagram_builder)\n", "arm_index, gripper_index = add_manipulator(robot_diagram_builder, \"ur5e\", \"robotiq_2f_85\", static_gripper=True)\n", - "add_floor(robot_diagram_builder)\n", + "floor_index = add_floor(robot_diagram_builder)\n", "robot_diagram, context = finish_build(robot_diagram_builder)\n", "\n", "scene = SingleArmScene(robot_diagram, arm_index, gripper_index, meshcat)\n", @@ -160,6 +161,28 @@ "scene.robot_diagram.ForcedPublish(context)" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can also check which bodies are colliding." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "contact_results = plant.get_contact_results_output_port().Eval(plant_context)\n", + "num_contacts = contact_results.num_point_pair_contacts()\n", + "for i in range(num_contacts):\n", + " contact = contact_results.point_pair_contact_info(i)\n", + " bodyA_name = plant.get_body(contact.bodyA_index()).scoped_name()\n", + " bodyB_name = plant.get_body(contact.bodyB_index()).scoped_name()\n", + " print(f\"Collision between body {bodyA_name} and {bodyB_name}\")" + ] + }, { "cell_type": "markdown", "metadata": {}, @@ -707,6 +730,117 @@ "animate_joint_trajectory(scene.meshcat, scene.robot_diagram, scene.arm_index, fastest_trajectory, context)" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Allowing collisions between bodies 🏳️\n", + "\n", + "It is possible to allow collisions between certain bodies. Just for this example, let's allow collisions between the ur5e and the floor." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "arm_body_indices = plant.GetBodyIndices(arm_index)\n", + "floor_body_indices = plant.GetBodyIndices(floor_index)\n", + "\n", + "import itertools\n", + "body_combinations = itertools.product(arm_body_indices, floor_body_indices)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Let's go to a configuration where only the arm and the floor collide." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "joints_table_collision = np.deg2rad([0, 45, 0, 0, 0, 0])\n", + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plant.SetPositions(plant_context, scene.arm_index, joints_table_collision)\n", + "scene.robot_diagram.ForcedPublish(context)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "for body_index_arm, body_index_floor in body_combinations:\n", + " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, True)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We should now see no collisions." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can re-enable collisions equally as easily." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "body_combinations = itertools.product(arm_body_indices, floor_body_indices) # Repopulate the generator.\n", + "for body_index_arm, body_index_floor in body_combinations:\n", + " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, False)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "collision_checker.CheckConfigCollisionFree(joints_table_collision)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Caveat\n", + "\n", + "The above collision filtering only operates on the collision checker. It will be out of sync with the plant context." + ] + }, { "cell_type": "code", "execution_count": null, @@ -717,7 +851,7 @@ ], "metadata": { "kernelspec": { - "display_name": "cloth-competition", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, @@ -735,5 +869,5 @@ } }, "nbformat": 4, - "nbformat_minor": 2 + "nbformat_minor": 4 } From dd5d86e973825e354eb362483a8c32933ec7901f Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Fri, 29 Mar 2024 15:05:15 +0100 Subject: [PATCH 2/7] Remove accidentally added notebook checkpoint --- .../03_collision_checking-checkpoint.ipynb | 873 ------------------ 1 file changed, 873 deletions(-) delete mode 100644 notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb diff --git a/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb b/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb deleted file mode 100644 index 73f4851..0000000 --- a/notebooks/.ipynb_checkpoints/03_collision_checking-checkpoint.ipynb +++ /dev/null @@ -1,873 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Collision checking tutorial 💥\n", - "\n", - "This notebook shows how to:\n", - "* Set up collision checking for joint configurations\n", - "* Apply collision checking to joint and TCP paths" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## 1. Creating a `SceneGraphCollisionChecker` 🛡️\n", - "Drake provides a very convenient class called [`SceneGraphCollisionChecker`](https://drake.mit.edu/doxygen_cxx/group__planning__collision__checker.html) that checks for collisions between the robot's links itself and its environment.\n", - "After you set it up with a `RobotDiagram`, you can check for collisions with:\n", - "```python\n", - "collision_checker.CheckConfigCollisionFree(q)\n", - "```\n", - "Where `q` are all the joint positions of the `MultibodyPlant`.\n", - "\n", - "In the previous notebooks we showed how to quickly create a `RobotDiagram` with a UR5e and Robotiq 2F-85 gripper.\n", - "You might have noticed that gripper introduces 6 degrees of freedom.\n", - "However, in this notebook we will, for simplicity, make the gripper static and do collision checks with the gripper in a fixed open position." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from pydrake.planning import RobotDiagramBuilder\n", - "from pydrake.all import CollisionFilterDeclaration, GeometrySet\n", - "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build\n", - "\n", - "robot_diagram_builder = RobotDiagramBuilder()\n", - "\n", - "meshcat = add_meshcat(robot_diagram_builder)\n", - "arm_index, gripper_index = add_manipulator(robot_diagram_builder, \"ur5e\", \"robotiq_2f_85\", static_gripper=True)\n", - "floor_index = add_floor(robot_diagram_builder)\n", - "robot_diagram, context = finish_build(robot_diagram_builder)\n", - "\n", - "scene = SingleArmScene(robot_diagram, arm_index, gripper_index, meshcat)\n", - "scene" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "plant = scene.robot_diagram.plant()\n", - "plant.num_positions(), plant.num_positions(arm_index), plant.num_positions(gripper_index)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from pydrake.planning import SceneGraphCollisionChecker\n", - "\n", - "collision_checker = SceneGraphCollisionChecker(\n", - " model=scene.robot_diagram,\n", - " robot_model_instances=[scene.arm_index, scene.gripper_index],\n", - " edge_step_size=0.125, # Arbitrary value: we don't use the CheckEdgeCollisionFree\n", - " env_collision_padding=0.005,\n", - " self_collision_padding=0.005,\n", - ")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## 2. Checking joint configurations 🤖\n", - "\n", - "Lets test some joint configurations for collisions!\n", - "\n", - "First, the default configuration. You can see in Meshcat that the robot is just barely not colliding with the table." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "collision_checker.CheckConfigCollisionFree(np.zeros(6))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "UR robots are always in self-collsion when elbow joint is at 180 degrees:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "joints_self_collision = np.deg2rad([0, 0, 180, 0, 0, 0])\n", - "collision_checker.CheckConfigCollisionFree(joints_self_collision)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Lets double-check that visually:" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "plant = scene.robot_diagram.plant()\n", - "plant_context = plant.GetMyContextFromRoot(context)\n", - "\n", - "plant.SetPositions(plant_context, scene.arm_index, joints_self_collision)\n", - "scene.robot_diagram.ForcedPublish(context) # updates the meshcat visualization" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We can make the robot collide with the table by make the shoulder angle slightly larger" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "joints_table_collision = np.deg2rad([0, 5, 0, 0, 0, 0])\n", - "collision_checker.CheckConfigCollisionFree(joints_table_collision)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "plant.SetPositions(plant_context, scene.arm_index, joints_table_collision)\n", - "scene.robot_diagram.ForcedPublish(context)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We can also check which bodies are colliding." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "contact_results = plant.get_contact_results_output_port().Eval(plant_context)\n", - "num_contacts = contact_results.num_point_pair_contacts()\n", - "for i in range(num_contacts):\n", - " contact = contact_results.point_pair_contact_info(i)\n", - " bodyA_name = plant.get_body(contact.bodyA_index()).scoped_name()\n", - " bodyB_name = plant.get_body(contact.bodyB_index()).scoped_name()\n", - " print(f\"Collision between body {bodyA_name} and {bodyB_name}\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Checking joint paths 🛤️" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "start_joints = np.deg2rad([0, -90, 90, -90, -90, 0])\n", - "\n", - "print(collision_checker.CheckConfigCollisionFree(start_joints))\n", - "\n", - "plant.SetPositions(plant_context, scene.arm_index, start_joints)\n", - "scene.robot_diagram.ForcedPublish(context)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "goal_joints = np.deg2rad([0, -90, 90, 180, -110, 0])\n", - "\n", - "print(collision_checker.CheckConfigCollisionFree(goal_joints))\n", - "\n", - "plant.SetPositions(plant_context, scene.arm_index, goal_joints)\n", - "scene.robot_diagram.ForcedPublish(context)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import animate_joint_configurations\n", - "\n", - "joint_path = np.linspace(start_joints, goal_joints, 20)\n", - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, joint_path, context=context)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "def path_collisions_as_emojis(is_collision_free: list[bool]):\n", - " \"\"\"Displays an emoji-based visualization of a path's collisions.\n", - "\n", - " Example output: \"✅✅💥✅✅✅💥✅✅✅✅\"\n", - "\n", - " Args:\n", - " is_collision_free: A list of booleans, where True indicates no collision.\n", - "\n", - " Returns:\n", - " A string of emojis representing the collision status of the path.\n", - " \"\"\"\n", - " emojis = [\"✅\" if is_free else \"💥\" for is_free in is_collision_free]\n", - " emoji_str = \"\".join(emojis)\n", - " return emoji_str\n", - "\n", - "print(collision_checker.CheckConfigsCollisionFree(joint_path))\n", - "path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(joint_path))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Checking TCP paths 📏\n", - "\n", - "### Use case 1: Grasping a hanging shirt 👕\n", - "\n", - "For the cloth competition, I've had the problem that my `pregrasp_pose` pose is collision-free, but moving linearly to the `grasp_pose` make the robot elbow collide with the table.\n", - "\n", - "Below is a recreation of this scenario, and a demonstration of how checking the TCP path can help us avoid this problem." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import visualize_frame\n", - "\n", - "\n", - "# grasp_location = np.array([0.2, 0.5, 0.5]) # This moves the robot through a singularlity for some start configurations\n", - "grasp_location = np.array([0.2, 0.4, 0.55])\n", - "\n", - "gripper_forward_direction = np.array([1, 0, 0])\n", - "\n", - "Z = gripper_forward_direction / np.linalg.norm(gripper_forward_direction)\n", - "Y = np.array([0, 0, -1]) # 0, 0, 1 is also an option\n", - "X = np.cross(Y, Z)\n", - "\n", - "grasp_orientation = np.column_stack([X, Y, Z])\n", - "grasp_pose = np.identity(4)\n", - "grasp_pose[0:3, 0:3] = grasp_orientation\n", - "grasp_pose[0:3, 3] = grasp_location\n", - "\n", - "pregrasp_pose = grasp_pose.copy()\n", - "pregrasp_pose[0:3, 3] -= 0.4 * gripper_forward_direction\n", - "\n", - "visualize_frame(scene.meshcat, \"pregrasp_pose\", pregrasp_pose)\n", - "visualize_frame(scene.meshcat, \"grasp_pose\", grasp_pose)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from ur_analytic_ik import ur5e\n", - "\n", - "tcp_transform = np.identity(4)\n", - "tcp_transform[2, 3] = 0.175 # 175 mm in z\n", - "\n", - "start_configurations = ur5e.inverse_kinematics_with_tcp(pregrasp_pose, tcp_transform)\n", - "goal_configurations = ur5e.inverse_kinematics_with_tcp(grasp_pose, tcp_transform)\n", - "\n", - "start_configurations = np.array(start_configurations).squeeze()\n", - "goal_configurations = np.array(goal_configurations).squeeze()\n", - "\n", - "len(start_configurations), len(goal_configurations)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(start_configurations)))\n", - "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(goal_configurations)))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, start_configurations, duration=len(start_configurations))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, goal_configurations, duration=len(goal_configurations))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_typing import HomogeneousMatrixType\n", - "\n", - "\n", - "def interpolate_linearly(a, b, t):\n", - " return a + t * (b - a)\n", - "\n", - "\n", - "def interpolate_pose_path_positions(pose_a: HomogeneousMatrixType, pose_b: HomogeneousMatrixType, n: int):\n", - " pose_path = []\n", - "\n", - " orientation = pose_a[0:3, 0:3]\n", - " for i in np.linspace(0, 1, n):\n", - " pose_interpolated = np.identity(4)\n", - " position = interpolate_linearly(pose_a[0:3, 3], pose_b[0:3, 3], i)\n", - " pose_interpolated[0:3, 0:3] = orientation\n", - " pose_interpolated[0:3, 3] = position\n", - " pose_path.append(pose_interpolated)\n", - " return pose_path\n", - "\n", - "\n", - "tcp_path = interpolate_pose_path_positions(pregrasp_pose, grasp_pose, n=20)\n", - "\n", - "for i, tcp_pose in enumerate(tcp_path):\n", - " visualize_frame(scene.meshcat, f\"tcp_path/pose_{i}\", tcp_pose, length=0.05, opacity=0.1)\n", - "\n", - "\n", - "path_joints_solutions = []\n", - "\n", - "for tcp_pose in tcp_path:\n", - " joint_solutions = ur5e.inverse_kinematics_with_tcp(tcp_pose, tcp_transform)\n", - " path_joints_solutions.append(np.array(joint_solutions).squeeze())\n", - "\n", - "\n", - "path_joints_solutions = np.array(\n", - " path_joints_solutions\n", - ") # note this is not always possible, because the number of solutions can change\n", - "path_joints_solutions.shape" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import create_paths_from_closest_solutions\n", - "\n", - "paths = create_paths_from_closest_solutions(path_joints_solutions)\n", - "paths = np.array(paths)\n", - "paths.shape" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "for i, path in enumerate(paths):\n", - " print(f\"path {i}: {path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path))}\")" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import matplotlib\n", - "import matplotlib.pyplot as plt\n", - "from airo_drake import calculate_joint_path_outlier_threshold\n", - "\n", - "path_distances = [np.linalg.norm(np.diff(path, axis=0), axis=1) for path in paths]\n", - "thresholds = [calculate_joint_path_outlier_threshold(distances) for distances in path_distances]\n", - "\n", - "colors = matplotlib.colormaps[\"tab10\"].colors[:len(paths)]\n", - "plt.figure(figsize=(20, 8))\n", - "plt.title(\"Distances between the consecutive configurations in the paths\")\n", - "for distances, threshold, color in zip(path_distances, thresholds, colors):\n", - " plt.plot(distances, marker=\"o\", color=color)\n", - " plt.axhline(y=threshold, color=color, linestyle='--')\n", - "plt.legend([f\"path {i}\" for i in range(len(paths))] + [f\"path {i} upper bound\" for i in range(len(paths))])\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import joint_path_has_large_jumps\n", - "\n", - "for i, path in enumerate(paths):\n", - " has_jumps = joint_path_has_large_jumps(path)\n", - "\n", - " distances = np.linalg.norm(np.diff(path, axis=0), axis=1)\n", - " threshold = calculate_joint_path_outlier_threshold(distances)\n", - " jumps = np.where(distances > threshold)[0]\n", - "\n", - " emoji = \"🦘\" if has_jumps else \"✅\"\n", - " print(f\"path {i}: {emoji} {jumps}\")\n", - "\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", - "\n", - "for path in paths_without_jumps:\n", - " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", - "\n", - "for path in paths_with_collisions:\n", - " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))\n", - "\n", - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_with_collisions[0])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", - "\n", - "for path in paths_without_collisions:\n", - " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))\n", - "\n", - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_without_collisions[0])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import time_parametrize_toppra\n", - "\n", - "\n", - "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path) for path in paths_without_collisions]\n", - "durations = [trajectory.end_time() for trajectory in trajectories]\n", - "\n", - "print(durations)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake import animate_joint_trajectory\n", - "\n", - "fastest_trajectory = trajectories[np.argmin(durations)]\n", - "animate_joint_trajectory(scene.meshcat, scene.robot_diagram, scene.arm_index, fastest_trajectory, context)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "scene.meshcat.Delete(\"grasp_pose\")\n", - "scene.meshcat.Delete(\"pregrasp_pose\")\n", - "scene.meshcat.Delete(\"tcp_path\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Use case two: Closing a Nepresso machine's lever ☕" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "# Colors\n", - "from pydrake.geometry import Rgba\n", - "yellow = Rgba(1, 1, 0, 0.5)\n", - "cyan = Rgba(0, 1, 1, 0.5)\n", - "magenta = Rgba(1, 0, 1, 0.5)\n", - "\n", - "\n", - "lever_axis_middle = np.array([0.35, 0.0, 0.2])\n", - "lever_axis_direction = np.array([0, -1, 0])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "from airo_drake.visualization.arrow import visualize_arrow\n", - "from pydrake.geometry import Sphere, Rgba\n", - "from pydrake.math import RigidTransform\n", - "\n", - "\n", - "level_axis_start = lever_axis_middle - 0.1 * lever_axis_direction\n", - "level_axis_end = lever_axis_middle + 0.1 * lever_axis_direction\n", - "visualize_arrow(meshcat, \"lever\", level_axis_start, end=level_axis_end)\n", - "\n", - "\n", - "meshcat.SetTransform(f\"lever/middle\", RigidTransform(p=lever_axis_middle))\n", - "meshcat.SetObject(f\"lever/middle\", Sphere(0.02), yellow)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "lever_length = 0.15\n", - "lever_tip_opened = lever_axis_middle + lever_length * np.array([0, 0, 1])\n", - "\n", - "meshcat.SetTransform(f\"lever/tip\", RigidTransform(p=lever_tip_opened))\n", - "meshcat.SetObject(f\"lever/tip\", Sphere(0.01), cyan)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "import numpy as np\n", - "from airo_typing import Vector3DType\n", - "from scipy.spatial.transform import Rotation\n", - "\n", - "# TODO: this is temporarily copied from Linen until it's available on PyPI\n", - "def rotate_point(point: Vector3DType, center: Vector3DType, axis: Vector3DType, angle: float):\n", - " \"\"\"\n", - " Rotate a point around an axis by a given angle.\n", - "\n", - " Args:\n", - " point: The point to rotate.\n", - " center: The center of the rotation.\n", - " axis: The axis to rotate around, which will be normalized.\n", - " angle: The angle in radians to rotate by.\n", - "\n", - " Returns:\n", - " The rotated point.\n", - " \"\"\"\n", - " unit_axis = axis / np.linalg.norm(axis)\n", - " rotation = Rotation.from_rotvec(angle * unit_axis)\n", - " return center + rotation.apply(point - center)\n", - "\n", - "\n", - "lever_tip_opened, rotate_point(lever_tip_opened, lever_axis_middle, lever_axis_direction, 0.03)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "level_tip_path = []\n", - "\n", - "max_angle = np.deg2rad(90)\n", - "for angle in np.linspace(0, max_angle, 20):\n", - " tip_position_rotated = rotate_point(lever_tip_opened, lever_axis_middle, lever_axis_direction, angle)\n", - " level_tip_path.append(tip_position_rotated)\n", - "\n", - "\n", - "for i, tip_position in enumerate(level_tip_path):\n", - " meshcat.SetTransform(f\"lever/tip_position_{i}\", RigidTransform(p=tip_position))\n", - " meshcat.SetObject(f\"lever/tip_position_{i}\", Sphere(0.005), magenta)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "X = np.array([-1.0, 0.0, 0.0])\n", - "Y = np.array([0.0, 1.0, 0.0])\n", - "Z = np.array([0.0, 0.0, -1.0])\n", - "top_down_orientation = np.column_stack([X, Y, Z])\n", - "\n", - "tcp_path_lever = []\n", - "\n", - "for tip_position in level_tip_path:\n", - " pose = np.identity(4)\n", - " pose[0:3, 3] = tip_position\n", - " pose[0:3, 0:3] = top_down_orientation\n", - " tcp_path_lever.append(pose)\n", - "\n", - "for i, tcp_pose in enumerate(tcp_path_lever):\n", - " visualize_frame(scene.meshcat, f\"tcp_path_lever/pose_{i}\", tcp_pose, length=0.05, opacity=0.1)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "path_joints_solutions = []\n", - "\n", - "for tcp_pose in tcp_path_lever:\n", - " joint_solutions = ur5e.inverse_kinematics_with_tcp(tcp_pose, tcp_transform)\n", - " path_joints_solutions.append(np.array(joint_solutions).squeeze())\n", - "\n", - "paths = create_paths_from_closest_solutions(path_joints_solutions)\n", - "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", - "\n", - "for path in paths_without_jumps:\n", - " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", - "\n", - "animate_joint_configurations(scene.meshcat, scene.robot_diagram, scene.arm_index, paths_with_collisions[0])" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", - "\n", - "for path in paths_without_collisions:\n", - " print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path)))" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path, joint_acceleration_limit=1.0) for path in paths_without_collisions]\n", - "durations = [trajectory.end_time() for trajectory in trajectories]\n", - "\n", - "print(durations)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "fastest_trajectory = trajectories[np.argmin(durations)]\n", - "animate_joint_trajectory(scene.meshcat, scene.robot_diagram, scene.arm_index, fastest_trajectory, context)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Allowing collisions between bodies 🏳️\n", - "\n", - "It is possible to allow collisions between certain bodies. Just for this example, let's allow collisions between the ur5e and the floor." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "arm_body_indices = plant.GetBodyIndices(arm_index)\n", - "floor_body_indices = plant.GetBodyIndices(floor_index)\n", - "\n", - "import itertools\n", - "body_combinations = itertools.product(arm_body_indices, floor_body_indices)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Let's go to a configuration where only the arm and the floor collide." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "joints_table_collision = np.deg2rad([0, 45, 0, 0, 0, 0])\n", - "collision_checker.CheckConfigCollisionFree(joints_table_collision)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "plant.SetPositions(plant_context, scene.arm_index, joints_table_collision)\n", - "scene.robot_diagram.ForcedPublish(context)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "for body_index_arm, body_index_floor in body_combinations:\n", - " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, True)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We should now see no collisions." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "collision_checker.CheckConfigCollisionFree(joints_table_collision)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We can re-enable collisions equally as easily." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "body_combinations = itertools.product(arm_body_indices, floor_body_indices) # Repopulate the generator.\n", - "for body_index_arm, body_index_floor in body_combinations:\n", - " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, False)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [ - "collision_checker.CheckConfigCollisionFree(joints_table_collision)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Caveat\n", - "\n", - "The above collision filtering only operates on the collision checker. It will be out of sync with the plant context." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "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.10.13" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} From 3be8e85b42914e54dc5bdf0df0561c2d0d24daf2 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 2 Apr 2024 10:49:18 +0200 Subject: [PATCH 3/7] Collision checking and filtering with SceneGraphCollisionChecker --- notebooks/03_collision_checking.ipynb | 549 +++++++++++++++++++++----- 1 file changed, 456 insertions(+), 93 deletions(-) diff --git a/notebooks/03_collision_checking.ipynb b/notebooks/03_collision_checking.ipynb index 73f4851..d489017 100644 --- a/notebooks/03_collision_checking.ipynb +++ b/notebooks/03_collision_checking.ipynb @@ -30,13 +30,30 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 1, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "INFO:drake:Meshcat listening for connections at http://localhost:7000\n" + ] + }, + { + "data": { + "text/plain": [ + "SingleArmScene(robot_diagram=, arm_index=ModelInstanceIndex(2), gripper_index=ModelInstanceIndex(3), meshcat=)" + ] + }, + "execution_count": 1, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "import numpy as np\n", - "from pydrake.planning import RobotDiagramBuilder\n", - "from pydrake.all import CollisionFilterDeclaration, GeometrySet\n", + "from pydrake.planning import RobotDiagramBuilder, RobotCollisionType\n", "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build\n", "\n", "robot_diagram_builder = RobotDiagramBuilder()\n", @@ -52,9 +69,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "(6, 6, 0)" + ] + }, + "execution_count": 2, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "plant = scene.robot_diagram.plant()\n", "plant.num_positions(), plant.num_positions(arm_index), plant.num_positions(gripper_index)" @@ -62,9 +90,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "INFO:drake:Allocating contexts to support implicit context parallelism 8\n" + ] + } + ], "source": [ "from pydrake.planning import SceneGraphCollisionChecker\n", "\n", @@ -90,9 +126,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "True" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "collision_checker.CheckConfigCollisionFree(np.zeros(6))" ] @@ -106,9 +153,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 5, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "False" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "joints_self_collision = np.deg2rad([0, 0, 180, 0, 0, 0])\n", "collision_checker.CheckConfigCollisionFree(joints_self_collision)" @@ -123,7 +181,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 6, "metadata": {}, "outputs": [], "source": [ @@ -143,9 +201,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "False" + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "joints_table_collision = np.deg2rad([0, 5, 0, 0, 0, 0])\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" @@ -153,7 +222,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 8, "metadata": {}, "outputs": [], "source": [ @@ -170,17 +239,51 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 9, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Body ur5e::wrist_2_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::wrist_3_link is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::base_link is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::left_outer_knuckle is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::left_outer_finger is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::left_inner_finger is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::left_inner_finger_pad is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::left_inner_knuckle is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::right_outer_knuckle is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::right_outer_finger is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::right_inner_finger is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::right_inner_finger_pad is colliding with body floor::base_link (type: environment)\n", + "Body robotiq_arg2f_85_model::right_inner_knuckle is colliding with body floor::base_link (type: environment)\n" + ] + } + ], "source": [ - "contact_results = plant.get_contact_results_output_port().Eval(plant_context)\n", - "num_contacts = contact_results.num_point_pair_contacts()\n", - "for i in range(num_contacts):\n", - " contact = contact_results.point_pair_contact_info(i)\n", - " bodyA_name = plant.get_body(contact.bodyA_index()).scoped_name()\n", - " bodyB_name = plant.get_body(contact.bodyB_index()).scoped_name()\n", - " print(f\"Collision between body {bodyA_name} and {bodyB_name}\")" + "def print_robot_collisions():\n", + " robot_clearance = collision_checker.CalcRobotClearance(joints_table_collision, 1.0)\n", + " indices_one = robot_clearance.robot_indices()\n", + " indices_two = robot_clearance.other_indices()\n", + " collision_types = robot_clearance.collision_types()\n", + " distances = robot_clearance.distances()\n", + "\n", + " collision_type_strings = {\n", + " RobotCollisionType.kEnvironmentCollision: \"environment\",\n", + " RobotCollisionType.kSelfCollision: \"self\",\n", + " RobotCollisionType.kEnvironmentAndSelfCollision: \"environment and self\"\n", + " }\n", + "\n", + " for index in range(len(indices_one)):\n", + " if distances[index] <= 0.0:\n", + " bodyA_name = plant.get_body(indices_one[index]).scoped_name()\n", + " bodyB_name = plant.get_body(indices_two[index]).scoped_name()\n", + " collision_type = collision_types[index]\n", + " print(f\"Body {bodyA_name} is colliding with body {bodyB_name} (type: {collision_type_strings[collision_type]})\")\n", + "\n", + "print_robot_collisions()" ] }, { @@ -192,9 +295,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 10, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "True\n" + ] + } + ], "source": [ "start_joints = np.deg2rad([0, -90, 90, -90, -90, 0])\n", "\n", @@ -206,9 +317,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 11, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "True\n" + ] + } + ], "source": [ "goal_joints = np.deg2rad([0, -90, 90, 180, -110, 0])\n", "\n", @@ -220,7 +339,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 12, "metadata": {}, "outputs": [], "source": [ @@ -232,9 +351,27 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 13, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]\n" + ] + }, + { + "data": { + "text/plain": [ + "'✅✅✅✅✅✅✅✅💥💥✅✅✅✅✅✅✅✅✅✅'" + ] + }, + "execution_count": 13, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "def path_collisions_as_emojis(is_collision_free: list[bool]):\n", " \"\"\"Displays an emoji-based visualization of a path's collisions.\n", @@ -270,7 +407,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 14, "metadata": {}, "outputs": [], "source": [ @@ -300,9 +437,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 15, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "(8, 8)" + ] + }, + "execution_count": 15, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "from ur_analytic_ik import ur5e\n", "\n", @@ -320,9 +468,18 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 16, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅💥💥✅✅✅✅\n", + "✅💥✅💥✅✅💥✅\n" + ] + } + ], "source": [ "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(start_configurations)))\n", "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(goal_configurations)))" @@ -330,7 +487,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 17, "metadata": {}, "outputs": [], "source": [ @@ -339,7 +496,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 18, "metadata": {}, "outputs": [], "source": [ @@ -348,9 +505,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 19, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "(20, 8, 6)" + ] + }, + "execution_count": 19, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "from airo_typing import HomogeneousMatrixType\n", "\n", @@ -393,9 +561,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 20, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "(8, 20, 6)" + ] + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "from airo_drake import create_paths_from_closest_solutions\n", "\n", @@ -406,9 +585,24 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 21, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "path 0: ✅✅✅💥💥💥💥💥💥💥✅✅✅✅✅✅✅✅✅✅\n", + "path 1: ✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", + "path 2: 💥💥💥💥✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "path 3: 💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥\n", + "path 4: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "path 5: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "path 6: ✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", + "path 7: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" + ] + } + ], "source": [ "for i, path in enumerate(paths):\n", " print(f\"path {i}: {path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path))}\")" @@ -416,9 +610,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 22, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAABjQAAAKqCAYAAACdPreyAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8g+/7EAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOzdeXxU1f3/8dfNLAlkj2SFJGxh35RFFpGg0GhRa92hFXEBv0pqKHWtpWwuiAgEqFRLFUvVKqLIz7ohilqVVUFECGEJYQkkBAJZIDPJ3N8fQwbGJCSBbMD72cc89H7uued+7szkjp3PnHMM0zRNREREREREREREREREGjGfhk5ARERERERERERERESkKipoiIiIiIiIiIiIiIhIo6eChoiIiIiIiIiIiIiINHoqaIiIiIiIiIiIiIiISKOngoaIiIiIiIiIiIiIiDR6KmiIiIiIiIiIiIiIiEijp4KGiIiIiIiIiIiIiIg0eipoiIiIiIiIiIiIiIhIo6eChoiIiIiIiIiIiIiINHoqaIiIiEijNmnSJAzDaOg0Gr3ExES6dOnS0GlcEDIyMjAMgxkzZjR0KnJS2WuycOHChk6l3qxdu5b+/fvj7++PYRhs2LDhgrgfLly4EMMwyMjIaOhUyqnP91nZ87Bu3bo6P1d9WblyJYZh8M477zR0KiIiInIBU0FDRERE6k3ZFzhlDz8/P2JiYkhKSmLOnDnk5+fXynn279/PpEmT2LBhQ630d7F65plnWLp0aUOnUWc+/PBDJk2a1NBpyGneeOMNZs+e3dBpNDin08mtt97K4cOHmTVrFosWLSI+Pr6h06qRC/3+UV0vvvjiBVeI09+piIiINCQVNERERKTeTZkyhUWLFjF//nz+8Ic/ADBu3Di6du3Kjz/+6NX2L3/5C8ePH69R//v372fy5MkqaJyjC/0LyQ8//JDJkyc3dBpymsq+KI2Pj+f48ePceeed9Z9UA9ixYwe7d+/m4YcfZsyYMfz+978nNDT0rO6HDaWy+8edd97J8ePHG2WBpi7eZypoiIiIiNQua0MnICIiIhefa6+9ll69enm2n3jiCT7//HOuu+46brjhBrZs2UKTJk0AsFqtWK36TxaRi1nZiK6LRXZ2NgAhISFe8Ya6H7pcLhwOR628BhaLBYvFUgtZ1b6L7X0mIiIicj7SCA0RERFpFK666iomTJjA7t27+fe//+2JVzRn/PLly7niiisICQkhICCA9u3b8+c//xlwz+Hdu3dvAO6++27P9FZlv5D9+uuvufXWW4mLi8PX15fY2Fj++Mc/lvvV86hRowgICGDfvn3ceOONBAQEEB4ezsMPP0xpaalXW5fLRWpqKl27dsXPz4/w8HCuueaacnOj//vf/6Znz540adKEsLAw7rjjDvbs2ePVJj09nZtvvpmoqCj8/Pxo0aIFd9xxB0ePHq3W87h+/Xr69+9PkyZNaNWqFX//+9/LtSkuLmbixIm0bdvW8xw8+uijFBcXe9oYhkFhYSGvvfaa5zkcNWoUP/74I4ZhsGzZMq9zGobBZZdd5nWea6+9lssvv9wr9tFHHzFw4ED8/f0JDAxk2LBhbN68uVyOW7du5ZZbbiEsLAw/Pz969erldU44NYXZN998w/jx4wkPD8ff35/f/va35OTknPF5GjVqFH/7298811r2+KWXX36ZNm3a4OvrS+/evVm7du1Z5VqZ6rx3SkpKmDp1qiePli1b8uc//9nr9QJo2bIl1113Hf/73//o06cPfn5+tG7dmn/9619e7ZxOJ5MnTyYhIQE/Pz8uueQSrrjiCpYvX35W15WXl8cf//hHWrZsia+vLy1atGDkyJEcOnQIqHzNhLL59leuXAm414H573//y+7duz2vR8uWLYHyaxvMmDEDwzDYvXt3uXyeeOIJ7HY7R44c8cRWr17NNddcQ3BwME2bNmXQoEF88803lb8wpzlx4gSTJk2iXbt2+Pn5ER0dzU033cSOHTs8bQoLC/nTn/5EbGwsvr6+tG/fnhkzZmCapldfhmGQnJzM0qVL6dKlC76+vnTu3JmPP/7Y02bUqFEMGjQIgFtvvRXDMEhMTAQqvh8eP36chx56iGbNmhEYGMgNN9zAvn37MAzDa0q1UaNGeZ7P01XUZ1mer7/+Op07d8bX19eT44wZM+jfvz+XXHIJTZo0oWfPnuXWTKjs/gGVvx9efPFFz7liYmIYO3YseXl5Xm3K1gr6+eefGTx4ME2bNqV58+ZMnz693HXNnTuXzp0707RpU0JDQ+nVqxdvvPFGuXanq2gNjZp8FvxSy5Yt2bx5M19++aXneSh7LcsUFxdX6/5V3XvnL5U931999RX3338/l1xyCUFBQYwcOdLrbwTg/fffZ9iwYcTExODr60ubNm2YOnWq13We6e+0jMvl4umnn6ZFixb4+flx9dVXs337dq825/pZJyIiIhcv/dxRREREGo0777yTP//5z3z66aeMHj26wjabN2/muuuuo1u3bkyZMgVfX1+2b9/u+XKyY8eOTJkyhb/+9a+MGTOGgQMHAtC/f38AFi9eTFFREQ888ACXXHIJa9asYe7cuezdu5fFixd7nau0tJSkpCQuv/xyZsyYwWeffcYLL7xAmzZteOCBBzzt7r33XhYuXMi1117LfffdR0lJCV9//TWrVq3yjER5+umnmTBhArfddhv33XcfOTk5zJ07lyuvvJIffviBkJAQHA4HSUlJFBcX84c//IGoqCj27dvHBx98QF5eHsHBwWd8/o4cOcKvf/1rbrvtNoYPH87bb7/NAw88gN1u55577gHcXzTdcMMN/O9//2PMmDF07NiRTZs2MWvWLLZt2+aZImbRokXcd9999OnThzFjxgDQpk0bunTpQkhICF999RU33HAD4C4S+fj4sHHjRo4dO0ZQUBAul4tvv/3Wc2xZn3fddRdJSUk899xzFBUVMX/+fK644gp++OEHz5dimzdvZsCAATRv3pzHH38cf39/3n77bW688UaWLFnCb3/7W6/r/sMf/kBoaCgTJ04kIyOD2bNnk5yczFtvvVXpc3X//fezf/9+li9fzqJFiyps88Ybb5Cfn8/999+PYRhMnz6dm266iZ07d2Kz2c4q11+qznvnvvvu47XXXuOWW27hT3/6E6tXr+bZZ59ly5YtvPfee179bd++nVtuuYV7772Xu+66i1deeYVRo0bRs2dPOnfuDLi/wH722Wc9r++xY8dYt24d33//PUOHDq3RdRUUFDBw4EC2bNnCPffcw2WXXcahQ4dYtmwZe/fupVmzZme8/tM9+eSTHD16lL179zJr1iwAAgICKmx722238eijj/L222/zyCOPeO17++23+dWvfkVoaCgAn3/+Oddeey09e/Zk4sSJ+Pj48Oqrr3LVVVfx9ddf06dPn0pzKi0t5brrrmPFihXccccdpKSkkJ+fz/Lly/npp59o06YNpmlyww038MUXX3DvvffSo0cPPvnkEx555BH27dvnuZYy//vf/3j33Xd58MEHCQwMZM6cOdx8881kZmZyySWXcP/999O8eXOeeeYZHnroIXr37k1kZGSlOY4aNYq3336bO++8k759+/Lll18ybNiwaj3nZ/L555/z9ttvk5ycTLNmzTx/n6mpqdxwww387ne/w+Fw8J///Idbb72VDz74wHPeyu4flZk0aRKTJ09myJAhPPDAA6SlpTF//nzWrl3LN9984/l7A/d97pprruGmm27itttu45133uGxxx6ja9euXHvttQD84x//4KGHHuKWW24hJSWFEydO8OOPP7J69WpGjBhR4+eiup8FvzR79mz+8Ic/EBAQwJNPPglQ7rWszv2ruvfOM0lOTiYkJIRJkyZ5nt/du3d7CovgLn4EBAQwfvx4AgIC+Pzzz/nrX//KsWPHeP7554Hq/Z1OmzYNHx8fHn74YY4ePcr06dP53e9+x+rVqwHO+bNORERELnKmiIiISD159dVXTcBcu3ZtpW2Cg4PNSy+91LM9ceJE8/T/ZJk1a5YJmDk5OZX2sXbtWhMwX3311XL7ioqKysWeffZZ0zAMc/fu3Z7YXXfdZQLmlClTvNpeeumlZs+ePT3bn3/+uQmYDz30ULl+XS6XaZqmmZGRYVosFvPpp5/22r9p0ybTarV64j/88IMJmIsXL6702iozaNAgEzBfeOEFT6y4uNjs0aOHGRERYTocDtM0TXPRokWmj4+P+fXXX3sd//e//90EzG+++cYT8/f3N++6665y5xo2bJjZp08fz/ZNN91k3nTTTabFYjE/+ugj0zRN8/vvvzcB8/333zdN0zTz8/PNkJAQc/To0V59HThwwAwODvaKX3311WbXrl3NEydOeGIul8vs37+/mZCQ4ImVvZ+GDBniea5N0zT/+Mc/mhaLxczLyzvjczZ27Fizov8c3rVrlwmYl1xyiXn48GFP/P333zcB8//9v/9X41wrUp33zoYNG0zAvO+++7z2P/zwwyZgfv75555YfHy8CZhfffWVJ5adnW36+vqaf/rTnzyx7t27m8OGDTtjbtW9rr/+9a8mYL777ruVXkPZ67Rr1y6v/V988YUJmF988YUnNmzYMDM+Pr5cX2Wvyel/0/369fP6WzRN01yzZo0JmP/61788OSQkJJhJSUle75GioiKzVatW5tChQ8/4PLzyyismYM6cObPS61u6dKkJmE899ZTX/ltuucU0DMPcvn27JwaYdrvdK7Zx40YTMOfOneuJlT03v7wX/PJ+uH79ehMwx40b59Vu1KhRJmBOnDjRE7vrrrsqfG5/2WdZnj4+PubmzZvLtf/lPdThcJhdunQxr7rqKq94ZfePX74fsrOzTbvdbv7qV78yS0tLPe3mzZtnAuYrr7ziiZXd58peX9N03+eioqLMm2++2RP7zW9+Y3bu3LncuatS0fusup8FlencubM5aNCgcvHq3r9qcu+sSNl5evbs6fkcME3TnD59utc92jQr/ny8//77zaZNm3rdCyr7Oy1733bs2NEsLi72xFNTU03A3LRpk2ma5/ZZJyIiIqIpp0RERKRRCQgIID8/v9L9ZXPKv//++7hcrhr3X7Y2B7iniTl06BD9+/fHNE1++OGHcu3/7//+z2t74MCB7Ny507O9ZMkSDMNg4sSJ5Y4t+9Xru+++i8vl4rbbbuPQoUOeR1RUFAkJCXzxxRcAnl+lfvLJJxQVFdX42qxWK/fff79n2263c//995Odnc369esB9wiVjh070qFDB69crrrqKgBPLmcycOBAvv/+ewoLCwH3L85//etf06NHD77++mvAPWrDMAyuuOIKwD1NWF5eHsOHD/c6r8Vi4fLLL/ec9/Dhw3z++efcdttt5Ofne9rl5uaSlJREeno6+/bt88pnzJgxXlPmDBw4kNLS0gqnI6qJ22+/3fMr/7J+Ac/rfza5nq46750PP/wQgPHjx3vt/9Of/gTAf//7X694p06dPHkChIeH0759e6/3bEhICJs3byY9Pb3CvGpyXUuWLKF79+4VjkSpaAqv2nT77bezfv16r6mf3nrrLXx9ffnNb34DwIYNG0hPT2fEiBHk5uZ6rqWwsJCrr76ar7766oz3kSVLltCsWTP+8Ic/lNt3+mtksVh46KGHvPb/6U9/wjRNPvroI6/4kCFDvEYrdOvWjaCgIK/XqLrKpoF68MEHveIV5VtTgwYNolOnTuXip99Djxw5wtGjRz33hLPx2Wef4XA4GDduHD4+p/7v6ejRowkKCir3Hg8ICOD3v/+9Z9tut9OnT59y7/G9e/dWOEXc2arqs+BsVXX/qu69szrnOX2kywMPPIDVavXcY8D7tS372x84cCBFRUVs3bq12td09913Y7fbva4JTt07z/WzTkRERC5uKmiIiIhIo1JQUEBgYGCl+2+//XYGDBjAfffdR2RkJHfccQdvv/12tYsbmZmZjBo1irCwMM9c6GXz1f9y7u6yNQ1OFxoa6jXv+I4dO4iJiSEsLKzSc6anp2OaJgkJCYSHh3s9tmzZ4lkAuFWrVowfP54FCxbQrFkzkpKS+Nvf/lbtOcVjYmLw9/f3irVr1w7AM199eno6mzdvLpdHWbuyXM5k4MCBlJSU8N1335GWlkZ2djYDBw7kyiuv9CpodOrUyfO8lH15ftVVV5U796effuo57/bt2zFNkwkTJpRrV/bF/y9zjIuL89ouK0L8cn74mqqq37PJ9XTVee/s3r0bHx8f2rZt6xWPiooiJCSkXNHmlzmX5X36czFlyhTy8vJo164dXbt25ZFHHuHHH3/07K/Jde3YsYMuXbpUmn9duvXWW/Hx8fFMzWOaJosXL+baa68lKCgIOPW+u+uuu8pdy4IFCyguLj7j39eOHTto3779GRfi3r17NzExMeXuWx07dvTsP111XqPqKnt/tGrVyiv+y/fL2fhln2U++OAD+vbti5+fH2FhYYSHhzN//vyzXvug7Plp3769V9xut9O6detyz1+LFi3KFct++fw99thjBAQE0KdPHxISEhg7dmy110ypSHU+C85WVfeZ6t47q5KQkOC1HRAQQHR0tNdaJps3b+a3v/0twcHBBAUFER4e7ike1eT1reqazvWzTkRERC5uWkNDREREGo29e/dy9OjRM34Z16RJE7766iu++OIL/vvf//Lxxx/z1ltvcdVVV/Hpp59isVgqPba0tJShQ4dy+PBhHnvsMTp06IC/vz/79u1j1KhR5YoiZ+qrJlwuF4Zh8NFHH1XY5+nzj7/wwguMGjWK999/n08//ZSHHnqIZ599llWrVtGiRYtayaVr167MnDmzwv2xsbFV9tGrVy/8/Pz46quviIuLIyIignbt2jFw4EBefPFFiouL+frrr71+tV/23C5atIioqKhyfZZ9YVzW7uGHHyYpKanC8//y/VHZ62T+YkHmmqqq37PJ9WxVd7RDdZ6LK6+8kh07dnjeYwsWLGDWrFn8/e9/57777qv166os96oWVK5KTEwMAwcO5O233+bPf/4zq1atIjMzk+eee87Tpuxann/+eXr06FFhP5Wt01FX6ur9WpWavg6n/1q/zNdff80NN9zAlVdeyYsvvkh0dDQ2m41XX321ygW3a0t1nr+OHTuSlpbGBx98wMcff8ySJUt48cUX+etf/8rkyZNr7Zy1obr3marunecqLy+PQYMGERQUxJQpU2jTpg1+fn58//33PPbYYzUaEVmd16iuP+tERETkwqWChoiIiDQaZYszV/YlahkfHx+uvvpqrr76ambOnMkzzzzDk08+yRdffMGQIUMq/eJu06ZNbNu2jddee42RI0d64suXLz/rnNu0acMnn3zC4cOHK/2lfdnCwa1atfKMhDiTrl270rVrV/7yl7/w7bffMmDAAP7+97/z1FNPnfG4/fv3U1hY6DVKY9u2bQCeRWPbtGnDxo0bufrqq6v8kryy/WVTvHz99dfExcV5phMZOHAgxcXFvP766xw8eJArr7zS6zkAiIiIYMiQIZWes3Xr1gDYbLYztqsN5zol0rnmWp33Tnx8PC6Xi/T0dM8v/gEOHjxIXl4e8fHxZ5V7WFgYd999N3fffTcFBQVceeWVTJo0ifvuu69G19WmTRt++umnM7Yp+3V2Xl6eV7yiKcFq+prcfvvtPPjgg6SlpfHWW2/RtGlTrr/+eq/8AIKCgs76NVq9ejVOp9Nrup7TxcfH89lnn5Gfn+81SqNsip6zfY2qo+z9sWvXLq9f4G/fvr1c29DQ0HKvAVT8OlRmyZIl+Pn58cknn+Dr6+uJv/rqq+XaVve1LHt+0tLSPO89cC8cvWvXrrO+D/j7+3P77bdz++2343A4uOmmm3j66ad54okn8PPzO6s+z8a53meqe++sSnp6OoMHD/ZsFxQUkJWVxa9//WsAVq5cSW5uLu+++67XvXvXrl3l+qqt6eTO9rNORERELm6ackpEREQahc8//5ypU6fSqlUrfve731Xa7vDhw+ViZb+8Li4uBvB8of/LL+/KfjV6+q9ETdMkNTX1rPO++eabMU2zwl/9lp3npptuwmKxMHny5HK/wjZNk9zcXACOHTtGSUmJ1/6uXbvi4+PjubYzKSkp4aWXXvJsOxwOXnrpJcLDw+nZsycAt912G/v27eMf//hHueOPHz/uWRcD3M9jRV+Agrt4sXr1ar744gtPQaNZs2Z07NjR8wv509dySEpKIigoiGeeeQan01muv5ycHMD9pV1iYiIvvfQSWVlZlbarDZW9T6rrXHOtznun7MvG2bNne+0vG2EzbNiwGudd9n4rExAQQNu2bT3vsZpc180338zGjRt57733Kr2Gsi9kv/rqK8++0tJSXn755XLH+Pv712jamZtvvhmLxcKbb77J4sWLue6667wKej179qRNmzbMmDGDgoKCM15LZf0fOnSIefPmldt3+mtUWlpars2sWbMwDINrr7222tdTU2XF3xdffNErPnfu3HJt27Rpw9GjR72mF8vKyqrwtauMxWLBMAyvUR0ZGRksXbq0XNsz3T9ON2TIEOx2O3PmzPG6P/7zn//k6NGjtfIet9vtdOrUCdM0K7z/1KXqPg+Vqe69syovv/yy1/Hz58+npKTE8/6s6PPR4XCUe29Bzf9Of+lcP+tERETk4qYRGiIiIlLvPvroI7Zu3UpJSQkHDx7k888/Z/ny5cTHx7Ns2bIz/np2ypQpfPXVVwwbNoz4+Hiys7N58cUXadGihWcB6jZt2hASEsLf//53AgMD8ff35/LLL6dDhw60adOGhx9+mH379hEUFMSSJUvOaR70wYMHc+eddzJnzhzS09O55pprcLlcfP311wwePJjk5GTatGnDU089xRNPPEFGRgY33ngjgYGB7Nq1i/fee48xY8bw8MMP8/nnn5OcnMytt95Ku3btKCkpYdGiRVgsFm6++eYqc4mJieG5554jIyODdu3a8dZbb7FhwwZefvllz6/L77zzTt5++23+7//+jy+++IIBAwZQWlrK1q1befvtt/nkk0/o1asX4P4y+LPPPmPmzJnExMTQqlUrLr/8csBdrHj66afZs2ePV+Hiyiuv5KWXXqJly5Ze04YEBQUxf/587rzzTi677DLuuOMOwsPDyczM5L///S8DBgzwfCH8t7/9jSuuuIKuXbsyevRoWrduzcGDB/nuu+/Yu3cvGzduPOvX63RlRZ6HHnqIpKQkLBYLd9xxR436OJdcq/Pe6d69O3fddRcvv/yyZ0qYNWvW8Nprr3HjjTd6/eK6ujp16kRiYiI9e/YkLCyMdevW8c4775CcnFzj63rkkUd45513uPXWW7nnnnvo2bMnhw8fZtmyZfz973+ne/fudO7cmb59+/LEE094RqP85z//KfeFJrhfk7feeovx48fTu3dvAgICvEZc/FJERASDBw9m5syZ5Ofnc/vtt3vt9/HxYcGCBVx77bV07tyZu+++m+bNm7Nv3z6++OILgoKC+H//7/9V2v/IkSP517/+xfjx41mzZg0DBw6ksLCQzz77jAcffJDf/OY3XH/99QwePJgnn3ySjIwMunfvzqeffsr777/PuHHjvBYAr209e/bk5ptvZvbs2eTm5tK3b1++/PJLz8is039Jf8cdd/DYY4/x29/+loceeoiioiLmz59Pu3btqr2g97Bhw5g5cybXXHMNI0aMIDs7m7/97W+0bdvWq1BSlltl94/ThYeH88QTTzB58mSuueYabrjhBtLS0njxxRfp3bu31wLg1fWrX/2KqKgoBgwYQGRkJFu2bGHevHkMGzbsjGs01YWePXsyf/58nnrqKdq2bUtERARXXXVVtY+vyb3zTBwOB1dffTW33Xab5/m94ooruOGGGwDo378/oaGh3HXXXTz00EMYhsGiRYsqnAqtpn+nv3Sun3UiIiJykTNFRERE6smrr75qAp6H3W43o6KizKFDh5qpqanmsWPHyh0zceJE8/T/ZFmxYoX5m9/8xoyJiTHtdrsZExNjDh8+3Ny2bZvXce+//77ZqVMn02q1moD56quvmqZpmj///LM5ZMgQMyAgwGzWrJk5evRoc+PGjV5tTNM077rrLtPf37/KfEzTNEtKSsznn3/e7NChg2m3283w8HDz2muvNdevX+/VbsmSJeYVV1xh+vv7m/7+/maHDh3MsWPHmmlpaaZpmubOnTvNe+65x2zTpo3p5+dnhoWFmYMHDzY/++yzKp/bQYMGmZ07dzbXrVtn9uvXz/Tz8zPj4+PNefPmlWvrcDjM5557zuzcubPp6+trhoaGmj179jQnT55sHj161NNu69at5pVXXmk2adLEBMy77rrLs+/YsWOmxWIxAwMDzZKSEk/83//+twmYd955Z4V5fvHFF2ZSUpIZHBxs+vn5mW3atDFHjRplrlu3zqvdjh07zJEjR5pRUVGmzWYzmzdvbl533XXmO++842lT9n5au3ZtuXMA5hdffHHG56ykpMT8wx/+YIaHh5uGYXhe1127dpmA+fzzz5c7BjAnTpxY41zPlENV7x2n02lOnjzZbNWqlWmz2czY2FjziSeeME+cOOHVV3x8vDls2LBy5xg0aJA5aNAgz/ZTTz1l9unTxwwJCTGbNGlidujQwXz66adNh8NxVteVm5trJicnm82bNzftdrvZokUL86677jIPHTrk1deQIUNMX19fMzIy0vzzn/9sLl++vNzrVFBQYI4YMcIMCQkxATM+Pt40zVOvyel/o2X+8Y9/mIAZGBhoHj9+vMLn+YcffjBvuukm85JLLjF9fX3N+Ph487bbbjNXrFhRYfvTFRUVmU8++aTn+Y+KijJvueUWc8eOHZ42+fn55h//+EczJibGtNlsZkJCgvn888+bLpfLqy/AHDt2bLlzxMfHe/19lb2HFy9e7NWuovtPYWGhOXbsWDMsLMwMCAgwb7zxRjMtLc0EzGnTpnm1/fTTT80uXbqYdrvdbN++vfnvf/+7wj4ry9M0TfOf//ynmZCQYPr6+podOnQwX3311Qr7qOz+UfZ3u2vXLq/28+bNMzt06GDabDYzMjLSfOCBB8wjR454tSm7z/3SXXfd5XmvmKZpvvTSS+aVV17peb3btGljPvLII173t4pU9D6ryWdBRQ4cOGAOGzbMDAwMNAHP32JN71/VvXf+Utl5vvzyS3PMmDFmaGioGRAQYP7ud78zc3Nzvdp+8803Zt++fc0mTZqYMTEx5qOPPmp+8skn1f47rex9+8vn9Vw+60REREQM06zj1edERERERESk3mzYsIFLL72Uf//732ecwk8ufAsXLuTuu+9m7dq1ntF3IiIiIuczraEhIiIiIiJynjp+/Hi52OzZs/Hx8fFa3FlERERE5EKgNTRERERERETOU9OnT2f9+vUMHjwYq9XKRx99xEcffcSYMWOIjY1t6PRERERERGqVChoiIiIiIiLnqf79+7N8+XKmTp1KQUEBcXFxTJo0iSeffLKhUxMRERERqXVaQ0NERERERERERERERBo9raEhIiIiIiIiIiIiIiKNngoaIiIiIiIiIiIiIiLS6NX7Ghoul4v9+/cTGBiIYRj1fXoREREREREREREREWlETNMkPz+fmJgYfHwqH4dR7wWN/fv3ExsbW9+nFRERERERERERERGRRmzPnj20aNGi0v31XtAIDAwE3IkFBQXV9+lFRERERERERERERKQROXbsGLGxsZ76QWXqvaBRNs1UUFCQChoiIiIiIiIiIiIiIgJQ5TIVWhRcREREREREREREREQaPRU0RERERERERERERESk0VNBQ0REREREREREREREGr16X0OjOlwuFw6Ho6HTEKkzNpsNi8XS0GmIiIiIiIiIiIiInDcaXUHD4XCwa9cuXC5XQ6ciUqdCQkKIioqqcqEbEREREREREREREWlkBQ3TNMnKysJisRAbG4uPj2bEkguPaZoUFRWRnZ0NQHR0dANnJCIiIiIiIiIiItL4NaqCRklJCUVFRcTExNC0adOGTkekzjRp0gSA7OxsIiIiNP2UiIiIiIiIiIiISBUa1RCI0tJSAOx2ewNnIlL3yop2TqezgTMRERERERERERERafwaVUGjjNYUkIuB3uciIiIiIiIiIiIi1dcoCxoiIiIiIiIiIiIiIiKnU0GjkUtMTGTcuHENnYaIiIiIiIiIiIiISIO6IAsapS6T73bk8v6GfXy3I5dSl9nQKVVp5cqVGIZBXl5erfS3ePFiOnTogJ+fH127duXDDz+slX5FRERERERERERERBqCtaETqG0f/5TF5P/3M1lHT3hi0cF+TLy+E9d0iW7AzOrPt99+y/Dhw3n22We57rrreOONN7jxxhv5/vvv6dKlS0OnJyIiIiIiIiIiIiJSYxfUCI2Pf8rigX9/71XMADhw9AQP/Pt7Pv4pq07Om5iYSHJyMsnJyQQHB9OsWTMmTJiAaZ4aGbJo0SJ69epFYGAgUVFRjBgxguzsbAAyMjIYPHgwAKGhoRiGwahRozzHulwuHn30UcLCwoiKimLSpElnzCc1NZVrrrmGRx55hI4dOzJ16lQuu+wy5s2bV+vXLiIiIiIiIiIiIiJSHxp1QcM0TYocJdV65J9wMnHZZiqaXKosNmnZz+SfcFarv9OLEdXx2muvYbVaWbNmDampqcycOZMFCxZ49judTqZOncrGjRtZunQpGRkZnqJFbGwsS5YsASAtLY2srCxSU1O9+vb392f16tVMnz6dKVOmsHz58kpz+e677xgyZIhXLCkpie+++65G1yQiIiIiIiIiIiIi0lg06imnjjtL6fTXT2qlLxM4cOwEXSd9Wq32P09Joqm9+k9PbGwss2bNwjAM2rdvz6ZNm5g1axajR48G4J577vG0bd26NXPmzKF3794UFBQQEBBAWFgYABEREYSEhHj13a1bNyZOnAhAQkIC8+bNY8WKFQwdOrTCXA4cOEBkZKRXLDIykgMHDlT7ekREREREREREREREGpNGPULjfNK3b18Mw/Bs9+vXj/T0dEpLSwFYv349119/PXFxcQQGBjJo0CAAMjMzq+y7W7duXtvR0dGe6apERERERERERERERC4GjXqERhObhZ+nJFWr7Zpdhxn16toq2y28uzd9WoVV69y1pbCwkKSkJJKSknj99dcJDw8nMzOTpKQkHA5HlcfbbDavbcMwcLlclbaPiori4MGDXrGDBw8SFRV1dhcgIiIiIiIiIiIiItLAGnVBwzCMak/7NDAhnOhgPw4cPVHhOhoGEBXsx8CEcCw+RgUtzs3q1au9tletWkVCQgIWi4WtW7eSm5vLtGnTiI2NBWDdunVe7e12O4BnRMe56NevHytWrGDcuHGe2PLly+nXr9859y0iIiIiIiIiIiIi0hAumCmnLD4GE6/vBLiLF6cr2554fac6KWaAe+qo8ePHk5aWxptvvsncuXNJSUkBIC4uDrvdzty5c9m5cyfLli1j6tSpXsfHx8djGAYffPABOTk5FBQUnHUuKSkpfPzxx7zwwgts3bqVSZMmsW7dOpKTk8/pGkVEREREREREREREGsoFU9AAuKZLNPN/fxlRwX5e8ahgP+b//jKu6RJdZ+ceOXIkx48fp0+fPowdO5aUlBTGjBkDQHh4OAsXLmTx4sV06tSJadOmMWPGDK/jmzdvzuTJk3n88ceJjIw8p+JD//79eeONN3j55Zfp3r0777zzDkuXLqVLly7ndI0iIiIiIiIiIiIXDFcp7PoaNr3j/qfr3GdOEZG6ZZimWdEMTXXm2LFjBAcHc/ToUYKCgrz2nThxgl27dtGqVSv8/Pwq6aFqpS6TNbsOk51/gohAP/q0CquzkRkAiYmJ9OjRg9mzZ9fZOeTCU1vvdxERERERERERqaGfl8HHj8Gx/adiQTFwzXPQ6YaGy0vkInWmusHpGvUaGmfL4mPQr80lDZ2GiIiIiIiIiIiINDY/L4O3R8IvV+I9luWO3/YvFTVEGqkLasopERERERERERERkUq5St0jMzAxXVB40M7R3U0oPGjHdJ0scHz8uKafEmmkLsgRGvVt5cqVDZ2CiIiIiIiIiIiIVGX3t3BsP8f2+HHw+2BKjls8u6xNSom87ChBsfvc7VoNbMBERaQiGqEhIiIiIiIiIiIiF4eCgxzb48e+b0IpOe791WjJcR/2fRPKsT1+UHCwgRIUkTNRQUNEREREREREREQuCmaTcA5+H3xyy/jFXvf2wR+CMJuE12teIlI9KmiIiIiIiIiIiIjIRaHokP3kNFO/LGaUMSgpslJ0yF6faYlINamgISIiIiIiIiIiIheFkkOHa7WdiNQvFTRERERERERERETkomANr95UUtVtJyL1SwUNERERERERERERuSg07dUTa1RU5Q0MA2tUFE179ay/pESk2lTQaOQSExMZN25cQ6chIiIiIiIiIiJy3jMsFiL//MTJLfMXO93rakT++QkMi6V+ExORalFBo5FYuXIlhmGQl5d3zn1t3ryZm2++mZYtW2IYBrNnzz7nPkVERERERERERC4EQb/6FZEj+vHLhcGtkZE0T51N0K9+1TCJiUiVVNC4ABUVFdG6dWumTZtG1JmG0ImIiIiIiIiIiFyE7H4FXtuhl/rTdsVnKmaINHIqaNSCxMREkpOTSU5OJjg4mGbNmjFhwgRM89SwtUWLFtGrVy8CAwOJiopixIgRZGdnA5CRkcHgwYMBCA0NxTAMRo0a5TnW5XLx6KOPEhYWRlRUFJMmTTpjPr179+b555/njjvuwNfXt9avV0RERERERERE5HzmzNzrHSg+qmmmRM4D50VBo8hRUunjhLO01tuejddeew2r1cqaNWtITU1l5syZLFiwwLPf6XQydepUNm7cyNKlS8nIyPAULWJjY1myZAkAaWlpZGVlkZqa6tW3v78/q1evZvr06UyZMoXly5efVZ4iIiIiIiIiIiIXO8eBQwD4NG0CgDOvBI4faciURKQarA2dQHV0+usnle4b3D6cV+/u49nuOfUzjv+icFHm8lZhvHV/P8/2Fc99weFCR7l2GdOG1TjH2NhYZs2ahWEYtG/fnk2bNjFr1ixGjx4NwD333ONp27p1a+bMmUPv3r0pKCggICCAsLAwACIiIggJCfHqu1u3bkycOBGAhIQE5s2bx4oVKxg6dGiN8xQREREREREREbmonTiG44gDaIJ/v8vJX7ESR74FDu+C5qENnZ2InMF5MULjfNC3b18M49RCQv369SM9PZ3SUndxZf369Vx//fXExcURGBjIoEGDAMjMzKyy727dunltR0dHe6arEhERERERERERkRo4sgtHvvt33v6D3NPAOwqtmDnbGzIrEamG82KExs9Tkird53NaEQFg/YQh1W77v8cGn1ti1VRYWEhSUhJJSUm8/vrrhIeHk5mZSVJSEg5H+REiv2Sz2by2DcPA5XLVVboiIiIiIiIiIiIXLPPQdpwFJwsaffpgWAzMUnDu+Al7j9saODsROZPzoqDR1F79NOuqbVVWr17ttb1q1SoSEhKwWCxs3bqV3Nxcpk2bRmxsLADr1q3zam+32wE8IzpERERERERERESk9pXs/AnTZYCPga1FC2zhQTgOHMW5Mw17QycnImekKadqSWZmJuPHjyctLY0333yTuXPnkpKSAkBcXBx2u525c+eyc+dOli1bxtSpU72Oj4+PxzAMPvjgA3JycigoKDjrXBwOBxs2bGDDhg04HA727dvHhg0b2L5dw+ZEREREREREROTi5tiRBoA9PBDDasXeItodz9zTkGmJSDWooFFLRo4cyfHjx+nTpw9jx44lJSWFMWPGABAeHs7ChQtZvHgxnTp1Ytq0acyYMcPr+ObNmzN58mQef/xxIiMjSU5OPutc9u/fz6WXXsqll15KVlYWM2bM4NJLL+W+++47p2sUERERERERERE53zl2u9e0tcVEAmBv2codz8ptsJxEpHrOiymnzgc2m43Zs2czf/78CvcPHz6c4cOHe8VM0/TanjBhAhMmTPCKrVy5slxfS5cuPWMuLVu2LNe3iIiIiIiIiIiIgDPrEGB4Chm2hM7ARziOFENxPvgGNmh+IlI5jdAQERERERERERGRi4OjCMfhEwDYEzq5/9mmg3tXvhUO72qw1ESkaipoiIiIiIiIiIiIyMXhSIa7cAHY23Z0/zM+DgBngRUzd0eDpSYiVdOUU7WgommhREREREREREREpHExc3fgKLAAYI9zFzJs0dHgY2C6oGTnT9i6/LYhUxSRM9AIDREREREREREREbkolOz8CbPUB3zAFhMDgGG1Ym/mXjfDsX1rQ6YnIlVQQUNEREREREREREQuCs4dWwCwhQVg2O2euK15JACOzD0NkpeIVI8KGiIiIiIiIiIiInJRcOzeDYA9JsIrbo9vCYAzK6e+UxKRGlBBQ0RERERERERERC4Kjv3ugoW9ZSuvuD2hs3t/7nFwHq/3vESkelTQEBERERERERERkQtfSTGO3CIA7G07eu2yt+0AgKPACkcy6jszEakmFTRERERERERERETkwndkN44CCwC2tp28dtnj4wFw5Fswc3fUe2oiUj0qaDRyiYmJjBs3rqHTEBEREREREREROa+ZuTtw5lsBsLeM99pni4kBHzBLfSjZ9VNDpCci1XBhFjRcpbDra9j0jvufrtKGzqhKK1euxDAM8vLyzrmvf/zjHwwcOJDQ0FBCQ0MZMmQIa9asOfckRUREREREREREzlOlGZtxlfiAAbYWLbz2GXY7trAAAJzpWxoiPRGpBmtDJ1Drfl4GHz8Gx/afigXFwDXPQacbGi6verRy5UqGDx9O//798fPz47nnnuNXv/oVmzdvpnnz5g2dnoiIiIiIiIiISL1zbP8ZAFtoU3zs9nL77TEROA8V4MjcTdP6Tk5EquXCGqHx8zJ4e6R3MQPgWJY7/vOyOjltYmIiycnJJCcnExwcTLNmzZgwYQKmaXraLFq0iF69ehEYGEhUVBQjRowgOzsbgIyMDAYPHgxAaGgohmEwatQoz7Eul4tHH32UsLAwoqKimDRp0hnzef3113nwwQfp0aMHHTp0YMGCBbhcLlasWFHr1y4iIiIiIiIiInI+cOzOAMAWHVHhfs86Gvuz6yslEamhxl3QME1wFFbvceIYfPQoYFbUkfsfHz/mbled/syK+qnca6+9htVqZc2aNaSmpjJz5kwWLFjg2e90Opk6dSobN25k6dKlZGRkeIoWsbGxLFmyBIC0tDSysrJITU316tvf35/Vq1czffp0pkyZwvLly6udW1FREU6nk7CwsBpdk4iIiIiIiIiIyIWirFBhj4+rcH/ZQuGOQ0VQUlxveYlI9TXuKaecRfBMTC11ZrpHbkyLrV7zP+8Hu3+1e4+NjWXWrFkYhkH79u3ZtGkTs2bNYvTo0QDcc889nratW7dmzpw59O7dm4KCAgICAjzFhoiICEJCQrz67tatGxMnTgQgISGBefPmsWLFCoYOHVqt3B577DFiYmIYMmRIta9HRERERERERETkglHqxJlTCPhhb9uxwib2hJMFjQIL5GVCs4R6TFBEqqNxj9A4j/Tt2xfDMDzb/fr1Iz09ndJS94Lk69ev5/rrrycuLo7AwEAGDRoEQGZmZpV9d+vWzWs7OjraM11VVaZNm8Z//vMf3nvvPfz8/Kp7OSIiIiIiIiIiIheOvEwcBe6vQu1tO1fYpGzKKWe+FTN3Z72lJiLV17hHaNiaukdKVMfub+H1W6pu97t3IL5/9c5dSwoLC0lKSiIpKYnXX3+d8PBwMjMzSUpKwuFwVJ2Kzea1bRgGLperyuNmzJjBtGnT+Oyzz8oVRURERERERERERC4WZu5OHPnur0LtrVpW2MYWGwsGuEp8KN29GWv7pHrMUESqo3EXNAyj+tM+tbkKgmLcC4BXuI6G4d7f5irwsdRmlgCsXr3aa3vVqlUkJCRgsVjYunUrubm5TJs2jdhY95RX69at82pvt9sBPCM6ztX06dN5+umn+eSTT+jVq1et9CkiIiIiIiIiInI+Kt2zBZfTPULDFlvxlPQ+dju20KY4DxfhSP8Z66/qM0MRqY4LZ8opHwtc89zJDeMXO09uXzOtTooZ4J46avz48aSlpfHmm28yd+5cUlJSAIiLi8NutzN37lx27tzJsmXLmDp1qtfx8fHxGIbBBx98QE5ODgUFBWedy3PPPceECRN45ZVXaNmyJQcOHODAgQPn1KeIiIiIiIiIiMj5ypm+GQBrSBN8zjAtuy06HADH7oz6SEtEaujCKWgAdLoBbvsXBEV7x4Ni3PFON9TZqUeOHMnx48fp06cPY8eOJSUlhTFjxgAQHh7OwoULWbx4MZ06dWLatGnMmDHD6/jmzZszefJkHn/8cSIjI0lOTj7rXObPn4/D4eCWW24hOjra8/jlOUVERERERERERC4Gjt27ALBHNztju7J1NBz7DtZ5TiJSc4ZpmhXNz1Rnjh07RnBwMEePHiUoKMhr34kTJ9i1axetWrU6twWsXaXuNTUKDkJApHvNjDoamQGQmJhIjx49mD17dp2dQy48tfZ+FxERERERERGRM8q5sxuH1joJSRpAdOqCStvl/m0W2XNfJij+BM0/TAdL456xX+RCcaa6wekuzL9IHwu0GtjQWYiIiIiIiIiIiEhDc5XiyMkH/LC1aX/GpvaELgA48n3g6B4Ia1UPCYpIdV1YU06JiIiIiIiIiIiInO7YPneBArC363rGpraWJ6ecyrdi5u6o89REpGYuzBEa9WzlypUNnYKIiIiIiIiIiIhU5PBOnPnu6ejtLVuesak9NhYAl9OH0syfsSYMqevsRKQGNEJDRERERERERERELlile36m1HGyoHGyYFEZnyZNsAa71zp1pv9c57mJSM2ooCEiIiIiIiIiIiIXLEf6ZgAsgb74+PtX2d4e3cx93O5ddZqXiNScppwSERERERERERGRC5Zj107gVKHCEy8p4Y2NK8k8doC4oChGdE/EbrVij4+jaOteHPsONES6InIGKmiIiIiIiIiIiIjIBct5sjBhjzs13dTzXy9mUfocTEueJzZzYwh3JjzE3W3aA9/iyD4GrlLwsdRzxiJSGU05JSIiIiIiIiIiIhcmlwtH9lEA7K3bAe5ixms7puDyyfNu6pPHazum8HFpAQDOfB84tr9e0xWRM1NBQ0RERERERERERC5MBQdwHHP/q719VxwlJSxKnwOAYXg3Ldt+68RyABz5Fji8s74yFZFqUEGjkUtMTGTcuHENnYaIiIiIiIiIiMj55/BOHPnuWfdtLVvxxsaVmJa8csWMMoYBWc3yASh1WCjdu6W+MhWRalBBo5FYuXIlhmGQl5d3zn29++679OrVi5CQEPz9/enRoweLFi069yRFRERERERERETOI6V7t1Ba7F4Dwx4XR+axqhf6LrYbOPzdRRBH+k91mp+I1IwWBb8AhYWF8eSTT9KhQwfsdjsffPABd999NxERESQlJTV0eiIiIiIiIiIiIvXCmb4ZAEuAHUtgIHFBUdU6rjQ8CAoP49i1kyZ1maCI1IhGaNSCxMREkpOTSU5OJjg4mGbNmjFhwgRM0/S0WbRoEb169SIwMJCoqChGjBhBdnY2ABkZGQwePBiA0NBQDMNg1KhRnmNdLhePPvooYWFhREVFMWnSpCrz+e1vf0vHjh1p06YNKSkpdOvWjf/973+1fu0iIiIiIiIiIiKNlWPXDgDskWEAjOieiFEawmlf23kxTTBKQoho3RYA576qR3SISP05PwoajsLKH84TNWh7vHptz8Jrr72G1WplzZo1pKamMnPmTBYsWODZ73Q6mTp1Khs3bmTp0qVkZGR4ihaxsbEsWbIEgLS0NLKyskhNTfXq29/fn9WrVzN9+nSmTJnC8uXLq5WXaZqsWLGCtLQ0rrzyyrO6NhERERERERERkfORY+9+AOyxLdz/tFq5M+GhCtuWFTnubPcQfm3bu48/eJRKqx8iUu/OjymnnompfF/Cr+B3i09tP98WnEUVt42/Au7+76nt2V2hKLd8u0lHa5xibGwss2bNwjAM2rdvz6ZNm5g1axajR48G4J577vG0bd26NXPmzKF3794UFBQQEBBAWJi7ShwREUFISIhX3926dWPixInuy01IYN68eaxYsYKhQ4dWms/Ro0dp3rw5xcXFWCwWXnzxxTO2FxERERERERERuaCYJo7sPMCOrXWCJ/zIwFvZejidNXlvejX3KQ3hznYP8cjAWzmWtwwAxzETCg5CYPWmqhKRunV+jNA4D/Tt2xfDMDzb/fr1Iz09ndLSUgDWr1/P9ddfT1xcHIGBgQwaNAiAzMzMKvvu1q2b13Z0dLRnuqrKBAYGsmHDBtauXcvTTz/N+PHjWblyZQ2vSkRERERERERE5DxVeAjnUffoCnsH7+/XovybeW1H+PRh3V1f8MjAWwGwtW4DgKPACod31kOyIlId58cIjT/vr3yfYfHefmT7Gdr+on4zbtPZ51QDhYWFJCUlkZSUxOuvv054eDiZmZkkJSXhcDiqPN5ms3ltG4aBy+U64zE+Pj60beue669Hjx5s2bKFZ599lsTExLO+DhERERERERERkfPG4Z3uggRgb9XGa9f2vF0AmKW+GJZiSsxi7NZTX5Xa4+IAKD1hoXTfFizx/espaRE5k/OjoGH3b/i2VVi9erXX9qpVq0hISMBisbB161Zyc3OZNm0asbGxAKxbt847FbsdwDOio7a5XC6Ki4vrpG8REREREREREZHGxrV/KyXH3T+GLitQlDlQtAeAELpxlLUcK/H+QbUlMBCLv53SQgfObT9hUT1DpFHQlFO1JDMzk/Hjx5OWlsabb77J3LlzSUlJASAuLg673c7cuXPZuXMny5YtY+rUqV7Hx8fHYxgGH3zwATk5ORQUFJx1Ls8++yzLly9n586dbNmyhRdeeIFFixbx+9///pyuUURERERERERE5HzhSHfPzmJpasMSHOy172jJPgAGRLunhXf6HOKE0/vHwPYo95q3jl1nmBFGROqVChq1ZOTIkRw/fpw+ffowduxYUlJSGDNmDADh4eEsXLiQxYsX06lTJ6ZNm8aMGTO8jm/evDmTJ0/m8ccfJzIykuTk5LPOpbCwkAcffJDOnTszYMAAlixZwr///W/uu+++c7pGERERERERERGR84Vjp7sQYYsM9YqfcBZT4pMLwC1dBrmnnTJM1mele7WzxzZ397M3qx6yFZHqOD+mnDoP2Gw2Zs+ezfz58yvcP3z4cIYPH+4VM03Ta3vChAlMmDDBK1bRQt5Lly49Yy5PPfUUTz31VNVJi4iIiIiIiIiIXKCce92jMOyxMV7xdfvTMQwTs9SXHtGx2MwoStjN+n3bGBDXxdPO1joBVq7HcTAPTBMMoz7TF5EKnNMIjWnTpmEYBuPGjauldERERERERERERETOneNgHgD2Vgle8XX709xxMwqb1UKo1V3w2HLIe2ope7tuADiPuqAot46zFZHqOOuCxtq1a3nppZfo1q1bbeYjIiIiIiIiIiIicm6KDuPIKwXA3q6L166tJwsXIScLGTH+8QDszt/t1c7eug0AjgIrHN5Zp+mKSPWcVUGjoKCA3/3ud/zjH/8gNDS06gMucCtXrmT27NkNnYaIiIiIiIiIiIgAHN6Fo8ACnJw66jSZJwsXZYWMdmGtAcgt3uvVzh4XB0DJcQuu/VvrNF0RqZ6zKmiMHTuWYcOGMWTIkCrbFhcXc+zYMa+HiIiIiIiIiIiISF1xHUijpMi9fLA9Pt5r36GThYuyQkb3KHfBo4gsrzVvLSEh+DRx9+FI/6nOcxaRqtW4oPGf//yH77//nmeffbZa7Z999lmCg4M9j9jY2BonKSIiIiIiIiIiIlJdzm2bAPDxs2I5bYYZ0zQ5ThZwqpDRL7Y9pmmAz3H2Hsvx6sceFQaAY2d6faQtIlWoUUFjz549pKSk8Prrr+Pn51etY5544gmOHj3qeezZs+esEhURERERERERERGpDscudwHCHhmCYRie+J5j2eBzAtM06BfbAYCIwECMUnfRY/Ue76ml7C3c62w49+6vj7RFpAo1KmisX7+e7OxsLrvsMqxWK1arlS+//JI5c+ZgtVopLS0td4yvry9BQUFeDxEREREREREREZG64tizDwB7i2iv+KrMLQAYpaFEBAZ44v6Gu92Gg9u82ttbt3X3d+BwneUqItVnrUnjq6++mk2bNnnF7r77bjp06MBjjz2GxWKp1eREREREREREREREaspxIBewYGvV1iu+8aB75EZZAaNMuF8shc7NbD+yyytub9cVeAdHXikcPwJNQhGRhlOjgkZgYCBdunTxivn7+3PJJZeUi4uIiIiIiIiIiIjUuxPHcB4pASzYE7y/s9yR5y5YRPh5r/PbKqglGbmQVZTpFbe1dq+z4SiwwOFd0FwFDZGGVONFwaV+JSYmMm7cuIZOQ0RERERERERE5PxwZJe7AAHY27b32lVWsGgZ1NIr3incPZLjWMk+r7g9Ph6AkiIrrqy0ushWRGrgnAsaK1euZPbs2bWQSu0pdZWy9sBaPtz5IWsPrKXUVX5tj8Zm5cqVGIZBXl5erfb7n//8B8MwuPHGG2u1XxERERERERERkcbIdXAbzqKTBY24OK99R08WLMoKGGV6NXcXPpw+uRQ7HZ64JTQUH193X85076n4RaT+1WjKqfPBZ7s/Y9qaaRwsOuiJRTaN5PE+jzMkfkgDZlb/MjIyePjhhxk4cGBDpyIiIiIiIiIiIlIvnOk/gmlg2H2wNGvmiZ9wFlPik4sB9GneweuY7lGxmKW+GJZivj+wnX6xnQAwDAN7ZAgnMnNx7EzHtz4vRETKuaCmnPps92eMXzneq5gBkF2UzfiV4/ls92d1ct7ExESSk5NJTk4mODiYZs2aMWHCBEzT9LRZtGgRvXr1IjAwkKioKEaMGEF2djbgLjwMHjwYgNDQUAzDYNSoUZ5jXS4Xjz76KGFhYURFRTFp0qQqcyotLeV3v/sdkydPpnXr1rV6vSIiIiIiIiIiIo2VY8c2AOwRwRiG4Ymv25+OYZiYpb50jWrhdYzNasFmRgKwdu9W730t3AuIO/bsrcu0RaQaGnVBwzRNipxF1XrkF+fz7JpnMTHL93Pyf9PWTCO/OL9a/Z1ejKiO1157DavVypo1a0hNTWXmzJksWLDAs9/pdDJ16lQ2btzI0qVLycjI8BQtYmNjWbJkCQBpaWlkZWWRmprq1be/vz+rV69m+vTpTJkyheXLl58xnylTphAREcG9995bo+sQERERERERERE5nzlPFh7sLWK84uv3u9fAsJmR2KyWcseFWN3tt+Tu8IrbW7UBwHHgcK3nKiI106innDpecpzL37i81vo7WHSQ/v/pX622q0espqmtabX7jo2NZdasWRiGQfv27dm0aROzZs1i9OjRANxzzz2etq1bt2bOnDn07t2bgoICAgICCAsLAyAiIoKQkBCvvrt168bEiRMBSEhIYN68eaxYsYKhQ4dWmMv//vc//vnPf7Jhw4Zq5y8iIiIiIiIiInIhcGTlAgb2lt6zlmw95C5UhFqbV3hcc/+WHCpcRWb+bq+4vV1X4H2cRxxQnA++gXWRtohUQ6MeoXE+6du3r9cQtn79+pGenk5pqXtB8vXr13P99dcTFxdHYGAggwYNAiAzM7PKvrt16+a1HR0d7Zmu6pfy8/O58847+cc//kGz0+YIFBERERERERERueA5CnEcKQbA3q6z167d+RkAxPjHV3hoQmgrAA6d2OMVt7d1r7fhKLDC4V21ma2I1FCjHqHRxNqE1SNWV6vt+oPreXDFg1W2e/HqF+kZ2bNa564thYWFJCUlkZSUxOuvv054eDiZmZkkJSXhcDiqPN5ms3ltG4aBy+WqsO2OHTvIyMjg+uuv98TK2lqtVtLS0mjTps05XI2IiIiIiIiIiEgjdSQDR777K09b245euw4V7wWfU4WLX+oe1Y539kIRBzBN0/PjZXtcHADOIgvmwW0Y0d0qPF5E6l6jLmgYhlHtaZ/6x/Qnsmkk2UXZFa6jYWAQ2TSS/jH9sfiUnyPvXK1e7V14WbVqFQkJCVgsFrZu3Upubi7Tpk0jNjYWgHXr1nm1t9vtAJ4RHWerQ4cObNq0ySv2l7/8hfz8fFJTUz3nFxERERERERERudCY2ek4C93f/dnjT43EME2T4xwAoEd0uwqP7RfXDnOtgeFTxL5jObQIjgDA0qwZht0H0+HCsX0Tvj1uqeOrEJHKXDBTTll8LDze53HAXbw4Xdn2Y30eq5NiBrinjho/fjxpaWm8+eabzJ07l5SUFADi4uKw2+3MnTuXnTt3smzZMqZOnep1fHx8PIZh8MEHH5CTk0NBQcFZ5eHn50eXLl28HiEhIQQGBtKlSxdP4URERERERERERORC40z/EUwDw+aDNTzcE99zLBt8jmOaBv1i21d4bGRgEEZpKACr9mz1xA3DwB4RDIBjx7Y6zF5EqnLBFDQAhsQPYWbiTCKaRnjFI5tGMjNxJkPih9TZuUeOHMnx48fp06cPY8eOJSUlhTFjxgAQHh7OwoULWbx4MZ06dWLatGnMmDHD6/jmzZszefJkHn/8cSIjI0lOTq6zXEVERERERERERC5Ejh1pANjDgzB8Tn31uSrTXaAwSkOJCKx8UW9/IxqAjQe9Cxf25u64M3NPuWNEpP406imnzsaQ+CEMjh3M99nfk1OUQ3jTcC6LuKzORmaUsdlszJ49m/nz51e4f/jw4QwfPtwrZpreU2NNmDCBCRMmeMVWrlxZrq+lS5fWKLeFCxfWqL2IiIiIiIiIiMj5yHGy4GBrHukV/zE7HThVsKhMuF8shc7NbD/ivfi3vWVrWP0zjgO5tZitiNTUBVfQAPf0U72jejd0GiIiIiIiIiIiIlKPHFmHALDHey/8vf3ITsBdsDiTlkHxZOTC/qJMr7itXWfgAxyHT4DzONia1F7SIlJtF9SUUyIiIiIiIiIiInKRKinGefg4APaEzl67sk4WKFoGtTxjF53C2wJwrGS/V9zetiMAjnwrHMmohWRF5GxckCM06ltF00KJiIiIiIiIiIhIPTqyG0e+e9p5ezvvgsbRkv1ggc4nCxaV6d28A2wFp88hip0OfG12d3/x8QA4Cy2Y2ekYER3r4AJEpCoaoSEiIiIiIiIiIiLnPTNnO45C9++3ywoQACecxZT4uKei6tW8/Rn76B4Vi+myYxguvj+w3RO3RkRg2HzANHBu/7EOsheR6lBBQ0RERERERERERM57zh0/gsvAsBpYo6I88fVZ6RiGiemy0z3qzGto2KwWbC73guLr9qV54oaPD/bwQAAcO7bWQfYiUh0qaIiIiIiIiIiIiMh5z7ndXWiwNQvE8Dn1tef6fdvccVcUNqulyn5CrM0B2HJoh1fcFuMukjh2Z5Y7RkTqhwoaIiIiIiIiIiIict5z7N4NgD0mwiu+5ZB76qgQa0y1+onxd09XtTs/wytub9nKfZ6sQ+eSpoicAxU0RERERERERERE5LznyMoBwB7f0iu+O99d6CgrVFQlIdRduDh0Yq9X3J7QCQBn7nEoKT6XVEXkLKmgISIiIiIiIiIiIue3UieOQ4UA2E4WHsocKnYXJsoKFVXpEeVeOLyILEzT9MTtCZ0BcORbIE/TTok0BBU0GrnExETGjRvX0GmIiIiIiIiIiIg0XnmZ7kIDYE/o4gmbpslxsoBThYqq9Itrh2ka4FPE/vwcT9we7x7h4Si0YuZsr63MRaQGVNBoJFauXIlhGOTl5Z1zXwsXLsQwDK+Hn5/fuScpIiIiIiIiIiLSCJmHduAssAJgb9nSE99zLAd8jmOaBv3i2lWrr8jAIIzSEAC+27PVE7dGRWFYDHAZOLf/WGu5i0j1qaBxgQoKCiIrK8vz2H1yUSQREREREREREZELTcmOTZguA3zAFh3tia/OdBckjNIQIgODqt2fv+HuY+OBdE/MsFiwNQsAwLlja4XHiUjdUkGjFiQmJpKcnExycjLBwcE0a9aMCRMmeM2xt2jRInr16kVgYCBRUVGMGDGC7OxsADIyMhg8eDAAoaGhGIbBqFGjPMe6XC4effRRwsLCiIqKYtKkSVXmZBgGUVFRnkdkZGStXrOIiIiIiIiIiEhj4dj+MwD2ZgEYVqsnvjF7G3CqQFFd4X6xAGw/stMrbm/u/o7NoR8PizSI86KgUeQsqvRRXFpc7bYnSk5Uq+3ZeO2117BaraxZs4bU1FRmzpzJggULPPudTidTp05l48aNLF26lIyMDE/RIjY2liVLlgCQlpZGVlYWqampXn37+/uzevVqpk+fzpQpU1i+fPkZ8ykoKCA+Pp7Y2Fh+85vfsHnz5rO6LhERERERERERkcaurMBgi47wim8/sgs4VaCorvgg93oZWUV7vOL2+Jbu8+3P+eUhIlIPrFU3aXiXv3F5pfsGNh/Ii0Ne9Gwnvp3I8ZLjFbbtFdmLV6951bN9zZJrOFJ8pFy7TXdtqnGOsbGxzJo1C8MwaN++PZs2bWLWrFmMHj0agHvuucfTtnXr1syZM4fevXtTUFBAQEAAYWFhAERERBASEuLVd7du3Zg4cSIACQkJzJs3jxUrVjB06NAKc2nfvj2vvPIK3bp14+jRo8yYMYP+/fuzefNmWrRoUeNrExERERERERERacyc+90zoZQt3F0mqygTOFWgqK7OzRL4MheOluzzitvadgQ+w5FbCKUlYDkvvl4VuWCcFyM0zgd9+/bFMAzPdr9+/UhPT6e0tBSA9evXc/311xMXF0dgYCCDBg0CIDMzs8q+u3Xr5rUdHR3tma6qIv369WPkyJH06NGDQYMG8e677xIeHs5LL710NpcmIiIiIiIiIiLSeLlKcRwqAMDetqPXrmMnCxKdmyXUqMveLdoD4PQ5RLHT4Ynb23UFwHHMB47uqfBYEak750UJcfWI1ZXus/hYvLZX3ray0rY+hnf95uObPz6nvKqrsLCQpKQkkpKSeP311wkPDyczM5OkpCQcDkeVx9tsNq9twzBwuVzVPr/NZuPSSy9l+/btNc5dRERERERERESkUTu2z11g4FTBAaDY6cDpk4vBqQJFdXWPisN02TF8HPxwYAd9Y92FEnvLlgA4C6yYh7ZjhLWqlUsQkeo5LwoaTW1NG7xtVVav9i66rFq1ioSEBCwWC1u3biU3N5dp06YRG+uer2/dunVe7e12O4BnREdtKi0tZdOmTfz617+u9b5FREREREREREQakpm7A0eB+0fPZQUHgPVZ6RiGC9Nlp3tUXI36tFkt2EojKfHZw7r9aZ6Chi06GnzAdBmU7NiErV3FU8KLSN3QlFO1JDMzk/Hjx5OWlsabb77J3LlzSUlJASAuLg673c7cuXPZuXMny5YtY+rUqV7Hx8fHYxgGH3zwATk5ORQUFJx1LlOmTOHTTz9l586dfP/99/z+979n9+7d3Hfffed0jSIiIiIiIiIiIo1Nyc5NmKU+YIAtJsYTX7cvDQCbKxKb1VLZ4ZUKsTUH4OecU7OeGFYr9ksCAHBs33IuaYvIWVBBo5aMHDmS48eP06dPH8aOHUtKSgpjxowBIDw8nIULF7J48WI6derEtGnTmDFjhtfxzZs3Z/LkyTz++ONERkaSnJx81rkcOXKE0aNH07FjR379619z7Ngxvv32Wzp16nRO1ygiIiIiIiIiItLYONM3A2ALa4pxchYUgC25OwAIsTY/q35j/N2jOnbnZ3jFbdHhADh2ZyAi9eu8mHLqfGCz2Zg9ezbz58+vcP/w4cMZPny4V8w0Ta/tCRMmMGHCBK/YypUry/W1dOnSM+Yya9YsZs2aVXXSIiIiIiIiIiIi5zlHRgYA9pOFhjKZx3YDpwoTNdU2tDU/FsKhE3u94vb4OAp/3IVzf/ZZ9SsiZ08jNEREREREREREROS85dh/EAB7nHfh4lDxHgASQlufVb89otoBUESWV9ze1r2ehiMnH1y1vx6uiFROBQ0RERERERERERE5P7lcOLLzAbC37eAJm6ZJEQcA6H6yMFFT/WJPHudTxP78HE/c3r4bAI58Hzi2/6z6FpGzoymnakFF00KJiIiIiIiIiIhIHSs4gMNdz8B2stAAsO9YDvgUAacVJmooKigYSkLBeoTvMrdyc2f3lFb2lq0AcORbMHN3YITEnsMFiEhNaISGiIiIiIiIiIiInJfM3B04892/2ba3OjW11Ko9W93/UhLqLkycJX8jGoCNB9M9MVtMDBhglvpQsnPTWfctIjWngoaIiIiIiIiIiIicl0ozfsJV4v6K09aihSe+8eA24FRB4mw183X3uf3wTk/MsNuxhTUFwJm++Zz6F5GaUUFDREREREREREREzkuObT8BYAttgo/d7olvP7ILOFWQOFstg1oCsL8o0ytuj27mPv/ujHPqX0RqRgUNEREREREREREROS85MtyFC1v0JV7xsgJEy+CW59R/p/C2ABwt2ecVt8fFuc+/7+A59S8iNaOChoiIiIiIiIiIiJyXHPsOAGCP9V6Y+1jJfgA6NWt7Tv33imkPgNPnEMUlDk/c1qaD+/w5x8A0z+kcIlJ9Kmg0comJiYwbN66h0xAREREREREREWlcTBNn9jEA7G3ae8LFTgdOn0PAqYLE2eoRE4/psmMYLjZknVpHw96+KwCOY0CBRmmI1BcVNBqJlStXYhgGeXl5tdJfXl4eY8eOJTo6Gl9fX9q1a8eHH35YK32LiIiIiIiIiIg0uMJDOI65R0fY23fzhL8/sB3DcGG67PSIiT+nU9itFmyuSADW7t96Kt6qDQDOfCtm7o5zOoeIVJ+1oROoC2ZpKUXr1lOSk4M1PJymvXpiWCwNnVa9cTgcDB06lIiICN555x2aN2/O7t27CQkJaejUREREREREREREaoWZuwNHvvvrTdvJAgPAun1p7pgrErv13L8TDLbGkMsetuScKlzYWrgXG3eV+FCa8RPWlgPO+TwiUrULboTGsU8/ZfvVQ8i86y72P/wwmXfdxfarh3Ds00/r7JyJiYkkJyeTnJxMcHAwzZo1Y8KECZinzZ+3aNEievXqRWBgIFFRUYwYMYLs7GwAMjIyGDx4MAChoaEYhsGoUaM8x7pcLh599FHCwsKIiopi0qRJZ8znlVde4fDhwyxdupQBAwbQsmVLBg0aRPfu3Wv92kVERERERERERBpCaeZmXE7315tli3QDbDnkLjwEW2Nq5TzN/d2jPHbnZ3hiPr6+2EKbAOBI/6lWziMiVbugChrHPv2UfSnjKDlwwCtecvAg+1LG1WlR47XXXsNqtbJmzRpSU1OZOXMmCxYs8Ox3Op1MnTqVjRs3snTpUjIyMjxFi9jYWJYsWQJAWloaWVlZpKamevXt7+/P6tWrmT59OlOmTGH58uWV5rJs2TL69evH2LFjiYyMpEuXLjzzzDOUlpbWzcWLiIiIiIiIiIjUM+c2dyHBGuyHj5+fJ15WeCgrRJyrtqGtAMg5sccrbou6BADHrp3ljhGRutGop5wyTRPz+PHqtS0t5eBTT8NpoyJO6wgMOPj0M/j361et6aeMJk0wDKPaucbGxjJr1iwMw6B9+/Zs2rSJWbNmMXr0aADuueceT9vWrVszZ84cevfuTUFBAQEBAYSFhQEQERFRbmqobt26MXHiRAASEhKYN28eK1asYOjQoRXmsnPnTj7//HN+97vf8eGHH7J9+3YefPBBnE6npx8REREREREREZHzmWOXeySGPSrMK37oxF7wOVWIOFfdIxN4dy8cN71/RG2Pi6Voy16c+w5UcqSI1LbGXdA4fpy0y3rWUmfukRrbevepVvP236/HaNq02t337dvXqwDSr18/XnjhBUpLS7FYLKxfv55JkyaxceNGjhw5gsvlAiAzM5NOnTqdse9u3bp5bUdHR3umq6qIy+UiIiKCl19+GYvFQs+ePdm3bx/PP/+8ChoiIiIiIiIiInJBcOzLAsAe28ITM02TItzx7pHtauU8/WI7wHowLYXsz88hJjDcfd7W7YDvcBw8evIH1dX/cbSInJ0LasqpxqqwsJCkpCSCgoJ4/fXXWbt2Le+99x7gXsC7KjabzWvbMAxPQaQi0dHRtGvXDstpI1E6duzIgQMHqnU+ERERERERERGRxs5xMA8AW5sET2zfsRzwKQKgf1z7WjlPdHAwlIQC8F3mVk/c3t69Xq3jmAlFubVyLhE5s0Y9QsNo0oT236+vVtuidevYM+b+KtvFvvwSTXv1qta5a2L16tVe26tWrSIhIQGLxcLWrVvJzc1l2rRpxMbGArBu3Tqv9na7HaBW1rkYMGAAb7zxBi6XCx8fd81q27ZtREdHe84jIiIiIiIiIiJy3io6jOOo+we/9nanZjdZtfdkwaEklKig4Fo7XVMjiiKOsPHgdm7uPBAAW+s2ADjyrZi5OzD8m9Xa+USkYo16hIZhGPg0bVqth/+AAVijoiof2mUYWKOi8B8woFr91WT9DHBPHTV+/HjS0tJ48803mTt3LikpKQDExcVht9uZO3cuO3fuZNmyZUydOtXr+Pj4eAzD4IMPPiAnJ4eCgoKzes4AHnjgAQ4fPkxKSgrbtm3jv//9L8888wxjx4496z5FREREREREREQajcO7cOa7Zyextzk1tdTGA+mAuwBRm8J93T9S3n7k1ALg9pM/XHY5fSjN3Fyr5xORijXqgkZNGBYLkX9+4uTGL4oRJ7cj//xEtRYEPxsjR47k+PHj9OnTh7Fjx5KSksKYMWMACA8PZ+HChSxevJhOnToxbdo0ZsyY4XV88+bNmTx5Mo8//jiRkZEkJyefdS6xsbF88sknrF27lm7duvHQQw+RkpLC448/fk7XKCIiIiIiIiIi0hiUZm6m1HGyoHGysACnCg5lBYjaEh/UEoD9hbs9MZ8mTbAG+wLg3LapVs8nIhVr1FNO1VTQr34FqbM5+MyzlBw44IlbIyOJ/PMT7v11xGazMXv2bObPn1/h/uHDhzN8+HCvmGmaXtsTJkxgwoQJXrGVK1eW62vp0qVV5tOvXz9WrVpVZTsREREREREREZHzjSPdXUCwBNrx8ff3xLOKMoFTBYja0qlZG746DEdL9nvF7ZFhlBzNwrFrJzWbwF5EzsYFVdAAd1Ej8OqrKVq3npKcHKzh4TTt1bPORmaIiIiIiIiIiIhI/XLs3A6APSrMK360ZD9Y3AWI2tS7eQf+vg2cPjkUlzjwtbrXqbXFtoBtWTj2ZtXq+USkYhdcQQPc00/5X96nodMQERERERERERGROuDc6x4pYY9t7okVOx04fQ5h4C5A1KYeMfGYLjuGj4MNWTu5PNbdv71NO1ixFkd2Xq2eT0QqdkEWNOpbRdNCiYiIiIiIiIiISN1wHDwCWLC3auuJ/XBgB4bhwnTZ6RETX6vns1st2FwRlPjsZd3+tFMFjfbdgNdx5pXC8SPQJLRWzysi3i6YRcFFRERERERERETkInDiGI68EgDs7bp5wuv2pwFgc0Vgt9b+9PPBVvdokJ8P7fDE7G3aAeAosMDhXbV+ThHxpoKGiIiIiIiIiIiInD+O7MJR4J54xta2vSf8c457XY2ywkNti/GPA2D3sVOFC3tsLAClxRZK92yuk/OKyCkqaIiIiIiIiIiIiMh5o3Tvz5SecI/AsMfFeeK78zOAU4WH2tY2tDUAh4r3emI+/v5YAt0LhDvSfqqT84rIKSpoiIiIiIiIiIiIyHnDue1HACz+NiyBgZ74oRPuQkNZ4aG29YhMAKDIleUVt0e6181w7Eqvk/OKyCkqaIiIiIiIiIiIiMh5w7HTPbWUPTLEK16Eu9BQVniobX1PLgRuWgrJyj/kidtjYwBw7t1fJ+cVkVNU0BAREREREREREZHzhmPPPgDsLWI8sf35OeBTBJwqPNS2mOBgKAkB4Ls9Wz1xeyt3AcVx8EidnFdETlFBo5FLTExk3LhxDZ2GiIiIiIiIiIhIo+A4cBgAW6u2nth3mScLDCUh7sJDHWlqRAOw8cCp6aXs7bq68zrihOL8Oju3iKig0WisXLkSwzDIy8s7574SExMxDKPcY9iwYeeeqIiIiIiIiIiISENxFOI84gDA3r6rJ7zhwDbgVMGhroT7tgAg/chOT8zWtqM7tQIrHN5Vp+cXudhZGzoBqX3vvvsuDofDs52bm0v37t259dZbGzArERERERERERGRc3Qkw104AOwJnTzhHUfchYRw39g6PX18UEt2H4aswkxPzB4fB0DpCQul+7Zgie5WpzmIXMw0QqMWJCYmkpycTHJyMsHBwTRr1owJEyZgmqanzaJFi+jVqxeBgYFERUUxYsQIsrOzAcjIyGDw4MEAhIaGYhgGo0aN8hzrcrl49NFHCQsLIyoqikmTJp0xn7J2ZY/ly5fTtGlTFTREREREREREROS85tq/lZLjFgDscXGe+P4id4EhPii+Ts/fqZl7mqu8kn2emCUwEIu/DQBn2o91en6Ri50KGrXktddew2q1smbNGlJTU5k5cyYLFizw7Hc6nUydOpWNGzeydOlSMjIyPEWL2NhYlixZAkBaWhpZWVmkpqZ69e3v78/q1auZPn06U6ZMYfny5dXO7Z///Cd33HEH/v7+tXOxIiIiIiIiIiIiDcCxbSMAliZWLKetlXH0ZIGhrOBQV3o2bw+A0ycHR+mpGVLskSHu/HZuq9Pzi1zszospp1xFRZXvtFjw8fWtXlsfH3z8/Kps69O0aY1zjI2NZdasWRiGQfv27dm0aROzZs1i9OjRANxzzz2etq1bt2bOnDn07t2bgoICAgICCAsLAyAiIoKQkBCvvrt168bEiRMBSEhIYN68eaxYsYKhQ4dWmdeaNWv46aef+Oc//1njaxIREREREREREWlMHDvcBQNb5KliRnGJA6fPIQyg18mCQ125NCYe02XD8HGy8cBOejfvAIC9RQzHd+bg2Lu/Ts8vcrE7LwoaaZf1rHSf/6AriXvpJc/2tgFXYB4/XmHbpr17E7/oX57t7VcPofTIkXLtOm7dUuMc+/bti2EYnu1+/frxwgsvUFpaisViYf369UyaNImNGzdy5MgRXC4XAJmZmXTq1KmybgF3QeN00dHRnumqqvLPf/6Trl270qdPnxpekYiIiIiIiIiISOPi3LMXAHvzU4t//5C1E8NwYbps9Iip2ymnfK1WbK5ISnz2snbvNk9Bw9aqDXy1EceBw3V6fpGLnaacqgeFhYUkJSURFBTE66+/ztq1a3nvvfcAvBbvrozNZvPaNgzDUxCp6rz/+c9/uPfee88ucRERERERERERkUbEkeUuGNhbtfHE1u/fCoDNFYmvte5/vx1sbQ7Az4e2e2L2dl0BcB4uBmfFP7YWkXN3XozQaP/9+sp3Wixem+2++V/lbX286zdtV3x2Lml5Wb16tdf2qlWrSEhIwGKxsHXrVnJzc5k2bRqxsbEArFu3zqu93W4HoLS0tNZyWrx4McXFxfz+97+vtT5FREREREREREQahPMEjsMnAF/sCV084Z9zdgCnCg11LbppLLlFq9l9LMMTs7ftCICjwApHMiCiY73kInKxOS9GaPg0bVr547T1M6pse9r6GWdqezYyMzMZP348aWlpvPnmm8ydO5eUlBQA4uLisNvtzJ07l507d7Js2TKmTp3qdXx8fDyGYfDBBx+Qk5NDQUHBWeVxun/+85/ceOONXHLJJefcl4iIiIiIiIiISIPK242jwP3jZltCZ094d34G4C401IeEUPfokJzivZ6YPd491VXJcQuu/TWfzl5Eque8KGicD0aOHMnx48fp06cPY8eOJSUlhTFjxgAQHh7OwoULWbx4MZ06dWLatGnMmDHD6/jmzZszefJkHn/8cSIjI0lOTj6nfNLS0vjf//6n6aZEREREREREROSC4MraSkmRe8IZe8tTa2XknHAXFsoKDXWtR1RbAIpcpxYAt4SE4NPEXWxxbPuxXvIQuRidF1NOnQ9sNhuzZ89m/vz5Fe4fPnw4w4cP94qZpum1PWHCBCZMmOAVW7lyZbm+li5dWmU+7du3L9e/iIiIiIiIiIjI+cq5bRMAPn4WLKGhnvhxMws4VWioa31jO8J6MC2FZOXnEh3onh3FHhHMid2HcezYhl8VfYjI2dEIDREREREREREREWn0HDvSALCHB2EYBgBZ+YcwLYXAyUJDPYgJDoaSEABW7dnqidtbRAPg3LOnXvIQuRipoCEiIiIiIiIiIiKNnmNPJgD25lGe2HeZJwsKJSHuQkM9aWq4ixcbD2zzxOwt3VNeObJy6y0PkYuNppyqBRVNCyUiIiIiIiIiIiK1x5F1CABby9ae2IaD6cCpAkN9aebbgsySLaQf2emJ2dt1AZbhyD0BJcVg9a3XnEQuBhqhISIiIiIiIiIiIo1bqRNn7nEA7O06e8LbTxYUmvm2qNd04oNaArC/8NT0UraELgA4CiyQl1mv+YhcLFTQEBERERERERERkcYtLxNHvgUAe7uunvD+QnfhoKzAUF86NXMvQJ5XstcTs7eMB6CkyIora2uFx4nIuVFBQ0RERERERERERBo118FtOItOFjTi4z3xoyX7gFMFhvrSq3k7AJw+h3CWOgGwhIbi4+vO0bltY73mI3KxUEFDREREREREREREGjXnto1gGhg2HyzNmgFQXOLA6ZMDnCow1JdLY1piumwYRikbD7invTIMA3tEEACOHWn1mo/IxUIFDREREREREREREWnUHNvdUzjZIwIxDAOAjQd2YhguTJeNS2Na1ms+vlYrNlckAGv3nSpe2GLcMUfmngqPE5Fzo4KGiIiIiIiIiIiINGrOTPdaGfaTBQOAtfvcRQ6bKxJfq7XecwqyxgCwOWe7J2Zv2QoAR9ahes9H5GKggkYjl5iYyLhx4xo6jUZp4cKFhISENHQalZo0aRI9evRo6DRERERERERERM57jiz31FJlBQOAnw+5p3oqKyzUt5imcQDsPrbbE7O36wKAM/c4lJY0SF4iF7ILsqDhcpnsSzvCtrUH2Jd2BJfLbOiUqrRy5UoMwyAvL69W+lu8eDEdOnTAz8+Prl278uGHH9ZKvyIiIiIiIiIiIvXKVYrjUBEA9oROnvDuYxnAqcJCfUsIbQ1ATvGp6aXs7boC4Mj3gaOadkqkttX/WKw6tuOHbL5+K53CvGJPzD/El4G3J9Dm0ogGzKz+fPvttwwfPpxnn32W6667jjfeeIMbb7yR77//ni5dujR0ejXmcDiw2+0NnYaIiIiIiIiIiDSEo3vdBQLA1r6bJ5xzYg/4nCos1LdukQm8tw+KXFmemL1lSwCcRRbMg9swwlpVcrSInI0LaoTGjh+y+filn7yKGQCFecV8/NJP7Pghu07Om5iYSHJyMsnJyQQHB9OsWTMmTJiAaZ4aGbJo0SJ69epFYGAgUVFRjBgxguxsdz4ZGRkMHjwYgNDQUAzDYNSoUZ5jXS4Xjz76KGFhYURFRTFp0qQz5pOamso111zDI488QseOHZk6dSqXXXYZ8+bNq/SYUaNGceONN3rFxo0bR2JiYo2us2XLlkydOpXhw4fj7+9P8+bN+dvf/ubVb15eHvfddx/h4eEEBQVx1VVXsXHjRs/+sqmaFixYQKtWrfDz8zvj9S5dupSEhAT8/PxISkpizx7v6vf8+fNp06YNdrud9u3bs2jRIs++jIwMDMNgw4YNXvkZhsHKlSuBU6NnVqxYQa9evWjatCn9+/cnLS3N6zzTpk0jMjKSwMBA7r33Xk6cOHHGvEVEREREREREpGpmdjrOQgvgPeXUcdNdSOgWmdAgefWL6wCAaSngQP5hACzNmmHYfMA0cGzb0CB5iVzIGnVBwzRNnMWl1XoUHy/h67e2nbG/r99Kp/h4SbX6O/1L+up47bXXsFqtrFmzhtTUVGbOnMmCBQs8+51OJ1OnTmXjxo0sXbqUjIwMT9EiNjaWJUuWAJCWlkZWVhapqaleffv7+7N69WqmT5/OlClTWL58eaW5fPfddwwZMsQrlpSUxHfffVejazqb6wR4/vnn6d69Oz/88AOPP/44KSkpXvneeuutZGdn89FHH7F+/Xouu+wyrr76ag4fPuxps337dpYsWcK7777rVWz4paKiIp5++mn+9a9/8c0335CXl8cdd9zh2f/ee++RkpLCn/70J3766Sfuv/9+7r77br744osaX/uTTz7JCy+8wLp167Bardxzzz2efW+//TaTJk3imWeeYd26dURHR/Piiy/W+BwiIiIiIiIiIuLNmb4RTAPDamANDwcgK/8QpqUQOFVYqG/Ng0OgJBiA7/ZsAcAwDOwRgQA4tqdVdqiInKVGPeVUicPFyylf1lp/hXnFLPjjV9VqOyZ1EDZfS7X7jo2NZdasWRiGQfv27dm0aROzZs1i9OjRAF5ffrdu3Zo5c+bQu3dvCgoKCAgIICwsDICIiIhyC11369aNiRMnApCQkMC8efNYsWIFQ4cOrTCXAwcOEBkZ6RWLjIzkwIED1b6es71OgAEDBvD4448D0K5dO7755htmzZrF0KFD+d///seaNWvIzs7G19cXgBkzZrB06VLeeecdxowZA7inmfrXv/5F+MkPqco4nU7mzZvH5ZdfDrgLLh07dmTNmjX06dOHGTNmMGrUKB588EEAxo8fz6pVq5gxY4ZnVEx1Pf300wwaNAiAxx9/nGHDhnHixAn8/PyYPXs29957L/feey8ATz31FJ999plGaYiIiIiIiIiInCPHdnexwB4eiOHj/n32d5lb3TtLgt2FhQbS1IimiKNsPJDObzsNAMAeE0HxvqM4M3dXcbSI1FSjHqFxPunbty+GYXi2+/XrR3p6OqWlpQCsX7+e66+/nri4OAIDAz1fjGdmZlbZd7du3by2o6OjPdNV1beqrrMsdrp+/fqxZYv7g2fjxo0UFBRwySWXEBAQ4Hns2rWLHTt2eI6Jj4+vspgBYLVa6d27t2e7Q4cOhISEeM63ZcsWBgwY4HXMgAEDPPtr4vTXITo6GsDzOmzZssVTVCnzy+dBRERERERERERqzrHbXRiwxZz6rmjjwXTAXVBoSM18YwHYfmSXJ2aPbwmAY39OQ6QkckFr1CM0rHYfxqQOqlbb/el5fDBvY5XtrkvuTkxCSLXOXVsKCwtJSkoiKSmJ119/nfDwcDIzM0lKSsLhcFR5vM1m89o2DAOXy1Vp+6ioKA4ePOgVO3jwIFFRUZUe4+PjU26aLafTWWVuNVVQUEB0dLRnfYrTnT4yxd/fv9bPXRGfk1X906+9sus+/XUoK+qc6XUQEREREREREZFz58hy/6C0rFAAsP3ITuBUQaGhxAfFk3kY9hWeGo1hS+gELMdxqBBcpeBT/VlgROTMGvUIDcMwsPlaqvWI7RSGf4jvGfsLCPUltlNYtfo7fRRCdaxevdpre9WqVSQkJGCxWNi6dSu5ublMmzaNgQMH0qFDh3IjLOx2O4DXSIez1a9fP1asWOEVW758+RlHDISHh5OVleUVq2jtijNd5+mxX7bp2LEjAJdddhkHDhzAarXStm1br0ezZs2qdX2nKykpYd26dZ7ttLQ08vLyPOfr2LEj33zzjdcx33zzDZ06dQLwjAI5/drPtGZHZTp27FjhcyMiIiIiIiIiIufA5cKZUwCAvW1HT3hfoXvWk/ig+AZJq0zHS9oAcLRknydmb9cdAEe+Dxzb3yB5iVyoGnVBoyZ8fAwG3p5wxjZX3JaAj0/NChXVlZmZyfjx40lLS+PNN99k7ty5pKSkABAXF4fdbmfu3Lns3LmTZcuWMXXqVK/j4+PjMQyDDz74gJycHAoKCs46l5SUFD7++GNeeOEFtm7dyqRJk1i3bh3JycmVHnPVVVexbt06/vWvf5Gens7EiRP56aefanSdZb755humT5/Otm3b+Nvf/sbixYs9bYYMGUK/fv248cYb+fTTT8nIyODbb7/lySef9CpMVJfNZuMPf/gDq1evZv369YwaNYq+ffvSp08fAB555BEWLlzI/PnzSU9PZ+bMmbz77rs8/PDDADRp0oS+ffsybdo0tmzZwpdffslf/vKXGueRkpLCK6+8wquvvsq2bduYOHEimzdvrnE/IiIiIiIiIiJymoIDOI65v8+zt+/uCZcVEMoKCg2ldwv3guQOnxycpe5ZP+ytWgHgLLRgZqc3WG4iF6ILpqAB0ObSCK65v0u5kRoBob5cc38X2lwaUWfnHjlyJMePH6dPnz6MHTuWlJQUzwLX4eHhLFy4kMWLF9OpUyemTZvGjBkzvI5v3rw5kydP5vHHHycyMvKMxYeq9O/fnzfeeIOXX36Z7t27884777B06VK6dOlS6TFJSUlMmDCBRx99lN69e5Ofn8/IkSNrdJ1l/vSnP7Fu3TouvfRSnnrqKWbOnElSUhLgHnXz4YcfcuWVV3L33XfTrl077rjjDnbv3l1uIfPqaNq0KY899hgjRoxgwIABBAQE8NZbb3n233jjjaSmpjJjxgw6d+7MSy+9xKuvvkpiYqKnzSuvvEJJSQk9e/Zk3LhxPPXUUzXO4/bbb/c8fz179mT37t088MADNe5HREREREREREROMXO24yh0z5pvb9UagOISB06fQ8CpgkJDuTSmJabLhmGUsvGAexosa0QEhtUA08CZvqFB8xO50BjmLxdOqGPHjh0jODiYo0ePEhQU5LXvxIkT7Nq1i1atWuHn53fW53C5TLLS8yg8Vox/kC/RCSF1NjIDIDExkR49ejB79uw6O0djUJ3rbNmyJePGjWPcuHH1ltf5qrbe7yIiIiIiIiIiFyrHJ3PYkTIfw2LQftNPGD4+rNm7lXtX3IrpsrH+zjX4Wht2meAe/7yGUus+Huz4DA/0uR6AnYP7UJyVT+wDVxCQ8o8GzU/kfHCmusHpGvWi4GfLx8egefvQhk5DREREREREREREzoEz/WcAbM38MXzck82s27cNAKsrosGLGQDB1uYcZh8/52z3xGzRERRn5ePYvfsMR4pITV1QU06JiIiIiIiIiIjIhcOxOwMAe3S4J/bzIXfhINjavCFSKiemaRwAGccyPDF7vHuxcsf+7IZISeSC1fAlzAvAypUrGzqFelGd68zIyKjzPERERERERERE5OLg2HcQAHtcnCdWVjgoKyQ0tLahrfipCHKK93hi9rYdgc9x5hSAaYJRd9Phi1xMNEJDREREREREREREGh/TxJGdD4Ct7anFvw8V7wXchYTGoHtkOwCKXFmemL19dwAcx4CCgw2RlsgFSQUNERERERERERERaXwKc9wFAU4VCOBU4aCskNDQ+sa5iy2mpYCDBUcAsLdqDYCj0Ip52toaInJuVNAQERERERERERGRRsc8tB1ngXvGfHvrtgBk5ediWgqAU4WEhtYiOARKggH4LnMLANaoKAyLAS4D5/YNDZecyAVGBQ0RERERERERERFpdEq2b8R0GeADtuhoAFbt2XpyZ7C7kNBINDXc+W08mA6AYbFgu6QpAM70nxssL5ELjQoaIiIiIiIiIiIi0ug40jcDYL+kKYbVPVJj4wF3waCsgNBYNPNtAUD64Z2emD06HABHxq4GyUnkQqSChoiIiIiIiIiIiDQ6jowMAGxRzTyx9CM7gFMFhMYiLqglAPuLdnti9vg4ABz7tSi4SG1RQaORS0xMZNy4cQ2dRqO0cuVKDMMgLy+voVOp0MKFCwkJCWnoNEREREREREREzkvOfQcAsMfFeWL7C/cApwoIjUWnS9oAkOfc74nZ2rjX+HBk54NpNkheIhcaFTQaidr8cn7z5s3cfPPNtGzZEsMwmD179jn3KSIiIiIiIiIiUp8cOUcBsLdp74nllewDThUQGouezd05OnyycZY6AbB36AGA85gJRbkNlZrIBUUFjQtQUVERrVu3Ztq0aURFRTV0OuestLQUl8vV0GmIiIiIiIiIiEh9KTqM46h7VIO9fXcAnKVOnD45wKkCQmPRs3krTJcNwyjlxwMZANhbtwXAUWDFPLS9AbMTuXCooFELEhMTSU5OJjk5meDgYJo1a8aECRMwTxtKtmjRInr16kVgYCBRUVGMGDGC7OxsADIyMhg8eDAAoaGhGIbBqFGjPMe6XC4effRRwsLCiIqKYtKkSWfMp3fv3jz//PPccccd+Pr6VusaJk2aRI8ePbxis2fPpmXLlp7tUaNGceONNzJ58mTCw8MJCgri//7v/3A4HDV6LoqLi3n44Ydp3rw5/v7+XH755axcudKzv2yqpmXLltGpUyd8fX3JzMysNPdvvvmGbt264efnR9++ffnpp5+89i9ZsoTOnTvj6+tLy5YteeGFF7z2G4bB0qVLvWIhISEsXLgQcL8+hmHw7rvvMnjwYJo2bUr37t357rvvvI5ZuHAhcXFxNG3alN/+9rfk5qryLiIiIiIiIiJyNszcnTjyLQDY2yQAsPHATgyjFNNlo2fzVg2ZXjm+VitWVwQAa/dtBcAWHQ0+YJYalGzf2JDpiVwwzouChrO4tNJHibO0+m0d1Wt7Nl577TWsVitr1qwhNTWVmTNnsmDBglPncjqZOnUqGzduZOnSpWRkZHiKFrGxsSxZsgSAtLQ0srKySE1N9erb39+f1atXM336dKZMmcLy5cvPKs9ztWLFCrZs2cLKlSt58803effdd5k8ebJXm6qei+TkZL777jv+85//8OOPP3LrrbdyzTXXkJ6e7mlTVFTEc889x4IFC9i8eTMRERGV5vTII4/wwgsvsHbtWsLDw7n++utxOt1D+9avX89tt93GHXfcwaZNm5g0aRITJkzwFCtq4sknn+Thhx9mw4YNtGvXjuHDh1NSUgLA6tWruffee0lOTmbDhg0MHjyYp556qsbnEBERERERERERKNmxEbPUBwywxcQAsHbvNgCsrgh8rdaGTK9CwVZ3nptz3KMxDKsVe1hTABzpmxssL5ELSeP7y6/AyylfVrovvsslXJfc3bP9yiNfU+KoeHqimIQQfvunyzzb/3ryW04UOMu1G/v3q2qcY2xsLLNmzcIwDNq3b8+mTZuYNWsWo0ePBuCee+7xtG3dujVz5syhd+/eFBQUEBAQQFhYGAARERHlFpLu1q0bEydOBCAhIYF58+axYsUKhg4dWuM8z5XdbueVV16hadOmdO7cmSlTpvDII48wdepUfHzc9bEzPReZmZm8+uqrZGZmEnPyw+jhhx/m448/5tVXX+WZZ54B3AWgF198ke7du1eaS5mJEyd6novXXnuNFi1a8N5773Hbbbcxc+ZMrr76aiZMmABAu3bt+Pnnn3n++ee9RsFUx8MPP8ywYcMAmDx5Mp07d2b79u106NCB1NRUrrnmGh599FHPeb799ls+/vjjGp1DRERERERERETAme6egcMW6odhtwOw+ZD7x7BlhYPGJqZpHIeL1pJxLMMTs0VdguNQEY6Mnfg3XGoiF4zzYoTG+aBv374YhuHZ7tevH+np6ZSWukd8rF+/nuuvv564uDgCAwMZNGgQwBmnUirTrVs3r+3o6GjPdFX1rXv37jRt2tSz3a9fPwoKCtizZ48ndqbnYtOmTZSWltKuXTsCAgI8jy+//JIdO3Z4jrHb7eWuuzL9+vXz/HtYWBjt27dny5YtAGzZsoUBAwZ4tR8wYIDXa1Ndp+cTHR0N4HkdtmzZwuWXX15pXiIiIiIiIiIiUn2OXTsBsEdd4ontPrYbcBcOGqO2oa0ByCne64nZ42IBcO470CA5iVxozosRGmNSB1W6z/hFSeae5wdW3tbw3h75dP9zSavaCgsLSUpKIikpiddff53w8HAyMzNJSkryWn+iMjabzWvbMIxaXyTbx8fHa50LwDNtU20qKCjAYrGwfv16LBaL176AgADPvzdp0sSrKFKXDMOo1rWf/jqU5abFykVEREREREREap9jXxYA9rgWnlhO8R4wThUOGptukQks3QdFrv2emL1Ne+BbHNnHGi4xkQvIeVHQsPlaqm5Ux22rsnr1aq/tVatWkZCQgMViYevWreTm5jJt2jRiY91V2XXr1nm1t58cOlfTUQO1JTw8nAMHDmCapufL+g0bNpRrt3HjRo4fP06TJk0A93UGBAR4rgvO/FxceumllJaWkp2dzcCBlRefamLVqlXExbkr80eOHGHbtm107NgRgI4dO/LNN994tf/mm29o166dp6ASHh5OVlaWZ396ejpFRUU1yqFjx44VXreIiIiIiIiIiNSc42AeYDlZEHArcmWBxV04aIz6xXaA78G0FJBdcISIgFDsHdzTqTuOuuD4EWgS2sBZipzfNOVULcnMzGT8+PGkpaXx5ptvMnfuXFJSUgCIi4vDbrczd+5cdu7cybJly5g6darX8fHx8RiGwQcffEBOTg4FBQVnnYvD4WDDhg1s2LABh8PBvn372LBhA9u3b6/0mMTERHJycvj/7P15dJRlnv//P++qpLLvO1kgQDZQ9lV+atwmPdNfe5jP+dhu/WGwUbtVusMPl6bbdkBATWsEaUE/TtuAOI62CzKOo44209hfsQWDgCwhCZANSAgCSUgg3JWq+v5RSUFkSyDJncDrcU6d9q57qddVxaHPeb+5ruvZZ59lz549LFu2jI8//visz54xYwY7d+7ko48+Yu7cucycOdO3f8aFvovMzEzuvvtupk2bxurVqykvL2fjxo0888wz/Nd//ddFjXf+/PmsXbuW7du3M336dGJjY5k6dSoADz/8MGvXrmXBggWUlpby2muvsXTpUh555BHf/TfeeCNLly5l8+bNFBUV8fOf//yMWTEX8stf/pJPPvmEwsJCysrKWLp0qfbPEBERERERERG5GC0NmA3ef/Trn+VtCBxsOorH7q2XTU7Ntiza+aRERkFrBAB/q94F4GvImMfseA7vtSybyOVCDY1uMm3aNE6cOMGECRN46KGHyM/P5/777we8MwBWrlzJO++8w7BhwygoKKCwsLDD/cnJyTz55JPMmTOHhIQEZs6cedFZDhw4wOjRoxk9ejQ1NTUUFhYyevRo7r333nPek5OTw0svvcSyZcsYOXIkGzdu7FD0b3fTTTeRkZHBddddx+23386PfvQj5s2b1+nvAmDFihVMmzaNhx9+mKysLKZOncrXX3/tm2XRVQUFBeTn5zN27Fhqa2v5z//8T9+MlzFjxvD222/z1ltvcdVVV/Ev//IvzJ8/v8OG4M8//zypqalce+213HXXXTzyyCMd9gnpjEmTJvGHP/yBJUuWMHLkSD799FN++9vfXtR4RERERERERESuZJ7De3Ee8y4s4xjqbV78rWqn92RrhLdx0EcFGYkAbKktBcB/wAAwwOOy0br3WyujiVwWDM/3Nw/oYY2NjURERNDQ0EB4eHiHcy0tLZSXl5Oenk5gYGBvxrokubm5jBo1ihdeeMHqKD1q+vTp1NfXs2bNmnNec6V8F92hv/55FxERERERERHpSa3rV1E24xkAsr7dis3hYN7/rOS96ucJcmWx8afvWpzw3P7hjVlUt65lVNj/4vX/9SQAu68ZjfNICwMf/geC73ve4oQifdP5+gan0wwNERERERERERER6TPM0m0A+EcGYGtbhaPsqHe5ptiAlHPe1xcMDEsHYH9zle89R2IMAGbFHksyiVxOutTQePnllxkxYgTh4eGEh4czefLks+6zICIiIiIiIiIiInIxzL3ewr9/YrTvvQNtDYL2hkFflRM7GIB6537fe45UbxPG3FdjSSaRy4lfVy5OSUmhoKCAjIwMPB4Pr732Gv/4j//I5s2bGT58eE9l7PPWrVtndYResXLlygtec6V8FyIiIiIiIiIi0jPMfQeAU40AgIbW/WA/1TDoq8YNyOYPZWDa6mh1teJn98N/cAawAbOu3up4Iv1el2Zo3HrrrfzDP/wDGRkZZGZm8tRTTxEaGspXX33VU/lERERERERERETkCuJsK/w7Bg/1HrucmLZDgLdh0JeNSU7H4/bDMFx8e7ACAEfWCADM+lY4eczCdCL930XvoeFyuXjrrbdobm5m8uTJ57zu5MmTNDY2dniJiIiIiIiIiIiInMFsxjzqBE41ArbWlmMYLjxuP8Yk9+0lpwL9/fBzxwPw9b5iABwZwwBwHvPDc3ivZdlELgddbmhs27aN0NBQAgIC+PnPf87777/PsGHDznn9M888Q0REhO+Vmpp6SYFFRERERERERETk8uQ5Uo55zLtKvv9Qb83x6/0lAPi54wn079IK+paI8BsAwI7v2vYCSfEuneVuteGq2GZZLpHLQZcbGllZWWzZsoUNGzbwwAMP8M///M/s3LnznNf/+te/pqGhwfeqrq6+pMAiIiIiIiIiIiJyeXJVbsft9JYsHWlpAOw8tBs41Sjo65KCBwJQ0VABgC0gAL/IAADMEjU0RC5Fl1uaDoeDoUO969eNHTuWr7/+miVLlvDKK6+c9fqAgAACAgIuLaWIiIiIiIiIiIhc9pyl3wLgF+HAFhgIQEVjBXCqUdDXDY1KZ8dxOHTy1D/sdiRG01pfg1m+m2ALs4n0dxe9h0Y7t9vNyZMnuyOLiIiIiIiIiIiIXMHMvd7ZGI74KN977Y2BoVF9e/+MdiMSMgBodtf43nOkJAPg3HfAkkwil4suNTR+/etf89e//pWKigq2bdvGr3/9a9atW8fdd9/dU/mueLm5ucyaNcvqGH3SypUriYyMtDrGOc2bN49Ro0ZZHUNEREREREREpN8wq/cD4Eg9tbzU8bbGQHujoK+bnJINgMd+jEPNRwFwDPaueGMerLcqlshloUsNjbq6OqZNm0ZWVhY33XQTX3/9Nf/93//NLbfc0lP5Lorb7aJ6x7cUr/+c6h3f4na7rI50QevWrcMwDOrr6y/5WX/4wx+49tpriYqKIioqiptvvpmNGzdeekgREREREREREZEeZB70NgD8070NgINNR/HYm4BTjYK+LiUyClrDAfhb1S4AHFkjATCPmuA8YVk2kf6uS3to/PGPf+ypHN2mbMOX/M/Kf6XpyHe+90KjY7lx+v1kTLzGwmS9Z926ddx5551cc801BAYG8rvf/Y6/+7u/Y8eOHSQnJ1sdr8tM08ThcFgdQ0REREREREREepKzBeeRk4ADR+bVAPytqth7rjXc2yjoBwzDIMhI4gSNbKkt5Uc5k/EfOgwA85gfniPlGAnDLE4p0j9d8h4afUnZhi/5YNHTHZoZAE1HvuODRU9TtuHLHvnc3NxcZs6cycyZM4mIiCA2NpYnnngCj8fju+b1119n3LhxhIWFkZiYyF133UVdXR0AFRUV3HDDDQBERUVhGAbTp0/33et2u3nssceIjo4mMTGRefPmnTfPG2+8wYMPPsioUaPIzs7m1Vdfxe12s3bt2nPeM336dKZOndrhvVmzZpGbm9ulcQ4aNIgFCxZw5513EhISQnJyMsuWLevw3Pr6eu69917i4uIIDw/nxhtvZOvWrb7z7Us1vfrqq6SnpxPYtgHUuaxZs4aMjAwCAwPJy8ujurq6w/mXX36ZIUOG4HA4yMrK4vXXX/edq6iowDAMtmzZ0iGfYRisW7cOODV7Zu3atYwbN47g4GCuueYaSkpKOnxOQUEBCQkJhIWFMWPGDFpaWs6bW0RERERERERETlNfiXnMDoAj8yoAth4sAyDISMIwDMuidVVsQAoAZUfLAXCkpQLgdtpwVW63LJdIf9enGxoejwdnS0unXiePN/M/K1457/P+Z+UrnDze3KnnnV6k74zXXnsNPz8/Nm7cyJIlS1i0aBGvvvqq77zT6WTBggVs3bqVNWvWUFFR4WtapKam8t577wFQUlJCTU0NS5Ys6fDskJAQNmzYwLPPPsv8+fP57LPPOp3t+PHjOJ1OoqOjuzSmixknwHPPPcfIkSPZvHkzc+bMIT8/v0Pe2267jbq6Oj7++GM2bdrEmDFjuOmmmzhy5Ijvmt27d/Pee++xevXqDs2Gs43tqaeeYtWqVaxfv576+nruuOMO3/n333+f/Px8Hn74YbZv387PfvYz7rnnHv7yl790eeyPP/44zz//PEVFRfj5+fHTn/7Ud+7tt99m3rx5PP300xQVFZGUlMRLL73U5c8QEREREREREblSuaq24zLbGhppaQCUHdkLnGoQ9BdpYYMA2N9cCYAtKAi/cO8KJM6Sb62KJdLvdWnJqd7WevIkv//n/91tz2s6cpil99zeqWt/+dq7+F9gZsDpUlNTWbx4MYZhkJWVxbZt21i8eDH33XcfQIfi9+DBg/n973/P+PHjaWpqIjQ01NdsiI+PP2Oj6xEjRjB37lwAMjIyWLp0KWvXru303iW/+tWvGDBgADfffHOnx3Ox4wSYMmUKc+bMASAzM5P169ezePFibrnlFr744gs2btxIXV0dAQEBABQWFrJmzRreffdd7r//fsC7zNSqVauIi4s7bx6n08nSpUuZOHEi4G245OTksHHjRiZMmEBhYSHTp0/nwQcfBGD27Nl89dVXFBYW+mbFdNZTTz3F9ddfD8CcOXP44Q9/SEtLC4GBgbzwwgvMmDGDGTNmALBw4UL+/Oc/a5aGiIiIiIiIiEgnmSXeFTzsof7YQkKAUw2B9gZBf5ETO4T1R6Heud/3niMhktbGOszyMoIszCbSn/XpGRr9yaRJkzpMe5s8eTJlZWW4XN4NyTdt2sStt95KWloaYWFhvsJ4VVXVBZ89YsSIDsdJSUm+5aoupKCggLfeeov333//gks3dcaFxtn+3ukmT55McbF3vcOtW7fS1NRETEwMoaGhvld5eTl79uzx3TNw4MALNjMA/Pz8GD9+vO84OzubyMhI3+cVFxczZcqUDvdMmTLFd74rTv8dkpKSAHy/Q3Fxsa+p0u7734OIiIiIiIiIiJybude7vJQjIcL3XkPrAcDbIOhPxg/wbmBu2upodbUC4J8ywPte9f5z3ici59enZ2j4BQTwy9fe7dS1+4q3s7pg3gWv+19z5pGSc1WnPru7NDc3k5eXR15eHm+88QZxcXFUVVWRl5eHaZoXvN/f37/DsWEYuN3uC95XWFhIQUEBf/7zn89oinyfzWY7Y5ktp9N5wc/oqqamJpKSknz7U5zu9JkpIW1d+J5ms3l7eqeP/VzjPv13aG/qdOZ3EBERERERERGRC3NW7wPA0Vb4d7qcmLY6DE41CPqLMcnpeNx+GLZWvj1YwZgBQ3GkD4G/bMGsPXLhB4jIWfXpGRqGYeAfGNip18CRowmNjj3v88JiYhk4cnSnntfVTYY2bNjQ4firr74iIyMDu93Orl27OHz4MAUFBVx77bVkZ2efMcPC4fCuoXf6TIdL8eyzz7JgwQI++eQTxo0bd8Hr4+LiqKmp6fDe2fauON84T3/v+9fk5OQAMGbMGGpra/Hz82Po0KEdXrGx5//9zqa1tZWioiLfcUlJCfX19b7Py8nJYf369R3uWb9+PcOGDQPwzQI5fezn27PjXHJycs763YiIiIiIiIiISOe0F/od6d7ZGFtryzEMFx63H2OS062M1mWB/n74ueMB+HrfLgAcWd5/cOw8chJaT1qWTaQ/69MNja6w2ezcOP3+815zwz/fj81mP+81F6uqqorZs2dTUlLCm2++yYsvvkh+fj4AaWlpOBwOXnzxRfbu3csHH3zAggULOtw/cOBADMPgww8/5NChQzQ1NV10lt/97nc88cQTLF++nEGDBlFbW0ttbe15n3njjTdSVFTEqlWrKCsrY+7cuWzfvr1L42y3fv16nn32WUpLS1m2bBnvvPOO75qbb76ZyZMnM3XqVD799FMqKir48ssvefzxxzs0JjrL39+fX/ziF2zYsIFNmzYxffp0Jk2axIQJEwB49NFHWblyJS+//DJlZWUsWrSI1atX88gjjwAQFBTEpEmTKCgooLi4mM8//5zf/va3Xc6Rn5/P8uXLWbFiBaWlpcydO5cdO3Z0+TkiIiIiIiIiIlcklxPzsHcvUkfG1QAU7S8BwM8dT6B/n15o5qwi/LwzTXZ8511m3ZHpHZfZZIf6Cy9DLyJnumwaGgAZE6/hR7N/c8ZMjbCYWH40+zdkTLymxz572rRpnDhxggkTJvDQQw+Rn5/v2+A6Li6OlStX8s477zBs2DAKCgooLCzscH9ycjJPPvkkc+bMISEhgZkzZ150lpdffhnTNPnf//t/k5SU5Ht9/zNPl5eXxxNPPMFjjz3G+PHjOXbsGNOmTevSONs9/PDDFBUVMXr0aBYuXMiiRYvIy8sDvLNuPvroI6677jruueceMjMzueOOO6isrCQhIaHLYw0ODuZXv/oVd911F1OmTCE0NJQ//elPvvNTp05lyZIlFBYWMnz4cF555RVWrFhBbm6u75rly5fT2trK2LFjmTVrFgsXLuxyjttvv933/Y0dO5bKykoeeOCBLj9HREREREREROSKVF/lLfQD/m0zGXa2NQLaGwP9TVJwGgAVDeUAONK8x66TdlxVZ/5DYhG5MMPz/Y0TelhjYyMRERE0NDQQHh7e4VxLSwvl5eWkp6df0gbWbreL/cU7aKo/SmhkFMk5w3tsZgZAbm4uo0aN4oUXXuixz+gLOjPOQYMGMWvWLGbNmtVrufqr7vrzLiIiIiIiIiLS37m2fkjp7Y8CkPn1RuxhYdz6Zj4V5v8wPPh/8dZtT1qcsOse/2wlHxx4nlBPFn+b7t0nuHTcCFxNTgbNvZ2gO+dZG1CkDzlf3+B0/W+uVifYbHZSh59/E2wRERERERERERHpG5wlWwCwB/thDwsD4NDJfWDAkMj+tX9Gu5GJmXxwAJrdp/ZudcRHcKLpO8y9pQRZmE2kv7qslpwSERERERERERGR/sfc490vwxF/6l9mH29rBIxMzLQk06WalJIFgMfeyHfN9QA4UpIAcFbtsyqWSL92Wc7Q6G3r1q2zOkKv6Mw4KyoqejyHiIiIiIiIiIhcXsyqagAcKYkA1DUdxWM/BpxqDPQ3qZHR0BoOfo38rXoXt2ZPwjFoMPx1G2btYavjifRLmqEhIiIiIiIiIiIilmov8PsPGgzA36p3eU+0hnsbA/2QYRgEGd4ZGVtqywBwZF4FgHmkBVytlmUT6a/U0BARERERERERERHruF04Dx8HwJExHICttaUABBlJGIZhWbRLFRuQAkDpkT0A+GeNBMA8ZoeGastyifRXamiIiIiIiIiIiIiIdRr2eQv8gCN7FAClR/YCpxoC/VVq2EAA9jdXAeAYNAgAV4sd176dVsUS6bfU0BARERERERERERHLuA8U03qiraExKB2AA8e9DYD2hkB/NSx2KAD1zv0A2MPCsAd7tzV2lmyxKpZIv6WGhoiIiIiIiIiIiFjGbCvs24Ps2CMigFMNgPaGQH81bkAmAKZRR2vbnhmO+HDve3tKLcsl0l+poSEiIiIiIiIiIiKWMXd7NwD3j/MW+ltdrZi2OuBUQ6C/GjNgMB63H4atlW11FQA4khMBMKuqLEwm0j+podHH5ebmMmvWLKtj9EkrV64kMjLS6hjnNG/ePEaNGmV1DBERERERERGRPs1Z5d0c25GcAMC3ByswDBcetx9jBgy2MtolC3L44+eOB+DrfSUA+Lctq2XWHLYsl0h/pYZGH7Fu3ToMw6C+vv6Sn7V69WrGjRtHZGQkISEhjBo1itdff/3SQ4qIiIiIiIiIiHQzs+YQcGrD7I37vDM2/NzxBDn8rYrVbcLtAwDYfmg3AI6M4QA4Dx8Ht8uyXCL9kZ/VAaT7RUdH8/jjj5OdnY3D4eDDDz/knnvuIT4+nry8PKvjdZlpmjgcDqtjiIiIiIiIiIhId3O7Mb87DvjjGOot9O/8zlv4b28E9HcDQtI4eryIysYKABxZowAwj9mg8QBEploXTqSf0QyNbpCbm8vMmTOZOXMmERERxMbG8sQTT+DxeHzXvP7664wbN46wsDASExO56667qKvzrgVYUVHBDTfcAEBUVBSGYTB9+nTfvW63m8cee4zo6GgSExOZN2/eBfP80z/9Ezk5OQwZMoT8/HxGjBjBF198cc57pk+fztSpUzu8N2vWLHJzc7s0zkGDBrFgwQLuvPNOQkJCSE5OZtmyZR2eW19fz7333ktcXBzh4eHceOONbN261Xe+fammV199lfT0dAIDA8873jVr1pCRkUFgYCB5eXlUV1d3OP/yyy8zZMgQHA4HWVlZHWarVFRUYBgGW7Zs6ZDPMAzWrVsHnJo9s3btWsaNG0dwcDDXXHMNJSUlHT6noKCAhIQEwsLCmDFjBi0tLefNLSIiIiIiIiJyxWuqxTxmAOCfPQqAioYKwNsIuBwMifQuMVXX0ra0Vrr3uPWEHfeBYstyifRH/aKh4WxpOeer1TQ7fa3TPNmpay/Ga6+9hp+fHxs3bmTJkiUsWrSIV1999dRnOZ0sWLCArVu3smbNGioqKnxNi9TUVN577z0ASkpKqKmpYcmSJR2eHRISwoYNG3j22WeZP38+n332WadyeTwe1q5dS0lJCdddd91Fja0r4wR47rnnGDlyJJs3b2bOnDnk5+d3yHvbbbdRV1fHxx9/zKZNmxgzZgw33XQTR44c8V2ze/du3nvvPVavXt2h2fB9x48f56mnnmLVqlWsX7+e+vp67rjjDt/5999/n/z8fB5++GG2b9/Oz372M+655x7+8pe/dHnsjz/+OM8//zxFRUX4+fnx05/+1Hfu7bffZt68eTz99NMUFRWRlJTESy+91OXPEBERERERERG5krhrdtF63LuIjCPdu19G3Ulv4b+9EdDfjUjIAKDZXQOAPTISW6AdALNki1WxRPqlfrHk1O//+X+f81z66HH8rznzfMcv3X83rSdPnvXalGFXcfvcAt/xH2b+lBPHGs+47uE/fdjljKmpqSxevBjDMMjKymLbtm0sXryY++67D6BD8Xvw4MH8/ve/Z/z48TQ1NREaGkp0dDQA8fHxZ2x0PWLECObOnQtARkYGS5cuZe3atdxyyy3nzNPQ0EBycjInT57Ebrfz0ksvnff67honwJQpU5gzZw4AmZmZrF+/nsWLF3PLLbfwxRdfsHHjRurq6ggICACgsLCQNWvW8O6773L//fcD3mWmVq1aRVxc3HnzOJ1Oli5dysSJEwFvwyUnJ4eNGzcyYcIECgsLmT59Og8++CAAs2fP5quvvqKwsNA3K6aznnrqKa6//noA5syZww9/+ENaWloIDAzkhRdeYMaMGcyYMQOAhQsX8uc//1mzNEREREREREREzsPZVtC3BdiwR0UBcNxdA/ZTjYD+bnJqNmwGj72R7443EBscgSM+jJaqeszduzj/2iQicrp+MUOjP5g0aRKGYfiOJ0+eTFlZGS6Xd2OfTZs2ceutt5KWlkZYWJivMF5VVXXBZ48YMaLDcVJSkm+5qnMJCwtjy5YtfP311zz11FPMnj3bt4TSpbjQONvfO93kyZMpLvZOn9u6dStNTU3ExMQQGhrqe5WXl7Nnzx7fPQMHDrxgMwPAz8+P8ePH+46zs7OJjIz0fV5xcTFTpkzpcM+UKVN857vi9N8hKSkJwPc7FBcX+5oq7b7/PYiIiIiIiIiISEfmbm+NxhEXhmEYHGqqx2M/BrQ1Ai4DqZHR0BoOwN+qvBueO5ITAHB2ojYoIqf0ixkav3zt3XOeM2wdezIP/usb536QzehweN/S5ZeUq7Oam5vJy8sjLy+PN954g7i4OKqqqsjLy8P83pJZZ+Pv79/h2DAM3G73ee+x2WwMHToUgFGjRlFcXMwzzzzTYU+M719/+l4Y4J390N2amppISko6a3Pl9JkpISEh3f7ZZ2Nr+/Nz+tjPNe7Tf4f2ps6FfgcRERERERERETk3s7ISAMeAeAD+Vu0t+NMa7m0EXAYMwyDISOQEjWypLeXW7Ik4BqbD30owaw5ZHU+kX+kXMzT8AwPP+fJzODp9rb8joFPXXowNGzZ0OP7qq6/IyMjAbreza9cuDh8+TEFBAddeey3Z2dlnzLBwtI3j9JkO3cntdnPyHEtxAcTFxVFTU9PhvbPtXXG+cZ7+3vevycnJAWDMmDHU1tbi5+fH0KFDO7xiY2O7OixaW1spKiryHZeUlFBfX+/7vJycHNavX9/hnvXr1zNs2DAA3yyQ08d+vj07ziUnJ+es342IiIiIiIiIiJybWeOtkfkPHATAltoSAIKMxA6rhPR3MQEpAJQd2QuAI8NbmzK/a4bv/SNjETm3ftHQ6A+qqqqYPXs2JSUlvPnmm7z44ovk5+cDkJaWhsPh4MUXX2Tv3r188MEHLFiwoMP9AwcOxDAMPvzwQw4dOkRTU9NFZ3nmmWf47LPP2Lt3L8XFxTz//PO8/vrr/OQnPznnPTfeeCNFRUWsWrWKsrIy5s6dy/bt27s0znbr16/n2WefpbS0lGXLlvHOO+/4rrn55puZPHkyU6dO5dNPP6WiooIvv/ySxx9/vENjorP8/f35xS9+wYYNG9i0aRPTp09n0qRJTJgwAYBHH32UlStX8vLLL1NWVsaiRYtYvXo1jzzyCABBQUFMmjSJgoICiouL+fzzz/ntb3/b5Rz5+fksX76cFStWUFpayty5c9mxY0eXnyMiIiIiIiIicsXweHAeagbAMdT7j1PLjpYDpxoAl4u0sEEA7G/2zkjxzxoFgNloQNNBi1KJ9D9qaHSTadOmceLECSZMmMBDDz1Efn6+b4PruLg4Vq5cyTvvvMOwYcMoKCigsLCww/3Jyck8+eSTzJkzh4SEBGbOnHnRWZqbm3nwwQcZPnw4U6ZM4b333uPf/u3fuPfee895T15eHk888QSPPfYY48eP59ixY0ybNq1L42z38MMPU1RUxOjRo1m4cCGLFi0iLy8P8E6x++ijj7juuuu45557yMzM5I477qCyspKEhIQujzU4OJhf/epX3HXXXUyZMoXQ0FD+9Kc/+c5PnTqVJUuWUFhYyPDhw3nllVdYsWJFh6W3li9fTmtrK2PHjmXWrFksXLiwyzluv/123/c3duxYKisreeCBB7r8HBERERERERGRK0bzIcxG7386ckYDsL/Zu6dEewPgcpETMwSAo879ADgGe49bj/vhrtllWS6R/sbwfH/jhB7W2NhIREQEDQ0NhIeHdzjX0tJCeXk56enpBF7k0k9WyM3NZdSoUbzwwgtWR+lRnRnnoEGDmDVrFrNmzeq1XP1Vf/3zLiIiIiIiIiLSHTx7vmDX/3MveAwy/t+/4hcXx5jlf4fTXsOMoU8xa8qPrI7Ybb6o2MUDn9+Gx+3HlmlfY7fZKR11Fe6TbgY/dz8Bt/7/rY4oYqnz9Q1OpxkaIiIiIiIiIiIi0uvMkm/AY2D4G9hjY2l1tWIa3k2yxyVnWpyue40dMASP2w/D1sr2ukoMw8ARFwqAubvY4nQi/YcaGiIiIiIiIiIiItLrzDJvId8RG4phGGw7WIFha8Xj9mPsgCEWp+teQQ5//NxxAGzc511iyj8pHgCzstKyXCL9jZ/VAS4H69atszpCr+jMOCsqKno8h4iIiIiIiIiI9H/OygoAHAM6Fvr93HEEOfytitVjwu0DOEoNOw7tAcAxcCB8vRvzQJ3FyUT6D83QEBERERERERERkV5nHjgItBX2gR3feQv94fYBlmXqSUnBaQBUNJYD4BiaA4DzUBP07jbHIv2WGhoiIiIiIiIiIiLSuzwezEPHAHAMzQagoqECOFX4v9wMjRoMQF1LNQCOnDEAmI3A8cNWxRLpV9TQEBERERERERERkd514ihmg/c//bNHA3DopLfQP6St8H+5uTo+A4Bmdw0AjsFDAXAet+M5WGpZLpH+RA0NERERERERERER6VWeujKczXYAHEMygVOF/hFthf/LzaQ070wUj72R7443YI+NxfA3wGNglnxjcTqR/kENDREREREREREREelVztIt4DEw/Az84uL4rrkej70ROFX4v9wMjIyG1jAAvqrehWEYOGJDADDLdloZTaTfUENDREREREREREREepVZtgMAR2wwhs3G36p3eU+0hnkL/5chwzAINBIB2FLjXWLKMSAOAGdlhVWxRPoVNTT6uNzcXGbNmmV1jD5p5cqVREZGWh3jnObNm8eoUaOsjiEiIiIiIiIi0ueYFXsB8E+MBWBzrbfAH2gkYhiGZbl6WqwjFYDSI97xO9IGAmDuP2hZJpH+5LJsaHjcHlr21HN8Sx0te+rxuD1WR7qgdevWYRgG9fX13frct956C8MwmDp1arc+V0RERERERERE5GK1F/AdaWkAlB0pB04V/C9XaeHeBsb+5koA/Id4l9cyDx2zLJNIf+JndYDudmL7d9T/5x5cDabvPXuEg8hbhxB0VayFyXpfRUUFjzzyCNdee63VUS6JaZo4HA6rY4iIiIiIiIiISDdxHmoEbDiGZAGnCvztBf/LVXbMEL48CkedBwBw5IwCwGzwwImjEBRlYTqRvu+ymqFxYvt3HP634g7NDABXg8nhfyvmxPbveuRzc3NzmTlzJjNnziQiIoLY2FieeOIJPJ5TM0Nef/11xo0bR1hYGImJidx1113U1dUB3sbDDTfcAEBUVBSGYTB9+nTfvW63m8cee4zo6GgSExOZN2/eBTO5XC7uvvtunnzySQYPHnzB66dPn37GLI5Zs2aRm5vbpXEOGjSIBQsWcOeddxISEkJycjLLli3r8Nz6+nruvfde4uLiCA8P58Ybb2Tr1q2+8+1LNb366qukp6cTGBh43uxr1qwhIyODwMBA8vLyqK6u7nD+5ZdfZsiQITgcDrKysnj99dd95yoqKjAMgy1btnTIZxgG69atA07Nnlm7di3jxo0jODiYa665hpKSkg6fU1BQQEJCAmFhYcyYMYOWlpbz5hYRERERERERuSK1NGDWuwBwZI8CoN65H/AW/C9n4wZ4GzimcZBWV6uvoeNstuOpK7Mymki/0KcbGh6PB7fp6tTL1dLK0Q/2nPd5Rz/Yg6ultVPPO71I3xmvvfYafn5+bNy4kSVLlrBo0SJeffVV33mn08mCBQvYunUra9asoaKiwte0SE1N5b333gOgpKSEmpoalixZ0uHZISEhbNiwgWeffZb58+fz2WefnTfP/PnziY+PZ8aMGV0ax6WOE+C5555j5MiRbN68mTlz5pCfn98h72233UZdXR0ff/wxmzZtYsyYMdx0000cOXLEd83u3bt57733WL16dYdmw/cdP36cp556ilWrVrF+/Xrq6+u54447fOfff/998vPzefjhh9m+fTs/+9nPuOeee/jLX/7S5bE//vjjPP/88xQVFeHn58dPf/pT37m3336befPm8fTTT1NUVERSUhIvvfRSlz9DRERERERERORy5zm0B7PZu3CMIyOHVlcrpuH9h7/tBf/L1djkwXjcfhi2VnbUVeIXH4/hZ4DHwFm6xep4In1en15yyuN0c+Bfvuy257kbTWrm/a1T1w6Yfw2Gw97pZ6emprJ48WIMwyArK4tt27axePFi7rvvPoAOxe/Bgwfz+9//nvHjx9PU1ERoaCjR0dEAxMfHn7HR9YgRI5g7dy4AGRkZLF26lLVr13LLLbecNcsXX3zBH//4x/M2Ai7WhcYJMGXKFObMmQNAZmYm69evZ/Hixdxyyy188cUXbNy4kbq6OgICAgAoLCxkzZo1vPvuu9x///2Ad5mpVatWERcXd948TqeTpUuXMnHiRMDbcMnJyWHjxo1MmDCBwsJCpk+fzoMPPgjA7Nmz+eqrrygsLPTNiumsp556iuuvvx6AOXPm8MMf/pCWlhYCAwN54YUXmDFjhq+BtHDhQv785z9rloaIiIiIiIiIyPc4yzaD28Cwg19iIlsO7sWwteJx+zE2+cIrjfRnwQ4Hfu44XLYaNuwvYWTSEBwxwZw82IxZtgPH2ct9ItKmT8/Q6E8mTZqEYRi+48mTJ1NWVobL5Z0+t2nTJm699VbS0tIICwvzFcarqqou+OwRI0Z0OE5KSvItV/V9x44d4//8n//DH/7wB2Jju3/PkAuNs/29002ePJni4mIAtm7dSlNTEzExMYSGhvpe5eXl7NlzaobNwIEDL9jMAPDz82P8+PG+4+zsbCIjI32fV1xczJQpUzrcM2XKFN/5rjj9d0hKSgLw/Q7FxcW+pkq7738PIiIiIiIiIiICztLtAPjHBGPYbHy9z7ust587juArYB/VcPsAAHYe2g2Af5K3hmdWlFuWSaS/6NMzNAx/GwPmX9Opa0+WN3B4xY4LXhdzz3AC0iM69dndpbm5mby8PPLy8njjjTeIi4ujqqqKvLw8TNO84P3+/v4dsxkGbrf7rNfu2bOHiooKbr31Vt977df6+flRUlLCkCFnrkVos9nOWGbL6XReMFtXNTU1kZSU5Nuf4nSnz0wJCQnp9s8+G5vN+zufPvZzjfv036G9qXOu30FERERERERERM6uvXDvSIwBYMch7z9ybS/0X+6SgtM4emIT5Q0VADjSUmFLJeb+WmuDifQDfXqGhmEY2Bz2Tr0CM6KwR5y/g2uPCCAwI6pTzzt9FkJnbNiwocPxV199RUZGBna7nV27dnH48GEKCgq49tpryc7OPmOGhaOt+3z6TIeLkZ2dzbZt29iyZYvv9aMf/YgbbriBLVu2kJqaetb74uLiqKmp6fDe2ZasOt84T3/v+9fk5OQAMGbMGGpra/Hz82Po0KEdXhczo6S1tZWioiLfcUlJCfX19b7Py8nJYf369R3uWb9+PcOGDQPwzQI5fewXs1RXTk7OWb8bERERERERERHpyNzvrcM42upUFY3eBkdScJplmXrTkMh0AOpaqgFObQxe12BZJpH+ok83NLrCsBlE3nrmzIPTRd46GMPWtUZFZ1VVVTF79mxKSkp48803efHFF8nPzwcgLS0Nh8PBiy++yN69e/nggw9YsGBBh/sHDhyIYRh8+OGHHDp0iKampovKERgYyFVXXdXhFRkZSVhYGFdddZWvcfJ9N954I0VFRaxatYqysjLmzp3L9u3buzTOduvXr+fZZ5+ltLSUZcuW8c477/iuufnmm5k8eTJTp07l008/paKigi+//JLHH3+8Q2Ois/z9/fnFL37Bhg0b2LRpE9OnT2fSpElMmDABgEcffZSVK1fy8ssvU1ZWxqJFi1i9ejWPPPIIAEFBQUyaNImCggKKi4v5/PPP+e1vf9vlHPn5+SxfvpwVK1ZQWlrK3Llz2bHjwjOGRERERERERESuNGZb4d5/SAZwqrDfXui/3F2d4B13s7utsZM1EgCz3gUnj1mWS6Q/uGwaGgBBV8US85OcM2Zq2CMCiPlJDkFXdf+eEu2mTZvGiRMnmDBhAg899BD5+fm+Da7j4uJYuXIl77zzDsOGDaOgoIDCwsIO9ycnJ/Pkk08yZ84cEhISmDlzZo9lPZu8vDyeeOIJHnvsMcaPH8+xY8eYNm3aGdedb5ztHn74YYqKihg9ejQLFy5k0aJF5OXlAd5ZNx999BHXXXcd99xzD5mZmdxxxx1UVlaSkJDQ5dzBwcH86le/4q677mLKlCmEhobypz/9yXd+6tSpLFmyhMLCQoYPH84rr7zCihUryM3N9V2zfPlyWltbGTt2LLNmzWLhwoVdznH77bf7vr+xY8dSWVnJAw880OXniIiIiIiIiIhc1sxmzKOtADiyRwGnCvtXxw+1KlWvmpzmXVnEY2/gu+MNODK8K4mYzX54Du05360iVzzD8/2NE3pYY2MjERERNDQ0EB4e3uFcS0sL5eXlpKenExgYeNGf4XF7OFnegPuYiS3MQUB6RI/NzADIzc1l1KhRvPDCCz32GX1BZ8Y5aNAgZs2axaxZs3otV3/VXX/eRURERERERET6C8+Bbym5+cd43AZDPvuUxphwbnjn/wfAf976FwZF99w/SO4rPB4PI5ZPAb9jFEx6lX8YOo6SEVfhccGQlx/DccM9VkcU6XXn6xuc7rKaodHOsBkEDokkeFQ8gUMie7SZISIiIiIiIiIiIp3TunsLHrcBNvBPSuJvVbvaToQxMCrG2nC9xDAMAo1EALbUlmHY7fhHBwHgLD1zCXgROeWybGiIiIiIiIiIiIhI32OWeQv2jqhADD8/ttaWAhBoJGIYV84/So51pABQcti7xJQj0dvMMSu05JTI+fhZHeBysG7dOqsj9IrOjLOioqLHc4iIiIiIiIiISP9klnsL9v5J3gJ+yZG9wKkC/5UiNWwg++phf3MVAI7UFNi2D3NfrbXBRPo4zdAQERERERERERGRXuHcdwAAR2oyAAeaKwFvgf9KkhPr3QC93rkfAP8hWQCYdQ2WZRLpD9TQEBERERERERERkV5hHqwHwDE4E4CjTm+Do73Af6UYN8A7/pPGQVxuF47skQA4653gPGFlNJE+TQ0NERERERERERER6XnOFsyjTgAcWSNpdbViGgeBUwX+K8XY5CF43HYMWys7DlbiyBgOgNnkh+fwXovTifRdamiIiIiIiIiIiIhIj/McrcA8ZgfAkTGc7XWVGLZWPG47Y5OHWJyudwU7HPi54wHYuL8E/wEDwAYel0Fr2RZrw4n0YWpoiIiIiIiIiIiISI9r3bMVj8sGBvgnJ7NxfwkAfu44gh0Oi9P1vnD7AAC2HyrD8PPDERUIgFm6zcpYIn2aGhoiIiIiIiIiIiLS45wlWwHwjwzAcDjYUbcbgHB7spWxLJMYnApARUMFAP6J0QCY5butiiTS56mh0cfl5uYya9Ysq2P0SStXriQyMtLqGOc0b948Ro0aZXUMEREREREREZE+wdzrLdQ7EqIAqGgsB04V9q80QyMHA1DXUg2AI9Xb2HHuO2BZJpG+Tg2NPmLdunUYhkF9ff0lP2vlypUYhtHhFRgYeOkhRURERERERERELpLZVqh3pHqXWqpr2QfAkMh0yzJZ6er4oQA0uWsAcKR7j82D9VZFEunz/KwOID0jPDyckpIS37FhGBamuTSmaeK4AtdRFBERERERERG5nJgHjwLg31a4b3YfADuMiM+wMpZlJqXmwFbw2Bs4fLyRgKyRwJuYR01oPQl+AVZHFOlzNEOjG+Tm5jJz5kxmzpxJREQEsbGxPPHEE3g8Ht81r7/+OuPGjSMsLIzExETuuusu6urqAKioqOCGG24AICoqCsMwmD59uu9et9vNY489RnR0NImJicybN++CmQzDIDEx0fdKSEg47/XTp09n6tSpHd6bNWsWubm5XRrnoEGDWLBgAXfeeSchISEkJyezbNmyDs+tr6/n3nvvJS4ujvDwcG688Ua2bt3qO9++VNOrr75Kenr6BWeXrFmzhoyMDAIDA8nLy6O6urrD+ZdffpkhQ4bgcDjIysri9ddf952rqKjAMAy2bNnSIZ9hGKxbtw44NXtm7dq1jBs3juDgYK655poODSOAgoICEhISCAsLY8aMGbS0tJw3t4iIiIiIiIjIFaPVxDxyEgBH1ki+O96Ax94ItBX2r0CDomOgNQyAr6p34Z85AgDzmB3P0Uoro4n0Wf2ioeE2Xed8eZzuLlzr6tS1F+O1117Dz8+PjRs3smTJEhYtWsSrr77qO+90OlmwYAFbt25lzZo1VFRU+JoWqampvPfeewCUlJRQU1PDkiVLOjw7JCSEDRs28OyzzzJ//nw+++yz8+Zpampi4MCBpKam8o//+I/s2LHjosbV1XECPPfcc4wcOZLNmzczZ84c8vPzO+S97bbbqKur4+OPP2bTpk2MGTOGm266iSNHjviu2b17N++99x6rV6/u0Gz4vuPHj/PUU0+xatUq1q9fT319PXfccYfv/Pvvv09+fj4PP/ww27dv52c/+xn33HMPf/nLX7o89scff5znn3+eoqIi/Pz8+OlPf+o79/bbbzNv3jyefvppioqKSEpK4qWXXuryZ4iIiIiIiIiIXI489VU4j9kBcGSPZEP1Lu8JV6i3sH8FMgyDQCMRgC21pThSksEAj8tG654t1oYT6aP6xZJTB/7ly3OeC8yKIvaeq3zHNQu+OqPJ0c6RHkH8z0b4jmt/txF3c+sZ16UUXNvljKmpqSxevBjDMMjKymLbtm0sXryY++67D6BD8Xvw4MH8/ve/Z/z48TQ1NREaGkp0dDQA8fHxZ2x0PWLECObOnQtARkYGS5cuZe3atdxyyy1nzZKVlcXy5csZMWIEDQ0NFBYWcs0117Bjxw5SUlK6PLaujBNgypQpzJkzB4DMzEzWr1/P4sWLueWWW/jiiy/YuHEjdXV1BAR4p80VFhayZs0a3n33Xe6//37Au8zUqlWriIuLO28ep9PJ0qVLmThxIuBtuOTk5LBx40YmTJhAYWEh06dP58EHHwRg9uzZfPXVVxQWFvpmxXTWU089xfXXXw/AnDlz+OEPf0hLSwuBgYG88MILzJgxgxkzZgCwcOFC/vznP2uWhoiIiIiIiIgI4Cr/Fner999W+6emsvlLb70vkKR+vVT6pYpxpLDfVUbpkb0YDgf+kQE4j57EWfIt/pN+bHU8kT6nX8zQ6A8mTZrU4S/fyZMnU1ZWhsvlnfGxadMmbr31VtLS0ggLC/MVxquqqi747BEjRnQ4TkpK8i1XdTaTJ09m2rRpjBo1iuuvv57Vq1cTFxfHK6+8cjFD6+BC42x/7/t5iouLAdi6dStNTU3ExMQQGhrqe5WXl7Nnzx7fPQMHDrxgMwPAz8+P8ePH+46zs7OJjIz0fV5xcTFTpkzpcM+UKVN857vi9N8hKSkJwPc7FBcX+5oq7b7/PYiIiIiIiIiIXKnMEu9y4/4RDmwOB6VH9gIQ40i2Mpbl0sIGArC/yVsjdCREAmDuLbMqkkif1i9maAyYf805z32/g5v0xKTzXNvxOPFXEy4pV2c1NzeTl5dHXl4eb7zxBnFxcVRVVZGXl4dpmhe839/fv8OxYRi43WefhXKu+0ePHs3u3bvPeY3NZuuwFwZ4Zz90t6amJpKSknz7U5zu9JkpISEh3f7ZZ2OzeXt6p4/9XOM+/Xdo/3PXld9BRERERERERORK1V6g928r2O9v9hbw08IGWZSob8iJHcLf6uGocx8AjpRkmncdxKzeb20wkT6qX8zQsDns53wZ/rYuXGvv1LUXY8OGDR2Ov/rqKzIyMrDb7ezatYvDhw9TUFDAtddeS3Z29hkzLBwOB0CHmQ7dxeVysW3bNt+sgrOJi4ujpqamw3tn27vifOM8/b3vX5OT493cacyYMdTW1uLn58fQoUM7vGJjY7s6NFpbWykqKvIdl5SUUF9f7/u8nJwc1q9f3+Ge9evXM2zYMADfLJDTx36+PTvOJScn56zfjYiIiIiIiIiIgLOtQO9I8danjjq9xzmxQyzL1BeMTcoCwDTqcLld+A/2fh/mwaNWxhLps/pFQ6M/qKqqYvbs2ZSUlPDmm2/y4osvkp+fD0BaWhoOh4MXX3yRvXv38sEHH7BgwYIO9w8cOBDDMPjwww85dOgQTU1NF51l/vz5fPrpp+zdu5dvvvmGn/zkJ1RWVnLvvfee854bb7yRoqIiVq1aRVlZGXPnzmX79u1dGme79evX8+yzz1JaWsqyZct45513fNfcfPPNTJ48malTp/Lpp59SUVHBl19+yeOPP96hMdFZ/v7+/OIXv2DDhg1s2rSJ6dOnM2nSJCZM8M6+efTRR1m5ciUvv/wyZWVlLFq0iNWrV/PII48AEBQUxKRJkygoKKC4uJjPP/+c3/72t13OkZ+fz/Lly1mxYgWlpaXMnTu32zZiFxERERERERHp78zawwA40ofgcrswjYMAjGkr6F+pxqYMxuO2g83JzroqHJneJc/NIyfB1f2rp4j0d2podJNp06Zx4sQJJkyYwEMPPUR+fr5vg+u4uDhWrlzJO++8w7BhwygoKKCwsLDD/cnJyTz55JPMmTOHhIQEZs6cedFZjh49yn333UdOTg7/8A//QGNjI19++aVvVsLZ5OXl8cQTT/DYY48xfvx4jh07xrRp07o0znYPP/wwRUVFjB49moULF7Jo0SLy8vIA71JNH330Eddddx333HMPmZmZ3HHHHVRWVpKQkNDlsQYHB/OrX/2Ku+66iylTphAaGsqf/vQn3/mpU6eyZMkSCgsLGT58OK+88gorVqwgNzfXd83y5ctpbW1l7NixzJo1i4ULF3Y5x+233+77/saOHUtlZSUPPPBAl58jIiIiIiIiInLZcbswD7cA4Mi8mu0HKzFsrXg8dsalDLY4nLVCHAH4ub0riGzYtwtH1kgAnMfseOovvPeuyJXG8Hx/44Qe1tjYSEREBA0NDYSHh3c419LSQnl5Oenp6QQGBvZmrEuSm5vLqFGjeOGFF6yO0qM6M85BgwYxa9YsZs2a1Wu5+qv++uddRERERERERKQrPEcqKL0+D7fTRvp/rGHVsT28uONX2FsT2TLjM6vjWe7alf9MvfENN8ffz/M33k/JyFEAZPzbM/iNm2ppNpHecr6+wek0Q0NERERERERERER6jKtyG26ntwzpGDiQnYd2AxBmH2BlrD4jKTgNgPKGCmwBAfhF+ANglmy1MpZIn6SGhoiIiIiIiIiIiPQY5y5vYd4v3B9bYCDlDRUAJAWlWpiq7xgcmQ5AXYt3iSlHfCQA5p4yqyKJ9Fl+Vge4HKxbt87qCL2iM+OsqKjo8RwiIiIiIiIiItJ/mHtLAHDERwBQ11INBgyOurL3z2g3In4o/1UDTe4aABypAzhedghn9T6Lk4n0PZqhISIiIiIiIiIiIj3GrPIW5h3JiQA0txXuR8QPtSxTXzIpNQcAj72Bw8cbcQzyNnrM2sNWxhLpk9TQEBERERERERERkR7TXpj3Tx/M4eONeOwNwKlC/pUuPToWXKEAbKguwZF5FQDm4RPgdlkZTaTPUUNDREREREREREREeobbjfPwCQAcGVfxVXWx931XqLeQLxiGQSDe2Stbakvxzx4NgHnMjqdhv5XRRPocNTRERERERERERESkZxyrwTxmAODIHsOWWu9G14EkYhiGlcn6lBhHCgAlR/biGDgIALfThqtym4WpRPoeNTRERERERERERESkR7iqtuM6aQfAMWgQpYf3AqcK+OKVFjYIgP1NldiCgvAL8wPAuWuLdaFE+iA1NERERERERERERKRHmLs2A2AP9cMWEsK+5krgVAFfvLJjvBuBH3V6l5hyxEcAYO4ptSyTSF+khkYfl5uby6xZs6yO0SetW7cOwzCor6+3OspZrVy5ksjISKtjiIiIiIiIiIhYxtxTAoAjLhyA+raCfXsBX7zGDsgGwDQO4nK78E/27qlhVldbGUukz7ksGxput5vy8nK2bdtGeXk5brfb6kgX1N3F+fr6eh566CGSkpIICAggMzOTjz76qFueLSIiIiIiIiIi0hnOKm9B3pGSiMvt4qRxEIAxA7KsjNXnjEsZjMdjB5uTnYeqcAzyNnzMmsMWJxPpW/ysDtDddu7cySeffEJjY6PvvfDwcH7wgx8wbNgwC5P1HtM0ueWWW4iPj+fdd98lOTmZysrKfjtbwOVyYRgGNttl2X8TEREREREREblsmTXfAeAYmM6Og5UYtlY8HjvjU4ZYnKxvCXEEYHfF4vY7yIbqEn6cORz4T5yHj4PHA9pAXQS4zGZo7Ny5k7fffrtDMwOgsbGRt99+m507d/bI5+bm5jJz5kxmzpxJREQEsbGxPPHEE3g8Ht81r7/+OuPGjSMsLIzExETuuusu6urqAKioqOCGG24AICoqCsMwmD59uu9et9vNY489RnR0NImJicybN++8eZYvX86RI0dYs2YNU6ZMYdCgQVx//fWMHDnynPfMmzePUaNGdXjvhRdeYNCgQb7j6dOnM3XqVJ588kni4uIIDw/n5z//OaZpdum7OHnyJI888gjJycmEhIQwceJE1q1b5zvfvlTTBx98wLBhwwgICKCqquqc2devX8+IESMIDAxk0qRJbN++vcP59957j+HDhxMQEMCgQYN4/vnnO5w3DIM1a9Z0eC8yMpKVK1cC3t/HMAxWr17NDTfcQHBwMCNHjuRvf/tbh3tWrlxJWloawcHB/NM//ROHD6uDLiIiIiIiIiJXMI8H87tmABwZw9m437v8lN0VS4gjwMpkfVK4PRmAHYd248geA4B5zIBjtVbGEulT+nRDw+PxYJpmp14tLS18/PHH533eJ598QktLS6eed3oBvjNee+01/Pz82LhxI0uWLGHRokW8+uqrvvNOp5MFCxawdetW1qxZQ0VFha9pkZqaynvvvQdASUkJNTU1LFmypMOzQ0JC2LBhA88++yzz58/ns88+O2eWDz74gMmTJ/PQQw+RkJDAVVddxdNPP43L5erSmM5m7dq1FBcXs27dOt58801Wr17Nk08+2aXvYubMmfztb3/jrbfe4ttvv+W2227jBz/4AWVlZb5rjh8/zu9+9zteffVVduzYQXx8/DkzPfroozz//PN8/fXXxMXFceutt+J0OgHYtGkTP/7xj7njjjvYtm0b8+bN44knnvA1K7ri8ccf55FHHmHLli1kZmZy55130traCsCGDRuYMWMGM2fOZMuWLdxwww0sXLiwy58hIiIiIiIiInLZaD7kLcgD/jmj2X5oNwDh9gFWpuqzkoJSAShvKMeR7l1yynXSjqtq+/luE7mi9Oklp5xOJ08//XS3Pa+xsZGCgoJOXfub3/wGh8PR6WenpqayePFiDMMgKyuLbdu2sXjxYu677z4AfvrTn/quHTx4ML///e8ZP348TU1NhIaGEh0dDUB8fPwZS0ONGDGCuXPnApCRkcHSpUtZu3Ytt9xyy1mz7N27l//5n//h7rvv5qOPPmL37t08+OCDOJ1O33MulsPhYPny5QQHBzN8+HDmz5/Po48+yoIFC3xLQp3vu6iqqmLFihVUVVUxYID3/7weeeQRPvnkE1asWOH7vZ1OJy+99NJ5Z5W0mzt3ru+7eO2110hJSeH999/nxz/+MYsWLeKmm27iiSeeACAzM5OdO3fy3HPPdZgF0xmPPPIIP/zhDwF48sknGT58OLt37yY7O5slS5bwgx/8gMcee8z3OV9++SWffPJJlz5DRERERERERORy4dq3A1eLHQBH+hAqdq4CIDEozcpYfdbgyHSKa6GupRpbSAj2EDuuZhfmrs0EXXX2OqDIlaZPz9DoTyZNmoRx2lp2kydPpqyszDcrYtOmTdx6662kpaURFhbG9ddfD3DepZTajRgxosNxUlKSb7mqs3G73cTHx/Ov//qvjB07lttvv53HH3+c//t//+/FDK2DkSNHEhwc7DuePHkyTU1NVFdX+94733exbds2XC4XmZmZhIaG+l6ff/45e/bs8d3jcDjOGPe5TJ482fff0dHRZGVlUVxcDEBxcTFTpkzpcP2UKVM6/DaddXqepKQkAN/vUFxczMSJE8+ZS0RERERERETkSuPctRkAe7Ade1gYdS3e+tGQyHQrY/VZVydkANDkrgHAER8OgLmnxLJMIn1Nn56h4e/vz29+85tOXVtZWckbb7xxwevuvvtuBg4c2KnP7i7Nzc3k5eWRl5fHG2+8QVxcHFVVVeTl5XXYf6KzWQzDwO12n/P6pKQk/P39sdvtvvdycnKora3FNM2zzjyx2WxnLLPVvmxTd2pqasJut7Np06YO+QBCQ0N9/x0UFNShKdKTDMPo1NhP/x3as53vdxARERERERERuZKZu3cB4IgLA9oK9fZThXvpaHJqDmwFj72eI8eP4UhO4ET5UZyd+AfRIleKPt3QMAyj08s+DRkyhPDw8DM2BD9deHg4Q4YM8S2N1J02bNjQ4firr74iIyMDu93Orl27OHz4MAUFBaSmetfCKyoq6nB9+zi7Y5+LKVOm8O///u+43W7fWEtLS0lKSjrn9xkXF0dtbS0ej8dXrN+yZcsZ123dupUTJ04QFBTkG2doaKhvXHD+72L06NG4XC7q6uq49tprL3ms7c9PS/NOVTx69CilpaXk5OQA3kbO+vXrO1y/fv16MjMzfQ2VuLg4ampqfOfLyso4fvx4lzLk5OScddwiIiIiIiIiIlcqs7ISAMeAeA4fb8RjbwBgUmq2lbH6rPToWHCFgL2ZDftKGD8wHb7YhVlzyOpoIn3GZbPklM1m4wc/+MF5r/nBD37QI80M8C4dNXv2bEpKSnjzzTd58cUXyc/PByAtLQ2Hw8GLL77I3r17+eCDD1iwYEGH+wcOHIhhGHz44YccOnSIpqami87ywAMPcOTIEfLz8yktLeW//uu/ePrpp3nooYfOeU9ubi6HDh3i2WefZc+ePSxbtuysm6ybpsmMGTPYuXMnH330EXPnzmXmzJkdvtfzfReZmZncfffdTJs2jdWrV1NeXs7GjRt55pln+K//+q+LGu/8+fNZu3Yt27dvZ/r06cTGxjJ16lQAHn74YdauXcuCBQsoLS3ltddeY+nSpTzyyCO++2+88UaWLl3K5s2bKSoq4uc//3mXZ+j88pe/5JNPPqGwsJCysjKWLl2q/TNERERERERE5IpmHvAu1e0/cBBfVXtna+AKYXB0nIWp+i7DMAjEu8z55ppSHEOHAWB+dxy+t7qIyJXqsmloAAwbNowf//jHhIeHd3g/PDycH//4xwwbNqzHPnvatGmcOHGCCRMm8NBDD5Gfn8/9998PeGcArFy5knfeeYdhw4ZRUFBAYWFhh/uTk5N58sknmTNnDgkJCcycOfOis6SmpvLf//3ffP3114wYMYJf/vKX5OfnM2fOnHPek5OTw0svvcSyZcsYOXIkGzdu7FD0b3fTTTeRkZHBddddx+23386PfvQj5s2b1+nvAmDFihVMmzaNhx9+mKysLKZOncrXX3/tm2XRVQUFBeTn5zN27Fhqa2v5z//8T99MlDFjxvD222/z1ltvcdVVV/Ev//IvzJ8/v8OG4M8//zypqalce+213HXXXTzyyCMd9gnpjEmTJvGHP/yBJUuWMHLkSD799FN++9vfXtR4RERERERERET6PY8H53fNADiGDmNLbRkAgST12jLj/VGMIwWA0iN78M8ZA4DZCBw/bGEqkb7D8Hx/84Ae1tjYSEREBA0NDWc0HlpaWigvLyc9PZ3AwMCL/gy3201lZSVNTU2EhoYycODAHpuZAd7ZDaNGjeKFF17osc/oC6ZPn059fT1r1qw55zVXynfRHbrrz7uIiIiIiIiISJ9z/AhlUybResLOoH9fxc8rP+abxndItufyyU9etDpdn3XffxTyVf1rJNgm8t9TF1M6fgIAmf/xf7FnXW9xOpGec76+wekuqxka7Ww2G+np6Vx99dWkp6f3aDNDREREREREREREOnLv30nrCe/+pY4hmexv8m5snRo20MpYfV52zBAAjjoPYA8Lwx7srWs6d222MpZIn6FKv4iIiIiIiIiIiHQrs8RbgLcH2rBHRHDUuR+A7OjBVsbq88YOyALANGpxuV044sK8x7uLrYwl0mf4WR3gcrBu3TqrI/SKlStXXvCaK+W7EBERERERERGRczPLdgLgHxeKy+3CNA4CMDY528pYfd74lCF4PHYMm5Odh6qJGRDPicoGzMpKq6OJ9AmaoSEiIiIiIiIiIiLdytlWgHckxbGzrgpsTjweO+NThlicrG8LcQRgd8UC8PW+EvwHDgLAPFBnYSqRvkMNDREREREREREREelW5gHvjAzHwIFs2FcCgN0VS4gjwMpY/UK4fQAA2+rKcAzNAcB5qMnKSCJ9hhoaIiIiIiIiIiIi0q3MtgK8Y2gOOw6VAacK9XJ+iUFpAFQ0VODIGQOA2QgcP2JhKpG+QQ0NERERERERERER6T4tDZgNbgD8c0ZT3lABnCrUy/kNiUwH4GBLNY4h3k3CW0/YcR/QxuAiamiIiIiIiIiIiIhIt3HXlNB63A/wztCoa6kGYHDkIAtT9R9XJ2QA0OQ+gD0yElugt4Rr7tpsZSyRPkENDREREREREREREek2zl3fAGBzGNijomhyHwBgREKmlbH6jYmp3lkZHns99S1NOGJDADB3a4aGiBoafVxubi6zZs2yOkaftHLlSiIjI62OcU7z5s1j1KhRVscQEREREREREelVZtkOABxxIRw90YTH3gCcKtTL+Q2JjgeXt4nxVfUuHAPiAHBWVliYSqRvUEOjj1i3bh2GYVBfX3/Jz8rNzcUwjDNeP/zhDy89qIiIiIiIiIiIyHmYbYV3R1IcG/aVeN90hXgL9XJBhmEQSBIA3xwoxTFwIADm/jorY4n0CX5WB5Dut3r1akzT9B0fPnyYkSNHctttt1mY6uKZponD4bA6hoiIiIiIiIiIdIK5/yAA/mlpfFPjbWgEkoRhGFbG6leiHckccO2m9MheHENygL9gHmq0OpaI5TRDoxvk5uYyc+ZMZs6cSUREBLGxsTzxxBN4PB7fNa+//jrjxo0jLCyMxMRE7rrrLurqvF3ViooKbrjhBgCioqIwDIPp06f77nW73Tz22GNER0eTmJjIvHnzzpun/br212effUZwcPB5GxrTp09n6tSpHd6bNWsWubm5XRrnoEGDWLBgAXfeeSchISEkJyezbNmyDs+tr6/n3nvvJS4ujvDwcG688Ua2bt3qO9++VNOrr75Keno6gYGB5x3vmjVryMjIIDAwkLy8PKqrqzucf/nllxkyZAgOh4OsrCxef/1137mKigoMw2DLli0d8hmGwbp164BTs2fWrl3LuHHjCA4O5pprrqGkpKTD5xQUFJCQkEBYWBgzZsygpaXlvLlFRERERERERC5HzrbCu2NIFqVH9gLeAr10XlrYIAD2NVfinzMaALPBDSePWZhKxHr9oqFhmuY5X06ns9uvvRivvfYafn5+bNy4kSVLlrBo0SJeffVV33mn08mCBQvYunUra9asoaKiwte0SE1N5b333gOgpKSEmpoalixZ0uHZISEhbNiwgWeffZb58+fz2WefdTrbH//4R+644w5CQkIuamxdGSfAc889x8iRI9m8eTNz5swhPz+/Q97bbruNuro6Pv74YzZt2sSYMWO46aabOHLkiO+a3bt3895777F69eoOzYbvO378OE899RSrVq1i/fr11NfXc8cdd/jOv//+++Tn5/Pwww+zfft2fvazn3HPPffwl7/8pctjf/zxx3n++ecpKirCz8+Pn/70p75zb7/9NvPmzePpp5+mqKiIpKQkXnrppS5/hoiIiIiIiIhIv2Y2Y9a7AHDkjGZ/UyUAaWEDrUzV72RHDwbgqLkfR8YwAFqP++GuKTnfbSKXvX6x5NTTTz99znMZGRncfffdvuPnnnvujMZFu4EDB3LPPff4jl944QWOHz9+xnUXmgFxNqmpqSxevBjDMMjKymLbtm0sXryY++67D6BD8Xvw4MH8/ve/Z/z48TQ1NREaGkp0dDQA8fHxZ2x0PWLECObOnesb79KlS1m7di233HLLBXNt3LiR7du388c//rHLY7qYcQJMmTKFOXPmAJCZmcn69etZvHgxt9xyC1988QUbN26krq6OgIAAAAoLC1mzZg3vvvsu999/P+BtNq1atYq4uLjz5nE6nSxdupSJEycC3oZLTk4OGzduZMKECRQWFjJ9+nQefPBBAGbPns1XX31FYWGhb1ZMZz311FNcf/31AMyZM4cf/vCHtLS0EBgYyAsvvMCMGTOYMWMGAAsXLuTPf/6zZmmIiIiIiIiIyBXFc7AU53E7AI6M4RzdtR/skB09xOJk/cuYAVms3AumUQsR4dgcBm7Tg3PXJgIGjbM6nohl+sUMjf5g0qRJHdYBnDx5MmVlZbhc3o70pk2buPXWW0lLSyMsLMxXGK+qqrrgs0eMGNHhOCkpybdc1YX88Y9/5Oqrr2bChAmdHcp5XWic7e+dbvLkyRQXFwOwdetWmpqaiImJITQ01PcqLy9nz549vnsGDhx4wWYGgJ+fH+PHj/cdZ2dnExkZ6fu84uJipkyZ0uGeKVOm+M53xem/Q1KSd2Om9t+huLjY11Rp9/3vQURERERERETkcmeWfAMeA8PfgOgoTMO7n8aYAVkWJ+tfxqcMweOxg83Jru/24Yj1rrxilu20OJmItfrFDI3f/OY35zz3/c2EHn300U5fO2vWrEvK1VnNzc3k5eWRl5fHG2+8QVxcHFVVVeTl5XVqiSt/f/8Ox4Zh4Ha7O/W5b731FvPnz7/gtTabrcNeGMA5Z7pciqamJpKSknz7U5zu9Jkp3bE8VmfYbN6e3uljP9e4T/8d2v8sdeZ3EBERERERERG5Upil2wFwxART/N0+sDnxeGyMT9EMja4IDQjE7orF7XeQjftK+LukWFoONGFWlFsdTcRS/WKGhsPhOOfr+8X+7rj2YmzYsKHD8VdffUVGRgZ2u51du3Zx+PBhCgoKuPbaa8nOzj5jhkX7554+0+FSvfPOO5w8eZKf/OQnF7w2Li6OmpqaDu+dbe+K843z9Pe+f01OTg4AY8aMoba2Fj8/P4YOHdrhFRsb29mh+bS2tlJUVOQ7Likpob6+3vd5OTk5rF+/vsM969evZ9gw79qD7bNATh/7+fbsOJecnJyzfjciIiIiIiIiIlcSZ1vB3ZEUw4bqXQDYXXGEBgRaGatfCrd7VwjZfmg3jrRUAMwDB62MJGK5ftHQ6A+qqqqYPXs2JSUlvPnmm7z44ovk5+cDkJaWhsPh4MUXX2Tv3r188MEHLFiwoMP9AwcOxDAMPvzwQw4dOkRTU9MlZ/rjH//I1KlTiYmJueC1N954I0VFRaxatYqysjLmzp3L9u3buzTOduvXr+fZZ5+ltLSUZcuW8c477/iuufnmm5k8eTJTp07l008/paKigi+//JLHH3+8Q2Ois/z9/fnFL37Bhg0b2LRpE9OnT2fSpEm+JbYeffRRVq5cycsvv0xZWRmLFi1i9erVPPLIIwAEBQUxadIkCgoKKC4u5vPPP+e3v/1tl3Pk5+ezfPlyVqxYQWlpKXPnzmXHjh1dfo6IiIiIiIiISH9m7vP+o1FHWio7Du0GIKytMC9dkxjk3Ui9vKEcx5BsAJx1jVZGErGcGhrdZNq0aZw4cYIJEybw0EMPkZ+f79vgOi4ujpUrV/LOO+8wbNgwCgoKKCws7HB/cnIyTz75JHPmzCEhIYGZM2deUp6SkhK++OIL3ybVF5KXl8cTTzzBY489xvjx4zl27BjTpk3r0jjbPfzwwxQVFTF69GgWLlzIokWLyMvLA7xLNX300Udcd9113HPPPWRmZnLHHXdQWVlJQkJCl8cZHBzMr371K+666y6mTJlCaGgof/rTn3znp06dypIlSygsLGT48OG88sorrFixgtzcXN81y5cvp7W1lbFjxzJr1iwWLlzY5Ry333677/sbO3YslZWVPPDAA11+joiIiIiIiIhIf2Ye8hbcHUOyqGioACAxKM3CRP3X4MhBABw8UY0jexQAZn0rmMetCyViMcPz/Y0TelhjYyMRERE0NDQQHh7e4VxLSwvl5eWkp6cTGNh/pqHl5uYyatQoXnjhBauj9KjOjHPQoEHMmjWr1/Yn6c/66593EREREREREZGzcrawe/LVOJv8SPvX33PL3lc5ZuzkHxLz+V3evVan63f+bcvn/G7rTGyuKDb9P+9Sdt31YHjI/uxPGCkjrY4n0q3O1zc4nWZoiIiIiIiIiIiIyCXzfLcHZ7N3n1VH5tU0uQ8AcHV8hpWx+q2JKVkAuO1HORYWhOFvgMfA3PWNxclErNOlhsYzzzzD+PHjCQsLIz4+nqlTp1JSUtJT2URERERERERERKSfcJZ8Ax4Dww+OhQXjsdcDMDE1y9pg/dTQmARwhQCwYV8JjpggAMyyM/e9FblS+HXl4s8//5yHHnqI8ePH09raym9+8xv+7u/+jp07dxISEtJTGfu8devWWR2hV3RmnBUVFT2eQ0RERERERERE+h6zdBsAjuggNuwv9b7pCvEW5qXLDMMggEROsoctNaVclRTDydrjOCv2Wh1NxDJdamh88sknHY5XrlxJfHw8mzZt4rrrruvWYCIiIiIiIiIiItJ/mOV7APBPimFzjbehEeBJxDAMK2P1azGOZA649lBypBxHaipsrsbcV2t1LBHLXNIeGg0NDQBER0ef85qTJ0/S2NjY4SUiIiIiIiIiIiKXF+f+GgAcKcmUHvE2N2ICkq2M1O+lhg4CoLqpAv8hmQCYdQ0WJhKx1kU3NNxuN7NmzWLKlClcddVV57zumWeeISIiwvdKTU294LM9Hs/FxhLpN9xut9URRERERERERES6jXmwHgDH4Ez2NVUBpwrycnGyY4YAcNTcjyNrFADmUSe0nrQwlYh1urTk1Okeeughtm/fzhdffHHe6379618ze/Zs33FjY+M5mxr+/v4YhsGhQ4eIi4vTdDS5LHk8HkzT5NChQ9hsNhwOh9WRREREREREREQuTauJecQJ+OHIGsnRqi/AfqogLxdnzIBMXtsLplGLPWM4AM5mO57v9mIk5licTqT3XVRDY+bMmXz44Yf89a9/JSUl5bzXBgQEEBAQ0Knn2u12UlJS2LdvnzaXlstecHAwaWlp2GyXtPKbiIiIiIiIiIjlPEcqMJvtANizRmBWe/d5GDMg08pY/d6ElKF4PDYMm5M9Nid2O3hcBs6Sb3CooSFXoC41NDweD7/4xS94//33WbduHenp6d0eKDQ0lIyMDJxOZ7c/W6SvsNvt+Pn5aRaSiIiIiIiIiFwWnKXfgNvAsMNuPyfYnHg8NiakDLU6Wr8WGhCI3RWL26+OjQdKuT4mkJN1LZil23Bcb3U6kd7XpYbGQw89xL//+7/zH//xH4SFhVFb6+20RkREEBQU1G2h7HY7dru9254nIiIiIiIiIiIiPcdZug0A/6hAvjxQBoDdFUtoQKCVsS4LYfYBNFDH9kN7uDkxhpN1+zHL91gdS8QSXVrr5uWXX6ahoYHc3FySkpJ8rz/96U89lU9ERERERERERET6OHPvbgAciVFsP+RtaITZB1gZ6bKRGJQGwN6GvThSkwFw7jtgZSQRy3R5ySkRERERERERERGR05n79gPgSEmmvKECOFWIl0szOHIQJbVQd6Iax+CrgY2YB+utjiViCe1GLCIiIiIiIiIiIpekvcDuP3goB09UA95CvFy6q+MzAGhy1+DIGgmAedQEl/YgliuPGhoiIiIiIiIiIiJy8dwunEdOAuDIGkGTuwY4VYiXSzMpNRsAt/0oJ9IzATCb7HiOVFiYSsQaamiIiIiIiIiIiIjIRfMcrcJssgPQMjgbj/0oAJNSsq2MddkYGpMArmAANjkbMWyA28BZ+o21wUQsoIaGiIiIiIiIiIiIXLTWsm/wuAywQZGr0fumK5ihsQnWBrtMGIZBAIkAbK7bjX90AADOkm1WxhKxhBoaIiIiIiIiIiIictHMkm8BcEQ62HxwDwABJGIYhpWxLisxjhQASo7sxZEQBYBZvsfKSCKWUENDRERERERERERELpq5twwA/8QoSo+WA6cK8NI9UkMHArCvqRJHSjIAZvV+KyOJWEINDREREREREREREblozrbCuiNlANVNFcCpArx0j6yYIQAcMffjP3goAObBo1ZGErGEGhoiIiIiIiIiIiJy0cyDRwBwpA/hqOltbrQX4KV7jB2QBYBp1OKfeTUAziMt4HZZGUuk16mhISIiIiIiIiIiIhfH7cY83AKA39DhmEYtAGMGZFqZ6rIzIWUoHo8NbCbVCUkAmE12PPX7LE4m0rvU0BAREREREREREZGL4mk8gHnMW2KsShwANicej42JKRkWJ7u8hAYEYnfFArCxtQFs4HEZtJZ9Y3Eykd6lhoaIiIiIiIiIiIhclNY9m/G4bGDA1+5jANhdsYQGBFqc7PITZh8AwLYj5TgiHQCYJVutjCTS69TQEBERERERERERkYvi3OUtqPtH+LP9aCVwqvAu3SsxKBWA8oZy/BMiATD3llmYSKT3qaEhIiIiIiIiIiIiF8XcUwKAIyGSvQ17gVOFd+le6RHpABw8UY0jxds0clbvtzKSSK9TQ0NEREREREREREQuilnt3ZTakZxI3Ylq4FThXbrXiATvviRN7gM4Bg0BwKw9YmUkkV6nhoaIiIiIiIiIiIhclPaCun/6EJrcNcCpwrt0r0kp2QC47UdxDvZ+x+bhE+DxWBlLpFepoSEiIiIiIiIiIiJd5/F4C+pAa3oGbvtR4FThXbrX0NgEcAUDsCMiEgDzmA1PY42FqUR6lxoaIiIiIiIiIiIi0mWeYwdxNhoA7IiK8r7nCvYW3qXbGYZBAIkAfM0xMMDjstG6e7PFyUR6jxoaIiIiIiIiIiIi0mWu8q24W73lxSKaAAgkEcMwrIx1WYt2pACwq7ES/wh/AJwlWyxMJNK71NAQERERERERERGRLjN3bQHAP8KP4mNVwKmCu/SMtNA0APY1VeGIjwDA3FNqZSSRXqWGhoiIiIiIiIiIiHSZuacEAP/4CPY1VQKQGpJmZaTLXlbMUACOmPtwpCQBYFbvszKSSK9SQ0NERERERERERES6zFnlnZXhSE7giLkfgOzYoVZGuuyNScoEwDQO4jcw3fvfNYetjCTSq9TQEBERERERERERkS5rL6T7p6VjGrXAqYK79IwJKRl4PDawneRwsnd5L/PwcfB4LE4m0jvU0BAREREREREREZGu8Xgwv2sG4NCAZLCZeDw2JqRkWBzs8hYWGIjdFQvA5tAQAJyNBp7m76yMJdJr1NAQERERERERERGRLvEcP4LZaACwLTwUALsrlrDAQCtjXRHC7N69MzbbmwBwt9pw7d1qZSSRXqOGhoiIiIiIiIiIiHSJq+Jb3E5vabHI7zhwqtAuPSshyLvx+u7j+/AL9wPA3LXZykgivUYNDREREREREREREekSZ1sB3S/Mzu4T+wBICEq1MtIVY3CEdzPw2hNVOOLDATD37LIykkivUUNDREREREREREREusTc7S2gO+LCOHiiGoDBEYOtjHTFuDp+KABN7hocAxIAcFZVWRlJpNeooSEiIiIiIiIiIiJdYlZVAuBITqDJfQA4VWiXnjUpNRsAl+0o7jTvrBizRpuCy5VBDQ0RERERERERERHpErPmEADu1BTc9qMATGwrtEvPGhqTgMcVjGF4qIyNAcD87rjFqUR6hxoaIiIiIiIiIiIi0iXOQ80AVMbGAuBxBZMRk2BlpCuGzWYjkEQAvg0LAcBsAE/zYStjifQKNTRERERERERERESk807UYzZ6APg2LAiAQBKx2VRq7C3RjmQAvvH3NpbcThuuym1WRhLpFfpbRkRERERERERERDrNVb0d10k7AN84TgCnCuzSO1JDBgJQbu7HL9T7Wzh3bbYykkivUENDREREREREREREOs3c+Q0A9hAb5U7vhuDtBXbpHdmxQwA4au7DERcGgLl7l5WRRHqFGhoiIiIiIiIiIiLSaebuYgAccWEcMfcDkBUzxMpIV5zRSZkAnDQO4j8gHgCzssrKSCK9Qg0NERERERERERER6TRnZSUA/klxmMZBAMYMyLQy0hVnYkomHo8NbCdpSmpraNTUWZxKpOepoSEiIiIiIiIiIiKd1l44b05KANtJPB4bE1PU0OhNYYGB2F0xAOyJigTAeajZwkQivUMNDREREREREREREek081ATAHuiwwGwu2IICwy0MtIVKdQ+AICt4QEAmI1uOHnMykgiPU4NDREREREREREREekcsxmzwQ3At+HeJkZ7YV16V2JQKgBbA44D4Dppx1W13cpIIj1ODQ0RERERERERERHpFNe+nbha7ABsCTgBnCqsS+8aHJEOQLW7BnuIt8xr7txkZSSRHqeGhoiIiIiIiIiIiHSKs9hbMLcH2ajy1ACQ3lZYl951VfxQAI65D+CIDQXA3F1sZSSRHqeGhoiIiIiIiIiIiHSKWbYTAEdcCE1ub0Pj6rbCuvSuSak5ALhsRzESYwFwVlZYmEik56mhISIiIiIiIiIiIp1iVpYDYCRE47IdBU4V1qV3ZcQk4HEFYRgeDsdHAWAeqLM4lUjPUkNDREREREREREREOsXcfxCA7+KiMQwPHlcQGTEJFqe6MtlsNgJJBGB3ZNuSU4earIwk0uPU0BAREREREREREZFOcR46BsCeqBAAAknEZlOJ0SrR/ikAfBvuD4DZ4ALzuJWRRHqU/rYRERERERERERGRC3OewKx3AbAt3AGcKqiLNVJDBwKwLdDbxHC12HHt18bgcvlSQ0NEREREREREREQuyH2ghNYTdgC2BnkL6CltBXWxRmbMYAD22w9iDzIAcBYXWRlJpEepoSEiIiIiIiIiIiIXZBZvAsAeaHDAz7v5dFZbQV2sMXZAFgAnjVr8Y73LgJllO62MJNKj1NAQERERERERERGRCzLLdgDgHxPMScO7OfiYpCwrI13xJqZk4vHYwHYSZ3wkAGZFubWhRHqQGhoiIiIiIiIiIiJyQc5Kb6HcGR8JtpN4PDYmpWZaG+oKFxYYiN0VDcDBmAgAzAMHrYwk0qPU0BAREREREREREZELMvfXAnAwJhwAuyuasMBAKyMJEGpPBmB3ZBAAzrpGK+OI9Cg1NEREREREREREROSCzLoGAPZEeQvn7YV0sVZCUAoA28K9pV6z3gWtJ62MJNJj1NAQERERERERERGR82s1MY+2ArA9zFtSbC+ki7UGR6QDsD3kOACtJ+y4a0qtjCTSY9TQEBERERERERERkfNy1+2h9bi3lLgttAU4VUgXa10dnwHAwYA6bAEGAGZxkZWRRHqMGhoiIiIiIiIiIiJyXs7irwEDmwNqA7ybTl8dl2FtKAFgYmo2AC7bUfxivMuBmWU7rIwk0mPU0BAREREREREREZHzMku3A+AXE4TLXg/AxLRsCxNJu8yYRDyuIAzDw/HYMACc5XstTiXSM9TQEBERERERERERkfMyK7wF8ubYUAzDg8cVRGZMosWpBMBmsxGI97eoiQkFwNxfY2UkkR6jhoaIiIiIiIiIiIicl7nPWyCvjfYWzAM9idhsKi32FdH+yQCURQYAYNY1WhlHpMfobx0RERERERERERE5L2ddPQC72wrm0Y5kC9PI96WEDgRgp3fFKcyjTnA5LUwk0jPU0BAREREREREREZFzc7ViHvEWx3eEG8CpArr0DVkxQwDYGd4MQOtxO+663VZGEukRamiIiIiIiIiIiIjIOXkOl+M87i0j7grzFszbC+jSN4xJygTgu+BD2Bze95zFRRYmEukZamiIiIiIiIiIiIjIOZm7isBjYPhDXeh3wKkCuvQNE1Mz8XgMsJsQHQiAWbrD4lQi3U8NDRERERERERERETknZ8k2AIyoALCbeDwGE1PV0OhLwgODsLtiADgWEwyAWb7HykgiPUINDRERERERERERETknc6+3MN5eKLe7YggPDLIykpxFqH0AAAei2hoa+2usjCPSI9TQEBERERERERERkXMy9x0AThXK2wvn0rckBKUCsDvSu4mG82C9hWlEeoYaGiIiIiIiIiIiInJOZlthfHeUPwAJgakWppFzGRyRDsDOcBcA5lET3C4rI4l0OzU0RERERERERERE5OzcbsyjJwHYFe4GYHBkupWJ5ByuihsKQFlkMwDOZhuew5VWRhLpdmpoiIiIiIiIiIiIyFl5jlbjbPKWEEvbCuXthXPpWyalZgNwOKweww/wGJjFRdaGEulmamiIiIiIiIiIiIjIWTl3FYHHwPCDw+ENAExMybY4lZxNZmwSHlcQhg1c0d59NMySby1OJdK91NAQERERERERERGRszJLvQVxV6Q/2MDjCiIrLsniVHI2NpuNAE8CAA3RQQA4y3dbGUmk26mhISIiIiIiIiIiImdl7i0DoLGtQB7gScBmU0mxr4p2JAOwPyoAAHPfASvjiHQ7/e0jIiIiIiIiIiIiZ+Ws3g+cKpC3F8ylb0oNHQTA7gg/AMyDRy1MI9L91NAQERERERERERGRs2oviO+J9BbI2wvm0jdlxgwGoDSiFQDzyEnweKyMJNKt1NAQERERERERERGRM3k8mIdbAChpK5C3F8ylbxqTlAnA3uhjADibbHiO7rMykki3UkNDREREREREREREzuBpqMFs8pYPy6ObABidmGllJLmASalZeDwGRyNMsAMeA+euIqtjiXQbNTRERERERERERETkDM6STeA2wA6HI008HoNJqVlWx5LzCA8MwuaKwWMYONuWCTNLvrU4lUj3UUNDREREREREREREzuAs2QJAa4QfHsPA5oohIijI2lByQWH2JADqo70buZt7y6yMI9Kt1NAQERERERERERGRM7QXwo+2FcbDbElWxpFOSghMA6A6ygGAc5/20JDLhxoaIiIiIiIiIiIicgaz2lsI3x/pD0BCUJqVcaST0iPTAdgT6S39mrVHrYwj0q3U0BAREREREREREZEzmLWHgVOF8fSIQRamkc66Om4IALsjnQCYh1vA47Eykki3UUNDREREREREREREOvJ4cB5uAaCsrTB+VfxQKxNJJ01MyQGgKuY4AGaTgedYnZWRRLqNGhoiIiIiIiIiIiLSgaf5MOYxA4Dq2BMATGorlEvflhWXhMcVyJFwj7f66zZwlhRZHUukW6ihISIiIiIiIiIiIh20ln2Dx2XgMTwcjvDgcQWSFadNwfsDm81GAIl4bAYnI+wAOHdttTiVSPdQQ0NEREREREREREQ6MIs3e/83wo7bZhBAIjabSon9RbR/MgBHorwbupt7S62MI9Jt9LeQiIiIiIiIiIiIdGDuKQHgaJQDOFUgl/4hJXQgANXtDY3qaivjiHQbNTRERERERERERESkA2dbAbw6yg84VSCX/iErZjAAeyO9x2bNYevCiHQjNTRERERERERERESkA7PmOwD2Rnk3Bm8vkEv/MDoxC4C90SYAzsMnrIwj0m3U0BAREREREREREZEOzO+OA1Ae5S2Ij2orkEv/MCk1C4/H4EBMKwDmMQNP03cWpxK5dGpoiIiIiIiIiIiIiI/n+FHMRu9/H4hpxeMxmJSaaW0o6ZKIoCBsrmi+iwCP4cHjMmgt+8bqWCKXTA0NERERERERERER8WndsxmPy4bH8HAoAmyuaCKDgq2OJV0UZhuA22bQEmEHwNy1xdpAIt1ADQ0RERERERERERHxcRZvBuBkuB2X3SDUlmRxIrkY8UGpAHzXtrG7uafEyjgi3UINDREREREREREREfEx9+wC4LtIbyE8ISjNyjhykQZHDAKgOtI7Q8NZVW1hGpHuoYaGiIiIiIiIiIiI+Jhthe99Ud5CeHthXPqXq+IzACiP8gBg1mhTcOn/1NAQERERERERERERH/PAIeBUIXx4W2Fc+peJKdkAVMU4ATAPH7cyjki3UENDREREREREREREfMzvmgGojDEBmJiSZWUcuUjZcQPwuAKpjfIemw0ePC2N1oYSuURqaIiIiIiIiIiIiAgAnpNNOBu8MzNqow08rkBy4pItTiUXw2azEUAidZHgMTx4XDZad2+2OpbIJVFDQ0RERERERERERABw7d2Ku9WGBw91ERBAAjabSoj9VbR/Mi67wYkw72/oLP7G4kQil0Z/G4mIiIiIiIiIiAgAZvEmAE6E2Wj1M4jyT7E4kVyK5NCBABxq2+Dd3LPLyjgil0wNDREREREREREREQHA3O0teH/XVgBPaSuIS/+UHTMYgKr2hkZlpZVxRC6ZGhoiIiIiIiIiIiICgLOyAoDqKG/ZMDN6sIVp5FKNSvRu6F4R7QLAPPCdlXFELpkaGiIiIiIiIiIiIgKAWXMIgIooNwBjkrKsjCOXaFJqJh6PwYFo7+9pftdscSKRS6OGhoiIiIiIiIiIiABgHmoC4ECMG4/HYFJqpsWJ5FJEBgVjc0VTG2UA4Gxw4zmppob0X2poiIiIiIiIiIiICDhPYDZ4/yV/bZSBzRVNZFCwxaHkUoXakqiLBA8e3K02XOXfWh1J5KKpoSEiIiIiIiIiIiK0VmzDbXrLhQcjvYVw6f8SglJx+hkcD/PO0jCLN1mcSOTiqaEhIiIiIiIiIiIiONsK3cdDwfQ3SAhKtTiRdIfBEekA1EXaATB3F1sZR+SSqKEhIiIiIiIiIiIimGU7gVOF7/S2Qrj0b8PjMwCobt9Ho7LCwjQil0YNDREREREREREREcFsK3RXR3sL31e1FcKlf5uQkgVAZYx3fxTzQJ2VcUQuiRoaIiIiIiIiIiIi4it0V0V7C9/thXDp34bFJeNxBVIb7T02DzVZG0jkEqihISIiIiIiIiIiIjgPHQOgNgo87gCGxSVbnEi6g81mI4AEatuWnDLr3XicLRanErk4amiIiIiIiIiIiIhc6VpNzHoXALVRBgGeRGw2lQ4vF1H+yRyM9P6322nDVbXD0jwiF0t/K4mIiIiIiIiIiFzhXPuKcZ30lgpro7wFcLl8pIQOwvQ3aAr1Hjt3FlkbSOQiqaEhIiIiIiIiIiJyhTOLvQXu48Fw0mGQHDLQ4kTSnTKjBwNwMNJbDjbLdloZR+SiqaEhIiIiIiIiIiJyhXOWeZcgOhjlLRdmxQyxMo50szGJmQBUR3mPzcoK68KIXAI1NERERERERERERK5wZnk5cKrgPToxw8I00t0mpWXh8Rjsj/Eem/sPWhtI5CKpoSEiIiIiIiIiInKFM/fXArA/Bjweg4mpmRYnku4UGRSMzRVNbVvDynmo0dpAIhepyw2Nv/71r9x6660MGDAAwzBYs2ZND8QSERERERERERGR3mK2Fbhro8DmiiY6ONTiRNLdQm1J1EYZAJj1LnA5LU4k0nVdbmg0NzczcuRIli1b1hN5REREREREREREpDe5WjGPtgJQG2UQakuyOJD0hISgVN8MDddJG659xdYGErkIfl294e///u/5+7//+57IIiIiIiIiIiIiIr3MVVOKq8X7755rIyE5KNXaQNIj0iPS2X3SoCkYQo+DubOIoIEjrI4l0iXaQ0NEREREREREROQK5tz5NQDHg+BEoEF6RLrFiaQnXBU3FODUslNlO6yMI3JReryhcfLkSRobGzu8REREREREREREpG9oL2y3F7qHtxW+5fIyITUbgH3R3mNnRbmFaUQuTo83NJ555hkiIiJ8r9RUTVkTERERERERERHpK8zyvQDsa9tfYWJKloVppKcMi0vG4w6gpn2Gxv5aixOJdF2PNzR+/etf09DQ4HtVV1f39EeKiIiIiIiIiIhIJ5n7awCoiTbwuAMYFp9icSLpCTabjQBPgm9jcLOuwdpAIhehy5uCd1VAQAABAQE9/TEiIiIiIiIiIiJyEZxthe3aKAhwJ2Czadvdy1WUfwq1UZUAmEdbwe0Cm93iVCKd1+W/nZqamtiyZQtbtmwBoLy8nC1btlBVVdXd2URERERERERERKQnud2YR5yAdw+NKIdmZ1zOUkIGcrBthoarxYarZre1gUS6qMsNjaKiIkaPHs3o0aMBmD17NqNHj+Zf/uVfuj2ciIiIiIiIiIiI9Bx33R5aT3hLhLVRkBwy0OJE0pMyYwZzPNCgOch77Nz5tbWBRLqoy0tO5ebm4vF4eiKLiIiIiIiIiIiI9CJzZxEAxwOhOcggM2awxYmkJ41OzOTNCqiJMhh6woNZtp3AW6xOJdJ5WhBPRERERERERETkCmWWbgO8BW6A0YkZVsaRHjYpNQuPx2B/tPfYLN9jbSCRLlJDQ0RERERERERE5ArlbCtoH4gCj8dgUmqWxYmkJ0UFh2BzRVHb1sAy99VYnEika9TQEBERERERERERuUKZ+w4A3v0zbK4oooNDLU4kPS3UNoDato3BnQcbrA0j0kVqaIiIiIiIiIiIiFyhzIP1ANRGGYTakqwNI70iISj11AyNoyZov2TpR9TQEBERERERERERuRJ5PN6CNt6GRnxgqsWBpDcMihjkm6HResKGu67c2kAiXaCGhoiIiIiIiIiIyBXIfbia1mbvv9SvjYb0iHSLE0lvuCoug+Ygg+ZA77G582trA4l0gRoaIiIiIiIiIiIiVyBn8deAwQkHHAuC4fFDrY4kvWBiinfj95q2WRpm6TYL04h0jRoaIiIiIiIiIiIiVyBz17dAW2HbMJiYnG1tIOkVw+JT8LgDfPtoOMt3W5xIpPPU0BAREREREREREbkCmeVlANREG3jcAQyLT7E4kfQGm81GgDvBt4+Gue+AtYFEukANDRERERERERERkStQeyG7NgoC3AnY7SoVXimiHCm+GRrmwXprw4h0gf6WEhERERERERERuQI5a48AUBtlEOnQ7IwrSXJIGjXtDY0jJ8HjsTiRSOeooSEiIiIiIiIiInKl8Xi8hWy8DY2UkDSLA0lvyowZQm20979bmw3cR7XslPQPamiIiIiIiIiIiIhcYTwNB3E2e/+Ffm0UZP5/7d13nCR1tf//d1X35LSzOc3OJjYDC2xgSUoQWBVZRQkXJRiuVwFB1K9471W4cjGh94eBK+iVdDGhyKqgpJV4icuSNrBszjMbJ+ykDlW/P6q7urqnqmem2d3umXk9eSxTVX3q05/+dNep7jpd1UMn57lHOJKOG32UWsuk9mJJMhRd/Uq+uwT0CgUNAAAAAAAAYJCJrHlFsg11FknNFdLc0dPy3SUcQSfWTZct0z1LI7L2rfx2COglChoAAAAAAADAIBNd+6Yk5+wMW6YWTZie5x7hSBpaXikzXpv6YfCN6/LcI6B3KGgAAAAAAAAAg0xk43pJzu9nmPEhGlpemece4UirNMeoodaZjmzbkd/OAL1EQQMAAAAAAAAYZCLbtktyztCoNMfmuTfIh5Glde4ZGtHG/XnuDdA7FDQAAAAAAACAQSaya58kaddQQyNL6/LcG+TDpCGTUpec2teZ594AvUNBAwAAAAAAABhkIvs7JDmXnJpYMzG/nUFezB4x1b3kVLTNkN3cmN8OAb1AQQMAAAAAAAAYROyWvYq2Ot/Mb6iV5oycmuceIR8WjJuupgqps0iSbSiy5tV8dwnoEQUNAAAAAAAAYBCJrl0u2Ya6wlJTpbRg3Ix8dwl5MHtknWy7NHWWxtq38tshoBcoaAAAAAAAAACDSGTtG5KkxlrJsks1eyS/oTEYhUKmSqxRqd/R2LA2zz0CekZBAwAAAAAAABhEkgeuG2oNFVujFApxiHCwGlI8zj1DI7Jte347A/QC2QoAAAAAAAAYRKJbnQPXDbVSbfG4PPcG+TS+oj51hkbD/jz3BugZBQ0AAAAAAABgEIk07JPknKExrmJCnnuDfJo2dHLqDI19HfntDNALFDQAAAAAAACAQSSyt12Sc4bG9KFT8twb5NPc0Ue5Z2hEWyX74IE89wjIjoIGAAAAAAAAMEjY7c2KtjrTDbWG5o4+Kr8dQl4tmjBd+ysNRcKSbEPRd17Nd5eArChoAAAAAAAAAINEdO1y2ZahSEjaV+0c0MbgNbS8SoZVq4YhznzknTfy2R2gRxQ0AAAAAAAAgEEi+s7rkqTdQyTFh2poeVVe+4P8qzTHqjH5w+Ab1+a5N0B2FDQAAAAAAACAQSKywTlg3VBrqMIcm+feoBCMLK1zfxg8unVbfjsD9ICCBgAAAAAAADBIRBIHrBtqpZGl4/PcGxSCiTUTtWto4gyNXfvy3BsgOwoaAAAAAAAAwCAR2bVHknOGxqSaSXnuDQrBnBFT3TM0Invb89sZoAcUNAAAAAAAAIBBIpo4YN1QK80eMTXPvUEhWDB+hhqSv6HRasvuaM1zj4BgFDQAAAAAAACAQcDualOkxZbknKExf/z0PPcIhWD2yDrtqyhWNCTJMhRd+1q+uwQEoqABAAAAAAAADAKxda/LjhuKmdKeqmIdPXJCvruEAhAKmQobo9U4xJmPvrMir/0BsqGgAQAAAAAAAAwCkTXOgerdNVJYoxUKcWgQjtqi8WpMXnZqw9o89wYIRtYCAAAAAAAABoHI+jWSnMtN1RaNy3NvUEjGVUxI/TD4lq357QyQBQUNAAAAAAAAYBCIbtkiSWoYKo2rrM9zb1BIpg2dnPph8F178twbIBgFDQAAAAAAAGAQSB6obqg1NK12cp57g0Jy3Ohp7hka0b1t+e0MkAUFDQAAAAAAAGAQiOw9KElqqJXmjpmW596gkCyaMN09Q6OrxZYd6chzjwB/FDQAAAAAAACAAc6OdqmryZbknKGxqG56nnuEQjK0vEp7K2oVMyXFDcXWvZ7vLgG+KGgAAAAAAAAAA1xsw5tS3FDckPZW1GpYRVW+u4QCUxYep901znRkzYr8dgYIQEEDAAAAAAAAGOCia16TJO2pkUqLxua5NyhEI0vHp34YfP2aPPcG8EdBAwAAAAAAABjgIutXS3IuNzWytC7PvUEhmlQzSY3JHwbfsiW/nQECUNAAAAAAAAAABrjIls2SpMZaaWL1xLz2BYVp9oipqTM0du3Oc28AfxQ0AAAAAAAAgAEustM5QN1Qa2jOyKl57g0K0YLx09WQOEOja8/B/HYGCEBBAwAAAAAAABjguna3SpIaaqX542fkuTcoRHNGTlDDkCJJUqTZkh2L5LlHQHcUNAAAAAAAAIABzI5FFWm2JEm7hhTp6JET8twjFKJQyNSBqjGyDEkxQ7GNb+W7S0A3FDQAAAAAAACAASy+ZZUUNWRJOlA1WqEQhwThr7psvPbUONPR1cvz2xnAB9kLAAAAAAAAGMAiiQPTe2ukqrK6PPcGhWxcRb12JX8YfP2aPPcG6I6CBgAAAAAAADCARdavkuT8IPjYyvo89waFbFrtZDUmfhg8snlzXvsC+KGgAQAAAAAAAAxg0cSB6cZaaVrtpPx2BgVt7phpakieobGzMc+9AbqjoAEAAAAAAAAMYJEdDZKcMzSOGzM9z71BIVs0YboaEmdodOxuyW9nAB8UNAAAAAAAAIABrD1xYLqhVjqxjoIGgg0rr9Ke6ipJUrTZkh2P5blHQDoKGgAAAAAAAMBAZVmKNjkHpfdUVWp4RVWeO4RC11o7XpYkI2oovmV1vrsDpKGgAQAAAAAAAAxQ8e3vyIg4hwBbh9bluTfoD2or67Wv2pmOrF6e384AGShoAAAAAAAAAANUZNWrkqR9VVJ1VX2ee4P+YGL1pNQPg69blefeAOkoaAAAAAAAAAADVGTdSknSrlpDk6on5rcz6BfmjJzq/jB4dPOm/HYGyEBBAwAAAAAAABigIps2SpIaa6XZI47Kc2/QH8wfP8M9Q6NjR0OeewOko6ABAAAAAAAADFCdiQPSDbWGFtTNyHNv0B/MGVmnxiEhSVLb7uY89wZIR0EDAAAAAAAAGKAO7m6SJDUOMTVnJD8Kjp6FQyEdqHGuOWU1xWVbVp57BKRQ0AAAAAAAAAAGIttWvCkuSTpQM1ThUCjPHUJ/0T5ikiTJjBiKb383z70BUihoAAAAAAAAAANQfNcGhTqd30JoSxygBnpjZO1U7atypqOrX81vZwAPChoAAAAAAADAABRJHIg+UCENr52S596gPzmqdpIanKtOKfLuyvx2BvCgoAEAAAAAAAAMQNF335YkNdRK04ZOznNv0J/MHT1NDbXO2T2RzRvz3BsghYIGAAAAAAAAMABFNm2QJDXUGpo7elqee4P+ZNGEGW5Bo2Xbjjz3BkihoAEAAAAAAAAMQC1bt0uSGoYaWjRhRp57g/5keEWV9leXSJLa97TkuTdACgUNAAAAAAAAYABq290sSdpXXaLhFVV57g36m5baEc5EU0yy7fx2BkigoAEAAAAAAAAMNLYtuykmSWqpHZ7nzqA/io4+SpIU7jQUb9iU594ADgoaAAAAAAAAwAAT37NdRR2JH3VOHJgG+mL0yOk6UOFMR1a/mt/OAAkUNAAAAAAAAIABJrrqZUlSc7k0ahS/n4G+mzViqhpqnenI2rfz2xkgIZyvO452xRXtindbbphSuCiUFhfEMKRwcY6xkbgUdOk3QyrKMTYWiWe9pFxRSY6x0bhs69DEhotNGYZToY9HLVlWcCf6FFtkyjATsTFLVvzQxIaKTJm5xMYtWbEssWFDZsjsc6wVtxTPEmuGDYVyibVsxaPBT5wZMhQK9z3WtmzFDlWsaShUlIi1bcUihya2T9s9OcI/lhzR91hyhCRyBDmi77HkiEQsOaLvseSIRDA5IqdYcoQkckQuseSIFHJE32P7e45oW7NScbNYO4dKs4ZMTXudkiMc5IgUvxwxb9R0vVRbomk7bbVu2KTyxOMgRzj6e44otPcR2bYTr7wVNO76f0+prLii2/IJs4fpI1+a587/6qvLFIv4D+6YqUN0wdcWuvP3fuNpdbbFfGNHTKjSRf92kjv/m289r9YDnb6xtaMrdOl/nOLOP3DLizrQ0OYbW1Vbqsu/9z53/sFbX9aera2+saUVYX32v8505//84+Xatb7JNzZcbOhffnq2O/+3n7+urav2+cZK0tV3nuNOP/4/b2rjG3sCY//5x2equNR56v9x30qtfWVXYOynb32/yqtLJEnP/n6NVj23PTD2UzefopqRznP6wp/e1ZvLtgTGXvzNRRo+vlqS9OrD67X878HX4bvg6ws1ZvIQSdLrT2zSS0vXB8aef9081c0cJkla+fQ2PffAO4GxH/ziXE0+dpQk6Z0Xduip+1cHxp792WM0bf4YSdL6FY16/H/eCow9/ZOzNPvUOknS5pV79Lf/fiMw9tQLZ+jYM+slSTvW7tefb1seGHvikqmat3iKJKlxc7Me/P7LgbHzFk/SiUumSZL27WzV725+MTD22DPrdeqFzjc1Wva263+/+Xxg7OxTx+v0T86WJHW0RnTX154OjJ2+YIw+8JljJDkJ6RfXLguMnTx3hD74hePd+Tu/9GRgLDnCQY5IIUc4yBEOcoSDHJFCjnCQIxzkCAc5IoUc4SBHOMgRDnJESr/PEW8ukk5d5Nx4n3TnfanXPznCQY5wZM0RQ7+vp0+VdFDSl54kR3j0+xxRYO8jOiL+r+VMeStoRJrvlFlU1G35ztXTJKWSQ9vu/5bkv8E3vFMvKZUcWnbdIdvq8I1t7BojKZUc9m/7haxYs2/s3vbhklLJYe/G/1Esstc3NnqwRlIqOTSuu1vRDv+NLdJSJimVHBreuU9dB/03oC6FJaWSw87Vv1FX07u+sY5Ucti+6gF1Na0MjIx2nazi0kpJ0raVf1RX04rA2I7W41RePdKJfXupupqCd0St+6epZuQkJ/ath9XV9HRgbFNDnYaPnyVJ2vr2Y+pqeiwwdv+24Roz+QRJ0vaV/1BX058DY/dsukF1M53nbvuqZ9TV9EBgbMO6L2nysc4Y71zzorqa7guM3fXO5zVt/nmJ6eXqarozMHbnmsvc5NCw7k11Nf00MHb7qgt17JmXJfq+JnvsyvPd5LB/24assVvfPsdNDk0N27PGbnvr/VLiDUTr/t3ZY99eJCn5BqI5e+zK4yUl30B09jAOcySl3kBkiyVHOMgRKeSIRCw5QhI5IokckUKOSMSSIySRI5LIESnkiEQsOUISOSKJHJFCjkjEkiMkkSOSyBEp5IhE7CHKEZFoNHA9r4L7DY3K1vSNJWQFP5CKth1p8+FocBWnvL0xbb6kqykwtrRzb9b5bO1k3k+2/mX23yvzcWeOSzbVLcGVQ0kyY6kqb3Xzxqyx4cjBVGzThqyxxZ6xqGlelzW2tCNVja1p6iG2bWeqDweyx5Yd3OZOVzUFV0UlqbJ1a2q6Oftjq/SMaWUP4+tty3sffrx99Pbdj/exe8fEj3dMvWPtG+t5roqzbBdS+mvA+9rwjfW8tryvOd/YHsbUixzhIEd4YskRksgRSeQIBznCE0uOkESOSCJHOMgRGxmJ3gAAP5ZJREFUnlhyhCRyRBI5wkGO8MSSIySRI5LIEQ5yhCeWHCHp8OWIIHk7Q+OMVZtVGQp1W751Zm3a/KlrN6nYv9ip7ZMq0+bnb9qiyg7/U712jS1Nm5+zY6tqm/2vy7VneHHa/FGN2zVib8Q39kBN+mOYsH+7xuz0T5YHy4y0+VGtO3XCJv8kHMl4Zmo7G3TsmgO+sZkqort19tvBSSrm6XKxvUdnvx38oowUp65jZpp7dPbbwcmksyT1RNnh/Vlj28tSyS9W0pQ9tiIV21nWnD32sq5UbHlr1tiDF6Qq4+0VbVlj9y9uT61X0Z41dvf75rrTbRUdWWN3zT/K04eurLHb5ozzxEazxm6dMjQVW5Y9dss5Ze50Z0ksa+ym96Vew5FiK3vswjp3OhZS1tjNidPokrI+NnKEJHJEWiw5QhI5Iokc4SBHeGLJEZLIEUnkCAc5whNLjpBEjkgiRzjIEZ5YcoQkckQSOcJBjvDEkiMkHboccTBe4L+h8cWrTIXKup8gsmj8HH3IM3/tlyvUGfM/Jeu4UTO12DP/zWuHqqnLfwOaMXyq52Qo6QfXjFZDm/9pVpNqJugMz/zPr56gTQFVwdEVo3WaZ/6+q6bqnb3+1zUbUlIr75X4/vT5mXq98TXf2NJwmbxXDnz0s3P04vb/842VJO9VzJ799DH6j83B1wd8pjy1w3j1suP07ZOCq66PDU0l65X/NE/fPj640rd07Gh3+t2L5uumWWsCY387aYI7vfVj83XjpOBTyO6ZMcWd3v3h+frW6OBx+Pncme70vnNP0L/WPBEY+18L57jTrWccp68XLQ2MveXUY9zpzlOP0ZXR4JOb/v3U49zp6MI5uvLLwbFfWXSCO23NnZk19up5891pY8YUXZEl9jPHeWInTcja7j8dnYo1x47OGvuxGfP0kWTs0NqssYunHpeKLS/LGnv6xGN0nmc+Wyw5wkGOSCFHOMgRDnKEgxyRQo5wkCMc5AgHOSKFHOEgRzjIEQ5yREq/zhEzxiqc+JHkz19lqr00/YA1OcJBjnD0lCNuvz2u6k7pXz9las/YcnJEQr/OEQX4PiLeYUvXBq6aWs+2s/2+/aHX0tKimpoa7dq7S9XV1d1uD5khlYRK3Pn2aHu3mCTTMFUaLs0ptiPWoaCHbhiGysJlOcV2xjpl2ZZvrCSVF5XnFNsV71LcCq5S9SW2LFwmw3B2ZJF4RDEroJzcx9jScKlMw3kRRuNRRbOceteX2JJQiUJmqO+xVlTReHBscahYYTPc59iYFVMk7l/9lqSiUJGKzKI+x8atuLriXcGxZpGKQn2PtWxLnVlOsexLbNgMqzjkfBvAtm11BOy4+xrbl+2eHOEfS44gR5Aj+h5LjsgtlhzhIEf0PZYc4SBH5BZLjnCQI/oeS45IIUf0PbY/54i2Zx/S1n/+V7WWSg//6Gu64bSLA2PJEeQIKThH/H3tCoW/9DlN2ykNv+4CVXzmX8kRCf05RxTi+4iWlhaNGT5Gzc3NvnWDpLwVNHrqGAAAAAAAAIC+a/nVzdpx62+0boyk2+/VR2YtyHeX0E/tbWvVg5ct1GmrbJWdd4wm3vr7fHcJA1Rv6wYF96PgAAAAAAAAAHK3791VkqSGWkOLJszIc2/Qnw2vqNK+Ic4ZAPu3Zv8haeBIoKABAAAAAAAADCD7tzo/pry/JqQRlVwhBe/NwSFVkqTY3tY89wSgoAEAAAAAAAAMKLE9LZJSB6KB96JrxFhJUrgp+HcqgCOFggYAAAAAAAAwgISbnB8R7ho5Ls89wUBQNPFYSVJZmyHrQGOee4PBjoIGAAAAAAAAMEBYLftUdtCZDtcfnd/OYECYNPkEHSx1piOrX8lvZzDoUdAAAAAAAAAABojomldkyFB7iVQ/5YR8dwcDwPxx09VQ60y3r3k9v53BoEdBAwAAAAAAABgg2lavkCQ11EoLxs/Mc28wEBwzul67hxiSpJ3vvJXn3mCwo6ABAAAAAAAADBA71rwpSWocYuiY0fV57g0GgnAopOaaYklSy/Ydee4NBjsKGgAAAAAAAMAA0bJtuySpeUixwqFQnnuDgaK9tkaSZO1tzXNPMNhR0AAAAAAAAAAGCGufc8C5vbY6zz3BQBIfUydJKmmO57knGOwoaAAAAAAAAAADRElTTJIUH1WX555gIKmYOs/522rLaj2Q595gMKOgAQAAAAAAAAwAdnuLKlptSVL51BPy3BsMJNOnn6j2EsmQoejqV/LdHQxiFDQAAAAAAACAASCy5lWZtqHOImnazJPy3R0MICfWz1JDrTPd8OaL+e0MBjUKGgAAAAAAAMAA0PDGC87fWucANHCojKis1r4a51DyzrVv5bk3GMzC+brjSCSiSCTSbblhGCoqKkqLC3K4YiWpuLg4p9hoNCrbtgs6tqioSIZhSJJisZgsyzokseFwWKZpFkxsPB5XPB78Q0WhUEihUKhgYi3LUiwWC4w1TVPhcLhgYm3bVjQaPSSxhbDdkyNSyBEOcsR7iyVHkCP6GkuOeG+xhbDdkyPIERI5Iokc8d5iyRHkiL7GkiNSsTvXvqkhkvYOCWlIcWnga4gc4SiE7b4/5YiW2nLFQh1q37nzkLabRI5wDNb3ET29npPyVtD40Y9+pJKSkm7Lj5oyVZd+6pPu/K233hqYeOon1OvKT1/pzt/2/92m9o5239ixY8bonz//eXf+9ttvV3Nzs2/siOHDddXVV7vzv/zFL7Rn717f2JqaGn35y1925+++6y7t3LXLN7a8rFz/7+v/z52//3/v15atW3xji4qK9G//9m/u/AO/+73WbVjvGytJN910kzv90IN/0up31gTGfuMb33DH/q9/+avefOvNwNivfvWrqqyslCQ9+vdHtfy15YGx137pWtUOdc49W/bkMr34UvDpZ1/4ly9o1OhRkqTnnnlWzzz3bGDsZz/zWY2vGy9JeunFl/TksicDYy+/7HJNmjxJkrT81eX6+6N/D4y95OJLNH3GdEnSW2++qT//5S+BsR+/4OOac/QcSdKa1Wv0xwf/GBh7/kc+ouOOP16StH7dev32d78NjF187mItPHGhJGnL5i269757A2PPOvMsnXLqKZKknTt26n9+9T+Bse879TSdfuYZkqQ9u/fo53f8PDB20YmLdM6550iSmpua9eOf/Dgwdt4J8/Th8z4sSWpra9MPf/jDwNhjjzlWH/3YRyU5Cem73/1uYOysGTN14cUXufPf+c53AmPJEQ5yRAo5wkGOcJAjHOSIFHKEgxzhIEc4yBEp5AgHOcJBjnCQI1L6Y45o27FDQyTtG1OX9fVOjnCQIxy9zhETP6Sl42M65ZWl7iJyRP/KEYX8PqKrqytwPa+Cu+RUZOfBtHk7Elwpija0pc1bHcEV1+iejrT5eHNwxSe2vzPrfLZ2Mu8nW/8y+++V+bgzxyWbyPbWrLfb0VS1MLKlJWus1Z7qc0+x8ZbUiy6y2T/xurEHUmPatTl7uzHPmEZ6iI3sSo1TT/2N7vTGZh+zyLZW32nfWE9b0R6eN28fvX33jfU89liW15mUPqbesfZvN/VceZ9D31hPf72vjZ5iva8539geXrNpseQISeQIL3JE4nZyhBNLjpBEjvAiRyRuJ0c4seQISeQIL3JE4nZyhBNLjpBEjvDqjznC2Oe0XVFzVA+x5AiJHBHUv2w5wggVq6wp9djJEcl2+0eO8LsP/9j854ggeTtD45LOU1RlV3RbXjahNm3+k9b7A5NPyeia9DbN02S1+yeT4nGVafMXlpymeLN/sgyPKEub/1jFqYFPRqgm/SyTJTWnKLLD/0k2y0Np8x8eerK6AjYioyi91rR4xCJ1vHvANzbTB0adqJMDqrOS0k5jO33MfC1orA+MLS8rd6dPHXuCjts+NjC2pir1fJw0/jjN2TwyMHZ47TB3esH4YzR93ZDA2NHDUu0cP362Jq0qD4wdNXKcO33M+Jka/3pRYOzI0anHPXPcURr5cvApbyPGTnanp42drMs73x8YO2xc6k3DpNH1WWOHjp/qTteNHJc1tnb8JHd69LCRWWNrxk9wp4fXDssaWz0+NWY1VTVZYyvHjnGny8vKs8ZWzEg9b0VFRVljy6cMT5vPFkuOcJAjUsgRDnKEgxzhIEekkCMc5AgHOcJBjkghRzjIEQ5yhIMckdIfc8SqA87lW6qqhujytuBYckSiLXKEpL7lCDvWpY7W38juOCijrJIckdBfckRSIb6PaO1q0/cC10wx7GwXLjsMWlpaVFNTowN79qu6urp7hwwjbedpZal2GoZkFIUOeawkmcW5xdrRuLKNaO6xVtZrzPUl1igy3WvM2TFLtnWIYsOmDLOAYuOW7HiW2JApI5RLrC07HlzhN0KGjJDZ91jLlh3LEmsaMsIFFGvbWb/p0KfYPm335Aj/WHJEn2PJEYc3lhyRUyw5ooBiyRGHN5YckVMsOaKAYskRhzeWHJFTLDmigGLzlCMU6dDqBfMUsgwt//61unTx57K0S46QyBF9jX19+3qZH7tQpZ0Rjb/vJ6pa8AFyRD/KEYX+PqKlpUW1I4aqubnZt27gtpGvgkZPHQMAAAAAAADQO62vPaXtl35RXWEp9sifNa9+Wr67hAEmFo/ryffPUf0eqfNLH9NxX7wl313CANLbukHeLjmFlFg0oree/J1ad21V1ZgJOuasixUuKs53twAAAAAAANBPrF/+D5VK2j1EOmP8lHx3BwNQOBRS0xBT9Xss7V2/Kt/dwSBFQSPPnv/1D6Uf36PWsklqLylTe9fLeunGH0jXXqFTLv1qvrsHAAAAAACAfmD3upWaIKlpiKlwKNRjPJCLtiFlktoUadiV765gkMpbQaM9ElM4Euu23DQMlXquG9fuE3MoYjsicdnyv9qWIUNlxbnFdkbjsrJcxau8ODXkT//vrWq692VtnDRLttoltSfanKXJd7+k5/VDt6jRl3Z7ii0rCrnXmOuKxRXPcn23vsSWhkMyE9eCi8Qsxazg66X1JbYkHFLIJzYWjWj1Uw/o4K6tqhwzQbNOv1AVZWVubDRuKZrlWnDFIVPhxLXg+hIbi1uKZIktCpkqyiE2btnqigVf+zBsmioO9z3Wsmx1HqLYkGmoJOy83m3bVkf00MQeqe2+v+WIfMUOlBzRUyw5ghxBjsgtlhzhIEf0PZYc4SBH5BZLjnCQI/oeS45IIUf0Pba/5YjILucA88EhpeQIcsRhyxHR4UMltSm8v+2QtiuRI5IG6/uIbNtJWhu9ijoMTrvlEYVKuv/y+ynTRumXnz4lNX/zw4GJ54SJw3T/v7zfnT/re3/XgfaIb+zscUP0x2vOdOc/9KPHtau53Td2yogqPfyVs935T/x0mTbsafWNHVNTrn98Y7E7/8k7ntaqHU2+sbXlxXrhW+dJcg7G7/rtK9o5rLNbnK12bRgmdf7mZcUujChcVKxr/vdFPf9uo2+7krTmexe40//vd6/oiVU7A2Nf+4+PqLykSJL0zT+u0F/f2BoY+/y/fUjDqkolSd/9y5v6/SubAmMf/9o5qhtWKUn6r0dX6t7n1wXG/vm6szRtdI0k6efL1uiOp94JjP3dF96vY+uHSZLufe5d/ddjq3Tigcd0xWv/p/aKyWovKVO061W9ftOtarziIl149bec9V7aoO/89a3Adv/7shN1+qxxTn9e26xv/un1wNgfXbxAH5xb5zzOt3foK797JTD25o8dp48vmCxJem7tLn3xvpcCY//1vGP0qZOPkiS9smGPPv2r5wJjrz9ntj53+gxJ0spt+3Xxz58OjP2X02fo2nNmS5LW727R+bc9mXa7acc06+Arqo3s19QZ03X9l65XuKhYOw606exbHwts96IFk3TTx46XJO0/2KVTbnkkMPa8uRP0g4vnS5I6IjGdcONfAmM/MHusfvKpRe78Cd/6c2DsYMkRkvTZXz2n1zbv840tKwppxc1L3HlyRHqOCHLXZ07VoqNGOuuRIyT55wivy085Sjd8+BhJIkeQIySRI5LIEQ5yhIMckUKOcJAjHOQIBzkihRzhOFw54kf7DkqSYsOHkSPIEYctR5xr1+p92qaKJuexkyP6T44o9PcR8S7/132mvBU0lpdepeoSo9vyN/cskPSEO/+8+c8qL+3ybWPV/qMlPe/OP2J9UbWlLb6x65qPkrTcnf911zUaU7rHN3ZzW52kle78z9qu18TSbb6xu7pGSFrvzn+3+es6qtR/ozhgVUtyksMbj/1Gu6q6P36vnZWmHvvEEoWHVem8A1t0kVplGFEZZlymacswbZmmZBi2Xviv5QoVl8gsKta5b/xVn45tU8i0FTJshUwpbFgKmbaKTGnvazWqrB6mcEmpLlh7i/7TesZpx7RlJP7KkAxD2t+xWqpyNqDFO3+qm0r/FNzf1lekYdMlSe/ffoduKP11YOzmA8uk0fMkSQu2361rS38ZGPvuvr9I9e+TJB29/Tf6Zcvd2rthoV6bMjvjzJbZmrz0LT1f65zZMm37g1pT+t3Adt9suFOadbEkacKOR7Sm9N8DY1/beZs090pJ0qidT2pN6XWBsa/s+E9J10iShjY8pzWlnw+MfXn7NyTdIEmq3v2q1pR+OjD2pe3XSvq2JKls38qssS9u/5ykH0qSig+sS4t9fne19EqVWiumqL2kTOXv/p9e+v390rVXaPLJ52Vt9+WdH5N0tyTJ6NiXNfbVXedK+r0zE23PGrui8TRJf3Xns8XmM0fELOmt5grtWD9EK/5+g/t7N4cjR0jSN/b/u2aXvu0b226XSFrizl+95z/0y9LgnZaUegNxReN39JPSZwMj26NbpRJn5/2JXT/UD0ofDYwtxByxpvTHgbGrdv9GOupDkkSOCMgR3du9VNJ/S5JCrTvIEQn5fh8hkSPIEeSIJHKEgxyRQo5wkCMc5AgHOSJlIOeI51rGSpJK6qaQI8gRhy1HrDArJNVoSItkd7aTI/pRjij09xEthq2awDVTCu43NOaMTe92WXFIivrHzhyd/mvnQ8qKpA7/2CkjKtPmR9WUSs3+sROGlnef3+sfO6qmtPv9BFxCbkhZkTu98bXNiYPxwWy16Z0SUzrYKRWNkYzxkkKSEZIhU5IpwzKc6Vd3y7ANOf8drY06JjEvmbYhw7YT87bMH/5RpiTDsmVqpNZZH5dp2zIty/lrWzItS4Ydl174qgzDkiFbhuL6i3WaDMOSacckIyZDMZlGXIYZlVZ9WauKwlLYkNG5W8u6RsgwJSUKJckijGFKxgN3alf1n2QWFSvUsEErdlXLNG2FTFvhRBEmZFgKm7bKdr6rRhWpqLhMU0MxLdu8UNt7cWbLvPpaaU3w+Hpfa8fX10pvBsfOratJn86Sp4+vr/W9Dz/zPLEzxlRlj5041J3OfD1nWuCJnVCbej0/v7tae99dqI1TTN/LnNmdzRrby/7Wlmf/4XrvOJR5Tp30c+z4IVlv98pXjvAWgiIlZWr83h/c37s56TDkCLf/AV9G8J42KiXGZYN/bKZjxw+Rgr9gkPZ8HV9fKwV/aSDtdTCvvtZ3HJKFoJa/36WGibN1zFkXa/7EWqkhuF3v63bBxKGS//szSenP3byJQ7OOg3c7K/QcEbMk88AmPXPXf6pqzATNnjI+uFEdmhzhZ/7EVH9HV5dk70OB5Ag7Hlf78tcU27NHof0lsmu7nP1Rhv78PkIaODkiyfv6Ikd0vw8/R/p9hJ/+mCO8BupnDYkckUSOcJAjeocc4SBHpPSnHGFbUk3idTV69knkiARyRMb9HIIcMa3c0oawVByTtq94hhyR7EOB5wi3LZ/78FMIOSKIYdtZLlx2GLS0tKimpkbNe3aqurq6e4ARkoo8G1ykLbgxw5SKynKMbZcCrjEnGVJxeW6x0Q5nLxKkuEKS9MDN39e2lclTdQxVDpmkUFG54tF2HWzalOX+ClnI+WeY6lZ4kalEeSVRWDFlyLmeX3rhRc4/SaZlu4WXkG07RRnLUkNFk6QuBY2boTJNb4zLNGwZsiVZMmTJNiTTsCXDmTecO5VhWLJDkgxLMp2XoEw7MW1KoZDsUEhK/DNCpmSaUjgkwwzJCIWc6VBiuqhIZrhYRjgswzRlmoaMcFhmOCwjlPgbLlIoFJZZXCqzqERmOOzMm5IZLlI4XOTEJKbNcLFCxeUKl5YrFC5WyAzJMOLOfYZDUkY/FC6RUZRI1pYlxToUi0b0xwv/WTsqA/agksYdLNPHH/iFwkUBbw7MsBROtGvbUjRLUa4vsX3a7o98jnj+dz/R3vte08ZhZloh0lC5Ju+zNPyyeTrl4muCGs4pR/Q9tlOyg69R2KfYonLnFC1JinVJVpZrGPYQ+/zvfiL97NdqLZvknBHU1aGqjk3SNZfplIuuCm43XOZsZ5IUi0hWwLtESQqXSmao77HxqBT3P+VXkhQqkULhHGJjUtz/WzpObLEUKsoaGzhuV1+qUy7+kn+7ZpEUTmy7VlyKdS/8+sc6OeLQxOY/R7Qse1oN37tV8cbUKc+hkSM0+oavqfqsMzLa7b/vI/oe23OO6Opo15N3/4c6dm1W+ajxOvOyG1RS6vMG8xDmiDR92u4LJ0d0dbTrybtuVEfD1uBxO8Q5wje2T9t9YeSIrta9Wnbf99TeuL372A2g9xE+we8pR3R1HAwetwH2PiLNe8wRXZ3t/uM2AN9H+MbmmCN8x628ZsC+jziUOSJ97Op05me+rZKyxLY6AN9H9Dq2h+3eO25lYybqrCtvdMZtgL6P6Hus/3bf1dmux3/4JU194A3FTKnmH49pwoixA/p9RH/PEdljCz9HPHn6PI3bJ61aOETl80/WmZd93f+zQ7d2++f7iODYvuWIrq6uxGeuLSofNS74M9cAeR/Rc2z6dt/S0qKaEWPV3NzsXzdIyF9Bo4eODXTL//asnrn3B6oeNksHhteo3Uy94MutItXubVbLvtVadOFVmnPaCYpFo4p2RRXrijh/I1FFI1HFIhHFIjFFuyKKR6OKRaOKR6KKRWPOfCwqKxpTLBZVPBpTPBZVPOb5G4/KSvy14zFZiX+2FU//Z8cl20r8jUvKkgCPgJ7GrW+cQotTwTBT0zITPy5kyim9JP8aqb+2d16eZU6rTnHGcIs0bsHGthPztgxbMmW704Zty0wUcEzPtOGeRWPJsG2FbEtG4mwa004st1LzUlyGbSXuMC7FLb06eYxsu03BxaByzduxTnZliWSask3D96/zzzMdMp2dSMh0Erm7zHQLQEYoUXgxDacwZKaKQ8nCkPvPcG4zQmFnPrG+mZg3Q+HEsrDMxD8jFJJphmSEnOKQEQ7LNEMyQyGZoaJE0ajIKTIl58NFzvpmyF3H6Y+Z6KOpmBXXQ5d+XjuqOgLHbdzBMn186a+DC0GD1PO//qH23v2SNg4LqWLIKHfc2poaNXlfXMOvPFGnXPrVfHez4CTHbdOwkIaVDlVZqFId8YPa17lfkxi3rFoef1zbv3StLBnaNmqKWwyqa9wgU7bG/+THqj777J4bGoQevOUKjXroldTlCLs6VNW2QY0fXaAL/u2efHevYD14yxUa89DLqj2YWnagUtr10YWMWw8Yu9wwbrlh3HLDuOWOscsN45Ybxg1H2oO3XKGpv31ZxZ76Aa+5nj14yxUa+dCr2n/UWeqsrFLpwVYNXfekdn90PuOW0Nu6AQWNPOnq7NR9X7lZO4YnKl3en9NIPCPj9kZ14Vc+rtKyUufAsOkcXDcNwzmYaxiJf4kD8UbiMLphJA7MGxnLst2eZX3D27lEF21bVjzuFEOSBZJEQSXSmSq6xLoi3Yov8WhU0UjEKbBEEkWYmLM87m0vFpUVi8uKRRWPxxSPx3Rw3y5VVI3WjhHlweO2p10t+9bJME3ZtiXJciryeS7CFIoei0FGhQyjSPIWbrpNpxdvUrclbrW9kanCjpKFncQy5zY7VfCRpLT5VJEnFWf7FIJsGYlCj2ErUQSyPLdbbkHIULJIFHcuu5aM9RSFDNuWKac4ZNu2npsxVlVD6wPHrXXfFr1/1SoZpi078UBsw0hMG7LN1LxtGrINIxVjOtuYbUhK3GYntzvT24ZnmWl6bk8td/6abrxhmO5fpwCV2LZNTwEqcZvhtml64k13ueEWspzbjeRtyWKVZ5mz7dna9rfVapo8OXDcajZu1LRLT3XOaDINGUbI7YthGE6hK/FXpinTSO+PaYQS/TGcgpZ7u5k4O8qZNhN9MhPtm0aiSOZp3wyFEssT80bycSXzo9LGSMqcN5wc7XkODMNnvgexaER/PP+fpFETNHfYGWopttShLpWpRNURU2/s+4e0e6s+vvQ3FNAy2PG43jxpvjZXTfYtok3aF9fE1o2a+8KrznML14O3XKHQUwcDi4/x0yt5g+3jwVuu0Mz/fVlxw9TGuakPJZPeeFJh29KaT/GBLghjlxvGLTeMW24Yt9wxdrlh3HLDuL13XZ1d+r9fP66WA02qrh2iky89WyWl2S9/NZjxmsvNg7dcIWvDGG0aX6V2M3W2RblVrEnbW2VO2cW4iYJGwVv53MP62xNvqt2Iph+UT7KlUoV1XnytQoYtQ5acQ2jJ37Ow5XyjPnHQNjEtpS6z5F2euvSSZBpxN857u5G4NJO3HTNxm+0WA5w2bPd+JNtw5pRYLtmyDPdhdPubircT8YYs2c5BWEmGkeiZkTykLdlyDgiu3VOv5dUnZh23crtYx7W+rKmjGhPrp9qxZMi2E4/STk3HbUO2bcqyTcXskCzLmY7LlG2FEn8Nxe2QLFuybFOWbbh/bTvRnqW0tm1biWklppUxbbvztpLTtmxnQWJZ4l+iMONM24kzZpzRkW25y5R4/vxUD5vVi2JQX89wGfh6N24bJbMorQDkKdMkzvCRZz6jOCSlFYi8y1O3p0pLSmw7bmFISptOxkpyC0SyPVuELad4pMTW4Z5FZCfW8RaQnJVNT0FJnunUGUdWYh1Lti01Tp+oHSNKsoxbRBPfWqWwbaX6YnvbTBSp5GwwppyNxZSVMW8n1rcS/bcz/vZiue8zf+hZTh3QKVTJU+hKzFu2tG7e+Ro7+gS9VLRObWbq9M8Kq0QnRo/SzobXNPHNv0rFTpb3vHzcPOoWyQxJShXG3DglClye9ZL9Sa6TLLrJ7/ZkccYtwCWXdb89+c+9H7d9I30+WRDytpHZrpkqvhtu/5wtInzgoPbvrtCeacFFtBHvbtSw8VHFRgxx+2d4+md4+mwk9kNGxuNwuuKZT7bjxiUKYJljoOR9OfnANpVapkS8Z93kfRuG6WztiS81GGnjmyjoJZ6b5GMxPH0zjIyCmifGMEzFo1Gt/+3zau6h+Dj9yrMUTl7KMNl3ZY5H+vK0PrjjlFgnscztl+npnxI50zDcx+s9G9It4qa12b0/aY/Z0w9nLDP66X0e5BlLt+30+4pGI9ry6Su0be6SwA8ldW8u1eR7fq3i0tLUGHj64/bV27b3dZktxrPtp68r33bcx+WN8xZZ+zot7+Ie4jOWRTra9cbi92n7McFjN+6tpTrusedVUua59EK2fryHZf6P6tDfT+D996LYLUldHe167dQTtCPLuI19e6nmPfta6pI2YNxyxLjlrj+NXU6HgqwsXxIMai/b5W0S63R1tmvFGSdlHbdxby/V8U88nxq3zPvzvf8eHmOvxiA9ptu49aaNbGMQ1E63drvfT1dnh17/0Dn94vVWqB6+7bdavX9Tt7GbNXSSPnzdJXnsWWHqTY4b99ZSzfzTX1XsvYyS57OBmfW9U/fbzORnjYDbvYvNxPt8/7bTl5kyg2/3Lg/8cqLh+X+AxGeKro52Lf3K9/XOuODjIzN2dOmjP/3moN9WKWgUuGW/+IWe27kz3904JJyDnWmHGjKm/Zel35pYZmcuU1pcVHEdNLNc3y2h1ipVqUKp/hnethJ/bVvJA8PJ27w5JbXMTq3j/rUz2rPTptPXT8V7D5yabpzt20byILJh2N3u00hbN3VQOhWX2KwTB51tSS3RCr1daiqiuH/GtaUShTWrLabqcIf7/ilRMpGRvAc7ca6Lbad6Yif/JuKT69qeR56Mtz0FrrQ42ykCKRVgJRq1E+sbyf4kijpuPSfRkJ04kJ4srCkZJ1u25Rzwtt32kmfuJAtByfXkrivbliVDTZOnqqOHIlrlhlWecU+1lGrV9oyDz/LerOuOTcC6BcVQfHrPxcfQ2hfV4weNXt5f96088c8wMm73HhBMPwspfV15blPaX8N3Xt2KUhm3pqbt7q1KhmKKafbE0/Rc6YbMG91hOqVzitZufl7FcTMVkswXdvpqhmc9Q0oVrDwNes+Wcntip25z80ryPtz+J6c9ucstGHnzbOp1a7ptpBfFUv2zUn1OrGvYGfHJApadvq5sW+uOm6sdI7Kc+bgnqtmvvOycjZXWVuqxuX3wFMC8jy19OrWuPI8leN30+d4dxjy8LBl64YyP9jhuJ/3jIXe/BcfKk5ZoVV3wh5LZ27o054WlR7pb/QJj13eWpNW9GLdZLyzN+sk6p604x2SVy33ZhzgxGrb0zok9j9uMl5Ye8vvuzw7HuBnvYRfynp+a97j76tP9233YVgOYgbcMbOwbctObcSufZ+lDX/z+Ee9boXv4tt9q+YG1zozP2M2rnU5RI8Mj//11tS832Vb7KG6Y+tsnLlW7Ecl6fGTG8CZ95Es/OOL9KyS9rRuEj2Cf4BE3KnoOklSmYpWEiz0HaZMHfr1z3gO63hjP7fK5PW1J7mwjveX35BB9kDhgZvnxmX7Fp7qcq7AtKcsPLxlSl2J6vVKSfL4ROahl+VEnQ2o3ImqfelTip+4zD2BnLul+ODz77QGHzu3sbae338NyWz63Zbabztns/duUpIgRV6uZ7UfPnHEbftRpKrFTu6LUweFki7aS5TRnmfc253bDzlzuPWifwfex+nTPPTCdbNu/LSNzQZbZtAPYvk3aCplFerl0s38HE115pXSLJtfNUMyKBPct805sn2VZlnsLmum3ZYxLULuZDQXNy9l7GJ65ZJjhadO7lmFn7LfsVC/3Di+TFAscu33Dy7Vu/jynsGJ3f3TeXmXrtqHkXs+z/SS/tdPtNRxcuvBufz3vjVOvRTvxmjfcaTkbT7KgZni6kfGoUsUn52/cjmr/8HJJPsXHxF3uH16uFxculmkUpR2QMty++/F77g23n8nmk7d129I8r63M29wzRD3d7PaA7czOpYpxqfXS+2i477W8XzBQ2nOUzA22Le0aXyXJ50NJosObxlcpMuP9MpV6ftNzQOqLCMn+JB9G2mNyc02ib3YyQ9vu43G/6OApqiUfk/tY7VTbqcJ/8p1GarwMz/14BjTt+UqNn+G5X+9j9PY7fazjibHpaeyqR8xQKHmGcMZ4pa2WsYGmFXLT+pr+eLx/UsW67q+htKKxz/162zYy2vV+0cFtq9t8923FfU48N8Vl9GrcJpYMVUiWzMDvrAXnGiNtnd7tXzJfJ725LyOwb37P1XvrW9wwezVu0xVWKNs3zwP7kovs6xdCXaW34zbTNhXu5bgNFr0duxlGSKGAb+1bWc/cMjL+Jme7l0FSb9U96/TYtpGalNyrJvRunYC4RN/cV35amDMTV6hX4za5Yqyzb/A8tvQzllP9cR+/YaZncMNzRQjDe3eJ62IkmshcJ3V/TtveM0HdrG54v2aYXJZYL/P58JyNmWQZmeOZfCwZ7ysTs5ZMbRhfqWzv4zaOr1Tdhja9vvTFxJcEnf2L++VB73tR20q9V3LfKiTeb3iPOdnOvXt3c7anLe83F93105Ynb/bcnvZeztOvtHXstGXeL/yl9dvbF2XcnrjNjsf1dovPl8g8Y/f2gQ2yfvBrmabprpv+ViH1/ie9/+l98T709L54ByP1ftHb17RHYfvFp79TthPv4Wx52ktvJdFW5nrp/UtfI7Wsq3O4dtV1Sn5flE00+W5duQ5+6Er3+IjbS58UkXZX7uvcWcM/Z6Ta675+ar7bZwtvfECqCtw7G8G3d+9jRt8T8xEzrnYzyw/eG87xkeatpcExSMMZGnnyznNv6nfLHuox7uIzP6oZpx572PvjXtbI/aBud/vntzzbMstK7AwtS7aVvN1y9pF2clnm7c6ezLacf5a7jtPutnc269k1L/X4eE6ccrzG1I/1XNIp2TfbvS/ZmY87Fete2sm7bvLb/lb643amLffL/pYnVmnrJ3fy3stGKXVfbptK9CW9T+lvJOxUkcvTbmo6ufNKnsVgq6nlgPbbWQ4wJ1QbZaosq5L3zYJ3x+/uFjOKau59J27z3OJpI/1Nh2f3n7YDTxXcvPfjXZ56U9DD+QxKjwAAFCxPsjZ8poKWGEGfSgLayX5YxsiY94+yZClqZPmSQEKxHVbI57u2vbmX7Ldkf9z+Y9l9SW8PnGa9L9+Wg261FVU87XJ6QSqtUhWpb7930/cDwf4fd41D9FX9zFbsgOW9aSeiuJpDWT4IJ9TEy1Tcx3E7XArh/Ve0D+PW19dbX/T2ue/9mPUc+V7GP6a4WkI9f0GsKp7aTvvcI6Pvfewen72FXMbgvd5HTHF1mlm+DJVQahWl7x+yjoffQUfvrX0d/d4/yp7aDmq3px5ltmvL7t3ZPt4jmQAwwEzprNCnvve1fHcjrzhDo8AdtWiOyp98RO1+30CQJFuqUImOWjTniPTHCLwmXGGZPPsoLb95RY/j9oFLPqRQuDA+zBWK3hbRPnjGuUekiJYPmUW3bMuSf999YaX+9OzDPbb9kZPP1ZQFMwPb6XafycKYlSw8eQpWtlPMS79dqeKO5emzlSwiWd1jEoUiy1PskpUqTCWLabKTlxHLaMNzu2Q73+JJK9A56ySaSsQ4N+zasl2vbV3Z47jNHTtTI8ePTrSrtMJWsh9p4+cW/eSJSS/mpQpkPo8ltVr6uLv3qbT23Ha6tZ3+nPrff0Cb3vW8fZGtAy3NaujY2+O4jSwZqprKKv+xSGs32XZqge3+Txnxdvoy97Gnz3QrFWbEdb/fjPlucf79SLstdVf+/7elrliXOrOdTZVQorCKQkXuekEtp/oTdEv3D+OZ/febyn5v/u0Grz3AePbrQWPX2yWFImLE8nPHhf+WrkcHB8zZtkdWbw7eozvGLTetvSh6wF9vih7wMQD2b90k3sYEfQEh6CEbSvx6Zi+u5xayPb8X0O0e0vsS9CWGbEv9buv+5Q3bP76Hx9+79nvuT/K+EifMKGpYavP8/kOQynixiu3gY0t9Gy9PvO0fmPqify++gGLIc7WC7tE+J0M5k7bfQr+109s1JHUoqn3h9qAeuYZHK1RuFHXvk+fhZz5bhmc2eY2Gbo/D00i311jGYzACH5/nPGPDJ1bKOD7q+RVTt/GAK2UkGjUyBr+1rVVbwwcyH0k3oydP7TEGDgoaeRIKh3T2SWdq6Qt/927JjsRW+4GTzuCgfAbGLXeFVkTLh1wKd7NPO06PPvN4j+N27Onzed15xGNxrbn53azjVq5inffpjzNuHps2btK9993bY9zii87TpMmTjkCP+o81z72p3/eiaLvkzPM0cwAXbb1/M6f9blv7wtv641N/6bHtC953nqadNCdre+91WX9oKzn98oNP6bXGNd3WzXT8qJlacP5paZ8HvcVAb8HPe5tPt9yib+bK3WK7FUyDbutNnO3Tl8wiY8Y6PgVIb+Bb/3hVb+5fl9loN8fUTtWc0+d1u2vfwQlenNnLbIGJmwPat3yKrZ72uhVI3SHMLAJnjpM33vbprvNcv/vqaq1u3ZK175I0s7JeR50wM7P3mY0Grp9+U5btqttkD7F2wG3d+paatAJCnHHy20i6T25etUHvdu7oHpthWulYTZg52Z030i4j2Fu9DDbk6X8P70v9mszlgG5A1/wPgUlb1mzUu109/97j9JKxqp81pVsjbluZ77u7H5Xq8eEYGZfl8TtAlbY86C7dCdPnRp91snxm8F5qKLOZ9SvWaFXb1sB1k+ZU1GvagtmpdjIfn6H0A2ae272/jWuYZnqA0sc//QpG3oOKRtpjzJw3kwcHDWXEJT5TpQ1+qv/Oaoa72H0MiY64fTDTY1/76//ptb1rfcfKa/7ImVp4wfskGTLNZHvp9+d9rIbnUlzeA5GSZHov05X4nJh6qIanjcRfM/l8e8YjMf6ZnzGD5g/1l0j/8au/6tltr/UYd/KE43XGZ847pPfd3/V27I6feDRj59HbcZs1eQbj5tHV2aUff+dHPf6GxmmXffCI962/oqCRR3PPWShJeuLFp9Sm1LdbKoxSfWDR6e7tSMe45YZiUG4Yt9z0ZtzOPulMxi1D/cR6VZVVqrX9YOAbnaryStVPrD/ifSt00xbNUfmTf1O7urIU0Uo0bYAXbb1/e2Pmyceq/B+P9Thus06dy/bqcfaVS7TmOxt6/FByzpVLVFJacsT7V8jGT63Xul58oPvQ5z/B2HnMXDBXm3sxbkuu/ifGzeOED5zcqwMIF1x3OePmMe/c3h14+diXGbdMs04+Xpt6MXbnXcO26jXss6O0phfjdtan2a96nXzp2Vr+nbd7HLeTLz37iPet0DF2uWHcclNSWqJZQyc5P0IfcHxk1tBJ5Lc+6H7OWS/cfvvtmjhxokpLS7Vw4UK98sorh7pfg8bccxbq+n//mi75wAX68LwP6JIPXKDr//1rHJTvAeOWm7nnLNSSkxarwkj/oaEKo1RLTlrM+AVg3HKTGrf0nTLjFsw0TS0+74PB3740pMXnfVCmmdPue0BzimhnODPdvm3u/Dmb4mM3jFtukh9KJAWOGx9K/DF2uWHccsO45YZxyx1jlxvGLTeMW+4Yu9wwbrn78HWXaF7tdJXbxWnLy+1izaudrg9fd0meetY/9flHwX//+9/rsssu0x133KGFCxfqtttu0x/+8AetXbtWI0eO7HF9fhQcyL94LK71L69W64EWVdVWa+rCWRys6gXGLTeMW9+tXr1ajz76qFpaWtxl1dXVOvfcczVr1qw89qzwvfHYy93P4BNn8PWEccvNw7f9Vqv3b1K75xrM5VaxZg2dxIeSHjB2uWHccsO45YZxyx1jlxvGLTeMW+4Yu9wwbrnr6uzS//36cbUcaFJ17RCdfOnZFIA8els36HNBY+HChZo/f75+9rOfSZIsy1JdXZ2uueYa3XDDDYesYwAADGaWZWnLli06ePCgKisrVV9fz5kZvUQRLTeMW274UJI7xi43jFtuGLfcMG65Y+xyw7jlhnHLHWOXG8YNh8NhKWhEIhGVl5frj3/8o5YsWeIuv/zyy9XU1KQ///nPh6xjAAAAAAAAAABg4Ott3aBPPwq+d+9exeNxjRo1Km35qFGj9M477/iu09XVpa6urrSOAQAAAAAAAAAA9MVhv3bFd7/7XdXU1Lj/6urqDvddAgAAAAAAAACAAaZPBY3hw4crFAqpsbExbXljY6NGjx7tu843vvENNTc3u/+2bduWe28BAAAAAAAAAMCg1KeCRnFxsU444QQtW7bMXWZZlpYtW6ZFixb5rlNSUqLq6uq0fwAAAAAAAAAAAH3Rp9/QkKTrr79el19+uebNm6cFCxbotttuU1tbm6688srD0T8AAAAAAAAAAIC+FzQuuugi7dmzR9/61rfU0NCguXPn6tFHH+32Q+EAAAAAAAAAAACHimHbtn0k77ClpUU1NTVqbm7m8lMAAAAAAAAAAAxyva0b9Ok3NAAAAAAAAAAAAPKBggYAAAAAAAAAACh4FDQAAAAAAAAAAEDBo6ABAAAAAAAAAAAKHgUNAAAAAAAAAABQ8ChoAAAAAAAAAACAgkdBAwAAAAAAAAAAFDwKGgAAAAAAAAAAoOBR0AAAAAAAAAAAAAWPggYAAAAAAAAAACh4FDQAAAAAAAAAAEDBo6ABAAAAAAAAAAAKHgUNAAAAAAAAAABQ8MJH+g5t25YktbS0HOm7BgAAAAAAAAAABSZZL0jWD4Ic8YJGa2urJKmuru5I3zUAAAAAAAAAAChQra2tqqmpCbzdsHsqeRxilmVp586dqqqqkmEYR/KuC1pLS4vq6uq0bds2VVdX57s7QF6xPQAOtgUghe0BSGF7AFLYHgAH2wKQwvbQP9m2rdbWVo0dO1amGfxLGUf8DA3TNDV+/Pgjfbf9RnV1NRsakMD2ADjYFoAUtgcghe0BSGF7ABxsC0AK20P/k+3MjCR+FBwAAAAAAAAAABQ8ChoAAAAAAAAAAKDgUdAoECUlJbrxxhtVUlKS764Aecf2ADjYFoAUtgcghe0BSGF7ABxsC0AK28PAdsR/FBwAAAAAAAAAAKCvOEMDAAAAAAAAAAAUPAoaAAAAAAAAAACg4FHQAAAAAAAAAAAABY+CBgAAAAAAAAAAKHgUNI6g22+/XRMnTlRpaakWLlyoV155JWv8H/7wB82YMUOlpaU6+uij9be//e0I9RQ4fL773e9q/vz5qqqq0siRI7VkyRKtXbs26zr33HOPDMNI+1daWnqEegwcPjfddFO31/aMGTOyrsO+AQPRxIkTu20LhmHoqquu8o1nv4CB5Nlnn9V5552nsWPHyjAMLV26NO1227b1rW99S2PGjFFZWZnOOussrVu3rsd2+/rZAygE2baHaDSqr3/96zr66KNVUVGhsWPH6rLLLtPOnTuztpnL+y0g33raN1xxxRXdXtfnnntuj+2yb0B/1NP24Pc5wjAM3XrrrYFtsm/o3yhoHCG///3vdf311+vGG2/UihUrdOyxx+qcc87R7t27feNfeOEFXXLJJfrMZz6j119/XUuWLNGSJUu0cuXKI9xz4NB65plndNVVV+mll17SE088oWg0qrPPPlttbW1Z16uurtauXbvcf1u2bDlCPQYOr9mzZ6e9tp9//vnAWPYNGKheffXVtO3giSeekCR94hOfCFyH/QIGira2Nh177LG6/fbbfW//wQ9+oJ/85Ce644479PLLL6uiokLnnHOOOjs7A9vs62cPoFBk2x7a29u1YsUKffOb39SKFSv0pz/9SWvXrtVHPvKRHtvty/stoBD0tG+QpHPPPTftdf3b3/42a5vsG9Bf9bQ9eLeDXbt26a677pJhGLrggguytsu+of8ybNu2892JwWDhwoWaP3++fvazn0mSLMtSXV2drrnmGt1www3d4i+66CK1tbXp4YcfdpedeOKJmjt3ru64444j1m/gcNuzZ49GjhypZ555RqeddppvzD333KPrrrtOTU1NR7ZzwGF20003aenSpXrjjTd6Fc++AYPFddddp4cffljr1q2TYRjdbme/gIHKMAw99NBDWrJkiSTn7IyxY8fqK1/5ir761a9KkpqbmzVq1Cjdc889uvjii33b6etnD6AQZW4Pfl599VUtWLBAW7Zs0YQJE3xj+vp+Cyg0ftvCFVdcoaampm7fVM+GfQMGgt7sG5YsWaLW1lYtW7YsMIZ9Q//GGRpHQCQS0WuvvaazzjrLXWaaps466yy9+OKLvuu8+OKLafGSdM455wTGA/1Vc3OzJGno0KFZ4w4ePKj6+nrV1dXp/PPP16pVq45E94DDbt26dRo7dqwmT56sSy+9VFu3bg2MZd+AwSASiej+++/Xpz/9ad9iRhL7BQwGmzZtUkNDQ1rur6mp0cKFCwNzfy6fPYD+qrm5WYZhaMiQIVnj+vJ+C+gvnn76aY0cOVLTp0/XF77wBe3bty8wln0DBovGxkY98sgj+sxnPtNjLPuG/ouCxhGwd+9exeNxjRo1Km35qFGj1NDQ4LtOQ0NDn+KB/siyLF133XU6+eSTNWfOnMC46dOn66677tKf//xn3X///bIsSyeddJK2b99+BHsLHHoLFy7UPffco0cffVQ///nPtWnTJp166qlqbW31jWffgMFg6dKlampq0hVXXBEYw34Bg0Uyv/cl9+fy2QPojzo7O/X1r39dl1xyiaqrqwPj+vp+C+gPzj33XN13331atmyZvv/97+uZZ57R4sWLFY/HfePZN2CwuPfee1VVVaWPfexjWePYN/Rv4Xx3AMDgddVVV2nlypU9Xqdw0aJFWrRokTt/0kknaebMmbrzzjt18803H+5uAofN4sWL3eljjjlGCxcuVH19vR544IFefaMEGIh+9atfafHixRo7dmxgDPsFABjcotGoLrzwQtm2rZ///OdZY3m/hYHIe8nBo48+Wsccc4ymTJmip59+WmeeeWYeewbk11133aVLL71UpaWlWePYN/RvnKFxBAwfPlyhUEiNjY1pyxsbGzV69GjfdUaPHt2neKC/ufrqq/Xwww/rqaee0vjx4/u0blFRkY477jitX7/+MPUOyI8hQ4Zo2rRpga9t9g0Y6LZs2aInn3xSn/3sZ/u0HvsFDFTJ/N6X3J/LZw+gP0kWM7Zs2aInnngi69kZfnp6vwX0R5MnT9bw4cMDX9fsGzAYPPfcc1q7dm2fP0tI7Bv6GwoaR0BxcbFOOOGEtB+jsSxLy5YtS/t2odeiRYu6/XjNE088ERgP9Be2bevqq6/WQw89pH/84x+aNGlSn9uIx+N6++23NWbMmMPQQyB/Dh48qA0bNgS+ttk3YKC7++67NXLkSH3oQx/q03rsFzBQTZo0SaNHj07L/S0tLXr55ZcDc38unz2A/iJZzFi3bp2efPJJDRs2rM9t9PR+C+iPtm/frn379gW+rtk3YDD41a9+pRNOOEHHHntsn9dl39C/UNA4Qq6//nr98pe/1L333qs1a9boC1/4gtra2nTllVdKki677DJ94xvfcOOvvfZaPfroo/rRj36kd955RzfddJOWL1+uq6++Ol8PATgkrrrqKt1///36zW9+o6qqKjU0NKihoUEdHR1uTOb28O1vf1uPP/64Nm7cqBUrVuiTn/yktmzZklPVHSgkX/3qV/XMM89o8+bNeuGFF/TRj35UoVBIl1xyiST2DRhcLMvS3Xffrcsvv1zhcPpVUdkvYCA7ePCg3njjDb3xxhuSnB8Cf+ONN7R161YZhqHrrrtO//mf/6m//OUvevvtt3XZZZdp7NixWrJkidvGmWeeqZ/97GfufE+fPYBClW17iEaj+vjHP67ly5fr17/+teLxuPtZIhKJuG1kbg89vd8CClG2beHgwYP62te+ppdeekmbN2/WsmXLdP7552vq1Kk655xz3DbYN2CgyLY9JLW0tOgPf/hD4OcB9g0DjI0j5qc//ak9YcIEu7i42F6wYIH90ksvube9733vsy+//PK0+AceeMCeNm2aXVxcbM+ePdt+5JFHjnCPgUNPku+/u+++243J3B6uu+46d9sZNWqU/cEPftBesWLFke88cIhddNFF9pgxY+zi4mJ73Lhx9kUXXWSvX7/evZ19AwaTxx57zJZkr127tttt7BcwkD311FO+742Sr3nLsuxvfvOb9qhRo+ySkhL7zDPP7Lad1NfX2zfeeGPasmyfPYBClW172LRpU+BniaeeesptI3N76On9FlCIsm0L7e3t9tlnn22PGDHCLioqsuvr6+3Pfe5zdkNDQ1ob7BswUPT0Xsm2bfvOO++0y8rK7KamJt822DcMLIZt2/Zhr5oAAAAAAAAAAAC8B1xyCgAAAAAAAAAAFDwKGgAAAAAAAAAAoOBR0AAAAAAAAAAAAAWPggYAAAAAAAAAACh4FDQAAAAAAAAAAEDBo6ABAAAAAAAAAAAKHgUNAAAAAAAAAABQ8ChoAAAAAAAAAACAgkdBAwAAAAAAAAAAFDwKGgAAAAAAAAAAoOBR0AAAAAAAAAAAAAWPggYAAAAAAAAAACh4/z9EMHshppwEnAAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "import matplotlib\n", "import matplotlib.pyplot as plt\n", @@ -439,9 +644,24 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 23, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "path 0: 🦘 [16]\n", + "path 1: 🦘 [16]\n", + "path 2: 🦘 [16]\n", + "path 3: 🦘 [16]\n", + "path 4: ✅ []\n", + "path 5: ✅ []\n", + "path 6: ✅ []\n", + "path 7: ✅ []\n" + ] + } + ], "source": [ "from airo_drake import joint_path_has_large_jumps\n", "\n", @@ -459,9 +679,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 24, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" + ] + } + ], "source": [ "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", "\n", @@ -471,9 +702,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 25, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n" + ] + } + ], "source": [ "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -485,9 +724,19 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 26, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" + ] + } + ], "source": [ "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -499,9 +748,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 27, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[1.0821133056402081, 1.0821133056402081, 0.9808441751547153]\n" + ] + } + ], "source": [ "from airo_drake import time_parametrize_toppra\n", "\n", @@ -514,7 +771,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 28, "metadata": {}, "outputs": [], "source": [ @@ -526,7 +783,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 29, "metadata": {}, "outputs": [], "source": [ @@ -544,7 +801,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 30, "metadata": {}, "outputs": [], "source": [ @@ -561,7 +818,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 31, "metadata": {}, "outputs": [], "source": [ @@ -581,7 +838,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 32, "metadata": {}, "outputs": [], "source": [ @@ -594,9 +851,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 33, "metadata": {}, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "(array([0.35, 0. , 0.35]), array([0.34550067, 0. , 0.34993251]))" + ] + }, + "execution_count": 33, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "import numpy as np\n", "from airo_typing import Vector3DType\n", @@ -626,7 +894,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 34, "metadata": {}, "outputs": [], "source": [ @@ -645,7 +913,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 35, "metadata": {}, "outputs": [], "source": [ @@ -668,9 +936,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 36, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥\n", + "✅✅✅✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" + ] + } + ], "source": [ "path_joints_solutions = []\n", "\n", @@ -687,7 +968,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 37, "metadata": {}, "outputs": [], "source": [ @@ -698,9 +979,20 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 38, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", + "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" + ] + } + ], "source": [ "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -710,9 +1002,17 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 39, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[1.6488317327683064, 1.5839720500574017, 1.583972050057404, 1.648831732768306]\n" + ] + } + ], "source": [ "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path, joint_acceleration_limit=1.0) for path in paths_without_collisions]\n", "durations = [trajectory.end_time() for trajectory in trajectories]\n", @@ -722,7 +1022,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 40, "metadata": {}, "outputs": [], "source": [ @@ -741,7 +1041,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 41, "metadata": {}, "outputs": [], "source": [ @@ -761,17 +1061,41 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 48, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" + ] + }, + { + "data": { + "text/plain": [ + "False" + ] + }, + "execution_count": 48, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "joints_table_collision = np.deg2rad([0, 45, 0, 0, 0, 0])\n", + "print_robot_collisions()\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 49, "metadata": {}, "outputs": [], "source": [ @@ -781,7 +1105,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 50, "metadata": {}, "outputs": [], "source": [ @@ -798,10 +1122,34 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 51, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" + ] + }, + { + "data": { + "text/plain": [ + "False" + ] + }, + "execution_count": 51, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ + "print_robot_collisions()\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, @@ -814,7 +1162,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 52, "metadata": {}, "outputs": [], "source": [ @@ -825,22 +1173,37 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 53, "metadata": {}, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", + "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" + ] + }, + { + "data": { + "text/plain": [ + "False" + ] + }, + "execution_count": 53, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ + "print_robot_collisions()\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Caveat\n", - "\n", - "The above collision filtering only operates on the collision checker. It will be out of sync with the plant context." - ] - }, { "cell_type": "code", "execution_count": null, From c8a33dfd972b3b627335c916296c212be3bc3737 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 2 Apr 2024 11:18:11 +0200 Subject: [PATCH 4/7] Add collision filtering and checking functions to airo-drake and call these from the notebook --- airo_drake/__init__.py | 6 + airo_drake/collision/__init__.py | 0 airo_drake/collision/collision_checking.py | 54 ++ notebooks/03_collision_checking.ipynb | 557 ++++----------------- 4 files changed, 152 insertions(+), 465 deletions(-) create mode 100644 airo_drake/collision/__init__.py create mode 100644 airo_drake/collision/collision_checking.py diff --git a/airo_drake/__init__.py b/airo_drake/__init__.py index 2da7d14..256ac9c 100644 --- a/airo_drake/__init__.py +++ b/airo_drake/__init__.py @@ -38,6 +38,10 @@ animate_joint_configurations, animate_joint_trajectory, ) +from airo_drake.collision.collision_checking import ( + filter_collisions_between_all_body_pairs, + list_collisions_between_bodies, +) __all__ = [ @@ -69,4 +73,6 @@ "calculate_path_ik_solutions", "calculate_joint_paths", "calculate_valid_joint_paths", + "filter_collisions_between_all_body_pairs", + "list_collisions_between_bodies", ] diff --git a/airo_drake/collision/__init__.py b/airo_drake/collision/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/airo_drake/collision/collision_checking.py b/airo_drake/collision/collision_checking.py new file mode 100644 index 0000000..cccdee4 --- /dev/null +++ b/airo_drake/collision/collision_checking.py @@ -0,0 +1,54 @@ +import itertools +from typing import List, Tuple + +from airo_typing import JointConfigurationType +from pydrake.all import BodyIndex +from pydrake.planning import RobotCollisionType, SceneGraphCollisionChecker + + +def filter_collisions_between_all_body_pairs( + collision_checker: SceneGraphCollisionChecker, + body_indices_one: List[BodyIndex], + body_indices_two: List[BodyIndex], + *, + filtered: bool +) -> None: + """Enable or disable collision filtering between all pairs of the bodies listed in body_indices_one and body_indices_two. + When collision filtering is enabled for two bodies, they are allowed to collide. + + Args: + collision_checker: The collision checker instance to alter. + body_indices_one: A list of body indices. + body_indices_two: A list of body indices. + filtered: Whether or not to filter collisions between these bodies.""" + + body_combinations = itertools.product(body_indices_one, body_indices_two) + for body_index_arm, body_index_floor in body_combinations: + collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, filtered) + + +def list_collisions_between_bodies( + collision_checker: SceneGraphCollisionChecker, q: JointConfigurationType +) -> List[Tuple[BodyIndex, BodyIndex, bool]]: + """List all collisions between bodies for a joint configuration. + The return type of this function is a list that contains all colliding bodies (if any) and a boolean value that indicates whether the collision is a self-collision. + When the boolean value is false, the collision is an environment collision. + + Args: + collision_checker: The collision checker instance to use. + q: The joint configuration of the robot to check. + + Returns: + A list of tuples of colliding body indices and a boolean value that is True when the collision is a self collision.""" + robot_clearance = collision_checker.CalcRobotClearance(q, 1.0) + indices_one = robot_clearance.robot_indices() + indices_two = robot_clearance.other_indices() + collision_types = robot_clearance.collision_types() + distances = robot_clearance.distances() + + return list( + map( + lambda tup: (tup[0], tup[1], tup[2] != RobotCollisionType.kEnvironmentCollision), + filter(lambda tup: tup[3] <= 0.0, zip(indices_one, indices_two, collision_types, distances)), + ) + ) diff --git a/notebooks/03_collision_checking.ipynb b/notebooks/03_collision_checking.ipynb index d489017..f76764d 100644 --- a/notebooks/03_collision_checking.ipynb +++ b/notebooks/03_collision_checking.ipynb @@ -30,31 +30,14 @@ }, { "cell_type": "code", - "execution_count": 1, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "INFO:drake:Meshcat listening for connections at http://localhost:7000\n" - ] - }, - { - "data": { - "text/plain": [ - "SingleArmScene(robot_diagram=, arm_index=ModelInstanceIndex(2), gripper_index=ModelInstanceIndex(3), meshcat=)" - ] - }, - "execution_count": 1, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "import numpy as np\n", "from pydrake.planning import RobotDiagramBuilder, RobotCollisionType\n", - "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build\n", + "from airo_drake import SingleArmScene, add_floor, add_manipulator, add_meshcat, finish_build, list_collisions_between_bodies, filter_collisions_between_all_body_pairs\n", + "from airo_typing import JointConfigurationType\n", "\n", "robot_diagram_builder = RobotDiagramBuilder()\n", "\n", @@ -69,20 +52,9 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(6, 6, 0)" - ] - }, - "execution_count": 2, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "plant = scene.robot_diagram.plant()\n", "plant.num_positions(), plant.num_positions(arm_index), plant.num_positions(gripper_index)" @@ -90,17 +62,9 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stderr", - "output_type": "stream", - "text": [ - "INFO:drake:Allocating contexts to support implicit context parallelism 8\n" - ] - } - ], + "outputs": [], "source": [ "from pydrake.planning import SceneGraphCollisionChecker\n", "\n", @@ -126,20 +90,9 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "True" - ] - }, - "execution_count": 4, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "collision_checker.CheckConfigCollisionFree(np.zeros(6))" ] @@ -153,20 +106,9 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "False" - ] - }, - "execution_count": 5, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "joints_self_collision = np.deg2rad([0, 0, 180, 0, 0, 0])\n", "collision_checker.CheckConfigCollisionFree(joints_self_collision)" @@ -181,7 +123,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -201,20 +143,9 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "False" - ] - }, - "execution_count": 7, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "joints_table_collision = np.deg2rad([0, 5, 0, 0, 0, 0])\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" @@ -222,7 +153,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -239,51 +170,19 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Body ur5e::wrist_2_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::wrist_3_link is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::base_link is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::left_outer_knuckle is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::left_outer_finger is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::left_inner_finger is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::left_inner_finger_pad is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::left_inner_knuckle is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::right_outer_knuckle is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::right_outer_finger is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::right_inner_finger is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::right_inner_finger_pad is colliding with body floor::base_link (type: environment)\n", - "Body robotiq_arg2f_85_model::right_inner_knuckle is colliding with body floor::base_link (type: environment)\n" - ] - } - ], + "outputs": [], "source": [ - "def print_robot_collisions():\n", - " robot_clearance = collision_checker.CalcRobotClearance(joints_table_collision, 1.0)\n", - " indices_one = robot_clearance.robot_indices()\n", - " indices_two = robot_clearance.other_indices()\n", - " collision_types = robot_clearance.collision_types()\n", - " distances = robot_clearance.distances()\n", - "\n", - " collision_type_strings = {\n", - " RobotCollisionType.kEnvironmentCollision: \"environment\",\n", - " RobotCollisionType.kSelfCollision: \"self\",\n", - " RobotCollisionType.kEnvironmentAndSelfCollision: \"environment and self\"\n", - " }\n", - "\n", - " for index in range(len(indices_one)):\n", - " if distances[index] <= 0.0:\n", - " bodyA_name = plant.get_body(indices_one[index]).scoped_name()\n", - " bodyB_name = plant.get_body(indices_two[index]).scoped_name()\n", - " collision_type = collision_types[index]\n", - " print(f\"Body {bodyA_name} is colliding with body {bodyB_name} (type: {collision_type_strings[collision_type]})\")\n", - "\n", - "print_robot_collisions()" + "def print_robot_collisions(q: JointConfigurationType):\n", + " colliding_bodies = list_collisions_between_bodies(collision_checker, q)\n", + "\n", + " for colliding_body_1, colliding_body_2, is_self_collision in colliding_bodies:\n", + " bodyA_name = plant.get_body(colliding_body_1).scoped_name()\n", + " bodyB_name = plant.get_body(colliding_body_2).scoped_name()\n", + " print(f\"Body {bodyA_name} is colliding with body {bodyB_name} (is self collision: {is_self_collision})\")\n", + "\n", + "print_robot_collisions(joints_table_collision)" ] }, { @@ -295,17 +194,9 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "True\n" - ] - } - ], + "outputs": [], "source": [ "start_joints = np.deg2rad([0, -90, 90, -90, -90, 0])\n", "\n", @@ -317,17 +208,9 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "True\n" - ] - } - ], + "outputs": [], "source": [ "goal_joints = np.deg2rad([0, -90, 90, 180, -110, 0])\n", "\n", @@ -339,7 +222,7 @@ }, { "cell_type": "code", - "execution_count": 12, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -351,27 +234,9 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]\n" - ] - }, - { - "data": { - "text/plain": [ - "'✅✅✅✅✅✅✅✅💥💥✅✅✅✅✅✅✅✅✅✅'" - ] - }, - "execution_count": 13, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "def path_collisions_as_emojis(is_collision_free: list[bool]):\n", " \"\"\"Displays an emoji-based visualization of a path's collisions.\n", @@ -407,7 +272,7 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -437,20 +302,9 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(8, 8)" - ] - }, - "execution_count": 15, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "from ur_analytic_ik import ur5e\n", "\n", @@ -468,18 +322,9 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅💥💥✅✅✅✅\n", - "✅💥✅💥✅✅💥✅\n" - ] - } - ], + "outputs": [], "source": [ "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(start_configurations)))\n", "print(path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(goal_configurations)))" @@ -487,7 +332,7 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -496,7 +341,7 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -505,20 +350,9 @@ }, { "cell_type": "code", - "execution_count": 19, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(20, 8, 6)" - ] - }, - "execution_count": 19, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "from airo_typing import HomogeneousMatrixType\n", "\n", @@ -561,20 +395,9 @@ }, { "cell_type": "code", - "execution_count": 20, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(8, 20, 6)" - ] - }, - "execution_count": 20, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "from airo_drake import create_paths_from_closest_solutions\n", "\n", @@ -585,24 +408,9 @@ }, { "cell_type": "code", - "execution_count": 21, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "path 0: ✅✅✅💥💥💥💥💥💥💥✅✅✅✅✅✅✅✅✅✅\n", - "path 1: ✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", - "path 2: 💥💥💥💥✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "path 3: 💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥💥\n", - "path 4: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "path 5: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "path 6: ✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", - "path 7: ✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" - ] - } - ], + "outputs": [], "source": [ "for i, path in enumerate(paths):\n", " print(f\"path {i}: {path_collisions_as_emojis(collision_checker.CheckConfigsCollisionFree(path))}\")" @@ -610,20 +418,9 @@ }, { "cell_type": "code", - "execution_count": 22, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], + "outputs": [], "source": [ "import matplotlib\n", "import matplotlib.pyplot as plt\n", @@ -644,24 +441,9 @@ }, { "cell_type": "code", - "execution_count": 23, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "path 0: 🦘 [16]\n", - "path 1: 🦘 [16]\n", - "path 2: 🦘 [16]\n", - "path 3: 🦘 [16]\n", - "path 4: ✅ []\n", - "path 5: ✅ []\n", - "path 6: ✅ []\n", - "path 7: ✅ []\n" - ] - } - ], + "outputs": [], "source": [ "from airo_drake import joint_path_has_large_jumps\n", "\n", @@ -679,20 +461,9 @@ }, { "cell_type": "code", - "execution_count": 24, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" - ] - } - ], + "outputs": [], "source": [ "paths_without_jumps = [path for path in paths if not joint_path_has_large_jumps(path)]\n", "\n", @@ -702,17 +473,9 @@ }, { "cell_type": "code", - "execution_count": 25, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥💥💥💥\n" - ] - } - ], + "outputs": [], "source": [ "paths_with_collisions = [path for path in paths_without_jumps if not np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -724,19 +487,9 @@ }, { "cell_type": "code", - "execution_count": 26, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" - ] - } - ], + "outputs": [], "source": [ "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -748,17 +501,9 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[1.0821133056402081, 1.0821133056402081, 0.9808441751547153]\n" - ] - } - ], + "outputs": [], "source": [ "from airo_drake import time_parametrize_toppra\n", "\n", @@ -771,7 +516,7 @@ }, { "cell_type": "code", - "execution_count": 28, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -783,7 +528,7 @@ }, { "cell_type": "code", - "execution_count": 29, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -801,7 +546,7 @@ }, { "cell_type": "code", - "execution_count": 30, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -818,7 +563,7 @@ }, { "cell_type": "code", - "execution_count": 31, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -838,7 +583,7 @@ }, { "cell_type": "code", - "execution_count": 32, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -851,20 +596,9 @@ }, { "cell_type": "code", - "execution_count": 33, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(array([0.35, 0. , 0.35]), array([0.34550067, 0. , 0.34993251]))" - ] - }, - "execution_count": 33, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "import numpy as np\n", "from airo_typing import Vector3DType\n", @@ -894,7 +628,7 @@ }, { "cell_type": "code", - "execution_count": 34, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -913,7 +647,7 @@ }, { "cell_type": "code", - "execution_count": 35, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -936,22 +670,9 @@ }, { "cell_type": "code", - "execution_count": 36, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥\n", - "✅✅✅✅✅✅✅✅✅✅✅💥💥💥💥💥💥💥💥💥\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" - ] - } - ], + "outputs": [], "source": [ "path_joints_solutions = []\n", "\n", @@ -968,7 +689,7 @@ }, { "cell_type": "code", - "execution_count": 37, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -979,20 +700,9 @@ }, { "cell_type": "code", - "execution_count": 38, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n", - "✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅✅\n" - ] - } - ], + "outputs": [], "source": [ "paths_without_collisions = [path for path in paths_without_jumps if np.all(collision_checker.CheckConfigsCollisionFree(path))]\n", "\n", @@ -1002,17 +712,9 @@ }, { "cell_type": "code", - "execution_count": 39, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[1.6488317327683064, 1.5839720500574017, 1.583972050057404, 1.648831732768306]\n" - ] - } - ], + "outputs": [], "source": [ "trajectories = [time_parametrize_toppra(scene.robot_diagram.plant(), path, joint_acceleration_limit=1.0) for path in paths_without_collisions]\n", "durations = [trajectory.end_time() for trajectory in trajectories]\n", @@ -1022,7 +724,7 @@ }, { "cell_type": "code", - "execution_count": 40, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -1041,15 +743,12 @@ }, { "cell_type": "code", - "execution_count": 41, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ "arm_body_indices = plant.GetBodyIndices(arm_index)\n", - "floor_body_indices = plant.GetBodyIndices(floor_index)\n", - "\n", - "import itertools\n", - "body_combinations = itertools.product(arm_body_indices, floor_body_indices)" + "floor_body_indices = plant.GetBodyIndices(floor_index)" ] }, { @@ -1061,41 +760,18 @@ }, { "cell_type": "code", - "execution_count": 48, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" - ] - }, - { - "data": { - "text/plain": [ - "False" - ] - }, - "execution_count": 48, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ "joints_table_collision = np.deg2rad([0, 45, 0, 0, 0, 0])\n", - "print_robot_collisions()\n", + "print_robot_collisions(joints_table_collision)\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, { "cell_type": "code", - "execution_count": 49, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ @@ -1105,12 +781,11 @@ }, { "cell_type": "code", - "execution_count": 50, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ - "for body_index_arm, body_index_floor in body_combinations:\n", - " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, True)" + "filter_collisions_between_all_body_pairs(collision_checker, arm_body_indices, floor_body_indices, filtered=True)" ] }, { @@ -1122,34 +797,11 @@ }, { "cell_type": "code", - "execution_count": 51, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" - ] - }, - { - "data": { - "text/plain": [ - "False" - ] - }, - "execution_count": 51, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ - "print_robot_collisions()\n", + "print_robot_collisions(joints_table_collision)\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, @@ -1162,45 +814,20 @@ }, { "cell_type": "code", - "execution_count": 52, + "execution_count": null, "metadata": {}, "outputs": [], "source": [ - "body_combinations = itertools.product(arm_body_indices, floor_body_indices) # Repopulate the generator.\n", - "for body_index_arm, body_index_floor in body_combinations:\n", - " collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, False)" + "filter_collisions_between_all_body_pairs(collision_checker, arm_body_indices, floor_body_indices, filtered=False)" ] }, { "cell_type": "code", - "execution_count": 53, + "execution_count": null, "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::base_link_inertia is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::upper_arm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n", - "Body ur5e::forearm_link is colliding with body floor::base_link (type: environment)\n" - ] - }, - { - "data": { - "text/plain": [ - "False" - ] - }, - "execution_count": 53, - "metadata": {}, - "output_type": "execute_result" - } - ], + "outputs": [], "source": [ - "print_robot_collisions()\n", + "print_robot_collisions(joints_table_collision)\n", "collision_checker.CheckConfigCollisionFree(joints_table_collision)" ] }, From 56d46b764a16f45c9a85ebd7783a894b38036d87 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Tue, 2 Apr 2024 15:02:46 +0200 Subject: [PATCH 5/7] Variable naming --- airo_drake/collision/collision_checking.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/airo_drake/collision/collision_checking.py b/airo_drake/collision/collision_checking.py index cccdee4..421df55 100644 --- a/airo_drake/collision/collision_checking.py +++ b/airo_drake/collision/collision_checking.py @@ -23,8 +23,8 @@ def filter_collisions_between_all_body_pairs( filtered: Whether or not to filter collisions between these bodies.""" body_combinations = itertools.product(body_indices_one, body_indices_two) - for body_index_arm, body_index_floor in body_combinations: - collision_checker.SetCollisionFilteredBetween(body_index_arm, body_index_floor, filtered) + for body_index_1, body_index_2 in body_combinations: + collision_checker.SetCollisionFilteredBetween(body_index_1, body_index_2, filtered) def list_collisions_between_bodies( From d43574a13494495dee0faca1eb9616586f0bb624 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Mon, 22 Apr 2024 14:24:48 +0200 Subject: [PATCH 6/7] More Pythonic version via list comprehension --- airo_drake/collision/collision_checking.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/airo_drake/collision/collision_checking.py b/airo_drake/collision/collision_checking.py index 421df55..4c56fbe 100644 --- a/airo_drake/collision/collision_checking.py +++ b/airo_drake/collision/collision_checking.py @@ -46,9 +46,8 @@ def list_collisions_between_bodies( collision_types = robot_clearance.collision_types() distances = robot_clearance.distances() - return list( - map( - lambda tup: (tup[0], tup[1], tup[2] != RobotCollisionType.kEnvironmentCollision), - filter(lambda tup: tup[3] <= 0.0, zip(indices_one, indices_two, collision_types, distances)), - ) - ) + return [ + (tup[0], tup[1], tup[2] != RobotCollisionType.kEnvironmentCollision) + for tup in zip(indices_one, indices_two, collision_types, distances) + if tup[3] <= 0.0 + ] From 5c0ae7326ad587a30126b9dbfe7988166e298a94 Mon Sep 17 00:00:00 2001 From: Mathieu De Coster Date: Mon, 22 Apr 2024 16:21:56 +0200 Subject: [PATCH 7/7] filtered is now also allowed to be a positional argument and is now True by default --- airo_drake/collision/collision_checking.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/airo_drake/collision/collision_checking.py b/airo_drake/collision/collision_checking.py index 4c56fbe..445e879 100644 --- a/airo_drake/collision/collision_checking.py +++ b/airo_drake/collision/collision_checking.py @@ -10,8 +10,7 @@ def filter_collisions_between_all_body_pairs( collision_checker: SceneGraphCollisionChecker, body_indices_one: List[BodyIndex], body_indices_two: List[BodyIndex], - *, - filtered: bool + filtered: bool = True, ) -> None: """Enable or disable collision filtering between all pairs of the bodies listed in body_indices_one and body_indices_two. When collision filtering is enabled for two bodies, they are allowed to collide. @@ -20,7 +19,7 @@ def filter_collisions_between_all_body_pairs( collision_checker: The collision checker instance to alter. body_indices_one: A list of body indices. body_indices_two: A list of body indices. - filtered: Whether or not to filter collisions between these bodies.""" + filtered: Whether to filter collisions between these bodies.""" body_combinations = itertools.product(body_indices_one, body_indices_two) for body_index_1, body_index_2 in body_combinations: