From bf9291d72d939e62c25e8c736eeb924cb4a6d009 Mon Sep 17 00:00:00 2001 From: Mitchell Cohen Date: Mon, 10 Jun 2024 12:57:47 -0400 Subject: [PATCH] Add batch tutorial example --- docs/source/tutorial.rst | 3 +- docs/source/tutorial/batch.ipynb | 899 +++++++++++++++++++++++++++++++ navlie/lib/models.py | 5 - 3 files changed, 901 insertions(+), 6 deletions(-) create mode 100644 docs/source/tutorial/batch.ipynb diff --git a/docs/source/tutorial.rst b/docs/source/tutorial.rst index bdcf0772..dd7fca15 100644 --- a/docs/source/tutorial.rst +++ b/docs/source/tutorial.rst @@ -24,4 +24,5 @@ All the dependencies should get installed by this command and the package should 2. Toy Problem - Traditional <./tutorial/traditional.ipynb> 3. Toy Problem - Lie groups <./tutorial/lie_groups.ipynb> 4. Specifying Jacobians <./tutorial/jacobians.ipynb> - 4. Composite States <./tutorial/composite.ipynb> \ No newline at end of file + 4. Composite States <./tutorial/composite.ipynb> + 5. Batch Estimation <./tutorial/batch.ipynb> \ No newline at end of file diff --git a/docs/source/tutorial/batch.ipynb b/docs/source/tutorial/batch.ipynb new file mode 100644 index 00000000..cfc157e6 --- /dev/null +++ b/docs/source/tutorial/batch.ipynb @@ -0,0 +1,899 @@ +{ + "cells": [ + { + "attachments": {}, + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Toy Batch SLAM Example\n", + "\n", + "In this example, we'll consider a similar example to the one in the toy problems\n", + "notebook, but this time, we'll consider it in a batch estimation framework. To increase the complexity of the problem, we will also assume that the landmark\n", + "positions are unknown, and will be part of the state for estimation. Our goal\n", + "will be to estimate the robot's trajectory and the landmark positions using all\n", + "of the measurements collected. The state to estimate is given by \n", + "\n", + "$$\n", + "\\mathcal{X} = \\left(\\mathbf{T}_{1}, \\mathbf{T}_2, \\ldots, \\mathbf{T}_K,\n", + "\\mathbf{p}_a^1, \\mathbf{p}_a^2, \\mathbf{p}_a^M \\right),\n", + "$$\n", + "\n", + "where similarly to in the previous example $\\mathbf{T}_k \\in SE(2)$ denotes the\n", + "pose of the robot at time $k$, written as \n", + "\n", + "$$ \n", + "\\mathbf{T}_k = \\begin{bmatrix} \\mathbf{C}_{ab_k}(\\theta) & \\mathbf{r}_a^k \\\\ \\mathbf{0} & 1 \\end{bmatrix} \\in SE(2).\n", + "$$\n", + "\n", + "Additionally, $\\mathbf{p}_a^i \\in \\mathbb{R}^2$ denotes the position of the $i$'th landmark in\n", + "the inertial frame. Similarly to the previous example, the robot collects wheel\n", + "odometry measurements, which are used as the input to the process model given by\n", + "\n", + "\n", + "$$\n", + "\\mathbf{T}_{k+1} = \\mathbf{T}_k \\exp(\\boldsymbol{\\varpi}_k^\\wedge \\Delta t)\n", + "$$\n", + "\n", + "In this example, the robot will also collects direct measurements of the\n", + "landmark position, resolved in the body frame of the robot. The measurement\n", + "model is now a function of one robot pose and one landmark state, such that the\n", + "measurement of the $j$'th landmark at time $k$ is given by\n", + "\n", + "$$\n", + "\\begin{aligned}\n", + "\\mathbf{y}_{jk} &= \\mathbf{g}_{jk} \\left(\\mathbf{T}_k, \\mathbf{p}_a^j \\right) +\n", + "\\mathbf{v}_{jk} \\\\\n", + "&= \\mathbf{C}_{ab_k}^\\mathsf{T} \\left( \\mathbf{p}_a^j - \\mathbf{r}_a^k \\right) + \\mathbf{v}_{jk} \\\\\n", + "\\end{aligned}\n", + "$$\n", + "\n", + "where $\\mathbf{v}_{jk} \\sim \\mathcal{N} \\left( \\mathbf{0}, \\mathbf{R}_{jk}\n", + "\\right)$ is white noise. Notice that unlike the previous example, each\n", + "measurement is a function of two states. To define the measurement model, the\n", + "[CompositeState](../_autosummary/navlie.composite.CompositeState.rst)\n", + "class can be leveraged. First, we'll start by defining some parameters that\n", + "we'll need for the rest of the example, and then we'll implement the measurement\n", + "model." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import navlie as nav\n", + "import numpy as np\n", + "import typing \n", + "from pymlg import SO3\n", + "\n", + "### Parameters used for the example\n", + "# if true, the information matrix in the batch problem will be inverted to compute the covariance\n", + "compute_covariance = True \n", + "# If false, will run without noise, and all states initialized to groundtruth \n", + "noise = True \n", + "# String keys to identify the states\n", + "pose_key_str = \"x\"\n", + "landmark_key_str = \"l\"\n", + "# The end time of the simulation\n", + "t_end = 20.0\n", + "\n", + "### Defining the measurement model\n", + "class PointRelativePositionSLAM(nav.types.MeasurementModel):\n", + " def __init__(self, pose_state_id: typing.Any, landmark_state_id: typing.Any, R: np.ndarray):\n", + " self.pose_state_id = pose_state_id\n", + " self.landmark_state_id = landmark_state_id\n", + " self._R = R\n", + "\n", + " def evaluate(self, x: nav.CompositeState):\n", + " pose: nav.lib.SE2State = x.get_state_by_id(self.pose_state_id)\n", + " landmark: nav.lib.VectorState = x.get_state_by_id(self.landmark_state_id)\n", + "\n", + " r_a = pose.position.reshape((-1, 1))\n", + " p_a = landmark.value.reshape((-1, 1))\n", + " C_ab = pose.attitude\n", + " return C_ab.T @ (p_a - r_a)\n", + "\n", + " def jacobians(self, x: nav.CompositeState):\n", + " pose: nav.lib.SE2State = x.get_state_by_id(self._pose_state_id)\n", + " landmark: nav.lib.VectorState = x.get_state_by_id(self._landmark_state_id)\n", + "\n", + " r_zw_a = pose.position.reshape((-1, 1))\n", + " C_ab = pose.attitude\n", + " r_pw_a = landmark.value.reshape((-1, 1))\n", + " y = C_ab.T @ (r_pw_a - r_zw_a)\n", + "\n", + " # Compute Jacobian of measurement model with respect to the state\n", + " if pose.direction == \"right\":\n", + " pose_jacobian = pose.jacobian_from_blocks(\n", + " attitude=-SO3.odot(y), position=-np.identity(r_zw_a.shape[0])\n", + " )\n", + " elif pose.direction == \"left\":\n", + " pose_jacobian = pose.jacobian_from_blocks(\n", + " attitude=-C_ab.T @ SO3.odot(r_pw_a), position=-C_ab.T\n", + " )\n", + "\n", + " # Compute jacobian of measurement model with respect to the landmark\n", + " landmark_jacobian = pose.attitude.T\n", + "\n", + " # Build full Jacobian\n", + " state_ids = [state.state_id for state in x.value]\n", + " jac_dict = {}\n", + " jac_dict[state_ids[0]] = pose_jacobian\n", + " jac_dict[state_ids[1]] = landmark_jacobian\n", + " return x.jacobian_from_blocks(jac_dict)\n", + "\n", + " def covariance(self, x: nav.CompositeState):\n", + " return self._R" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Evaluating The Measurement Model\n", + "\n", + "To evaluate this measurement model, we just need to create a CompositeState that\n", + "contains the robot state and the landmark state, as done below." + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[[ 0.09642014]\n", + " [-0.05653507]]\n" + ] + } + ], + "source": [ + "pose = nav.lib.SE2State(np.array([0.1, 1.0, 2.0]), state_id=pose_key_str)\n", + "landmark = nav.lib.VectorState(np.array([1.0, 2.0]), state_id=landmark_key_str)\n", + "R = np.identity(2) * 0.01\n", + "\n", + "# Create the measurement model\n", + "model = PointRelativePositionSLAM(pose_key_str, landmark_key_str, R)\n", + "\n", + "# Create a composite state\n", + "state = nav.lib.CompositeState([pose, landmark])\n", + "# Evaluate the model\n", + "y = model.evaluate(state)\n", + "print(y)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Creating the simulated data\n", + "Next, we'll create the simulated data for this example. To use the data\n", + "generator included in navlie, it is convenient to define the same relative\n", + "position measurement model, but where the landmarks are included in the state\n", + "vector. We'll start by defining some landmarks and creating the relative\n", + "position measurement model with known landmarks. Then, we'll create the process\n", + "model using the BodyFrameVelocity process model defined in navlie." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "class PointRelativePosition(nav.types.MeasurementModel):\n", + " def __init__(self, landmark_position: np.ndarray, landmark_id: int, R: np.ndarray):\n", + " self.landmark_position = landmark_position.reshape((-1, 1))\n", + " self.landmark_id = landmark_id\n", + " self._R = R\n", + "\n", + " def evaluate(self, x: nav.lib.SE2State):\n", + " r_a = x.position.reshape((-1, 1))\n", + " p_a = self.landmark_position\n", + " C_ab = x.attitude\n", + " return C_ab.T @ (p_a - r_a)\n", + " \n", + " def covariance(self, x: nav.CompositeState):\n", + " return self._R\n", + " \n", + "# Now, create some landmarks arranged in a circle and create a list of\n", + "# measurement models, one for each landmark\n", + "landmark_positions = [np.array([3.0 * np.cos(theta), 3.0 * np.sin(theta)]) for theta in np.linspace(0, 2*np.pi, 10)]\n", + "landmarks = [nav.lib.VectorState(landmark, state_id=f\"{landmark_key_str}{i}\") for i, landmark in enumerate(landmark_positions)]\n", + "R = np.identity(2) * 0.1\n", + "meas_models = [PointRelativePosition(l.value, l.state_id, R) for l in landmarks]\n", + "\n", + "# Create the process model\n", + "Q = np.identity(3) * 0.4\n", + "process_model = nav.lib.BodyFrameVelocity(Q)\n", + "\n", + "# Input profile \n", + "input_profile = lambda t, x: np.array(\n", + " [np.cos(0.1 * t), 1.0, 0]\n", + ")\n", + "\n", + "# Generate the data\n", + "x0 = nav.lib.SE2State(np.array([0, 0, 0]))\n", + "dg = nav.DataGenerator(\n", + " process_model,\n", + " input_profile,\n", + " Q, \n", + " input_freq=100,\n", + " meas_model_list=meas_models,\n", + " meas_freq_list=[10] * len(meas_models),\n", + ")\n", + "\n", + "gt_poses, input_list, meas_list = dg.generate(x0, start=0.0, stop=t_end, noise=noise)\n", + "\n", + "# Plot the true state\n", + "import matplotlib.pyplot as plt\n", + "fig, ax = nav.plot_poses(gt_poses, step=100)\n", + "for landmark in landmarks:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'x')\n", + "ax.set_title(\"Groundtruth poses and landmarks\")\n", + "ax.set_xlabel(\"x\")\n", + "ax.set_ylabel(\"y\")\n", + "plt.show()" + ] + }, + { + "attachments": {}, + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Batch Estimation: From Weighted Nonlinear Least Squares to Unweighted Nonlinear Least Squares\n", + "Now, we wish to estimate the full state of the system using all of the inputs\n", + "and all of the measaurements. To do this, we want to define a nonlinear least\n", + "squares problem of the form \n", + "\n", + "$$\n", + "J (\\mathcal{X}) = \\frac{1}{2} \\sum_{i=1}^N \\mathbf{e}_i (\\mathcal{X})^\\mathsf{T} \\mathbf{W}_i\n", + "\\mathbf{e}_i (\\mathcal{X}), \n", + "$$\n", + "\n", + "where $N$ is the number of error terms in the problem, and each $\\mathbf{e}_i\n", + "(\\mathcal{X})$ is an error term that is function\n", + "of the state. Additionally, $\\mathbf{W}_i$ is a weight matrix, generally the inverse\n", + "covariance of the error. navlie has\n", + "a nonlinear least squares solver [Problem](../_autosummary/navlie.batch.problem.rst) that can be used to solve\n", + "general nonlinear least squares problems. However, the solver can only handle\n", + "*unweighted* nonlinear least squares problems of the form\n", + "\n", + "$$\n", + "J (\\mathcal{X}) = \\frac{1}{2} \\sum_{i=1}^N \\mathbf{e}_i (\\mathcal{X})^\\mathsf{T} \\mathbf{e}_i (\\mathcal{X}).\n", + "$$\n", + "\n", + "Thankfully, converting the weighted nonlinear least squares problem to an\n", + "equivalent unweighted problem is possible. Consider the Cholesky factorization\n", + "of $\\mathbf{W}$, given by \n", + "\n", + "$$\n", + "\\mathbf{W}_i = \\mathbf{L}_i \\mathbf{L}_i^\\mathsf{T}.\n", + "$$\n", + "\n", + "Defining $\\tilde{\\mathbf{e}_i} = \\mathbf{L}_i \\mathbf{e}_i$, we can rewrite the\n", + "original weighted cost function as \n", + "\n", + "$$\n", + "J (\\mathcal{X}) = \\frac{1}{2} \\tilde{\\mathbf{e}_i} (\\mathcal{X})^\\mathsf{T} \\tilde{\\mathbf{e}_i} (\\mathcal{X}).\n", + "$$\n", + "\n", + "Thus, for each error term in the problem, the user must pay careful attention to\n", + "weight the error by the square root of the inverse covariance matrix of that\n", + "particular error term.\n", + "\n", + "Now that we've seen how to convert the original weighted nonlinear least squares\n", + "problem into a nonweighted one, let's explore how to define nonlinear least\n", + "squares problems in navlie." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "# Defining Nonlinear Least Squares Problems in navlie\n", + "The `Problem` class in `navlie` is used to define and then solve nonlinear least\n", + "squares problems of the form \n", + "\n", + "$$\n", + "J (\\mathcal{X}) = \\frac{1}{2} \\sum_{i=1}^N \\mathbf{e}_i (\\mathcal{X}_s)^\\mathsf{T} \\mathbf{e}_i\n", + "(\\mathcal{X}_s).\n", + "$$\n", + "\n", + "where each error term is a function of *a subset* of the full state, written\n", + "$\\mathcal{X}_s$, where $\\mathcal{X}_s \\subset \\mathcal{X}$. In `navlie` each\n", + "$\\mathbf{e}_i$ is called a `Residual` (similarly to Ceres), and each state in\n", + "the problem is called a `Variable`. In many problems, residuals correspond to\n", + "one of three types: \n", + "\n", + "- A prior residual of the form\n", + " $$\n", + " \\mathbf{e} \\left(\\mathcal{X}_k \\right) = \\mathcal{X}_k \\ominus \\tilde{\\mathcal{X}}_k,\n", + " $$\n", + "where $\\tilde{\\mathcal{X}}_k$ is a prior estimate of the state at time $k$.\n", + "\n", + "- A process residual, defining an error using the process model for the\n", + " state written \n", + "\n", + " $$\n", + " \\mathbf{e} \\left(\\mathcal{X}_{k-1}, \\mathcal{X}_k \\right) = \\mathcal{X}_k\n", + " \\ominus f \\left(\\mathcal{X}_{k-1}, \\mathbf{u}_{k-1} \\right), \n", + " $$ \n", + "where $\\ominus$ represents a general minus operator for the group, and $f\n", + "(\\mathcal{X}_{k-1}, \\mathbf{u}_{k-1})$ is the process model.\n", + "\n", + "- A measurement residual of the form \n", + "\n", + " $$ \n", + " \\mathbf{e} \\left(\\mathcal{X}_s \\right) = \\mathbf{y} - \\mathbf{g} \\left(\\mathcal{X}_s \\right),\n", + " $$\n", + "where $\\mathbf{y}$ is a measurement, $\\mathbf{g}$ is the measurement model, and $\\mathcal{X}_s$ is the subset of the state that the measurement model is a\n", + "function of. Note that these are all *unweighted* forms of the residual.\n", + "\n", + "To define a `Residual`, a user must inherit from the `Residual` base class\n", + "defined in [Residual](../_autosummary/navlie.batch.residuals.rst). Each\n", + "`Residual` The user must then implement the `evaluate()` method, which computes\n", + "the residual and the Jacobians of the residual with respect to each state that\n", + "the residual is a function of. The `Residual` class must also contain the unique\n", + "keys of each variable involved in the residual.\n", + "\n", + "In the toy batch SLAM example, we will define a prior residual on the first\n", + "pose, process residuals that connect consecutive robot states through the\n", + "process model, and measurement residuals that connect the robot states to the\n", + "landmark states. The next section will show how these can be defined in navlie." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "## Defining the residuals\n", + "from navlie.batch.residuals import Residual\n", + "\n", + "# Define the prior residual, used to place a prior on the first state\n", + "class PriorResidual(Residual):\n", + " \n", + " def __init__(self, \n", + " keys: typing.List[typing.Hashable],\n", + " prior_state: nav.lib.SE2State,\n", + " prior_covariance: np.ndarray):\n", + " super().__init__(keys)\n", + " self._cov = prior_covariance\n", + " self._x0 = prior_state\n", + " # Precompute squarae-root of the inverse covariance\n", + " self._L = np.linalg.cholesky(np.linalg.inv(self._cov))\n", + "\n", + " def evaluate(self, \n", + " states: typing.List[nav.types.State], \n", + " compute_jacobians: typing.List[bool] = None):\n", + " # Extract the SE2State from the list\n", + " # The list should only be of length one since only one state is involved\n", + " # in this residual\n", + " x = states[0]\n", + " error = x.minus(self._x0)\n", + " # Weight the error by the square root of the information matrix\n", + " error = self._L.T @ error\n", + "\n", + " # Compute Jacobian of error w.r.t x\n", + " if compute_jacobians:\n", + " # jacobians should be a list with length equal to the number of\n", + " # states involved in this residual (in this case 1)\n", + " jacobians = [None] \n", + " if compute_jacobians[0]:\n", + " jacobians[0] = self._L.T @ x.minus_jacobian(self._x0)\n", + " return error, jacobians\n", + "\n", + " return error\n", + "\n", + "# Define the process residual, which links two consecutive robot states\n", + "class ProcessResidual(Residual):\n", + " \"\"\"\n", + " A generic process residual.\n", + "\n", + " Can be used with any :class:`navlie.types.ProcessModel`.\n", + " \"\"\"\n", + "\n", + " def __init__(\n", + " self,\n", + " keys: typing.List[typing.Hashable],\n", + " process_model: nav.lib.BodyFrameVelocity,\n", + " u: nav.Input,\n", + " ):\n", + " super().__init__(keys)\n", + " self._process_model = process_model\n", + " self._u = u\n", + "\n", + " def evaluate(\n", + " self,\n", + " states: typing.List[nav.types.State],\n", + " compute_jacobians: typing.List[bool] = None,\n", + " ) -> typing.Tuple[np.ndarray, typing.List[np.ndarray]]:\n", + " # Extract the states at times k-1 and k\n", + " # The list should be of length 2, since there are two states\n", + " # involved in this residual\n", + " x_km1 = states[0]\n", + " x_k = states[1]\n", + " # Compute the timestamp from the states\n", + " dt = x_k.stamp - x_km1.stamp\n", + "\n", + " # Evaluate the process model, compute the error\n", + " x_k_hat = self._process_model.evaluate(x_km1.copy(), self._u, dt)\n", + "\n", + " # Compute the error, the difference between the state predicted from the \n", + " # process model and the actual state at time k\n", + " e = x_k.minus(x_k_hat)\n", + "\n", + " # Scale the error by the square root of the info matrix\n", + " L = self._process_model.sqrt_information(x_km1, self._u, dt)\n", + " e = L.T @ e\n", + "\n", + " # Compute the Jacobians of the residual w.r.t x_km1 and x_k\n", + " if compute_jacobians:\n", + " # jac_list should be a list of length two, where the first element\n", + " # is the jacobian of the residual w.r.t x_km1 and the second element\n", + " # is the Jacobian of the residual w.r.t x_k\n", + " jac_list = [None] * len(states)\n", + " if compute_jacobians[0]:\n", + " jac_list[0] = -L.T @ self._process_model.jacobian(\n", + " x_km1, self._u, dt\n", + " )\n", + " if compute_jacobians[1]:\n", + " jac_list[1] = L.T @ x_k.minus_jacobian(x_k_hat)\n", + "\n", + " return e, jac_list\n", + "\n", + " return e\n", + " \n", + "# Define the measurement residual, which links a robot state to a landmark\n", + "class PointRelativePositionResidual(Residual):\n", + " def __init__(\n", + " self,\n", + " keys: typing.List[typing.Hashable],\n", + " meas: nav.types.Measurement,\n", + " ):\n", + " super().__init__(keys)\n", + " # Store the measurement, where the measurement contains the model\n", + " self.meas = meas\n", + " # Evaluate the square root information a single time since it does not\n", + " # depend on the state in this case\n", + " self.sqrt_information = self.meas.model.sqrt_information([])\n", + "\n", + " def evaluate(\n", + " self,\n", + " states: typing.List[nav.types.State],\n", + " compute_jacobians: typing.List[bool] = None,\n", + " ) -> typing.Tuple[np.ndarray, typing.List[np.ndarray]]:\n", + " # In this case, states is a list of length two, where the first element\n", + " # should be the robot state and the second element should be the\n", + " # landmark state.\n", + " \n", + " # To evaluate the measurement model that we previously defined,\n", + " # we need to create a composite state from the list of states\n", + " eval_state = nav.CompositeState(states)\n", + " \n", + " # Evaluate the measurement model\n", + " y_check = self.meas.model.evaluate(eval_state)\n", + " # Compute the residual as the difference between the actual measurement\n", + " error = self.meas.value - y_check\n", + "\n", + " L = self.sqrt_information\n", + " error = L.T @ error\n", + "\n", + " if compute_jacobians:\n", + " # Jacobians should be a list of length equal to the number of states\n", + " jacobians = [None] * len(states)\n", + " # The Jacobian of the residual is the negative of the measurement\n", + " # model Jacobian\n", + " full_jac = -self.meas.model.jacobian(eval_state)\n", + " # The first 3 columns of the Jacobian are the Jacobian w.r.t the\n", + " # robot state, and the last 2 columns are the Jacobian w.r.t the\n", + " # landmark state\n", + " if compute_jacobians[0]:\n", + " jacobians[0] = L.T @ full_jac[:, :3]\n", + " if compute_jacobians[1]:\n", + " jacobians[1] = L.T @ full_jac[:, 3:]\n", + "\n", + " return error, jacobians\n", + " return error" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Generating the Initial Estimate\n", + "\n", + "Now that we've defined the residuals that will be used in the problem, we can\n", + "now create the problem, and add all of our variables and residuals to the\n", + "problem. We will first need an initial estimate for the states, where here, the\n", + "initial estimate for the robot trajectory is generated via dead-reckoning of the\n", + "noisy odometry measurements. The initial estimate for the landmarks in this\n", + "example will be generated by simply perturbing the groundtruth landmark\n", + "positions, but in practice, landmarks can be initialized by inverting the\n", + "measurement model." + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "Text(0, 0.5, 'y (m)')" + ] + }, + "execution_count": 5, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Dead-reckon initial state forward using the noisy measurements\n", + "x0_hat = gt_poses[0].copy()\n", + "x0_hat.state_id = pose_key_str + \"0\"\n", + "init_pose_est = [x0_hat]\n", + "x = x0_hat.copy()\n", + "for k in range(len(input_list) -1):\n", + " u = input_list[k]\n", + " dt = input_list[k + 1].stamp - u.stamp \n", + " x = process_model.evaluate(x, u, dt)\n", + " x.stamp = x.stamp + dt\n", + " x.state_id = pose_key_str + str(k + 1)\n", + " x.direction = \"left\"\n", + " init_pose_est.append(x.copy())\n", + " \n", + "# Generate estimates of landmarks by perturbing the groundtruth landmarks\n", + "init_landmark_est = []\n", + "for i, landmark in enumerate(landmarks):\n", + " if noise:\n", + " sigma_init = 0.4\n", + " else: \n", + " sigma_init = 0.0\n", + " perturbed_landmark = nav.lib.VectorState(landmark.value + np.random.randn(2) * sigma_init, state_id=landmark.state_id)\n", + " init_landmark_est.append(perturbed_landmark)\n", + "\n", + "# Plot the initial estimate compared to the groundtruth\n", + "fig, ax = nav.plot_poses(gt_poses, step=None, line_color='tab:blue', label=\"Groundtruth\")\n", + "nav.plot_poses(init_pose_est, step=None, ax=ax, line_color='tab:red', label=\"Initial Estimate\")\n", + "\n", + "# Plot the true and the estimated landmarks\n", + "for landmark in landmarks:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'tab:blue', marker='x')\n", + "for landmark in init_landmark_est:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'tab:red', marker='x')\n", + "\n", + "ax.legend()\n", + "ax.set_xlabel(\"x (m)\")\n", + "ax.set_ylabel(\"y (m)\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Now that we've generated our initial estimate, we can create the nonlinear least\n", + "squares problem and add our initial variable estimates to the problem. Each\n", + "variable that we'd like to optimize needs to have an associated key that is\n", + "unique to that variable - in this example, robot poses will have the keys `x0`,\n", + "`x1`, `x2`, etc., and landmarks will have the keys `l0`, `l1`, `l2`, etc." + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "First 10 keys: \n", + "['x1', 'x2', 'x3', 'x4', 'x5', 'x6', 'x7', 'x8', 'x9']\n", + "Last 10 keys:\n", + "['l0', 'l1', 'l2', 'l3', 'l4', 'l5', 'l6', 'l7', 'l8', 'l9']\n" + ] + } + ], + "source": [ + "from navlie.batch.problem import Problem\n", + "\n", + "# Create a problem with default settings\n", + "problem = Problem()\n", + "# Add poses and landmarks to the problem\n", + "for i, state in enumerate(init_pose_est):\n", + " problem.add_variable(state.state_id, state)\n", + "for i, landmark in enumerate(init_landmark_est):\n", + " problem.add_variable(landmark.state_id, landmark)\n", + "\n", + "# Now, lets print the keys of the variables that are in the problem!\n", + "init_keys_list = list(problem.variables_init.keys())\n", + "print(\"First 10 keys: \")\n", + "print(init_keys_list[1:10])\n", + "print(\"Last 10 keys:\")\n", + "print(init_keys_list[-10:])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can see that we've added all the poses to the problem, followed by all the landmarks.\n", + "Next, let's add in the error terms to the problem - one prior residual on the\n", + "first pose, process residuals connecting consecutive poses, and measurement\n", + "residuals connecting each pose and each landmark." + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "# Get the estimated pose timestamps (we'll need this for later)\n", + "est_stamps = [state.stamp for state in init_pose_est]\n", + "\n", + "init_cov = np.identity(3) * 1e-7 # set a small covariance since we've initialized to groundtruth\n", + "x0_hat = init_pose_est[0].copy()\n", + "prior_residual = PriorResidual(x0_hat.state_id, x0_hat.copy(), init_cov)\n", + "problem.add_residual(prior_residual)\n", + "\n", + "# Add process residuals\n", + "for k in range(len(input_list) - 1):\n", + " u = input_list[k]\n", + "\n", + " key_1 = f\"{pose_key_str}{k}\"\n", + " key_2 = f\"{pose_key_str}{k+1}\"\n", + " process_residual = ProcessResidual(\n", + " [key_1, key_2],\n", + " process_model,\n", + " u,\n", + " )\n", + " problem.add_residual(process_residual)\n", + "\n", + "from navlie.utils import find_nearest_stamp_idx\n", + "\n", + "# Before adding in the measurements to the problem, we need to replace the\n", + "# measurement model on the measurements with the measurement model with unknown\n", + "# landmark position\n", + "for k, meas in enumerate(meas_list):\n", + " # Get the pose key \n", + " pose_idx = find_nearest_stamp_idx(est_stamps, meas.stamp)\n", + " # Get state at this id\n", + " pose = init_pose_est[pose_idx]\n", + " landmark_state_id = meas.model.landmark_id\n", + " meas.model = PointRelativePositionSLAM(pose.state_id, landmark_state_id, R)\n", + " key_1 = pose.state_id\n", + " key_2 = landmark_state_id\n", + " meas_residual = PointRelativePositionResidual(\n", + " [key_1, key_2],\n", + " meas,\n", + " )\n", + " problem.add_residual(meas_residual) \n" + ] + }, + { + "attachments": {}, + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Run Batch!\n", + "\n", + "Now that all the variables and residuals have been added to the problem, we can\n", + "run our solver on the problem! Calling `problem.solve()` will return a\n", + "dictionary containing the optimized state and a summary of the optimization. The\n", + "problem will output the cost at each iteration, as well as the step sizes taken,\n", + "the change in cost `dC`, and the norm of the gradient." + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Initial cost: 10209.908382510479\n", + "Iter: 0 || Cost: 2.1187e+03 || Step size: 1.8430e+01 || dC: 8.0913e+03 || dC/C: 3.8191e+00 || |grad|_inf: 2.5900e+02\n", + "Iter: 1 || Cost: 1.9963e+03 || Step size: 2.1161e+00 || dC: 1.2235e+02 || dC/C: 6.1290e-02 || |grad|_inf: 8.5779e+00\n", + "Iter: 2 || Cost: 1.9963e+03 || Step size: 5.0496e-02 || dC: 4.0240e-02 || dC/C: 2.0158e-05 || |grad|_inf: 3.1471e-01\n", + "Iter: 3 || Cost: 1.9963e+03 || Step size: 4.9900e-03 || dC: 1.9980e-04 || dC/C: 1.0009e-07 || |grad|_inf: 4.1650e-02\n", + "Iter: 4 || Cost: 1.9963e+03 || Step size: 2.6577e-04 || dC: 1.5637e-05 || dC/C: 7.8333e-09 || |grad|_inf: 2.0333e-03\n", + "Iter: 5 || Cost: 1.9963e+03 || Step size: 1.1292e-05 || dC: 3.4423e-07 || dC/C: 1.7244e-10 || |grad|_inf: 1.7811e-04\n", + "Iter: 6 || Cost: 1.9963e+03 || Step size: 1.7510e-06 || dC: 1.0526e-07 || dC/C: 5.2728e-11 || |grad|_inf: 1.3721e-05\n", + "Iter: 7 || Cost: 1.9963e+03 || Step size: 1.0217e-07 || dC: 6.7209e-09 || dC/C: 3.3668e-12 || |grad|_inf: 1.5173e-06\n", + "Iter: 8 || Cost: 1.9963e+03 || Step size: 4.5874e-08 || dC: 1.3465e-09 || dC/C: 6.7452e-13 || |grad|_inf: 3.0893e-07\n", + "Number of states optimized: 6017.\n", + "Number of error terms: 9997.\n", + "Initial cost: 10209.908382510479.\n", + "Final cost: 1996.258310853446.\n", + "Total time: 40.7240629196167\n" + ] + } + ], + "source": [ + "# Solve the problem\n", + "opt_results = problem.solve()\n", + "variables_opt = opt_results[\"variables\"]\n", + "print(opt_results[\"summary\"])" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Extracting the Estimates and the Covariances\n", + "To extract the covariance, we can use thee `problem.get_covariance_block()`\n", + "method, which will extract the *marginal covariance* of a particular variable\n", + "based on the state ID of that variable.\n", + "Note that this is useful for visualizing three sigma bounds and individual NEES\n", + "values for subsets of the state, but sometimes it is also useful to compute the\n", + "NEES for the entire trajectory. The problem class also outputs the full\n", + "information matrix of the problem, and the user can choose to manipulate this\n", + "themselves after the optimization has completed." + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAkIAAAHHCAYAAABTMjf2AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8pXeV/AAAACXBIWXMAAA9hAAAPYQGoP6dpAADyXElEQVR4nOy9d5wb9Z3//5pR79req+u6N2xcwIANpiQEQgiQEMAhHLkkR3JcGrmEQJLv+cgFfhAS4EgOCEnoJIROjLHBvWLjuvb23tW7Zub3x2hmZ6SRVrur9bbP8/HYx+5KI+kjaebzeX3eleI4jgOBQCAQCATCNIQe7wEQCAQCgUAgjBdECBEIBAKBQJi2ECFEIBAIBAJh2kKEEIFAIBAIhGkLEUIEAoFAIBCmLUQIEQgEAoFAmLYQIUQgEAgEAmHaQoQQgUAgEAiEaQsRQgQCgUAgEKYtRAgRCISMcckll+CSSy4Z72HI2LFjByiKwo4dO8Z7KAQCYQJChBCBMA147rnnQFFU0p99+/al/VynTp3CAw88gKamprEb8Ah44okn8Nxzz433MGRccsklST/zuXPnjvfwCAQCAPV4D4BAIJw/fvGLX6Cqqirh9pkzZ6b9HKdOncKDDz6ISy65BJWVlbL7/vnPf452iCPmiSeeQG5uLu644w7Z7RdffDECgQC0Wu24jKu0tBRbtmxJuN1ms43DaAgEQjxECBEI04irrroKK1asGLPnHy+xkQqapqHX68ft9W02G2699dZhP87n88FkMiXcznEcgsEgDAbDiMcUDAah1WpB08QpQCCQq4BAIMh46aWXsHz5clgsFlitVixcuBCPPfYYAN7FduONNwIALr30UtHNI8TfxMcICfE5r7zyCh588EGUlJTAYrHgS1/6ElwuF0KhEL73ve8hPz8fZrMZmzdvRigUko3n2WefxWWXXYb8/HzodDrMmzcPTz75pOyYyspKnDx5Eh9//LE4JmEcyWKEXn31VSxfvhwGgwG5ubm49dZb0d7eLjvmjjvugNlsRnt7O6677jqYzWbk5eXh+9//PhiGGeUnPcgDDzwAiqJw6tQpfOUrX0FWVhbWrVsnvrfPfe5z+OCDD7BixQoYDAb87//+LwCgoaEBN954I7Kzs2E0GnHhhRfinXfekT238P5feukl/PSnP0VJSQmMRiPcbjcikQgefPBBzJo1C3q9Hjk5OVi3bh22bt2asfdGIEx0iEWIQJhGuFwu9PX1yW6jKAo5OTkAgK1bt+KWW27Bhg0b8NBDDwEATp8+jd27d+O73/0uLr74Ytxzzz347W9/i5/85CeoqakBAPF3MrZs2QKDwYAf//jHqKurw+OPPw6NRgOapuFwOPDAAw9g3759eO6551BVVYX7779ffOyTTz6J+fPn49prr4VarcZbb72Fb33rW2BZFt/+9rcBAI8++ij+7d/+DWazGf/5n/8JACgoKEg6nueeew6bN2/GBRdcgC1btqC7uxuPPfYYdu/ejU8//RR2u108lmEYbNq0CatWrcJvfvMbfPjhh3j44YcxY8YM/Ou//uuQnznDMAmfOQAYDIYEi8+NN96IWbNm4b/+67/AcZx4e21tLW655RbcfffduOuuuzBnzhx0d3djzZo18Pv9uOeee5CTk4M//elPuPbaa/Haa6/h+uuvlz33L3/5S2i1Wnz/+99HKBSCVqvFAw88gC1btuAb3/gGVq5cCbfbjUOHDuHIkSO4/PLLh3xvBMKUgCMQCFOeZ599lgOg+KPT6cTjvvvd73JWq5WLRqNJn+vVV1/lAHDbt29PuG/9+vXc+vXrxf+3b9/OAeAWLFjAhcNh8fZbbrmFoyiKu+qqq2SPX716NVdRUSG7ze/3J7zOpk2buOrqatlt8+fPl712/BiE8YbDYS4/P59bsGABFwgExOPefvttDgB3//33i7fdfvvtHADuF7/4hew5ly5dyi1fvjzhteJZv3590s/97rvvFo/7+c9/zgHgbrnlloTnqKio4ABw77//vuz2733vexwAbufOneJtHo+Hq6qq4iorKzmGYWTvv7q6OuGzXLx4MXfNNdcM+T4IhKkMcY0RCNOI3//+99i6davs57333hPvt9vt8Pl8GXeN3HbbbdBoNOL/q1atAsdx+PrXvy47btWqVWhtbUU0GhVvk8bCCBat9evXo6GhAS6Xa9hjOXToEHp6evCtb31LFjt0zTXXYO7cuQmuJQD45je/Kfv/oosuQkNDQ1qvV1lZmfCZb926Fd/73veGfB2BqqoqbNq0SXbbu+++i5UrV4ouNAAwm834l3/5FzQ1NeHUqVOy42+//faEuCK73Y6TJ0/i3Llzab0XAmEqQlxjBMI0YuXKlSmDpb/1rW/hlVdewVVXXYWSkhJcccUV+PKXv4wrr7xyVK9bXl4u+1/ImCorK0u4nWVZuFwu0V23e/du/PznP8fevXvh9/tlx7tcrmFnXzU3NwMA5syZk3Df3LlzsWvXLtlter0eeXl5stuysrLgcDjSej2TyYSNGzemdaxSRl+y25ubm7Fq1aqE2wU3ZXNzMxYsWJDyOX7xi1/gC1/4AmbPno0FCxbgyiuvxNe+9jUsWrQorfESCFMBYhEiEAgi+fn5OHr0KN58801ce+212L59O6666ircfvvto3pelUo1rNu5WHxMfX09NmzYgL6+PjzyyCN45513sHXrVvz7v/87AIBl2VGNKx2SjXEsSJYJNpoMsVTPcfHFF6O+vh7PPPMMFixYgD/+8Y9YtmwZ/vjHP4769QiEyQIRQgQCQYZWq8XnP/95PPHEE6ivr8fdd9+N559/HnV1dQD44OrzxVtvvYVQKIQ333wTd999N66++mps3LhRcVFPd1wVFRUA+ADkeGpra8X7JzoVFRWK7+HMmTPi/emQnZ2NzZs348UXX0RraysWLVqEBx54IJNDJRAmNEQIEQgEkf7+ftn/NE2LbhIhrV3IdHI6nWM+HsEaw0kyqFwuF5599tmEY00mU1pjWrFiBfLz8/HUU0/JUvXfe+89nD59Gtdcc83oB34euPrqq3HgwAHs3btXvM3n8+Hpp59GZWUl5s2bN+RzxH/fZrMZM2fOTChhQCBMZUiMEIEwjXjvvfdEi4GUNWvWoLq6Gt/4xjcwMDCAyy67DKWlpWhubsbjjz+OJUuWiLEnS5YsgUqlwkMPPQSXywWdTifW+ck0V1xxhWihuvvuu+H1evGHP/wB+fn56OzslB27fPlyPPnkk/jVr36FmTNnIj8/H5dddlnCc2o0Gjz00EPYvHkz1q9fj1tuuUVMn6+srBTdbpnC5XLhL3/5i+J9Iym0KPDjH/8YL774Iq666ircc889yM7Oxp/+9Cc0Njbi9ddfT6tY4rx583DJJZdg+fLlyM7OxqFDh/Daa6/hO9/5zojHRSBMNogQIhCmEdL6PFKeffZZVFdX49Zbb8XTTz+NJ554Ak6nE4WFhbjpppvwwAMPiAtrYWEhnnrqKWzZsgV33nknGIbB9u3bx0QIzZkzB6+99hp++tOf4vvf/z4KCwvxr//6r8jLy0vIOLv//vvR3NyMX//61/B4PFi/fr2iEAL4QolGoxH//d//jR/96EcwmUy4/vrr8dBDD8lqCGWCtrY2fO1rX1O8bzRCqKCgAHv27MGPfvQjPP744wgGg1i0aBHeeuuttK1a99xzD958803885//RCgUQkVFBX71q1/hBz/4wYjHRSBMNihOanMmEAgEAoFAmEaQGCECgUAgEAjTFiKECAQCgUAgTFuIECIQCAQCgTBtIUKIQCAQCATCtIUIIQKBQCAQCNOWSSeEfv/736OyshJ6vR6rVq3CgQMHkh578uRJ3HDDDaisrARFUXj00UfP30AJBAKBQCBMeCZVHaGXX34Z9957L5566imsWrUKjz76KDZt2oTa2lrFGiZ+vx/V1dW48cYbR1wkjWVZdHR0wGKxnNfWAgQCgUAgEEYOx3HweDwoLi5OXWCUm0SsXLmS+/a3vy3+zzAMV1xczG3ZsmXIx1ZUVHD/3//3/w37NVtbWzkA5If8kB/yQ37ID/mZhD+tra0p1/lJYxEKh8M4fPgw7rvvPvE2mqaxceNGWa+d0RIKhWR9drhYvcnW1lZYrdaMvQ6BQCAQCISxw+12o6ysDBaLJeVxk0YI9fX1gWEYFBQUyG4vKChQ7J00UrZs2YIHH3ww4Xar1UqEEIFAIBAIk4yhwlomXbD0WHPffffB5XKJP62treM9JAKBQCAQCGPEpLEI5ebmQqVSobu7W3Z7d3c3CgsLM/Y6Op0OOp0uY89HIBAIBAJh4jJpLEJarRbLly/Htm3bxNtYlsW2bduwevXqcRwZgUAgEAiEkeINRcf19SeNRQgA7r33Xtx+++1YsWIFVq5ciUcffRQ+nw+bN28GANx2220oKSnBli1bAPAB1qdOnRL/bm9vx9GjR2E2mzFz5sxxex8EAoFAIBAAluXQ7Q7CnGcetzFMKiF00003obe3F/fffz+6urqwZMkSvP/++2IAdUtLi6xWQEdHB5YuXSr+/5vf/Aa/+c1vsH79euzYseN8D59AIBAIBIKEfl8Y4Sg7rmOgOCE/nKCI2+2GzWaDy+UiWWOECYdw+VIUBZblQNMUGJaDiqYQZVioaAocxxfToCkgynLQqGiEoyy0av63mqb4Yhtc7HGxY4TnYVkOFMW/BsdxpLAogUDIGCfaXVDRFGqKMr++prt+TyqL0HSH4zhwHK+gu1xBZJu1ONLsQE2RBQebHJhTaEFdjxc2gwY0RaHfG8KsAgtOdbiwrCILx1pdWFBiRcuAHzaDBkatCj3uEOYVW/FZmwsXVGbjWJsTNYVWtDsDMOlUMOnU6HIFUVNkxfF2F5aW23Gqw43qPBOc/gi0KhpmvRrd7iBm5ptxrtuLOYUWNPf7UGDVIxBmAAow69To94ZRYjegzRFAaZYBfd4QbEYNIgy/mOvVNHwhBjajBi5/BFaDGr4wA72aBssBLMdBp6YRiDAwatXwhqIwaVUIRBhoVTQ4AAzLH+MLMzDr1HAFIrDq1fAEo/CGosg2aRFhWBi1avT7Qsgz69DpCiLfosOAPwy9RgWOA3yhKHLMWjT3+zEjz4zaLg8qcozocgdh1Kqgoij0+8IoyzbiTKcb84tt+KzNiRn5ZnQ6g9BpaGhVNDqcAcwqsOBIiwNLy+w40uLErAIz2hwBaGgKZr0aTf1+zCuy4FCTA0vLs3C01YHqPDM6XUEAQJZRg4ZeH2qKrDjS4sDiUjuOtztRnm1Cvy8EluWQZ9GhvtfHf5etLswvtqK224Niux6eYBQRhkO+RYemPh/mFllxssOFuYVW1Pd6kW/RIRhhEIywKLLr0djrw/wSK463ubGghD+mwKpHhOHgC0VRmWvCmU43lpZn4VirEwtLbWjo9SHPwicZOP3h2HnnxorKLBxt4Y9p6vMhy6SFRkVjwBfG3EILTrS7sKIyG5+1OTGv2IoOZwBWvQZ6jQp93hBm5vOf/cJSG851e1GRY4QrEIFOrYJBq4I7EEGhVY8udxBFNj0cfv77jsbEm4amEWZY6DUqUfwJglEqIjNJjzuIJ3bU49YLyzEzP3X9EgJhutPlCqIkyzCuYyAWoSGYCBYhXyiKKMvh/ROd8IUYhKIsghEGNEWBzeDXR1EAx0H2vKqYhUEdsxQIVgSdhkYowoKmKOg0NAJhBlaDBu5ABFlGDRz+COxGDbzBKGiaglmnxoCPF0LtzgDKso1oHfCj0KaHJxgBywF5Zh1aHX7MLbTidKcbNUVWnOv2oNhugDcURTjKothuQF2PF4vKbDja4sSCEhvOdnv4xTzKIhCOojTLiLPdHiwotuHJj+tRmWPE6U4PTnW68Y11lcgy6VBiN6Cxz4fqPBMaen0osRvQ6QrCpFMB4IP3cs069HpCyDFr0e8Ni+9Pq6ZBUxSCEV5seUNRGLQqBMKM+LlQFKCi+M9M+AyFz1X4nKc78eebcI7RFAUVDUQYTvxcLTExazNo4AlGoVFT0KtVcAcjKLYb0O4IiN9lZa4RvZ4QtCoaWSYt2hwBLCq14XCzAxdW5+DTFidqiizo8YSgoigU2w042+3Bmhk52FPfj4tn5+FIM7+xcAUiYDkOpVlG1Ha5saoqB/sb+7GyKgcn2l0ozzbCH2YQijIosRtwpsuD32+vw/7GAQDAty+ZgRuWlwIA/GEGpVkG1HZ5YoLXifnF/MYkx6QFB/5aL7Yb0NTvw5wCC+p7fSjPNsLpD8OoU4OmgECYQZZRiz5vCPlWPQZ8YdgNGgSjDNQ0DZqSf3YGrQqhKL9ZYDmAin32LIeYxZBY+Qjjx1/3N2NZeda4WoSIEBqC8RZCrkAEL+xvQSjKkMVzmBxvd+GjMz2y2ypyjLhuSck4jWj4BCMMPmtzYW6hBVaDBlGWhTpVzxzCqFHaECTbCOg0NCJRDizHwahVwR9m8Ni2c7Ln+9yiIswttCDCcAmbhVyzFn3eMCx6NRiWQzDCosDKWykrc41o6vOjKteE1gE/7EYNKIqC0x/GzHwzTnd6sKwiC5+2OLCo1Ia6Hi/sRi30GhU6nQEsLrNjX0M/Lp2Tj53nerGiMhvneryw6tWwGTSo7/VhzYwcbK/twVULivDRmR6sqspGQ58PRo0KuRYdarvcWDszF9vP9ODyeYX45GwvFpfZ0eEKQEVRKLTpcarDjXWz+GMum5uPvQ39qCmyYsAXBsNyKLYZcKLDhbUzc7GjtgfrZ+fhQOMAZuab4Q7yG5zSLAM+a3Nh3axcfHK2F2tn5OJYmxMVOUYEIywCEQbl2Uac6nBjVXU2DjYNYGlZFhr6vMiz6EQrbrHdgPpeL+YVWXG224vqPBP6vCGYdWpQFIVAmEGOSYseTwiFNj2/0TFp4QtHxQ1OKMrCpFWJVuVghIFOTYubGfH8ICJy1DAsh99vr8Pl8wqIEJrIjJcQ4jgO22t70NDrgyc4vqmFk5X4BUnguxtmneeRjJy3jnWgoc+HLKMGlTkmHG934SurypFl1I730AhJiD/vaoosuGJe5mqdZZJ40SdYL4FB8adRUYgwgyJQ+A1A/FuvUSEYYWRWqGCE37yZdCr4QoPWU+G3UatCKMqCYTnR4icIRbtRA6c/ArNOjTDDIsKwyDHxorHQpkeXK4jSLN7NnmPWIhxlEQgzKMs2orGPdyMLVuW6Hg/yLXpw4NDvC2NBMW8dXD8nD5+c7cWqqhyc7HAhz6KDVkWjzRHAyqps7KjtxTWLivD+iU6sn52PEx0u5Ji0sOg1qO/1Yv3sPLx/ogvXLyvBeye6sG5mLhr7vDDrNMg2aVDX48WambnYUduLK+YVYG99PxaU2NDvC0GjomE3aNDqCGBBsRXH2pxYUpaF+l4vSuwG+MJRUKBg0avR6wmhNMuA5n4/KnJ4a6fdyLv4WY6DScuHAGSZtHAFIrAZNLx1Wk2D5TiwHP89haIMdGoVIgwrxgDSMQ0nCDvBbSz9TSU5RhqLSMcOirAsdGoV/OEojFpJaEIoyocvcIAzEEaeWYed5/owu9CCVw624soFhUQITWTGSwid7nTj/RNd5+31phJRhkWE5fDywVa4ApGE+yeTEFISczPyTPjcouJxGA0hHSaTEIonHGXx4eluzCowY9Y0jG9KJgwFMUhRvECUuh4FoSeIOTVNwaBVwROMIs/Cu9eFkICSLAN6PSGoaQrZMbftghIbTrS7ROve3EIrOl0BUADKso042eHGRbN4QXXZ3HzsquvD/GIrej0hRBgOM/PNONg0gGsWFuGNo+34wpISbDvdjfnFNriDEXiDUcwvseLj2l7csLwULx9sxfVLS7CjthdzCi0IhBn0+0JYUmbH1lPduHFFGV460IJrlxRjd10/qnKNiDIcutxBrKjMxrufdeKmlfwxVy8swv6GARTZ9aBAobnfhzUzcvHmsXbcdEE5XjnUig01+TjS7ES2SQOtmsbZbi9WV+fgozM9oqglQmiCMx5CqNcTwpvHOuBWWMQzibAjmGqm3T/taYIzxWc32YVQsU2PG1eUjcNoCEPBshwe314nu20shFA4yqLV4UdVjgk0nbnrd19DvxjfNJmuk6lKMmEmWOsAJLhrBRetQatCKMJbjQSRJljask1aDPh4l2woyiIcZUU3rSDe8q069LhDotvWH2ZE4SL8LrDq0R1LIKEpKhZbyT+P8Bo2gwauQARqmoJaRSMYYUQLosB4CyESbDDBiDAs/nG0/byIoD/va8Yrh9rG9HXGg1QiSKMazBaarHTEssmmCo19PjyzuxHd7sn/voTFScYYnG4vH2rF25914my3J6PPK12cCOOPMFUJsWqC21J6ngluylCE/+0P899hIMyIjxPCK5x+fm4c8IXF24XH93n523o9IQBAjzskHiM8Z1ds7hF+C9esP8yI1aGF5xFeQ7DKR1lOPL8m2nlGhNAEo7bLc15iggZ8YbgCEXS5g4gy41vMKpMMJXIiDIed5/rO02jGjsku5qS8eawDnmAULx2c/A2Oo2zitXS6K7Nipc8bEheZcz3ejD63KoPWJQJhskCE0ATjVKf7vLyO1Bvmn2DqfDQo7sjj+LTVOfYDyQCpxI5Qe2mqwca+vwNNA3j9SNukEen7G/rxyqFWvm6WApm08L53fDB20KTLbCk4kpFImI6M+KyPRCJobW1FbW0tBgYGMjmmaYsrEEGHM3BeXisqWUj9ksnbG4yiZxK7KPxxC1GWUYNVVdlYUmofnwGNglRGnyc/rscbR9vP32DOE4J5fW99P9ocARxtc47vgNJkX+MAOl1BHG93Kd4fyaCgG/CHxb8zWUcMANSqwR3SZBGhBMJoGZYQ8ng8ePLJJ7F+/XpYrVZUVlaipqYGeXl5qKiowF133YWDBw+O1VinPIebB85braD9jf3i3wPewYn1r/ub8eLBVvR7Q2P6+qFhWKHCURZ/3d+MXXVDu7QONztk/2tUNC6szsGyCvtwhzjuMEOcDM39ftGff75h07C8pYtBoxL/jo8T2l3XH3/4hOZYm7IQSsdSmS4aiVgJZbhHkz80eF1m+rkJhIlK2kLokUceQWVlJZ599lls3LgRb7zxBo4ePYqzZ89i7969+PnPf45oNIorrrgCV155Jc6dU67hQlCGYTmcyXAsQSqa+v3i357QoNk+GJv86nt9Y/baR1oceOqTBhxoTM+SeLrLjT5vGIebHYiy7BAuI/nkLcQ8TEaTfzq7fWcgjGgswH7nud7zMCpebD71SX3GgpsZiUjwhCZfzax0ROFoRUWEYXG60y2mTAtkulml1AIXJhYhwjQhbQfzwYMH8cknn2D+/PmK969cuRJf//rX8dRTT+HZZ5/Fzp07MWsWSb9Ml3ZHQIz6P98Ew/zrSk3hoejgzrDLFYRBq4LNoBnR8/tCUTT180XOaIrCntguf29DP1ZWZQ/5eOmC++SOeqyqykn6OItefkprVbwA0mkmnxBi0lhg2xwBGDV8v7Kmfj+WV2TBqB3bFoKCZe7D09346qqKUT+f9H3yRfgmV/xTMsGgoijRqvf3T9txyew8LC6zj+g1PjnXixPtifGD0us00yjNR4EIA5oavK4mQ+mNqVomhJA50p4xX3zxxbSO0+l0+OY3vzniAU1XWh3+oQ8aIwKxyVS6axX+dvjDePkQn80z0roif97XjFCURSjKYll51pAuHyn+cBSnOwctZSyXWkDF77wNWt7tQmd4EuQ4Dnsb+qGiKSwty4JWrSy09tT3wRdisLEmf9gTsUICEjavqcSze5rE/3s9IRRa9eL/YxVE7fSH4QxEUJTh1+I4TnY+HGxy4NMWp/i/1A00UVGy9swuMOOyufk42OjA4RbeXbsj1p5iJJzplFuL6VivMIcvgjeOtmNxqR1VuaYRPbfAkTi3cnyKczjK4g87G2DS8i06aBq4fknJhBYY4SiL5/c2odCmn7JFSE92uOALMbigMmtCfxcTmcm3TZ6itMeCpDtdATT0ZjYldihc/gjcgQjqJa/b6eStMH0ZiEERFoqd5/oU04tTji1Jto0/rOxCSSaEAOCGZXyPMWlMykhpcwRwsMmBfQ0DePLjeriDieN0ByI42OTAqU53ytpGyZAKBK2axoXV2bAaNLhlZRnmxYqPdbqC+OepbvG4sQhw7fWE8Ke9zfjH0Q7srh+M2cmEW0bJ6iWNp8m0gB0LlOLddGoVdGoVcs2ZaYUSn9YutFgJMyya+/1481jHqJ7fF4piZ1wMXnw2abc7CI7jA9rbnQG0DgQmvPussc8HX5gZU1f/eMJxHD483YO9Df1T9j2eD9K2CH3xi19M+0n/9re/jWgw0xWW5cSgV6HA4S0ry+D0R1CebYQ+Awt3KrrcQZmVAQBcwUhGXBTx8RMNvT5QGKwxJ/QuSkayuiY9nhAqcxJP3/hFqSzLKP4tCCAuAxXufHFC7NndTQkWM2kG20iyhgRRo1XTuPvialEU5Fv0mF3AKJZayGRQroBQswaALCtqOJa9ZAw13nTcg+ONkkVIH3PFGuPS26MMC7Vq+PtPNU1BuiWxGzXol3wv/Dj4XlLD5UyXGx+c7E64Pb4UQK9CAoXw9bgDEVj06glnkZBOH0KPrKmE9Bp0+MMpjiSkIu0r0maziT9WqxXbtm3DoUOHxPsPHz6Mbdu2wWazjclApzKuQAThqDwI+G9H2vHeiS68Nwb9xtJZXIRO2FLSCd491elGY58PO2p78NyeJpztkZv0u1xBWQ0jQVA4/GHlcSV5yfg0eQFhUTJoVJhfbEVlzqAQEgRX/Gc9Evq8Q086UuvXcNxIwti6YrFR2UZtgmUkWfC3VFj4QlG8fqRt1NWHpZafAqsuYZyjYagg4ijLTfiYoYCCRUgfEyS6OJH/3J6mEb0fa1x8nlLT3c4RVhxXEkFAotW1X+GcZxgOZ7rceHZPE3acPT/B+unAcRzaHH6ZUJiKWXDSMijjFWM6FUjbIvTss8+Kf//oRz/Cl7/8ZTz11FNQqfgLnmEYfOtb3zqvjUmnCn2xnVaYSYzRaRnwwx2IJEyEoyFd60T8cQzLgVZRaOrz4VCzAxtr8mGXTMiuQARbT8kn1fhJ1huKQqp3/CEG7oAPbxztUGwmmszqkMwFJCzaVy4oRHm2UXafYFljOcS6aY9sd9jU50tI01ce4+DY0/nMXYEIXtjfAg4cvrqqQixjX5plSDjWqFXe+Us/l511fWhzBNDmCGB2wcgbaIaYwYW+2z1oFciEPhGCfYX+SEr0ecNw+MNo6PPh4lm5Yx4MPlyU3LdCcH68gPWFGdEK6g1F4Q1FYTNohnxPmjgrUq5Zl3CMJzC8jDtp93El4i1CA75EIRRlWbHEwWdtLlw6Jz/lazr8YdAUNeLEi3T57Ud1CbcFo4zMVT4VkG58xjPOdLIzohihZ555Bt///vdFEQQAKpUK9957L5555pmMDW66ICwuyWIunt3TlDRWZiT4YinKQ5XTj3f/CBabfxzrQLszgD/tbZbdn07/mPj34Q1FcaCJT6NX8nEn2+Ums7AIAjJ+Jw7w7gXhPX9wsmvExSuTVaaO3+lLJ6lIGrvRVw+3IsywiDAc9jX0i5aG+Ew4AMgyKceeyFLRR3HOcByHY61OnOpwJ62WnAk7jXDO6zUqVMQJV4FDTQN470QXars8E7Ku0L4Gfkx5lkFxIojuLFPigh9mWOyp78czu5vwyqE2/GFnY9LK0xzHIRxlE66tPIsOxTY9n8EVO9fbnQF0OANoHRh6QTzZ4cLvttfh7c86kx4TlJyzUYYVLZRSmvr9MgtvKmsXH7jcjOf2NGW0DhXAF4Kt7fKkfN6xsJgM+MJ4bNs5PLbtHBiWw47aHjy27RzazpMokW58ejwhNPWlFyeU6c9/sjMiIRSNRnHmzJmE28+cOQN2mMGwhEGLUOtA8oU5ncktHXo8QfxlfwsAQENTiouswDufdcqsN1GGw5EWuSXEJ6n7ko6FoCcu+LrfF0KHU1nsOHzhpH3BklmEBAuDkhCiKEpM+23o8+GtEQaYJhOl8Ttm6RjTid3xSYrZnenyiK7J4cSISV9nNDE8Hc4gdpztxdbT3TjWqlwkMJOuMZ2axox8s3i7NAPKJQlEd06wOIjGPp94jeRLhJBw/qlpGpvmF8geE46yOBRnUWxIsoB9cq4PT35cn3DdGLUq3LCsFHddVI3La/jnb3cG8OrhNvzt0/YhA9k/PN2T8nUBuXhPVt/p47O9UEs2VLUxN2yUZdHQ65Wl93sk32MmK20DfCHY90924VibM+l7z1SpAVbirv3zvsHN4N76frGg5utHzk/V9/gN4T9PKbs5peyo7cH/7mxIq+2LO0OxohOdEQmhzZs3484778QjjzyCXbt2YdeuXXj44YfxjW98A5s3b870GKc8fd4QQlEGW08nP4lHWkqf4zg09HnFStGHmgYn4GCUxWUpTNm+MCNaawCgrtebIEyk7rxUk9vaGTmKtx9ski8I3e4gTna4wHEcHIHki15EQVgwLCdODLok4kHaQiA4wpiBZFWx44ckEyUj2IEJ7SaURF0y5FaokU9g0iy4ZIIqE4Gxwi5dq6axoHjQrR6Jsiix8y5BqYtxogTj9nlDeOlgC3ZLMq2krlhp0HJVjjytfTjxYkeTWB91aho0TUGvUcGk41/LKxErmejuLb22pRWn45HGKzX2+uAORLC/YQBvfdYp64smjTnMdLaZcC039PmSVluPj3mU0uEM4EzX0H0eGZbDX/Y349XDbQkCoTYuFs93HoqDxou7Yrs+yZE8EYbFsTYXwlF2yAK+57o9eHZ3U0K4Qzx1PV68fqQN3vPQLHysGJGz/Te/+Q0KCwvx8MMPo7OTN60WFRXhBz/4Af7jP/4jowOc6oSjLDzBaFL3g4DS1MlxHKIslxA/IOVcjxfvnehCllGD21ZXyhZVq16Nihwjimx6dLqC+PyiIlTnmfHYtsGq4FIrR6cr0WLFshwYloOKplJObvnW1BeogNCB3G7Uylp/xKNkIZPuBHVJPhPNEBWmWZbDuyc6YTdqsW5mbsL9Db1ecdJdVm7HrHwLXj3cCpaTix1fKCqLeRlJNpdgebLoleMpbltdgefj3JOCFYrjOFlPquGSKpNPgOM4RBg25fk3FFILnlTkmPRqCP/FZ0dNBN493gmHf1AsFlh1KJCc43pJAc94Ua50nQxX3kk/KyWLYbJr8US7S9HFpUSEYRGOsvjwdHdSIW/SqWTn9tkeL872DJbhaI5dpx3OAF470jY4vjEKXG5zBPCao03xPm8KYfLqYf4x2SYt8i3J5yp3MBL73iMyC67S84eiLEyJoVwZJd46rRS4L0UaDpAszlBgf6zy/+kuD66YX5j0uHeOd4q/b7qgLOVzTlRGNIPRNI0f/vCHaG9vh9PphNPpRHt7O374wx/K4oYIQ+OMWT2GymhgGA5RRp7t9Pej7fjDzoaUu7/TsRRrYdKWTprrZuaCoijcuLwU31hXJbojrl6ofNK7FYIxd9f343fb63CwaQA97uQ1h+Ivuo01qYMq+7whWc2aeHo8IfR45BO6sKhqVFTSNFl1XIG+eFdLq8OP+l4+GFrJCveWJKZi3cxcFNr0YiC7sFh4ghH8cVcj9jYMjl+472y3By0KIi7+vUixJnFfZhm1+O6GWVhUMpipKSxK8bFV/zjaLrpg06GlP7UrVkVTYDneNfTKoVZFkZwOg1Yv/vy4YVkJZuebcdHMXDQquG2SWR3DURZNfb6MmPHTeY5468KiErus+GOqNHZFETAKQ5de4bW2n+kRLZf7G/qxv7EfHMdh25kenOwY2vIB8GJqZ10vzvV4k7rQSmyGtGqD/f1TuatoPOoP7arrG9Ky7vCldhdJvzuXQu0wKZmq6dXlCuLFAy04ptCAWBA+QvD5gDeMcz0eMCyHKMsmCNhWx+B1OqTrfJjnZFfMmj8ZGXVBRavVSjLFRoHgpx1KCDkDEfxhZ6OscFrrQAARhktYMDiOw3vHO7G7rk/WUyzKsLKTPzsWcEtRFEy6wRogs/KVM4y6FRZr4bX31PentEDEFzFMtesCkHTRlsZhNMct1oPxJskXoXgh9PZxebCo1Ioj/bvdEYAjzjIhfF5CjISwIMSPC+CFkDsQwXsnuvD3T9sTFlulxwgMFdR+6dx8zI+5lQQhFJ+B1dTvx1/3t6QtFD5L0kVdQPg+3zvRhU5XUKx/pUS7M4D/29UoK9gJALVdHhyJVZEW3mFplhFXLSyCSadWvCaiSdxKf93fjH8c60gZ85J0fI6AaNb/uLYXz+1pGtK1FO+hU9EUjFo1VlfnYM2MnASL2ipJJXQlETAc16k0KBtQdp12uII42enGwaYB7GscwL6GAcU6QAL5Fh3MOjVWVGTh+qV84dFIlEN9T+rPM8ywSb8TKfEW0XePZ74sSDoI7qpddX344GQXOE5enmEoUSez8g4hdJTc98PB6Q/jSIsD2850o8cTwo7a3gRXmOBmFebyYJTFu8e78NLBFvx+ez1+t71OVgZBauEfKk4rHR0U704UYs8mGyPOQ33ttdfwyiuvoKWlBeGwfIE4cuTIqAc2XXDFrCx1PamrSQuF7ARhI5044xfKLndQZp4WCEVZMQCyxG5AjkIKrsA1C4tEk6fAUGtoqvcQb77PNWtRnm1UtI4A8sDhbKNWFFlWgwYOfxgRhsOe+n7MKbTAGnMdCYtXqpiaeJEUXxtFOmEHwgzMOjW63UG8dqQNRq1K1j9KQKjpI3wn8WJLuE9qtnYFIrLSA9oU7qV04mIEMcbEJsZkk1xTv3/UrRgA3vWTroFpf0M/vKEo3v6sE19aVoqSLAP84SjePzm4GCpV3r50Th6218pr00SSLFTumJBp7PNhRp5Z8RglOl2DLhvp+XikxYELq3PE9HehpYpBo8LS8qwEq47wnSdr/XJhdQ76vCHU9/oQibKyoqIAb7ldVp4le4ySGJtfbMXKSvlr0DSfBBAvsPY19MvikVz+5BaMi2blojRWfFQQC2GGBeKGYDNo4ApEsKDYihMdboSjbEIgdzp4Q1FwHIcudxBNfX6srMoeUvBngh5PCCatWix/sbIyW5Z2PpQglboVIwyHHLNWsb4SkFwo9XtD6PWGMKfAkvLa3tvQj7Pd8jn1nc86cc3CItHdKlzn9rhyBNI6ZzvP9WFTzLUljVsaTQyh8NrJalBNNkZkEfrtb3+LzZs3o6CgAJ9++ilWrlyJnJwcNDQ04Kqrrsr0GKc03lAUrkBEVrFX4NrFxchJkiYt3RnE1ypJFowZjDDiBD4zP/VikSqbbCTET3IUReH6pSW4bE6+4mtJdzFXSVx1NAUsKrWL/++QLJTCxW83Jq9RsqzcLqthUmjVo9cTEneF0olQmGSE9if+MCNWpf78oqKE9yaIKJXC5MawnGyHJQ06jzKsWIyupsiCOSOo+SOIMWFHm8z1MJoyDLLilMOIC5Jadt49wYvr+Jg4tcIiKP2eBTzBaGKZAsl7NQ2zxlCbxFUgFeUHmxx482gHOI7Drro+vHO8EwebHPjkXF/M7RAvhodexAURXtfrFUWQcO4oFehUatuysaZAsaaYXqGpcPw84E4RzCq1YKWKD7ttdQW+fckMMcOvM814IyUCEQavHGrDgaaBhGzUseLtzzrllkYKMrEdL4TixYw0IDjCsCnT0JPFBf5lfws+ONmddBMoEC+CAN619fTOBtkYgNTf2ZkuD1iOQ6crIBOtQ7knqSFsQkPFI00mRiSEnnjiCTz99NN4/PHHodVq8cMf/hBbt27FPffcA5drcvoIxwtvMJpQcyLbqMXnFhWhKteEVdWJO0yO42QX84HGgYT7lQhGWIRiJ/9QzSzNupELofWz89I+dmGpDV9fW5UQByPUViqw6pBr1mFuIS8OlldkybrRS1NyhQszVfHJ0iwj7lhTieuW8IUbu9xBvHCgBSc73IiyrMySIvwtXbSFuU1q4RKtMbE7lSbALndQtjBJXTjSmA2tikbREJkfSqhi36fgpkinblEylM4fmgI2zS9ErlmLtTNyoBkimJphOdT1ePHigRbZ5Cs8dbwJfU5h+uIvvt6U1F2hZI1LRapeZs0Dfjz1cQMONztkrxmIMAnXR7JK31KExUoqvlIVYxJ27Fo1jRl5JvGcVSKd1hqpRLD08clEnV5Dg6YoqFW0KITTDclS2hxIg4v3pIgHFFCqCB+KMnjjqHKqenaSTWRQson8a6yUiIDUnVXf68WTH9fjoCRzVmqlizCJMThSjiXJ+BNIpzq9EvElTQB+3tCnuCad/gj2NcjXiaFcY8lO6QjDor7Xi2Cy+mKTMN1+REKopaUFa9asAQAYDAZ4PHwa3te+9rW0u9QTeHzhqGxRXVmZja+trhDN+0qCpN8Xlpnm433/ya7NYHTQIjRUVtBQGQWpWFJmxw3LSoblgknWGVpYYK6YV4Bvrq9GvkUv24lI4xPYFBaZeOIXjn2N/XhmV5NsQk4WbwPIK/3GW4SUYibanQF82qq865VOzBoVLYuDShd13BiS7fbSmaROKATT3rKyHHqNCl9dVYEVldlDZoodaBzAO8c7E9wmwmcVn7k0awgLpZT4CrrSwp/DLTMx1Kmi9DnW93hRmSsv/qhKQ4ApWdGkwi3+u5G6PT63qBgVOcmvp1TxPwKpAlmlY0vmrpHG+Q0nUzASF5soEJ9unerc7HIF8eTH9fjT3mbZd3yoyZE0vi4riWVY2kg6XsiEJUHwZ7s9YDm5SAvIhBAnWtlyFJrrtjoCCEYYhKKMuGFjU4Q0jAThHFGrKKxRyHIV8AQjCZvfVJul1gG/rIq8NHZq2+kevP1ZpyxxRLpOTfRGvEqMSAgVFhZiYIBXl+Xl5di3bx8AoLGxcVKqwfHEH4rKDJDxKl1pp/nX/S2iuwZIzCpKVjH5dKdbzCYaagdJURTKFFo7pEtplhHZCv2QkpFn0eFf189IqIMh7MAoihLHfJHkgpdaxoTJNp3GivGWA1+ISTD1ekNRbDvTjeaBxIBR6SQriJBTMQEhxLFkGTUoyx78DJN1h5aaoG0GjWL7hKGQBmy3DPgT6jMJpFNk8aMzg9YamuLdh/FjGsqimKwFiRAbEk86cVAz8kyxMfHHugMRtDn8sgU1VaxrlGVxqsMt1tSSPtdw2HG2V2YJsRk0aZ3r/kiia0oaRB2/gZEucsMhvrVMsueXEr8xWlpmTzhGKoSshsQNmrQPnZRkFpu2uHkqVX2lc7Geha5ARFY9OVWtntkFFmyaV4B5RVZ8TuLKFooeKiGdA6Rzi5AVKbUOSy3TyT7zlw+14qmPG/DM7ibsa+gXU9KB9DZsSkhjIIXPTKPi63B9dVW54mMCESbB1ZVKsPwtLstP+r6FekmCRU+ronHnuipR2KWq1zRRGZEQuuyyy/Dmm28C4Isr/vu//zsuv/xy3HTTTbj++uszOsCpjj/CyFwp8ZkyySbBT2PZNgBgirMaxVetNcWsO9KFOB2LT6odaDIulLjyllXYYdWrcUElHwR604oyGDQqbEiSOs8X1bPJblNyMxXbB8WFdOIajkUonZiOHbW9ONHuTqgXYtapZR3EhTTaLncQ/nBUtAiV2A1YNyP5Lk2YSKTDtRs1I6rLI8YIMZwsVTl+gt5d1z+sDKU711XhyytKE25PFSMUZZUtAAJDxUYkQ/jeA2EG7kAEfz3QgtePtMtjPFK87skON7ae7sYbR/nMy9Fs2oRzbd3MXNy+uiKtuktKvcAWlkpKH8QtTNJFbjjMKxp+Fm+8dULJPStt6xK/kdKqaNy4vAz/cnG1mHUmIK0c/8311WK5B+kcBqSu/CwVytIq19Ks2LmFFtxz2Ux8blERrl5YiFn5ZswtsuLyeQWwSObI9hStdaSudmlZAqGwpXS+kf6drHeaUxKgvr9xQFagtscTlGVxnehw4aWDLUnF3ZeW8dehMHe7AxHxWtKo+DpcuWad4twWirKoi8vaHE5hz1SZgUIWoxCntu10d1q9GCcSIxJCTz/9NP7zP/8TAPDtb38bzzzzDGpqavCLX/wCTz75ZEYHOJVhWA6hiDz9dEncTiyZ+VTqX0+0Ig0+pjzbiPVzEmN24sWTEiOx3EoXSKNWjc1rq7AmJgYKbXrcdVFVgtiREj/pS4OSBeIvdMFqJCyC6ZicR1MEMN4a4pFYJHo9IclOnkaeRacYyApAbPEhFULCAvPN9dUosRtwqcJ3p4QgmOPTxytyjKgpksffdKXoUh4vDgwalaK1piCuQKbUWtDUl1roDCc2QhDRN19QBmPsNfyRKF493Ca6eaUL0rFWZ1KBI1hDBavUSwdb8fEIO6YLsSQ0lX6163Wz5KJ4YYkNKooSv//4hSkixvMNfa5K63INt6FpfDo+kPj9AqnjBheX2aCiKRg0KpRlGXDLSuXCejq1Kunc0+5ILlCkyRPC58Jy8kxMfexcnZFnxqx8y5BFJwW+u2EWbljGizepyJLOI74QH1Yg3agK846apmRzUrrz5okON/68rxnvxFxM2073oNsdShovJVzjDn8EEYaVWdqkc9I318/AghKrbBOkVLuq3RlQbKSrRKqCsIIwE4rVtjoC2FXXJ16HTX0+fFzbm3QDNpKq+5lm2KtBNBrFr371K3R1Daa+3nzzzfjtb3+Lf/u3f4NWm747ZLojXEjCTqjEbkiYlNKxXPhCjGzyL5G4tMqyDQk1e3LN2oS6PkokOz11alqx6jIwdOzRUIuG9ILWqmjFFP/45xB2UIxkcRqK4bob5GOUv0epkA1FB4WtRkWBoihcWKXcXqTHE0KvJyQzWQvj0qlV+NLyUsXMKSWSiT+lW4Vu8qFY/IKU+MU42fcVn+knjSFIVcEX4Gu4pMuaGbn47oZZKLDqxc7hLn8k6WtEWQ4vHGiR7ewFpNdIIMIkTfuuzjWhIkfZ1SEgXLvDca3FuxdXV+eAoihxAYkvDRBJM7EBkIuUZC6qeFZWZqPYrsfFsxKvZbNC9l0qQVZkG5xzKIpKWScs2fv54FQ33jshL9nR3O+DLySvvB+JcmBZDq9LKlUDqa2UVoMGRbZUY+If64yJDEBuXWx3BtDQJ7eoCC4gm0EjW8yHu67X9XplgmTAF1YU81KX2KEmh6yyeXzM4oa5Bbh+aQkWlPDWQWkNL6lQ/vO+5oTXUnpt4fpWCrAujH2u8XMq30CaxT+OdeBomxMnFDKjT3W48eTH9QkJP+ebYQshtVqNX//614hGJ29fkYmCsLsQAh2VgvvSyUYJRBj4JBOFVP3rNSrYDBqZpUlo0jgUyYrKfWl5KRaX2mDUqhJER0X26GrUSIVUMhdaPH/Z3wKG5UQXVjoWoXQ+12QkCCHJAhaKsuKCJrxGqgyrd453iin5AGQm/OFQmcSNWZVrSqg7E46y8IWieGZPE57d3STrnSad6FKVyy+06ZFj0iI3FiQalTSiHKs4QaHuUqo0cIC3OD2zuwkeScPICMPK0pFT9UXSaeghNyAjEUIJryM0Zo3L+BMYjmtMKoQoikpadkNKWbYBNy4vE+sHSVGKs4sPRC+RuKgrhxCOUuKvT+ncdLbbK7oIj7Y68cbRDvxxV6PMBRZmWLQ7A4nNmof4KpSyWYU+bdLP+O2YhYaJ+z7ia+YI4kytomSbmaXldgwXqXWnyx1UjN8xSzYfUhcbkNziJWx4pYHPVy2Qdw4QXMUCSkJOODel1fJnF5ixZkYOlsQ2a/HnaTjKysSPUjmIrbH2LQ//s1Zx/OeLEa0GGzZswMcff5zpsUw7BMEiNDRU6seVbmaBNANAKoSEmjTrZ+fhS8tKcdWCwrT7fuUlCdrVqGioVTS+srIcd66rkt1nHmX9IalfPlVNmHgx99rhNtH3n06w9GgyNuJ3tIslE3kowiTs5ON3qtIduysQwe46fnKpyjXJYo+GQzJLnEGrgt2olS02/jCD5gG/aOp/98SgdVcwgatpCoUpzhM1TeOrq8pxQyxugeMGJ9BkFXWTuVaGqmklYNWr07JkCjyzu0lc1LbXytP1T8c1nJQGB3McsDSuuKGAIF6ERXC4evr21RWoyDbi+qUl4nkqLCDxu+3huMZyzDpcXlMgpthfMX/ozc5wr4F4i8oNy0pwy8oyfPvSGYqWw2QWmng3i1RQAUC3J4SXU7gtj7Y6cVqhQWrREPOakrvvxuW82Jde00LcTbJ4M+FYqSt+TqEFeWYdVlRkYc2MnLStcgKeOGGu1Hsy1eYtWRsepXjJeNEUH7OnFEP15rEONPf7ZHFd62bm4oLKbPE8jrcIhaLy8gLCORKKMuhyBWX3pXJdng9GtGpdddVV+PGPf4zjx49j+fLlMJnku9Frr702I4Ob6giCRbAMKQUwpztXSXcQwvPdckGZbBItGWYW2Mx8MzbNK0CuRYcXD7SIC52wW04nzmi42CRWMYtCZorAvGIrtp4e3KFJ07FHmo2hxOY1lXD4w2BYTkwXjV+Y1szIQUOvjxc19f3iYi2ImnjhlGXUynZoAqWjyNID+Ikp3u0kuF2k5vADjQOyhb9lwA9PMIIud1BsfZBOk1iKomSTX5RloaJVOJjEzB3vzlpSasecQotoVUrn9Yps+mG10Wjo84HlOJzulAuf+K7u0ok4ynIosRtw57oqGLUqHGt14pNYAUyDVoVQlBUtsMONNbMbtbguLphY+AzjhdCnsTGm26B0XvFgkHS+RY/Nayux9WQ3lpbbEY6y+CDWRVyoQp2TZkfQYpseq6pzEgTLUC6wr64qx7N7mhJujz+34gXZa4eTt2sRiP8+N9bkD+nOjOfbl8yQXKOJ32Oydhvx7mM1TUOrpvEVScZW/DVelWtS7J2XjGCS7/zmC8rExtSyMSQ5D+M/2xl5pqTFcqMsCzVNJ/SF4+/jEixH8fN/fEPrVw+1ycpMCNbZVw+1od8XxoWSjMmRVCfPJCNayb71rW8BAB555JGE+yiKAsNMnYqTY0mYkccIKbWG4IP/TElTr4WS99LJUny+UapsiqIwN5aBYjcMtrlIJ25ppNAUhZtWlCEQYcTWGcmYmW9WbOuR7k53Vr4Z54ZobWI1aGA1aGQ+/PhJU03TqM4zibslIYBTEEDxu2VDkoy9VDEM6bC8IitBCAm7tfnFVnGHHYqy2BcnVqIsN6L+T1LRGWU4aFWJVZeTYdCqxPiCdMk2aUUhtLIyO8FFoESqFGsBTzCCOYUW1HZ5sLyCtwYJFizp9xd/jY4m6F58DrEquPLnNtJq4Fa9Bjcs5y12oQiDbKMWlblGXFidA5bl0sp0A/jNSbL08JSvb+DLR7QO8BaGK2NtHoySeWl5RVaCwBouWUYN5qdIwJBSmmUQC1pKxYPS9yhYLOYVWXGqc9ACVWI3yKwmSsHp8dm/s/PNUNGUOF+ZtCowHJc01bwpiWgaruUkfi7Ms+hAUxTuuWwmfvtRnXh7pyuA14+0Y3kSS2g8F8/KTXALK8UISd3RgkWrPzaXxpcx+PBUNzbOSy9sI9OM6CpmWTbpDxFB6SPEVQi7y2Rm/8slJ8fNF5ThG+uqcNWCQtx9cbX4mAjDwh+O4u3POsQdS6qeW8NFekHF7z5GO5HFU2jTp1WMce0M5SDkkdThUUIq+KSmZ6WGsEqmbGmfKinJvufRVPMeCo2Kxupq5c8LGLrKbDIoihIF35vHOvCcxAKwvDwLM/PMKLDqsLIyGxfFBeWmEwQcj3TxzjINLkAGjSppdepud2jIOj/BKIsragpw59qqBJegVKDGW/IysSnQqGMWIcniKT1n4j+3kaDTqPC11RW4aFYeNCp6WJuk0cTTuSUlA4Tvp6bIigXFVmyaV4B1M3PTFmTJGE5E2vVLS/D5RUW4Na7ejoqmsCwW2yPEagpCaEa+SaxhBchrPwHKWXfS62n97DzMKbSgQHLcF5aU4O6LZyQdZ7L2FUpz+sKS5CIwXggJx1IUhW9fMvj6u+r41jHxG4tkc4ZS9f6hNgVhhsUHkv6C8WMbalM6lozdzEsYEobl4A/zaZkU5G4hKTq1CpvXVEJFU6I5cnYs9kdYTMIMizNdHpnlaDj9oIZEcs4mBEjnGNHuDJyXpolS7AqL2+cWFSUtrR+PdLSzC8xYNzMXH5/tRXWuGTlmrcyELKsbpLBDVxISQnBpvFBMFhCdCT/5LSvL0Bhz08XHRMwuMMuCHaW8eCDR3J4uappGhEnMwlo7M0dmTTketwOcPYKeatJF06IbvF4CESap8P/oTI+4sKydkYPdCunJa6pzQNOUYoxbgVWPLy4tgdWgkQm9TCHExcVXLRaIb6h5vhmJYBVQCpxX0RQ2pJmwkd6LpH8oTVGoTtKUd2a+GUdanKIAEn6rKAorKrJR3+vD/GJrwnmm1NqiOteENkcAZp1ajM9bWp4lnntCSY3l5Vk4HOuzZjNoYNWr0eoIiHGjAC/yhZgvpTkivgitFOmcfN2SYhi18jlNp6YRirJJwwlWVGQpzhlKoifeNRZPjzuIDknpjvi6WXdfXJ3y8WNJ2kLopZdews0335zWsa2trWhpacHatWtHPLDpAMvKq8emDIZLMhkKC0MowsoaeWpVdFpBw+miFPQmsKw8C3q1CuXD9NGPBcPpPC7lqgV8vaJkrT4AvljkvoYBXDY3MZtNqRaGEGKgVtH4/KIiMcZIqSQAkBnrQr5FnzRuw27UosimF+vppEIo3pYOSVP3486T+DYUIxF+0kVIWp/JoFEl/fykAmN2gQVLy7Pwu+11smOyhhDPZUlcQ5kIRxM+B6mbRMhKU9HUiAPoR0uOSYt+X3hYfeDiSVejrJmRk1a/MSWGGxuUDGH+FYKgGTFxgEahTY8711ZBr6UTCmMqnceLS+0w69Sy4q8qmsIXl5YgGGFgibn9i7P0OBxrd2bQqMT5XGgbU55txHVLimXX0tcurMCf9zUP+/0pWd4EIZQs4y7ZGqIkjh2B1DWJPHEuamkc1CNfXpzR9Wq4pH2FPfnkk6ipqcGvf/1rnD59OuF+l8uFd999F1/5ylewbNky9PeP7KSeTjAcN7jrGOFJIChzqQ8bGLqez3BJVXhLRVNYWGobdiG3ycbKymx8Y12VoiVDKZ5JapkqshtgM2hQU2RBnkUnuv60ahoqmkK+RZd2Yb7RkK67dDiNX5W+d6F+iZTZBWYx1kSvoUd0zkuzCvUaFb6+thILiq24YVkJlsXFN8S7DPQaGiadGiqawvrZeTBoVJhfbE1wk6RLaZYhI25hgyiEBgWb0H8uVSPNseamC8pwx5rKlAHRQ5FuJYULKrNxc4pyDQJfWSn/ripzjFibosfWcBDOR1+IwZEWhxizJdxu1quhpumEWBilbDSapjCrwJIQUFyWbcQsyfwhtdpr1bQ4bzti8ZhCLTIp8RbvVMH00srWSt+jIOLiSwUMhVKLJrfEUq7kjYjPjBNYXGpDzQiqoWeStC1CH3/8Md588008/vjjuO+++2AymVBQUAC9Xg+Hw4Guri7k5ubijjvuwIkTJ1BQMD5BT5MJhuWGVQ1ZCUGgJGtumSmE3aE9iftuIvA5hSrUqVhSbsfZHi+q02wOS1FU0ky51TNy0DzgF91mJp08ENigUeGONZXi/59fVITaLg/sRi2yTdrz5lZMN7h3OPVxFpXaElJuFysUglTTNK5fWgJXIDJi65f089drVAluFpNWBV+YwReXlqA37pqYGQtYBfjaNfFV3NNByP7JNWvF0gGjRbBsyYRQzDo0nmnFGhUNm+H8CbGhSiPkWXQJQn5VVU5GAtYB+Zy581yfmMUbf21KX291dc6oNp3SuEA1TaHAqsfpTo/4/adjDZyVwsU8u8CCQ80OlNgNinOMMHalxtJCvaHlFVkJLTOU4hkXl9mxo7YXM/JMuGJeIRr7fHj/5NAJGJnetI+EYcUIXXvttbj22mvR19eHXbt2obm5GYFAALm5uVi6dCmWLl0KehSBdenw+9//Hv/zP/+Drq4uLF68GI8//jhWrlyZ9PhXX30VP/vZz9DU1IRZs2bhoYcewtVXXz2mY0wXVmoRGqE1IFkG0nC7cA/FlQsK8WmLMyFQcLy5ZHYe9jb04/qlJYo7s1QU2Qy466KqYdWmSQbfmb0cT+yoB4CEIobxSDPyzifpCJCvr60c1nMqCclUk9toLIe5Zi0Wldhg0KoUJ/ZbL6xAIMwgy6RNKEq3KkmF7+Fw+bwCnOxwYW5h5r47QexIKwULRS51SdqzTBYWltiwt6Ff1nw4GcnSur++thKnOtyYX2xLsMYka18zEuLPWUEcxF8zUiGUrH5PukhDHiIMmxA/qEnjek01f+VZdPj62kpZbJAUwcLqVIh7FKy3Ss+vdH0vKrGhwKJHrlkLtYoWi1UORUZjWUfIiL7F3NxcXHfddRkeytC8/PLLuPfee/HUU09h1apVePTRR7Fp0ybU1tYiPz8xbmPPnj245ZZbsGXLFnzuc5/DCy+8gOuuuw5HjhzBggULzvv442HY0bvGLqjIRnN/Ym+nZGbIkZJr1smy1yYKi8vsWFRqG7FbKdkEMRI0KhoXzcpFfa93RIHA5wOpPF5Wboc3FJWluNIUxPiFdFGr+OKKf93fIt6WyYxFKRRF4VKFGC0BvUYlCouyLCPsBg1YjsPtaypHVQVawKBRYUVFZjcDwnh7vSHU93pRlWvCR7ECkHoFF8RkYkVFFgpt+pTFOQUoisK1i4tR3+vFyQ7e1V9k08Oi12BVLHspfoOXSYtZsnM23uIknastowwHkJ6TUZZLeD/JrF0Ulb7bMdX1nEpoC59HuksTRVEyK3i6381EsAiN/wiGwSOPPIK77roLmzdvxrx58/DUU0/BaDTimWeeUTz+sccew5VXXokf/OAHqKmpwS9/+UssW7YMv/vd787zyJVhMyCEjGmq7qnM+YitSZdl5Vm4cXnZuFdKTYZ04vWGogm+/pH2P8w162SNPzPlrhgNWjUv0DIlgsYK6Y77k7O96HAGRNfIRFgkRgNNUyjPNqb9PqpyTdhYU4BN8wuQbdImVJCP/x4zKbiTnSNKlo11M3OxuNSG4lHW/pLCDEMIZaqWWzKhnWvWivNq/NqUTvsWYGhXpziGCTBXTpqrLBwO4/Dhw9i4caN4G03T2LhxI/bu3av4mL1798qOB4BNmzYlPR4AQqEQ3G637Gcs2HqqG1/5436xWudIhZB0IrAZNGJNi6vj+skQCIC8BkqU4RKy3UYT/CvNhpsowkOtoifMWJIhde+YdWrZdxLff2y6MLfQiq9dWKGYzSd1pYz1JmjD3HzF11hekYVL5ijfN1wqYi6omfnmBFdfsubQgkBck6SWWrokswhJA6ula9PScju+tDy92Lh0Bc6sNFvsjCWTpo5QX18fGIZJCMIuKCjAmTNnFB/T1dWleHxXV/IAri1btuDBBx8c/YCH4LsvfSr7f6QxQtIdPd8ELzMZFISpiTQmwahTYVl5Fup6vJhTaIHdoBlVCYRCqx5rZuRM+ezBTCON8zPr1LIeV+OYUTxhWTcrFx+d6Rn6wBFwxbwCfHi6W7SMjqZ0QLpcOjcfvZ4QZuSZEtxdySxCswos+Ga2cdTdA5JZhKTiR7rGlGcZ0xY4yTb3G2ryUZ1rwtufdaLAop8QFv1JI4TOF/fddx/uvfde8X+3242ysqHTOofLf9+wCPe8OCiGRmoCl55s57ugIWFy8oXFxTjZ4cbq6hwYtWrcfXF1xmp4XDBEkDghEZ1ahepcE98XDfJUZtMog3GnIgtLbNCoqLQLpw6HmiIr5hZasKuuDzq16ry4eG0Gjbh5iNcEqYpZjlYEAcmDzaWNkKXHDHeNuXF5KXyhqKyxc02hFSqawpdXZH5dHSmT5irLzc2FSqVCd3e37Pbu7m4UFiq7gQoLC4d1PADodDrodJlp0ZCKq+JcV5nIXJoI0feEiU9lrgmVkkyv8SxkRuCZmW9GQ58Pna6ArH/eUNmH05VMZu3FQ1EULpqVN2bPPxzGWohJhQ1NAXddVA2nPyILepZahIY7V4gFJU8kb60xERixEGpra8Obb76JlpYWhMPyYntKzVhHi1arxfLly7Ft2zYxY41lWWzbtg3f+c53FB+zevVqbNu2Dd/73vfE27Zu3YrVq1dnfHzDJf4ET5YGnw5Ly+xo6vfJuk8TCITJg1hRWNJaIc+smxCBpITzi0GjEquhJ4sRyhTSGCw+RkmFQpv8nJNZhEbpxso1Z96KlwlGJIS2bduGa6+9FtXV1Thz5gwWLFiApqYmcByHZcuWZXqMIvfeey9uv/12rFixAitXrsSjjz4Kn8+HzZs3AwBuu+02lJSUYMuWLQCA7373u1i/fj0efvhhXHPNNXjppZdw6NAhPP3002M2xpEymp3fxbPzcDEmxg6GQCAMHyVrbq9Cc1/C1Oeyufl45zjfjicTnoJUZEn6NSr1bgTkQc/MCOvTXTonD/saBnDFvImZxDMiIXTffffh+9//Ph588EFYLBa8/vrryM/Px1e/+lVceeWVmR6jyE033YTe3l7cf//96OrqwpIlS/D++++LAdEtLS2ygo5r1qzBCy+8gJ/+9Kf4yU9+glmzZuGNN96YEDWEAODJW5fhNx/UYu2M3Iz4ewkEwuREoxAjOG+c2w4Qxgdpuv75SDz48opS1PV4sTyuRY2ANFVfqbl0OiwqtWNhycjrvY01FKfUHngILBYLjh49ihkzZiArKwu7du3C/PnzcezYMXzhC19AU1PTGAx1fHC73bDZbHC5XLBaMzsxHW11YvsYZT8QCITJgy8UxR93Ncpu+9f1MyZ9HSHC8OE4Dp+c64OKprAuQ33URsvLB1vh8Ifx9bVVY3JOXrmgcEz6jaW7fo/IImQymcS4oKKiItTX12P+/PkA+DR3QnqM1t9KIBCmBiadGp9fVIS3PuNdIisrs4kImqZQFN8UeCLx5RWlYFgurd5nk5ERCaELL7wQu3btQk1NDa6++mr8x3/8B44fP46//e1vuPDCCzM9xinLGLdlIxAIk4jKXBPMOjXCURYXVCq7KQiE8YCiqDEP3B5PRiSEHnnkEXi9fIrngw8+CK/Xi5dffhmzZs0ak4yxqcpETCMkEAjjA01RuHVVOYD0uo4TCITMMCIhVF1dLf5tMpnw1FNPZWxA04lM9YshEAhTA5I0QSCcf0a07aiurkZ/f3/C7U6nUyaSCKnRqsikRyAQCATCeDIiIdTU1ASGYRJuD4VCaG9vH/WgpgskGJJAIBAIhPFlWK6xN998U/z7gw8+gM1mE/9nGAbbtm1DZWVlxgY31dERIUQgEAgEwrgyLCEktLagKAq333677D6NRoPKyko8/PDDGRvcVEeXpOEdgUAgEAiE88OwhBDL8lUlq6qqcPDgQeTmToxiT5MVvZrECBEIBAKBMJ6MKGussXGwAmowGIRer09xNCEZNE1Br1EhGEmMtyIQCAQCgTD2jMg3w7IsfvnLX6KkpARmsxkNDQ0AgJ/97Gf4v//7v4wOcKpjIO4xAoFAIBDGjRGtwr/61a/w3HPP4de//jW02sGOtQsWLMAf//jHjA1uOmDUjcgoRyAQCAQCIQOMSAg9//zzePrpp/HVr34VKkktnMWLF+PMmTMZG9x0wEyEEIFAIBAI48aIhFB7eztmzpyZcDvLsohEIqMe1HSCCCECgUAgEMaPEQmhefPmYefOnQm3v/baa1i6dOmoBzWdMOuJECIQCAQCYbwY0Sp8//334/bbb0d7eztYlsXf/vY31NbW4vnnn8fbb7+d6TFOaax6zXgPgUAgEAiEacuILEJf+MIX8NZbb+HDDz+EyWTC/fffj9OnT+Ott97C5ZdfnukxTmlsBiKECAQCgUAYL0bsl7nooouwdevWTI5lWmI3EiFEIBAIBMJ4MaoAlXA4jJ6eHrHitEB5efmoBjWd0KhoWA0auAMkyJxAIBAIhPPNiITQuXPn8PWvfx179uyR3c5xHCiKUuxMT0hOrllLhBCBQCAQCOPAiITQHXfcAbVajbfffhtFRUWgKCrT45pW5Jl1aOj1jfcwCAQCgUCYdoxICB09ehSHDx/G3LlzMz2eaUm+VTfeQyAQCAQCYVoy4jpCfX19mR7LtCXXTIQQgUAgEAjjQdpCyO12iz8PPfQQfvjDH2LHjh3o7++X3ed2u8dyvFMSm0EDrZo0XyUQCAQC4XyTtmvMbrfLYoE4jsOGDRtkx5Bg6ZFBURQKrHq0DvjHeygEAoFAIEwr0hZC27dvH8txTHuK7UQIEQgEAoFwvklbCK1fv178u6WlBWVlZQnZYhzHobW1NXOjm0aUZRmxHwPjPQwCgUAgEKYVIwpMqaqqQm9vb8LtAwMDqKqqGvWgpiPFdgMMWtV4D4NAIBAIhGnFiISQEAsUj9frhV6vH/WgpiMqmsLcQst4D4NAIBAIhGnFsOoI3XvvvQD44N6f/exnMBqN4n0Mw2D//v1YsmRJRgc4nVhekYVjrS6wHDfeQyEQCAQCYVowLCH06aefAuAtQsePH4dWqxXv02q1WLx4Mb7//e9ndoTTCIteg5IsAwmaJhAIBALhPDEsISRkjm3evBmPPfYYrFbrmAxqOlNTZCFCiEAgEAiE88SIYoSeffZZIoLGiDkFFtiNmvEeBoFAIBAI0wJSzniCoVbR+MKSEmQRMUQgEAjTDmkeEh37R0Xzv9Wx39JOBDoN/7eQdWzW8Y4ek04lPk7YXGeb+HCWXAvf1slq0IiPF3peFtr4hKdiu148RnjOErtB9ls4xqxTw6Lnjymw6mWvIbymRkXBGBujcYJlSBMhNAHJNmmxZmbueA+DQCAQpiyC4JAKD+FvQUBoVHLhQVOU+LdJxy/mggAQxIZWTcNm4P8uiomK8myj+FurpmHWqVGZawRFAUvK7QCAVdXZoChgQbENOWYtcs1aLCqzQU1TuGxuPgDgspp8aNU0FpXaUJFjRLFdj1VVOdBpaFyzsAg0ReHKBYWwGzVYWp6F+cVWVOeZcNGsXFj0aly7uBhGrQqb5hWgJMuAFRVZWFqWhdkFFlw8Kw92owafW1QEq0GDS+fkozrPhOUVWVhWkYVZBWZcPDsPNoMGV8eOuXh2HqrzTFhcZsfiMjtKsgxYPycPWjU/Hp2GxpoZOSi26zGrwII5hRaYdCqsja1vgqAabyiOIylKqXC73bDZbHC5XOfVHchxHHbV9aGuxwunP3LeXpdAIEx9KArgOH5hZzkOKpoCw3JQ0xSiLL8kaFQUIgwHrZpGOMpCp6ERirDQa1QIRhhQFKBT83+bdCr4QgzMOjW8oShMOhUCYRYcOJh1aniCUVgNGrgDEdgMGrgCEVj0agTCDBiOg1XP35Zt0mLAF0aOWYt+bxhWgwahKINIlEOeRYdudxClWQa0OQKozDWiud+PXLMOEYaFLxRFZa4J57q9WFxmw7FWFxaV2nCmyyNaKfq9ISwsteFA4wA2zC3AR2d6sHZmDj5rcyHfqoNWRaPVEcCF1dn46HQPrl1SjHeOd+KS2fk40eFCnlkHi16N+l4vLp6dh3+e7Ma1i4ux9VQ3Vs/IQVO/DyadGllGLRr7vFhVlYOd5/pw6dw8HGpyoKbIigFfCBoVDbtBizanH3MLrTjV4cb8YiuaB/wosunhD/Ntqsw6Nfp9IRTZDOhwBlBk08Phj8CqVyPKcmA5DgaNCt5QFBa9Bv5wFEatGqEoA62KBscBHCB+vyqaAstyoGlKVgZH+DvZ71THsCwnCkiG5aBW0QhGGOg1KvhCURi1KvjDDNQxUekORJFt0mJfQz9m5Jnx4oEWXLmgEDVFmV9f012/iRAagvESQgKeYAQvHmhBIMyStHoC4TwgiAOpKBDEgCAChMndoFUhHGXBsBwsevmCbzdq4PRHYNKpEGE4RBgWWUZ+oc+16NDnCSHfqkOPOwSrQQOW5RCIMCiy6dHmCGBmvhl1PV7MKjCjud8Pu1EDFUWh3xfGnAILjre7sKo6GwcaB7CsPAtnuz3INmlh0KjQ7gxgWUUWdp3rw8aaAmyv7cGF1Tk42+2BzaCBzaBBfa8Xa2bkYkdtDzbNL8SOs724oDILTX1+GLQq5Ji0ONvtwdqZudh+pgcbagqwq64XC0vs6HYHoaIp5Fl0qO3yYM2MHHx8theXzM7H/sZ+zC20ot8XAsvxrpbTHW5cOCMHn5ztxbpZuTjS7EB1rhnuYARhhkWp3YATHS6srs7Frro+XFidjZMdbpRmGRCKsgiEGZRlGVHb7cGycjuOtjqxoMSG1gE/csw6sByHQJhBvlWHln4/Zuab0djnQ3m2EQP+MMw6NShQCEYY2I2amNjSweWPwGpQIxhhoVZRoCkKEWbwe9ZrVIgwLDQqWlzwlWroEUYGw3J4YnsdNs4rIEJoIjPeQggAghEGDMvhg5Nd8IWiCEQY+EKMbKIeDfG7Q+F5KQpQUfzfSgtBIMKApijoNTR8IUbczeVZdOj1hJBj1sITjIKiAKteg15PCBU5/C6uOs+Exj4fiu0GuAMRcBzvo27u92NhiQ1HW51YUmbHqU5+MvQEowhHWZRmGVDb5cGyiiwcbBrAkjI7Tnd6UGTTxz6XKCpyTDjd6caSMjuOtDiwoNiGcz1e5Ji1iDAs3IEoyrINONftxdxCC850eVCRY0S7IwCTTg2K4nctBVYdOl1BFFj16HYHkW3SwuEPQ6umoaIo+MOMuOgJO2GDVoVAmP9c1CoK4SgrfnbCrkz4nKWf/XQk/nyTfk4qmv/shM9VEBXZJi1cgQi0ahoGjQoOfxiVOfy5NLfQgrPdXlTlmdDjDkKnppFt0qFlwI+l5XYcbBzA2tgiPK/Yih53CDRNocRuEBfzvQ39WDczF0dbnZhdYIErEAHLcSixG3C224MLqrJxsHEAKyqzcarDjbJsAwJhBqEoiyKbHud6vOJ5t7jUjroeLwqsekQYFv4wgyK7HnU9XiwqseF4uwtzC61odwaQZdSAA8TFvN0RQFWuCW0O3grgDkah19CgKQqhCAurQQ2nP4IskxaeIH/+haIs1DS/mEs/T62aFq0BnHjeUUkL4xII55MXD7RgSZmdCKGJzEQQQvE4fGH0eEKwGzU42upETaEVB5sGMKfQgvpeL6x6DWiaQp8nhNkFFpzscGFFZRY+bRncRVkNGhi1KvR6QqgpsuJ4uwvLK7JwvM2F2YUWdLmCMGpVMGnV6HIHMafQglMdbiwus+F0pwdVuSa4AhFoVBTMOjV6PSFU5prQ0OvDjDwT2p0B5Fl0CEZYUOAD+VyBCPItOnS5gyi06uH0R2DWq8GwHDgO0KlpBCIMTDq1aOINRngTL8tx4MAHC4YZFjq1CqEoI/7W0DQ4QFxYQzHRFggz0GtohKKxXR3HIcpw0KlpuIMR2I1a9HpCyDZp4Q5EoNPw5mRfOIosoxbtjgDKs41o6POhNMuAXk8IOg0vhBz+iLhAzi3iP5+qXBO63EHo1CpoVBS6XEHMyDPjaJsTi0vtONrqwMw8C9qcfmhVNEw6NZr7fagpsuJwswNLyvjdbnWeGV2uIAA+9qCh14d5xVYcaXZgcZkNn7W5UJljQp83BJbjkGvWob7XiwXFNnza6sTCEpsoIt2BKCIMiwKrnj+mxIZjrU4sKLHibLcXhVbeFB+MMCjNMuBcjxeLS+041ubEolIbznV7UWTTI8yw8IUYVOYacaaTF6NHWxxYVGZHQ68PuWYtKIqC0x/GzHwzTnW4saIyG0dbHVhYYkdTnw9ZJi20Khr9vhDmFlpxsoM/7z5rc2FukQXdrhDMejX0Ghr93jCq80yo6/GipsiKxth34A1GoVHR0MdcArlmLfq8YeSatfCEojBr1aKQF0SWsKOnabLwEwgTiW2nu1FsNxAhNJGZiEKIQEiFki8fgOjPp2n5b8EowHGQxQ4QiwGBQBhrTrS7oKKpcRVCJGuMQJhiCOJF+lv4W7CISH8L9wu3xT+eQCAQxgohXX88IUKIQCAQCATCuJBj0kKnHl8pMmmE0MDAAL761a/CarXCbrfjzjvvhNfrTfmYp59+GpdccgmsVisfu+B0np/BEggEAoFAGBKKosTyBuPFpBFCX/3qV3Hy5Els3boVb7/9Nj755BP8y7/8S8rH+P1+XHnllfjJT35ynkZJIBAIBAJhOJh0w2p7mnEmRbD06dOnMW/ePBw8eBArVqwAALz//vu4+uqr0dbWhuLi4pSP37FjBy699FI4HA7Y7fZhvTYJliYQCAQCYfIxpYKl9+7dC7vdLoogANi4cSNomsb+/fsz+lqhUAhut1v2QyAQCAQCYWoyKYRQV1cX8vPzZbep1WpkZ2ejq6sro6+1ZcsW2Gw28aesrCyjz08gEAgEAmHiMK6OuR//+Md46KGHUh5z+vTp8zQanvvuuw/33nuv+L/L5UJ5eTmxDBEIBAKBMIkQ1u2hIoDGVQj9x3/8B+64446Ux1RXV6OwsBA9PT2y26PRKAYGBlBYWJjRMel0Ouh0OvF/4YMkliECgUAgECYfHo8HNpst6f3jKoTy8vKQl5c35HGrV6+G0+nE4cOHsXz5cgDARx99BJZlsWrVqjEdY3FxMVpbW2GxWDJaYM7tdqOsrAytra1TNgh7qr/Hqf7+gKn/Hqf6+wOm/nsk72/yM1bvkeM4eDyeIROqxjdnLU1qampw5ZVX4q677sJTTz2FSCSC73znO7j55pvFN9je3o4NGzbg+eefx8qVKwHwsUVdXV2oq6sDABw/fhwWiwXl5eXIzs5O67VpmkZpaenYvDEAVqt1yp7cAlP9PU719wdM/fc41d8fMPXfI3l/k5+xeI+pLEECkyJYGgD++te/Yu7cudiwYQOuvvpqrFu3Dk8//bR4fyQSQW1tLfx+v3jbU089haVLl+Kuu+4CAFx88cVYunQp3nzzzfM+fgKBQCAQCBOPSWERAoDs7Gy88MILSe+vrKxMCIh64IEH8MADD4zxyAgEAoFAIExWJo1FaKqh0+nw85//XBaYPdWY6u9xqr8/YOq/x6n+/oCp/x7J+5v8jPd7nBSVpQkEAoFAIBDGAmIRIhAIBAKBMG0hQohAIBAIBMK0hQghAoFAIBAI0xYihAgEAoFAIExbiBAiEAgEAoEwbSFCiEAgEAgEwrSFCCECgUAgEAjTFiKECAQCgUAgTFuIECIQCAQCgTBtIUKIQCAQCATCtIUIIQKBQCAQCNMWIoQIBAKBQCBMW4gQIhAIBAKBMG0hQohAIBAIBMK0RT3eA5josCyLjo4OWCwWUBQ13sMhEAgEAoGQBhzHwePxoLi4GDSd3O5DhNAQdHR0oKysbLyHQSAQCAQCYQS0traitLQ06f1ECA2BxWIBwH+QVqt1nEdDIBAIBAIhHdxuN8rKysR1PBmTTgj9/ve/x//8z/+gq6sLixcvxuOPP46VK1cqHvuHP/wBzz//PE6cOAEAWL58Of7rv/4r6fFKCO4wq9VKhBCBQCAQCJOMocJaJlWw9Msvv4x7770XP//5z3HkyBEsXrwYmzZtQk9Pj+LxO3bswC233ILt27dj7969KCsrwxVXXIH29vbzPHICgUAgEAgTEYrjOG68B5Euq1atwgUXXIDf/e53APhA5rKyMvzbv/0bfvzjHw/5eIZhkJWVhd/97ne47bbb0npNt9sNm80Gl8tFLEIEAuG8wnEcKIpClGGhoimwHBCOstBraPR6Qsi36tE64EeJ3YAeTwgGrQoaFQVXIIJCqx7tzgBKs4xwBSKw6tWIshxoigJNAQzLQa2ixdcgEKYa6a7fk8YiFA6HcfjwYWzcuFG8jaZpbNy4EXv37k3rOfx+PyKRCLKzs5MeEwqF4Ha7ZT8EAoGQKaIMCwDocQfBcRxa+v1w+SPodAVwot0FTzCCN491IMKw+Mu+ZvR6Qnj3RBcONztwuNmBN4+1o2XAj5cOtqLXE8Ibn7ajttuDD093Y19DPw42OfDe8S409/vx+uF2OHxhvLC/BY19Pmw91Y39jf041enGP452wB2M4Lk9TQhHWfztSBt6PEEcbnbgdKcbvZ4QDjQOgGU5HG52gOM4tA74EWFYBCMMwlF2nD9JAiEzTJoYob6+PjAMg4KCAtntBQUFOHPmTFrP8aMf/QjFxcUyMRXPli1b8OCDD45qrAQCYXoSjDDQa1Ro6PWiIseEkx0u5Fl0GPCF0ecNY0aeCe8e78QXl5XixQOt2LSgAJ+c7UWJ3YhQlEGnK4hFpTbU93ixq64Pfd4wDjUNoKHXC4cvDIoC+r1hHGpygGE5fHSmG1GWw6ctTvR6QvAEo9CpabgCEexv7AfLcdhe24NghMGJDjea+nww6dSw6tVocwRwqGkATn8EBxoH0Nzvh93oQl2PF0atGnkWHWq7PDDr1PjkbC9yTFq8c7wTa2fmot0RgEFLozrXjGNtTlyzsAg7z/Vh/ew8tAz4UWTXgwJvZdKqJ81+mzBNmTSusY6ODpSUlGDPnj1YvXq1ePsPf/hDfPzxx9i/f3/Kx//3f/83fv3rX2PHjh1YtGhR0uNCoRBCoZD4vxB1TlxjBAIBAHyhKEw6Nep6vMg2adHhDGDAF0axXY8PTnbj6oVFeOPTdqydmYv9Df0otOnhDUXhDkRRkmVA64AfuWYt+rxhmHVqeENRaFQUGBZgOQ5qmkKU5UBRwFjNzsJz0xQle02tmhYtPToNjVCEhUWvhicYRY5Zi35vGEU2PXo8IWhUNIrtejT0+nBhdQ72NfTjivkF2H6mByurctDvDUFFU5hXbMWJdheumFeIQ80OrKjIgjMQgc2ggYomLjkCbyVVqzIvmNN1jU0ai1Bubi5UKhW6u7tlt3d3d6OwsDDlY3/zm9/gv//7v/Hhhx+mFEEAoNPpoNPpRj1eAoEweRH2hw5/BL5QFGoVhT11/Vg7MxevHGrFxbPzsPNsLwpsejj9YfjDDJr6tQhHWbx/ogsAsK+hHwzLoc0REJ+3dcAPAOjzhgEA3lAUABBhBhVPlOViYxjL98f/ZmN/CK8pdXeFIvzfniA/xv7YmDtdQQAAwzJo6PUBAA41DQAAdtf1IcJwON3phisQAU0B/jCDxj4f7EYt9tb38xamc724oDIbUYYFTVOYW2hBY58Pi0rtaB3wozTLgFCUhU5Nk/ilKU6/N4R+XxizC1KnuI8lk0YIabVaLF++HNu2bcN1110HgA+W3rZtG77zne8kfdyvf/1r/L//9//wwQcfYMWKFedptAQCYbLAcRx8YQZ6NY2DTQ7ML7HirWMdKMsyornfB3cwiiyjFt3uIPqOtoNhOeyo7QHHAe0SkSMIhWCEAcAHI08XBCHlC/HvfcDHfxYMgMY+XiwdaOTF0s5zvQiEGZzscMlE1ulON2iKwtZT3fjcoiJ8cq4Pi0ttCDMsQhEWi8vsONnhwrqZuTjd6cGcQgtCUQZ6tQo0sSxNSjiOw7YzPVhYYhvXcUwaIQQA9957L26//XasWLECK1euxKOPPgqfz4fNmzcDAG677TaUlJRgy5YtAICHHnoI999/P1544QVUVlaiq4vfqZnNZpjN5nF7H9MdwQza5w3BrFPDHYggFGVh0qnR2OdFTZEVB5scWFJqx7E2J8qyjfCFoghFWZRlGVDX48Wyiiyc7HBhfrENvZ4QskxaaFQUOA7Qa1Tj/RYJExhXIAKdmkZjnw8DvjBoisKBxgHMzDfjbLcHJ9pd8Iai6HEPusi73bwVxB/mF/rJEVAwsRCEofAZCsIRAE538kkpO2r5UigfnemBP8zgaKsToSiLKMOhzxtCmyOAKMvhaIsTgUgUR5qdqCmyQqOi4AtHsaw8Cyc73FgzIwf1vV5U5ZoRiPAidyxcL4SRw7AcDjUNoN0RIEJoONx0003o7e3F/fffj66uLixZsgTvv/++GEDd0tIi6yfy5JNPIhwO40tf+pLseX7+85/jgQceOJ9Dn3aEoyzUNIU+bwj+MAMOwGdtTlTmmLCjthdziyw40+lBtkkDdzCKKMPBpFPBE4zicLMDvhC/YwxFWBxvdyHCsKLICUYYnOxwwxuK4mSHG/3eMHLNWkQYDizHYXaBBQ29Xlw2twDnejxYUZENXziKbJOWiKRpAstyYDgOgQiDln4/8i06fHSmBzPzzdjX0A+LXgNXIAJGEotzttsDYNBdRTj/CC5CQSwJFiMAoovxaIsTALC7jnc9ftbuBMNwiLIcut0hdLmCCIQZHG93YVV1Nk60u1CVa4ZeQ8Phj2DdzFx81ubERbPy0NjHB7ULbjgNKSdwXnAHI/jH0Q70eUJDH3wemDTB0uMFqSM0NIEwg3anH1a9Bnsb+lFsN+Bg0wC/2PjDiDCDwZjjgVGrgj/MINukhVZNQ0VRWFhqQ783jOUVWRjwh1Fo1ZPAzUkKy3JodwZgN2pwoJE/72q7PfCHotCo+AwqFU1NK1cVQQ4dEzYsx8Fq0MAdiKAq14TGPh8WlNjQ0OtFoU0Pi16NHncIF83Ow6ctDlw2Nx8nO9yYW2iBJxiFSauGQatChOEt2ITh4QtFcbBpAHU9XpnIvXJBIWqKMr++prt+EyE0BEQIDeIP8wvLqQ431CoKdT1eOP38rtoViIxplstYoVFRiDAcCqx6+MNRlNgNyDHroFFRmF1gQTDCCyiyQxx//OEoaIpCy4Af3lAU3mAU9b1eGLUqdDiDYgYUgTBahHlByJjLtegw4A3DpFPBpFPD4Q9jSakdn7W7YmLJhcWldgz4wrDoNcgyauAMRFCda0K3J4Rim37aBn9zHIf6Xh8a+3xo7POKcWRSiBCa4ExXIeQORuDyR+D0R9DQ5wVN8cJHmCCmE3kWHfzhKCpyTOA4INukhd2ogZqmUGw3gOMAg5a43DKBKxBBMMLAE4yixx0EKD7YVq9WodXhBwUidggTE0GIUxSgUfFlCGwG3gVblm1Em8OPqlwTvKEojFoV8i169HpCmF1gQX2vF/OLrWge8KM824hQhIVWTSPXrIUrEEGJ3YA+b1iciwwaFZjYdaChaYQZVgwb0KlpcBxfIuF8iC5BQoQZFp4gv1lp6PUCAE51uuELMWICQTKIEJrgTAchFGFYNPf7EY6yONPlRijKoscdmlQLTrszgJxxjAHKMmrAcECuWQs1TcOoU8GkVUNFAxa9BhwHmHQqUTTRFAW1ioImFtOmVdNgWE4M+I6fv4TbWA5iewSaosBwfFwUTVGIMhxUNIUww8dnRRgWapoWv0dVzD2pUfHHalT8awphdRwH8TaNihJfSwlhPAzLv6YgjlmOQyRWOTkQYUBTFPyxHaAvHAXDcghFGfhCDFiOE7OLumLByELKNmHisruuD2e7Pcgx67CyMht5Fh1xK48RgrgS6jsJdafMOjXCDAuO42DUquEKRKDXqOAJRlBsN8DhC8Nu1CDKcmA58LGYAd7i3e8LodBmgDcYhVmvBstxYBgOZr0aTn9ErHFlN2rExAKG5RCMsDDqVOjzhGDRa9DpCsCkU6PPy8f5cBxGXG18vIUQcXJOQ3o9IfR4guh2B9HS70cgwg6p2MeaLlcQLx9qRZZRg6+sLB9WhkeHM4DXDrdBr6bxjYuqx2VSdvgjAAB3IDKq55EWuuPAiwvBCiLdcY61Ro0vuCeNsRDibYgranpwvN2F+h4vrl5YBI2KwqFmBwDAHYyisc+HYrseNy4vO69jijIsWG7qV60Wri9BYAiB/NKAflcgAn84it9tr4NBo8JNF5SB5ThZTKYwLwkbjw5ncJQj4wPXnf7RzXcTBSKEpgEOXxg9nhDOdLnR5w2PerEeC1470gaAFxT1vT7MKUy/uFZzP1+kLhizaM0vHt9UzNEQX+gOgCiIhNvOh/aIH4d0PELQMRFBUx+W5fDRGT6lvbbbgxqF63L0i+rwCEYY/O8nDTBpVbhjbSXU9MQVQ6Eog78daYdaReH6JSUZS+H3haJo6PXhRIcLl87NB8NwYFgO3lAU/7erEQDwjXVVJKA7TcinNEXp8QRR2+VB60BArIEykZFm9ISiw7NOCUIBAD483YOyLCOsBk3GxkYgTEWa+n0wxXqKJSMgsRR/dKYH5iQLq9RqOBSeIF83LNc8sgr+z+zmF3pfmIE3GIXdqB3R84w1e+r7cLDJIf7f5Q6iNMs46uf9tMWBT871if+/fLBV8bhudxDVeaReXjpMXClNGDahKIODTQP4894m/HVfCw41OSaFCHL6w7L/t9f2Yjiha/FxJc/uaRLjVAgEQiKtA37842gHXjvclvK4QJzL/M1jHcrHhdPfvPz903b8dX8LejzDn5s8wYgsWaPXm7wOTZvDj9ePtMmqf58vXIGITAQBmXEjhSKMTASlYrzKlUxGiBCaAriDEXxwsgtPf9yAXef6xD5Gk4W/f9qecFu/L/33EFYQPf881a1wJIEwvQlHWew814uTsUrOYSZ1fGC6xSWFAoiBMIMX9rdgT73yYh0IM2I83blub9rjZlg+KWBfw4Ds9jZHIOmm6YOT3WhzBPDakbYxiYE83OzAq4daEyzYHc4AntvTlHC80KNtNAyn2CcpDJo+RAhNYryhKD442YVndzXhVId7Uu4AOI6DO5h4wf51fwt8aVzILQN+nOnyJNxe18NPsk39Pjy27Rx216W3iyIQpiq1XR48+XE9jrQ4USu5ZgZSbDo+Ptub9L4r5xci18y7pXxh/lpt6veh1xvCwSYH2hz+hMd8cm7w+eKtTcnwhfhA4Gd2N0IbF2PzWZsLT+9sSLAqA3Ih8L+fNKT1WunCsBx21fWhwxXEu8e70BUTOSzLYW9Dv+Jj+lJYr9Kh1xPCX/a3yG7bMDcfWUYNZheYcefaKsyVxHD5Fer1EJQhQmgSwrIcjrQ48PxeXgBN1qBVhz+Mtz7rlN1WaNWLf/95X7P4N8dxONPFd7SWIrUmXTGvQHZfpyuAfxzlTflCpguBMFWIMiwGfGFsO92NY63OlMee6nTj/ZNdive9ergNb3/WkWBZCUSYpO6czWsrMafQApOWjxnyhxj0ekI4KhnH60faE6p56yRZXqE0U62Fa9wXYlDfx29wimyD80QwwmJ3XaL4iBdNJzpcw3K5p2Lr6UGLc8uAHy8fasVj287hDzsbxFYg8fR4QsNyIcZT2y3f8F21oBDzi624bXUlrlpQBLNejSvmFWDNjBwAxCI0HEiw9CTDE4zg/RNdSS+2yQLDcnh+b7Pstgurs3Gi3S3+H4ryZnu9RoV/HOtAc78faprCty+dCSCxZoVOTePmC8rwUix48JVD8viHUJSBTk0KHxImNxzH4f2TXTgb51paVGpLWkBv6xCu4vpeH052uLFA0vzSJRFBX1pWilyLFjvP9aE61wSrnk9GMOr462lvQ7/iwnu6y435RVZxXFIrULqiQOomF9oyFNsMMldThyuAdz7rxAWVWci36hFl2ASX+bbTPcgyaFGSZRBvE+pgCXx4uhvN/X5cu7g4IYhc2oOsVsEKDfCZqwI3XVCGPLMOEYbFX/Y1wxdm4A5GRlx8VS0Z522rK5ClECROURQsen5ZT8eiTuAhFqFJRHO/D3/Z1zLpRRCQuFtZXpGFVVU5CdatQ80O+MNRMUU+ynJi+r87KN+tGrQqFFj1sl2nlFQuAALhfBGMMDjR4UJ0hAH9jX2+BBEEpLawpFNaa9uZHvH6C0QYbDvDiyeTToWSLAN0ahU21hTIMpHyYplfyawP20734Lcf8W6tTldAlmrf7gwk7f/mCUbwzmedaHcGYFQQDkV2vex/f5hBXa8XO+v6EIwwaOzzKT5vtyRA+1ibE7/bXof/28WP7eOzvWIz5xcOtMjGtu10N57Z3QRfKAqPZN5RJRGeKppCnpkvNKnXqKCPvYeXDraiwzm8+dvhD6O53yd+vysqshRFkICQ2dfmDOAPOxtwqsOd9FgCDxFCk4TTnW688WnHuBc+BPid0T9PdeH5vU2ySWE4xO9WFhTzVT+z4y7ww80O/GFno+y2j2r5uibeuNgioap0sgXBPwqzNIGQKfbU92Pb6R68fbxz6IMVSObi8ijE2gHDq/ckXFPHWp1i0kVeijT3nCT3rZ2ZkzC2Vw61JQimZPPHoWYH6nq9eO1wm+J1K3WhS2lzBPD6kTa8e4L/jMw6NVbPGByLJzD4+jtq+Xglb4gf29E496IQ0xOOsjgRE0inu9x4ZneTeMy3L52Bey6biRK7QfbYb10yQ2Zp6pcksLx6uE100XEch0NNA2gdSIynEnh+bzPeONohjm+o6vnSEgf+MJM0ZokwCHGNTQKOtTrFomYTgfpeH0538qbhg018h+bhIkyIBo0K1y8tEWuBbKjJx/snu9DtTh5YKFiH9jUOXuA0BdFcH49Jp4IvxJDgQcKY4gtF8Vm7C3MKLMg2Jd+xn45lbAnn8XDgOC5prz9vKKpYE8gXiortUv51/QzQNN/GJRRlUNfjxfbawQBmTzAqdmcXSJWEYUiyKKeyWAC8mycaa9YcXweI5Th81uZK+XglK5GANGvWqFVhZWU2dCoaO872whOK4FirE+1pWGVeOtiK0iwDim2DIkeamLGk1C66yr60vBSPbTsHAJiRZ0qoqWTUqmSC7kyXBzVFVrQM+LG7fnAeW1WVjQur5SIynmS1nJLd7w1FMeALpzwnpzvEIjTBqe3yTCgRBAB1vYNmeaXU9XQQhFBZlkE2eduNWtx8QTmuW1Kc8vEsy8nE0rcvnSnuwL68olS8PcuoQUW2CQBvSUrmN+c4Dj3uIPGrE0bMiXYXDjQO4M/7mlMG5UoF+3DrXTlTVIVPZl053s6LCoteA7WKBk1RUNEUjFo1FpXa8c2Lq8VjBYHgkyzaqUSHEI8iQFNAsV2P0jgLSTxl2XxhwTeOdmDnOXlmWp9n6OyqdJuJCkLNHBtnfa8PO8724lxPeqn7bY4ADjQNpuwLlp3KHCPWzcpVfEyhLdFatWl+oex/obyHJ26+2d84IHOdKblP4z/zeNQqGpfMzpPddrZbOaaJwEOE0ASmzeHHB0nM4OOJ9KQZaVsvQXCYklzU+XGmb5tBgzkFg6mhA5J02SvnF8p2YEU2A767YRa+u2EWbltdKdshvXO8U9FVUNvlwYsHW/HHXY1iKmwqSK9iQjzSjMZndjclBPNHGDYhiPeJHfXoGUbR04Ze5dgXgLfmBCMM2Lgq7UJhv2SxczqNSsw0cvjD4DhOXIxVFIWVldlJXzPeTbN5bRWuW1ICnUaV4B4TKLTqYdINPu5IixPhKIv6Xi9cgYii2DNoVPjCkmLQVGJ2aCqEZr5Cdls6bErj+S+dk5/Q0/DG5aVYUZGFJWX2hOOVrDgMy2FAoeZbl+R8UCoxMJQQAoDFZXZ8c301LqjMApDcbUrgIa6xCYo3FMU7n3UmDSYcT6R+fodv+DFCwQiDIy1OAMnNvPGpr7euKoeKptDQ50WE4fBXST2N2QWpy8hbDIOv0ekKYvuZHmyokU920iqwu+v7cMOyUigRZVj8YVcjwlEWK6uysXoIMzZh4sCyHJoH/CixG8akWac0u4mPO2nFrRdWAOAXvT/vawaFxMDilw+14t8um5XWawgWm7JsA2wGDYJhFi0DfoQZFoeaHTjU7EBZtgHXLynBu8e7ZNbbVNiNvJXqTJdH5v75l4urh/ysaAoQpinp9bysPAszcs2wGzVoGfDjjaMd0KppXDG/AC5/RJYh+uTH9QnPW5VrEoOetWoalTkm2ed0++oK7K7vh0WnxmdtLjAKm5Nl5bwQSNVGZG6hBb3eEPItOlxeU4DeISxSOjWtKEaK7QYUJ7GEZRk1mFdkRb8vJFqy9zb042xPoqVm57k+7DzXh3Uzc1EWy3DTqmhRQKfbP0ynVsESsz6mU7MpHGWhoqlxaVo93hAhNAHhOA4fnuqesMG90gKIXe4gIgwLTRrNBKUNAQWS7dSkF+PFs3LFZoVqmkaEGfxcdGp6SDN5fCDjiQ53ghCSWphS9Uyq6/GKO/0DjQNECE0izvZ48MHJbhi1KnxjXVXa7pV0iDIseuIW0H5fWCzZ4AlGUgQz89bfdPpQCcHMC4ttmBWzkB5rc4qBvwDQOhCAMxBJEEFSi2o8VTkmMZZOikY19GekUdGKCQo0RSErFpdSkWPCnWurYNSp0u5JVmzTI8KwaHMEsKDEmnC/3ajFNQuLAABrZ+bi/3Y1Jiz4S8vtAPj55KYLyhT7csW7rXLNOhRYdQjH+qHFu9G0acw58VAUhcvnFcAViIhVpw9LaptdMa8AYYaVfY+76vrEEAGLQY1rFhSBpqm0Pz9g0DXY2OdLiBPqcAZgM2hg0qkRijJ46mO+6OS1i4tRlWsa1vub7BDX2ATkZIc7afrneOMNReEKRCC9FuOzLZJxpjMxjbM6L/kFJ1StnVs4OAnGxyvcdVE1hkJp98amsLS1KlTEFRAy1gBMy53TZEaI7/CHGdSncDGNBGlLF+k56g8xiLIs3jia2KPrphVl4t+vH0lsM6OEYE2SBhjrFDYhryv0EFtYaku4TUCtomHRyZMNtKr0FvyLZ/HxKItTPD/Ax+kIi7jdoBEzRZNRZDfgc4uKcN2SYiwry0p5bDJLhnSDlizTLB6apnDTijJ87cIKXDG/ADlxQcajiSO06tXIMiYmddQUWRUDzAUro0mrRpZJC9swm0lLaxb9eV8zXj/Shk5XAGe63Hj1cBv+GLNuS8MB3jzWMe1iJYkQmmAEwgx2ptlU73wRjDDY39gPTzCC47FsDmm8Qbo9dOJbaVwyJy+lJemmC8pw98XVsov50jmDGWorq7LTEiNqmk6wCgXj+gNJn4fj+OaG8UQYVpaxw7DciGrBcByXUogRxgZp9tM7SVLXOY5DbZdnWBWAu91B0Wpg1Kpw10XV4oL1/sku/O/HDQkV0QFAr0lv+vXF6tq8eaxDtHiYJeJeyXXlixt/id0wpNV2ZdVgLND8YituvbA8rfHVFFlwx5pKrI8L0E0FRVHYUFOA726YlTQ9v8Cig06tQkWOCXQa17lgHQL4ApB3rq0a8jErKpQFFkVRoCgKaprGLSvL8fW1leJ9o7l0KYpKcLsLAlJpwyasBUriKR3is/raHAG8cqgNH5wcFO47z/UmxLP9cVcjouz0aVxNXGMTjH2N/ROiVpCUt2OFzaQND/UaFS6alYetp7rR2OeD0x9OSIM93enGP09146JZuVhWnoVOlzxltSI7tStATdOIn+NLsgy45YIyWA2aIetpSLlhWQk4Dnh6Z0OsYjULYbgsxyXEYrmCEeTHPb9SuwFfmIHNwA/yg5NdGPCF8aXlpUkXHY7j8GqsNsqtq8pFlx9h7IlvjvnKoVZcMa9Adt4ebXXik3N9KLDqcPMF6QmBlyTuli8uLQEwWAU43l0mJT7Wo8cTRL4l0WrR2OdDryckxq6oaAp6yYURf90psTzJgi+lKteEr6wsR4Rhk8a6KEFR1LAtFVIWltrEzFiLXi26EId7bRTa9Lj74mqEomzS8WQZNXD4I8i36HD1wqK0xq2iKVj0Glw0Mxc76/rEAOSREi9cBfdhsvIfAGAd4edr1qnFUgXJ8IeZhOw1ADjT6UGWSZuwiZyKkFl4AuGWWFwmEko1N5aVZaFAEoCo1JxRcBfsPNeHKMOKZt5bVpbh9tUVaU3gSuRb9cMSQQA/WdOxKq+APHhQSXjGx0oAg26JPItOdH+8Hyvc5g5GcKbLgx5PCE/sqE8o9gjwIigYYdHpCsIViKSslUTIPKGIfIfb6QrizWNyl5WwA+92h9JKVIgPrBViMGbkKwfwb6zhm2R+flFRglh+8UArPjjZBX9Yfu74485PVcxaIX3NjTX5uHxegWKl43sum5l2zEeeRTcsEZQJFhRbsaEmH19cWoIvLi2BiqIwK8nnNxR6jSqluPnCkhIsK7fjc4vSE0FSllVk4Ssry1Nm0aWDmqZkoQW5MYuYiqawekYOSrMSP/9FJandjsnQxtoOCWEGSjT0+RS9ENvO9OC1w21DBo9PBYgQmkAcbnJMyCwxa5zJVkVTWFhqg1Gyo/WG+NTd1gG/osvoszYXOI53qeWZdSMWQaNFMBWf7nSLKfBC7IjUNK3k8hKKzFl0ajGQXUh1jbcWCe0JBPzhKH77UR2e3jnYBTu+RQhhbFESvA5/BEeaHTjV6cbTnzRAevU99XG9Ym2eUJSBNxRFKMrghQOD2YvfvnSGKFAuULDAGDQqzCm04LbVlWKbis1rKmXHnOnyYNvpwTg0hy+MvfXyysBqhQDm+cU2zCuyJizuy8rtGQ0KHwsoisKCYhvKso2wG7X4xkVVuHJB4dAPHAE2gwYXzcoTs6mGS55FN2orLkVRMpeVNMxgZWU2blhWirWSatjziqyjes0csw6LFVL6lQTXBoXiuNK2JFMV4hqbIAQjDE52TDxrEJCYejkjtruUmuf7vGH87yf8Ir9+dl6COXVnHb/jmJVvHteJWYg3OtnhBk1RyDZpsSs2tjyzDtkmLZr7/Xj3RBc2RFlZE8oTse8ny6TFZTkmMXC6oc+LTqd8smiKqxrcolBCfyrX9ogwLE51uFGdZxIXHY7jcLDJAatBDQoUKnOM0A3TsjcahMym+Cq/wrkZT5Tl0OUKwqBRgeE46NQqhCIM/nqgRfG7U9OD10P8wvXtWMuF+HPfatBgRUUWDkkyiNzBCBp6vXjrM+U4plRVm69cUIg99X3i+Te/eGSWhPFkuNbeyYhWRcMP/hxUqu+0vCILh1scCEZYVOYOnU04FPOLrPCH5O02rl9Sgj/vb5Zt4haU2HCo2SGLaTvU5MCCSXgeDQcihCYIJzvcSUvnjyfxAcIARHGQTNAouckElIqNnU9skp2gUHFXIMywsmyJbWd6oFXTiDAsPpTs0rNNWswttIhC6K1jnbLO0ALSbtWtA4nuxQONA7IA1anE7ro+HGtz4dNWJ+6IWT2a+v0JfY+umFeAmqLU2UOjxRuKgmU5UbwsL89KKn7iEXpWaVQUvrKyHH/a26x43HyFDKglZXYcbXVi0/yClDv6JWV2mRDq84aTiiAASSsaA7zF4gtLSviAfI5kNk5ULp6dJ7pldepE4ScEVXuCUVTmjF4IURSFlVXZqMwx4sPTPVhWbhez44QNrMCGufn426eDWYzeUJQPnOaGH7c1WRi2EHI6nfj73/+OnTt3orm5GX6/H3l5eVi6dCk2bdqENWvWjMU4pzQcx+HUBLUGKdUykgbuXbOwKGkGjhLJmjSeL1Qp6qIsK89KiBl570RiZe8imx40RSHHrBXdakIw4heXloiTSH2vDyzHYVa+WdENxnBc2jWYJhtCerp0Z6mUOfXPU91jKoS6XEG8fGgwmJmm+Kq7VXkmuAMRxbR2JSIMhxcPJNagEVDKmLpoZi4WldjEYoXJSNXCQsqmeQUoyzamVVCPoiikUQKIME5U5Zpw5fxCsByXtGBlrlknxg9linyrHl9ZNZgEoNeoRME+t5CvM1WWbcQV8wrEGE+G5fB/OxtBURTuWFM5JsVIx5u031FHRwe+8Y1voKioCL/61a8QCASwZMkSbNiwAaWlpdi+fTsuv/xyzJs3Dy+//PJYjnnK0esNyRoFTgS6XEH881SXWGrfolfj5gvKcE1cpsVQ5d6lxy4cYcBfJomvCSKlKteU0KMnnooco+iauGZBkew+muL97kJV7HeOd+K9E104JynCeHlNAT6/ePBxDt/E+t7Hgt9tr8OJdldKS+FYcSJug5Fj0kFFU8gyahOqmqtoCkUKfaIEkvXVu311haKYpWm+oOBQrmCKonD76oqUxwB8r7B0qwoTJj5zCi1jbg1Nh7UzcnD1wkJcMmdw7qspsuLbl8wQ44iCURaBCCPrgzaVSPuqWrp0KW6//XYcPnwY8+bNUzwmEAjgjTfewKOPPorW1lZ8//vfz9hApzJ1aTYAPJ8Iu2ihy7xRq0KBVY+CuOs2z6xDrlmLPm8YdoMGS8rs2CFZ8G5cXoo/xqpJjzbtNBPMKbTAGYig2xVEsyRuZ9N8vtL04jI7Zhda8HScuVhAulAadfKdPMspuwub+nxiGrXNqEGJ3YBiux4dziAG/OGEvmpTAWnQP8Ny2JaicbArEBlV+nUq4gWKtKhg/GvefXE1NCoaH5zswpkuD3JMWlnbDCnXLSlGoU2v6NYYCXajFvdcNhPP7WlKqLcFAKurc1Bsn3rnCWH8UatozMpPrDquVvH119ocg+InnXpOk5G0hdCpU6eQk5O6nYDBYMAtt9yCW265Bf39/SmPJQySqpHi+YTjONR2exTTZ5P1BKNpPnaCA19SPxRlZELIoFVh85pKBCPMiDM1MglNUWJbjECYEbO4pBNBfBEyAZ2axuJSu+R/FRaV2PBZXKzRmhk5ss/gtKR3k2AtyjZq0eEMotcTwtyxSZAZNxiWS6jZk4pPzvbi84uLwXEc3MEorHp1xgLq4yvkSqsZq1U0Vs/IEbOyBNF0xbwCrJuZC7WKwrFWF+xGjcxFunZmDipyMt+CgKIoXLWwSGwDsXlNJUABerVqSrojCBOf+PpFH5zsSqua/2QjbSE0lAga7fHTFV8oOmHqNHza6kxa1XpGXvK6HhRFQVi2dGoV8i069HhCmJVvBk1RsBo0Iy4INpYYtCp8d0N6zS4B4KuryhMyWi6dm4+ybCPeOd4ppp6migkRrBBCrNSRFidmF1hQMIWsQu5gJGn1XYteDbNOjbmFFmyP9VVq6PPBH47iVKcbu+v6ccnsPMV035EgBEjPyDNhZVV2gsC6oCILapqSff4URYkuqJVV2eA4Du9JHmM3jF3ph0IrXxRQRVNTMnaMMLnIjQsl8IcZBCPMlMvsG7HDuaOjA7t27UJPTw/YuFLc99xzz6gHNl1QKlY4XpxW6AUmUKJQcyIZVy4oxIl2l8x6MpmZXWDGupm5SS1aM/PN+PalM8RiduXZRiwotsIZiMjMyhQGq8pKq2p/cLILX7uwAoEIA2OSJrSTCaFwoUWvxpdXlMka7RZa9bg61gqB4yBazs52e7G7jrfM7DjbmxEh1OUKinWeVlXlKHYgpyhK7FCeDIqiZEkBY+2immqLDGHyouS2/+RcL66YN7XM2COadZ977jncfffd0Gq1yMnJke2yKIoiQmgYnOv24FSHGzPyTRmLNxgOgTBfW6Kux5tQL0hKupktAF/n5KJZ6fcdmohcWJ2NfQ0DWFWVjQvT6DAvrSEj9FECgH8cbRdruqyRFEmzSaxGnmAUh1sc2F3Xj03zC2RNZicjn7U7AfDvK97NKLVyzCowi0IoVZPhUJTBn/Y0IxBhsGZGDpaW2XGszYWZ+eaksUUDvrAsW2ykvZoEqnNNWDMjB2VZxikhVgmEdLluSTF21fWJCT2nOz24bE7+lEqlH9EV/bOf/Qz3338/7rvvPtD01PkwxoMndtTjZIcbrQ4LNs0/fyrbG4rimV2NSFW56MblpfCHGahpSrbQTwcuqMzGrHzLqBdQaWyVdMNAUxTWzczFrro+aNW0aA3Zdrpn0gshIcBep6YT6tg0DwwKHqNWjZoiC053ehJS66U1mLae6hZF+p76fuyJxfSc6XLjq6uUs632NcRXYx7d+UvTFC4YZWsFAmEyUpFjQkWOCY9tOyfe5g5GxXYyU4ERzQ5+vx8333wzEUGjhOM4nOzg3VFnJAG154OPzvSkFEEAH+syM9+MyjT7FE0lhKrTow3apSWPj2+fItTtkNZqMuvVk7YzfZ83hK2nBluLXDqHj5mSdviuigsyFpqMxguh2u7B66E+STJBqpIT0iaTV8wrGGroBAJhCGqKBhNKhGSI1gE/9jf0i+2KJisjUjJ33nknXn311UyPZdqhVKwwFR3OAJ7f24SmFG6EdOlyJe8fY9SqMDvfTFwAGWBpuV38e15czRCl7DSnP4Jn9zSh3zsxAujTxRuM4q/7W3BKEmc2I48XPdKU23Uz5VWRlfodAYlVv5PhCUYQjDA41DSA//2kXkw8EITVgmLrhKjVQiBMdi6vKRD7ToajLBiWw98+bce+xgGcm4AlYIbDiFa6LVu24HOf+xzef/99LFy4EBqN3H3wyCOPZGRwU52d54ZXYO7tzzoRiDD4x7GOYWU7DcXaGTlYUZmNCMOCoqDYwZowMuxGLe6+uJp3L8a5Z2iab74YH5vlDUXxl/0tuHZxcdpdw8eTCMPKmo8CvMgT3u/iUhvOdnswp8CS0FssWYHLDmcQ/nBUZkXbUJMva0gKAM/sbpL9f6BxADoNjYFY/R8iggiEzCBkU7qDUYQZFh9JaoNN9r6JIxZCH3zwAebMmQMACcHShPT49fu1sv+jDJsylkG6YL54oAU3Li8dUexDlGHFKrnXLCzCzHw+NZ6k644NqbKAUgWotwz40xJCLQN+sCw3Li7MKMvi+b3NCe9DmqFl1Kpx++pKxcdTFIWLZuaKvb82zSvABzH32utH2kVBA/CNI+OFUDx1vfKdaeEUKktAIIw3QtbrgC8ss/4q9VqcTIxo5Xv44YfxzDPP4PTp09ixYwe2b98u/nz00UeZHqOM3//+96isrIRer8eqVatw4MCBlMe/+uqrmDt3LvR6PRYuXIh33313TMc3HAb88hiH3fWJRSg5jkNzvw+RuPL+PZ4QPmsbWX+yTlcQDMvBoFGhehJYHKYyyQpVAnzLjqFo6PXi75+24x/HOmSi4XzhCUThDSXuBodqvSJlfokVWhXN1xcqsmJWTJhL309FtnHYmyy9hp6ylXAJhPHAFAuX2NcwkPZjfKEo2hz+oQ8cR0YkhHQ6HdauXZvpsQzJyy+/jHvvvRc///nPceTIESxevBibNm1CT4/yLnHPnj245ZZbcOedd+LTTz/Fddddh+uuuw4nTpw4zyNPhGE5uGNxDEK14aOtTjjixNGJDjfeONqBJ3bUJzyHP4U1QeBoqxPvHu/kuwfHEBqA5ll0ZKEYZ6SBvLMLzLh2cbH4/2CZSmV8oaisS3mHK3M1qcJRFq8casXBptQTXjBJBWnvMEzlOrUKd11Uha+vrQQArFBoxVIe68B966pyXDI7D8srhm7XMluhbQCBQBg5yfpFxq9bAhzH4Y+7GvH6kXY8tu0c/OGJ6UIbkRD67ne/i8cffzzTYxmSRx55BHfddRc2b96MefPm4amnnoLRaMQzzzyjePxjjz2GK6+8Ej/4wQ9QU1ODX/7yl1i2bBl+97vfneeRJ3K60y1W382XuBGe39ssO+5UR/Iihx6FjuZSOpwBfHy2F+d6vKjvGQywFvy51mHs2gljQ5mksGKxzYCqXJPYky3KKjf5FPh7rMu9QI87cwHWpzrd6HQFsae+H72eEPY39itOYskEz5JhFkRUq2jR4qMURC5MwDlmHRaX2XFBRRZK7YaEAHQpSoKKQCCMnGQp80IvxUCEwRuftuNMF79uNcQl9vwpbn2bKIxoJTxw4AA++ugjvP3225g/f35CsPTf/va3jAxOSjgcxuHDh3HfffeJt9E0jY0bN2Lv3r2Kj9m7dy/uvfde2W2bNm3CG2+8kfR1QqEQQqHBBcXtTi5ERsP7sd5FJp0KG2ryZSeIECAaCDNiZVyBVVXZcPojqO324Gy3F1ctSP4ab0usBUdaHJgTS9cWLEITofcXgW/j0O8NYX6sD5ZQs6mux4tLYino8TAsl9AQdChhPBykzyUEQnuCUWyskaeiC2OYV2TFxpp83tI5yhojFr0Gq6qysb+Rt0YtK7cnxK/pNCrcsLwUvlBUjFW4sCob+2KPuWJeATm/CYQMo1XTUNOUWJ5iZr4ZdT1ecU15+1gHOmINrZv6/QnJEOEoC5bjZGVFJgIjEkJ2ux1f/OIXMz2WlPT19YFhGBQUyCfigoICnDlzRvExXV1disd3dXUpHg/wgeAPPvjg6Ac8BJ5gBCqKwqrKHNiNWtx8QRleijVbPNrqxK66PsVqzisrs3Gy0y2rsxKMMKApKqExY75Vh+ZYVeMeT0gsUifcRixCE4PVcZWrhTnCF2bgDkZgVVjQleKBfMMsx5AMjuMU09d74nriuQMRUaxYYo1S1SoqI4XWLqzOiQnEMHLMyZ9PGohuNWjwpWWl6PeFxBpNBAIhs0hrdK2szEZdjxe+EANXIIIOSVmWWkltvMoco1hh3xWIIMs4sYoxjmglfPbZZzM9jgnDfffdJ7Miud1ulJWVZfx1HvzCAqyfnYfDzQ4AQIFVDxVFgeE47Ipl0MTXGVJRFGiaQmXOoDvlT3ub4PRHYNDwcRaCe4EPspYHqHlDUfT7wuLzkh3zxEQqJJx+ZSEUn64OAL2eEPq8IeTGGrqGoyzOdntQnm0cVtPbAV8YESaxQFq8y0oaPzQW/bFoilLsDyZFRVNYWZWNhl4vqnJN0GtUw+qLRyAQRk6uZJPy3J6mpMflWXTwhxn0eEJw+MITTghNmnzp3NxcqFQqdHd3y27v7u5GYaFya4rCwsJhHQ/wgeBWq1X2M1ZkmbSy9HeNWtlcuLjUhlK7AZfM4ft3SRckp583SQYijKzSrlLvJn+YwT+Odoj/F1hTLzKE8aE61wSNij8XnApBiOe65VXIv7KyXPz7r/tbxCqvb33WgW1nerDtTOqU83iS1QTxxcUISdNnxzPmfnV1Dr66qoI0KyUQzjMURUGnHlpG6NQqGGIejvPdRSEd0hZCV155Jfbt2zfkcR6PBw899BB+//vfj2pg8Wi1Wixfvhzbtm0Tb2NZFtu2bcPq1asVH7N69WrZ8QCwdevWpMefb+LjHrRJ6vhcNCsPNywvxYJYwKhaReOiWbkJx/3z1KDLzxdKdJMca3OKf88ttEyppnlTCYqixCDg7bW9sirgHMfh3RNy126860j47oXO9y0DfkSZ1IHXUjwK6fAA4PJHwHEc3MEIWgf8kHYCmV1AXFEEwnRA2PQIoRhrZySuRfHMzDeLWdLnerwJ5WDGm7RdYzfeeCNuuOEG2Gw2fP7zn8eKFStQXFwMvV4Ph8OBU6dOYdeuXXj33XdxzTXX4H/+538yPth7770Xt99+O1asWIGVK1fi0Ucfhc/nw+bNmwEAt912G0pKSrBlyxYAfHbb+vXr8fDDD+Oaa67BSy+9hEOHDuHpp5/O+NhGgl4jFyJC1U4Bo1aF65eWJDSuBPisnJ3n+mS39XnDYFkONE3hE0nVaqF6sdAME0BC0CthYlGVa8KxWJ2olw+1Is+iw3VLimUWPQC4YVlJQuChJxRBn08ez/OHnY345vrqIWvx1Pd6k3aCj7IcfvtRXcLtX19bSawxBMI04YZlpfjkXC/Wz+Y9FAtKrPioNrnVef3sPNgMGuSYdHDEPBhdrqAsY3a8SVsI3Xnnnbj11lvx6quv4uWXX8bTTz8Nl4ufqCmKwrx587Bp0yYcPHgQNTU1YzLYm266Cb29vbj//vvR1dWFJUuW4P333xcDoltaWmSNYNesWYMXXngBP/3pT/GTn/wEs2bNwhtvvIEFC1KkWp1H4mN0LHo1OmMxqiqawjfWVSVduGiKQkW2Ed3uID6/uBivHm4DALx9vBPrZ+eJAW3836zY3Rzg69UoiSvCxKEixwSrflAY93pC+MPORtkxC4qtKM3iJ5P1s/Pw8Vle/L5yqC3h+cIMi+21vbhsrnIWGgA09/tkmYYWvVp0k9EUoNQLtiLHSGLNCIRpRLHdgJsvGHTHUxSFaxYW4Z3j/NxRnWvCFfML8NTHDQD4eQoALpqVK1Z+b3cGJpQQorhRtI11uVwIBALIyclJSKGfKrjdbthsNrhcrozHCwUjDJ6UFEr858kunJb4T4fqJ8ayHKIsB7WKwuOSnbpeQyMY4U2P/7p+Bno8Qbx+ZLDmzKb5BZhbSHowTXROdLhStpT41iUzZO7VJ3bUKQY5S1E6p1iOw9+OtKPdKS/IuLIqG8danZhfbMWALyxmfUi5ZE4eFpfah3gnBAJhKsNxHGq7PAhFWSwosUFFU2gd+P/bu+8oOao70ePfqs65J+egOMoRSQgMIsggkklrA8YkY1h7wV6M9z2bc2xweMfYxs/Lgr2Gt8+AvcYG4wfYxjZG5CQQSAJFlDXSaHKezqHq/VHTrWlNHmk06fc5Z05Pd1dV3+rq7vrVvb97bwiTqlDsP9Z54aMj7ekLtpn5bi6cX4BZVVm3oHBU5gUc6vn7hPpP+3w+fL6+R5oUg7NbTDitpnQvroocVzoQGsqAdKqqYO2jZicVBOW5bVjNaq9eR331QhLjT567/2T2dfMLe+WY9XVJs2paNl2RY2PtRBNJbObMZqyatnCvIAhgdr6b06dloyhKr8Ebh1JGIcTUoCgKc44LZPqq8XHZjv327GsMsKjENy5qhmQgmTGW67ZxuNW40p5V4AYKcdlMlPhPvAtwU8DIE/HYzRT57NR1J90O1iVZjA+5/QQZKyuz04Nj9uSymekIHxsI8fMry8l2WTGpCodbQwSiCeo6IlTmZM4vF+1jmoxzq/LI6fH6VQUeDreGyHVbmVXgYcP+FhYUezOu9oQQYiBOS2bIcfwQMWNFAqExVuC1pwMhVVH6PMENxWcWF/PnjzMTaVMzAiuKwudOK0sPqCgmhv7yuFZOy+7z8XXzC3n6wyPp+z0DXp/DQiCa4KPD7b0CofBxP0az8t0sOq65a26RB6tZpTTLgd1iYnl5luSZCSGGpcCXeXHX1/AgY0H6T4+xYr/9pGxnWh+zyF+xtCTjvgRBE1+h195vAFLos3PZoiIsJoV18zPHyvI7jebQ5kDv+chSV2XTcl2cMzsvYyLYFEVRmJnvTvcOkyBICDFcZjUz5HjvYOu4mIhVaoTGWLHfgaooaCPPWU+7dkUZ2452sKN7otZi38kJssTYuX5VOfsaAyyvyKI9FO9z2pWepue5+cqaGb2C3ul5LnbUdhKMJaltD2c0aW053A4Y+T6LhzlZqhBCDEfPucoAPj7SwVXLSsewRCOsEXrttdf6fe7RRx8dcWGmIrvFRNFJClgKvHbWzi3gyqUlfPHMSqkBmgRy3TZOn56DxaSS57Hhsg1+7dLXce85Gvmu+mMjQneE48S6BzfzyNxzQohRdsPpFRlzAW48NPa1QiMKhNatW8f/+B//g3j8WGJmc3Mzl112Gd/61rdOWuGmiul5vZu1TkR5toztIjIVeI4F2z2rpxs6j41abSTrCyHE6PE6LHx6XkHGgML/+6U9Y1iiE6gReu6551ixYgU7d+7kr3/9KwsWLKCzs5OPPvroJBdx8puVL9MTiNGlqgrndI8E2xU5dgGTCoQWlfh6dasXQojRoCoKt581PX3/3f0tAyw9+kYUCJ1xxhl89NFHLFiwgGXLlnHllVfy9a9/nddff52KioqTXcZJz+e0nLSkaSH6k2r6OtA9hYam62zuzg/Klwl4hRCnkKIoXLGkGIDKnLEdS2jEvcb27NnDhx9+SGlpKWazmd27dxMK9R55VgzN/GIZmFKMrlRzqa7D5uq2jNHIZTwgIcSpZuvOXexrkvBTaUSB0I9+9CNWr17Npz/9abZv387GjRvZsmULixYtYsOGDSe7jFNCVaFHJq4UoyrVhR7grX2ZE/b6HZJTJoQ4tWzdM9gHJ2Ky9H/8x3/w/PPP8/DDD2O321mwYAEbN27kqquu4pxzzjnJRZwaLCZ1SNNqCDFSFpNKRR/D2a+ozJIehkKIUy4VCIViSZJ9zep8iowoENq2bRsXXXRRxmMWi4UHHniAl1566aQUbCpaWu7HapYxLsXomZnfu2dYoVfy04QQp17P810gOna1QiM66+bm5vb73Jo1a0ZcmKnObjFxWkXWWBdDTGJVhR4WlmTmo0nwLYQYC2ZVTY9S37M366kmv4DjzLKKLLySryFGicWkct6c/IwpOKwm+RkQQoyN1GCvDZ29p/85VeQXcJxJnaiEGE05bmv6f7/TOsCSQggxenK7f4u21rSPWRlkTP1xaFquiwUlPrYf7RjroohJKtdt49yqPFw2szSNCSHGzJxCL2fOzGVFZfaYlUECoXFqzew8atvDtAZjY10UMUktKvWPdRGEEFNcVaGHdQsKmVvkHbMyyKXgOGU1q1y2uFjGFhJCCCFGkQRC41i2y8pnlhRjVmWMFyGEEGI0SCA0zpX4HVy6WIIhIYQQYjRIIDQBTMt1cdXyUmwWOVxCCCHEySRn1gmixO/gmtPKyHZJV2chhBDiZJFAaALJcdv4/KpyFpTITPVCCCHEySCB0ARjMal8el4BVy4tkdohIYQQ4gTJOEITVGWui9IsB1uOtLPlcBvBaHKsiySEEEJMOBIITWBmk8qKymwWl/r5uKad7Uc7aA+N3cR1QgghxEQjgdAkYDUbAdFpFVnsbwqwq66L6pYg8aQ+1kUTQgghxjUJhCYRRVGYme9hZr6HcCzJ/qYANW0h9jYESGgSFAkhhBDHk0BoknJYTSwo8bGgxMfauRqtwRif1HfREoxS0xqWwEgIIYRAAqEpwWxSyffayffaAYjEk7QGYzR0RjjcGqIrkqCpKzrGpZw6FAV0HSwmBbPJ6LhpNalouo7VrJJI6lhMCqlYVVUgqemYVIV4UsdsMm5Tj+u6sc2EpmNWFaIJDUv3MiZVQdONDZkUhYSmYzWpxDXNuE3q6VHLdXTMqlEOi0klqRnlSGo6amoZHVRVIZHUMKsKse7140kNMMqTCrJjCe1Uvq1CCDEiEghNQXaLiWK/g2K/g6XlWei6TlsoTiyhsau+k2hco7olSCgmPdEG47KZ0HQo8tnRdJ1ctw2TquCymnHZTKiKgsduQUfHbTOj62Azq5hUBUWZ3NOmJDUdBQjGEgCEYkkSmk40niQUS6LpOi2BGCjQ0BFBUaA5EJMASkxJqQsks2pcsKiKgt2iEoolyfXYaO6KUpLloKkrSq7bSiSuoek6fqeFpq4oJX4nR9tDlGY5aQlEyXJZSWo6SU0n22WlM5KgxO+gJRClyOegKxrHY7Og6cbFi8dupj0UJ8dtpSUQI8tpoT0cx2ZWSWg6kXgSl9VMcyCKx26hriOcvg/GBXZ7OI7FpE6477AEQgJFUdJjEhX6jFqjRFIjktBoC8Y41BJEVRS2He3AYTHRGoyNZXFPGbvFRDypMSPPTSiWoDLXha5DtsuCz2HFYlLwO2Usp/6YumuRPHZLxu1AUj/cXZE4Td0/sAebgtgtJnY3dGFWFQLRBLq07IpxQlWMWle7xUQknsRiUrBbTASiCcqynBxuDbGo1MeBpiBzijwEIgkcVhP5HjtNgShVBR72NwWYW+TlSGuIYr+DpGbU/HrtFsLxJD6HhWgiic1sOiX7NCNv+Ovouo6mQ0LTqGkLA7CztpNQLEFdR2Rcf2cVXR/PxRt7nZ2d+Hw+Ojo68Hq9Y12cMafrOjVtYcwmhX2NAdpCcSKxJEfbw9gsKtH4xLoS8DksdITjVBUaCeYlWQ5y3VYsJpXybGf3D5KMOzqeNHZFCEWTBKIJ9jcFsFtM7KztxGk1SS2mGDFFMYKapGbU3gaiCQp9duo7IlTkOKnvjOBzWPDaLTQHoqyalsP2ox2sqcpjV10n84q8dEYSuGwmPHYLoViCPLeNcDyJ0zq16xyaA1GqW4LsquvqMw1j3YJC5had/PPrUM/fEggNQgKhwSU1nfZQDLvFxObDbRT5HGw40ILfYVSfRuIaNrN6yk9SqSrmXLeV1mCckiwHbpsZk6qwqNRHcyDK3EIv0YSGw3pqrrTE6AhEEzgsJj460o7PYWZXXReBaAJVgdr2iARJU1TqN8BqNi5mYgmNIp+duo4IS8r9fHS4nTNm5LC7oYvSLAc+h4XmQIzTp+Wwo7aDldOyOdQSoizbQTRh/I5ZTWo6V04MTyKpsbOuk+1HO2nojKQfl0BonJNA6MQEowliCY24pvFJXReVOS5e+aSBBSU+PjjUSqHXTmswRjSh4XdaaOyMku+10dgZJctpoS0Ux2UzEY1rJHUdn8NCeyiecaVW0xamxO8gqRvNKgtLfOxvCrBmdh4HmoPMK/IaVddmk/x4TTGxhEZTIIrPYeGdfc3MzHfz6q5GslxWGjojxBIaVvPEy2mYylK5NKkaaLfNTELTiSc1KnNd7G8McNasXN7a28zauQVsOdLGzHw3LquZrkiCpeV+9jcFWFjioyUYI8dlRdONTgmTPW9vvIgmkvxjRwP7GwOABEJD1trayle/+lX+8pe/oKoqV199Nf/xH/+B2+3ud/n77ruPl156icOHD5OXl8cVV1zBD37wA3y+oU9aKoHQ6InEk1hNKqF4kmTSuGqr6whTnu1kV10Xswrc7GsMkO+1EY1rxJIa+R4bNW1hqgo8HGoJUpHjIhBN4LSa0r2f5MdMDCSR1DCpCkfbw3SGE2i6ztv7mllY4mPjwVbyPDaauqKYVKOZRIy+1HvtsJoIx5Jku6y0BmPkuK1Gkn1SY3qem931XZxTlcfru5u4aGEhHxxqY2GJD6tJJRxPMq/Iy8HmIPOKvTQHohLkjHN7Grr469a6MQ+EJkzD5fXXX09dXR3r168nHo9zyy23cPvtt/O73/2uz+Vra2upra3lpz/9KfPmzaO6upovf/nL1NbW8sc//vEUl170xW4xmqPctmMfw+l5RmC7sNQIVheU9A5a5xZZMpb1OQZPwhUiJZXzVZrlhCzjsfnFxo9krtvGtFwXr+xqoNjvYE9DF22hGPkeOwebg+kTtNQiDd3xNTipmt4in53OiDEl0JxCLx8daeeiBYU8v6WWtfMKeGtPE4tK/Wi6TjShMafQQ3m2kwUlPop8Dgq8NqoKPL0CnHk9jiWASeKfcWt2gYc9BV1jXYyJUSO0a9cu5s2bxwcffMBpp50GwIsvvsjFF19MTU0NxcXFQ9rOM888wxe+8AWCwSBm89BiQKkREmLqCsUSROMaigJbDrezrCKLpzYeZu28Al7a0UBploPmQJSuSIJCr52j7eF0An4qWEr1KpqMUjU5qR5TPYOclmAMVVGYluvkk/ou1s4tYP3OBq5cWsKrnzRy+vQcAFQVpuW6upu6XXRF4saQE7outThTQCCaoKEzwoy8vlt3TsRQz98TojvMhg0b8Pv96SAIYO3ataiqyvvvvz/k7aTejKEGQUKIqc1pNZPlsuJ3Wjl3Tj4+h4Xbz57OjDw3Vy8r4fy5+Zxblc+a2XmcMTOHbJeVSxcVoSoK51TlYbOoTMtzke+1YTEpVBV6ACjLdgKQ4zaGX7BZVCzdVRepmtLUfVOPvLaRxAWpddQeK6eakVNJxDaLceuymdLrpGpqc7vLWOJ3AFCZ68RqVvHYzczKd6MocOZMI6hZU5WPw2pibpGX+cVeFpX6WFGZzenTc5hf7OWyxUVU5Dj5/Kpy5hZ5mFfsZU6hF5vZREWOCzg2zIIEQVOD22Zmeq5rTMswISKC+vp68vPzMx4zm81kZ2dTX18/pG00Nzfzgx/8gNtvv33A5aLRKNHose59nZ2dwy+wEGLSSp2gUyO1V+Ye+xm96YxKAG5YXUGW04LLasbvNGqI2kJxSrMcdIbjrFtQyK/fPcQ5s/N59ZMGSrOcRBMaR9tDLC3P4u29zayclsM7+5pZWOpjW00HuW4bigINnRFmF3jYXd/FjHw3+xsDVOY6OdQcwmM3YzOrNAdi6efmFHrYVdfF3CIPexsDeO1mvA4LB5uDLCvP4r0DLZw+PYc3djcxr8jH3sYuXDYzeR4bO2s7+dSsPJ7fcpRzqvJ4bstR5hR68Tks2C0mpue6cdnMLCj2oelQmePks8tLyXJa0wGYoijkdDdTzcw3AsFUsCcEjH3QO6aB0Le+9S1+/OMfD7jMrl27Tvh1Ojs7ueSSS5g3bx7f/e53B1z2/vvv53vf+94Jv6YQYupKDVBa2X2l63daqTAqTbh2ZTkAXzxzGg6ricsWF+O0mokmknSEvRR47UTjGisqs2jsirCs3EhkKvTaSWo6LpuZ5RVZHGoJcm5VHjVtIZaUZZFI6uR5bNgtJlQ1wMrKbA63BDlrVh617REWlPiwmlX8Tit+hwWHxcSSMj8NnREWl/rpCMVZWOoj32vDbjbhd1ko8tmpzHFy+ZJi8r12PndaGX6npTs3xziBpQZhXVLmB0gHPUJMFGOaI9TU1ERLS8uAy0yfPp3f/va3fOMb36CtrS39eCKRwG6388wzz3DllVf2u35XVxcXXnghTqeTF154AbvdPuDr9VUjVFZWJjlCQogxp+t6egybcCyJw2qiIxzHazfTGUmkp28JxYzRiDsjcbx2izE3nEmVvBsxpUyIXmN5eXnk5Q0+lvfq1atpb29n06ZNLF++HIBXX30VTdNYtWpVv+t1dnZy4YUXYrPZ+POf/zxoEARgs9mw2eSKRggx/iiKkm5ySg0Cmuo12bP3pM9h5Px4u/NtUj3lJAgSorcJkSw9d+5c1q1bx2233cbGjRt55513uPPOO7n22mvTPcaOHj3KnDlz2LhxI2AEQRdccAHBYJBf/epXdHZ2Ul9fT319PcmkjDArhBBCiAmSLA3w5JNPcuedd3L++eenB1R86KGH0s/H43F2795NKBQCYPPmzekeZTNnzszY1sGDB6msrDxlZRdCCCHE+DQhxhEaSx0dHfj9fo4cOSI5QkIIIcQEkcrxbW9vH3BGiQlTIzRWurqMUS/LysrGuCRCCCGEGK6urq4BAyGpERqEpmnU1tbi8fQeyv1EpCLVyVzTNNn3cbLvH0z+fZzs+weTfx9l/ya+0dpHXdfp6uqiuLgYVe0/JVpqhAahqiqlpaWjtn2v1ztpP9wpk30fJ/v+weTfx8m+fzD591H2b+IbjX0cyiTrE6LXmBBCCCHEaJBASAghhBBTlgRCY8Rms3HfffdN6sEbJ/s+Tvb9g8m/j5N9/2Dy76Ps38Q31vsoydJCCCGEmLKkRkgIIYQQU5YEQkIIIYSYsiQQEkIIIcSUJYGQEEIIIaYsCYSEEEIIMWVJICSEEEKIKUsCISGEEEJMWRIICSGEEGLKkkBICCGEEFOWBEJCCCGEmLIkEBJCCCHElCWBkBBCCCGmLAmEhBBCCDFlSSAkhBBCiCnLPNYFGO80TaO2thaPx4OiKGNdHCGEEEIMga7rdHV1UVxcjKr2X+8jgdAgamtrKSsrG+tiCCGEEGIEjhw5Qmlpab/PT7hA6Be/+AUPPPAA9fX1LF68mIcffpiVK1f2uewTTzzBLbfckvGYzWYjEokM+fU8Hg9gvJFer3fkBRdCCCHEKdPZ2UlZWVn6PN6fCRUIPf3009x999088sgjrFq1igcffJALL7yQ3bt3k5+f3+c6Xq+X3bt3p+8Pt3krtbzX65VASAghhJhgBjvvT6hk6Z/97Gfcdttt3HLLLcybN49HHnkEp9PJY4891u86iqJQWFiY/isoKDiFJRZCCCHEeDZhAqFYLMamTZtYu3Zt+jFVVVm7di0bNmzod71AIEBFRQVlZWVcfvnl7NixY8DXiUajdHZ2ZvwJIYQQYnTouj6mrz9hAqHm5maSyWSvGp2CggLq6+v7XKeqqorHHnuMP/3pT/z2t79F0zTOOOMMampq+n2d+++/H5/Pl/6TRGkhhBBi9EQT2pi+/oQJhEZi9erV3HjjjSxZsoQ1a9bw7LPPkpeXx6OPPtrvOvfccw8dHR3pvyNHjpzCEgshhBBTSyiWHNPXnzDJ0rm5uZhMJhoaGjIeb2hooLCwcEjbsFgsLF26lH379vW7jM1mw2aznVBZhRBCCDE0wWiCbJd1zF5/wtQIWa1Wli9fziuvvJJ+TNM0XnnlFVavXj2kbSSTSbZt20ZRUdFoFVMIIYQQQ6RputQIDcfdd9/NTTfdxGmnncbKlSt58MEHCQaD6bGCbrzxRkpKSrj//vsB+P73v8/pp5/OzJkzaW9v54EHHqC6upovfelLY7kbQgghhADC8STaGCdLT6hA6JprrqGpqYl7772X+vp6lixZwosvvphOoD58+HDGMNptbW3cdttt1NfXk5WVxfLly3n33XeZN2/eWO2CEEIIIbqNdW0QgKKPdb+1ca6zsxOfz0dHR4cMqCiEEEKcRNUtQUKxJHOLTv75dajn7wmTIySEEEKIySUYHfsaIQmEhBBCCDEmwvHEWBdBAiEhhBBCjI3xkCMkgZAQQgghxkRYAiEhhBBCTFXhuARCQgghhJiiIhIICSGEEGKqkqYxIYQQQkxZ4fjYzjwPEggJIYQQYgzouk40ITVCQgghhJiCogmN8TC3xYSaa0wIIYQQE18wmiCeHPtmMZAaISGEEEKMIk3T0XWdpKbTEoii6zr/b3PNuOg6DxIICSGEEGKEEkkNXdeJJzXagjEA9jR0AfDuvmYSSY0tR9o51BLiSGuIDw610hGO0xKIUd8RGcuip0kgJIQQQohe9O4EnkRSoysSR9d1PqnvBOD13Y0kkhobD7VysDnIoeYgG7uDnFd2NaLrOtuOdlDfGaGmLcTRtjD1nRHqOyK0dAdMEggJIYQQYkxomhHkxBLHgpyDzUEA3t3fTFLTeXd/C4dbQuxtDPDegVaaAzFe/cQIgLYf7aCuI0JNa5iatjB1HUaQ09gZIRJPUtcRIRRL0hKI0RqM0RKM0h6K0xFO0B6KA9AciI7Z/vckgZAQQggxiSS7c3Ii8SSdkThJTWdnrVGT8/LOBhJJjdf3NHK4JcSuuk7eO9BKfWeEf+yoJ5bQ+PBQG3UdYaOmpyXI0bYwte1hGjojROMa1a0h4kmd5kCU5mCUlmCUtlCM9lA8XdtzqDuoagvF6Awn6AzH6YzE0XSdhk6jJqg1GB+bN+g40mtMCCGEmCBiCQ2LSSEcT5LQdBwWE/ubAlQVeHh5VyPnzcln/c4G5hZ5qO+I0B6OMyvfzet7GinLdrDtaAdVhR4ONAVRFYVANEFTV5Rsl5VwLMm+xgBJTae+I0JrMIbTajLyf0IxmrprcA40GUFOfYcRGHWE4qiqgqbr6eauuu7bxs4omq7TFU2Q6K6FauoytqONh77zSCAkhBBCjKloIonNbKK+I0KO20pzIEpS0/HYLWyr6WD1jBz+8OERrl5Wygtba1lc5qemLUw4lqAix8WrnzSS47Kx/WgHM/Pd7G8KYDUrtARidITjuKxmonGNHd21Qgebg3RFEjR2RQlFjaaqVC3N3kYj0flwa4ikptMeipPQjPF+jraFATjaFgKgtjvYCUQTKIoCHAuA6ru319hl3EbjGomkEfi0hWKj/p4OhwRCQgghxCgJxRI4rWaOtIYo8No52m4EE3aLyubqds6dk8ev363mhtUVvLC1lhWV2RxqCZJI6pRkOdhU3UaB10Z9R4Q9DV0cbg3hsplp6DRycFRFIZbQ2FrTDsCuuk5iCY2GTqO5KhrXONpuBC57GwMA7G8ybluDxvNgBD4ANelgx7jtiiTSNTepnJ627hyfzrBxG0/qgLFMahLVWELr8Zwh2V0jNE4qgtIkEBJCCCGGyJgWQsNmVqnriFDsd7CztpNpuS72NwWwmFSsZpWPjrSxZnY+T75XzedXlfOXrbWsrMxmT0MARYFct409DV1ku6xE4kk2HmyhK5LgQHOA2vYISU0nqetous6m6jYAthxpR9eNYMVIcIZDLUYz1e7uLusHuoOcVJMUHKulae5ukkolK/ec8DT1fyqASTVj9Wy+6iuAaQvFsJlVnNaJG05M3JILIYQQJ0DXdRRFIRhNYDYpJJI6baEYeR4bWw63s6Iym5d3NbC8Iosth9tx28xYTArbj3Zw9uw8/vRRLZctLuKlnfUsr8hiV10nVpOK32nlUHMIm7mFhKbz6ieNROMaO+s6aQkYzUJdESMY2XLECHJ2HDWarapbQumAI1Urc3wgk6qJAQhGjQAmGteIJTR21QUoy3Jit6jsqO1kRr4bt210TvV7G7v427Z6clxWvnB6xai8xqkggZAQQohJJxhN4LSaaApEsVtMhKJJGrsilPgdvLGnifPm5PPHTTWcPTuP9w604HdaURUjEFlY4mNTdRtdkQQ7azsJRBIcaQthNavYzSY6wnFe390EwMu7GtF1+PhIO/GkTpAkHeEEALvrjVqaVHNTKggyyncsgIFjNTAjbTbSdZ0/fHiElmAMq1kl32Ojpi3M3sYAVy8rSefwjFRjV4StNR0sK8/CazfTFIjyt231ALQEjVwkr918wq8zFhRdH2+tdeNLZ2cnPp+Pjo4OvF7vWBdHCCGmrKSmY1IVWoMx/A4L1a0hXDYTHaE49Z1GkPPa7ibOnpXL37fXs6w8i61H2/HaLSQ1ndZgjAKvnYbOCB67ma5IAqtZTTcHqYrR80lRxl8ey0BiCY3H3jlINNH33F0mVaEsy8GMPDcLSnzD3vZTHxxO5wUN5nOnlVLkcwzrNdYtKGRu0ck/vw71/C2B0CAkEBJCiJMrddqJJjTiSQ2TqnC0LUxplpMtR9qYXeBha007eW57eoyaIp+DDw+1srjMz4eH2qjMdVLdEuru3q0TS2jpoGaiBTInamddJ+t3Ngx5+WtOK6PQZx90OV3X+fWGajrC/QdBFdlOqrsTrVOK/Xb+aVnpkGuHJBAa5yQQEkKIwYVjSewWlaauKHaridZAjFAsidWscrA5SJHPztaaDipynOyo7cDvtNIRihOJJ3HZzHSE49gtJiLxJCZVSfcwmir2NnbxSV0Xn55XgN1iGvJ6n9R38o8dx4Kgc6ry+KSuC6fVxLlV+Tz+7kH6eiu/smYGVvOxMZVTvdCm5boIx5L8ZWttOjepP59dXkqB186be5vYWtPR6/mFJT7Om5M/6D5IIDTOSSAkRG9JTUcBQvEkJkUhGDNyIhLdV+Zmk5GAajOb6IzEsZpVgt1jjSQ1nWg8icWs0hmO47Ca6AzHsXXncagKKAqE40lcVjOdkQQ+h4XOcByP3Uy0e0A5i8m4+vfYLQSiCfxOC8FoArfNTKK7CSVVQ+C1WwjFjGVCsSRumxlNN5oMHBZjwDif00I0ruFzWEhoGjazCbX7gnYi5j0MVyRudMXujMRJJHV09PQYNPWdEXwOC0fbwtgtJtpCsXTNS31HhCynlaPtYbzdx2kqBjInQtN0Hn5tHwCFXjsrKrOYlusa9HOn6zoPvbovff/KpSWUZzszlglEE/z2vWriSS0jICr22/ns8jLAOIZPf3gEgFn5bvY1Bjj+6F23sow8t40DzUHC8SQLins3sW2qbuPtfc0Zj/VVpuNNqECovb2d5557jrfeeovq6mpCoRB5eXksXbqUCy+8kDPOOOOkFH48mSyBkKYZP2pxTaMrkiCWMHoYhGJJFMVILDSpSnpcimjiWLfKeFJPn1DsFjVdBa13n0jMqoKmG+NiJDUdm9mEjo5ZVVEUo93dpCqAjsVkrGcxqRnLKIDafdYxqwq6bqynoxu33Z9SRek+CSvHxqdIaEa7eFLT6f6XWNL4J5pIomDsj45xoo4nNRSME21qn82qkm5f13WdWFLHYjKes5nV9G00oaEqSrocNrNKJJ7EYTUTiSexW0wkuqv6U++Lo3tkVofFZKxjUbv3U8ViUgEdm8WEruvYzSZ0jPdHVVLvr/EemU3G+2BWFXSM9yf1nhjvkZ7OcVAVhaSup/dH042mgnj3+5J6f2IJY6C0hKalT37RuHGCi3TfhmNJNB1iiSTRhIaO8VjqtSYrU/fn0KSC3WJC18FlM5PUNBxWM7puHDeToqAqpL8TdosJTTc+GwDm7mN57HtgHEswPgNAOuACI+hKH0Mtla+iY3xLdHTdOOYJTU+PIaMoxrHUdN0IRpMaCgqhmPG9DsaMgDUcT6JpRpfscDyJ2aTSEYphM5u6B8WbWk1K48VrnzSy9WhmjcpgPbF21XXyUo/msDNm5HBaRVafwVM0YRx/s0nlha217O8eGfpzp5V21/7UDVi+m8+oxOewDGlfqluCPP9RbcZj03JdXLaoqN/AbkIEQrW1tdx77708+eSTFBcXs3LlSoqLi3E4HLS2trJ9+3Y2bdpERUUF9913H9dcc81J3ZmxNJECIU3Taewy2tPbgjFaQzFC0SQtwRjxpCZXaEIIMQ79+t1DtPeRh1PgtXHtivJejzd2Rfj9xiPp+4VeO9esKBvSa4ViCf7rrYODLlfotbOkzM+sAnf6omsodF3nw+o23t3fkvH4jDwXly4q7nOdsQ6EhtR9funSpdx0001s2rSJefPm9blMOBzm+eef58EHH+TIkSP827/928hKLoasMxLncEuIxq4INW1h2oLxSX2FLoQQk42m6XR0jym0qMTH0Y5wupt9Q2eU/U0BZuS5M9b56Eh7xv2rl5UM+fWcVjNXLCnuVWsDMLvATTieZHGpn2k5rnQt/XAoisKKymzmF3t5/0BruqZrf1MwPW7TeDOkQGjnzp3k5OQMuIzD4eC6667juuuuo6WlZcBlxcjouk5dR4S9jQEONAXSo4MKIYSYeI62hfnj5pr0/TVVeajdAzz+37eNWpsXuputFAXOmplLkc/BrjpjfKLFpT7WzM4bdnBRltU7Z+eqpSWUDZLLMxxOq5lz5+SztNzPrzdUA8bo13MKx1/LypACocGCoBNdXgwsEE2w42gH24520BVJjHVxhBBi0moLxUgkdfI8tpO2zXAsSXs4RqH3WJf1SELLCIIUjuX9uWxmlldkpafWACN36829zSwoORZIjCQIAiMf85YzKtnT0EUkoWE3qyc1COrJ77RS5LNT1xHhHzsa8NotFPuHN87QaBvRyNK1tbW8/fbbNDY2ommZAzh97WtfOykFE0bT1wcHW9lR2yn5PUKMgqSmG/NE5blGbRoCMf41dEb467Y65hZ6+eBQK6qqcOunpuEYRjd2MDqdBGMJLCZjBGpVhdr2CH/+uHcz1PGuPS7HZ2GJj4NNQVqPm6l9e/dUHKun55xQM5PXYeG0yuwRrz8cZ87ITQd9z2yq4aqlJbz6SSMVOU7WzM47JWUYyLC/+U888QT//M//jNVqJScn80AoiiKB0EmQSGp8cKiNDw+1poddF2K0dYbjbD3awfKKrGGfACLxJJquT7iJF3/e3WWZ3fAv58zo7sVniMaTBGNJ/E7LsJJFxfij6zrbjnZQ6LOT77ETiRu9QFPnr6c+MBKPNx5qBYwAeWtNO6um5aBpOi/tbCChaXx6XgE2c9/fjc2H23hrb3Ofzw3mjnNmYO7x2QPwOSzcsNroNXaoOch7B1to6Iymn89yDq0X13hQkuXg/Ln5vLKrEYBntxwFoL2mY1SSpIdr2L9a3/nOd7j33nu55557UFV18BXEsDQHovx9Wx3NgdjgC09Quq4TihmDqImxF40neXbLURq7J3TcVN3GV8+dOWCi5Dv7mmkLxVg7t4D9TQFe7v6BA2OQtZFUfR+fSNnQGSGa0CjPdhJNJNNjBp0sTV3RjPtv720m32sjy2nFZlb57fuH08+dMzuPRaW+cZnoORriSc0YFmAEybLjTTiW5P+8daDX47Pz3axbUEioxwzsPW053M7yiix21namZ3bf/4axHY/dzKWLishx2egIG4NCjjQIuvXMab2CoONV5rqoyHHy2DuHCESN9Ijx1rw0mPlF3nQg1FNrMDbmLR7DHlAxJyeHjRs3MmPGjNEq07hyKrvPH2gK8Pft9el5b0ZLalwZUz8/coFogl91J+rddta0k36Vv35nAzvrOrl0UVGv3hDi1OqZlNnT8oosPjUzt891dtd38eKO+gG3e/mSYipzXEMuR8+xR3LcVmbmuXn/YGvv7S4uptjvyBgRdyTqOyO8taeJ2kFGzu1peq6Lc6ryMoKx3fVdfFDdytmz8ijPdhKJJ3l9dxPzi72jlnPRl511nRxsDnLenHw6QnHyvbYR12I1dUX5/QeH0XXIc9v43IpSjraF0XTYeLCVlmCUq5cZIwrDsekyxmuQ+MS7h/qdImJmnpt9TYF+17WYlPR4ZSfivDn5VOQ42dcQoMhvx+ew8OonjUzLdTG/j4EJ+6PpOkdaQ5hVlZKsiRUIwbGBG/sacPP7l8/nxtWVJ/X1Rm1k6f/5P/8n2dnZfOtb3zrhQk4EpyoQ2l3fxYvb609J9/fnPzpKdUuIGXku1s7tPZz7nz46yqGWY3PHLC71GTMOD3FArYHEkxr/+fp+wOiqedGCohPephi5N/Y09eqKm/Kv58/q9Vg8qfFfbx0Y9ORgN6v88xrjYik1OGBf2kMxYkktY0yUoVhW7ufMmbkZ29V1Y9BQn8PS66Sc1HSe23IUW/es3O/1CLJOq8jiwx5JqT157cbI1j1ds6KMQq+dznCcx989lH784gWFvLO/JX3S/cziYqblDj0YPBH/8crejPtZTgsLS3zsrOtkZWU2swo8Q9pOX2PM5LltNAWifS5/0+oKnttyFJfNzNXLSvu9uBorb+5pYkuPz3cqabcvi0t9lGY5aQlGqWuP9J4/y2cfNHBeWOJjTqHHWFc3fuPsFpPUfvfh7b3NbDp87Hv38HVLuWxx3+MMjdSoBULJZJJLL72UcDjMwoULsVgyT44/+9nPRlbicepUBEI1bSH+36ajox4E7W3o4m/be1/Jzyvycv7cfFRF6XewLZtZZVaBm121XZw7J29YVzEpmq7zu42H02NkpLZ766emZYy6K06NeFLjkTf2o+nGCeKKJSW0hWI89cERVAX+5ZyZvY7JjtqOdDNYz1m7z6nKo9BrZ3N1G3sajSvsr6yZQTie5JlNRyjw2DljRg5+pzU9Aveehq6MkXGHK99j48L5hWS7rOi6zut7jPmOTqvIojTLgaooFPnsvH+wtd9AB+DG0yuwWVT+/HFtRg5Gqd/B1ctLe30nspwWzpyZm+7WPJBbzqgkqetkOa0j3s/jaZpOfWeEP26qQYchTWdx+1nTcVj7z/tqCUQzmgJHKsdl5ZyqPIr9Dt7Y00Rte5grlpSkA4FgNEFXJDGkCT9PVFNXlN9tPLZPqebeRFLjr9vqMi72spwWrltZns4R6wjHeaJHkFuW5eCqZaXEkxqbqtv6rK20m1VuP3v6uK0ZG2+aA1Ge7PGZ+/jeC/Cd5LynUQuE/tf/+l/ce++9VFVVUVBQ0CtZ+tVXXx15qceh0Q6EIvEk/72hOt3uO1qSmn4sMbQP/7SslAKfjV+9dTDdnTLSTxOdWVX457Onp9u1o4kk7+xrYV6Rd8AfuP+3uYaatnC/z+e4rFyyqCjjpDFQbYLon67rJHU9PYVDX2rbwzyzqQabWeXL3bU3uq7zyBsHiCU1Zue7uWihUWN3sDlINJFkR20nNW1hVk7LZlGJj/cOtLCwxEd+j27Bv3r74Ig+z9lOK7MK3DR2RTnYHOTMGTnMLfLSHo5jNakZJ7We6yyr8GfkKA3VvCIvqgrnVeVn/I7VdYSpbgmxtNyfTox970BLnye/obKZVdYtKBxWc2F//vxxLQebg8Nax2pS+dJZ09In+tr2MIdbQ3xc0040rvWaV2pRiY9z5+Rn1DSVZjmYmedmdqGH//Nm75ybgdx5rhFUP/l+Nc2B2JBnPx+ORFJj/a4G9jUGmJnvZk/DsSavyxcXU9mjdq41GOMPHx7BbjFxxZJi/H0Eqpur23hrXzNeu5mbz6jsFeAcbg3hc1hIajq17WFKshwnNeCdCtqCMfY3Bbj7gtksrzj5PdhGLRDKysri3//937n55ptPtIwj8otf/IIHHniA+vp6Fi9ezMMPP8zKlSv7Xf6ZZ57hO9/5DocOHWLWrFn8+Mc/5uKLLx7y6412IPTGniY2H3e1uv1oB6980sj8Yi9r5xac0PaTms7fttVx4Lgfzum5rl6Plfod1LQbgcqn5xbgtJoIxBJsrm6jbYDBG1NzcEH/OUWv7Gpge21n+v6SMn+/TTKXLSqiNMvJL98wmtBcNhPr5heS57Gxu76LGXnuAauaNU1nw4EWivx2pudOzRykDftb2HiolbVz85ld4DEG4mzoorYjwow8F1trOtLHbGa+m0sWHmui7HmivWJJMbXtkXRvmpTrV5WT6+57nJW+5k0aijWz81hS5geMBG7bcU22se7JVuNJPf3ZGKmqQg/r5hcOa52+8qkKvDbOq8rn9929jop8di5aUMhTHxzpMwk31dy48VArde1h2kJxVk7LZl4fPWeSms7B7t5Cs/M9rJyWzYGmQL/zQq2bX0hVoYemrihPfXC414zjlTlOLl9ijEB8fFNaT/keG587rQyTqvDW3iY2H26nIsfJFUuOjV4cT2r8bVsdbaE4hT47u+u7+t1eyvHNUsU+O2vnFZy04OFv2+rY29g73+f8ufl9ThA6mKRm9DQr8tnT+VBidIz1FBvDDoQKCwt56623mDWrd/7AaHv66ae58cYbeeSRR1i1ahUPPvggzzzzDLt37yY/P7/X8u+++y5nn302999/P5deeim/+93v+PGPf8zmzZtZsGDBkF5zNAOhaCLJf72ZmW9x/GzCC0t8nFs1skGzwBiK/Y09Ten7lTlOzpqVR5bTQkNnlFc+aeizh1rP7pzD7RZ6fG7J8U0LlywsYma+m6Sm8+ib+4edjFia5WBmvpvXdxv7tbjUxzlVx45/zxmQbzi9gmyX8UOraXq6KWG4YgmNl3c10ByIUuJ3cNasvBNO2B0txzcJDCZ1Ak1JJDX+/HEtR/qpvXNaTXzpU9P6/UzGEhq/3nAoIxDIcVlpCfb+nOW6reR77KgKnDsnf8i1fz0T+ofiznNnoirQHIjxcU07y8uzyHIN/wTcHorxwtY6wvEkZ83KparAk54kVeFYwvDb+5ozBsNL+eKZlfx9e32vPJWKHCcOiwm/00Kp38lrexozmpDBCLp6Nt1dsrAIVTESv0OxJOdW5ac/23UdYWIJjVy3LSN4s1tUIvG+a3pdNhOfX1mO1aRm9GIayrQIgWgCp9XElsPtvWYfH8zXzpvZ7/Z1XSeS0LCZ1X4/Gx3hOH/66GifF2sXLyhkZr5bmqvGuQkXCN1///3U1dXx0EMPnXAhh2vVqlWsWLGCn//85wBomkZZWRlf/epX+0zevuaaawgGg7zwwgvpx04//XSWLFnCI488MqTXHK1AqCMU51+f2oLfaaGiR3X50fYwf9xUk7FsKnAYji2H29h8uL1XE0Vfw6gfaA7wl4+PXWWurMxm9Yxjo4Prus7BliANHVHKs50Zo6H2ZXa+mz2NAc6alcuy8iw2HmxlwwFj2pVbzqzE26PXTVckTmNXFK/dwtaa9oxao+FaXpHFmTNy0k07Pfclqen893vGMO/Xrihjy+F2YgmNqiIPL+9qoDzbydIyPx67hbqOMCZFSTf36LrO37fX97ravGJJcfrYpWacbw7EeP9gC8srsijyndpeHdFEkj98UNNrALaBnD0rlyVl/l4niuOD3zNm5BCKJWkLxVhY4htSb7+mrigfHGrl9Ok5ZLusfHColU3VbVy1rISmrig7ajs5b05+vzVLg2kLxvhN9zGdlutiRaXxnrcGY0QTSQq9drYe7aDQe/Kv6AcLDj6p7+QfO4z8p4sWFPLGniZCsWRGreuJyPfYuG5l78k4ByvL8W791DQ2HmxlV10n/7S89ITfJ03TaeiKkOexYVZVIvEkT7x7KF372F8Z+hvM8rktRzncGuL06dmsmnbsN6k1GOPDQ60caQv3+o372nkz2XK4HYfVNC7GqBGDm3CB0JVXXsmrr75KTk4O8+fP75Us/eyzz46sxIOIxWI4nU7++Mc/csUVV6Qfv+mmm2hvb+dPf/pTr3XKy8u5++67ueuuu9KP3XfffTz//PN8/PHHfb5ONBolGj121dXZ2UlZWdlJD4T+xzMf80x3wJM6oR5qCfKn7i7EM/KME+z+piDFfjufXT60mYWh7xqBL55Zidtm7vfHO5Uv4rSaupNH+06s7BkU2MwqVy0toaY9TI7L2uckfj2tmpbN6dMHnn7l+PyHfI8tPb7NUFy5tITnugfrSvnaeTNpDcaGlAyqKqSbFFKB3EA1Ymtm56Hpeq/ns5yWk94VtD+f1HViMau8u7+F1h61Lsc3f960uoKOcJw/f1yLWVW5flV5vz0Be9binVeVz8LS4TctnAo1bSGauqIsLvOPq1yyVI2VxaTwlTUz2HCghQ8OZdYQLSj2EowlB833yXFbM2qHctxWrlpaMqxhLf7fpppeAVjPQH60J8PccriNjnCcVdNziCc0DjYHeb27pvpTM3NZXpEFGBcUiqJwpDXEy580EIweq1W8eEEh+V6j6/nft9Wlk/J7unZFmTRjTUBjHQgNu0+f3+/nqquuOqHCjURzczPJZJKCgsycmYKCAj755JM+16mvr+9z+fr6/sdAuf/++/ne97534gUexK76YzUfz39U26vau9jvoNjvYH9TkNr2CP/nzQNctriItmCcAq+NnO6r6ANNAUKxJPOLjaTSjQdbSRzX1DSn0DPoQHTFfkef3aWPpygKFy0oZE2PARFTNSdnz8rlzQGa0OYXD/5BP2tWLsFogsauKDluK9euKCOp6yQ1HZvZRFckzmPvHEovf/6cfF755FiibKoZ0GExEY4bP6IvbK1jTtHQug/3zKvYsN9IAN9Zd+xY3bS6gk/qu9KJsz2bHXtqC8XZsL8lo2btZNN1nec/quXwcd18wWhSPW9OPq980kBDZ5RLFxXhtVvwO63cdtZ0kpo+YJ6V02oe0udhrJVmOSntYwLJsea2mbnh9AosJgVFUVhU4s8IhHrWcLQGYxxqCTIt18VvuienBKMJ94J5BZRlO9PJyedW5bGo1D/s8ly9vJRgNMHexgCVOc5eycGj3XS0tDwr/b/DYmJxdy7Y63uaONAcYG6Rh40HW/m4pv/cslSP12m5rl7B4+rpOaycdmqmixCTz7ADoccff3w0yjFu3HPPPdx9993p+6kaoZPth1cu5Nr/8146j6JnEFSe7WRBsQ+rWWV+sZcdtZ2E40n+8OGxJqk7z52JpuvpxMn9TYGM7qBg5B2srMw+6VdIiqL0eRJdWp7FjrpO2kNxLKqS0evsC6vKhzQqcJbTynUryznSGiLLZUVRFMyKQiodx2O3UJnj5FBLiBWVWSwo8VGW7eTlnQ3UtIfTNSJLy/28u99ojjvQHEzXjCgKFHkzxwO5cXUFGw+28slxCZ8JTefRHr1jLlpQiN9p5fTpOXRG4ukZoPuz8VArO2qNYf2bAzHOrcrLaAY9UYdaQn0GQakZqQHOn9M72f74caPE6MjukYPktpuZW+hhV30Xa7pHqe65XGrZ61aW8fbeZhaU+JjdY+yfr6yZQWswdkI9rVw2czoZfTyoyDEC2Nr2SJ9DdvSnZxCU47Jy8cKijPdaiOGaMKM85ebmYjKZaGjIbOtuaGigsLDv3h+FhYXDWh7AZrNhs528WYf7s6jUz0tfP5s/fHAkIzk6z2PjiiXF6Su0JWV+dvSRN3N8V/jjgyBFMZJgT/VJ7/qV5caYJgo0dkbJ89hIaPqw564aaFTedQsKOdgUTA8S53NYOHdOfjoHCIxgsjTLkRE8Alwwr4A5hUbNVENnBJfNjNtmTl95v3eghbNn5ZHQtIy8igKvjVk98rTOn1PA0bZwr8H2ZuS5iMa1dDNEMJZkf5Pxw/38R7V89dyZKArsawzQHo6zpMyfMb9VSiyh0RyIUuSz93m1Hokn+5zIcfWMHJaU9s75EWPvgvmFrJ1XMGATXr7HzlXLSns9bjWrp2TsnVPJ10+zbJbTQlsozvRcFwtKfOS4rWyubuOT+q6MXKN5RV4+Pe/EetUKAUMMhNatW8d3v/tdTj/99AGX6+rq4j//8z9xu93ccccdJ6WAKVarleXLl/PKK6+kc4Q0TeOVV17hzjvv7HOd1atX88orr2TkCK1fv57Vq1ef1LKNVLHPkZGjUZrl4KqlJRknsVy3jc8uL+Xv2+uHPDbLp2bmMjPfPSZX/oqiYDYZ5U/NhXOyi2Ezm5hzXHtytsvK1ctK+KS+i8ocV7oW7IwZOemaoXyPjdn5x66ye9aUKYrCvCJvRjdmi0nlha11qIqRdN3zuJhUhc+vKufVXY1YLSprZuURTWg4rSZCsSTrdzVQ0xbuNdDdL17fx2mV2WzsblqLJjRK/A5yXNb0Z6FnF+mzZuayrOJYs0JXJM7Wmo6MAQIXlHgpz3KS5bKOOPFYnBrjKY9prCmKwqx8d0YnhON7MKacU5XPOVX5HG0P0xyIMrfQO257bYqJZ0jJ0r/61a+499578fl8XHbZZZx22mkUFxdjt9tpa2tj586dvP322/ztb3/jkksu4YEHHqC8fGg9Gobj6aef5qabbuLRRx9l5cqVPPjgg/zhD3/gk08+oaCggBtvvJGSkhLuv/9+wOg+v2bNGn70ox9xySWX8NRTT/HDH/5w3HSfB/j4SDuPvrGfD6rbuGh+Yb9desPxJKFoghy3rVeX+PJsJ/UdEUqyHFy6sGhSTJR4MqVyhYZbKwVGHk40oY04qNx+tINtRzsGTfh228yUZjl6Nc+5bCZuPfNYV/WXdtSz67hlRmM+OCFOBV3X2dcYoMBnxzNAZw4xuY11svSQe41Fo1GeeeYZnn76ad5++206OoykNkVRmDdvHhdeeCG33norc+fOPTl70I+f//zn6QEVlyxZwkMPPcSqVasAOOecc6isrOSJJ55IL//MM8/w7W9/Oz2g4k9+8pNxNaCipuk8s+kIte1Dn/wRjKaTPQ1dqIrC3CKP/IBMAD2HERiO0yqyOHNmLvsaA/x1W+ZgehIECSEmugkTCB2vo6ODcDhMTk5Ory70k8mpmGusKxLnqY1HRn2aDTG2YgmNx945SDShsbw8K2PCwZ4WFHtZNS2HzYfbMiaMPN4/LS+lxD/xZqAWQoiexjoQGvGlpM/nw+cbn2OLTDQeu4WrlpXw7OajEgxNYtbUpIwYNalzijy8tbcZl9WUbu7qOSfSWbNy2dPYlTGWSspgk2gKIYQYGsk2Gydy3DY+t6KMXI8ku05mqqKkmzFz3TauXFrCOVX5VOQ4+dTM3IyJIRVFYWVl77FRLpxXIEGQEEKcJJJcMI74HBauXVHGm3ua2DrAwGJicrGa1YwJLXtaWOLDrKqs32V05f/ymunpGdGFEEKcOAmExhmLSeX8uQVUFXp4bXcTzcOYXkJMPoqiMK/YS1WhB1UZ/RGAhRBiqpGmsXGqNMvJF1aVc+miIvKkuWzKM6mKBEFCCDEKhh0I3XTTTbz55pujURZxHEVRmFXg4fpV5Vyzoox5xTKImBBCCHEyDbtprKOjg7Vr11JRUcEtt9zCTTfdRElJ3/kN4uRQFCU9CevauTqHW0McaApwpDVEWyg+1sUTQgghJqwRjSPU1NTEf//3f/PrX/+anTt3snbtWm699VYuv/zySTem0KkYR+hEdITjNHZGjAlHAzEauiJE49rgKwohhBDjwFiPIzTiARVTNm/ezOOPP87//b//F7fbzRe+8AX+5V/+hVmzZp3IZseN8R4IHU/XdUKxJK3BGK3BGKFYkpZglFhCozUYI6HphGO9x6UZzxQFUp/Snv8LIYSY+MY6EDqhXmN1dXWsX7+e9evXYzKZuPjii9m2bRvz5s3jJz/5CV//+tdPZPNiBBRFwWUz47KZ+53BPZpIEk/qxBMaoXgSBQhGE5hUhWA0iUlViCaS6IACxJM6VrNKNJ7EbjERT2pYzSqaDqbuSVZ1HWwWFU3TsZlNaLqOpTufSVWMZF8Aq0lF1zHWAcyqgoKC0mMZk2I819+UaalAKK4ZNV9JTUfXQdN1NA10dGJJDQVjPxRFIRo39ieR1IknjfXCcWNfw7EkZlUhktBQgKRuvDcWk0o4nsRmVgnGklhNKrGkhqoY4wHFk8YcZJF4EofFRCShYTerJDUdVVWwmBSSmjHHWVzTcFpMJDQdu8V4X0yqiqV7glq7xYSuG++drhtd6lUFYzuqsXzP98x4X5XuY278r+s6qqKg6TpK9y1kvi+J7vcqntTSt5quk0gaz4FOJK6hKBDprlmMxJNouk4soRFLaGg6BGMJTIpCoPtzE4oZA4HGu99fs6oQT+rjNnBNvU9q9+c3kdTxOszEEho+h4V4UsNpNac/lw6LCU035oSLaxouqxlN17FbTOnPg82sogP27s+/zXLss64qxl/qM546hqkJilVFQYH0dy51m9R1FFLH1Ci7rhvHPKkZ5Tc+68bI5UldJ6kZxwog1P3ZTh2ncCyJ1v1dCceSWMwq7aEYNrNKSzCGWVXoCMfTxy4aN45lQhuHB1GIk2TYgVA8HufPf/4zjz/+OC+99BKLFi3irrvu4vOf/3w64nruuef44he/KIHQOGUzm7CZARtkDbr0+JM6IdhUGU8nU/dJtfvWxKnvZdazgjnaHUwGogkjmOweNV3TjeDKalbpDMdxWE20h4zbYDSRDvCiiSROq5nOcByf00JXJIHHbiYa1zCpRuARTWh47Ra6onGynFaC0QRuu5lE0ghGbWaVWELD67AQiibwOixG4No9IKWqKOmgZDz2yhvKD/RIJwQeTFLTiXRfCLQEY3jsZmrbIzisJtqCsfRFRn1HBL/Twv6mIAUeG/ubgrjtxnFLXTRF41o6+BRivBl2IFRUVISmaVx33XVs3LiRJUuW9Frm3HPPxe/3n4TiCSEmkp7BROoE7XNYMu73VOC1A1B6CiJyt83cbzlEbybVqF2GY8dpZr4boM857s6YkQscC4Yjcc2orVKgtj1ModfOtqMdVGS72FHbgd9ppbErQlckgc9hYX9TgLIsJ4dbQ2S7rLQGY1jNKomkjqbrUjMlRs2wA6F///d/57Of/Sx2u73fZfx+PwcPHjyhggkhhJh4UsGww2rCgRF0eguNYPisWXkAlOdkNtvrutEka7eo1LSFKfTZqW4J4rVb6AjH6YzEyXPb2XS4laVlWby8q4HFZX42Vbfh667l6wjHyXZZaQnEcFpN6WZBCZ7EYE44WXqym2jJ0kIIMVUEownMJiO3sSMcx++w8MGhVlZOy+av2+o4fXoO7+5rJsdtI5bQONoeZkaei111XVTkOKluCZHjNoIni8kYtDSWMJrzYgmjCTapjd9ct8liQidLCyGEEGMl1XRnM5vIdlkBuGB+IQDXr6oAoDzbiUlRiCY0uqJxvHYLOW4bS8v8vLyrkeUVWWw82EqW00JS19nbEGDltGzW72zg3Kp8Xt7VwKJSH7vqunBaTTitJmrbI5RnG814eR4bTV1RPHYzXZEEikI6L8piGt+dBoRBAiEhhBCTlsVk9Lp0WE3pJPkVldmAURMBcMmiIgA0TWdFZTY2s0q2y0qx34FJVZiW6yLfY0/3Etxd38WKadn84cMjXLSgkKc/PMJpldlsO9qBzazic1j4pK6LZRVZvH+glQXFPrYd7aA828nR9jAK4HdaaA7E8DsttIfiuGwmgtFkujYKSDftHesNKgHVaJBASAghhMAYrsLe3Ru1uDshfF6x0aSyoMSXXm56npE0fvtZ0zGbVK45rYwsp5UCrw2TqmBSFLKcVhaW+KhuCfGpWbnUtIVYUOJLD5mQ67bRFmpj5bRsXtrRwPKKbN7c08SMPBeHW0MkNSjJcrC/McCMfBd7GwJU5Dg51ByiwGunJRAloenkuq00B2L4HEY+lQRUwyeBkBBCCDEC5u7aphy3MTF2ke9Yb7rUY9etLAfgmhXl2C0qBV7jcZOq4LSaqCrwsLu+i0WlPvY1djEz34NJVUkkNYr9DmraQiyvyGJvQ4ClZVkcbQtTkuXArCoEYwnKc1w0B2LML/by7v4Wqgq9bK5uo8Brpz0UIxBNUJ7j5EBTkJIsB0daQxR67dR1RPA5LITjSWIJLV0zlWric1hNxlhT3eOh9ey5N9kCKpnBUwghhBhlDqsJRVHwO634nVY8dgtLy7Mwm1SuWlaKxaRyxdISZuS5OGNGDp+alcucIg8XzCuk0Gtn5bRsyrOdLCr1M7fIw4x8NzPz3VTmOPE6LCwo8aEoMKfQg8dupthnJ99rJ8dlTQdocwo9gDEMgqJAtsuK32nBpCqUdw/Ae/yt12HBbTfqTAp9Rm/x/O5gLhXs2Swqzu5mR2/3cBmp4SpSzZGp3Ck4NqDoeCGBkBBCCDEO2Mym9OwAHrsFm9nUHbQonDkzF1VVOHt2HvkeO0vL/JwxI5fybCdXLCnGZTNz4fxC8j02lpb7qSr0MCPPxfQ8N2XZDrwOC7MK3OmgJ8dto8BrJ89tI8dtJd9jBDlzCo2mwLIsJ1azit9pJctpwawq6fGjSrO6b7vve+zHgqWi7mApFTQVdo9B5bSa8HQvkwqgxgtpGhNCCCEmGLVHrUoqsEh1QV9eYSSDZ7usaLoxXdHlS4qxmU18el4BeR4bi0p8lGY5aAvFcNvMlGU7yHFbKc1yYLOoFPnt5HtsFHhsRBMa0YRGrsd4nZn5bj481Eaex4bHbibLaUFBoT0Up8BrZ3d9F8V+B/saA+R5bNS0hXDbLMYo5cTI99ho6Ixk5DGNJQmEhBBCiElIURS6c7PJPS5YWlzmB4xgaXquG1VVuHJpCaqqcPGCInJcVhaU+Mj32AhGjcEpi3x2fA4LhV47TquJfK+NXLfxp+vQEY6T0z2MwYw8F2/uacLvtOBzWPA7LVhNKlazSkH3KOPZLiv1HZFT/r4cTwIhIYQQYopSFCU9f6PHbuT3VOa6gGNBU47baA5TVYUrlpagKAprqvLIc9uYVeAmz23UGsWTGoU+O1lOS3culIV8j508j41sl9GjLhUYAeR7bBIICSGEEGL8SzXFpQauTOUSzS82hhXQdZ1Cnx2LSeUzS0oAY0qVXLeVmfkevA4zug6dkTg5bmMbxX4HW2s6TvWu9CKBkBBCCCFOiKIoWEyZwVJqkt7Ura7rZDlzsZpVZhd40gHRWJNeY0IIIYQYdYqipLvQX7ywELvFNMYlMkggJIQQQohTSlEUbObxEYKMj1IIIYQQYkqxmlRM42BwRQmEhBBCCHHKKYqC3TL2YcjYl0AIIYQQU9J4yBOSQEgIIYQQY0ICISGEEEJMWQ4JhIQQQggxVaVmrR9LEggJIYQQYkxIjZAQQgghpiyH1AgJIYQQYqpyWsd+pi8JhIQQQggxJiRHSAghhBBTlssmNUJD1trayvXXX4/X68Xv93PrrbcSCAQGXOecc85BUZSMvy9/+cunqMRCCCGEGMh4qBEa+1BsiK6//nrq6upYv3498XicW265hdtvv53f/e53A65322238f3vfz993+l0jnZRhRBCCDEENrOKeYznG5sQgdCuXbt48cUX+eCDDzjttNMAePjhh7n44ov56U9/SnFxcb/rOp1OCgsLT1VRhRBCCDFEiqKMefPYhGga27BhA36/Px0EAaxduxZVVXn//fcHXPfJJ58kNzeXBQsWcM899xAKhQZcPhqN0tnZmfEnhBBCiNHhGuOeYxOiRqi+vp78/PyMx8xmM9nZ2dTX1/e73uc//3kqKiooLi5m69atfPOb32T37t08++yz/a5z//33873vfe+klV0IIYQQ/XPZxjZPaEwDoW9961v8+Mc/HnCZXbt2jXj7t99+e/r/hQsXUlRUxPnnn8/+/fuZMWNGn+vcc8893H333en7nZ2dlJWVjbgMQgghhOif2TS2jVNjGgh94xvf4Oabbx5wmenTp1NYWEhjY2PG44lEgtbW1mHl/6xatQqAffv29RsI2Ww2bDbbkLcphBBCiIlrTAOhvLw88vLyBl1u9erVtLe3s2nTJpYvXw7Aq6++iqZp6eBmKD766CMAioqKRlReIYQQQkwuEyJZeu7cuaxbt47bbruNjRs38s4773DnnXdy7bXXpnuMHT16lDlz5rBx40YA9u/fzw9+8AM2bdrEoUOH+POf/8yNN97I2WefzaJFi8Zyd4QQQggxTkyIZGkwen/deeednH/++aiqytVXX81DDz2Ufj4ej7N79+50rzCr1crLL7/Mgw8+SDAYpKysjKuvvppvf/vbw3pdXdcBpPeYEEIIMYGkztup83h/FH2wJaa4mpoaSZYWQgghJqgjR45QWlra7/MSCA1C0zRqa2vxeDwoyskb/TLVG+3IkSN4vd6Ttt3xZLLv42TfP5j8+zjZ9w8m/z7K/k18o7WPuq7T1dVFcXExqtp/JtCEaRobK6qqDhhJniiv1ztpP9wpk30fJ/v+weTfx8m+fzD591H2b+IbjX30+XyDLjMhkqWFEEIIIUaDBEJCCCGEmLIkEBojNpuN++67b1IP3jjZ93Gy7x9M/n2c7PsHk38fZf8mvrHeR0mWFkIIIcSUJTVCQgghhJiyJBASQgghxJQlgZAQQgghpiwJhIQQQggxZUkgNIp+8YtfUFlZid1uZ9WqVekJYfvzzDPPMGfOHOx2OwsXLuRvf/vbKSrp8N1///2sWLECj8dDfn4+V1xxBbt37x5wnSeeeAJFUTL+7Hb7KSrx8Hz3u9/tVdY5c+YMuM5EOn4AlZWVvfZRURTuuOOOPpcf78fvzTff5LLLLqO4uBhFUXj++eczntd1nXvvvZeioiIcDgdr165l7969g253uN/j0TTQPsbjcb75zW+ycOFCXC4XxcXF3HjjjdTW1g64zZF81kfLYMfw5ptv7lXWdevWDbrdiXIMgT6/k4qi8MADD/S7zfFyDIdyXohEItxxxx3k5OTgdru5+uqraWhoGHC7I/3uDpUEQqPk6aef5u677+a+++5j8+bNLF68mAsvvJDGxsY+l3/33Xe57rrruPXWW9myZQtXXHEFV1xxBdu3bz/FJR+aN954gzvuuIP33nuP9evXE4/HueCCCwgGgwOu5/V6qaurS/9VV1efohIP3/z58zPK+vbbb/e77EQ7fgAffPBBxv6tX78egM9+9rP9rjOej18wGGTx4sX84he/6PP5n/zkJzz00EM88sgjvP/++7hcLi688EIikUi/2xzu93i0DbSPoVCIzZs3853vfIfNmzfz7LPPsnv3bj7zmc8Mut3hfNZH02DHEGDdunUZZf39738/4DYn0jEEMvatrq6Oxx57DEVRuPrqqwfc7ng4hkM5L3z961/nL3/5C8888wxvvPEGtbW1XHXVVQNudyTf3WHRxahYuXKlfscdd6TvJ5NJvbi4WL///vv7XP5zn/ucfskll2Q8tmrVKv2f//mfR7WcJ0tjY6MO6G+88Ua/yzz++OO6z+c7dYU6Affdd5++ePHiIS8/0Y+fruv6v/7rv+ozZszQNU3r8/mJdPwA/bnnnkvf1zRNLyws1B944IH0Y+3t7brNZtN///vf97ud4X6PT6Xj97EvGzdu1AG9urq632WG+1k/Vfrav5tuukm//PLLh7WdiX4ML7/8cv28884bcJnxegyPPy+0t7frFotFf+aZZ9LL7Nq1Swf0DRs29LmNkX53h0NqhEZBLBZj06ZNrF27Nv2YqqqsXbuWDRs29LnOhg0bMpYHuPDCC/tdfrzp6OgAIDs7e8DlAoEAFRUVlJWVcfnll7Njx45TUbwR2bt3L8XFxUyfPp3rr7+ew4cP97vsRD9+sViM3/72t3zxi18ccHLhiXT8ejp48CD19fUZx8jn87Fq1ap+j9FIvsfjTUdHB4qi4Pf7B1xuOJ/1sfb666+Tn59PVVUVX/nKV2hpael32Yl+DBsaGvjrX//KrbfeOuiy4/EYHn9e2LRpE/F4PON4zJkzh/Ly8n6Px0i+u8MlgdAoaG5uJplMUlBQkPF4QUEB9fX1fa5TX18/rOXHE03TuOuuuzjzzDNZsGBBv8tVVVXx2GOP8ac//Ynf/va3aJrGGWecQU1NzSks7dCsWrWKJ554ghdffJFf/vKXHDx4kLPOOouurq4+l5/Ixw/g+eefp729nZtvvrnfZSbS8Tte6jgM5xiN5Hs8nkQiEb75zW9y3XXXDTiR5XA/62Np3bp1/OY3v+GVV17hxz/+MW+88QYXXXQRyWSyz+Un+jH89a9/jcfjGbTpaDwew77OC/X19Vit1l6B+WDnxtQyQ11nuGT2eXHC7rjjDrZv3z5om/Tq1atZvXp1+v4ZZ5zB3LlzefTRR/nBD34w2sUclosuuij9/6JFi1i1ahUVFRX84Q9/GNLV2UTzq1/9iosuuoji4uJ+l5lIx2+qi8fjfO5zn0PXdX75y18OuOxE+qxfe+216f8XLlzIokWLmDFjBq+//jrnn3/+GJZsdDz22GNcf/31g3ZKGI/HcKjnhfFAaoRGQW5uLiaTqVcmfENDA4WFhX2uU1hYOKzlx4s777yTF154gddee43S0tJhrWuxWFi6dCn79u0bpdKdPH6/n9mzZ/db1ol6/ACqq6t5+eWX+dKXvjSs9SbS8Usdh+Eco5F8j8eDVBBUXV3N+vXrB6wN6stgn/XxZPr06eTm5vZb1ol6DAHeeustdu/ePezvJYz9MezvvFBYWEgsFqO9vT1j+cHOjallhrrOcEkgNAqsVivLly/nlVdeST+maRqvvPJKxhV1T6tXr85YHmD9+vX9Lj/WdF3nzjvv5LnnnuPVV19l2rRpw95GMplk27ZtFBUVjUIJT65AIMD+/fv7LetEO349Pf744+Tn53PJJZcMa72JdPymTZtGYWFhxjHq7Ozk/fff7/cYjeR7PNZSQdDevXt5+eWXycnJGfY2Bvusjyc1NTW0tLT0W9aJeAxTfvWrX7F8+XIWL1487HXH6hgOdl5Yvnw5Fosl43js3r2bw4cP93s8RvLdHUnBxSh46qmndJvNpj/xxBP6zp079dtvv133+/16fX29ruu6fsMNN+jf+ta30su/8847utls1n/605/qu3bt0u+77z7dYrHo27ZtG6tdGNBXvvIV3efz6a+//rpeV1eX/guFQulljt/H733ve/o//vEPff/+/fqmTZv0a6+9Vrfb7fqOHTvGYhcG9I1vfEN//fXX9YMHD+rvvPOOvnbtWj03N1dvbGzUdX3iH7+UZDKpl5eX69/85jd7PTfRjl9XV5e+ZcsWfcuWLTqg/+xnP9O3bNmS7jH1ox/9SPf7/fqf/vQnfevWrfrll1+uT5s2TQ+Hw+ltnHfeefrDDz+cvj/Y9/hUG2gfY7GY/pnPfEYvLS3VP/roo4zvZTQaTW/j+H0c7LM+Xvavq6tL/7d/+zd9w4YN+sGDB/WXX35ZX7ZsmT5r1iw9Eon0u38T6RimdHR06E6nU//lL3/Z5zbG6zEcynnhy1/+sl5eXq6/+uqr+ocffqivXr1aX716dcZ2qqqq9GeffTZ9fyjf3RMhgdAoevjhh/Xy8nLdarXqK1eu1N977730c2vWrNFvuummjOX/8Ic/6LNnz9atVqs+f/58/a9//espLvHQAX3+Pf744+lljt/Hu+66K/1+FBQU6BdffLG+efPmU1/4Ibjmmmv0oqIi3Wq16iUlJfo111yj79u3L/38RD9+Kf/4xz90QN+9e3ev5yba8Xvttdf6/Eym9kHTNP073/mOXlBQoNtsNv3888/vtd8VFRX6fffdl/HYQN/jU22gfTx48GC/38vXXnstvY3j93Gwz/qpNND+hUIh/YILLtDz8vJ0i8WiV1RU6LfddluvgGYiH8OURx99VHc4HHp7e3uf2xivx3Ao54VwOKz/y7/8i56VlaU7nU79yiuv1Ovq6nptp+c6Q/nungil+0WFEEIIIaYcyRESQgghxJQlgZAQQgghpiwJhIQQQggxZUkgJIQQQogpSwIhIYQQQkxZEggJIYQQYsqSQEgIIYQQU5YEQkIIIYSYsiQQEkJMODfffDNXXHHFmL3+DTfcwA9/+MMhLXvttdfyv//3/x7lEgkhRkpGlhZCjCuKogz4/H333cfXv/51dF3H7/efmkL18PHHH3PeeedRXV2N2+0edPnt27dz9tlnc/DgQXw+3ykooRBiOCQQEkKMK/X19en/n376ae699152796dfsztdg8pABktX/rSlzCbzTzyyCNDXmfFihXcfPPN3HHHHaNYMiHESEjTmBBiXCksLEz/+Xw+FEXJeMztdvdqGjvnnHP46le/yl133UVWVhYFBQX813/9F8FgkFtuuQWPx8PMmTP5+9//nvFa27dv56KLLsLtdlNQUMANN9xAc3Nzv2VLJpP88Y9/5LLLLst4/D//8z+ZNWsWdrudgoIC/umf/inj+csuu4ynnnrqxN8cIcRJJ4GQEGJS+PWvf01ubi4bN27kq1/9Kl/5ylf47Gc/yxlnnMHmzZu54IILuOGGGwiFQgC0t7dz3nnnsXTpUj788ENefPFFGhoa+NznPtfva2zdupWOjg5OO+209GMffvghX/va1/j+97/P7t27efHFFzn77LMz1lu5ciUbN24kGo2Ozs4LIUZMAiEhxKSwePFivv3tbzNr1izuuece7HY7ubm53HbbbcyaNYt7772XlpYWtm7dCsDPf/5zli5dyg9/+EPmzJnD0qVLeeyxx3jttdfYs2dPn69RXV2NyWQiPz8//djhw4dxuVxceumlVFRUsHTpUr72ta9lrFdcXEwsFsto9hNCjA8SCAkhJoVFixal/zeZTOTk5LBw4cL0YwUFBQA0NjYCRtLza6+9ls45crvdzJkzB4D9+/f3+RrhcBibzZaR0P3pT3+aiooKpk+fzg033MCTTz6ZrnVKcTgcAL0eF0KMPQmEhBCTgsViybivKErGY6ngRdM0AAKBAJdddhkfffRRxt/evXt7NW2l5ObmEgqFiMVi6cc8Hg+bN2/m97//PUVFRdx7770sXryY9vb29DKtra0A5OXlnZR9FUKcPBIICSGmpGXLlrFjxw4qKyuZOXNmxp/L5epznSVLlgCwc+fOjMfNZjNr167lJz/5CVu3buXQoUO8+uqr6ee3b99OaWkpubm5o7Y/QoiRkUBICDEl3XHHHbS2tnLdddfxwQcfsH//fv7xj39wyy23kEwm+1wnLy+PZcuW8fbbb6cfe+GFF3jooYf46KOPqK6u5je/+Q2aplFVVZVe5q233uKCCy4Y9X0SQgyfBEJCiCmpuLiYd955h2QyyQUXXMDChQu566678Pv9qGr/P41f+tKXePLJJ9P3/X4/zz77LOeddx5z587lkUce4fe//z3z588HIBKJ8Pzzz3PbbbeN+j4JIYZPBlQUQohhCIfDVFVV8fTTT7N69epBl//lL3/Jc889x0svvXQKSieEGC6pERJCiGFwOBz85je/GXDgxZ4sFgsPP/zwKJdKCDFSUiMkhBBCiClLaoSEEEIIMWVJICSEEEKIKUsCISGEEEJMWRIICSGEEGLKkkBICCGEEFOWBEJCCCGEmLIkEBJCCCHElCWBkBBCCCGmLAmEhBBCCDFl/X8Wj0xQQkOGcgAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAjUAAAGwCAYAAABRgJRuAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8pXeV/AAAACXBIWXMAAA9hAAAPYQGoP6dpAACceUlEQVR4nOzdd3yN1x/A8c9zV/beO0FE7NijlKJWKVVUtWirpZQq2lKt6qJTUZSftnRQ1KiW1t577y0JQSJ7J3c+vz8ul9sECSHDeb9eXr3Pec5znnNvb+793jMlWZZlBEEQBEEQyjlFaVdAEARBEAShJIigRhAEQRCECkEENYIgCIIgVAgiqBEEQRAEoUIQQY0gCIIgCBWCCGoEQRAEQagQRFAjCIIgCEKFoCrtCjxMJpOJq1ev4uTkhCRJpV0dQRAEQRCKQJZlsrKy8Pf3R6G4fXvMIxXUXL16laCgoNKuhiAIgiAI9yAuLo7AwMDbnn+kghonJyfA/KI4OzuXcm0EQRAEQSiKzMxMgoKCLN/jt/NIBTU3upycnZ1FUCMIgiAI5czdho6IgcKCIAiCIFQIIqgRBEEQBKFCEEGNIAiCIAgVQrkdU/P5558zduxY3nzzTaZMmVKiZRuNRvR6fYmWKQhlgVqtRqlUlnY1BEEQHohyGdTs27eP2bNnU7t27RItV5ZlEhISSE9PL9FyBaEscXV1xdfXV6zVJAhChVPugprs7Gz69u3LnDlz+PTTT0u07BsBjbe3N/b29uJDX6hQZFkmNzeXxMREAPz8/Eq5RoIgCCWr3AU1Q4cOpXPnzrRt2/auQY1Wq0Wr1VqOMzMzb5vXaDRaAhoPD48Sq68glCV2dnYAJCYm4u3tLbqiBEGoUMpVULNw4UIOHjzIvn37ipR/0qRJfPTRR0XKe2MMjb29/T3XTxDKgxvvcb1eL4IaQRAqlHIz+ykuLo4333yT+fPnY2trW6Rrxo4dS0ZGhuVfXFzcXa8RXU5CRSfe44IgVFTlpqXmwIEDJCYmUq9ePUua0Whk69atTJ8+Ha1WW+BXp42NDTY2Ng+7qoIgCIIglIJyE9S0adOGY8eOWaW99NJLVKtWjXfffVc0owuCIAjCI67cdD85OTlRs2ZNq38ODg54eHhQs2bN0q6ecA8mTJhA3bp1H+o9Y2NjkSSJw4cPP9T7CoIgCA9euQlqhDtLSEjgzTffpEqVKtja2uLj40Pz5s35/vvvyc3NLe3qFcmAAQPo1q1bmS1PEARBKNvKTfdTYTZv3lzaVSgToqOjad68Oa6urkycOJFatWphY2PDsWPH+N///kdAQABdu3YtcJ1er0etVpdCje9Pea23IAiC8GCJlprbkGWZXJ2hVP7Jslysug4ZMgSVSsX+/fvp1asXkZGRVKpUiaeffppVq1bRpUsXwDzr5fvvv6dr1644ODjw2WefAfD9999TuXJlNBoNERER/Prrr5ayC+uuSU9PR5IkS1C5efNmJEliw4YNNGjQAHt7e5o1a8aZM2es6vn555/j4+ODk5MTr7zyCvn5+ZZzEyZM4Oeff2bFihVIkmQp/8b9Fy1axOOPP46trS3z588vtOtqypQphIaG3rG8G6Kjo2ndujX29vbUqVOHXbt2Fes1FwRBEMqect1S8yDl6Y1UH7+mVO598uP22GuK9r8mJSWFtWvXMnHiRBwcHArNc+sU3gkTJvD5558zZcoUVCoVy5cvt+yf1bZtW1auXMlLL71EYGAgrVu3Lla9x40bxzfffIOXlxeDBw/m5ZdfZseOHQAsXryYCRMmMGPGDB577DF+/fVXpk2bRqVKlQAYPXo0p06dIjMzk7lz5wLg7u7O1atXARgzZgzffPMNUVFR2NraMnv27DvW5W7ljRs3jq+//prw8HDGjRtHnz59OH/+PCqV+JMQBEEor8QneDl3/vx5ZFkmIiLCKt3T09PSEjJ06FC++OILAJ5//nleeuklS74+ffowYMAAhgwZAsDIkSPZvXs3X3/9dbGDms8++4zHH38cMAchnTt3Jj8/H1tbW6ZMmcIrr7zCK6+8AsCnn37K+vXrLXV0dHTEzs4OrVaLr69vgbJHjBjBM888U+S63K280aNH07lzZwA++ugjatSowfnz56lWrVqxnrMgCIJQdoig5jbs1EpOfty+1O59v/bu3YvJZKJv375WW0U0aNDAKt+pU6d47bXXrNKaN2/O1KlTi33PWzcYvbGvUGJiIsHBwZw6dYrBgwdb5W/atCmbNm0qUtn/rff9ul1dRVAjCIJQfomg5jYkSSpyF1BpqlKlCpIkFRi/cqNb58ZePzfcrovqdhQK87CrW8f53NhS4r9uHbx7o8vLZDIV63638996KxSKAmOPblevwjzIugqCIAilQwwULuc8PDxo164d06dPJycnp9jXR0ZGWsa93LBjxw6qV68OgJeXFwDx8fGW8/eyxktkZCR79uyxStu9e7fVsUajwWg0Fqk8Ly8vEhISrAKb/9arOOUJgiAI5V/Zb4oQ7mrmzJk0b96cBg0aMGHCBGrXro1CoWDfvn2cPn2a+vXr3/bat99+m169ehEVFUXbtm35+++/WbZsGevXrwfMLT1NmjTh888/JywsjMTERN5///1i1/HNN99kwIABNGjQgObNmzN//nxOnDhhaVECCA0NZc2aNZw5cwYPDw9cXFxuW16rVq1ISkriyy+/5Nlnn2X16tX8+++/ODs731N5giAIQvknWmoqgMqVK3Po0CHatm3L2LFjqVOnDg0aNOC7775j9OjRfPLJJ7e9tlu3bkydOpWvv/6aGjVqMHv2bObOnUurVq0seX766ScMBgP169dnxIgRfPrpp8WuY+/evfnggw945513qF+/PhcvXuT111+3yvPqq68SERFBgwYN8PLyKtCCdKvIyEhmzpzJjBkzqFOnDnv37mX06NH3XJ4gCIJQ/klycRdFKccyMzNxcXEhIyPD6hc9QH5+PjExMYSFhRV5F3BBKI/Ee10QhPLmTt/ftxItNYIgCIIgVAgiqBEEQRAEoUIQQY0gCIIgCBWCCGoEQRAEQagQRFAjCIIgCEKFIIIaQRAEQRAqBBHUCIIgCIJQIYigRhAEQRCECkEENY8gSZL4888/75hnwIABdOvWrchlxsbGIknSPe0LdT8mTJhA3bp1H+o9BUEQhLJJBDXlXHGDDzBvTtmxY0fg9sHI1KlTmTdvXslU8rpWrVohSVKBf4MHDy7S9YUFY6NHj2bDhg0lWs/CiOBJEASh7BMbWj6CfH1975rnQW3++Oqrr/Lxxx9bpdnb299zeY6Ojjg6Ot5vtQRBEIQKQLTUVDCtWrVi+PDhvPPOO7i7u+Pr68uECROs8tza4hEWFgZAVFQUkiRZNrL8bwvQ6tWreeyxx3B1dcXDw4OnnnqKCxcuFLt+9vb2+Pr6Wv27sY+HTqfjjTfewM/PD1tbW0JCQpg0aRJg3nEboHv37kiSZDn+bwvKjXpPnDgRHx8fXF1d+fjjjzEYDLz99tu4u7sTGBjI3Llzrer17rvvUrVqVezt7alUqRIffPABer0egHnz5vHRRx9x5MgRS+vSjVas9PR0Bg4ciJeXF87OzjzxxBMcOXKk2K+LIAiCcP9ES81tyLKMnJdXKveW7OyQJOmer//5558ZOXIke/bsYdeuXQwYMIDmzZvTrl27Ann37t1Lo0aNWL9+PTVq1ECj0RRaZk5ODiNHjqR27dpkZ2czfvx4unfvzuHDh1EoSiY2njZtGn/99ReLFy8mODiYuLg44uLiANi3bx/e3t7MnTuXDh06oFQqb1vOxo0bCQwMZOvWrezYsYNXXnmFnTt30rJlS/bs2cOiRYsYNGgQ7dq1IzAwEAAnJyfmzZuHv78/x44d49VXX8XJyYl33nmH3r17c/z4cVavXs369euBmy1ZPXv2xM7Ojn///RcXFxdmz55NmzZtOHv2LO7u7iXyugiCIAhFI4Ka25Dz8jhTr36p3Dvi4AGk++iSqV27Nh9++CEA4eHhTJ8+nQ0bNhQa1Hh5eQHg4eFxx26pHj16WB3/9NNPeHl5cfLkSWrWrFnkus2cOZMffvjBKm327Nn07duXS5cuER4ezmOPPYYkSYSEhBSop6ur6127z9zd3Zk2bRoKhYKIiAi+/PJLcnNzee+99wAYO3Ysn3/+Odu3b+e5554D4P3337dcHxoayujRo1m4cCHvvPMOdnZ2ODo6olKprO69fft29u7dS2JiIjY2NgB8/fXX/PnnnyxZsoTXXnutyK+LIAiCcP9EUFMB1a5d2+rYz8+PxMTE+yrz3LlzjB8/nj179pCcnIzJZALg0qVLxQpq+vbty7hx46zSfHx8AHPXUbt27YiIiKBDhw489dRTPPnkk8Wua40aNaxaj3x8fKzqqFQq8fDwsHpNFi1axLRp07hw4QLZ2dkYDIY7bm8PcOTIEbKzs/Hw8LBKz8vLu6euOUEQBOH+iKDmNiQ7OyIOHii1e98PtVptXZ4kWYKQe9WlSxdCQkKYM2cO/v7+mEwmatasiU6nK1Y5Li4uVKlSpdBz9erVIyYmhn///Zf169fTq1cv2rZty5IlS4p1j8Ke/51ek127dtG3b18++ugj2rdvj4uLCwsXLuSbb765432ys7Px8/Nj8+bNBc65uroWq86CIAjC/RNBzW1IknRfXUDlxY0xNEaj8bZ5UlJSOHPmDHPmzKFFixaAuevlQXB2dqZ379707t2bZ599lg4dOpCamoq7uztqtfqO9bxXO3fuJCQkxKoF6eLFi1Z5NBpNgXvXq1ePhIQEVCqVZeCyIJSmXH0uaqUavVGPnco8Nu/AtQNEZ0QT4BhAmHMYDhoHzqaeJSYzhqcrP41GWfg4OkEoj0RQ84jz9vbGzs6O1atXExgYiK2tbYHp3G5ubnh4ePC///0PPz8/Ll26xJgxY+7pfrm5uSQkJFil2djY4ObmxuTJk/Hz8yMqKgqFQsEff/yBr6+vpdUjNDSUDRs20Lx5c8s1JSE8PJxLly6xcOFCGjZsyKpVq1i+fLlVntDQUGJiYjh8+DCBgYE4OTnRtm1bmjZtSrdu3fjyyy+pWrUqV69eZdWqVXTv3p0GDRqUSP0E4U5kWeZa7jXe3fouR5KOYJTNwbet0pZwt3COJR+77bWLTi9icqvJBDoFEp0eTZY+iwi3CGxVtigkMTlWKH9EUPOIU6lUTJs2jY8//pjx48fTokWLAt0pCoWChQsXMnz4cGrWrElERATTpk2zTP8ujjlz5jBnzhyrtPbt27N69WqcnJz48ssvOXfuHEqlkoYNG/LPP/9Yxsd88803jBw5kjlz5hAQEEBsbOw9PmtrXbt25a233uKNN95Aq9XSuXNnPvjgA6up8D169GDZsmW0bt2a9PR05s6dy4ABA/jnn38YN24cL730EklJSfj6+tKyZUvLOCFBuBfR6dGcSz9HqHMo0RnRXMy8yIAaA9CZdKTmpaKQFHjaeXIl+wrP/PVMoWXkG/MtAY2bjRu5hly0Rq1VnjNpZ+i8vHOh1/eq2gt/R39qe9Wmvk99EeQI5YIky7Jc2pV4WDIzM3FxcSEjI6PAIND8/HxiYmIICwvD1ta2lGooCA+eeK8/XHmGPH4//Ts5+hwquVRCrVDzRPATHEo8xJ74PRxKPGQJUoKdgzmadJTtV+6te7eJ/btk6BO4qt+NU1Y21eJ0tD2owzdVz6moZlwOdKPh9s24JsazqZELB0K1nAg0IN9lBYnanrWZ8+Qc7NUVv0teKJvu9P19KxHUXCc+6IVHhXivPxyZukze2vQWexP23nMZSpMKo8Jw13yy1o2ci0OQDY4MOraCbtFFD4pSHSHGV8IrXSYgBSZ1rM/5cAmVnYFM6bhV3hYBLXi55sssOL0AlaSirnddekX0QqUQjf7CgyWCmkKIoEYQxHu9pOXoc5CQuJgew5w1n7E//zR6pUS2ouDMQI1eRqc2N4vY5cvUPy9T/ZIMEixvqsCgBN80aH3UxGMnZFTXJy0aJYjzAp0K/FPhqjtkOEhExsk45t++bml1GuF4/hTqnCwAsv1DuFq9AZfCaqBOiCf84Cb8r5znvE9lqly7uQyBEQklMsnOMGTo3QOWRr6NmNFmBpm6TDxsPVAqbr84piDci6IGNeUmvP7+++/5/vvvLeMoatSowfjx4y0bMwqCIDwssixzMfMi47aP42jyUeuT1qsH0Gurke47ZZTXfz7qlbAvwA/fTD1X7P1pcfUoRiQeO6bgiFc4Kf6hqN3sUJmWWspQhFQisuXj2Ls4Yoi/iuOSpcCdf4/6ffYpkbcsminLciErlY8EIBIwZmSQ9NdK0hcuQnnhHACembBokoEzAXAqWOL3VoUHK3sT9tJwfkMAOoV25vOWkyzn7md1dEEornLTUvP333+jVCoJDw9HlmV+/vlnvvrqKw4dOkSNGjWKVIZoqREE8V6/Vzl79qKLvsAB3QXeYlGheapclWl+0kRlr6Ys8DuFY5YzUmxzUtROfL5jNnpJSd+O48nSOBDqYU8Nfxeq+zsT7qqhkrcjIb6uqJU3B+TqLl9BUqtR+3gXuJf+WiLGjHQklZq8Qwcx5eRiWz0SpbsHmrDQew4mZFkm7/BhDPHx2EREYMrNI37cOLRnz5JpBxJgpwWVCcY++RKnww+idj5hVYYz1TCpklApTDQNaELPqj2p61UXtVJd+E3v4Nt1Z1EqJIa3CWfm4ZkoJAWD6wwGYNqGcxhNMm+1q8qsI7MwySaG1B1yT89bKNseie4nd3d3vvrqK1555ZVCz2u1WrTam6P9MzMzCQoKEkGN8EgT7/WiMWbnYExNIS82hq1fj2ZzWC7RvhLn/W8GCyHXZLrsNVHHpRHnKjdimWMNDsdn899PVR9nGxqGulM3yJWaAeZAxtm2+F/wpc2YlcW55o8h37LopikikkPPDeHYsd/Z4xVDintSodcqJSX9qvfj9bqvY6cq+gKj0zacY/K6s4xsVxWN5wZmHJ7B0LpD0SW3KTT9RsAjVCwVOqgxGo388ccf9O/fn0OHDlG9evVC802YMIGPPvqoQLoIaoRHmXiv35lsMnH5+2nMOj6HKx5w0Vsi2cW61SNKH8hjCdVJzQtnc44dp209rc5X8XakYag7DUPdaBjqTqDb/W1SW5bIBgMX+/Un7+DBQs8fDZU4WcWJGO967HFUovHYUmg+d1t3mvs3Z1CdQYQ4hxSa54bCAhttUjveiHpdBDSPiAoZ1Bw7doymTZuSn5+Po6MjCxYsoFOnTrfNL1pqBKEg8V6/yZiRgT7hGqbsLNIWLcKUm8vp41sY+ZJ1PrVeRq+WCLNtQH56fc7FhiLfMg/a3UHDY1U8aRHuSYtwL3xdKv7rKssy6X/8QcKHEyjQNHVrPqWSnY068mW4F33P/Y6s0rH0Mes1b4Kcghh3siqVnELxe3NEoeXcCGw0SgW4rcPGax1qhRq9SS8CmkdAhRsoDBAREcHhw4fJyMhgyZIl9O/fny1btty2pcbGxsaye7IgCMINsiyT9ssvXPv6G9DrSXaCX9oouBoicanhzWClbUBn9DnhnL4QzPlEHbcOCa4T5Eq7SG8er+pNDX9nFIqK0RJTVJIk4darF07t2mFMS0NhY4PK15eUOT+QNGXKzXxGI813rWSNcwfSYj2xi7+MQ1IoPzSpg8pzGwp1Oo3+vYj7thhmt1DgeUjFG1FvFLjf8DbhTN94Hp3RhCatHWqfzehNetQKtQhoBIty1VLzX23btqVy5crMnj27SPnFQGFBeLTf68aMDDL+/JO0P/5Ad/4CeiXsD5f4tnvBWT0u+W24HNPOcqxSSDSt7MGTNXxpF+nzSLTG3CtjZiZZa9eS+utvaM+cKTSP3saO1eH10Unx9Dh2gYWPKVnWwhwYzu80n9peta3yi5aaR1uFbKn5L5PJZNW9JDwYEyZM4M8//+Tw4cP3XEZsbCxhYWEcOnSIunXrlljdbjVv3jxGjBhBenr6Ayn/dlq1akXdunWZcsuvU6H05R48hCYkGIW9PUgS+SdOED1qBMftUojzhE0DlSR4qdBzc6NSb0NXYmKrY9K7kgUoFRItwz3pWtefJ6r54GJX/gb3lgalszOuzz6L67PPIssyGX+uIP/YMSRbW3K2b0d79ixqbR5djpsXCTwW0ZgFXk9gy1cA9P2nLyNrTSYq0Is98XvYdtyR7cdcbxlTsw5tUjtevWVMDSACG6H8tNSMHTuWjh07EhwcTFZWFgsWLOCLL75gzZo1tGvX7u4FUHFbauLi4vjwww9ZvXo1ycnJ+Pn50a1bN8aPH4+Hh0exypIkieXLl9OtWzdLWnZ2Nlqttthl3cpoNJKUlISnpycq1YOJpYsS1NxusObvv//Oc889d8fyN2/eTOvWrUlLS7NssgmQmpqKWq3GycnpXqpdZCUVPJXn93pRmHQ6Mv/6i/j3P7BKT3OAj59XcsXT+j2gxhFdVlXyUhpgzKsEQIMQN56u60+nWn54OIou7JJmzM7mbOMmYDRapf/5mBt/1YFs5yxLmjbpCXTJT+Los5nHamax4+oOMfvpEVThWmoSExPp168f8fHxuLi4ULt27WIFNBVVdHQ0TZs2pWrVqvz++++EhYVx4sQJ3n77bf799192796Nu7v7fd3D0dERR0fH+ypDqVTi6+t7X2WUlLlz59KhQwertFuDlOK639dXKBna6GhS584j4++/kfOtl9ndHSExp6OSLDuwVdggYUOeKRNtUluyUlqAbEOIhz29WgbRtY4/Qe5ij6MHKfWXX8BoRFKrkfV6JFtb5Px8um1Po8MemNBXRbTfjdwKNJ5rkdw3suOqOaWZfzNq1wkHwGiSLYGMSTY9/CcjlCnlZtvVH3/8kdjYWLRaLYmJiaxfv/6RD2gAhg4dikajYe3atTz++OMEBwfTsWNH1q9fz5UrVxg3bpwlb2hoKJ988gl9+vTBwcGBgIAAZsyYYXUeoHv37kiSZDmeMGGCVZfRgAED6NatGxMnTsTHxwdXV1c+/vhjDAYDb7/9Nu7u7gQGBjJ37lzLNbGxsUiSZOnCGjBgAJIkFfh3Y4dwrVbL6NGjCQgIwMHBgcaNGxfYPXzevHkEBwdjb29P9+7dSUlJKdJr5urqiq+vr9W/Gy0WFy9epEuXLri5ueHg4ECNGjX4559/iI2NpXXr1gC4ubkhSRIDBgwAzC0oI0aMsHodP/30U/r164ejoyMhISH89ddfJCUl8fTTT+Po6Ejt2rXZv3+/5ZqUlBT69OlDQEAA9vb21KpVi99//93qNd+yZQtTp061vFY3Vtc+fvw4HTt2xNHRER8fH1588UWSk5OL9FpUBJlr1hLdpSvRnTqT/scfloBG4eCA+7ChzJ78OJOfMQc0SmzJvDCCxBPvkXXqc0h/km51wvj91SZsGtWKoa2riIDmAUuaOZPkad/hOXwY1Y4dxXP4MOT8fJzatcO9fz9s9TBxnoEJvxl4/swTyClt0Kc3Rp/6mKWMvv/0ZefVnbStq6dzA3MwM7jOYLHwnlB+gpqHTZZlcvW5pfKvqD2CqamprFmzhiFDhmBnZ72Yla+vL3379mXRokVW5X311VfUqVOHQ4cOMWbMGN58803WrVsHwL59+wBzS0Z8fLzluDAbN27k6tWrbN26lcmTJ/Phhx/y1FNP4ebmxp49exg8eDCDBg3i8uXLhV4/depU4uPjLf/efPNNvL29qVatGgBvvPEGu3btYuHChRw9epSePXvSoUMHzp0zL9++Z88eXnnlFd544w0OHz5M69at+fTTT4v0ut3J0KFD0Wq1bN26lWPHjvHFF1/g6OhIUFAQS5eal60/c+YM8fHxTJ069bblfPvttzRv3pxDhw7RuXNnXnzxRfr168cLL7zAwYMHqVy5Mv369bP8v8nPz6d+/fqsWrWK48eP89prr/Hiiy+yd+9ey+vVtGlTXn31VctrFhQURHp6Ok888QRRUVHs37+f1atXc+3aNXr16nXfr0V5YMzO4cqbb6K9/r7Qt6zPrikvsuOnwSyb3p23K+1jQ9IOc958XzLOv4E2341qvk581LUG+95ry5Tnomha2eORm71UGm4NaLyGmAMQryFD8Bw+jKx161C4uOA3aRIKoHocdFu2lr+2fs7TIQHkX3uK/GudLWUNWjeI3it70+OvHjz959MsPrOYxNzEUnpmQllRbrqfHrY8Qx6NFzQulXvveX4P9uq7/1o8d+4csiwTGRlZ6PnIyEjS0tJISkrC29u8zHrz5s0ZM2YMAFWrVmXHjh18++23tGvXDi8vL+BmS8aduLu7M23aNBQKBREREXz55Zfk5uby3nvvAeYxUJ9//jnbt28vdKyKi4sLLi4uACxbtozZs2ezfv16fH19uXTpEnPnzuXSpUv4+/sDMHr0aFavXs3cuXOZOHEiU6dOpUOHDrzzzjuW57Jz505Wr15919etT58+KJXWs11OnjxJcHAwly5dokePHtSqVQuASpUqWT1nAG9v77t2V3Xq1IlBgwYBMH78eL7//nsaNmxIz549AXj33Xdp2rQp165dw9fXl4CAAEaPHm25ftiwYaxZs4bFixfTqFEjXFxc0Gg02NvbW/2/mT59OlFRUUycONGS9tNPPxEUFMTZs2epWrXqXV+P8izlhzmWxz7ffcsow0L2X/sdrt3MI8sSuqR2GNNa06mGPwOah9IgxK3CLIZXrhhNVgHNDZZjownX7t1watuGtPnzSZoyFVJSGLb0c56b+Rsf/e1MdPo1NK77Uch2mKQ8AGIzY/lk9ycsObuE+Z3no1aIAd2PKhHUVADFGevdtGnTAsf3MvC0Ro0aKBQ3G/p8fHyoWbOm5VipVOLh4UFi4p1/OR06dIgXX3yR6dOn07x5c8C8yKLRaCzwhXzrYOVTp07RvXv3As+lKEHNt99+S9u2ba3SbgRPw4cP5/XXX2ft2rW0bduWHj16ULt27cKKuaNbr/Hx8QGwBEq3piUmJuLr64vRaGTixIksXryYK1euoNPp0Gq12NvfObg9cuQImzZtKnTM04ULFypsUGPKyyNt0SJSZs0mXw3r32zKH4njyTPkWeXTpTbBPv9x+tdrwAtNQvBzKfry/ELJ8xpWcP0Zy7lbAh2lkxOegwebgxpAFxtLnazLrBz2GL/vC+DLDdvIyHRFqdLRoUE2ubbb2H9tH6dST9Hvn3783PFnNErNA38+QtkjgprbsFPZsef5PaV276KoUqUKkiQV+gUP5i9+Nzc3SwtMSVKrrX8JSZJUaJrJdPuBewkJCXTt2pWBAwda7d+VnZ2NUqnkwIEDBVpU7nfAMpi75qpUqVLouYEDB9K+fXtWrVrF2rVrmTRpEt988w3Dhg0r1j1ufS1utAgUlnbj9fnqq6+YOnUqU6ZMoVatWjg4ODBixAh0t+yxU5js7Gy6dOnCF198UeCcn59fIVeUP8bsnOsbNuaQf+YMKT/8CHo9+Wr4p5nEwseVwD4wmPMbciqRf+V5Irz8eKVFGF3q+GOrLnx36Yflvxsx3kpsxHh7QT/+QPz7H2CIj+di/wE4tWvHEwoFLQKCmOIdxvLzWazabU8lr34MatmW2ScncTzlOPV/q8/aHmvxc6wYfwNC0Ymg5jYkSSpSF1Bp8vDwoF27dsycOZO33nrLalxNQkIC8+fPp1+/flbN7Lt377YqY/fu3VbdV2q1GuN/plk+CPn5+Tz99NNUq1aNyZMnW52LiorCaDSSmJhIixYtCr0+MjKSPXusg87/Prd7FRQUxODBgxk8eDBjx45lzpw5DBs2DI3G/MvvQbw+O3bs4Omnn+aFF14AzMHO2bNnrVbL1mg0Be5dr149li5dSmho6AObKl9aDElJJH//PWkLfi/0/MzOCnZHmlsLTXoXtNeewpBTmcYhgQzuV5lWVb3KTBeTQlIUupbKrCOzLFORhYIcmzcnbNlSLrRpiyk3l8y//7acG16nNh3f+Zz3V18gOimHqX+6Urdea05nbwLgyaVP0ti3MZ0qdeKZ8GdK6ykID5kYKFzOTZ8+Ha1WS/v27dm6dStxcXGsXr2adu3aERAQwGeffWaVf8eOHXz55ZecPXuWGTNm8Mcff/Dmm29azoeGhrJhwwYSEhJIS0t7YPUeNGgQcXFxTJs2jaSkJBISEkhISECn01G1alX69u1Lv379WLZsGTExMezdu5dJkyaxatUqwNxNtHr1ar7++mvOnTvH9OnTi9T1BJCenm65341/OTk5AIwYMYI1a9YQExPDwYMH2bRpkyXoCwkJQZIkVq5cSVJSEtnZ2SX2eoSHh7Nu3Tp27tzJqVOnGDRoENeuXbPKExoayp49e4iNjSU5ORmTycTQoUNJTU2lT58+7Nu3jwsXLrBmzRpeeumlhxKcljTt+fPEPNODU9UiOdeipVVAo6lSGXVIMC49niHjsy8sAY0x35e8i4NpE9yW5YPbsmhQU1pHeJdaQPPturNM23DOKm1wncEMrTuUGYdn0H+Z+W/y1oBGrK1yeyo3N4J/+hHbGjUAkK53yeYfOUrIaz35MyyZDjV80Rtl9u1rj4+pi+XaPQl7+HDnh2yO21wKNRdKgwhqyrnw8HD2799PpUqV6NWrF5UrV+a1116jdevW7Nq1q8AaKqNGjWL//v1ERUXx6aefMnnyZNq3b285/80337Bu3TqCgoKIiop6YPXesmUL8fHxVK9eHT8/P8u/nTt3AuYZWP369WPUqFFERETQrVs39u3bR3BwMABNmjRhzpw5TJ06lTp16rB27Vref//9It37pZdesrqnn58f3333HWBuhRk6dCiRkZF06NCBqlWrMnPmTAACAgL46KOPGDNmDD4+Przxxu3HBxTX+++/T7169Wjfvj2tWrXC19fXagFEMA+WViqVVK9eHS8vL8tA6h07dmA0GnnyySepVasWI0aMwNXV1WrMU1klG43EDX2DU9Uiie3zPDHP9iT/5EnLeZuqVQn+6UeqnTpJ5ZUryfjfQt6t1JV+MRsteTq5f8G64d2Y/WIDooLdSuNpWFEqJCYXEtjoktugTWrHwayF1Pu1nghoisGubl3Cli4h8vQpqh08QMB305BsbDDl5JDx8Ud81ymUSc/Uwlat4PyZ5qiTBxLpevPza9jGYQXGWwkVU7lZUbgkVNQVhYsqNDSUESNGWK2pIjx6ytJ7Pem76STfslYSgGRnh1PrVjh17IhT27ZIksShS2l8vf4ou6/uR+V4Eo2bear781VfYWzTEQ+/4ndxY5+ike2qMrxNuNXxvKu9LRsxHnzxYGlXtdzK2bOXS/37A+DUsQO+779PrFHD0PmHOHMtC7VSYmA7+O3iuwA08GnAjDYzyvywAqFwFW5FYUEQKg791aukLV5Myqybm9F6DnsD28jqOLZ6HOl6K9PxK+l8tHYthxJOYeOxGfugm4sKhjqH8k7j4g3gfliGtzGvdjt53VnLztI3lvPXX9ZbNmKcdWSWaKm5R/aNGuLUoQNZq1eT9a/5nyYkhHk9evJJrbr8cyyB71dDk7ovckL7K/uv7efzvZ/zcfOPS7vqwgNU9tunBUGoUPIOH+ZCp85WAU3wvLl4DR2K0xOtkRQKLqXk8uKCX+n9b2dOKz7Bzn8JChtzQOPn4MfoBqNZ2nUpSkXpzmq6k+FtwtEoFeiMJjRKhdX+RAdfPGgZYzPryKzSrmq5JEkSXsOHoXByguvjp3QXL5I++WveP7GUD+s4IEmw+3ANPEzmCQcrLqzgTGrhu4YLFYNoqXmE3FhWXxBKgyk/n9jez6E9Y/5SsQmvgmuv3rj1fd7SMnMq8RKfbV7MwcSDKJ2OcWMNtSDHUIJdAhhRbwQRbhFlZlbTnUzbcM4S0OC2jhmH11mNobnxX7HD9L2zqVSJ8G1bAcg/eYqLzz8PQMay5TRdvYYf5/zB0D/PEnumE17hKeSrTvLs38/SxK8JHcM60ia4DS42LqX5FIQSJoIaQRAemJy9e8lcuQqUCrJWr8F4fUadOiCAkN9+Q+nigizLXMlMZvq23fyd8BmSKhvl9Q3PW/i2Z0zT4QQ7B5fisyi+/46p6b9sP7ui26FLbmOVT2zEeP8U18eF2deLotqpk2SuXMnVt99Bzs2l1o5VLHztRV6et4/k6B64hGoxai6wO343u+N38+HODznS7wgKSXRaVBRioPB1NwZPhoaGFthHSRAqkry8PGJjYx/4QOHU3+ZzbeJEKGQBxqr79qJ0cmLZ2T/5cNcHBc7bKR34ouUkWge3fmD1e1D+G9DcLV0oeam/zefa9b3ggv43m+Tq9ek/dy8XU3LwCNiGzvkfS94e4T3oU60PEe4RpVVdoQiKOlBYBDXXGY1Gzp49i7e3t2UpfkGoiFJSUkhMTKRq1aoFVmy+H7IsI+fnE9vnebSnT1vSNaGh2DdqhKZSGK7du6O8vufXmlMxjN7b1aqM6i7NmNbuY7ztS2+dmfv17bqzKBVSoYHLtA3nMJpk3mpXMbevKCtkvZ7TtW5uVVJl6xbS7JzpO2cP5xKz8XbWULven+y5Zu66UkgKRtUfxYvVXyy377uKTgQ1hbjbixIfH096ejre3t7Y29uLN7dQociyTG5uLomJibi6upboNgoZK1aQNH0G+rg4q3SP117D660RVn9LJ+OTeHvtLGL1/6JQZwHQ3W88I1o8ibudGN8glIzs7TuIGzgQAJvISEJ/X0CqQeL5Obs5ey0bTycVr3ZMYe3lpZxNOwtAv+r9GNVglOiOKoNEUFOIu70osiyTkJBAenr6w6+cIDwkN3Zhv9+g3ZCcTOY//5L6yy/oL1+2OufQrCmer7+OfcOGlrSMXD1TN5xh4eVxKO2jLemv1hzCsHqDxY8IocTFf/AB6X8ssRz7jB2D3OM5+v6wh9MJWQS62bFoUCOWx8xj9lHzbLzanrX5qcNP2ChtSqvaQiFEUFOIor4oRqMRvV7/EGsmCA+HWq2+7y6nlHnzSP99IbqLF63SnTt1xHvUKFReXkiamzskG4wmFuy5yDd75mByN+/dI8kqXoh4jdei+uBq63pf9RGE2zFptVwe+gY527ebExQKqh0+RLJWpuesncSm5BLh48TiQU2Zd3omPxz7AYCeVXvyQZMPRKBdhoigphBFfVEEQSjIpNMRP2YMmf/8a06QJGyqVsWxVStcuj2NTViYVf4cfQ7D143lYMIp9FIqkuLmjuMTH5tIl8pdEISHQRsdTXSnzgB4vfUWnoNeIy41lx7f7yQxS0v9EDd+e6URv5/9hW8PfAvA1NZTeSL4idKstnALEdQUQgQ1glA8xuwctGfPkvbbrzeDGcDj1YF4vPoqykL+jnL0OVxKT2Xg6qFkmmIs6RIK7FS2TGwxkTbBbQpcJwgP0qlq5o1pJVtbqu7ZjcLGhtMJmfSatYvMfAPdowL4pmdtxu0Yx8rolQQ7BbOy+0rRWlNGiG0SBEG4J/mnTqG9EM21SZMwpqRYnZPs7QmY/A1OrVoVvM6Qz/6Eg7y+YZAlTTbaEW7bgZcbtqS+X3X8Hf0fdPWFh8yQlkb+sWPY1qyJ6j8b6JYlwfPmcmnAS8j5+aTNX4DHyy9RzdeZmX3N072XH7pChK8T7zR+h5XRK7mUdYmNcRtFAF7OiJYaQRAASF+2nJTZswuMlblVlY0bUPtbByYGk4G5x+fy/ZFZ6E03u5iQJcbX/56etZo/qCoLD4ghLY3Mv1eCQkH21i3kbN0GgMrHB5du3XDp8hQZf68kZ8cO8k+cgOtfI0pPT4zJyTh36oTC2Yn84ydw7d0LOV+L0tkJu/r10QQGltrziunZyxyA1a5N2OJFlvSfd8by4V8nkCT4oV8DRuxtC4CExOF+h8VsqDJAdD8VQgQ1glCQ9tw5Lg54yapVRrKxwaFJE2yqhuP5xhsobKxngphkEyeST/B39N/8fvp3S7osS0hGZx737c5nbV7DxdbpoT0PoWSYcnM506BhoYsm3jeFAteePfEZ8y6KUljkNP/UKWK6PwMqFSG//Ix9vXqAeebre8uP8/veSzjbqviwt8SEvaMs1y3tupSqbmJtodIkgppCiKBGEG6SZZncXbu48vY7loDGrd+LeA4ahOo2C1DKssyPx39k/qn5JOfd3DFbNqkwZFejs+8o3utYCw9HMR22LJJlmdSf5pKzYzsqL29MuTkonJ2xrRaJysuT7M1byN6+HWPyzf+3jm3boAkKJmfXLpAkdNHRyFotdg3q4/rsszg0a4bK1ZW8I0fIP30GSa0id/8BdLGx5B8/DioVGAxoqlRGd/4CAHZ162LfpDEYTXgNH4akVj+01yDu9SFkb9oEgOeQ13Ht2RO1nx86g4mes3Zy5HIG9YJd6f3EVT7dc3NH72P9jz20OgoFiaCmECKoEQSz/NOnienW3XKsqVSJgG++xjYy8rbX5Opz+WzPZ/x14S8AFLIN2qwIDJk1qezYiInd6lE/xO2B1124d8mz/0fSt9/eNZ/Kzw/3/v1wffZZlI6OVud0sbHkHT2Kc4cOVlP3iyJr82Yuvz7E0l0FoA4MxL5JY4zp6Tg0aYpDk8ZoQkIeWKBjTE/n4oCXrFa9DpozB8cWjxGXmkunadvIyjcw+PHKuPhtYuaRmQAs6bJEbKVQikRQUwgR1AiCeexM/HvvWY6dnnwSv4kTUTo6FMgbnR7N0nNL+eXkL1bpxoxG5MZ3xU5lw1vtwnm5eRgqpRh3UJZlbdzE5SFDAFC4uODcvj02VSqTvXkLOTt3og4Oxj6qLnYNGuDSpYtlo8iSlvnPPyR//z3ac+fvmM/jtddw7/ciKk/PEq+DSasl7rVB5O7ZA4Da358qGzcA8M+xeIbMPwjAgoGNmX1uFAcTD+Jj78P/nvwflVwqlXh9hLsTQU0hRFAjPOq00TFEd+0KBgMA7gMG4DPmXas8J1JOcCTxCN/s/wbdrQN/r8u9+CrG3Mq0ivDik6drEuRu/1DqLty7a59/Qeq8eZbjyNOnrM4b0tJQurggKR5eYCobDGSsXInuwgUkOztMWdlkb9mCLjraKl/Y8mXYVK5c7Fahu95flkmd9zOJX3wBgE31SHw/+AD7qCjGLjvK73vjCHa355fXInhhdS8ytBkA9I3sy5hGY0q0LsLdiaCmECKoER5Vprw8tGfPEtv7OQBUvr5UWb8OSXVzVYddV3fxzf5vOJN25rbl5MQMw0NdiQ+7VKdzLT+xhkcZp4+PJ2nKVDJWrLCkha1YgW1E2R30mr1tG1dGjsKUlWWVrnR3x2v4cGSjAbfeva3eu/cjacYMkmfMBJMJSa0mdPEi9GFVaP/tVq5m5PNS81CeaWLi+X+et1wzttFYno98/g6lCiVNBDWFEEGN8Kgw5eYi2doiKRSk/PADiV9/Y3Xea8SbeA4eDEC2Lpvhm4azL2Gf5bynnSftgtuh1tXk961KUrPN6X0bB/NOh2q42D28gZ1C0eQeOED64j+wq1eP/FMnyd21G92VK5ZWOU2lSoT9sRiFQ8FuxrIoZ+9err7zLoaEhALnvN99F4+XBpTYvQwpKcT2fg795csoXV0JWbCA3QZH+v+0F0mCJYObUjPQgQa/NQAg0j2SxV0Wl9j9hbsTQU0hRFAjPAr0V65wvo15nQ1NSIjVujOSvT3ufZ/Ha+RIJEkiISeBkZtHcizZPLOjuX9zPnvsM3Lz7Hhv+TG2nTPPgqnq48ikZ2pRP6TsLq72KNNeuEDsc30KtG4A2DdsiMfgQTg0a1buWtZkWUbOzSXj75Ukz5iBISkJMK+HE7ZsKWpv7xK7lzEjg0sDXyX/mPlvofL6dby3K4UlBy5T3c+Zv4c9xl8X/mT8zvE4qh1Z33M9DuryESBWBCKoKYQIaoSKypCaivb0aXQXL5Lw0ccFzttERhL84w+WFV+zdFn0+7cf59PNgzVdbFx4t+G7dAztzK+7L/LVmjPk6ozYqBQMbxPOqy0qoVGJgcBljSk3l5Sf5pIyezby9U141cHB6C9dwqlDB7yGD8Om0sMd2JpnyONo0lFqedZiw6UNOGmcqONVBzfb+58ZZ8zMJPqpLhgSE3F8/HECZ85Aus8NWm+lu3SJ6M5PIev12ERE4PzbQp74ZguZ+QY+7VaT3o38qfereW2bWW1n0TxALCz5sFS4bRImTZrEsmXLOH36NHZ2djRr1owvvviCiAgxxU54tJlycoh9tif6q1et0p07d8a5cydsq1WzWgX4cOJhBqwegFE2WtJ+6/gbBq0HvWbv4uCldAAahbnzRY/ahHmKX6NlUfa2bcS/N87SeuHQogW+H7yPJjj4gd9ba9TyT/Q/zD81n0tZl/Cx9yE2MxZvO2+y9dnkGnKt8qsVarpX6c47jd5h55WdVHKtRIhzCCbZvMBfUVfsVTo74/fZZ8S9+irZW7aQMOEj/D4pGMTfK01wMCG//Ups3xfQnjmDtHgBI9u1ZsLfJ/l67Rmqh+RY8rrbilbLsqjctNR06NCB5557joYNG2IwGHjvvfc4fvw4J0+exKGIfcSipUaoaEw5OVweNpycnTsBkDQaZJ2OsBV/YltIwJ+rz+Wp5U+RlGf+Imzo25Dprb/np+2XmLbhPDqjCUcbFWM6VuP5RsEoFOWru+J+JX03HZQKvK5PfbY6N3OmebG4YW+UQs1u0kZHk/rLL6QvNC/zr/L2xmfsGJw6dCjx7iW9Sc/3h79nTewaXG1caeLXBIPelsXnfyHbkF6kMlSyEwapYLdYm+A2HEo8RI4+hwi3COJz4mkd1JrnI5+nsmvl25YnyzKX3xhG9gbzFOzwXTtRuZXs+khJ300necYM1AEBhKxeTefpOzh7LZs+TV3YlDOaHH0OzfybMavtrHLXpVdeVfjup6SkJLy9vdmyZQstW7YsNI9Wq0Wr1VqOMzMzCQoKEkGNUGFcff99MpYsBSD4l5+xb2AeyPjfqbl6k55TKafo+09fS9rW3lu5nKzg7SVHOJ1g/tJpHeHFZ91r4e/68JewLwuSZs4kedp3eA4fZhXY3C79YZNNJk7XrmMZ/GvfuDH+X31ZomNLAK7lXOPj3R9zNvUsCbkFB+oCmPQu6FObIZtsUWhSMBkcwaQBhRbZ4ArIGHOqIBsdUTmewDZgAZLCWGhZ/9UioAWv13kde7U9Ic4hqBTWnQrG9HTONm0GsozvJx/j1rPnfT7j/zy3/HzO1I0CwP+brzkc3oj+P+1Fo1Lw46t+DNn8IgALOi2glletEr33vfh23VmUConhbcILnJu24RxGk8xb7crujLeiqHDdT/+VkWFeM8D9DrvCTpo0iY8++uhhVUkQHqqMFSssAY1DyxY4NGpUaL5LmZfovLyzVVoT36bM2pTAD9tiMJpk3OzVTOhag651/B/pX543Apbkad9ZjstKQJOzdy9xg1+3BDQer71m3mKghKY236Az6mi7pG2h52SjBkmpw1nXiiiHfoQFOxPoZoervQZnWzVOtua6mGQZvVEmK19PcraO5OxqnE1pyPHU/VxLhzwug8kGY14QADZOF1F6rLHcZ9uVbWy7ss1yHOwUTC2vWkx6bBKSJKF0dcXlme5kLF1G2q+/lXhQc+vCg9c++ZSWu3bSKNSdvbGprDmkpKFvQ/Yl7GPdpXVlIqhRKiQmrzsLYBXYTNtwjsnrzjKynAc0xVEuW2pMJhNdu3YlPT2d7du33zafaKkRKiJZpyN7xw7zcvOAyt+PsKVLrZrgx+8Yz/Lzy6njVYcjSUcs6a42rtR2e4wTx54gNtm8sF6XOv5M6FJd7Nd0ixuBjKRWI+v1pRrQ6K9cIXHqVDL/+tuS5jF4EN4jRpTofdJzdfy46xgLz80m326XJd146W2ah1TnsSqeRAbYoLFNpo53zXsOfmVZJiEzn70xqeyOTmH7+WTiUvNu3A2nwBWonI5hIK/AtRMfm0iXyl3M9b1lZezA6d/h1LbwQOxeJU6dSsr3swAI+fUXjnpU4rn/7UatlBjWLZ45J6fQxK8Jc56cU6L3vVe3BjDD24QXOC7vKnT30+uvv86///7L9u3bCSzGNvZiTI1QXsk6Hdc+/wJDUiK62FirJeYjjhy27KItyzJjto3hn5h/rK4PdAxkfONPWbVfw2+7LwHg42zDp91q0a66z8N7IuXI6Vq1kfV6JLWaaseOlkodTPn5xPZ+Du0Z84KITh064DN2LGqf++tuMpqMxOfEcyH9Alsu7eHI5VTOpEQjOdxcaThY1Z5R9UfTrLIXtuqSm2H0X7Isc+JqJv8ej+fvI/FcSr05yDiqWhz+/tFsjf8XMA8ontdhHlHeUciyTOLnn5P6s3kLD/+vvsSlS5cSrVvcoMFkb9kCgM977zFcV5Xt55NpEnWEE/m/0zKwJTPazCjRe96PG4GMRqlAZzRVmIAGKnBQ88Ybb7BixQq2bt1KWFhYsa4VQY1QHplyc4l9rg/as2et0hXOzni9MRT3fv3Yl7CPz3Z/xoWMC1Z5hkcNp6FvQ1JSfPngzxNczcgHoE+jIMZ2isTZViyiV5iy0FIjyzKnI6tbjj1eH4zX0KH33d10Pu08r6x9hdT81ELP2yocea/xOLpXfeq+7nMvTCaZbeeT+XVXLBtOJ1r2vWxX3Z1st1kcTzXvyfR+4/fpXa03hrQ0LjzZ3rI+T+CM6Ti1aVNi9TFmZnK2UWMAbMLDif/2J/r+sAd790MofcwDtf0c/FjVfRVqZdn4W6o67l9wW4NSUnJq1DcFzs86MguTbGJI3dLrSr0XRf3+LjcLT8iyzBtvvMHy5cvZuHFjsQMaQSiP9AkJXHzpJauAxqVbNyqvWU3VPbtx79ePTF0m43eMLxDQ7Hl+Dz0q9+fnTfDKzwe4mpFPsLs9CwY2ZtIztUVAcxu3jqGpduwonsOHkTztO/Psp4coZc4PlsdO7drh/eabJTJ+5rtD0y0BjWy0QZ9eH7XJCzeNN581/4ztz28ulYAGQKGQeLyqFz/0b8jGUa3oHhWAJMG6k6ns29sRJeb9nz7d8ykJOQmo3NyotHKl5frLQ98ga/36EquPeQr5pwDorlyhiZ8d1XydyE2tg6+NeXZhfE68ZfHK0jZtwzl0RhNKSYnKcy0Dln9mdX7WkVnMODyjyFPoy6Ny01IzZMgQFixYwIoVK6zWpnFxccHOrmgzNURLjVCe6C5f5kLbdgBIajXB8+ZiX7++VR6DycDLa17mUOIhHNQOfNzsYxw1jtT1qsuGk+lM+OsEKTk6FBK83DyMUU9GYKd5cF0J5V1Zmf2Uf+YMMU93A0Dh5ET41i0oivg5dyeHLl+h34YOAOReepnKjvUY17k6j1f1uu+yH5Rz17L4YvUZ1p+6Bop8nCImAPBcxHOMazIOgOytW4l7bZDlmsCZM3B64okSub+s03H+yfYYEhKwrVObA29/zeglR/FxVpMbMAqAN+u9ycBaA0vkfvfqv2NoBiz/jAOZC6nv/Bzzuo+zBDRD6w5lcJ3BpVrXe1Hhup9uNyht7ty5DBgwoEhliKBGKC/SFi4kYcLNmXthy5ZiW716gXw/Hf+Jbw98C8Dc9nNp4NuAa5n5jFt+3PwlAET4OPHFs7WpG+T6UOpenpWFdWpyDxzgYr/+YDQi2dpS+Z9VVosn3gtZlvlxewxTo5+2pL1T9W/6NApGpSwfv9o3nLrGh3+d4Jq8GVu/5QAs7/oXVdzMrfa3/s3YVKtGpT+Xl9i9M1ev4cr1gdk2UVH0qvESydk6nCLNu3VXdavK0q5LS+x+xXW7QcE3AhsFKkwYym1AAxUwqCkJIqgRyoOcPXu51L+/5dhn7Bjcbzm+YdvlbQzZYP7yre1Vm986/saifXF89s8psvINqJUSQ1tXYUirKmKLg3Ii7/Bh4oYMxZhq7h4KWTAf+3r17qvMzHw9oxcfYVP8Umx9zV01HUOe5stWn953fR+2XJ2BCSsP8k/6G0jKPJQmZ37v/AeR3uag79YWrtstQHmvLg9/k6y1awHY9/ybjM8NokbkPi6xFI1Cw87nd2KjLJ0ZhHdap6bOz1GYMKBWqDn44sFSqF3JqHBjagThUZA8a5ZVQBO6dIkloMnQZnA06Sjx2fGM2jzKEtDYqewYVecznp+zhzHLjpGVb6BOkCsrh7VgRNuqIqApJ/KOn+Bi/wEYU1OxiYggfNvW+w5ozl3Louv07WyK/xMbn1WAeSZceQxoAOw1Kr58phHjo34AgytGRSa9/m3PpB2zAbCpWhWHx82Lscb27EXe4cMldu+AqVMsjxtdM88SOxttXvlYZ9JxIf1CYZc9FG/dZpbTrCOzLAGN3qRn1pFZpVC7h6vcLr4nCBVJ/pkzXPv8c3J37bakVV6zGk1ICABXs6/SZXkXdCZdgWtbug3m+VmnyNebsFUrGP1kBC81D0P5iG1xUN4lTZ2KrNVi16A+wbNnoyji9i+FSctPY3v0Rcat3IjsM5cbS8m1D23PJ80/KZkKl6JeUbVR2U7gw70jAFhwfjpHUw4yvd1EfEaP5tLZcxji44l9rg824eGE/L4ApaPjfd1TkiQc27Qhe8MGXDzdqOPtyonM/ZbzOfqcO1z98P13DM2NY6DcdkEVhfgJJwilTH/lCrE9e1kFNGF/rbAENGdSz/DKmlesAppQ51DeqPk+vnnDWLLVm3y9iaaVPFgzoiUDW1QSAU05Y9Jqyd23DwCfd9+9r4AmJS+F9ks68d6+F5F95lrS327wNl+1/Ao7VcXYAuOZyDbs6HUzqDietpNWi1uR6GtL5VUrLVuGaM+dI7pTZ/JPnbpdUUVmU6WKucwzZ3gmKgBDZh1sTOa10sZtH3ff5ZeUwgYFD64zmKF1hzLj8IwK3WIjWmoEoRTIJhNpv/1G3tFjZG3YgKzToXBwIGDKtzg0b27Zu2nk5pGsu7gOMHcbfPX4V9grnflzfw5fL4tBb3TEyUbFuM6R9G4Y9EhvcVCe5Wzbhpyfj8rPD9saNe6rrE+3zSbPmG2VtuipRVT3KDjQvLxztrNhYefFPLeqlyVt7KYv+a3rdwT9+APJ02eQtmABhsRELg99g8prViOp730pg6zVqwFQ+/vzZA0fPvxLTWZSHWx8LhOfE8+lzEsEOz/4XdLvxiSbCh0UfOP4xu7oFZEIagThIco7epSLL/ZD1ungljH66sBAAr79FrtaNQE4nHiY/x39n2X/m8oulZnVbhYJqba8vuQoZ66ZFxtrG+nDp91q4utiW/BmQrkgm0ykLfgdAOf27QtsRlocX++Yz/p4c1mVlb1Z0ue9cjO76V7V8Izk8AtH6Lf4fxzVzeBI2mZm7V3F4Ead8R41Eqd2bYnt1Rv91asY0tLua/NPWa8HwKTTEuBiR51AF05kuFrOO2mc7vfplIg7LaxXkbueQHQ/CcJDIZtM5O7fT2yv3sharSWgUXl74/Hqq1T6+y9LQHM56zIv/vui1YZ+v3ZYxA+bUnlm5g7OXMvCw0HDd32imNOvvghoyrnsTZvI2bkTVCpcune/53L+d2AZ8859AYAf7fjjubEVPqC5QalUMLfnQFyIBGDGqTG8uGogZ1LPWK3vY7h27b7u4/vRBABytmxFlmWerOFr2ZQTYPqh6fdVvnD/Ho13vCCUIlmWSVu4kIsvvGhJc+/fj4ijRwjfugXvUSMtH7wrzq+g47KOlnwj64/k2yZ/03naTn7YHoNJhu5RAawb+ThdHvEdtSsCWaczr40DOD/ZDtuIe9tNeX30br479jGSJONhepwVz3+BWvVoLbKoUamY3+1bHEzmbrbDyXt49u9nmZb+J4rWzQHzjCjTLZscF5d9/fogSch6PYbEJFpHeCMbXJHzzLOgFp9dTFp+2v0/GeGeiaBGEB6g3AMHONu4Cdc+vjnjJGDyN/iMHYtCo7GknUg+Qd9VfXl/x/uWtGmtZnH2bH0Gzj3BpdRc/FxsmTugId/2rou7gwahfEv95VdO166D9vRpJI0Gj0H31i2wIXYzI7e+AZIRlcGP5b2/xO4+xo2UZyEuAazq+Qu2mT0sab+c/IXJXeFGZ2/Kjz/ec/kKe3vLAP78Uyep5uuEm72a3PguKDAHkRV5EG55IIIaQXgAdJevcHnYcC72fQFTZiYA6uBgKq9fj3OnTlZ5z6Wd44V/X+BosnknaAe1A29Vn8mY+Xn8vjcOgBebhLD2rZa0rnZ/uzMLZYMxO4drX3xhOQ6c/t09t9K8u/UDZMnc+jC97RTc7O1LpI7llYejDb88OxLd+YloE9sDsDNxD5rRrwOQ9utvGK9vgFlcxowMdHHmv0mbKlVQKCQah3lg0vpSxcG8Po7WeO8tQcL9EwOFBaEEaS9cIGvtWpKmTrOkKRwcCJj8jXlWk0qF1qjlSvYV5h6fy4mUE8Skx2CQDdip7Pi25WwWbDXy8VJz33+YpwOfP1OLxpU8SuspCSXMkJLChU6dwWgEIHjePByaNL6nsj7eMgetnA5At+BBNA+peDOc7kWknzPjOtXiw3/SsPFeA0BSuyhcp6oxpqWRd+gQji1bFrtc7blzlv9vKi/zfllNK3uw+kQC8VnXQAEapWhFLU0iqBGEEmDKzeXKO++QvX6DVbo6MJCQ+fNR+3hjkk18u38yc0/MLXB9Ha86NHV5nTfmJpGWq0epkHi1RSVGtA3HVv1ojY2o6LK3bMWUkQGA/9df33NA8/vJ5fwRaw6e/dT1ebt5vxKrY0XwYpMQNp6OYHdWddROJ3lt8xC+bBZK6JbzaM+evaegxjYyEhQKMJk4U6cu1U6dpH6IGwBZciwAv5/+nfcav1eST0UoBhHUCMJ9kGUZU3Y21z7/3BLQ2NaujUvXrrh0e9qyiune+L38dOIndlzZYbk2wDGASPdIIl2asG5fIF9tTQfMvzK/7FGbWoEuD/35CA9e3jFzNyNqNS5Pdb6nMo4kHWHivvEA2OhqsqLPD9hpxMf5rSRJYmL32rSd/CI4jQVgfJM45m2F1N/m49qzJ0qX4v2NKRwccHz8cbI3bQJA1moJ93FEpZAwyQoxnqMMEH8FgnCPZKORSwNesqwEiyQRMHUKzk8+aclzNfsqhxMPM2HXBPIMeZb05V2XE+gYxvSN5/lq6QX0xnTs1EreahfOS83DUD8iU3EfRUon82Z8an+/ey5j8t6bg1EntfxQBDS34e9qx4i2kUxaOwbH8M/JVxj54zEFvbclkL1t+z0FlbcGNQpbW2yAKt6OnL/WCbuAxSX8DITiEp+cglBMstFI6m/zudDuyZsBDeDz3ntWAc2V7Cv0/Lsn72571xLQPF35aXb02cHVJBfaT9nK9E3n0Rtl2kZ6s25kS15rWVkENBWc4VoCALYR1e7p+sz8LA4mbwfAQ1GTdvdYzqPipeZhhLoGoE1qC8CWWuZlENKXLsGQklLs8pQe7pbHN6aH1/B3QWGTDEBTv6b3W2XhPojwXhCKIf/MGa6MHIXuws0deR3btMFn7Bg0geY9YFZFr2L8jvFWezXV9KjJ4DqDiXRtzLilp/j7yFUAfJ1tmdC1Bu1r+Ig1Zx4RN1alta1Z856un7p7heXx563HlkidKjK1UsGItuGMWNIQG6/1JLtInAqEyF27iRs0mLAlfxSrPPu6dS2P9VevYhMWRriPI1K8eZZjUl5SSVZfKCYR1AjCLQypqSR8+CFZm7fg2KwZrr16krV+AxnLl1vlk2xtcenSBa83h6Py9CQpN4k/Ds9k3cV1nE8/b8nn5+DHzx1+xsfel/l7L/HGj1vIyjegkKB/s1BGPRmBo434M3yU6K+YA1qls3PxrzUaWX5+CajBRRVAk8DaJV29CqlLbX9mbgrkUk4lVA7RfN1DxVc/GvC8eLHYZWWuXmN5LOfnAxDsbo8+rTEa1/2cTz/P/FPz6RvZt8TqLxSd+DQVhOtMOh2X3xhG3sGDAGRv2UL2li0F8mmqVCbk559ReZinWUenR9NvdT8ytOYZLUpJiVE20juiNyPrjyQ6Uc/rP+/kcFw6ALUDXZjYvRY1A8RA4EfS9b2djNdnQBXH19uXoVebWwmfr97jLrmFGxQKiYEtwnhnxTM4VvmaLHs4WEWid8PexS7r1v9v6iDzFgnB7vaY8oOQdH7ImnimHpwqgppSIoIa4ZGnvXCB5Jnfk7lqlVW6XZ065B05YpXm2Lo1fhM/Q+XmxvHk46yOWc2y88vI0mUR5BREv+r9aBXUCl8HX1JzdHzy9xkW7ruELIOjjYq320fwQpMQlArR1fTIur7vl6Qp3nomJtnEsgsLuL5wLa/XHVjSNavQutTx5/N1NtzoFP5fRyVJHOHjYpbj8fJLJE83b22hPXUK+4YNCXIzL3iYm9wMO/+luNiIHyylRQQ1wiMtbfFiEj7+BAwGACS1mqA5/8OhSRPAvDKwysPdalM8o8nIsnPL+HDnh5a0au7V+F+7/+Fm64bRJPPrrli+XnuWjDzz+Iludf0Z2ykSH2ex+eSjTBsdQ97hwwAY04q3R9DXu38iX3ke2aRhQcfFYgxWMdmqlfSOqsvsPYOwD50NwHIO8VZ+Gm62bkUvSHlz3ajc/fuxb9gQZzsVaqWEMd88ri4hJ4G04pYrlAgxzUJ4JOmvJRLb9wUSxn8IBgOSnR3u/ftR6d9/LAENgCYwwBLQ5Bvy+fnEzzRf2NwqoOkY2pEfnvwBN1s39sWm0uW77Xyw4gQZeXoi/ZxZPKgpU56LEgGNgP7KZctjx8eLt/jb0nO/AxCu7k5t38olWq9HRfeoAIx5YfRfHGVJS12/5g5XFGRIujkQ2LFVK8C8Jo6bvQaT9uY0/e8OfXd/lRXuiWipER45Jq2WS/37o4uNBcCt34t4jx5ttcHkDbIsk2fIIzkvmbHbxlr2Z1JJKrpW6corNV8h2DmYxMx83vrzMMsPXQHA2dbc1dSnUTAqMUVbuE7p6mp5bMrNLfJ1+XojOcYMJAW8UKf9A6jZoyHcx4ka/s78rqwCHAJAeeQMPFX0Mm4d4J25Zo15lWHA3UFDYpaWQIcqXM45zx9n/2B80/ElWX2hCERQU8LyT54ka/16vIYPL+2qCP8hyzIpP/xA0jeTzQlqNUEzZ+DYogWHEw8z/dB0MnWZVPeoTlP/psw+OptzaeesynBSO/FyrZfpV70fGqWGfL2R7zdfYPrGc+TojEgSPNcwiNFPRuDhaFMKz1Ioy27tcrKvV6/I1205mwSyubspKlDsA3Y/2tfwZXJCdZyuH/+hOcLbxbhe6eyM0sMDY0oK6UuX4j1iBADOtuad0Zt4dGNJztdUdbu3DUqF+yOCmhJkTE8n9rk+yDod+mvX8B49GpWb6FMtbcbMTNKXLiPtt9/QX7liSfcY0B/HFi2Izohm0LpB5BrMv5xPpZ5i6bmlBcqRkPit029Ucq2ELMusOHyFL1ef4Uq6eWG9qGBXPupag9qBrg/leQnliyzLpPxvDgAOzZqicHAo8rWrjsaDZB73Zae2u0tu4U5aVvVi8jo7Kl/WcCFQxy/e56gevYrOlYq+urDPO29z9d0xGJOS0UbHYFMpDI3K3CKrlsyDhi+kXyBbl42jxvGBPA+hcCKoKUFKV1dce/cm7ddfyVi6jJyt2/AZOwa7+vXJWLYMdWAQLl2K0c4p3JYxKwuFgwOS4mbXjqzTkbN3H7I2H5sqVVD5+KCwtSXu9SHkHThgdb3P++8T374O324by/Yr2y0BjZedF5VcK7Enfg8AjwU8RmxGLG2C2/B0laep5FqJ/bGpfLLqFEeuT9H2dbbl7fYRdI8KQCFmNQm3YcrJIXf/fgBsa9Yq8nVGk8zmmGNIAQYkFDhpnO5+kXBbtQJccLVX0/yoLRcCzXOhxm4bW6ygxrZGDcA8g03t5wuASmn+21dg7sa2V9ljqxLj6B42EdSUMJ8x72JbvTrJ06ejv3KFKyNHWZ1P/fVX/L/4HJuwsFKqYfmUMm8e2es3IBsMSHa25O7dB0YjmtBQc+uLSoWcl2d1jcLBAdlgQL6+lDmA9zvv4NrvBX46OY9p//SxpAc6BvJrp1/xtPMEQG/So1aorcq7mJLDkPkH+OeYeZl7e42S1x+vzMAWlbDTiJ2079XMwzNRSAoG1xlc4NysI7MwySaG1B1SCjUrWTc2NwXI/U+QfScnr2aSyyXsgDCXUPHL/z4pFRJ1g1xZkjSIDxZ8zifPK5GRMZqMKBVF+zvOWPEXACo/X8tEghvbm2TqzF2MWfosVArxFfuwiVe8hElKJa7du+HQvBkJH4wn98ABTNnZlvP5R49y6aWX8R3/AUpnZ+zq1xdTM29hys1FF3cZTWgI+rg4Mlb8Rf6J4+Ts3FVo/huDfbm+9LxVWTk5lsdKL09Cf/sNAv34YOeH/B39NwB2Kju6VOrCsKhhuNq6WvLfGtCk5+qYvvE8P++KRW+UUUjQu2EQb7WrireT+CV2vxSSghmHZwBYBTazjsxixuEZDK07tLSqVqJufT+69epZ5Ou2nb+G2uUwgAhoSkidQFfsVp/FcEsMk63PLvL6Mhl//gmA/uIlS5p8ff0htfLmZ8eOKztoHtD8/issFJkIah4Qtbc3QbNnmb+kL13CJiICfVwcsc/3xZCQwOUh5g9qTVgYSnd3bMKrYFerNrLJiPbMWbTnz5O7ezd2deogI6MJDMK9fz80lSphSExC7e+HwrbifKHKskzW6tUkfDYRY3LybfP5jP/AHMgYjBizsrBv0ABTXi666BhsIqri2LIl6oAAMJlI/n4WmStXItnaEvLzPBJVefT6ow3p2nQAXq31KkPrDr3tr7McrYG5O2KYvTWarHzzeIaWVb14r1M1qvkWf4l7oXA3AplbA5tbA5rCWnDKI+35m9tn2Dct2qaHRpORuRffQOUYD5g3RBXuX80AF2qd34KTSbakfX/ke8Y0GlOk6yWbgpMA8vUmAOq6Pc6yy58D5vF5Iqh5uERQ84Ap7O2xrWbeRVcTHEzY0iUkfv0NmX+bWwp0MTEQE0PegQOkL1xU4PobK9rmHzlaYMXbW3mNGIFd3bpkb9mCLiYGl2e6W+0YXVZlrl5N6tx55J04YbUA3o1N/+yionB+qjNKZxecnmhd9MGVCgVew97Aa9gbAJxJPcOzS581l6my4/0m79O1ctdCL83XG1mw5xIzNp0nJcfc517N14kxHavRKsL7fp6ucBu3Bjb/O/o/9CZ9hQpoAHJ2m8dpKT09UXsX7X2UlJdEPuaApp5HS3pF9Hpg9XuUhFw5izHH/OPp2ZCnWXJxBfNPzWdUg1EFup0LY1e3LvrLl7G5Pp0bzJ8bAHYapWWrlAY+DR7MExBuSwQ1D5nax4eAr77Ef9JE0n5fiCExEdlkxJiaRv7p0xiSk1D7+KKPj0fh4IAhORlJpcKUmXnHcpOmTLE6zt68mSuYWzZcuna16s8vDbIsI+fno798mWtffkX+0aPIgOmWfVQkjQaPV1/FY9BrGNPSMGVloalc+b6751bHrObtrTcnbX7e4nOeCH6iQD6D0cTSg5eZuv4cVzPMG9WFetjzVruqdKntLwYBl7Bv151FqZAY3iYcMAc2NwIaBSryEgv+PyrPbmyLoHR0RJblu76vDSYDb258y3L8TauvHmj9HiWOh/dw45MnC4MlXVGE9Whlk4nMf/8FwPP1m0F33vWgJl9OwyibH4uhBQ+fCGpKiaRS4f7iC0XKK8syppxc0hcvxqFZUzSVKpE8bRoqPz8wyWSuXo327FkktRrb6tXBZLSMQbn28Sdc+/gTANz69iX34EHUPj7YVq9Ozp49KBwd0ISE4Na7N4akZOwbNyrxP0Td5SvEDRx4c/zLf6j8/QiaORNNWBiK6826Ch8f8PG553vqTXpmHp7JquhVxOfEW9Kb+TejVVArq7xGk8zKo1eZuv4c0cnmcQ++zra82TacZ+sHWgYACiVLqZCYvO4sAMPbhDPryCxLQGPCwJHsP4BxpVvJEuTydFeSpk5FFxtLxooVuHbrdsf8Z9POcjL1OAC26c/h6Wj/EGpZ8WnPnyfjxx8B2OMTyb6EvQB0CutUpIHCptybExKULq6Wx2nXW3WNinRLmq+9bwnUWCiOchXUbN26la+++ooDBw4QHx/P8uXL6XaXD4aKQJIklI4OeLz8kiXNe/Roy+PCgiPd5cskTZ5Mzs5dGNPTAUibPx8wb8KWvXmzJW8OkPbLr+Z72dnhOeR1JKUKhZMjttWrIymV2EREFAh2DMnJ5J86jX3jRrddjTd90WISJkywSrcJr4Lb88+j9PREzsvDuVMnJNW9vxVjMmKIyYjB294bpaSkmns1VkWv4odjP1jl+6f7PwQ5B92sv9HEn4evMnPTeUsw4+6gYUiryrzQJARbtZjR9CDdaKGZvO4sBzMXcyBzIfWdn2Pznrq0anyYA5kLmXXEo8J0Qanc3XHp8hTpfywh8YsvcXnqqTu+75Pzbo4tq2T32MOo4iPBkJhoefxDgwZkaM3bT7zdsGhL8CkdHXB8/HGyN27kUv/+VDt6BNRqkrPNQU093+qWvBczL+LjcO8/zoTiK1dBTU5ODnXq1OHll1/mmWeeKe3qlGmawEACJk/GlJtL2u+/k3/mDLrYi+guXsS5U0eMySnor1xB6epiNbNIzsu7ueLuf9jVqYNtjRrorlwm7+AhTFlZlnMqb28q/f0XaQsXYcrLxa5WLdKXLiN740ZLHo/XB+M5cGCxFh2TZZksfRY2Sht+O/kb/o7+pOancjz5OOnadM6kniEpL+mOZSx8aiFVXKtgozS3AukM5m6mmZvPE5dq/tXlYqfmlcfCePmxMBxtytWfRbk2vE24JaAxJD/J5lN1GdmuKsPbdGbWEY9CZ0WVZ5rQUMC8srBsNN4xqLmxvACYWw6FkiEbzV1DJiSSA2O4MYLm1tf7blye6mz5bNNfu0aehy86o3mgsElxc6iAvVq0rj1s5erTu2PHjnTs2LG0q1GuKOzt8XjllTvmkXU6jDk5mDIySF+6lLzDR1C6upB3+IjV5m15R45YBi7/lyExkbONmxR6zvGJJ/D98EPUPsUbZDtu+zj+ifkHg8lw98yYBwDnGazXqvnuie+o4WFeKCtfb2Tx/jhmbb5gGTPj4aBhYItKvNg0RAQzpaRRmBt7NjxJXtITaJQKqzE2ACbZVJrVK1F2tWtbHhuTk1EEBNw2761fst7OBVtChXtjV7s2kp0dirw81O6776kMtb+/+YFSiToggJhEc0uvs62KNRdXAhDgGGD57BEengr9Ka7VatHesvBa5l0G2z6qJI0GlUYDbm54j7q5WKApNxftuXOovLzIO3KE3P0HkDQa8g4fRunmhsrDHeenunCpf/9Cy1V5eeHx6qu493vxrnW4sfBVfHY880/NZ8fVHZxPP19o3iCnIIKdg4nPjqeeTz3ahbSjjlcdHNQOXM66zPxT8zHJJl6v8zqutq6k5ej4bfdFft51keRs8/vB28mG11pW4vnGwdhrKvSfQZlnSGlHXlIIGqUCndHEtA3nCgQ2FYV9w4aWx4akJPPyA7fhpHFCQomMEZUm67b5hOJRupjXopFvSfuk+SfFKkNxY1NLoxFMJmKSzWuRhXra8uf5PwHoU62PGChcCir0p/mkSZP46KOPSrsa5ZbC3h67OnUA8y8T59u0kkWePoUpP5/8Y8ewrV0bZLnIa+jojDq+2vcVS84twWgyIlt91ECocyhzO8wlMTeRIKcgcvQ5eNh53HbaZaBTIO82eheAmOQcvl59jCUHLlvWkPB3sWVwq8r0ahAkxsyUAdM2nGPyurPXu5zCLcdwc8xNRWNbowb5J06gi4vDrm7d2+azU9lhgxf5JJBhigVaPqwqVngKe3tMeXko81wx2qUTnx1/94tuoQkOtjzO+Hsl0W41AQjyhK3XJyaEOIeUXIWFIqvQQc3YsWMZOXKk5TgzM5OgoKA7XCHcK4WtrdWv0LuJyYhhbexa1lxcU2An7CquVXit9mv4O/pT27M2kiRZmuLvtu+NLMvsi01jzrZo1p+6xvVFPqnh78yrLSrRubafmM1URvw3oAHrwcO3HlckdvXqkX/iBJkrV+HSpcsd82pMvuQrEriYewDo93Aq+AiwCQvDmJJCSLwN0ZUgQ5dx94tupbz5g0hhoyE6ydz9FOHlz4FrDuToc8S+T6WkQgc1NjY22BSy8qPw8MmyzKHEQ+hNepaeW8q/Mf9azjlpnPis+Wf4O/qTZ8ijukd1NMrijSHI1Rn46/BVfttzkeNXbnYzPlHNm4EtwmhayUM0BZcxRpNsFdDccOPYaJILu6zcc+3ejbRffyV7yxb0iYl3XIjPyVSHTMVhruSdKdLaNkLRaCpVInf/fgKykokGNIrifd7cur6WXVQUJxebu8qreDngmu5Kjj4Ho8lYklUWiqhCBzVC6UvLT+NU6in+vvA3K6NXFjg/qv4o2oe2x8/R757KP5+YxW+7L7H04GXLVgYalYIe9QJ45bEwqniLHY3LqrfaVb3tuYrYQnODyu/me/3GZoi3o7m+IWKK7gpxWXEEOwffMb9QNDc2FPVM1wB5rL24lmFRw6z2bboTQ0rKzbJSUjlzzTzm6appM1eyryAhEeYiNi0uDeUqqMnOzub8LfunxMTEcPjwYdzd3QkOFn/sZc284/P49uC3BWav2KnsaObfjE+af3LX7qTC5OuNrD91jd92X2R3dKolPdjdnr6Ng+nZIAh3BzFbRCib8g4ftjzOWrsO1x63X55Cq7hieXzrhqvC/dFduABAVEw+yx+HK9lXuJpztcjjYG5sWaMJC+O8ox9GUyyejjacTN9vLtc7Cn9H/wdTeeGOylVQs3//flq3bm05vjFepn///sybN6+UaiX8l96o59M9n7Ls3DJLWn2f+vQI70GXynceQ3A7sixz5HIGSw7E8feReDLyzHtDKSRoE+nDC01CaFHFU2xlIJR5trfsFxQ/btwdgxpfdT2u6lcDsPPqTjqEdnjg9XsUGNp1QrXuHxa1NsL1rRGKM7D3RmCqi4nhUFw6AHUCXVh3cR0ABxMPlmR1hWIoV0FNq1atLNu7lyUJOQn8fOJnRjUYhUpROi+p0WQkS5f1UH7NmWQTOfocq1YWnVGHJEnIssw7W99hw6UNAKgkFZt7b8bFxuWe7pWQkc/yQ1dYciCOC9cH4wH4udjybP1A+jQKxt/1zk34glCWqH19CZ77E5deehmAtD/+wK1nz0Lz+jn6QJr5cZRX1MOqYoWX7O6HL6C6x2EvhuurtCs9Pdlx3rzys7vPKbi+WLGtUgwSLi3lKqgpi/QmPQNWD+BK9hU2XNpAn2p96B3RG3u1PXvj9/JPzD/0CO9BdY/qRdpX5Fbx2fGka9Op6lYVg2zgVMopbFW2nEk9w8ZLG6ntVZtq7tVIyU9h6sGpJOaa/6KeDHmS/jX6U9m1Mg5qB2RZ5kr2FQIcA8jUZfLn+T9RK9S42rhS3aM6FzMv0jKwpSUokZHJ0mWhlJTIyDhpnJBlmYuZF7mafZXxO8dzLfcaAMFOwTTxa8Lis4sL1L9HeA/eb/J+sQO9xKx8Vh9PYNXRePbGplpmMNmqFXSo4UuP+oE0q+yJUrTKCLeR9N10UCrwGjKk4LmZM8FosuzgXhocmjbF9bnepC9cRMKEj3Bs+Xihi1M62uktQY2YTVNy5IP7AHC7Zfkfg8lQpM8q2WBAe/IUADZ167I7OhWFzVXWJE635NnUa1PJVlgoMhHU3Ce1Qs3wqOGM2TaG+Jx4Jh+YzLSD03C1dbXs3bL03FJCnUMZ23gske6R5Bpy8XfwJ12bjqPGEaWk5FrONeafms/GuI3EZcUV6d4b4zYWmr724lrWXlxrOfay87rrVgJ2KjsquVQiOiO6wKq8vg6+5OpzydQVXLzwUtYlLmVdskpTSkrea/wevSJ6Fel5wO0DGYBGoe70qB9Ap1p+ONkWbSCf8IhTKkie9h2AVWCTNHMmydO+w3P4sNKqmYXvhx+SvnARGI3kHTyAupB1oFJNxy2Pk/OS77nFU7CWk6dDBnbXUAHmMX9FDWrSFi6yPE7o0Z+8NddwDTiGERP1ferz45M/FvsHrFByRFBTAjpV6kSEewR7E/by3cHvyNJnWW1Gp5JUxGbGMmjdIEuah60HKfnmEfQSUoFF5+7G297b0jIT4BhAh9AOPBH8BJviNvHDsR9QSArLAN27BTQAeYY8TqScKPRcQk6C1bGt0pZnwp9hwekFuNu6k2fII9wtnNZBrannXY/KrpXv+uEryzKn4rPYePoaG08ncigu3SqQqRvkSudafnSs5Uugm9g/RSieG4HMrYHNrQFNYS04D5skSeb1ToxGTLm5heZpF9KGdQnzANiXsI/KrpUfYg0rprToi1S5fJosO8hXmT8ju1XpVuSWsKw1ayyP1+aYP5tcXBNJNcETQU+IgKaUiaCmhFR2rYyTMoCrV6ri652AQZFMFdcqNPNvRkp+Cl/t+4q1F9da9jG6EdAAloDG1caVPEMeTfyaEOwcjKedJyHOIcw8PJPuVbrTN7IvV3Ou4qh2xMXGxTK+6Na1K2p71ebNem+Srctm7cW1pOWnkaHLoJ53Paq6VUUpKXG3c0clqbicfRmNQoON0oZ91/aRmpdKba/aJOUlEZsRS33f+uTp87iYeZEQ5xCCnYPRGrX4OfihUqgY23gsYB5jo5DuvqBdttbArgspbDydyOYzicRf33/pBhHICCXp1sAm5ftZyHp9mQlobpBsbJBzc1H5+hZ6vo7/zW0Ugh0iC80jFJ1sMhE3cCBqYG2UmhubJbxV/62iXS/L5O4zd125Pv88/xwzrx7saq8gNZti/zgVSp4IakrQupPX+G6duVWjincoT1b3wNaQRp1Ad75o+QUf6D5Aa9SyJtYc6Tfxa4JKocIkmzBhIsw5rNDFtdoEt7E8DnC8+SF3p4W4HDWOPBN+553Mg5xurq7cLqSd5XEkkbQMvLkkewPfBncs53YBTa7OwP7YNHZFp7DrQgrHrmRYLahmq1bwWBVPWlfzpnWEtxjwK5Q4ryFDLAGNpFaXqYAGwCa8CvlHjpK1dh2OzZsXOO9qd3NH+4spuTQTC6LfF/3VeNRXL7OmrpJFj5s/i2yVtrjbuhfp+rTff7c8TqjVmPg9+TjawDVtzAOpb1GV9TFkD5MIakqQv4sdLcI92XUhhfOJ2ZxPzGbm5gs42ahoUtmDFuGePFbFs0JudCbLMvEZ+RyOS+dIXDoHLqZx5HI6eqP1L5cQD3ser+rFE9W8aVLJQ+y/JDxQSTNnWgIaWa8naebMMhXYODRuQv6Ro+QdO4oxI8Oy2eINWbqbI1nPJeT993KhmHJjYgFYX1cNGOgd0Zt3G75bpGu158+T+PU3ALj26sVsZQAQS5XwA1zQZ+OscaZn1cJnsT1w5WAM2cMigpoS1LqaN62reZORp2fzmUTWnrzGjvPJpOfqWXfyGutOmmcMeThoiAp2JSrYjaggV2oHueJoU37+V5hMMlfS8zidkMWZhEyOXM7gcFw6SVnaAnkDXO1oUsmDppXN/wJEa4zwkPx3DM2NY6DMBDZObduQ8sMPaE+eIqb7MwTPm2u1WaKPgw+emmCSdZdYmTCZYflRuNm6lWKNy7eTW/fhIkGcj3kYQP/q/Yu8inDilCnI18c+ubzzLsu+3obK6TgXTX8CMKTuEOzVpdNtXh7GkD0s5eebtBxxsVPzdN0Anq4bgNEkc+JqBtvOJbP9XDIHLqaRkqNj/alE1p8yD/SVJAhys6eqjxMRvo5U9XEi3NuJIHe7Up3tk5GnJy41l7jUXC6l5hKdlMOZa1mcu5ZFjq7gAg9KhUQ1XyfqBrlSJ8iVJmEeBLnbVbhWKaHsK+wDvbAP/tJmV7s2wT/+wJW3RqK/epWLAwZQZf16JMXNLt0xDT5l1PaXyVNc5LV1g1j01MIijWETrMlGI8oVS9gdIWFSmGd8+joWPpapMIYk84QLl27d+OdMKpn5WpzCfsMgg7edN89WffZBVb1IysMYsodBBDUPmFIhUTvQldqBrgxtXYV8vZGT8ZkcupTOoUtpHLqUzpX0PC5dDxzWn7pmdb2LnZpANzsCXO3wd7XD3UGDu4MGj+v/dbFXY6tSYqdRYqtSYqNWYKMyf+DJMphkGdP1/+brjeTojORoDWRrDeRoDaTn6knO1pr/ZelIytaSmJVPXGqeZdXewmiUCip7OxLh40gNfxfqBrtS098FO43oThLKAKOp0A90y7HRVMhFpcOhaVOCf/6ZmKefxnA1Hv3Vq2gCAy3n21Wui2pVZ4xuKzideopMbabYMqGYZJOJ819Oxj47hV/amL/2BtQYgFpRtB+NptxcDInmoMapbRsW7LmI0uGC5fzPHX/GRln6myeX9TFkD4MIah4yW7WSesFu1At2A8wbniVnazl7LYtz17I5cy2LswlZRCfnkJqjIyNPT0aenhNXC64R8zB4OmoIcrcn2N2eEHd7InydifB1JNTDAZVS/FoUyqY7DYosix/0thFVUbq7Y0xNxZCUZBXUKBQSjwU8xubslUgKI7+f/p3X675eirUtf+I/+IDTO5cx9TUlqc7gqHZkQI0BRbpWNhq5+MKLGOLjUTg4cManCgfXn8A+YL8lT6BT4B1KeHjK+hiyh0EENWWAp6MNno42NKvsaZWeozVwJT2Py2m5XE7LIz4jn7QcHSk5OlJzdKTl6MjM15OvN5GnN1rNLLodjUqBg0aJg40KB40KZzsVXk42ljp4Otrg5WRDkLsdQW72OJSjsT6CUJ7ZRkaSs2MHeUeOYB9lvSVCj1r1WLe6ARq3PWyM28jgOoNFt24RmfLzSVu6jPfG3vws+7T5p0Ue/5J/4gT5J08CEPjdNIYdMLfYKJ2PAtzTprwPQnkYQ/YwiG+sMszBRkVVHyeq+hTtj0ZvNAc3Wr0JSQKFJKGQzFO/JQlsVUo0KtG6IghlkUPTJuTs2EHi51+QMms2vuM/wLlTJwCaVfFAk9Ue2eUAp1NP83f033St3LWUa1z2ac+d4/izXRk15Ga3+PdtvuexwMeKdH329h3EDRxoOb4UHMnGv7ZiF3BzW5hpraeVXIXvUXkZQ/YwiG+4CkStVOBsq7a0vLg7aHC11+Bip8bZVi0CGkEow9xeeAHbWrUAMKank7pggeWcjUrJ07WqoUs1r2Xz4Y4PiU6PLpV6lhey0cj+Pl0ZMFJFiou5VctZ7V7kgCbhk0+tAhqbiAi+3XgBlfNxVNdbaaK8o6jvU7/kK19cdxhD5jl8WJkaQ/agiZYaQRCEMkBha0vwTz+SPH06qT//Qt6Ro5jy8lDYmZdB6NMomN/2tEXtdAqDTSK74ndRybVSKde67MrespXfWt/8IWdj8uDXzj8V8dotpM2fD4Bzp044d+3CqZDarJ29CxvveEu+UQ1GlYluwPI2huxBEj/dBUEQygilkxPeY8aYt03Q68lcfXOfoRr+LtQJ8ASFeXuRz/d+XmBfNsFMn5DAb98PZXtN81ecPm4oS7uuopJL0YLA9D//BMCle3cCJn+D4+OPM/GfU4ARF0/z+JrqHtWp41XnQVRfuA8iqBEEQShDJEnCsdXjACRMmIAuNtZy7tWWlTBkR1iO2y1ph9ZYcNHLR1n+2bP8O/o5Zj5lHkcj6Rx4o9kThHg43OVKM31iIln/rgbAqf2TAKw4fJXDcenYO8eRJyfhZuPGvA7zHkj9hfsjghpBEIQyxuftt7GpVg1Zq+XK2+9YNq/tWNMPf+MLmLQ3Z0p2Wd5FtNhcl3f4MIvf6824djc3DPY1DOS1llWKdL3u8mUu9esPgGRnh12tWqTl6Phk5UmQdNSOuAhAsHMwdiqxOnpZJIIaQRCEMkbh4EDg9OlINjbkHztG6o8/AubFPIc8Hk5O9Gik5D64alyJz4ln9tHZpVzj0qe/lsi6iUP5+qmbi4aaYj5mTq8+d50kIev1JE6ZQmzPXuhiY1F6eBC6YD4qDw8m/nOKVG0SruHTOJH9LwAtAlo80Oci3DsR1AiCIJRBmsAAXLp1AyBxylR0cXEAdI8KIMLHicykOrhJ9QBYcnZJaVWzTJBlmSMjX+OLVhnIkgSZlcg6/QkTuzUqUrfTpYGvkjJrNsa0NNQhwYQu/B3byEi2nE3ijwOXsQucj1GZjFJS8lb9txhYa+BdyxRKhwhqBEEQyijfD97HvkEDMBhInj4DAJVSwftPRQJw+ly4JW9qfmqp1LG0Za1fz962zRjW4jyZDuaZSNkJfRjaqhpP1w246/XG9HRy9+wxHyiVVPrzTzRBQSRlaRm1+AhKh3Mo7S4B8HbDt3m55ssoFWI7mLJKBDWCIAhllKRS4f3uOwBk/P036cv/xJidTYtwL9pU80aXG4BSNrdEfLP/m9Ks6kMnm0ykLVrMrJ+HM7BfNtl25oDGlFWZDpHhjGoXcZcSzGKe7Wl5XHXPHhR2dphMMqP/OEJythb74B8t558Jf6Zkn4RQ4kRQIwiCUIbZ1aqFU8cOYDIRP3Ys55o1J23xYj7uVhMHtR05CeYZOiujV/LF3i+4kn2llGv8cKTM+YEpGz7il7bWrSZ17N5kynN1USjuvH5M+pIlnK5VG/3lywB4vPYaSkdzgDhr6wW2nE3CRq2z5J/42EQxOLgcEEGNIAhCGec/cSLur7yMOiQYWacjYfyHmMaM5CuXK+jTo5C1fphkE7+d+o0OSzvwb8y/pV3lB0Y2Gkn44gtWrZzCsubmrzA5N4Tc2MFUzf+KH19siY3qzt1D+mvXiH//A2S9eVCxa89n8R75FgDrT17jqzVnABjfuZ7lmnkn5j2AZyOUNBHUCIIglHEKOzt83n6byqtX43l9hdjszZsJm/M1//75Hn6HnsIlawBuNm4AfLH3C8s08IpE1um4NGgQ31z+ha+fNQcucp4P2RcH0Tq0Eb+91A47zZ0DGt3ly8R06245du/fD9+PPgLgTEIWby48hCxD38bBNKlmsORrFdSq5J+QUOJEUCMIglBOSJKE1/BhhPy+AIX9zV2mp236HvmUO/X4Bo1CQ0p+ChsvbSzFmpY8WZa5NOwNptvtYnWD6ysFZ9Qm+9JgnmsYwqwX6t81oJFNJuIGDcaYlgaA78cf4TN2LJJCQXxGHi/P20eOzkiTSu689oQb3VZ0AyDcLZw36t5+KwKh7BBBjSAIQjljHxVF1f37cO3Vy5L2w4Yv2bnzNDUczTt7f7DjA/qu6sv3R74vrWqWCJNWS9LMmeytV53PXXZYApr8a50wJPTlo6caMOmZWqiUt/86M2ZkkPrrb8QNHIjuwgUUDg5U2bIFt+uvX0q2lhd+2MOV9DzCPB2Y2bc+Pxy/ufbPm1Fvlok9noS7ExtaCoIglEOSQoHfxx/h9lxvYp7pAcDPayfynM1bONR1IUufwdHkoxxNPsozVZ7Bx8GnlGt8b06Pf4dp8np2jLj5dWXIDsfT+CTfvRZFg1D3O16fs3cvca8NQs7Pt6S59uyJ2scbgIw8Pf3n7uVCUg7+Lrb8NrAxexI38Of5PwHoEd6DloEtS/6JCQ+EaKkRBEEox2yrV8e1z3OW4+eP7yH13GBquTW1pP10vGi7U5clObv3sGvYC3ylWs+OGje/qox5/nT0GsOat1reNaDJWLmKS/36WwIat34v4v/113i/8zYAydla+vxvN8evZOLhoGFy31A6rGjEO1vN0+j9HPwY12ScaKUpR4rVUpOens7y5cvZtm0bFy9eJDc3Fy8vL6Kiomjfvj3NmjV7UPUUBEEQbsN37FgyV/yFKTeXrjE70SvV/KrvxhtdOvC/Mx+y+MxiGvs15ongJ0q7qkVizM5m8f9GMvnxTCy/vU0K3JO/ZkKXOrSu5n3XMjL//Zero0dbjsOWL8M2MtJyfDU9jxd+3EN0Ug6ejhqGd9Hx6qZulvMRbhHMeXIOaoW6pJ6W8BAUqaXm6tWrDBw4ED8/Pz799FPy8vKoW7cubdq0ITAwkE2bNtGuXTuqV6/OokWLHnSdBUEQhFtIGg3e77xjOe5xfgtNLh5k+kobqjrXwyAbeHPTmyw7t6wUa1k0aTk6/vngI+Y0zABAMqghtR0DQ35h7VtPFCmgAUibv8DyOHz7NquA5lR8Jj1n7SL6epfTotea8O3R9y3nP272MUu6LsHN1q2EnpXwsBSppSYqKor+/ftz4MABqlevXmievLw8/vzzT6ZMmUJcXByjb4mQS9KMGTP46quvSEhIoE6dOnz33Xc0atTogdxLEAShvHDt1RPJxob4sWMBGLN/PmNtHDmy/xlq11dzLmsPH+36CIPJQK+IXncpreQZs7NBpUJpa2uVbtLpiN+7i8NGN/65rMN92U9citxClr0CtU7Di2G/8nLzcFzsit5iYsrNJXf/fsuxyvPmruZrTiTw1qLD5OqMhHk68PPL9fn5zBQMJvP07dntZtPMX/Q63E3v2btQKiQWvNqkwLnn5+zGaJJZNKhpIVc+WJJchMUMUlJS8PDwKHKhxc1fVIsWLaJfv37MmjWLxo0bM2XKFP744w/OnDmDt3cRmiMzM3FxcSEjIwNnZ+cSr58gCEJpy9qwgctDb04/7vz0l5gkiXr113MudwMAHzX76KEu+f/Lz6OZpluNg1YiMs+NDIUWG5MGT503CfpojobqkSWJWjEmon0lcq5veTCu3vs8V6t3se6VtX49l98YZj6QJDxefRXvkW9hNMlM33ieb9efRuO5CS+PJOoEunI4+QBZuiwAPGw9WN9zPSqFmENzN8/P2c3OCyk0q+xhFdjcLv1+FfX7u0hBTVnRuHFjGjZsyPTp0wEwmUwEBQUxbNgwxowZc9frRVAjCMKjIPXnn7k26XMATnbtxyipFkgmKlfbSKK0AaWk5OvHv6axX2Mc1A4opJKbM2Iyyfy6/FeWXpyCp9aBfDmfYwH5d7/wFi6yHR88/jHtwzoU67q8w4eJfa6P5ThwxnSc2rQhPiOPtxYdZnd0Ig6Vv0WhSbG6ztXGlQE1BvByzZfFoOBieH7ObsJWLiDQw5HXf5pYIKBJmjkTjCa8ht3/Gj8PNKi5evUq27dvJzExEZPJZHVu+PDhxa9tEeh0Ouzt7VmyZAndunWzpPfv35/09HRWrFhR4BqtVotWq7UcZ2ZmEhQUJIIaQRAqvIsvvUTurt0ApLR5itdcWpJrknAPWYre/mbXjLe9N6/Veo1KrpXwdfAlyCnovu578vAGeh8ZUSDdJ1mDfWoARvskVDk+2CpUKB0zcbV35bHaT7Pw3PfEaDLoF9aLQU3exFlTtM9oQ0oK8ePeJ3f/fkzZ2ZZ0v88+w7XHM/x7LJ6xy4+RnqvFIfAPFE6HAKjuUZ1Wga0Idg6mdVBr7NX2t7uFUIiZh2eyP2E/0u5MRi88wS/V2vN7tXY0q+xBy0aH2bF/OVV2XWZIvaF4XV8F+34UNagpdhvbvHnzGDRoEBqNBg8PD6uoVpKkBxbUJCcnYzQa8fGxXmvBx8eH06dPF3rNpEmT+Oj68teCIAiPkoBvvuFcs+YAeGxYyRL7jezxr8lXhk6YgmQ0roeQMZGYm8inez61unZU/VEMqDngnu4bWecJqq9y5WRgOo55EjUyGmHvFE5Q9bYEeXgR6ulANV8nXO01Vtc936pvse8V/8EHpP+xxCpN6eVJyE8/keodyDu/7GftyXiUdhdxr7oKvdK8eeXoBqPpX6P/PT0/wUwhKdh3bR+EwftPV+XTFWsACOlTjRmHZ4AKoho3xuvV+w9oiqPYLTVBQUEMHjyYsWPHolA8vGVurl69SkBAADt37qRp05uDj9555x22bNnCnj17ClwjWmoEQXiUaWNiSPhwAvlnzmDKMM8muhpSjeE1+pKj0VDJy4ZWDWM4nrGRU6mnrK4NdQ7l544/425757VgCqPT5REXe4zKVUtmEkf+mbMYEuJxaNoUSaNB1uuJf/99Mlb8ZZXP95OPse/chd8OXOXbbWvR2x1C7XwUSWVuwXHSOPFe4/d4qtJTJVKvR92sI7PMAQxQ9WQl6iafY3FL81YVL+kaMvLVklsf6YF1P3l4eLB3714qV65835UsjnvpfvovMaZGEIRHkWwykbtnD5eHvoEpNxeA/UG1mV6tM9ccPOhQw5cR7YJYcGE6y88vt7p24mMT6VK5S2lUG318PDE9e2FMTrakKRwdrbqZ7OrWJeT3BcgyrDoWz+cbNpNquxiVwwVLHhulDR1COzCywch7CtKEwj0/Zzf7MxZj47XOKv3ZbfDhD8dK9F5F/f4udlPLK6+8wh9//HFflbsXGo2G+vXrs2HDBkuayWRiw4YNVi03giAIgjVJocChaVMCpnwL11vYG8QdZd66SXhoM1l9IoGu3x3AlNSTf7vuoUd4D8u1721/j3e3vkuGNuOh1FU2mcg/fZprX35F9NPdrAIawCqgsYmMxG/aNFYfT6DrjO0MW7SbDNdvUTlcQCmp6VKpCzPazGDX87v49LFPRUBTgm4MCm7g0stqgUKVAXptN/D9y++VSr2K3VJjNBp56qmnyMvLo1atWqjV1msHTJ48uUQreKtFixbRv39/Zs+eTaNGjZgyZQqLFy/m9OnTBcbaFEa01AiC8Kgz6XSk/jSXpClTzAkKBXvrPMGE4CeRJQVqpcQzUQEEhhzlfye/tFxnq7Rlc+/NOKgdSqwusiyjPXuWrDVr0Z4/jy4mBm1MDBgMljzqwEC8334bpzZPoI2OxpicjDogAL2PH8sOXeWH7TFcTDG3Pjl6b0fyWAnAqu6rCHYOLrG6PmqSvpsOSkWhg3yTZs5kyd6LbGvenZaNDlu6oG5oFBPB6IUn8Bw+rEQGCcMDHCg8adIk1qxZQ0REBECBgcIPUu/evUlKSmL8+PEkJCRQt25dVq9eXaSARhAEQQCFRoP7SwMwpKSQu3cv2jNnaHRoPX/pk5kf2Z4dqSaOrolhp8YO96gnSVWvBSDfmE+TBU34tPmnPF3l6RKpS9KUqaTMnl0gXVKrcWzdGqf2T+Lcrh2Sxjyo2CY8nH1qT5bsi2PV0VPk6IwAuNqrebFxEPMSzEt7OKgdREBzv5QKkqd9B2AVmCTNnEnytO94dvgwpFsCmpd0DbFv1IgZh2ewN+wM/45qSsdvCl7/oBW7pcbNzY1vv/2WAQMGPKAqPTiipUYQBMFaxooVXB0zFgr5KtgUGMXM2t0geDOS2zZL+tC6QxlYa+B9LVKXtXETl69/2Uk2NniPGonSwwP7qChUXl5I13sBDEYT+2LTWH/qGmtPJhCXmmcpI9TDnpeah/Fs/QC+PzqVn0/+jEpSsfW5rThpnO65boLZjQDmRovLrcdLmyusApobg4JvHTz8kq4hL+bXK9vr1Pj6+rJt2zbCw8Pvu5IPmwhqBEEQCsratIkrI0ch55kDBsnOzvIYINnWmb/ruvNv68tW19krHHCxdaE/jekW2gWHhg2LdD9jdjZnG9zMG3HoIAo7OwDydEZOJWSyLyaVPTHJ7I9NJzPfgKTMRuV0Eo0hjM7VoujZIIhqfmqOJB9hc9xmFp0x7zvYwKcBczvMvZ+XQ7jFjUBGUquR9XpLgHNjnZpGfo0YXGew1TWzjsxib8JeGvg0YEjdh9v9VOygZtKkScTHxzNt2rT7ruTDJoIaQRCEwhnT00GS0F+9iiY0lIyVK0n88itMWVmWPHGeMOrV27fOOObJVMpwYeT8VDTVG2Dz5WRcXJ1QKiQUkoRCgszde8gZ8hoABk9vToz5mlilExdTcjiTkEVMShao0lA5ncTGezWSZCxwH297b5AhMS/RKl0pKVnTYw0+DmJIQkk6Xas2sl6PpFZT7djRUqnDAwtqunfvzsaNG/Hw8KBGjRoFBgovW1Z2d4EVQY0gCELRyQYDpuxssrdtQxcTS96RI+QZjOzLOoZdVg4uOXCgisTilgp0ausxlS45Mi2PyfhdCiYgK4PL3lr2RBrR2hqod95ElavwR0QzDvlUBoUelX00kiobhSYJhSa1yHW0Udpgp7LD1caV+Z3nF3klYqFobtdS87A9sIHCrq6uPPPMw9sITRAEQSgdkkqF0tUVly7W69SE63ToL15E5e1Nvex8aqYmcuL4Vk5e/JMDfgkAZDhI/N1EgiaX/1sqZwKV1x/vwY6CC6cCBDgG0CmsE9Xcq3E69TTdw7sT6BjIuovr2H5lO8vPL6dX1V6MbDCyRGdkCTfdbkwNPNzBv8VRrja0vF+ipUYQBOHBMckmTqWewkXjwoFD//LDmXnEajIt52sqgqgh+bNGeRqdSY+TxglnG2fsVfbU8qxFgGMABpOBNiFtCHQMFJtLlqL/BjR3S3/QKuQu3fdLBDWCIAgP14FrB4jNiOXJ0CdxVDuKQKWcuNs6NSW1+3ZRlWhQ06FDByZMmECTJk3umC8rK4uZM2fi6OjI0KFDi1/rB0wENYIgCIJQ/pTomJqePXvSo0cPXFxc6NKlCw0aNMDf3x9bW1vS0tI4efIk27dv559//qFz58589dVXJfZEBEEQBEEQiqLI3U9arZY//viDRYsWsX37djKu7/gqSRLVq1enffv2vPLKK0RGRj7QCt8P0VIjCIIgCOXPAx9Tk5GRQV5eHh4eHgWmdZdVIqgRBEEQhPLngU3pvsHFxQUXF5d7vVwQBEEQBKFEKUq7AoIgCIIgCCVBBDWCIAiCIFQIIqgRBEEQBKFCEEGN8P/27j04qvpg4/izG5IAhY0RllsJlyDIK1ZCQ4kXOm8QBKza0guKWF6ClDEmkFFslUgL0haZVgpOYpal1YJl7KBgKWrV1xhEUFu0kUS0DTdLwcTLhuAuL9hk2T3vH5iVmBA2ySYn5+T7mdlxzmU3z55xch5+55dzAACwhRaXmrlz52rXrl3tkQUAAKDVWlxq/H6/pkyZopEjR+rBBx9UZWVle+QCAABokRaXmj//+c+qrKzUnXfeqSeffFLDhg3T9ddfr61btyoYDLZHRgAAgAtq1Zwat9utxYsXq7y8XHv27NEll1yiOXPmaNCgQbr77rt18ODBWOcE0EX4Ch85+8C8prZ5PGcftAcATWjTROEPP/xQxcXFKi4uVlxcnL71rW9p3759uuyyy7R27dpYZQTQlcQ5VV1Q2KjY+DweVRcUSnH8fQOAprX4jsLBYFDPPPOMNmzYoJdeeklXXHGF7rrrLs2ePTty6+Jt27bp9ttv19133x3zwADszZ2TI0lnC8zny/WFpm/eosh2APiyFpeagQMHKhwO69Zbb9Wbb76ptLS0RvtMmjRJF110UQziAeiKzi02x9d5ZQSDFBoAF9TiB1pu2rRJM2fOVPfu3dsrU7vhgZaAtVR87QoZwaAc8fEave8ds+MAMEm05+8WX5yeM2eOJQsNAGvxeTyRQmMEg+edPAwA9ZhxB6DTOXcOzeh976hv3qImJw8DwLlaPKcGANpTU5OCm5o8DABfRqkBYBpPmUdOh1PZY7O/WBkKq2/eIj19jVPhMo9y0hoWG4XCJiQFYAVcfgJgGqfDqaKyInnLvZF17kUL9fQ1Z9c7HQ1/RblzcuRetLCjYwKwCEZqAJimfoSmqKwosuwt96qorEi5abkNR3AA4AIoNQBMdW6x+e07v1UwHKTQAGgVy1x+Wrlypa6++mr17NmTG/sBNpM9NlvxzngFw0HFO+MpNABaxTKlpq6uTjNnztSdd95pdhQAMbC2+IAKSs4+/NZb7o0UmmA4qKxtK7W2+IDJCQFYjWUuP61YsUKStHHjRnODAIiJOKdDa4oP6O3AUyoNbI5ccsratlKlgc2f77XU1IwArMUyIzWtUVtbq0Ag0OAFoHPImzxSmRllKg1sVrprlrLHZqug5KB27klTumuWSgObG/xVFABciGVGalpj1apVkREeAJ3PhOHJ0r9maeeeNI36+wuqC4W1+LpRypt8g7zlfRQ2uCcNgOiZOlKzZMkSORyOZl8VFRWt/vz8/Hz5/f7I69ixYzFMD6CtctJytPG7S5UQ51RdKKyEOKfyJo+UdHbycP2N9wAgGqaO1Nxzzz3Kyspqdp/U1NRWf35iYqISExNb/X4A7a+g5GCk0NSFwiooORgpNgDQEqaWGrfbLbfbbWYEACYqKDmoNcUHPr/kNDKyLIliA6DFLDOn5ujRo6qpqdHRo0cVCoVUVlYmSbrkkkvUq1cvc8MBaLEvFxrpiyJDsQHQGpYpNcuWLdPjjz8eWR43bpwk6ZVXXlFmZqZJqQC0VihsNCg09eqXQ2HDjFgALMxhGEaX+c0RCASUlJQkv98vl8tldhwAABCFaM/ftr5PDQAA6DooNQAAwBYoNQAAwBYoNQAAwBYoNQAAwBYoNQAAdCG+wkfk83ia3ubxyFf4SAcnih1KDQAAXUmcU9UFhY2Kjc/jUXVBoRRn3WpgmZvvAQCAtnPnnH1QbHVBYWS5vtD0zVsU2W5FlBoAALqYc4vN8XVeGcGg5QuNxOUnAAC6JHdOjhzx8TKCQTni4y1faCRKDQAAXZLP44kUGiMYPO/kYSuh1AAA0MWcO4dm9L531DdvUZOTh62GOTUAAHQhTU0KbmrysBVRagAA6EpC4SYnBUeWQ2ETQsWGwzAMw+wQHSXaR5cDAIDOI9rzN3NqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACALVBqAACwsLXFB1RQcrDJbQUlB7W2+EAHJzIPpQYAAAuLczq0poliU1ByUGuKDyjO6TApWcfrZnYAAADQenmTR0qS1nw+IpM3eWSk0Cy+blRke1dgiZGaI0eOaP78+Ro+fLh69OihESNGaPny5aqrqzM7GgAApvCUeeQt90o6W2QWXzdKa4oPaNTSF/TI3nX67wlvd6lCI1mk1FRUVCgcDmv9+vV67733tHbtWnm9Xt1///1mRwMAwBROh1NFZUUNik1CnFNKLlaiu1hXjXCbnLDjWeLy0/Tp0zV9+vTIcmpqqvbv369169Zp9erVJiYDAMAc2WOzJUlFZUWSpLrqyZFCU+u77uxyF2OJUtMUv9+viy++uNl9amtrVVtbG1kOBALtHQsAgA5zbrExwl4lukPKTctVXfXkBnNsugpLlppDhw6psLDwgqM0q1at0ooVKzooFQAAHa+uerKMsFcOZ0jxzvhI0ZHU5YqNqXNqlixZIofD0eyroqKiwXsqKys1ffp0zZw5UwsWLGj28/Pz8+X3+yOvY8eOtefXAQCgw5X6n4oUmmA42GjycChsmJyw4zgMwzDt2/p8Ph0/frzZfVJTU5WQkCBJqqqqUmZmpq688kpt3LhRTmfLOlkgEFBSUpL8fr9cLlercwMA0Bl4y70qKitSblqussdmN1q2i2jP36ZefnK73XK7o5udXVlZqUmTJik9PV0bNmxocaEBAMBOmiowX548bKdiEw1LzKmprKxUZmamhg4dqtWrV8vn80W2DRgwwMRkAACYI2yEmxyRqV8OG2EzYpnK1MtP0dq4caPmzZvX5LaWxOfyEwAA1hPt+dsS13CysrJkGEaTLwAAAMkipQYAAOBCKDUAAMAWKDUAAMAWKDUAAMAWKDUAAMAWKDUAAMAWKDUAAMAWKDUAAMAWKDUAAMAWKDUA0AF8hY/I5/E0vc3jka/wkQ5OBNgPpQYAOkKcU9UFhY2Kjc/jUXVBoRTHr2OgrSzxlG4A6Mw8ZR45Hc5GT0uWJG+5V2EjrJycHEk6W2AkuXNyIoWmb94iuT/fDqD1KDUA0EZOh1NFZUWS1KDYeMu9KiorUm5ariRFikt1QaGOr/PKCAYpNEAMUWoAoI3qi8y5xebcQnNu0XHn5EQKjSM+nkIDxBClBgBi4Nxis65svcI606jQFJQc1LDnN2vk54XGCAbl83goNkCMMDMNAGIke2y2nOqmsM7IqW6NCs2HhUUa+Zc/qm/eIo3e94765i1qcvIwgNah1ABAjHjLvZFCE9YZZW1bKemLQvM/Ff/bYA6NOyeHYgPEEJefACAGvjyHJmvbSpUGNuu/flOjz3zX6pHUZPWd2nhScGQ5FDYhNWAvDsMwDLNDdJRAIKCkpCT5/X65XC6z4wCwifNNCv6v39yjbn1f0pnqqfrnPb8xMSFgbdGev7n8BABtFDbCTU4K/sx3rc5UT1XICKmg5KCJCYGugctPANBGOWkNLykVlBzUmuIDWnzdKOVNviGyLEl5k0eaERHoEig1ABBDDQvN2QJT/1+KDdC+KDUAEEOhsNGg0NSrXw6Fu8w0RqDDMVEYAAB0akwUBgAAXQqlBgAA2AKlBgAA2AKlBgDQKXjKPPKWe5vc5i33ylPGoyTQPP76CQDQKTgdThWVFUn64qnna4sPqPz/tqg0sFm5abkN9i8oOahQ2NDd143q8KzonCg1AIBOob7InFts6gtNumtWozs2198PCKhHqQEAdBrnFpvfvvNbBcNBpbtmaeeeNBW4Dipv8sgmb3AISBaaU/Ptb39bQ4YMUffu3TVw4EDNmTNHVVVVZscCAMRY9thsxTvjFQwHFe+M18bvLtXi60ZpTfEBjVr6AoUG52WZUjNp0iQ99dRT2r9/v55++mkdPnxYP/jBD8yOBQCIMW+5N1JoguGgvOVe5U0eqYQ4p+pCYSXEOSk0aJJl7yj8zDPPaMaMGaqtrVV8fHyT+9TW1qq2tjayHAgElJKSwh2FAaCT8pZ7VVRWFHnqef1y/SWo+mLDSE3XYus7CtfU1OiJJ57Q1Vdffd5CI0mrVq1SUlJS5JWSktKBKQEALfHlQiOdvRSV7pql0sBmZWaU6cDK6yOXogpKDpqcGJ2NpUrNfffdp6985Svq06ePjh49qu3btze7f35+vvx+f+R17NixDkoKAGipsBFuUGiks3/ltHNPmtJdszRheLKksw8HpdigKaZeflqyZIl+9atfNbvPP//5T40ePVqSVF1drZqaGv373//WihUrlJSUpOeee04OhyOqn8cDLQHAWtYWH1Cc09HkpSbuU9N1RHv+NrXU+Hw+HT9+vNl9UlNTlZCQ0Gj9Bx98oJSUFL3xxhu66qqrovp5lBoAAKwn2vO3qfepcbvdcrvdrXpvOByWpAYTgQEAQNdliZvv7dmzR2+99ZYmTpyo5ORkHT58WD/72c80YsSIqEdpAACAvVlionDPnj31pz/9SZMnT9all16q+fPn64orrtCrr76qxMREs+MBAIBOwBIjNV/72te0Y8cOs2MAAIBOzBIjNQAAABdCqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAALZAqQEAmMJX+Ih8Hk/T2zwe+Qof6eBEsDpKDQDAHHFOVRcUNio2Po9H1QWFUhynKLRMN7MDAAC6JndOjiSdLTCfL9cXmr55iyLbgWhRagAApjm32Bxf55URDFJo0GqM7QEATOXOyZEjPl5GMChHfDyFBq1GqQEAmMrn8UQKjREMnnfyMHAhlBoAgGnOnUMzet876pu3qMnJw0A0mFMDADBFU5OCm5o8DESLUgMAMEco3OSk4MhyKGxCKFiZwzAMw+wQHSUQCCgpKUl+v18ul8vsOAAAIArRnr+ZUwMAAGyBUgMAAGyBUgMAAGyBUgMAAGzBcqWmtrZWaWlpcjgcKisrMzsOAADoJCxXau69914NGjTI7BgAAKCTsVSpeeGFF/TSSy9p9erVUe1fW1urQCDQ4AUAAOzJMqXm448/1oIFC7Rp0yb17NkzqvesWrVKSUlJkVdKSko7pwQAAGaxRKkxDENZWVnKzs7W+PHjo35ffn6+/H5/5HXs2LF2TAkAAMxkaqlZsmSJHA5Hs6+KigoVFhbq5MmTys/Pb9HnJyYmyuVyNXgBAAB7MvUxCT6fT8ePH292n9TUVN1888169tln5XA4IutDoZDi4uJ022236fHHH4/q5/GYBAAArCfa87clnv109OjRBpN8q6qqNG3aNG3dulUZGRkaPHhwVJ9DqQEAwHqiPX9b4indQ4YMabDcq1cvSdKIESOiLjQAAMDeLDFRGAAA4EIsMVLzZcOGDZMFrpoBAIAOxEgNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwBUoNAACwhW5mB+hIhmFIkgKBgMlJAABAtOrP2/Xn8fPpUqXm5MmTkqSUlBSTkwAAgJY6efKkkpKSzrvdYVyo9thIOBxWVVWVevfuLYfD0erPCQQCSklJ0bFjx+RyuWKYsGvhOMYGxzF2OJaxwXGMDY7jFwzD0MmTJzVo0CA5neefOdOlRmqcTqcGDx4cs89zuVxd/n+0WOA4xgbHMXY4lrHBcYwNjuNZzY3Q1GOiMAAAsAVKDQAAsAVKTSskJiZq+fLlSkxMNDuKpXEcY4PjGDscy9jgOMYGx7HlutREYQAAYF+M1AAAAFug1AAAAFug1AAAAFug1AAAAFug1LTRgQMH9J3vfEd9+/aVy+XSxIkT9corr5gdy5L+8pe/KCMjQz169FBycrJmzJhhdiRLq62tVVpamhwOh8rKysyOYylHjhzR/PnzNXz4cPXo0UMjRozQ8uXLVVdXZ3Y0SygqKtKwYcPUvXt3ZWRk6M033zQ7kqWsWrVK3/jGN9S7d2/169dPM2bM0P79+82OZQmUmja68cYbdebMGe3YsUOlpaUaO3asbrzxRn300UdmR7OUp59+WnPmzNG8efNUXl6u119/XbNnzzY7lqXde++9GjRokNkxLKmiokLhcFjr16/Xe++9p7Vr18rr9er+++83O1qn9+STT2rx4sVavny53n77bY0dO1bTpk3TJ598YnY0y3j11VeVm5urv/3tbyouLlYwGNTUqVN16tQps6N1fgZazefzGZKMXbt2RdYFAgFDklFcXGxiMmsJBoPGV7/6VePRRx81O4ptPP/888bo0aON9957z5Bk7N271+xIlvfrX//aGD58uNkxOr0JEyYYubm5keVQKGQMGjTIWLVqlYmprO2TTz4xJBmvvvqq2VE6PUZq2qBPnz669NJL9Yc//EGnTp3SmTNntH79evXr10/p6elmx7OMt99+W5WVlXI6nRo3bpwGDhyo66+/Xu+++67Z0Szp448/1oIFC7Rp0yb17NnT7Di24ff7dfHFF5sdo1Orq6tTaWmppkyZElnndDo1ZcoU/fWvfzUxmbX5/X5J4v+/KFBq2sDhcOjll1/W3r171bt3b3Xv3l1r1qzRiy++qOTkZLPjWcb7778vSXrggQf005/+VM8995ySk5OVmZmpmpoak9NZi2EYysrKUnZ2tsaPH292HNs4dOiQCgsLdccdd5gdpVOrrq5WKBRS//79G6zv378/l+RbKRwO66677tI111yjyy+/3Ow4nR6lpglLliyRw+Fo9lVRUSHDMJSbm6t+/fpp9+7devPNNzVjxgzddNNN+vDDD83+GqaL9jiGw2FJ0tKlS/X9739f6enp2rBhgxwOh7Zs2WLyt+gcoj2WhYWFOnnypPLz882O3ClFexzPVVlZqenTp2vmzJlasGCBScnRVeXm5urdd9/V5s2bzY5iCTwmoQk+n0/Hjx9vdp/U1FTt3r1bU6dO1YkTJxo8Fn7kyJGaP3++lixZ0t5RO7Voj+Prr7+ua6+9Vrt379bEiRMj2zIyMjRlyhStXLmyvaN2etEey5tvvlnPPvusHA5HZH0oFFJcXJxuu+02Pf744+0dtVOL9jgmJCRIkqqqqpSZmakrr7xSGzdulNPJvwObU1dXp549e2rr1q0N/npx7ty5+vTTT7V9+3bzwlnQwoULtX37du3atUvDhw83O44ldDM7QGfkdrvldrsvuN/p06clqdEvOqfTGRl96MqiPY7p6elKTEzU/v37I6UmGAzqyJEjGjp0aHvHtIRoj2VBQYF++ctfRparqqo0bdo0Pfnkk8rIyGjPiJYQ7XGUzo7QTJo0KTJySKG5sISEBKWnp6ukpCRSasLhsEpKSrRw4UJzw1mIYRhatGiRtm3bpp07d1JoWoBS0wZXXXWVkpOTNXfuXC1btkw9evTQ7373O/3rX//SDTfcYHY8y3C5XMrOztby5cuVkpKioUOH6qGHHpIkzZw50+R01jJkyJAGy7169ZIkjRgxQoMHDzYjkiVVVlYqMzNTQ4cO1erVq+Xz+SLbBgwYYGKyzm/x4sWaO3euxo8frwkTJujhhx/WqVOnNG/ePLOjWUZubq7++Mc/avv27erdu3dkPlJSUpJ69OhhcrrOjVLTBn379tWLL76opUuX6tprr1UwGNSYMWO0fft2jR071ux4lvLQQw+pW7dumjNnjj777DNlZGRox44dTLiGKYqLi3Xo0CEdOnSoURnkin3zbrnlFvl8Pi1btkwfffSR0tLS9OKLLzaaPIzzW7dunSQpMzOzwfoNGzYoKyur4wNZCHNqAACALXCRGAAA2AKlBgAA2AKlBgAA2AKlBgAA2AKlBgAA2AKlBgAA2AKlBgAA2AKlBgAA2AKlBoBlPfbYY5o6dWqbPqO6ulr9+vXTBx98EKNUAMzCHYUBWNJ//vMfpaamasuWLbrmmmva9Fk//vGPdeLECT322GMxSgfADIzUALCkrVu3yuVytbnQSNK8efP0xBNPqKamJgbJAJiFUgPAVD6fTwMGDNCDDz4YWffGG28oISFBJSUl533f5s2bddNNNzVYl5WVpRkzZujBBx9U//79ddFFF+nnP/+5zpw5o5/85Ce6+OKLNXjwYG3YsKHB+8aMGaNBgwZp27Ztsf1yADoUpQaAqdxut37/+9/rgQce0N///nedPHlSc+bM0cKFCzV58uTzvu+1117T+PHjG63fsWOHqqqqtGvXLq1Zs0bLly/XjTfeqOTkZO3Zs0fZ2dm64447Gs2hmTBhgnbv3h3z7weg4zCnBkCnkJubq5dfflnjx4/Xvn379NZbbykxMbHJfT/99FMlJydr165d+uY3vxlZn5WVpZ07d+r999+X03n232yjR49Wv379tGvXLklSKBRSUlKSHn30Uc2aNSvy3sWLF2vv3r165ZVX2vFbAmhP3cwOAACStHr1al1++eXasmWLSktLz1toJOmzzz6TJHXv3r3RtjFjxkQKjST1799fl19+eWQ5Li5Offr00SeffNLgfT169NDp06fb+jUAmIjLTwA6hcOHD6uqqkrhcFhHjhxpdt8+ffrI4XDoxIkTjbbFx8c3WHY4HE2uC4fDDdbV1NTI7Xa3LjyAToFSA8B0dXV1+uEPf6hbbrlFv/jFL/SjH/2o0UjKuRISEnTZZZfpH//4R8wyvPvuuxo3blzMPg9Ax6PUADDd0qVL5ff7VVBQoPvuu0+jRo3S7bff3ux7pk2bptdeey0mP//06dMqLS1t8438AJiLUgPAVDt37tTDDz+sTZs2yeVyyel0atOmTdq9e7fWrVt33vfNnz9fzz//vPx+f5szbN++XUOGDGkw6RiA9fDXTwAsa+bMmfr617+u/Pz8Nn3OlVdeqby8PM2ePTtGyQCYgZEaAJb10EMPqVevXm36jOrqan3ve9/TrbfeGqNUAMzCSA0AALAFRmoAAIAtUGoAAIAtUGoAAIAtUGoAAIAtUGoAAIAtUGoAAIAtUGoAAIAtUGoAAIAtUGoAAIAt/D/Pn3wNdkux3wAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Extract estimates\n", + "poses_results_list: typing.List[nav.types.StateWithCovariance] = []\n", + "for pose in init_pose_est:\n", + " state = variables_opt[pose.state_id]\n", + " if compute_covariance:\n", + " # Extract the covariance for only this current pose state\n", + " cov = problem.get_covariance_block(pose.state_id, pose.state_id)\n", + " else:\n", + " cov = np.identity(3)\n", + " poses_results_list.append(nav.types.StateWithCovariance(state, cov))\n", + " \n", + "landmarks_results_list: typing.List[nav.types.StateWithCovariance] = []\n", + "for landmark in init_landmark_est:\n", + " state = variables_opt[landmark.state_id]\n", + " if compute_covariance:\n", + " cov = problem.get_covariance_block(landmark.state_id, landmark.state_id)\n", + " else:\n", + " cov = np.identity(2) \n", + " landmarks_results_list.append(nav.types.StateWithCovariance(state, cov))\n", + "\n", + "# Postprocess the results and plot\n", + "gaussian_result_list = nav.GaussianResultList(\n", + " [nav.GaussianResult(poses_results_list[i], gt_poses[i]) for i in range(len(poses_results_list))],\n", + ")\n", + "\n", + "# Plot NEES \n", + "fig, axs = nav.plot_nees(gaussian_result_list)\n", + "axs.set_xlabel(\"Time (s)\")\n", + "axs.set_title(\"NEES\")\n", + "\n", + "fig, axs = nav.plot_error(gaussian_result_list)\n", + "axs[0].set_title(\"Estimation Errors\")\n", + "axs[0].set_ylabel(\"theta (rad)\")\n", + "axs[1].set_ylabel(\"x (m)\")\n", + "axs[2].set_ylabel(\"y (m)\")\n", + "axs[2].set_xlabel(\"Time (s)\")\n", + "plt.show()\n", + "\n", + "# Plot the initial estimate, optimized estimates, and groundtruth\n", + "opt_poses: typing.List[nav.lib.SE2State] = [state.state for state in poses_results_list]\n", + "fig, ax = nav.plot_poses(gt_poses, step = None, line_color='tab:blue', label=\"Groundtruth\")\n", + "fig, ax = nav.plot_poses(init_pose_est, step=None, ax=ax, line_color='tab:red', label=\"Initial Estimate\")\n", + "fig, ax = nav.plot_poses(opt_poses, step=None, ax=ax, line_color='tab:green', label=\"Optimized Estimate\")\n", + "\n", + "opt_landmarks: typing.List[nav.lib.VectorState] = [state.state for state in landmarks_results_list]\n", + "for landmark in landmarks:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'tab:blue', marker='x')\n", + "for landmark in init_landmark_est:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'tab:red', marker='x')\n", + "for landmark in opt_landmarks:\n", + " ax.plot(landmark.value[0], landmark.value[1], 'tab:green', marker='x')\n", + "ax.set_xlabel(\"x (m)\")\n", + "ax.set_ylabel(\"y (m)\")\n", + "ax.legend()\n", + "\n", + "# Visualize the sparsity pattern of the information matrix\n", + "fig, ax = plt.subplots()\n", + "ax.set_title(\"Sparsity pattern of the information matrix\")\n", + "ax.spy(opt_results[\"info_matrix\"])\n", + "plt.show()\n" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "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.11" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/navlie/lib/models.py b/navlie/lib/models.py index 540c3b11..c624c967 100644 --- a/navlie/lib/models.py +++ b/navlie/lib/models.py @@ -524,11 +524,6 @@ def __init__( def evaluate(self, x: CompositeState) -> np.ndarray: """Evaluates the measurement model for the landmark state.""" - - # The pose is always assumed to be the first element - # TODO: is there a better way to do this? The - # Measurement class already hold on to the IDs of these two - # states pose: MatrixLieGroupState = x.get_state_by_id(self._pose_state_id) landmark: VectorState = x.get_state_by_id(self._landmark_state_id)