diff --git a/crocoddyl/__init__.py b/crocoddyl/__init__.py
index b92d7b7180e827dd9f96638148624a6b095e66e1..97432b70bab52f2185554e4756046d69f2988b5c 100644
--- a/crocoddyl/__init__.py
+++ b/crocoddyl/__init__.py
@@ -1,7 +1,7 @@
 from .action import (ActionDataAbstract, ActionDataLQR, ActionDataNumDiff, ActionModelAbstract, ActionModelLQR,
                      ActionModelNumDiff)
-from .activation import (ActivationDataInequality, ActivationDataQuad, ActivationDataSmoothAbs,
-                         ActivationDataWeightedQuad, ActivationModelInequality, ActivationModelQuad,
+from .activation import (ActivationDataInequality, ActivationDataInequalityCont, ActivationDataQuad, ActivationDataSmoothAbs,
+                         ActivationDataWeightedQuad, ActivationModelInequality, ActivationModelInequalityCont, ActivationModelQuad,
                          ActivationModelSmoothAbs, ActivationModelWeightedQuad)
 from .actuation import (ActuationDataFreeFloating, ActuationDataFull, ActuationDataUAM, ActuationDataDoublePendulum,
                         ActuationModelFreeFloating, ActuationModelFull, ActuationModelUAM, ActuationModelDoublePendulum)
diff --git a/crocoddyl/activation.py b/crocoddyl/activation.py
index 80891b63c0970417b87d7b5cd2226c1ce8ee62b6..d7aeecac576aa9c3ad3e6e2112307af25f056dc8 100644
--- a/crocoddyl/activation.py
+++ b/crocoddyl/activation.py
@@ -8,6 +8,7 @@ class ActivationModelAbstract:
     the activation value and its derivatives from it. Activation value and
     its derivatives are computed by calc() and calcDiff(), respectively.
     """
+
     def __init__(self):
         self.ActivationDataType = ActivationDataAbstract
 
@@ -78,6 +79,7 @@ class ActivationModelInequality(ActivationModelAbstract):
     a(r) = (r**2)/2 for r<b_l.
     a(r) = 0. for b_l<=r<=b_u
     """
+
     def __init__(self, lowerLimit, upperLimit, beta=None):
         assert ((lowerLimit <= upperLimit).all())
         assert (not np.any(np.isinf(lowerLimit)) and not np.any(np.isinf(upperLimit)) or beta is None)
@@ -95,6 +97,7 @@ class ActivationModelInequality(ActivationModelAbstract):
 
     def calc(self, data, r):
         '''Return [ a(r_1) ... a(r_n) ] '''
+        # return np.minimum(r - self.lower, 0)**2 / 2 + np.maximum(r - self.upper, 0)**2 / 2
         return np.minimum(r - self.lower, 0)**2 / 2 + np.maximum(r - self.upper, 0)**2 / 2
 
     def calcDiff(self, data, r, recalc=True):
@@ -115,6 +118,45 @@ class ActivationDataInequality(ActivationDataAbstract):
         pass
 
 
+class ActivationModelInequalityCont(ActivationModelAbstract):
+
+    def __init__(self, lowerLimit, upperLimit, beta=None):
+        assert ((lowerLimit <= upperLimit).all())
+        assert (not np.any(np.isinf(lowerLimit)) and not np.any(np.isinf(upperLimit)) or beta is None)
+        self.ActivationDataType = ActivationDataInequalityCont
+
+        if beta is None:
+            self.beta = 0
+            self.lower = lowerLimit
+            self.upper = upperLimit
+        else:
+            assert (beta > 0 and beta <= 1)
+            self.beta = beta
+
+        self.m = (lowerLimit + upperLimit) / 2
+        self.d = (upperLimit - lowerLimit) / 2
+        self.lower = self.m - self.beta * self.d
+        self.upper = self.m + self.beta * self.d
+
+    def calc(self, data, r):
+        '''Return [ a(r_1) ... a(r_n) ] '''
+        return ((r - self.m) / self.d)**6
+
+    def calcDiff(self, data, r, recalc=True):
+        if recalc:
+            self.calc(data, r)
+
+        return 6 * ((r - self.m) / self.d)**5, (30 * ((r - self.m) / self.d)**4)[:, None]
+
+    def createData(self):
+        return ActivationDataInequalityCont(self)
+
+
+class ActivationDataInequalityCont(ActivationDataAbstract):
+    def __init__(self, model):
+        pass
+
+
 class ActivationModelWeightedQuad(ActivationModelAbstract):
     def __init__(self, weights):
         self.weights = weights
diff --git a/crocoddyl/cost.py b/crocoddyl/cost.py
index 08bbd7b6f796555e219499ffd3263b9189ef7b55..9212e8de56f2541f95aa507f60d094a58201e06e 100644
--- a/crocoddyl/cost.py
+++ b/crocoddyl/cost.py
@@ -320,6 +320,7 @@ class CostModelFrameVelocityLinear(CostModelPinocchio):
     end-effector. It assumes that updateFramePlacement and computeForwardKinematicsDerivatives
     have been runned.
     """
+
     def __init__(self, pinocchioModel, frame, ref=None, nu=None, activation=None):
         self.CostDataType = CostDataFrameVelocityLinear
         CostModelPinocchio.__init__(self, pinocchioModel, ncost=3)
diff --git a/examples/notebooks/kinton/hector_flying_mission.ipynb b/examples/notebooks/kinton/hector_flying_mission.ipynb
deleted file mode 100644
index c7aeb3d021d837632f0cb4e080ee3ab9f2c9b576..0000000000000000000000000000000000000000
--- a/examples/notebooks/kinton/hector_flying_mission.ipynb
+++ /dev/null
@@ -1,252 +0,0 @@
-{
- "cells": [
-  {
-   "cell_type": "code",
-   "execution_count": 5,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "from crocoddyl import *\n",
-    "import pinocchio as pin\n",
-    "import numpy as np\n",
-    "from crocoddyl.diagnostic import displayTrajectory"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": 10,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "# LOAD ROBOT\n",
-    "robot = loadHector()\n",
-    "robot.initViewer(loadModel=True)\n",
-    "robot.display(robot.q0)\n",
-    "\n",
-    "robot.framesForwardKinematics(robot.q0)\n",
-    "\n",
-    "rmodel = robot.model"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": 11,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "def uavPlacementModel(targetPos, targetQuat, integrationStep, frameName):\n",
-    "    # ACTUATION MODEL\n",
-    "    distanceRotorCOG = 0.1525\n",
-    "    cf = 6.6e-5\n",
-    "    cm = 1e-6\n",
-    "    actModel = ActuationModelUAM(robot.model, '+', distanceRotorCOG, cf, cm)\n",
-    "\n",
-    "    # COST MODEL\n",
-    "    # Create a cost model per the running and terminal action model.\n",
-    "    runningCostModel = CostModelSum(rmodel, actModel.nu)\n",
-    "    terminalCostModel = CostModelSum(rmodel, actModel.nu)\n",
-    "\n",
-    "    state = StatePinocchio(rmodel)\n",
-    "    SE3ref = pin.SE3()\n",
-    "    SE3ref.translation = targetPos.reshape(3,1)\n",
-    "    SE3ref.rotation = targetQuat.matrix()\n",
-    "\n",
-    "    wBasePos  = [1]\n",
-    "    wBaseOri  = [1]\n",
-    "    wBaseVel  = [10]\n",
-    "    \n",
-    "    stateWeights   = np.array(wBasePos * 3 + wBaseOri * 3 + BaseVel * robot.model.nv)\n",
-    "    controlWeights = np.array([0.1]*4)\n",
-    "    \n",
-    "    goalTrackingCost = CostModelFramePlacement(rmodel,\n",
-    "                                               frame=rmodel.getFrameId(frameName),\n",
-    "                                               ref=SE3ref,\n",
-    "                                               nu =actModel.nu)\n",
-    "    xRegCost = CostModelState(rmodel, \n",
-    "                              state, \n",
-    "                              ref=state.zero(), \n",
-    "                              nu=actModel.nu,\n",
-    "                              activation=ActivationModelWeightedQuad(stateWeights))\n",
-    "    uRegCost = CostModelControl(rmodel, \n",
-    "                                nu=robot.\n",
-    "                                model.nv-2,\n",
-    "                                activation = ActivationModelWeightedQuad(controlWeights))\n",
-    "    uLimCost = CostModelControl(rmodel, \n",
-    "                                nu=robot.\n",
-    "                                model.nv-2,\n",
-    "                                activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1, -1, -1, -1, -1, -1, -1]), \n",
-    "                                                                    np.array([5, 5, 5, 5, 1, 1, 1, 1, 1, 1])))\n",
-    "\n",
-    "    # Then let's add the running and terminal cost functions\n",
-    "    runningCostModel.addCost(name=\"pos\", weight=1, cost=goalTrackingCost)\n",
-    "    runningCostModel.addCost(name=\"regx\", weight=1e-6, cost=xRegCost)\n",
-    "    runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n",
-    "    # runningCostModel.addCost(name=\"limu\", weight=1e-3, cost=uLimCost)\n",
-    "    terminalCostModel.addCost(name=\"pos\", weight=1e3, cost=goalTrackingCost)\n",
-    "\n",
-    "    # DIFFERENTIAL ACTION MODEL\n",
-    "    runningDmodel  = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n",
-    "    terminalDmodel = DifferentialActionModelActuated(rmodel, actModel, terminalCostModel)\n",
-    "    runningModel  = IntegratedActionModelEuler(runningDmodel)\n",
-    "    terminalModel = IntegratedActionModelEuler(terminalDmodel) \n",
-    "    runningModel.timeStep =  integrationStep\n",
-    "    terminalModel.timeStep =  integrationStep\n",
-    "    \n",
-    "    return runningModel, terminalModel   "
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": 12,
-   "metadata": {
-    "scrolled": true
-   },
-   "outputs": [],
-   "source": [
-    "# DEFINING THE SHOOTING PROBLEM & SOLVING\n",
-    "\n",
-    "# Defining the time duration for running action models and the terminal one\n",
-    "dt = 5e-2\n",
-    "\n",
-    "# For this optimal control problem, we define 250 knots (or running action\n",
-    "# models) plus a terminal knot\n",
-    "T = 25\n",
-    "\n",
-    "\n",
-    "# DEFINE POSITION WAYPOINTS\n",
-    "target_pos = [np.array([0,0,1])]\n",
-    "target_pos += [np.array([0,1,1])]\n",
-    "quat = pin.Quaternion(1, 0, 0, 0)\n",
-    "quat.normalize()\n",
-    "target_quat = [quat]*2\n",
-    "\n",
-    "# Plot goal frame\n",
-    "for i in range(0,len(target_pos)):\n",
-    "    robot.viewer.gui.addXYZaxis('world/wp%i' % i, [1., 0., 0., 1.], .03, 0.5)\n",
-    "    robot.viewer.gui.applyConfiguration('world/wp%i' % i, \n",
-    "                                        target_pos[i].tolist() + [target_quat[i][0], target_quat[i][1], target_quat[i][2], target_quat[i][3]])\n",
-    "    \n",
-    "robot.viewer.gui.refresh()"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": 13,
-   "metadata": {
-    "scrolled": true
-   },
-   "outputs": [
-    {
-     "ename": "NameError",
-     "evalue": "global name 'BaseVel' is not defined",
-     "output_type": "error",
-     "traceback": [
-      "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m",
-      "\u001b[0;31mNameError\u001b[0m                                 Traceback (most recent call last)",
-      "\u001b[0;32m<ipython-input-13-7c8226739a42>\u001b[0m in \u001b[0;36m<module>\u001b[0;34m()\u001b[0m\n\u001b[1;32m      1\u001b[0m \u001b[0mmodels\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m      2\u001b[0m \u001b[0;32mfor\u001b[0m \u001b[0mi\u001b[0m \u001b[0;32min\u001b[0m \u001b[0mrange\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;36m0\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mlen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mtarget_pos\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m----> 3\u001b[0;31m     \u001b[0mrunningModel\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mterminalModel\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0muavPlacementModel\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mtarget_pos\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mi\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mtarget_quat\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0mi\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mdt\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m'base_link'\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m      4\u001b[0m     \u001b[0mmodels\u001b[0m \u001b[0;34m+=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mrunningModel\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mT\u001b[0m\u001b[0;34m-\u001b[0m\u001b[0;36m1\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0mterminalModel\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m      5\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;32m<ipython-input-11-8b96bca807aa>\u001b[0m in \u001b[0;36muavPlacementModel\u001b[0;34m(targetPos, targetQuat, integrationStep, frameName)\u001b[0m\n\u001b[1;32m     20\u001b[0m     \u001b[0mwBaseVel\u001b[0m  \u001b[0;34m=\u001b[0m \u001b[0;34m[\u001b[0m\u001b[0;36m10\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     21\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m---> 22\u001b[0;31m     \u001b[0mstateWeights\u001b[0m   \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0marray\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mwBasePos\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0;36m3\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0mwBaseOri\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0;36m3\u001b[0m \u001b[0;34m+\u001b[0m \u001b[0mBaseVel\u001b[0m \u001b[0;34m*\u001b[0m \u001b[0mrobot\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmodel\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mnv\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m     23\u001b[0m     \u001b[0mcontrolWeights\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mnp\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0marray\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m[\u001b[0m\u001b[0;36m0.1\u001b[0m\u001b[0;34m]\u001b[0m\u001b[0;34m*\u001b[0m\u001b[0;36m4\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m     24\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n",
-      "\u001b[0;31mNameError\u001b[0m: global name 'BaseVel' is not defined"
-     ]
-    }
-   ],
-   "source": [
-    "models = []\n",
-    "for i in range(0,len(target_pos)):\n",
-    "    runningModel, terminalModel = uavPlacementModel(target_pos[i], target_quat[i], dt, 'base_link')\n",
-    "    models += [runningModel]*(T-1) + [terminalModel]\n",
-    "\n",
-    "q0 = robot.q0\n",
-    "x0 = np.hstack([m2a(q0), np.zeros(robot.model.nv)])\n",
-    "\n",
-    "problem = ShootingProblem(x0, models[:-1], models[-1])\n",
-    "\n",
-    "# Creating the DDP solver for this OC problem, defining a logger\n",
-    "ddp = SolverFDDP(problem)\n",
-    "ddp.callback = [CallbackDDPVerbose()]\n",
-    "ddp.callback.append(CallbackDDPLogger())\n",
-    "\n",
-    "us0 = np.zeros([problem.T, 10])\n",
-    "xs0 = [problem.initialState+0.1]*len(ddp.models())\n",
-    "\n",
-    "# ddp.solve(init_xs=xs0,init_us=us0,maxiter=150)\n",
-    "ddp.solve(maxiter=150)"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "displayTrajectory(robot, ddp.xs, dt)\n"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "robot.nv"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "np.size(ddp.xs,0)"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "distanceRotorCOG = 0.1525\n",
-    "cf = 6.6e-5\n",
-    "cm = 1e-6\n",
-    "pltUAM = PlotUAM(ddp.xs, ddp.us, np.size(ddp.us,0), dt, distanceRotorCOG, cf, cm)\n",
-    "\n",
-    "fig, axs = pltUAM.plotMotorForces()\n",
-    "fig,axs = pltUAM.plotActuation()"
-   ]
-  },
-  {
-   "cell_type": "code",
-   "execution_count": null,
-   "metadata": {},
-   "outputs": [],
-   "source": [
-    "t = np.arange(0, 2*T*dt-dt, dt)\n",
-    "control = np.vstack(ddp.us)\n",
-    "fig = plt.figure()\n",
-    "axs = plt.plot(t, control[:,1])\n",
-    "axs.set_title('Moments')"
-   ]
-  }
- ],
- "metadata": {
-  "kernelspec": {
-   "display_name": "Python 2",
-   "language": "python",
-   "name": "python2"
-  },
-  "language_info": {
-   "codemirror_mode": {
-    "name": "ipython",
-    "version": 2
-   },
-   "file_extension": ".py",
-   "mimetype": "text/x-python",
-   "name": "python",
-   "nbconvert_exporter": "python",
-   "pygments_lexer": "ipython2",
-   "version": "2.7.12"
-  }
- },
- "nbformat": 4,
- "nbformat_minor": 2
-}
diff --git a/examples/notebooks/kinton/quadcopter_mission.ipynb b/examples/notebooks/kinton/quadcopter_mission.ipynb
index 50c6d619b0d5a1187642055fd3882eb66c6e00ca..9070e399eb4eb9a808eca18a2b4f7eb959f6c9b1 100644
--- a/examples/notebooks/kinton/quadcopter_mission.ipynb
+++ b/examples/notebooks/kinton/quadcopter_mission.ipynb
@@ -2,7 +2,7 @@
  "cells": [
   {
    "cell_type": "code",
-   "execution_count": 1,
+   "execution_count": 31,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -14,7 +14,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 2,
+   "execution_count": 32,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -30,7 +30,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 69,
+   "execution_count": 37,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -52,8 +52,8 @@
     "    SE3ref.rotation = targetQuat.matrix()\n",
     "\n",
     "    wBasePos  = [0.1]\n",
-    "    wBaseOri  = [100]\n",
-    "    wBaseVel  = [100]\n",
+    "    wBaseOri  = [1000]\n",
+    "    wBaseVel  = [1000]\n",
     "    wBaseRate = [10]\n",
     "    \n",
     "    stateWeights   = np.array(wBasePos * 3 + wBaseOri * 3 + wBaseVel * robot.model.nv)\n",
@@ -63,6 +63,9 @@
     "                                               frame=rmodel.getFrameId(frameName),\n",
     "                                               ref=SE3ref,\n",
     "                                               nu=actModel.nu)\n",
+    "    goalFrameVelocity = CostModelFrameVelocity(rmodel,\n",
+    "                                              frame=rmodel.getFrameId(frameName))\n",
+    "    \n",
     "    xRegCost = CostModelState(rmodel, \n",
     "                              state, \n",
     "                              ref=state.zero(), \n",
@@ -75,15 +78,16 @@
     "    uLimCost = CostModelControl(rmodel, \n",
     "                                nu=robot.\n",
     "                                model.nv-2,\n",
-    "                                activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1]), \n",
-    "                                                                    np.array([5, 5, 5, 5])))\n",
+    "                                activation = ActivationModelInequalityCont(np.array([0.1, 0.1, 0.1, 0.1]), \n",
+    "                                                                    np.array([10, 10, 10, 10])))\n",
     "\n",
     "    # Then let's add the running and terminal cost functions\n",
     "    runningCostModel.addCost(name=\"pos\", weight=0.01, cost=goalTrackingCost)\n",
     "    runningCostModel.addCost(name=\"regx\", weight=1e-6, cost=xRegCost)\n",
     "    runningCostModel.addCost(name=\"regu\", weight=1e-6, cost=uRegCost)\n",
     "    runningCostModel.addCost(name=\"limu\", weight=1e-4, cost=uLimCost)\n",
-    "    terminalCostModel.addCost(name=\"pos\", weight=50, cost=goalTrackingCost)\n",
+    "    terminalCostModel.addCost(name=\"pos\", weight=100, cost=goalTrackingCost)\n",
+    "    # terminalCostModel.addCost(name=\"vel\", weight=10, cost=goalFrameVelocity)\n",
     "\n",
     "    # DIFFERENTIAL ACTION MODEL\n",
     "    runningDmodel  = DifferentialActionModelActuated(rmodel, actModel, runningCostModel)\n",
@@ -98,7 +102,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 70,
+   "execution_count": 38,
    "metadata": {
     "scrolled": true
    },
@@ -127,7 +131,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 71,
+   "execution_count": 39,
    "metadata": {
     "scrolled": true
    },
@@ -172,327 +176,73 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 72,
-   "metadata": {},
+   "execution_count": null,
+   "metadata": {
+    "scrolled": true
+   },
    "outputs": [
     {
      "name": "stdout",
      "output_type": "stream",
      "text": [
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "   0  1.49063e-01  1.43562e-04  1.11205e+00  1.00000e-09  1.00000e-09   0.5000     0\n",
-      "   1  1.44419e-01  4.04310e-05  2.98015e-01  1.00000e-09  1.00000e-09   0.5000     0\n",
-      "   2  1.41430e-01  1.70531e-05  1.74841e-01  1.00000e-09  1.00000e-09   0.1250     0\n",
-      "   3  1.62549e-01  1.17043e-05  2.15751e-02  1.00000e-09  1.00000e-09   1.0000     1\n",
-      "   4  1.53148e-01  1.25240e-05  1.51471e-01  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "   5  1.51509e-01  4.15297e-06  1.60413e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "   6  1.49708e-01  4.91016e-06  2.97482e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "   7  1.48270e-01  3.41466e-06  1.19152e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "   8  1.46923e-01  3.69564e-06  2.10745e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "   9  1.45710e-01  2.77103e-06  9.21471e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  10  1.44663e-01  2.94523e-06  1.58120e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  11  1.44341e-01  2.26251e-06  7.35190e-03  1.00000e-09  1.00000e-09   0.5000     1\n",
-      "  12  1.42242e-01  4.78284e-06  5.45618e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  13  1.41447e-01  2.10589e-06  1.47243e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  14  1.41030e-01  1.51869e-06  5.67241e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  15  1.40383e-01  1.78221e-06  1.30769e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  16  1.40183e-01  1.29005e-06  5.40093e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  17  1.39548e-01  1.69022e-06  1.47019e-02  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  18  1.39193e-01  1.14072e-06  5.73348e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  19  1.38922e-01  8.96443e-07  3.15628e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "   0  1.80325e-01  2.95784e-03  2.95508e+00  1.00000e-09  1.00000e-09   0.5000     0\n",
+      "   1  2.13623e-01  9.25537e-04  6.31544e-02  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "   2  2.07526e-01  3.50519e-03  6.95135e+00  1.00000e-09  1.00000e-09   0.0078     1\n",
+      "   3  2.04907e-01  2.86215e-04  3.15590e-01  1.00000e-09  1.00000e-09   0.0625     1\n",
+      "   4  2.01688e-01  1.51368e-04  5.74597e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "   5  1.98967e-01  4.57606e-04  5.93434e-01  1.00000e-09  1.00000e-09   0.0312     1\n",
+      "   6  1.97659e-01  1.37920e-04  3.35128e-02  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "   7  1.91358e-01  1.18266e-03  1.80604e+00  1.00000e-09  1.00000e-09   0.0312     1\n",
+      "   8  1.91215e-01  1.38116e-04  3.96459e-02  1.00000e-09  1.00000e-09   0.0312     1\n",
+      "   9  1.91058e-01  1.27091e-04  2.36198e-02  1.00000e-09  1.00000e-09   0.0625     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  20  1.38557e-01  1.10719e-06  7.48324e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  21  1.38318e-01  7.92714e-07  3.56071e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  22  1.38086e-01  6.91736e-07  2.24165e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  23  1.37835e-01  7.88126e-07  5.19253e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  24  1.37652e-01  6.24253e-07  2.70150e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  25  1.37471e-01  5.21580e-07  1.70699e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  26  1.37281e-01  6.23285e-07  3.91068e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  27  1.37232e-01  4.67481e-07  2.05004e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  28  1.36994e-01  7.15274e-07  6.35670e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  29  1.36852e-01  4.54366e-07  2.82905e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
+      "  10  1.90619e-01  1.17710e-04  1.03161e-02  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  11  1.88739e-01  1.12975e-04  9.63074e-03  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  12  1.88401e-01  1.54747e-04  8.90043e-02  1.00000e-09  1.00000e-09   0.0312     1\n",
+      "  13  1.88397e-01  1.16498e-04  2.61181e-02  1.00000e-08  1.00000e-08   0.0020     1\n",
+      "  14  1.88397e-01  1.16498e-04  2.61165e-02  1.00000e-07  1.00000e-07   0.0020     1\n",
+      "  15  1.88397e-01  1.16499e-04  2.60997e-02  1.00000e-06  1.00000e-06   0.0020     1\n",
+      "  16  1.88397e-01  1.16506e-04  2.59341e-02  1.00000e-05  1.00000e-05   0.0020     1\n",
+      "  17  1.88397e-01  1.16500e-04  2.44183e-02  1.00000e-04  1.00000e-04   0.0020     1\n",
+      "  18  1.88398e-01  1.16193e-04  1.61671e-02  1.00000e-03  1.00000e-03   0.0020     1\n",
+      "  19  1.88180e-01  1.15156e-04  5.47186e-03  1.00000e-03  1.00000e-03   0.5000     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  30  1.36803e-01  3.66277e-07  1.51369e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  31  1.36575e-01  6.57583e-07  5.23703e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  32  1.36425e-01  4.37883e-07  2.51651e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  33  1.36320e-01  3.51611e-07  1.45836e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  34  1.36159e-01  4.68814e-07  3.83685e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  35  1.36049e-01  3.29411e-07  1.87932e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  36  1.35973e-01  2.69452e-07  1.09215e-03  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  37  1.35851e-01  3.54592e-07  2.92419e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  38  1.35768e-01  2.54240e-07  1.43367e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  39  1.35711e-01  2.04975e-07  8.33967e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  20  1.87919e-01  9.77169e-05  2.58460e-03  1.00000e-04  1.00000e-04   1.0000     1\n",
+      "  21  1.87052e-01  8.62852e-05  2.30731e-03  1.00000e-05  1.00000e-05   1.0000     1\n",
+      "  22  1.87052e-01  7.84746e-05  3.27787e-03  1.00000e-04  1.00000e-04   0.0020     1\n",
+      "  23  1.87052e-01  7.82413e-05  2.59827e-03  1.00000e-03  1.00000e-03   0.0020     1\n",
+      "  24  1.86799e-01  7.74429e-05  1.81164e-03  1.00000e-04  1.00000e-04   1.0000     1\n",
+      "  25  1.86549e-01  7.01303e-05  2.27520e-03  1.00000e-05  1.00000e-05   1.0000     1\n",
+      "  26  1.86226e-01  1.20355e-04  8.63138e-02  1.00000e-05  1.00000e-05   0.0312     1\n",
+      "  27  1.86214e-01  7.21470e-05  1.40971e-02  1.00000e-05  1.00000e-05   0.0078     1\n",
+      "  28  1.86210e-01  6.97790e-05  1.06683e-02  1.00000e-05  1.00000e-05   0.0039     1\n",
+      "  29  1.86208e-01  6.88798e-05  9.38236e-03  1.00000e-04  1.00000e-04   0.0020     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  40  1.35617e-01  2.74558e-07  2.23762e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  41  1.35553e-01  1.93820e-07  1.09350e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  42  1.35510e-01  1.58519e-07  6.31795e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  43  1.35439e-01  2.09030e-07  1.69837e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  44  1.35391e-01  1.50421e-07  8.30555e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  45  1.35359e-01  1.21901e-07  4.83961e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  46  1.35308e-01  1.52510e-07  1.27914e-03  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  47  1.35273e-01  1.03990e-07  6.10453e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  48  1.35253e-01  8.48426e-08  3.44008e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  49  1.35215e-01  1.11569e-07  9.59001e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  50  1.35189e-01  7.99990e-08  4.61242e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  51  1.35177e-01  6.28589e-08  2.54978e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  52  1.35149e-01  8.99001e-08  7.35389e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  53  1.35130e-01  5.96259e-08  3.48775e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  54  1.35121e-01  4.94345e-08  1.94297e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  55  1.35099e-01  6.64752e-08  5.68975e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  56  1.35084e-01  4.83036e-08  2.71611e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  57  1.35077e-01  3.73795e-08  1.52546e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  58  1.35060e-01  5.51920e-08  4.58442e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  59  1.35048e-01  3.62546e-08  2.12275e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  60  1.35043e-01  3.00242e-08  1.16329e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  61  1.35029e-01  4.01583e-08  3.36668e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  62  1.35024e-01  4.40004e-08  2.24277e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  63  1.35002e-01  5.76909e-08  6.39571e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  64  1.34989e-01  3.54257e-08  2.83648e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  65  1.34980e-01  2.52395e-08  1.43069e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  66  1.34974e-01  2.07059e-08  8.54626e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  67  1.34964e-01  2.72541e-08  2.25673e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  68  1.34958e-01  1.95973e-08  1.10304e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  69  1.34953e-01  1.58079e-08  6.33059e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  70  1.34946e-01  2.09694e-08  1.66354e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  71  1.34941e-01  1.50800e-08  8.45972e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  72  1.34937e-01  1.25339e-08  5.13837e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  73  1.34932e-01  1.71805e-08  1.47899e-04  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  74  1.34927e-01  1.20124e-08  6.82963e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  75  1.34924e-01  9.63737e-09  3.80106e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  76  1.34920e-01  1.26502e-08  9.78031e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  77  1.34917e-01  9.11001e-09  4.93212e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  78  1.34914e-01  7.63467e-09  2.97540e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  79  1.34911e-01  9.73672e-09  7.59754e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  80  1.34909e-01  7.23795e-09  3.85144e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  81  1.34907e-01  5.94691e-09  2.33830e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  82  1.34904e-01  7.71660e-09  5.90896e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  83  1.34902e-01  5.58616e-09  3.00304e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  84  1.34901e-01  4.69765e-09  1.82013e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  85  1.34899e-01  6.06763e-09  4.85759e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  86  1.34897e-01  4.55942e-09  2.55998e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  87  1.34897e-01  3.74121e-09  1.61305e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  88  1.34895e-01  5.65204e-09  5.29829e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  89  1.34893e-01  3.69978e-09  2.34646e-05  1.00000e-09  1.00000e-09   0.1250     1\n"
+      "  30  1.86207e-01  6.78246e-05  5.71813e-03  1.00000e-04  1.00000e-04   0.0039     1\n",
+      "  31  1.86205e-01  6.74495e-05  5.40021e-03  1.00000e-04  1.00000e-04   0.0039     1\n",
+      "  32  1.86204e-01  6.71010e-05  5.10714e-03  1.00000e-03  1.00000e-03   0.0020     1\n",
+      "  33  1.86018e-01  6.53778e-05  2.09693e-03  1.00000e-04  1.00000e-04   1.0000     1\n"
      ]
-    },
-    {
-     "name": "stdout",
-     "output_type": "stream",
-     "text": [
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      "  90  1.34893e-01  2.91875e-09  1.14777e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  91  1.34891e-01  3.81864e-09  3.11718e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  92  1.34890e-01  2.86724e-09  1.65333e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  93  1.34890e-01  2.34551e-09  1.04444e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  94  1.34889e-01  3.66078e-09  3.55623e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  95  1.34888e-01  2.41271e-09  1.66945e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  96  1.34888e-01  1.87561e-09  8.15072e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
-      "  97  1.34887e-01  2.60268e-09  2.36205e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  98  1.34886e-01  1.85305e-09  1.14409e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "  99  1.34885e-01  1.50861e-09  7.35515e-06  1.00000e-09  1.00000e-09   0.1250     1\n",
-      "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\n",
-      " 100  1.34885e-01  1.35726e-09  5.50366e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
-      " 101  1.34884e-01  1.62271e-09  1.25570e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      " 102  1.34884e-01  1.19312e-09  5.41702e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
-      " 103  1.34884e-01  1.75123e-09  1.70159e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
-      " 104  1.34883e-01  1.25484e-09  8.85495e-06  1.00000e-09  1.00000e-09   0.1250     1\n",
-      " 105  1.34883e-01  1.01858e-09  5.97769e-06  1.00000e-09  1.00000e-09   0.1250     1\n",
-      " 106  1.34883e-01  9.14728e-10  4.59803e-06  1.00000e-09  1.00000e-09   0.1250     1\n"
-     ]
-    },
-    {
-     "data": {
-      "text/plain": [
-       "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0.]),\n",
-       "  array([-6.20464074e-07,  5.53926180e-04,  1.10871654e-02, -4.98986956e-02,\n",
-       "         -1.09026993e-04, -1.59607050e-03,  9.98753003e-01,  0.00000000e+00,\n",
-       "          0.00000000e+00,  3.70186867e-01, -3.32796314e+00, -7.27148899e-03,\n",
-       "         -1.06448951e-01]),\n",
-       "  array([-1.21004983e-06,  3.75061235e-03,  3.33491575e-02, -1.02684987e-01,\n",
-       "         -6.86382934e-05, -1.33111686e-03,  9.94713032e-01, -3.02161576e-05,\n",
-       "         -7.62540239e-03,  7.49989401e-01, -3.52978846e+00, -3.84003489e-03,\n",
-       "          1.77379963e-02]),\n",
-       "  array([-1.58431907e-07,  1.11048995e-02,  6.60993206e-02, -1.41608622e-01,\n",
-       "         -6.52544898e-05, -9.89373737e-04,  9.89922227e-01, -6.85144909e-05,\n",
-       "         -2.69237213e-02,  1.11882089e+00, -2.61465513e+00, -5.59254805e-03,\n",
-       "          2.24443096e-02]),\n",
-       "  array([ 2.62553211e-06,  2.33727013e-02,  1.08232498e-01, -1.62518146e-01,\n",
-       "         -8.09875740e-05, -7.19330240e-04,  9.86705289e-01, -1.94180777e-05,\n",
-       "         -3.21727925e-02,  1.46251661e+00, -1.41039289e+00, -4.98118965e-03,\n",
-       "          1.75530300e-02]),\n",
-       "  array([ 6.38871615e-06,  4.07198129e-02,  1.58633069e-01, -1.67265945e-01,\n",
-       "         -9.23356100e-05, -5.18647444e-04,  9.85911673e-01,  6.63468421e-05,\n",
-       "          3.31925093e-04,  1.77675162e+00, -3.20909981e-01, -3.15276364e-03,\n",
-       "          1.30656609e-02]),\n",
-       "  array([ 1.01135256e-05,  6.28415045e-02,  2.16077892e-01, -1.59708282e-01,\n",
-       "         -9.44843439e-05, -3.72585580e-04,  9.87164179e-01,  1.29881967e-04,\n",
-       "          8.02922518e-02,  2.05035199e+00,  5.10718599e-01, -1.50096297e-03,\n",
-       "          9.57319067e-03]),\n",
-       "  array([ 1.32518520e-05,  8.92463726e-02,  2.79511995e-01, -1.44137526e-01,\n",
-       "         -8.65482015e-05, -2.67471108e-04,  9.89557626e-01,  1.55342345e-04,\n",
-       "          2.04504453e-01,  2.28128940e+00,  1.05025362e+00, -1.95060997e-04,\n",
-       "          6.96384007e-03]),\n",
-       "  array([ 1.53207706e-05,  1.19410453e-01,  3.48246795e-01, -1.24071516e-01,\n",
-       "         -7.40299160e-05, -1.91449890e-04,  9.92273257e-01,  1.38313765e-04,\n",
-       "          3.60335805e-01,  2.47616569e+00,  1.34995230e+00,  4.68843072e-04,\n",
-       "          5.06844013e-03]),\n",
-       "  array([ 1.63559352e-05,  1.52710869e-01,  4.21394134e-01, -1.02336492e-01,\n",
-       "         -5.85181397e-05, -1.35886302e-04,  9.94749828e-01,  1.01057364e-04,\n",
-       "          5.33081165e-01,  2.62566889e+00,  1.45840678e+00,  8.56239667e-04,\n",
-       "          3.72855932e-03]),\n",
-       "  array([ 1.63402790e-05,  1.88574601e-01,  4.98401593e-01, -8.05954752e-02,\n",
-       "         -4.34434097e-05, -9.43398357e-05,  9.96746888e-01,  5.07919623e-05,\n",
-       "          7.07878962e-01,  2.74196185e+00,  1.45553195e+00,  9.21075580e-04,\n",
-       "          2.79156608e-03]),\n",
-       "  array([ 1.55488996e-05,  2.26441294e-01,  5.78876416e-01, -5.95364756e-02,\n",
-       "         -2.84305363e-05, -6.21195385e-05,  9.98226128e-01,  4.34511991e-06,\n",
-       "          8.74893522e-01,  2.83281645e+00,  1.40741870e+00,  9.61284105e-04,\n",
-       "          2.17016967e-03]),\n",
-       "  array([ 1.76114165e-05,  2.65634813e-01,  6.54916635e-01, -4.69710518e-02,\n",
-       "         -2.76065713e-05, -1.55265606e-04,  9.98896239e-01, -3.92704959e-05,\n",
-       "          1.02948329e+00,  2.65931919e+00,  8.38890648e-01,  4.77859396e-04,\n",
-       "         -6.21665719e-03]),\n",
-       "  array([ 1.27766185e-05,  3.05037950e-01,  7.22263163e-01, -3.54940241e-02,\n",
-       "         -1.94025469e-05, -3.83842017e-05,  9.99369888e-01, -2.89916203e-04,\n",
-       "          1.12402627e+00,  2.34552488e+00,  7.65790813e-01,  3.00005943e-04,\n",
-       "          7.79313450e-03]),\n",
-       "  array([ 1.13109338e-05,  3.44607761e-01,  7.80818114e-01, -2.48967175e-02,\n",
-       "         -1.20854262e-05, -2.05306030e-05,  9.99690028e-01, -6.04507658e-05,\n",
-       "          1.19879040e+00,  2.02793021e+00,  7.06812721e-01,  4.72795169e-04,\n",
-       "          1.19393814e-03]),\n",
-       "  array([ 1.00017963e-05,  3.84315036e-01,  8.30555997e-01, -1.49814781e-02,\n",
-       "         -8.41615864e-06, -1.39964373e-05,  9.99887771e-01, -5.36883234e-05,\n",
-       "          1.25644107e+00,  1.70941111e+00,  6.61150115e-01,  2.47431163e-04,\n",
-       "          4.33855308e-04]),\n",
-       "  array([ 8.81580561e-06,  4.24130931e-01,  8.71423168e-01, -5.40996865e-03,\n",
-       "         -3.09766190e-06, -9.90363937e-06,  9.99985366e-01, -5.51003789e-05,\n",
-       "          1.29916350e+00,  1.38903938e+00,  6.38136232e-01,  3.59430295e-04,\n",
-       "          2.72859377e-04]),\n",
-       "  array([ 7.60754973e-06,  4.64038413e-01,  9.03512788e-01,  4.16748778e-03,\n",
-       "         -6.93569784e-07, -8.95526306e-06,  9.99991316e-01, -6.12983889e-05,\n",
-       "          1.32893965e+00,  1.07132240e+00,  6.38499658e-01,  1.66255632e-04,\n",
-       "          6.21182630e-05]),\n",
-       "  array([ 7.34143840e-06,  5.04028910e-01,  9.26899897e-01,  1.40357509e-02,\n",
-       "          3.34583332e-06, -3.10905624e-05,  9.99901494e-01, -6.45515122e-05,\n",
-       "          1.34700786e+00,  7.55188870e-01,  6.57914124e-01,  2.69033036e-04,\n",
-       "         -1.47732998e-03]),\n",
-       "  array([ 8.41566155e-06,  5.44100799e-01,  9.41654091e-01,  2.43680710e-02,\n",
-       "          6.53710360e-06, -8.73956797e-05,  9.99703051e-01, -1.28119871e-04,\n",
-       "          1.35365271e+00,  4.40163300e-01,  6.88951447e-01,  1.81508092e-04,\n",
-       "         -3.75446431e-03]),\n",
-       "  array([ 4.16016539e-06,  5.84230188e-01,  9.48170701e-01,  3.64587548e-02,\n",
-       "          7.31969077e-06, -1.20033899e-05,  9.99335158e-01, -2.77883774e-04,\n",
-       "          1.34841144e+00,  1.35493125e-01,  8.06423515e-01,  2.45245843e-04,\n",
-       "          5.02663711e-03]),\n",
-       "  array([ 3.35784522e-06,  6.24036472e-01,  9.51038800e-01,  4.76935243e-02,\n",
-       "          9.74965896e-06, -2.07479854e-05,  9.98862016e-01, -7.09783041e-05,\n",
-       "          1.33024407e+00, -1.62980997e-02,  7.49652488e-01,  1.49860102e-04,\n",
-       "         -5.83400265e-04]),\n",
-       "  array([ 1.48631122e-06,  6.62919796e-01,  9.54708809e-01,  5.46510470e-02,\n",
-       "          9.42666782e-06,  1.97636232e-06,  9.98505515e-01, -8.78724087e-05,\n",
-       "          1.30183707e+00, -1.07840511e-02,  4.64444276e-01,  6.06012236e-05,\n",
-       "          1.51830089e-03]),\n",
-       "  array([ 6.67436875e-07,  7.00576332e-01,  9.60669522e-01,  5.73863128e-02,\n",
-       "          9.33338306e-06,  3.25907472e-06,  9.98352048e-01, -2.30787217e-05,\n",
-       "          1.26956729e+00,  5.70328797e-02,  1.82637897e-01, -1.80020037e-06,\n",
-       "          8.74655270e-05]),\n",
-       "  array([ 2.19577607e-06,  7.36933916e-01,  9.69130652e-01,  5.67070961e-02,\n",
-       "          1.17631082e-05, -5.28756585e-05,  9.98390856e-01, -1.43698481e-05,\n",
-       "          1.23615786e+00,  1.42155148e-01, -4.53549327e-02, -5.29195319e-05,\n",
-       "         -3.74587527e-03]),\n",
-       "  array([ 2.37850144e-06,  7.72028951e-01,  9.80066240e-01,  5.26257637e-02,\n",
-       "          1.10450062e-05, -6.80196740e-05,  9.98614302e-01, -1.44381462e-04,\n",
-       "          1.20264035e+00,  2.34631196e-01, -2.72496467e-01, -1.19610408e-04,\n",
-       "         -1.00767743e-03]),\n",
-       "  array([ 2.89746764e-06,  8.06117651e-01,  9.91878856e-01,  4.68304681e-02,\n",
-       "          9.95450001e-06, -8.92084366e-05,  9.98902848e-01, -1.71296711e-04,\n",
-       "          1.16978966e+00,  2.78936225e-01, -3.86832152e-01, -1.73431040e-04,\n",
-       "         -1.40976758e-03]),\n",
-       "  array([ 3.76173037e-06,  8.39453891e-01,  1.00289750e+00,  4.04821634e-02,\n",
-       "          8.71593618e-06, -1.18446826e-04,  9.99180254e-01, -2.11007602e-04,\n",
-       "          1.13901843e+00,  2.68959285e-01, -4.23624870e-01, -2.11703837e-04,\n",
-       "         -1.94579678e-03]),\n",
-       "  array([ 5.01237094e-06,  8.72243898e-01,  1.01165894e+00,  3.43779100e-02,\n",
-       "          7.49432994e-06, -1.58434859e-04,  9.99408892e-01, -2.67840041e-04,\n",
-       "          1.11179202e+00,  2.09465937e-01, -4.07236185e-01, -2.37630089e-04,\n",
-       "         -2.66214474e-03]),\n",
-       "  array([ 6.73307980e-06,  9.04646363e-01,  1.01690996e+00,  2.90397556e-02,\n",
-       "          6.40836197e-06, -2.12885278e-04,  9.99578235e-01, -3.47524858e-04,\n",
-       "          1.08901006e+00,  1.06220636e-01, -3.56056362e-01, -2.53616972e-04,\n",
-       "         -3.62628896e-03]),\n",
-       "  array([ 9.06644921e-06,  9.36788817e-01,  1.01742518e+00,  2.47962404e-02,\n",
-       "          5.52206399e-06, -2.87069040e-04,  9.99692485e-01, -4.57779455e-04,\n",
-       "          1.07078981e+00, -4.05111564e-02, -2.83003688e-01, -2.62955227e-04,\n",
-       "         -4.94198869e-03]),\n",
-       "  array([ 1.68888857e-05,  9.68779022e-01,  1.01165169e+00,  2.04637286e-02,\n",
-       "          8.00355080e-06, -5.35309183e-04,  9.99790453e-01, -6.09414889e-04,\n",
-       "          1.05654311e+00, -2.40503360e-01, -2.88908111e-01, -3.27932332e-04,\n",
-       "         -1.65481278e-02]),\n",
-       "  array([-7.53894460e-08,  1.00041937e+00,  1.00000547e+00,  2.15730341e-06,\n",
-       "          5.63587538e-08,  3.34392998e-07,  1.00000000e+00, -1.12513759e-03,\n",
-       "          1.04658489e+00, -4.09739635e-01, -1.36420005e+00, -5.29317372e-04,\n",
-       "          3.57119853e-02])],\n",
-       " [array([ 8.207219  ,  3.96942747,  8.18890915, 12.34934778]),\n",
-       "  array([8.26409957, 8.04752555, 8.2488596 , 8.55567614]),\n",
-       "  array([8.09483381, 9.24861322, 8.09464155, 6.94428206]),\n",
-       "  array([7.73152087, 9.24867302, 7.73701618, 6.2163097 ]),\n",
-       "  array([7.31313789, 8.68631782, 7.31941077, 5.94297002]),\n",
-       "  array([6.78559018, 7.83357484, 6.79003211, 5.73950959]),\n",
-       "  array([6.29414536, 6.97395962, 6.29710408, 5.6153937 ]),\n",
-       "  array([5.94949498, 6.32672117, 5.95067369, 5.57207018]),\n",
-       "  array([5.53055767, 5.66687403, 5.53107192, 5.39378192]),\n",
-       "  array([5.2651881 , 5.26112666, 5.2649848 , 5.26836536]),\n",
-       "  array([5.07420474, 5.01331735, 5.07403208, 5.13446792]),\n",
-       "  array([1.918109  , 1.19856412, 1.91668582, 2.63013627]),\n",
-       "  array([ 0.06046991, -0.026522  ,  0.06037362,  0.15754598]),\n",
-       "  array([ 0.02317576, -0.05345985,  0.02320856,  0.09504876]),\n",
-       "  array([ 0.01073596, -0.04734234,  0.0101116 ,  0.06763757]),\n",
-       "  array([-0.01589311, -0.04479511, -0.01563042,  0.01315459]),\n",
-       "  array([0.01797556, 0.01810747, 0.0174774 , 0.01719235]),\n",
-       "  array([0.04461027, 0.06862213, 0.04486639, 0.01973586]),\n",
-       "  array([0.07120175, 0.10937344, 0.07104688, 0.03122047]),\n",
-       "  array([0.21065877, 0.3619159 , 0.21099363, 0.06611743]),\n",
-       "  array([2.1472105 , 2.07343985, 2.14669706, 2.21639107]),\n",
-       "  array([4.04167157, 3.68325573, 4.04147629, 4.40141937]),\n",
-       "  array([4.65904011, 4.30361905, 4.65883544, 5.01321675]),\n",
-       "  array([4.73257733, 4.44407294, 4.73244754, 5.01816636]),\n",
-       "  array([4.71616176, 4.43109204, 4.71598238, 5.00304186]),\n",
-       "  array([4.02674082, 3.88256721, 4.02658679, 4.17046821]),\n",
-       "  array([3.31672851, 3.27014456, 3.31659538, 3.36278981]),\n",
-       "  array([2.70022723, 2.72054017, 2.70010638, 2.6792729 ]),\n",
-       "  array([2.1760523 , 2.24008158, 2.17593896, 2.11120907]),\n",
-       "  array([1.66732715, 1.75876838, 1.6672166 , 1.57481929]),\n",
-       "  array([1.04665814, 1.03487857, 1.04640025, 1.04974602]),\n",
-       "  array([1.41450159, 0.07926474, 1.41367222, 2.78688475])],\n",
-       " True)"
-      ]
-     },
-     "execution_count": 72,
-     "metadata": {},
-     "output_type": "execute_result"
     }
    ],
    "source": [
-    "ddp.solve(init_xs=xs0, init_us=us0, maxiter=150)"
+    "ddp.solve(init_xs=xs0, init_us=us0, maxiter=150)\n",
+    "#ddp.solve(init_xs=xs0, maxiter=150)"
    ]
   },
   {
    "cell_type": "code",
-   "execution_count": 73,
+   "execution_count": 29,
    "metadata": {
     "scrolled": false
    },
    "outputs": [
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "iVBORw0KGgoAAAANSUhEUgAAA2oAAAKGCAYAAAA72mhGAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAIABJREFUeJzs3Xl83Gd57/3vpd3SSJYsjRbvtiRbdvbY2QMhGwQIW0spUCBhy2kPZevTp6ftoQf6ek4L9DndHkppAwkkIYSyQxdCSCCLQzYvgdjxvki2Y0sjyYtmRprRzNzPHzPjKIoXSTPSb+Y3n/frlZdlzXjmUgjz8/d339d1m3NOAAAAAIDCUeZ1AQAAAACAVyKoAQAAAECBIagBAAAAQIEhqAEAAABAgSGoAQAAAECBIagBAAAAQIEhqAEAipalfd3MjpnZs17XAwBAvhDUAADnZGYHzCxuZi2Tvr/FzJyZLZ/Ca9xuZhvyXNq1km6WtNg5d3meXxsAAM8Q1AAAU7Vf0nuyvzGzCyTVztWbm1nFab69TNIB51wkT68HAEBBIKgBAKbqPkkfmPD72yTdO/EJZjbfzO41s5CZ9ZrZZ8yszMzWSPoXSVeZWdjMjp/t+ZnHbjezJ83s781sSNLnJr3XhyV9bcJr/mXm+x81sz1mNmxmPzGzhRP+jDOzj5nZbkm7M987z8x+nnl+v5n9eeb7ZWb2p2a218yGzOw7ZrYg81iNmX0z8/3jZvacmbXl7181AKDUEdQAAFP1tKQGM1tjZuWS3i3pm5Oe8yVJ8yWtlHSd0sHug8657ZJ+X9JTzrmAc67xbM+f8HpXSNonqU3SX018I+fcXZNe87NmdoOkz0t6l6QOSb2Svj2pxrdnXnetmdVLeljSg5IWSuqS9EjmeR/PPPe6zGPHJH0589htmbqXSGrO1DF6tn95AABMB9s+AADTkV1Ve0zSdkmHsw9MCG8XO+dGJI2Y2d9Ker+kuya/0BSf/5Jz7kuZrxNTqO/3JN3tnNuceY8/k3TMzJY75w5knvN559xw5vH3SDrqnPvbzGNjkp7JfP37kv7QOXco89zPSeozs/dLGlc6oHU5534jadMUagMAYMoIagCA6bhP0uOSVmjStkdJLZIqlV7FyuqVtOgMrzWV5x+cZn0LJW3O/sY5F85sm1wk6cBpXnOJpL1neK1lkn5oZqkJ30sqvbp3X+bPftvMGpVeWfyfzrnxadYLAMBpsfURADBlzrlepYeKvEnSDyY9PKj0StOyCd9bqpdX3dw0n3+6P3MuL018PTOrU3rl60yveVDpbZenc1DSG51zjRP+qXHOHXbOjTvn/tI5t1bS1ZJu1Sv79wAAyAlBDQAwXR+WdMPkSYvOuaSk70j6KzOrN7Nlkv5IL/ex9UtabGZVU3z+TDwg6YNmdrGZVUv6a0nPTNj2ONl/SOows0+ZWXWmjisyj/1LprZlkmRmQTN7W+br683sgsz2zZNKB87U6d4AAICZIKgBAKbFObfXObfxDA9/XFJE6QEgGyR9S9Ldmcd+IWmbpKNmNjiF58+ktocl/YWk70s6IqlT6T64Mz1/ROlz2N4i6ajSkyCvzzz8j5J+IukhMxtRephKNsS1S/qe0iFtu9I9e/fNtG4AACYz56a7qwQAAAAAMJtYUQMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAwAAAIACQ1ADAAAAgAJDUAMAAACAAkNQAzLM7ICZxc2sZdL3t5iZM7PlU3iN281sQ57rOt/MfmZmg2bm8vnaAABMRQFfI28zs01mdtLMDpnZ35hZRT7fA/AKQQ14pf2S3pP9jZldIKl2rt78DBeXcUnfkfThuaoDAIDTKMRrZK2kT0lqkXSFpBsl/fFc1QTMJoIa8Er3SfrAhN/fJuneiU8ws/lmdq+Zhcys18w+Y2ZlZrZG0r9IusrMwmZ2/GzPzzx2u5k9aWZ/b2ZDkj43uSDn3E7n3F2Sts3OjwwAwJQU4jXyK865J5xzcefcYUn3S7pmVn56YI4R1IBXelpSg5mtMbNySe+W9M1Jz/mSpPmSVkq6TumL1gedc9sl/b6kp5xzAedc49meP+H1rpC0T1KbpL+alZ8KAIDcFcM18rXixiZ8gj28wKtl7xg+Jmm7pMPZByZcmC52zo1IGjGzv5X0fkl3TX6hKT7/JefclzJfJ2bnRwIAIC8K9hppZh+StF7SR2b+4wGFg6AGvNp9kh6XtEKTtnQovQe+UlLvhO/1Slp0hteayvMP5lIsAABzqCCvkWb2dkmfl3STc25wKn8GKHRsfQQmcc71Kt0w/SZJP5j08KDSwz2WTfjeUr18R3HyVMZzPf90fwYAgIJUiNdIM7tF0lclvcU598K5ng8UC4IacHoflnSDcy4y8ZvOuaTSExj/yszqzWyZpD/Sy3v0+yUtNrOqKT7/nCytRlJV5vc1Zlad248HAMCMFdI18galB4j8tnPu2Rx/LqCgENSA03DO7XXObTzDwx+XFFG6uXmDpG9Jujvz2C+UbmI+amaDU3j+VCyTNKqXm6NHJe2cxp8HACBvCuwa+RdKDyP5r8w0ybCZ/XQ6Pw9QqMw5dl0BAAAAQCFhRQ0AAAAACgxBDQAAAAAKDEENAAAAAAoMQQ0AAAAACsycHnjd0tLili9fPpdvCQDwwKZNmwadc0Gv6ygWXB8BoHRM9Ro5p0Ft+fLl2rjxTNNcAQB+YWa9XtdQTLg+AkDpmOo1kq2PAAAAAFBgCGoAAAAAUGAIagAAAABQYAhqAAAAAFBgCGoAAAAAUGAIagAAAABQYAhqAAAAAFBgCGoAAAAAUGB8G9Si8YRefOmk12UAAFBw9gyM6OTYuNdlAADOwrdB7b6nevXmLz2hx3eFvC4FAICC8p6vPqMPf+M5pVLO61IAAGdwzqBmZneb2YCZbZ3wvQVm9nMz2535tWl2y5y+w8dH5Zz06X97Xv0nx7wuBwCAguCc01A4pucOHNM3fnXA63IAAGcwlRW1b0i6ZdL3/lTSI865bkmPZH5fUAbDMS2oq9LoeFIff2CLEsmU1yUBAOC5sfGUUk6qLDf9zc926MBgxOuSAACncc6g5px7XNLwpG+/TdI9ma/vkfT2PNeVs8GRuLpbA/qrd5yvZ/cP6x8e3u11SQAAeC4ST0iSPvqalaosL9OffO83bIEEgAI00x61NufckczXRyW1nemJZnaHmW00s42h0Nz1i4XCMbXUV+sdlyzW765foi8/ukeP0a8GAChxkVg6qK0MBvS/bl2rZw8M656nDnhaEwDg1XIeJuKcc5LOeCvOOXenc269c259MBjM9e2mbHAkpmCgWpL0ubeep1Wt9fr0vz2voyfoVwMAlK5wJqgFqsv1znWLdf3qoL74IFsgAaDQzDSo9ZtZhyRlfh3IX0m5GxtPaiSWUEugSpI0r6pcX/69SzU2ntQnvk2/GgCgdEXjSUlSXXWFzEyf/60L01sgv88WSAAoJDMNaj+RdFvm69sk/Tg/5eTHYDgmSWrJrKhJUldrQH/9jgvoVwMAlLTsilpddYUkqX1+jf7i1rV6dv+w7n3qgHeFAQBeYSrj+R+Q9JSk1WZ2yMw+LOkLkm42s92Sbsr8vmAMhuOSXhnUJOntlyzSuy+jXw0AULqyPWp1VRWnvvc76xbrdauD+uKDO9U7xBZIACgEU5n6+B7nXIdzrtI5t9g5d5dzbsg5d6Nzrts5d5NzbvJUSE8NjmRW1OqrX/XY5956nla30a8GAChNp4Jadfmp76W3QF6gijJjCiQAFIich4kUope3Pla96rGaynL903sz/WqcrwYAKDGRWLpHLVBd8Yrvd8yfp7+4da2e2T+s+57u9aI0AMAEPg9qr15Rkyb0qx0Y1t8/vGsuSwMAwFPZFbXaqopXPfY76xfrulVBfeGnO9Q3FJ3r0gAAE/gyqIVGYqqvqVBNZfkZn/P2SxbpPZcv0Zd/uZd+NQBAyQjHE6oqL1NVxav/CvCKLZDf/zVbIAHAQ74MaoPh+Kkz1M7ms285Tz3t9KsBAEpHNJZ8RX/aZAsb5+kzt67R0/uG9c1n2AIJAF7xZVALhWNn3PY4UU1l+ny1WKZfLcmdQwCAz0ViiVOj+c/kXeuX6LVsgQQAT/kyqA2GY2qpf/UgkdPpDAb0v96yVs8eGNaz+wtqeCUAoMCZ2d1mNmBmWyd8b4GZ/dzMdmd+bfKyxsnCscQrRvOfjpnpC791gcqMLZAA4BV/BrWRqa2oZb3hvHZJ0ua+Y7NVEgDAn74h6ZZJ3/tTSY8457olPZL5fcGIxBNn3fqYtbBxnj7z5vQWyPuf7ZuDygAAE/kuqMUSSZ0cS0wrqDXWVqm7NaCNB1hRAwBMnXPucUmTLx5vk3RP5ut7JL19Tos6h0gsec6tj1m/e9kSXd3ZrL97aKfCmWmRAIC54bugNhSOS5KCpzns+mzWLWvS5r7jbO8AAOSqzTl3JPP1UUltp3uSmd1hZhvNbGMoNHfThyOxxKvOUDsTM9Of3NKjY9Fx3fvUgVmtCwDwSr4Lauc6Q+1M1i1r0onRce0NhWejLABACXLOOUmnvQPonLvTObfeObc+GAzOWU2RWOK0Z6idycVLGnX96qC++vg+VtUAYA75LqiFRrJBbWrDRLLWLUv3em/qpU8NAJCTfjPrkKTMrwMe1/MKkXhSgSn0qE30yZtW6Vh0XPf86sDsFAUAeBXfBbWZrqitaKnTgroqbSSoAQBy8xNJt2W+vk3Sjz2s5RWcc1Mazz/ZxUsadUNPq776BKtqADBXfBjUZtajZma6dGmTNhPUAABTZGYPSHpK0mozO2RmH5b0BUk3m9luSTdlfl8QYomUEik37aAmSZ+8sVvHWVUDgDkz/U/qAhcaiSlQXaGayult65Ck9cub9PD2fg2FY2qe5oocAKD0OOfec4aHbpzTQqYoklkNq6ua/jXyogmrah+4apnqayrzXR4AYAIfrqjFpt2flpXtU9vcdzyfJQEAUBCi8aQkzWhFTZI+dROragAwV3wa1Ga2GnbBovmqLDdt7OU8NQCA/2T7y6Y6nn+yCxc36saeVn31if0aGRvPZ2kAgEl8GNTi0+5Py6qpLNf5i+bTpwYA8KXs1sfaGQY1SfrUTat0YnRc33jyQJ6qAgCcju+CWmhk5itqkrR+WZN+feiEYolkHqsCAMB7kczWx+mO55/ogsXzddOaVn1tw36dZFUNAGaNr4JaPJHSidHxnILaumVNiidS2vbSyTxWBgCA904NE8lhRU1iVQ0A5kJOQc3MPmlmW81sm5l9Kl9FzdRQJHOGWv3MholI0qXZg68PsP0RAOAv4VNTH3MLaucvmq+b1rTpa0/sY1UNAGbJjIOamZ0v6aOSLpd0kaRbzawrX4XNxOBI+gy1XFbUWutrtHRBrTbRpwYA8Jl8rahJ6QmQJ8cS+vqGAzm/FgDg1XJZUVsj6RnnXNQ5l5D0mKTfyk9ZMzMYzqyo5XgG2vplTdrYe0zOuXyUBQBAQXh5PP/Me9Syzl80XzevbdNdG/bpxCiragCQb7kEta2SXmNmzWZWK+lNkpZMfpKZ3WFmG81sYygUyuHtzi2UCWrBHIPapcuaNBiO6eDwaD7KAgCgIIRjCVWWm6orcg9qkvTJGzOrak/uz8vrAQBeNuOg5pzbLumLkh6S9KCk5yW9alSic+5O59x659z6YDA440Kn4tSKWg49apK0fnm6T43z1AAAfhKJJVSbY3/aROcvmq/Xr23TXRv2s6oGAHmW0zAR59xdzrl1zrnXSjomaVd+ypqZwZG46qrKc74IdbfWq766gj41AICvRGLJGR92fSafvKlbI2MJ3b2BVTUAyKdcpz62Zn5dqnR/2rfyUdRMhcIxtczwsOuJystMlyxrIqgBAHwlEkvkpT9tovMWztcbzmvT3U+yqgYA+ZTrOWrfN7MXJf27pI85547noaYZG8zxsOuJ1i1t0s7+EcYOAwB8IxLP79bHrE/euEojYwndxaoaAORNrlsfX+OcW+ucu8g590i+ipqpwXBMLYHc+tOy1i9vknPSlj5PsycAAHkTjiXyvvVRktYubNAt57Xr6xv260SUG5wAkA+5rqgVlHRQy8+K2kVLGlVm0qYDDBQBAPhDNJbM+9bHrE/e1K2RWEJ3bdg3K68PAKXGN0FtPJnSseh43oJaoLpCazoatKmPPjUAgD+EY4m8HHZ9Oms6GvSmC9r1lcf26uEX+2flPQCglPgmqA1H4pKkYB6GiWStW9akLX3HlUim8vaaAAB4JRJPqG4WetSyPv+OC7W2o0F/cP8mPbj16Ky9DwCUAt8EtdBI5gy1PK2oSemgFo0ntePoSN5eEwAAr6S3Ps5eUJtfW6n7PnKFzl80X3/4rc36rxeOzNp7AYDf+SaoZQ+7DuZ42PVE65alD75mTD8AoNjFEynFkykFZqlHLauhplL3fuhyXbykUR9/YIt+8uuXZvX9AMCvfBPUZmNFbVHjPLU31BDUAABFLxJLSNKsjOefrL6mUvd86HKtW9akT317i3605fCsvycA+I1vgtpgON2jls+gZmZax8HXAAAfCGeC2myM5z+duuoKfeODl+mKFc369Hee1/c2HZqT9wUAv/BRUItpXmV53vfer1vWpMPHR3XkxGheXxcAgLkUjSclaVZ71CarrarQ3bdfpmu7WvR/f+/X+s5zB+fsvQGg2PkqqLXksT8tiz41AIAfZFfUZusctTOZV1Wur35gvV7bHdSffP83+tYzfXP6/gBQrPwV1PK47TFr7cIG1VSWEdQAAEUtciqozd2KWlZNZbn+9f3rdENPq/78hy/ovqcOzHkNAFBs/BPURuIKzkJQqywv00WLGwlqAICiFo1ngtocDBM5nZrKcn3lfZfq5rVt+osfb9PXn9zvSR0AUCz8E9TCMbXk8bDridYvb9K2l06eusgBAFBswrF0j9pcDRM5neqKcn35vZfqlvPa9Zf//qK+9sQ+z2oBgELni6CWSKY0HI3PytZHKd2nlkw5/frgiVl5fQAAZtup8fxz3KM2WVVFmb703kv05gs79L//c7se3Mqh2ABwOr4IasORuJyTgoH8DxORpEuXpgeKbO5j+yMAoDjN9Xj+s6ksL9PfvesiXbSkUX/83d9oXyjsdUkAUHB8EdRC4fwfdj1RY22VuloD2nhgeFZeHwCA2RaNJ1ReZqquKIxLf3VFuf759y5VZbnpv9+/WaOZ4wMAAGmF8Wmdo1OHXc9Sj5okrV/WpM19x5VKuVl7DwAAZkskllRdVbnMzOtSTlnUOE//8O5LtLN/RP/zRy/IOa6xAJDlj6A2MrsrapJ06bImnRgd1162ZwAAilA4lvBkNP+5XLcqqE/c0K0fbD6sB57lQGwAyPJHUMtsfQzO8oqaxMHXAIDiFI0XZlCTpE/c2K3Xrgrqcz/ZphcOMbgLACQfBbWayjLVVc3eJKsVLXVaUFeljQQ1AEARCseSBRvUystM//C7F6slUKU/uH+TjkfjXpcEAJ7LKaiZ2afNbJuZbTWzB8ysJl+FTcdgOD2afzb33ZuZLl3apM0ENQBAEYrEErN6QzNXC+qq9M/vW6f+k2P69L89T084gJI346BmZoskfULSeufc+ZLKJb07X4VNx2A4Nqv9aVnrljVp32BEQ5mtlgAAFItIgfaoTXTxkkb9xa1r9cudIf3zo3u8LgcAPJXr1scKSfPMrEJSraSXci9p+kIjcxPU1i/Pnqd2fNbfCwCAfIrEEwVxhtq5vP/KZXrbxQv1dz/fpSf3DHpdDgB4ZsZBzTl3WNL/kdQn6YikE865hyY/z8zuMLONZrYxFArNvNKzGAzHFKyfncOuJ7pg0XxVlps29k7tPLWhcEyP7wrp5Nj4LFcGAMDZRWJJ1VUX7tbHLDPT53/rAnUGA/rEA1t05MSo1yUBgCdy2frYJOltklZIWiipzszeN/l5zrk7nXPrnXPrg8HgzCs9g2TKaTgSn5MVtZrKcp2/aP4Z+9SOnhjTj58/rD//4Qu66e8e07r//bA+cPezete/PKVjERqjAQDeCccSqqsq/BU1SaqtqtBX3rdOY+NJfez+zYonUl6XBABzLpdP7Jsk7XfOhSTJzH4g6WpJ38xHYVM1HIkr5Wb3DLWJ1i1t0r1P9yqWSKr/REzP7B/Ss/uH9cz+YfUNRyVJgeoKrV/epN++dLGa66r0mR9v1Qfuflb3f/QKNdRUzkmdAABkjSdTiidSBd+jNlFXa0BffOeF+sNvbdHnf7pdn33LeV6XBABzKpdP7D5JV5pZraRRSTdK2piXqqZhLs5Qm2j98iZ9bcN+Xf35X2gos0rWWFupy5cv0AeuWqYrVzZrTUeDystenkDZUl+l/3bfJn3w68/p3g9dXlQXSgBA8YvGkpJUdNefWy9cqE29x/T1Jw9o3bIm3XrhQq9LAoA5M+NPbOfcM2b2PUmbJSUkbZF0Z74Km6psUJurFbWrOlt02fImtTbU6MoVC3T5imZ1twZUVnbmowFu6GnT//fuS/Sxb23WR+7ZqK9/8DLVVBZ+nwAAwB/C8YQkFfR4/jP5szeu0a8PHtf/+N5vdPmKBWqt9+QkIACYczlNfXTOfdY51+OcO985937n3JzPrX85qM3+MBFJmj+vUt/9/av15fdeqvdftVyr2+vPGtKy3nhBh/72XRfp6f1D+m/3bVIskZyDagEAkKKxTFArshU1SaqqKNNnbl2rSDzJWaYASkqu4/k9NziS3n7YMkdbH3PxjksW66/fcYEe2xXSJx7YovEkzdEA4Fdm9mkz22ZmW83sATPzbCkonAlqxTCe/3TWtDfITNp+ZMTrUgBgzhR9UAuFY6qqKFN9kVx83nP5Un32LWv1s239+r++82slU87rkgAAeWZmiyR9QtJ659z5ksolvdureiJF2qOWNa+qXCua67TzKEENQOkozk/sCQZHYgoGqmV27u2HheKD16zQ2HhKX3xwh6oryvTF375wStsnAQBFpULSPDMbl1Qr6SWvCsmuqNUWYY9a1ur2em0/ctLrMgBgzvhiRW2u+tPy6Q9e16lP3Nit7246pM/9+zY5x8oaAPiFc+6wpP+j9ITkI5JOOOcemvgcM7vDzDaa2cZQKDSr9UTjxb31UZJ62hvUOxw99bMAgN8VfVAbDMfnbDR/vn36pm7d8dqVuvepXn3hpzsIawDgE2bWJOltklZIWiipzszeN/E5zrk7nXPrnXPrg8HgrNYTKeJhIlk9HfVyTtrVH/a6FACYEz4IarE5G82fb2amP3tjj95/5TL96+P79I+P7Pa6JABAftwkab9zLuScG5f0A0lXe1VM+FSPWvFufexpr5ck7WD7I4ASUby31iSlUk7DkXjRBjUpHdb+8q3naWw8qX94eLda62v03iuWel0WACA3fZKuNLNaSaOSbpS00atiovGEykyaV8RneC5pqlVtVbl2MFAEQIko6hW1Y9G4kilXlD1qE5WVmb7w2xdqTUeDfvT8Ya/LAQDkyDn3jKTvSdos6QWlr7d3elVPOJZQXVVFUQ3emqyszLSqrV47jrKiBqA0FHVQGwwXzxlq51JeZrp0aaN2HDlJrxoA+IBz7rPOuR7n3PnOufc752Je1RKJJYq6Py1rTUe9dhwd4ToJoCQUdVALjaSvecW89XGino4GnRxL6MiJMa9LAQD4SCSWVG0R96dl9bQ36Hh0XAMjnmVeAJgzRR3UBsP+Cmprso3SbOsAAORRJJ4o6tH8Wasz10nOUwNQCnwR1II+CWovX4BolAYA5E8k06NW7LKTH3cyUARACSjqoBYKx1RVXqaGecV/8ZGk+ppKLVkwj4lWAIC8CseSRT2aP6uxtkod82u4TgIoCUUd1AZH4moJVBX1FKvJetob2NIBAMiraNwfw0Sk9O4TrpMASkFxB7VwzBcTHyda016vfaGwxsaTXpcCAPAJv0x9lNI3NPeGwhpPprwuBQBmVfEHNZ/0p2X1dDQo5aQ9A2GvSwEA+EQ45o9hIlK6T2086bQvFPG6FACYVT4IasV92PVkPUy0AgDkUSKZ0th4SrVVxd+jJkk9HUxIBlAaijaopVJOg+G471bUljXXqaayjEZpAEBeRDNb6f2yorayJaDKcuM6CcD3ZhzUzGy1mT0/4Z+TZvapfBZ3NsdHx5VMOd8FtfIy0+q2eu4UAgDyIhJLSJJvetSqKsrUGQxoBztPAPjcjIOac26nc+5i59zFktZJikr6Yd4qO4dTZ6j5bJiIlJ38OCLnnNelAACKXDao+WXro5RuE+AsNQB+l6+tjzdK2uuc683T653T4Eg6qPltRU2S1nTUazgSVyjzMwIAMFORmL+2PkrpwVsvnRjTiei416UAwKzJV1B7t6QHTveAmd1hZhvNbGMoFMrT26UPu5akYL2/holI6QuQJG3nbiEAIEd+2/oopc9SkxgoAsDfcg5qZlYl6a2Svnu6x51zdzrn1jvn1geDwVzf7pTBcFySP1fUspMf2X8PAMhVOBPU/LSitqY9fUNzZz83NAH4Vz5W1N4oabNzrj8PrzVlg+GYKstN8+dVzuXbzonG2ip1zK9hohUAIGeRuP961NoaqjV/XqW2H+E6CcC/8hHU3qMzbHucTYMjMTXXVcvM5vqt50RPez1nqQEAcubHHjUzywwU4ToJwL9yCmpmVifpZkk/yE85UxcKx9Tiw/4rwURhAAAgAElEQVS0rJ6OBu0NhRVPpLwuBQBQxPzYoyZJazoatPPoiFIpJiQD8KecgppzLuKca3bOnchXQVM1GI75sj8tq6e9XuNJp32DYa9LAQAUsWxQm1fpn62PUnqgSCSe1KFjo16XAgCzIl9TH+fc4EhcQR8HtbXZyY9sfwQA5CAST6quqlxlZf5qFehh8iMAnyvKoOac01AkphYfHnadtaKlTlXlZdpBozQAIAeRWMJ32x4laVVbvczE4C0Ac2I0ntSWvmOndinMhaIMaidGxzWedL7e+lhRXqbutgBnqQEAchKOJXw1SCSrrrpCSxfUaifXSQBz4MUjJ/WOf/6Vntk/NGfvWZRBbTBz2HVLwL/DRCSpp72Bs9QAADmJxBKqrfZXf1pWT3u9trP1EcAc6BuOSJKWLqibs/csyqAWGkkfdu3nHjVJWtNRr4GRmIYywRQAgOlK96j5b0VNkla3N+jAYERj40mvSwHgc31DozKTFjfNm7P3LMqgdmpFzcc9alJ6RU0S2zoAADMW8enWR0la016vlJN29zMhGcDs6h2OqL2hRjVzOEG3KINaaCS79dHnQa0jPdHqRbY/AgBmyK/DRKT0maOS2P4IYNb1DUW1dEHtnL5nUQa1wXBMFWWmxnmVXpcyq1oC1WoJVDPRCgAwY5F4UnU+7VFbuqBWNZVMSAYw+3qHo1rWTFA7p8FwTM2BKt+dCXM6azrqOSMGADBjkVjCtz1q5WWm1W312tnPdRLA7InGEwqNxLSsee4GiUhFG9Tivt/2mLWmo0G7+sNKJFNelwIAKDKplFM0nvTt1kcpOyGZFTUAs6dvOCpJbH2cisFwrGSCWk97veKJlA4MRbwuBQBQZCLx9MGsft36KEmr2+s1FImf6l8HgHzrHUoHNbY+TsHgSCkFtUyjNHcLAQDTFI2nx9b7ekUtM3iLNgEAs6UvG9Tm8Aw1qQiDmnMuvfWx3t+HXWd1ttaposy4AAEApi0cS6+o+XU8v/TyDU22PwKYLb3DEc2fV6n5tXM7yLDogtrJsYTiyZTvD7vOqq4oV2cwwIoaAGDaIpmg5tdhIpK0oK5KrfVMSAYwe3o9GM0vFWFQK5Uz1Cbq6ajXDs5SAwBMUySW3vpY6+MeNSl9nho7TwDMloPDUS2d4/40qQiD2mA4HdSC9aUT1NZ0NOilE2M6ER33uhQAQBGJlMDWRyk9eGv3ABOSAeRfIpnSoWOjWsaK2rllg1pJrai10ygNAJi+l6c++j+oMSEZwGw4cmJMiZSb84mPUjEGtVNbH0tjmIiUXlGTxP57AMC0hEugR01iQjKA2ZMdzb90jic+SsUY1MJxlZeZmmpLJ6i11lerqbaSFTUAwLREY9nx/P7uUetsrVN5mWknNzQB5FnvcHqlvuhW1Mys0cy+Z2Y7zGy7mV2Vr8LOZDAc04K6KpWV2Wy/VcEwM/W0N3CnEAAwLaWyopaekFzHDU0Aedc3FFVVRZnaG2rm/L1zXVH7R0kPOud6JF0kaXvuJZ3dYLh0DrueqKejXjuPjiiZcl6XAgAoEpFYQrVV5SVxc5MbmgBmQ+9QVEua5nnyOTrjoGZm8yW9VtJdkuScizvnjuersDMJjcRKqj8ta017g0bHk+objnpdCgCgSETiSdX6fDUta3V7vQ4fH9XJMSYkA8if3uGoljXPfX+alNuK2gpJIUlfN7MtZvY1M3vVT2Fmd5jZRjPbGAqFcni7tMFwvKRG82f1dGQmP3KeGgBgiiKxhAI+70/LWpO5Tu6iTw1Anjjn1DcU8eSwaym3oFYh6VJJX3HOXSIpIulPJz/JOXenc269c259MBjM4e3S/7JC4ZiCJbj1cVVbvcpM2s4FCAAwRZFYwvej+bNWtzMhGUB+DUXiisSTRRnUDkk65Jx7JvP77ykd3GbNSCyheCJVkj1qNZXlWtFSx4oaABQJLwZuTRaOJXw/SCRr4fwa1ddUMFAEQN5kW468mPgo5RDUnHNHJR00s9WZb90o6cW8VHUGp85Qqy+9HjVJ6ulo4E4hABSPOR+4NVk0nvT9aP4sM9Oa9gbtYKAIgDzpGyrSoJbxcUn3m9lvJF0s6a9zL+nMBsNxSSrJFTVJWtNer77hqEZolAaAgubVwK3JSmnro5QeKLLz6IicY0IygNz1DkVlJi1uKsKg5px7PtN/dqFz7u3OuWP5Kux0BsOZFbUSDWo9mf33u/q5WwgABe6cA7fyPWzrdMKxhAIlFNR6Ouo1Ekvo8PFRr0sB4AO9wxG1N9SoptKbnQm5rqjNqZIPapmJVpwTAwAF75wDt/I5bOtMoiU0nl96+YbmTtoEAORB31DUs0EiUpEFtdBITGUmLagrzR61RY3zVF9NozQAFIE5H7g1mXNOkXjpjOeX0lsfJSY/AsiP9BlqBLUpGQzHtKCuWuUenAxeCMxMPR31NEoDQIHzYuDWZNF4Us6ppHrUAtUVWrJgnrYzIRlAjqLxhEIjMc8Ou5bSWzOKRk97gyrLiypb5t2ajgb9YPNhOedkVpqBFQCKRHbgVpWkfZI+OJdvHoklJEm1JRTUJGl1WwNbHwHkLDua38utj0X16X3b1cu9LsFzPe0NCsd6dejYqJZ4+B8OAODsnHPPS1rv1ftH4klJKqmtj5K0pqNev9w5oFgiqeqK0vrZAeRP75D3Qa20l6eK0MsDRdjWAQA4s+yKWqkceJ3V096gZMppz0DY61IAFDGvz1CTCGpFZ3UbjdIAgHMLZ4JaKY3nl14eKML2RwC56BuOqqGmQo213g0xJKgVmbrqCi1rrmXyIwDgrKLx0uxRW9Zcq4oyY0UNQE7SEx+9GyQiEdSKUk87kx8BAGcXjpVmj1pleZmWt9Rpb4igBmDm+oYiWurhtkeJoFaUetobtH8ootFMozgAAJOd6lErsRU1SeoM1rGiBmDGEsmUDh0b1TKPB/cR1IrQmo4GOSft6mdVDQBweqfG85fYMBFJ6moNqHcoqvFkyutSABShIyfGlEg5TweJSAS1orSmIztQhD41AMDpRTJbH+uqSmvroyR1BgNKpNyp8doAMB0vj+anRw3TtKSpVrVV5dpOnxoA4Awi8YRqKstUUV56l/qu1oAk0acGYEZ6hyOSvB3NLxHUilJZmWl1e71e5Cw1AMAZhGOJkhvNn7UymA5q9KkBmIm+oaiqysvU3lDjaR0EtSK1uq2eCxAA4IyisURJ9qdJ6bPj2htqWFEDMCO9Q1EtXjBPZWXmaR0EtSLV1RrQcCSuoXDM61IAAAUoHEuW5MTHrK7WgPZyQxPADPQORz2f+CgR1IpWd1t6oMhuLkIAgNOIxBIld4baRJ3BOu0NReSc87oUAEXEOaeDBXDYtURQK1rdmUZpghoA4HSi8dLd+iilV9TCsYQGRth5AmDqhiNxhWMJLWVFDTPVMb9GdVXlbOsAAJxWKQ8TkdIj+iUGigCYnt7h9Gh+ryc+SjkGNTM7YGYvmNnzZrYxX0Xh3MxMXW312j3AiH4AwKtFYknVlfDWR0b0A5iJvqHCCWr5uNV2vXNuMA+vg2nqbg3o8V0hr8sA4CORWKKkB1D4San/bxmsr1Z9dQUragCmpXcoKjNpcZP3QY2tj0WsuzWggZGYTkTHvS4FgE/89/s367a7n/W6DOTIOadIPKG6Eu5RMzN1tgZYUQMwLb3DEbU31Kim0vsdCbkGNSfpITPbZGZ3nO4JZnaHmW00s42hEKs/+ZTd1rEnxPZHALk7MTquX+0d1Or2eq9LQY7GxlNKOZX0ipqU7lNjRQ3AdPQNRQtikIiUe1C71jl3qaQ3SvqYmb128hOcc3c659Y759YHg8Ec3w4TdbdmRvT3cxECkLtf7hjQeNLpDee1e10KchSOJSSppMfzS+kbmv0nYxoZY+cJgKnpHY4WRH+alGNQc84dzvw6IOmHki7PR1GYmkVN81RTWcaIfgB58eDWo2qtr9YlSxq9LgU5isbTQa2Ux/NL6bPUJGlvKOJxJQCKQTSeUGgkVvwramZWZ2b12a8lvV7S1nwVhnMrLzN1BgMENQA5G40n9eiuAb3hvHaVlZnX5SBH2RW1kt/6mJ38yHUSwBT0ZUbzLy2Aw66l3KY+tkn6oZllX+dbzrkH81IVpqy7NaBn9w97XQaAIvfYrpDGxlO65Xy2PfpBJJaUpJI+R02Sli6oVWW5aQ8DRQBMwanR/AWyojbjT3Dn3D5JF+WxFsxAd1u9fvT8SxoZG1d9TaXX5QAoUg9tO6rG2kpdvmKB16UgDyKnVtRKu0etsrxMy5rrWFEDMCV9BXTYtcR4/qL38oGe7L8HMDPxREoPb+/XTWvaVFnOZcEPInG2PmZ1BRnRD2BqeoeiaqipUGNtldelSCKoFb3uTFDb3c+IfgAz8/S+IZ0cS+gWpj36RoQetVM6W+vUOxTVeDLldSkAClx64mNh9KdJBLWit3RBrarKy9h/D2DGHtx2VLVV5bq2u8XrUpAn4WyPWolPfZTSO08SKafeTO8JAJxJ31BESwtk26NEUCt6FeVlWhms0x7OUgMwA8mU00Pb+nV9T6tqKku7n8lPopkVtdoS71GT0odeS+LgawBnlUimdOjYaMEMEpEIar7Q1cqIfgAzs7nvmAbDMbY9+kw4nlBVRRk9h3o5qNGnBuBsjpwYUyLlCmaQiERQ84Xu1nodPBbVaDzpdSkAisyDW4+qqrxM1/e0el0K8igSS5T8aP6suuoKdcyvYfIjgLPKbo9ewooa8qmrNSDnuFsIYHqcc3pw61G9pruFv9T7TCSWLPnR/BN1tTL5EcDZ9Q6nJ6gzTAR51d3G/nsA07ftpZM6fHxUb+CQa9+JxBKqY5DIKZ3BgPaGInLOeV0KgALVNxRVVXmZ2htqvC7lFIKaDyxvrlN5mWn3ACP6AUzdg1uPqrzMdNOaNq9LQZ5F4glG80/QGaxTOJZQ/8mY16UAKFC9Q1EtXjBP5WXmdSmnENR8oKqiTMuba7WbyY8ApuHBbUd1xYoFWlBXGAd7In/CsSRBbYLOVnaeADi7vuFoQU18lAhqvtHdWs8FCMCU7RkY0Z6BsG5h26MvRWMJ1VXRo5bVxeRHAGfhnEsHtQLqT5MIar7R3RbQgaGIYgkmPwI4t59t65ckvX4tQc2PIjG2Pk4UrK9WfU0FQQ3AaQ1H4grHElrKihpmQ1drQCkn7R+MeF0KgCLw4NajumRpo9rnF07TNPInzHj+VzAzdQYD7DwBcFq9w+nR/IV0hppEUPON7tZ6Sey/B3Buh45F9cLhExxy7VPOOUXijOefjBH9AM6kb4ighlm0MlinMhMDRQCcU3bb4xsIar4US6SUTDnVMp7/FTqDAfWfjOnk2LjXpQAoMNnDrhc3EdQwC2oqy7V0QS0ragDO6Wdbj6qnvV7LWwqraRr5EYklJImtj5N0ZSY/7gvRIgDglXqHI2pvqFFNZWHtRCCo+UhXaz1nqQE4q9BITM/1DjPt0ccisfRQKYaJvFJnMH1jghuaACbrG4pqaYFte5QIar7S1RrQ/sGIxpMpr0sBUKB+/mK/nBNBzcci8fSKGuP5X2npglpVlht9agBepbcAz1CTCGq+0t0a0HjSndpnCwCTPbjtqJY312p1W73XpWCWZLc+sqL2ShXlZVreXMeKGoBXiMYTCo3ECm6QiJSHoGZm5Wa2xcz+Ix8FYea629L77/ew/RHAaZwYHdev9gzqDee3y8y8LgezJExQO6POIJMfAbzSweFRSdLSAjvsWsrPitonJW3Pw+sgR53BdFBj8iOA0/nFjn4lUo6x/HPIi5uZ2R41hom8WldrQL1DUcUTtAgASOsdSg8Y8t3WRzNbLOnNkr6Wn3KQi7rqCi1qnKfdbOsAcBoPbj2q9oYaXbS40etSSsmc38zM9qjV0qP2Kp2tdUqmnPqGmfwIIK2vQA+7lnJfUfsHSX8i6Yy3pszsDjPbaGYbQ6FQjm+Hc+luCxDUALxKNJ7QY7tCesN5bSorY9vjXPDqZibj+c+sK5juzdwzQFADkNY7FFVDTYUaa6u8LuVVZhzUzOxWSQPOuU1ne55z7k7n3Hrn3PpgMDjTt8MUdbem998nU87rUgAUkMd3hTQ2ntIbmPY4l856M3O2bmQyTOTMVmZG9NOnBiCrdziqZQXYnybltqJ2jaS3mtkBSd+WdIOZfTMvVWHGulvrFU+kdHCYyY8AXvbg1qNqqq3U5csXeF1KSZjKzczZupEZiSdVWW6qqmCw82R11RVaOL9Ge9l5AiCjbyiipQXYnyblENScc3/mnFvsnFsu6d2SfuGce1/eKsOMdJ2a/MhFCEBaPJHSI9sHdPPaNlWU85f3OeLZzcxILMFq2ll0tga0hxU1AJISyZQOHRstyMOuJc5R852u1szkR4IagIxf7R3USCzBIddzyMubmeFYQnVVBLUz6QwGtHcgLOdoEQBK3ZETY0qkXEFOfJTyFNScc486527Nx2shNw01lWpvqNFuzlIDkPGzbUcVqK7Q1Z0tXpeCORCJJRgkchadrQFF4kkdPTnmdSkAPHYgM5q/UFfU+CT3oe62AFsfAejw8VH962N79f1Nh3XL+e2qqWRcuxecc49KenSu3i8aT6q2mv+tz6Qrc+bo3oGIOubP87gaAF4YGRvX3RsO6Gsb9qmmskyr2uq9Lum0CGo+1BkM6DsbDyqVcozhBkrQ/sGIvvLoHv1g82GZSb91yWL98RtWe10W5kiYFbWz6mxNT3fbMzCia7tZZQZKSSSW0D1PHdCdj+/T8ei4bl7bpj+6eZVaAtVel3ZafJL7UHdbQNF4Ui+dGNXipsJcygWQfzuOntSXf7lX//mbl1RZXqb3XblMd7x2pRY2smpQSiKxhNrqa7wuo2AFA9Wqr6nQ3hBnqQGlYmw8qW8+3auvPLpXQ5G4rl8d1B/dvFoXLJ7vdWlnRVDzoe7W9PLt7oEwQQ0oAc8fPK5/+sUePby9X3VV5froa1fqI9euVLC+MO8QYnZFYkmmPp6FmamrlRYBoBTEEkk98EyfvvzoXoVGYrq2q0WfvnmV1i1r8rq0KeGT3Ie6M5Mf9/SHdf3qVo+rATAbnHN6Zv+wvvzLPXpi96Dmz6vUp27q1u1XL1djbZXX5cFDkXhCdfSonVVnMKDHd+XvkHEAhSWeSOm7mw7qn36xR0dOjOnyFQv0T++5RFesbPa6tGkhqPlQU12VWgJVTH4EfOh4NK6fbj2q7248qM19x9USqNKfvrFH77tyGX1JkMQ5alPR1RrQ9zYd0smxcTXUVHpdDoA8OXQsqv964YjufapXh46N6pKljfp/33mRrulqllnxzW3gk9ynuloDnKUG+MRoPKlHdvTrR1te0mO7BjSedFrZUqfPvWWt3n35UqY54pRYIqnxpCO0n0PnqcmPYV2ytDi2QAE4vZeOj+q/Xjii/3zhiLb0HZckXbK0Uf/P287X61YHizKgZfFJ7lPdrfX60ZbDcs4V9X+gQKlKJFN6cu+Qfvz8Yf1s61FF4km11lfrtquW620XL9L5ixr4/zZeJRpLSpJqqwjvZ9OVaRHYG4oQ1IAi1H9yLB3OfnNEG3uPSZLWdjToT25ZrTdf0KFlzXUeV5gfBDWf6m4LaCSW0MBITG0NTP8CioFzTlsOHtePtxzWf75wRIPhuOprKnTrhQv1tksW6ooVzSrnyA2cRTiWkCS2Pp7DkqZ5qiovY6AIUEQGRsb04Naj+o/fHNFzB4blnNTTXq8/fv0qvemCDq3MrJT7CZ/kPpW9W7i7P0xQAwpYMuW0pe+YHnqxXz/dekQHh0dVXVGmm9a06a0XL9TrVgdVXcHqCKYmEk8HNbY+nl1FeZmWt9Rqb4igBhQq55z2hsJ6ZPuAHtk+oI29w0q59NC8T924Sm++sF1drYV5UHW+8EnuUy+P6OdAT6DQjI0n9au9g3poW78e3t6vwXBcleWmqztb9MkbV+kN57WpngEHmIFIZusjK2rn1hkMaOdRhm4BhSSeSOm5A8N6eHu/frFjQL1DUUnSmo4G/eH1Xbr1ooVa1ebvcDYRn+Q+1RKoUmNtJQNFgAJxYnRcj+4c0EPb+vXozgFF4kkFqit0fU+rXr+2Ta9bHSScIWeR7NZHetTOqas1oIde7Fc8kVJVRZnX5QAlaygc06M7Q/rFjgE9viukkVhCVRVluqazWR95zUrd2NOqhY3zvC7TEwQ1nzIzdbcGtKefoAZ45aXjo3pkx4Ae2nZUT+0dUiLlFKyv1tsuWaTXr23TVZ3NbGtEXkXoUZuyzmBAyZRT71BE3SV0hx7wWirl9OKRk3psVzqcbe47Juek1vpq3XpRh27oadM1Xc2qreJzjH8DPtbVGtBPtx5l8iMwR5Ipp18fOq5fbB/QIzsGtP3ISUnSypY6feQ1K/X689p08eJGlTEQBLMkO0yEHrVzOzWiPxQmqAGzbDgS1xO7Q3psV0iP7xrUYDgmSTp/UYM+cUO3blrTpvMWNnB9nIRPch/raq3X8ehBDUXiaglUe10O4EsjY+N6YvegHtk+oEd3DmgoEld5mWn9sib9+Zt6dENPq++bnVE4onHG80/VymB6fDeTH4H8y964fGxnOpz9+tBxOSc11VbqNd1BXbcqqNesalFrPQPvzoag5mPdEyY/EtSA/OkdiuiR7QP6xY4BPbN/SONJp/nzKnX96qBuWNOm67qDml9LvxnmHuP5p66uukIL59dobyjidSmAL/SfHNPju0J6fPegntgd0vHouMpMumhJoz514ypdtzqoCxbN55iZaeCT3Me629JBbc/AiK7qbPa4GqB4xRJJPbt/WL/cEdKjuwa0L/MXu1VtAX342pW6cU2rLlnSqIpyBhLAW5FYQhVlpmqGY0xJZ2uAEf3ADEXjCT2zf1hP7BrUhj0h7crMRQjWV+umNW26blVQ13a1qKmuyuNKixdBzcfaG2oUqK5g8iMwA4eORfXozpAe3TmgJ/cMaXQ8qeqKMl25slkfuHKZbuhp09LmWq/LBF4hGk+qrrqCvuQp6gwG9N2NB+nlBqYglXLa9tJJPb47pA27B7Wp95jiyZSqK8p0+YoFeue6xbq2K6g1HfX8/ylPCGo+Zmbqag1oN5MfgXOKJ1La2DusR3eG9MsdA6ducCxZME+/s36xrl/dqitXNmsevT8oYOFYgtH809DVGlAkntTRk2PqmF+a47+Bs3np+Kg27B7U47tDenLPoI5FxyWlzzW7/Zrlek13iy5bvkA1lXzuzIYZBzUzq5H0uKTqzOt8zzn32XwVhvzobg3olztDXpcBFKQjJ0ZPrZpt2D2oSDypynLTFSua9buXLdH1Pa1a2VLHnUEUjUgsQX/aNGQnP+4ZCBPUAEknx8b19N4hbdgzqA27B7VvML3VP1hfret7WvWa7hZd08UQkLmSy6d5TNINzrmwmVVK2mBmP3XOPZ2n2pAH3W0BfXfTIR2PxtVYyx5hlLbxZEqbeo/plzsH9NjOkHYcHZEkLZxfo7devEg39LTq6s5m/qKLohXJbH3E1HRlhm69+NJJvaY76HE1wNwbT6b0/MHjemL3oDbsDunXh04omXKaV1muK1Yu0HuvWKpru1u0uo3tjF6Y8ae5c85Jyu6pq8z84/JRFPKnOzMWfM9AWOuXL/C4GmDu9Z8c06M7B/TozvSe+pHMsIXLli/Qn7+pR69b3aru1gAXIPhCekWNLUhT1RKo0kWL5+vvfr5L5y2cr2u7W7wuCZhVzjntDYUzwWxQT+8bUiSeVJlJFyxu1B9c16lru1t06dImVTGUyHM53XYzs3JJmyR1Sfqyc+6Z0zznDkl3SNLSpUtzeTvMQPZu4W6CGkrEeDKlzb3H9OiukB7dGTp16HR7Q41uvahD161q1TVdzaqvYXw+/CcSS6i5jiE3U2Vm+voHL9d7v/q0PnzPc7rrtssIa/Cd/pNjenLPoDbsGdSTewbVfzJ92PSy5lq9/ZJFek13i65a2cKxMgUop6DmnEtKutjMGiX90MzOd85tnfScOyXdKUnr169nxW2OLWqcp3mV5QwUga/1nxzTYzvTo/Of2D2okbH0qtm6ZU36H7f06PqeINs2UBLCsYQCbH2clgV1VfrWR688Fdbuvv0yXdNFWEPxGhkb1zP7hk8Fs+xwrAV1Vbq6s1nXdqX7zJYs4KZOocvLp7lz7riZ/VLSLZK2nuv5mDtlZZnJjwMjXpcC5M3ZVs3efEGHXrc6qKu7WtTAqhlKTJQetRlZUFel+z9yhX7va8+kw9ptl+lqwhqKRDyR0pa+Y3py75Ce3DOo5w8eVzLlVFNZpstXNOt31i/WNV0tWtPeoDIOmy4quUx9DEoaz4S0eZJulvTFvFWGvOlqDeiJ3YMaG08yPhVF6+iJMT2+68yrZq9bHVRPO6tmKG3hWEK19KjNSHOgWvd/5Aq996vP6EOENRSwZMpp20sn9OSeIf1q76CeOzCssfGUyky6MNNndk1Xiy5d1qjqCj4Pilkut906JN2T6VMrk/Qd59x/5Kcs5NMbz2/XD7cc1kfv3ag737+ec6BQFGKJpDYdOKbHdoX02K6XJzSyagac3ngypXgipUAVK2oz1Ryo1v0fvUK/R1hDAXHOac9AWE/uGdSv9g7p6X1DOjmWkCStagvo3Zct1dWdzbpiZbPmz+Oa6Ce5TH38jaRL8lgLZsnrz2vX37zzQv2P7/9GH/rGc7rr9vWq5UKOAtQ7FNHjmWD2q71DimbONbt8xQL92Rt79NpVrJoBZxKNJSWJrY85asmEtfd+9el0WLv9Ml3dSVjD3HHOqXcoqqf3DempfUP61d4hhUbSA0CWLJinN13Qoas6m3VVZzPnmfkcn+Yl4l3rl6iqvEx/9J3nddvdz+ru2y9j6h08F40n9PS+IT22Mx3ODgxFJUlLF9TqnesW67pVQV25knPNgKkIx9N32BnPn7uWQPWpASMf+sZz+vrtl+uqzmavy4JPOed0IBPMngOB6fwAACAASURBVNk3pKf3DevoyTFJ6f8Wr+lq1tWdzbq6kwEgpYa//ZSQt1+ySJXlZfrkt7fo/Xc9q3s+dDlL5JhTyZTT1sMntGHPoB7fFdLmvmMaT6Ybnq/ubNEHr1mh61YFtbylzutSgaITiWWDGpf2fMiGtffcmQ5rd99+GWENeTExmGX/yY7MD9ZX68qVzbpixQJdubJZncE6dpGUMD7NS8ybL+xQZbnpY9/arPd97Rnd9+HL1Vhb5XVZ8LH/n737Dm/7Ou/+/7lBcBPgXhokNUnRcmxJ9LYTO3bsxHHiZjRxmuUsN4mz0/m0Tdv0SX9NmzbJk9HEzbbr7Nkk9YztxNuSvLQ3NUmBEvcCCZzfHwBlWpYskATxxXi/rosXB0Dg5tcUjz8459znYO+IHtzZoz/s7NFDu3vUNzIhSWpvDOrdly7RZctr1dFSSaMbYI6GCGpJV1NWqO/f9FxY+/a7ztOFSwlrmJlI1GlH96DW7zuux/f16vG9LwxmFy6NBbOlNQQzPIe/5jno6rMadMvbO/Snt23QW/7rMd32nvNVXVbodVnIEgPx81v+sDOkB3f2aE/PsCSpPlioK9vq9dKVsfNbavidA5Jqao8a56gl1/RlkO/69hP68p+s0ZWr6r0uC2lsbCKiZw7264l9x/XEvuPa0NmrwXjzj/pgoc5fUq2L4uFsCcEML4K/5jnqirY6feMdHXrf99brLf/1qG577wVsSMWsjIYj2tDZq4d3x7pRPXOwT1EnFeX7dOHSar31wmZdtqJGK+rKGIyAeTQ1o1ZCZ9+kqw3Ewtpbv/Go3vPd9bpoabX+7JpWrWuu9Lo0pIG+kbA2dPbqiX29Wr/vuJ452K9wJCpJWlFXputeskDntVTqvJYqLaosZixEwghqOeylK2v17Xedp/d8Z71uuOVR3f7eC9VQTljDi5uIRPX0gT49vDt2fsvGzj6FI1H5faZzFlfo5iuW66Jl1VrXXMn5LUAKTe1RY0ZtftQGCvWrD12q2x/br6/ev0tv+M+HdWVbnT55davaFwS9Lg8pMhmJanv3oJ7c3xd7O9CrPaHYyhG/z3T2onLdeEmLzmup0rrmSlWVsr0Es8df8xx38bIafe895+td335Cb77lEd3+vgu1sKLY67KQRiYjUW05MqBH4y2CH997XCPhiMxi+8xuvKRFFy2r1nktVfwPIuChkTB71OZbUX6e3n3pEr35vMX6zsP79PUHduva//cHXfeSRn38FSu1rLbM6xKRZEcHx/TU/j49eaBPT+7v1TMH+zUSji0zri4t0JqmCr1+zUKta67SuYsrOKsWScVfc+i8lird+p7z9Y5vPa43f/0Rff99F9L+NYeNT8bW1j++97ge23tcG/Yd13B8UFpeV6Y3rlsUO1hzSbUqeaUQSBtDU+eocU7mvCst9OvmK5brbRc065Y/7Na3H9qn3z57RG9ct0gfuXKFFlUyhmai/tEJbT7Ur02H+/XMwX49daBPB3tHJcVmy85aENSbOhZrTVOF1iyu1OIqljFifvHXHJKkNU2Vuv29F+pt33xMb/zaw/qLa9p0/bkL5M/zeV0a5tlIeFIbO/v0+N5jemzvcT15oE/hydja+tb6gF6/dpHOX1Kl85dUqT7I0lggXQ2PT8pnsf2hSI3yknz9+TVtetclS/TV+3brtkc79YsnD+tPLmjSB69Yxt7vNNY/MqFNh/v17KHY26ZD/eqMn+UpSQsrinXu4grdeHGL1jRV6KwF5XQnRsoR1HDC2YvK9YObLtQnfvS0Pvnjp/Wl3+3Uh1++gsCWZboHxrSxs1cb98c2Pm861K/JqJPPpNULy/WOC5t1/pIqnddSxYwZkEGGxidVWujnFX4P1JQV6lOvadd7L1uiL/1up259tFM/fOKA3tSxSNesbtB5LVXKZxz1hHNOR/rHtL1rUFu7BrT50ICePdSv/cefH8rOXliuN3Us1uqF5Vq9IEg3bKQFc86l7Mk6Ojrc+vXrU/Z8mJ1o1Onurd364j07teXIgFqqS/Shl6/QHxHYMk54MqrNh/u1cX+fNu7v1ZOdvTrcPyZJKvD79JKF5bpgaZXOX1KttU0VChRxADqSw8w2OOc6vK4jUyRjfPyLnzytP+zs0SN/fWWSqsJs7e0Z1hfv2aHfbupSeDKqYJFfV7TV6apV9XpZa62C/K2dFwNjE9reNahtXYPa3jWg7V2D2t41qIF4a3xJWlQZC2WrF5afeE/DD6RaomMkM2p4AZ/PdM1ZDbq6vV53b+nWF+7ZqT+Lz7B96Irlet2ahQS2NOScU9dAbNPzxv292ri/T88e6j+xjHFhRbHWNlfqvU2VWttcqfbGoAr8/HcEssXweITW/GliSU2pvnDDGn1mfFJ/2Nmje7d263fbjuqXTx2W32e6cGm1rlwVC27sCZ+53uGw9vQMa2/PsHYdHToRyqZeiJSkQKFfrQ0BveacBWptCKi1PqC2hqDKSwjJyBzMqOGMnHMnAtuWIwNqri4hsHnMOadDfaPadGhAm+Lr6zcf7lfPUFjSc7Nla5srtWZxhdY2V7K/DCnFjNrMJGN8fOe3HlffSFi//NClSaoKyRSJOj11oFd3bzmqe7Z2a9fRIUlSW0PgxExbW0OAlQ1xI+FJ7Y2Hsb2h2PupcNY/OnHifvl5pmW1ZbEw1hBQW0NArQ1BLSgvYhkw0laiYyRBDQlzzumerUf1hXt2aPPhATVVlejmK5bp2rMbGVjmkXNOB3tHT2x2joWyAR0fjoWyPJ9pRV2Zzl5YrrMXlesliyqYLYPnCGozk4zx8Y+/9rDy83y6/X0XJqkqzKe9PcO6d2u37t7SrfWdvYpEY/8/trCiWK0NAa2sj4WOlfUBLasrzbpzKQfHJnS4b0yH+0Z1qG9Uh0+8jWn/8RF1DYw97/6N5UVaUlN64m1pbamW1JRpUWUx+/+QcVj6iKQzM72ivV5XrarTvVuP6gv37tBf/vRZ/c3PN2ldc6Uub63Ty1bWalVjgFexZun4cFjbuwa1o/u5t+nr6/0+08r6gF6xql6rF8U2PK9qDNKJCoCGxiNaWMFem0yxpKZU771sqd572VL1jYS1fl+vtk/7u/+HnSFNRGLhLc9nWlJTqtb6WHBbUV+m2kChqkoLVFNaqGBxejSRiUSd+kbCOj4c1rHhsHrj748Ph3V0cOx5wWxw2r4xKTa+NZQXaUFFsS5eXq2lNbEgtqSmVC01JSrh2AnkIH7rMWNmpqva63Xlqjo9vve47tse0gM7QvrsHdv02Tu2qS5QqJetrNXlrXW6dEWNyouZbTvZwNiEdnYPnRTIhtQzNH7iPsGi2Pr6685ZoPbGoM5eWK7WhgChDMgAZrZY0vck1Utykm5xzn1xPp9zeHxSZYX8fchEFSUFuqq9Xle115/42kQkqr09wycaYmzvHtSmw/367aYjOnkxlN9nqiwtUHVpgarLClRVWhj7uLRAlaUFKvD75PeZ8nym/Dyf8nx24nO/L/55XuzzicmoRiciGpuIamwiorGJyAs+n/pa/+iEjseD2PHhsPpGJ15Q23M/Y74WVhRrcVWJLlxarQUVsVDWWF6shRXFqg0UKs/nfdgE0glBDbNmZrpgabUuWFqtv3pVm7oHxvTAjpAe2B7SnZu79OMNB5XnM61ZXKHLW2v1spV1amsM5MQSBeecekcmtO/YsPYfG3ne+85jIzoWX7YoSSUFeVpRH9AVrbUnlru0NgRUFyhMi1dIAczKpKRPOuc2mllA0gYzu9s5t2W+nnA43p4f2SE/z6eV8Rm015zz3Nen9m4dG4qFo56h8RNBqWcorOPD43q2t0/HhsIaHJ88/RPMUqHfp+KCPBX58xQs9quqtEBtDUFVluafCIhTobEq/lZZUsByfGAW+IuOpKkPFulNHYv1po7FmoxE9dSBPj2wI6T7t4f0ubt26HN37ZDfZ2qqKtHS2lItqy3T0tpSLa0t07LasoxqjzsRiSo0OK7ugTF1D4zr6OCYjvTH1tV3HhtWZ8/I8wZIM2lBebGaqkp09Vn1aqoq1Yq62ObnhRXF8vEqIpBVnHNHJB2JfzxoZlslLZQ0f0EtPKkyglrWKynw66wF5Qndd3wyor6RCYUno4pEnSajLv7+pM8jsa9NRp0K83wqzM9TcX6eivKfC2XFBXkqyPMxXgEpxF90zAt/nk8dLVXqaKnSJ69uVc/QuB7a1aMd3YPafXRYe3qG9PsdPQpHoie+p6IkX0trYsFtaW2pGoJFChblK1icr/LifAWL/QoW5aukIC+pM03OOY2EIxocm9TQ+IQGxiY1ODapwbEJ9Y1M6OjguI4OjD0vlB0bDp9y6cniqhI1VZVoXVOlmqpL1VJdoubqUi2qLGbJIpCjzKxF0hpJj5309Zsk3SRJTU1Nc3qOyUhUYxNR9vHgeQr9eaoPMvYAmWrWf9G9WH+PzFVTVqjrz134vK9Fok6Heke1OzSk3aEh7ekZ1p7QkB7YEdJPNhw87WP5faZgcb6CRf4TIa7Q75NzsV9E51z8/XOf68TnThOTTgNjE/FgFnub6rZ1Kmax+uuDhWosL9I5iytUHyxUfbBI9cFC1QWKVB8sUlVpAevrATyPmZVJ+qmkjznnBqbf5py7RdItUqzr41yeZzgckSSVskcNALLGXF56S/n6e2SXPJ+pqbpETdUluqKt7nm3DY5N6NhQWANjE+ofndDA6KQGxiY0MBr/fCz2tf7458cjUU1NsplMZpJJkpks9i7+3pSfF5v5ChT6FSjyK1CUr0CRX2XTPo7dFguBNWUFnBcHYMbMLF+xkPbfzrmfzedzTUaiWr0wqMby4vl8GgBACs06qHmx/h65IxaY6BYJIDNZbH32NyVtdc79x3w/X3VZoX794cvm+2kAACmUlGmC062/j992k5mtN7P1oVAoGU8HAEC6u0TS2yW93Myeir9d63VRAIDMMeddxy+2/l5K7hp8AAAygXPuQcVXYAMAMBtzmlFL5fp7AAAAAMgVsw5qqV5/DwAAAAC5Yi4zaqy/BwAAAIB5MJeuj6y/BwAAAIB5wOFQAAAAAJBmCGoAAAAAkGYIagAAAACQZsy51B1tZmYhSZ1zfJgaST1JKCfbcZ0Sx7VKDNcpcVwrqdk5V+t1EZkiSeOjxO9eorhOieE6JY5rlRiuU0xCY2RKg1oymNl651yH13WkO65T4rhWieE6JY5rBa/wu5cYrlNiuE6J41olhus0Myx9BAAAAIA0Q1ADAAAAgDSTiUHtFq8LyBBcp8RxrRLDdUoc1wpe4XcvMVynxHCdEse1SgzXaQYybo8aAAAAAGS7TJxRAwAAAICsRlADAAAAgDSTtkHNzF5pZtvNbJeZ/dUpbi80sx/Gb3/MzFpSX6X3ErhOnzCzLWb2jJnda2bNXtSZDs50rabd7w1m5swsJ9vHJnKdzOxN8d+rzWZ2e6prTAcJ/NtrMrP7zOzJ+L+/a72oE9mH8TFxjJGJYXxMDONj4hgjk8Q5l3ZvkvIk7Za0VFKBpKcltZ90nw9K+lr84xsk/dDrutP0Ol0hqST+8Qdy8Toleq3i9wtI+r2kRyV1eF13Ol4nSSskPSmpMv55ndd1p+l1ukXSB+Ift0va53XdvGX+G+Nj0q9Vzo+RjI9J/X3K+fFxBteKMTKBt3SdUTtf0i7n3B7nXFjSDyRdf9J9rpf03fjHP5F0pZlZCmtMB2e8Ts65+5xzI/FPH5W0KMU1potEfqck6Z8kfVbSWCqLSyOJXKf3SfqKc65XkpxzR1NcYzpI5Do5ScH4x+WSDqewPmQvxsfEMUYmhvExMYyPiWOMTJJ0DWoLJR2Y9vnB+NdOeR/n3KSkfknVKakufSRynaZ7j6T/ndeK0tcZr5WZrZW02Dn3m1QWlmYS+Z1aKWmlmT1kZo+a2StTVl36SOQ6/YOkt5nZQUm/lfTh1JSGLMf4mDjGyMQwPiaG8TFxjJFJ4ve6AKSGmb1NUoekl3ldSzoyM5+k/5B0o8elZAK/Yss7Llfs1effm9nZzrk+T6tKP2+R9B3n3L+b2UWSbjWz1c65qNeFAXg+xsjTY3ycEcbHxDFGJiBdZ9QOSVo87fNF8a+d8j5m5lds2vRYSqpLH4lcJ5nZVZL+RtJrnXPjKaot3ZzpWgUkrZZ0v5ntk3ShpF/l4IbpRH6nDkr6lXNuwjm3V9IOxQamXJLIdXqPpB9JknPuEUlFkmpSUh2yGeNj4hgjE8P4mBjGx8QxRiZJuga1JyStMLMlZlag2GboX510n19Jemf84zdK+p2L70jMIWe8Tma2RtLXFRuAcnWttHSGa+Wc63fO1TjnWpxzLYrtVXitc269N+V6JpF/e79Q7NVCmVmNYks99qSyyDSQyHXaL+lKSTKzVYoNQqGUVolsxPiYOMbIxDA+JobxMXGMkUmSlkEtvqb+Q5LulLRV0o+cc5vN7NNm9tr43b4pqdrMdkn6hKTTtpPNVglep3+TVCbpx2b2lJmd/A8lJyR4rXJegtfpTknHzGyLpPsk/blzLqderU/wOn1S0vvM7GlJ35d0Y47+zzKSiPExcYyRiWF8TAzjY+IYI5PHuCYAAAAAkF7SckYNAAAAAHIZQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ0AAAAA0gxBDQAAAADSDEENAAAAANIMQQ2IM7N9ZhY2s5qTvv6kmTkza0ngMW40sweTXNcNZrbdzPrN7KiZfdfMgsl8DgAAXky6jpEnPf698Vr88/UcQCoR1IDn2yvpLVOfmNnZkkpS9eSnGVweknSJc65c0lJJfkn/N1U1AQAQl45j5NRtb5WUn6pagFQgqAHPd6ukd0z7/J2Svjf9DmZWbmbfM7OQmXWa2d+amc/MVkn6mqSLzGzIzPpe7P7x2240s4fM7PNmdkzSP5xckHPugHOuZ9qXIpKWJ/WnBgDgzNJujJx6DEl/L+kvkv4TAx4iqAHP96ikoJmtMrM8STdIuu2k+3xJ0tTs1ssUG7Te5ZzbKun9kh5xzpU55ype7P7THu8CSXsk1Uv6zKmKMrNLzaxf0qCkN0j6wlx/UAAAZigtx0hJ/yzpPyV1ze3HA9ILa3iBF5p6xfABSVslHZq6YdrAdK5zblDSoJn9u6S3S/rmyQ+U4P0PO+e+FP948lQFOecelFRuZgslvU/Svrn+kAAAzEJajZFm1iHpEkkflbQoKT8hkCYIasAL3Srp95KW6KQlHZJqFFsD3znta52SFp7msRK5/4FEC3POHTKzOyT9QNLaRL8PAIAkSZsxMr5E8quSPuqcmzSzROoHMgZLH4GTOOc6Fdswfa2kn510c4+kCUnN077WpOdeUXQzvP+pvudM/JKWzfB7AACYszQbI4OSOiT90My6JD0R//pBM7vsxX8SIP0R1IBTe4+klzvnhqd/0TkXkfQjSZ8xs4CZNUv6hJ5bo98taZGZFSR4/zMys7eaWVP842bF1ujfO6efDgCA2UuXMbJf0gJJ58bfro1/fZ2kx2b7wwHpgqAGnIJzbrdzbv1pbv6wpGHFNjc/KOl2Sd+K3/Y7SZsldZlZTwL3T0S7pIfNbFixVv3bFdunBgBAyqXLGOliuqbeJIXiN3U758Iz/LGAtGPOzXTVFQAAAABgPjGjBgAAAABphqAGAAAAAGmGoAYAAAAAaYagBgAAAABpJqUHXtfU1LiWlpZUPiUAwAMbNmzocc7Vel1HpmB8BIDckegYmdKg1tLSovXrT9fNFQCQLcys0+saMgnjIwDkjkTHSJY+AgAAAECaIagBAAAAQJohqAEAAABAmiGoAQAAAECaIagBAAAAQJohqAEAAABAmiGoAQAAAECaIagBAAAAQJrJ2qD22J5j+uB/b9Dg2ITXpQAAkBYOHB/RNx/cq7d/8zH992OcSQ4A6cx/pjuY2bckXSfpqHNudfxrVZJ+KKlF0j5Jb3LO9c5fmTN33/aQfvtsl8KTUd3y9g75fOZ1SQAApJRzTluODOiuzd26a0u3th4ZkCRVluTrDzt7VFbo1/XnLvS4SgDAqZwxqEn6jqQvS/retK/9laR7nXP/YmZ/Ff/8L5Nf3uyFBsflM+merUf173dv159f0+Z1SQAAzLvJSFRP7OvVXVu6dNfmbh3qG5WZ1NFcqb+5dpVe0V6vhvIiveNbj+vPfvy0qkoLdNmKWq/LBgCc5IxBzTn3ezNrOenL10u6PP7xdyXdrzQLaj1D4zprQbnOWhDUV+7brbaGoF5zzgKvywIAIOnGJiJ6YEdId23u1r3butU3MqECv0+XLa/RR65critX1aumrPB53/Nf7+jQm7/+iN5/6wb94KaLdPaico+qBwCcSiIzaqdS75w7Ev+4S1L96e5oZjdJukmSmpqaZvl0M9czNK76YJE+ff1q7To6pD//ydNaUlOq1QsZiAAA2aV3JKw/vXWDyovzdWVbnV7RXq+XrqxVaeHph/ny4nx9993n6/VffVjv+s7j+ukHLlZzdWkKqwYAvJg5NxNxzjlJ7kVuv8U51+Gc66itTd3Sip6hcdWUFajA79N/vm2dqkoK9L7vrVdocDxlNQAAkAqN5cX6+Qcv1vq/vUr/8eZz9aqzG180pE2pDxbpu+8+X5Go09u/+ThjJACkkdkGtW4za5Sk+PujyStp7qJRp56h8IllHrWBQt3yjg71joT1gds2aHwy4nGFAAAk15qmSuXnzXxYX15Xpm/eeJ6ODo7pXd95XEPjk/NQHQBgpmYb1H4l6Z3xj98p6ZfJKSc5+kYnFIm6563HX72wXP/2xnO0vrNXf//LzYpNBAIAgLVNlfrqW9dq65FB/emt63lBEwDSwBmDmpl9X9IjklrN7KCZvUfSv0h6hZntlHRV/PO00TMUW7pRG3j+xunXnLNAN1+xTD944oC+9wjnxwAAMOXlbfX67Bteood2HdMnf/S0olFe0AQALyXS9fEtp7npyiTXkjQ98TX2J3e4kqRPvqJV27sG9elfb9HyujJdsrwm1eUBAJCW3rhukUKD4/rsHdtUGyjUp65rlxnnkAKAF+bcTCQdhU7MqBW84Dafz/T5N5+rpTWluvn2jdp/bCTV5QEAkLbe/7KletclLfr2Q/v0tQf2eF0OAOSs7AxqLzKjJkmBonx9450dck567/eeYOM0AABxZqa/e3W7XnPOAn32jm36yYaDXpcEADkpK4Naz1BY+Xmm8uL8096nubpUX/mTtdodGtbHf/gUa/EBAIjz+Uyf++OX6JLl1frLnz6j+7enVXNnAMgJWRrUxlVTVnjGdfWXrqjR3756le7e0q3P37MjRdUBAJD+Cv15+trb1mlxZbG+et9ur8sBgJyT1UEtETde3KI3dSzSl363S7uODs5zZQAAZI5AUb7OX1KlfceGvS4FAHJOFge1FzYSORUz081XLJckPbrn+HyWBQDIIWb2UTPbZGabzexjXtczW83VpTo6OK6RMPu5ASCVsjKohQYTn1GTpKaqEtWUFWjj/t55rAoAkCvMbLWk90k6X9I5kq4zs+XeVjU7zdUlkqROuiQDQEplXVCLRp2ODYVVE0g8qJmZ1jRVamMnQQ0AkBSrJD3mnBtxzk1KekDS6z2uaVZaqkslSZ0sfwSAlMq6oNY/OqHJqFPtDGbUJGldc6X2HRvRsfgZbAAAzMEmSZeZWbWZlUi6VtLi6Xcws5vMbL2ZrQ+FQp4UmYim+IzaPmbUACClsi6o9cSD1kxm1KRYUJOkjfv7kl4TACC3OOe2SvqspLsk3SHpKUmRk+5zi3OuwznXUVtb60GViQkW5au6tIAZNQBIsawLaqGpoJZgM5EpZy8sl99n7FMDACSFc+6bzrl1zrmXSuqVlLHnwDRXl2hfDzNqAJBK2RfUBmNBbaZLH4vy83TWwnJtYJ8aACAJzKwu/r5Jsf1pt3tb0ey1VJdq/3GCGgCkUtYFtZ6hsCSpdoZLHyVpbVOFnjnYp4lINNllAQByz0/NbIuk/5F0s3MuY9fWN1WX6HD/qMYmIme+MwAgKbIwqI0rP89UXpw/4+9d11ypsYmoth4ZmIfKAAC5xDl3mXOu3Tl3jnPuXq/rmYuW6lI5Jx3sZVYNAFIl+4La4LiqSwtlZjP+3rVN8YYiLH8EAOCEqbPU2KcGAKmTfUFtaFw1gZk1EpmyoKJYjeVF2kDnRwAATpg6S20fnR8BIGWyLqiFhsZVM8NGItOt5eBrAACep6IkX8Eivzo5Sw0AUibrglrPYHjGHR+nW9tcqUN9o+rqH0tiVQAAZC4zU0tNKTNqAJBCWRXUnHM6Njw+48Oup3vu4Gtm1QAAmNJMi34ASKk5BTUz+6iZbTKzzWb2sWQVNVv9oxOaiLg5LX1sbwyq0O9j+SMAANM0V5XoYO8oR9gAQIrMOqiZ2WpJ75N0vqRzJF1nZsuTVdhsTB12XVM2u2YiklTg9+kli8q1gRk1AABOaK4uUSTqdKh31OtSACAnzGVGbZWkx5xzI865SUkPSHp9csqandBQLKjNZY+aFGsosvnQAAd7AgAQ11JD50cASKW5BLVNki4zs2ozK5F0raTFJ9/JzG4ys/Vmtj4UCs3h6c6sZygsSaqdwx41KdZQJByJavPh/mSUBQBAxps6S43OjwCQGrMOas65rZI+K+kuSXdIekrSC6agnHO3OOc6nHMdtbW1sy40ET0nlj7OfUZNkjZ2cp4aAABSbLVKSUEeM2oAkCJzaibinPumc26dc+6lknol7UhOWbPTMzQuv89UXpw/p8epDRSqqapEG2goAgCApFiL/ubqUmbUACBF5tr1sS7+vkmx/Wm3J6Oo2QoNjqu6rEA+n835sdY2VWjD/l4555JQERib2gAAIABJREFUGQAAma+5qkSdzKgBQErM9Ry1n5rZFkn/I+lm55ynawV7hsbnvOxxyrrmSoUGx3WQ7lYAAEiSmmtKdOD4qCJRXsQEgPnmn8s3O+cuS1YhydAzFJ5zI5Epa6cdfL24qiQpjwkAQCZrqS5VOBLVkf5RLapkbASA+TTXGbW0kswZtdb6gEoK8jj4GgCAODo/AkDqZE1Qc84lNaj583w6d3EFB18DABDXUs1ZagCQKlkT1PpHJzQRcaopK0jaY65tqtTWI4MaCU8m7TEBAMhUDcEiFfh9zKgBQApkTVDrGYqdoZasPWpSrKFIJOr09AEOvgYAwOczNVeVaF8PM2oAMN+yJqiFBsOSYgdyJsuapgpJsYYiAAAgtk9t/3Fm1ABgvmVNUJuaUatJ4oxaRUmBltWW0lAEAIC45upS7Ts2zDmjADDPsi+oJXFGTYrtU9vIwdcAAEiSWqpLNDYR1dHBca9LAYCsljVBLTQ4rjyfqaI4P6mPu665Ur0jE9rLenwAwAyY2cfNbLOZbTKz75tZkdc1JUPzVOdHxkUAmFdZE9RirfkL5PNZUh933YmDr/uS+rgAgOxlZgslfURSh3NutaQ8STd4W1VyTLXop/MjAMyvLApq4aQve5SkZbVlChb5tYF9agCAmfFLKjYzv6QSSYc9ricpFlQUye8zzlIDgHmWRUEteYddT+fzmdY0VepJOj8CABLknDsk6XOS9ks6IqnfOXfX9PuY2U1mtt7M1odCIS/KnBV/nk+Lq0rUSedHAJhX2RPUBucnqEmxhiLbuwc1MDYxL48PAMguZlYp6XpJSyQtkFRqZm+bfh/n3C3OuQ7nXEdtba0XZc5aU1WJOplRA4B5lRVBzTkXW/oYKJiXx1/XXCnnpKcPsE8NAJCQqyTtdc6FnHMTkn4m6WKPa0qaluoSdfaM0BEZAOZRVgS1gdFJhSPRpB52Pd05i8tlJvapAQAStV/ShWZWYmYm6UpJWz2uKWmaq0s1OD6p48Nhr0sBgKyVFUEtFD9DrTaJh11PFyjKV2t9gKAGAEiIc+4xST+RtFHSs4qNt7d4WlQStdSUSJL20fkRAOZNVgS1+Trserq1zZV6an+folGWeQAAzsw59/fOuTbn3Grn3Nudc1lzQnTziRb97FMDgPlCUEvQuqZKDY5PaufRoXl7DgAAMsGiymL5jBk1AJhPWRHUQoNTQW1+molI0w++ZvkjACC3Ffrz1FherP3MqAHAvMmKoNYzNK48n6myZP6CWnN1iapKC9inBgCAYvvUmFEDgPkzp6BmZh83s81mtsnMvm9mRckqbCZ6BsOqLi2Qz2fz9hxmprVNlcyoAQCg2D419qgBwPyZdVAzs4WSPiKpwzm3WlKepBuSVdhM9AzN32HX061trtCe0LB6aUcMAMhxLdUl6h2ZUP/IhNelAEBWmuvSR7+kYjPzSyqRdHjuJc1caGhcNfPUmn+6dU2xfWpPHmBWDQCQ2050fjzOrBoAzIdZBzXn3CFJn1PsUM8jkvqdc3edfD8zu8nM1pvZ+lAoNPtKX0TP4Pi8HXY93UsWVcjvs4T3qQ2OTeixPcc0PD45z5UBAJBaLfGgxj41AJgf/tl+o5lVSrpe0hJJfZJ+bGZvc87dNv1+zrlbFD/ks6OjI+mHkDnn1DMUVk1g/hqJTCkuyFP7gqA2dvad8vah8Uk9se+4Ht19TI/uOaZnD/Ur6qSzFgR1+/suVHlx/rzXCABAKjRVxQ697uxhRg0A5sOsg5qkqyTtdc6FJMnMfibpYkm3veh3JdnA2KTCkWhKZtQkaW1TpX74xAFNRqIan4zGgtme43pkzzFtOtSvSNQpP8+0ZnGlPnTFctUGCvXpX2/Rjd9+XLe+5wKVFc7lkgMAkB6KC/JUHyxU53Fm1ABgPswlNeyXdKGZlUgalXSlpPVJqWoGUnHY9XRrmyv1nYf36bovPaidR4dOBLNzF1fog5cv04VLq7W2qVLFBXknvqc2UKSbb9+o9373CX37xvOfdxsAAJmKzo8AMH9mHdScc4+Z2U8kbZQ0KelJxZc4ptJzh12nJqhdtLRaCyuKVVro1/tftlQXLa3R2uYKlRSc/lK+cnWD/uNN5+hjP3xKf3rbBv3XO9ap0E9YAwBktpbqEt23fX72nwNArpvTOjzn3N9L+vsk1TIrUzNqtSno+jj1PA/91ctn/H3Xn7tQ4xNR/cVPn9GHbn9SX33rWuXnZcV54wCAHNVcXarQ4EENj0+qlKX9AJBUGZ8Uek7MqM1/M5G5etN5i/Xp68/S3Vu69fEfPqVINOm9VQAASJmpzo+ddH4EgKTL+Je/eobCyvOZKkvSP6hJ0jsuatHYRET//NttKsrP07++4SXy+czrsgAAmLHm6njnx2PDal8Q9LgaAMguWRDUxlVVWpBRYeemly7TaDiqz9+zQ0X5Pv3T9atlljn1AwAgPRfUOEsNAJIv44NaaHA8ZY1EkukjVy7X6EREX3tgt4r8efqbV68irAEAMkqgKF/VpQXaf5zOjwCQbBkf1HqGxlPWSCSZzEx/+cpWjU1E9I0H96qkIE+fuLrV67IAAJiR5uoS7ethRg0Aki0LglpYy+rKvC5jVsxMn7quXaPhiP7f73apMD9PN1+x3OuyAABIWEt1qR7dc8zrMgAg62R010fnnEJD46rNwKWPU3w+0z+//mxdf+4C/dud2/Wj9Qe8LgkAgIQ1V5fqcP+YxiYiM/o+55yGxifnqSoAyHwZHdQGxycVnoxm5B616fJ8pn//43PU1hDQzzYe9LocAAAS1lITayhy4PjMlj9+8d6dWvPpu/SNP+yRcxxXAwAny+igFpo6Qy2QGa35X4w/z6e1zZXa1jXIgAUAyBjN8bPUZtL58cDxEX31/t0KFOXr//5mq979nSd0bGh8vkoEgIyU0UFt6rDr2rIijytJjlUNAfWNTKh7gMEKADKZmbWa2VPT3gbM7GNe1zUfmqueO0stUf/f/25Vnpl+85FL9enrz9JDu4/pVV/8gx7e3TNfZQJAxsnsoDYUlpQdM2qS1NYYOyx0a9eAx5UAAObCObfdOXeuc+5cSeskjUj6ucdlzYuKknwFi/zqTHBG7dE9x/TbZ7v0gcuXqbG8WO+4qEW/+OAlKivy663feEyfu3O7JiPRea4aANJfhge1+NLHDN+jNmVlfUCStO3IoMeVAACS6EpJu51znV4XMh/MTC01pdqXwIxaJOr0j/+zRQsrinXTS5ee+Hr7gqB+/eFL9cfrFunL9+3Sm295VAd7afkPILdlfFDzmVRZkh0zauXF+VpYUaxtzKgBQDa5QdL3T/6imd1kZuvNbH0oFPKgrORpri5NaEbth08c0NYjA/rra9tUlJ/3vNtKCvz61zeeoy/ecK62dw3q2i/+QXdsOjJfJQNA2svooBYaHFd1WaHyfOZ1KUnT1hBgRg0AsoSZFUh6raQfn3ybc+4W51yHc66jtrY29cUlUUt1iQ72jig8efoli/2jE/r3u7br/JYqvfrsxtPe7/pzF+o3H7lULTWlev9tG/W3v3h2xq3/ASAbZHRQ6xkaz5plj1PaGgPaHRrS+CSDEgBkgVdJ2uic6/a6kPnUXF2qqJMO9Y2e9j5funenjo+E9anXtMvsxV9gba4u1U/ef7FueulS3fbofv3RVx7Szm5exASQWzI6qIWGwqopy45lj1PaGoKajDrtPpp49ywAQNp6i06x7DHbtFTHOj+ebp/a7tCQvvPwPr25Y7FWLyxP6DEL/D79n2tX6TvvOk+hwXG99ssP6Uj/6YMgAGSbjA5qPYPjqs2yGbVVjfGGIuxTA4CMZmalkl4h6Wde1zLfmuJBbf9p9ql95jdbVZSfp09e3Trjx768tU7fftd5Gp2I6PG9x+dUJwBkkowNas652NLHQHYFtZbqUhX4fdrWxRIPAMhkzrlh51y1c67f61rmW21ZoUoK8k45o3b/9qP63baj+siVy1U7yzG7rSGogjyfthzhRUwAuSNjg9rg+KTGJ6NZN6Pmz/NpZX2ZtjIYAQAyhJmdsvPjRCSqf/r1FrVUl+jGi5fM+vEL/D4tryvTlsOMjQByx6yDmpm1mtlT094GzOxjySzuxfQMxs9Qy5LDrqdrawgyowYAyCgt1SUvmFG77dFO7Q4N629e3a4C/9xeG25fENRWuiIDyCGz/qvpnNvunDvXOXeupHWSRiT9PGmVnUHPUFhS9hx2PV1bQ0ChwfETB3oDAJDumqtLdeD4iCJRJ0k6PhzW5+/eoctW1OiqVXVzfvz2xqB6hsZ1dHBszo8FAJkgWUsfr5S02znXmaTHO6OpEJONQW1VY1CStJ1ZNQBAhmipLtFExOlwvEX/5+/eoeFwRH933Znb8SeifUFsbGT5I4BckaygdoNO037YzG4ys/Vmtj4UCiXp6WKHXUvZGdTaGmKdH9mnBgDIFFOdHzuPjWhb14D++7FOve2CJq2sDyTl8adexKShCIBcMeegZmYFkl4r6cenut05d4tzrsM511FbWzvXpzuhZ2hcPpOqSrNvj1p1WaFqA4XsUwMAZIyW6lJJsbPUPv0/WxQoytfHrlqZtMcvL87XwopiZtQA5Ax/Eh7jVZI2Oue6k/BYCesZGldVaaHyfHNfTpGO2hoCnKUGAMgYDcEiFfh9uvWRTm3vHtQ/vvYsVSb5xdRYQxHGRgC5IRlLH9+i0yx7nE+hwbBqyrJvNm3KqsagdnQPaTIS9boUAADOyOczNVeVaHv3oFbUlemtFzQl/TnaG4Pa0zOskfBk0h8bANLNnIKamZVKeoWknyWnnMT1DI3P+uDMTNDWEFB4MnrKw0MBAEhHzfHlj596Tbv8eck/qrV9QVDO0WwLQG6Y019R59ywc67aOdefrIISFRocz8pGIlPaGmKbpjkzBgCQKd56YZM+ftVKXbYieXvSp2unoQiAHJL8l7tSwDmX9TNqy+pK5fcZ+9QAABnjitY6ffSqFfP2+IsqixUo8tNQBEBOyMigNjQ+qfHJaFbvUSv052lZbZm2MaMGAIAkycy0qjHIjBqAnJCRQa1nKCwpO89Qm66tMUCLfgAApmlvDGp716AiUed1KQAwrzI0qGXvYdfTtTUEdahvVP2jE16XAgBAWmhfENRIOKJOmm0ByHIZGdRCg7Ggls171KTYjJpEdysAAKbQUARArsjIoJYrM2qr4p0faSgCAEDMivoy+X1GQxEAWS8zg9rguHwmVZVmbzMRSaoPFqqiJJ8W/QAAxBX687S8rowZNQBZLyODWmgorKrSAuX5zOtS5pWZqa0hwIwaAADTtDcGtZWgBiDLZWRQ6xnK7sOup2triHW3itLdCgAASbGGIt0D4ye2QgBANsrIoBYazO7Drqdb1RjQSDiiA70jXpcCAEBamGoowqwagGyWkUEt12bUJLFPDQCAuFVTnR9pKAIgi2VcUHPOxYNadjcSmbKyPiAzOj8CQKYxswoz+4mZbTOzrWZ2kdc1ZYvK0gI1lhfRUARAVvN7XcBMDYcjGpuI5syMWnFBnpZUl2obM2oAkGm+KOkO59wbzaxAUonXBWUTGooAyHYZN6PWM5gbZ6hN19ZI50cAyCRmVi7ppZK+KUnOubBzrs/bqrJL+4KgdoeGNTYR8boUAJgXGRfUQvEOT7nSTESK7VPrPD6i4fFJr0sBACRmiaSQpG+b2ZNm9g0zK51+BzO7yczWm9n6UCjkTZUZrL0xqEjUaUc3K04AZKeMC2o5OaPWEJBzYjACgMzhl7RW0n8659ZIGpb0V9Pv4Jy7xTnX4ZzrqK2t9aLGjNa+gIYiALJb5gW1+IxaTSA3molIz3W32tZFUAOADHFQ0kHn3GPxz3+iWHBDkiyuLFFZoZ+GIgCyVsYFtdBQWGZSVUnuBLWFFcUqK/RrG4MRAGQE51yXpANm1hr/0pWStnhYUtbx+UxtDQEaigDIWnMKal60Hg4Njqu6tED+vIzLmLPm85laGwLayowaAGSSD0v6bzN7RtK5kv7Z43qyTvuCoLYeGVQ06rwuBQCSbq5pZ6r1cJukcyRtnXtJLy6XDruerq0hoG1HBuQcgxEAZALn3FPxPWgvcc79kXOu1+uask17Y1BD45M60DvidSkAkHSzDmpetR7O2aDWGNTA2KSO9I95XQoAAGmBhiIAstlcZtTO2HpYSn774VhQy539aVNWNQQkifPUAACIW1kfUJ7PaCgCICvNJaidsfWwlNz2w8459QyGc3JGbWU8qG09wj41AAAkqSg/T0trSmkoAiArzSWopbz18HA4otGJSE4ddj0lWJSvRZXFtOgHAGCa9gVBlj4CyEqzDmpetB7OxcOup2trCPKqIQAA07Q3BnW4f0y9w2GvSwGApJpr18eUth5+7rDr3AxqqxoD2hMa0thExOtSAABIC1MNRXghE0C2mVNQS3Xr4RNBLQebiUixGbWok3YdHfK6FAAA0sKqxnjnR4IagCyTUadGh4Ziyxpqc3XpY+NUQxEGIwAApNh2iLpAIUENQNbJrKA2OC4zqao0N2fUWqpLVej30VAEAIBpaCgCIBtlVFDrGRpXVUmB/HkZVXbS5PlMrQ0BzlIDAGCa9sagdh0d0vgke7gBZI+MSjyLKot12Yoar8vwVFtDQFuPDMo553UpAACkhfYFQU1GnXZ2s4cbQPbIqKD2wcuX6ws3rPG6DE+1NQR1fDisULyxCgAAua6dhiIAslBGBTU811Bk2xH2qQEAIEnN1aUqKcij2RaArEJQyzBtDbFXDdmnBgBAzNQebhqKAMgmBLUMU1VaoPpgITNqAABM094Y1JYjA+zhBpA1CGoZqK0hqK206AcA4IT2BUENjk3qYO+o16UAQFIQ1DJQW2NAu44OaiIS9boUAADSAg1FAGQbgloGWtUQ1ETEaU9o2OtSAABIC20NQflM7FMDkDUIahnoROdHGooAACBJKi7IU0tNKZ0fAWQNgloGWlpTpvw801YaigAAcMJUQxEAyAYEtQxU4PdpWW0ZrxoCADBN+4KgDvaOqn90wutSAGDOCGoZqq0hoJ3dzKgBQLoys31m9qyZPWVm672uJxdMNRThhUwA2YCglqFW1Ad0uH9MQ+OTXpcCADi9K5xz5zrnOrwuJBe0L4h3fqShCIAsQFDLUMtqyyRJu48OeVwJAADpoS5QpJqyAmbUAGQFglqGWlEfC2o7CWoAkK6cpLvMbIOZ3XTyjWZ2k5mtN7P1oVDIg/Ky0yoaigDIEgS1DNVcVaL8PNPOo+xTA4A0dalzbq2kV0m62cxeOv1G59wtzrkO51xHbW2tNxVmofYFQe3sHlJ4Mup1KQAwJ3MKamyU9o4/z6elNWXa1c2MGgCkI+fcofj7o5J+Lul8byvKDe2NQYUjUe0OMT4CyGzJmFFjo7RHlteXaRcDEQCkHTMrNbPA1MeSrpa0yduqcsNU50caigDIdCx9zGDLa8u0//iIxiYiXpcCIEt86peb9On/2eJ1GdmgXtKDZva0pMcl/cY5d4fHNeWEJTWlKsjzaQdH2ADIcHMNai+6UVpis/R8WlFfJufE8g4ASRGejOrnGw9paJzDgufKObfHOXdO/O0s59xnvK4pV/jzfFpWV6ZtXQQ1AJltrkHtRTdKS2yWnk8r6gKSpF10fgSQBA/v7tHg+KReubrB61KAOWlrCDCjBiDjzSmosVHaWy01JcrzGUENQFLcublLZYV+XbysxutSgDlpbQjoSP+Y+keYHQaQuWYd1Ngo7b1Cf56aq0q0k86PAOYoEnW6a3O3Lm+tVVF+ntflAHPSWh9bcbKdWTUAGWwuM2pslE4Dy+vKOEsNwJxt6OzVseEwyx6RFVobCGoAMp9/tt/onNsj6Zwk1oJZWFFfpnu3HVV4MqoCP008AczOHZu6VOD36fLWOq9LAeassbxIgSK/tnfRoh9A5uL/7DPcirqAIlGnfceGvS4FQIZyzunOzV26bHmNygpn/fodkDbMTK31AW2n8yOADEZQy3DL68ok0fkRwOxtPjygQ32juoZlj8girQ2xoOac87oUAJgVglqGW1ZbJjPRUATArN2xqUs+k65aVe91KUDStDYENDA2qa6BMa9LAYBZIahluOKCPC2qLKahCIBZu2Nzly5YUq2q0gKvSwGSZqrzIwdfA8hUBLUssKIuwNJHALOy6+iQdh0dotsjss5U58cdBDUAGYqglgVW1JVpT2hYk5Go16UAyDB3bu6SJF19FssekV0qSgpUHyykoQiAjEVQywLL68oUjkR1oHfU61IAZJg7N3fpnMUVaiwv9roUIOlaG4IsfQSQsQhqWWCq8+NODvYEMAOH+kb1zMF+vfIslj0iO7U1BLQrNMSKEwAZiaCWBU4ENfapAZiBu+LLHq9h2SOy1Mr6gMKTUe07NuJ1KQAwYwS1LBAoyldjeRENRQDMyB2burSyvkxLa8u8LgWYF23xhiLsUwOQiQhqWWJ5XRlBDUDCjg2N64l9x1n2iKy2vK5MPpO2szUAQAYiqGWJqaAWjTqvSwGQAe7Z2q2ok64mqCGLFeXnqaW6VNu7BrwuBQBmjKCWJVbUBTQ6EdGhPjo/AjizOzZ1aVFlsc5aEPS6FGBetTYEWPoIICMR1LLEivrYHhOWPwI4k8GxCT2065heeVaDzMzrcoB51doQUOfxEY2GI16XAgAzQlDLEstrpzo/8qohgBd33/aQwpGorlnNskdkv9b6gJxjfASQeQhqWaKytEA1ZYXMqAE4ozs3dammrFBrmyq9LgWYd610fgSQoQhqWWR5XSlnqQF4UWMTEd23/aiuPqteeT6WPc43M8szsyfN7Nde15KrmqtLVej3EdQAZByCWhZZURfQru4hOUfnRwCn9uDOHo2EI7qGbo+p8lFJW70uIpfl+Uwr6sto0Q8g4xDUssiK+jINjk+qe2Dc61IApKk7NncpUOTXRUurvS4l65nZIkmvlvQNr2vJda31QWbUAGScOQc1lnWkj+V1dH4EcHqTkaju2dqtK9vqVODndboU+IKkv5AUPdWNZnaTma03s/WhUCi1leWYtoaAjg6Oq3c47HUpAJCwZIzULOtIE1NBjc5WAE7l8b3H1TcyoVfS7XHemdl1ko465zac7j7OuVuccx3OuY7a2toUVpd7VsYbimxjVg1ABplTUGNZR3qpLStUeXE+DUUAnNIdm7tUlO/TS1cSClLgEkmvNbN9kn4g6eVmdpu3JeWutnhQ28E+NQAZZK4zai+6rENiaUcqmZlW1JVpVzdBDcDzRaNOd23u1ktX1KqkwO91OVnPOffXzrlFzrkWSTdI+p1z7m0el5Wz6gKFqijJZ0YNQEaZdVBLZFmHxNKOVFtRX8bSRwAv8PTBPnUNjLHsETnJzLSyPqDtXQNelwIACZvLjBrLOtLQ8rqAekcmdGyIzo8AnnPn5m75faYr2+q9LiXnOOfud85d53Udua6tIaAdHGEDIIPMOqixrCM9PddQhOWPAGKcc7pj0xFdtKxa5SX5XpcDeKK1IaCh8Ukd6hv1uhQAaWA0HNHtj+3XX//sWY2GI16Xc0psVMgyK6YFtQs5JwmApB3dQ9p3bETvvWyp16UAnmmtjzUU2d41qEWVJR5XA8ArR/pHdesjnbr98f3qG5mQJC2qLNbNVyz3uLIXSkpQc87dL+n+ZDwW5qaxvEilBXnaRWcrAHF3bu6SmXR1O8sekbumWvRv7x7Ulav4twDkmif39+pbD+3T/z57RFHndHV7g9596RLd8vs9+tr9u/WW85tUVVrgdZnPw4xaljEzLa8PaFeIpY8AYgPTjzcc0NqmStUFi7wuB/BMsChfC8qLtJ3Oj0DOmIhE9b+buvStB/fqqQN9ChT6dePFLXrnxS1aXBWbWa8sydc1X/i9vnLfLv3dde0eV/x8BLUstKKuTL/fwVEIQK5yzumxvcf15d/t0oO7elRRkq9PX59+SzqAVGttCBDUgBzQOxzW95/Yr+893KmugTG1VJfoH197lt6wbpHKCp8ff1bUB/TH6xbr1kc6deO0AJcOCGpZaHldmX6y4aD6RyZoHADkEOecHtgR0pd/t0vrO3tVU1ao/3Ntm956QbNKC/lzD7Q2BPXgrh5NRKLKz5vrUbIA0kkk6vTI7mP62ZMH9dtnj2hsIqpLl9foM69brSta6+Tz2Wm/92OvWKFfPHVI/3H3Dn3+zeemsOoXx8idhaYaiuwKDWpdc5XH1QCYb9Go011buvWV+3bp2UP9aiwv0j++9iy9+bzFKsrP87o8IG20NpRpIuK0t2dYK+PNRQBktm1dA/r5xkP6xVOH1D0wrkChX69bs1DvvLhFbQ3BhB6jsbxY77pkib7++91672VLdNaC8nmuOjEEtSy0oi42+OzsHiKoAVlsMhLVb549oq/ct0s7uofUXF2iz77hbL1uzSIV+JktAE7WWh/7n7ZtXYMENSCDHR0Y0y+fOqyfPXlIW48MyO8zvWxlrT513SJduapuVi9SfuBly/T9x/frX+/Yru+++/x5qHrmCGpZaGFlsYryfdrFWWpAVhocm9Cvnzmirz+wW/uOjWhFXZm+eMO5evXZjfKznAs4rWV1pcrzmXZ0DUrneF0NgJkYCU/qzs1d+tnGQ3poV4+iTjpnUbn+4TXtes05C1RdVjinxy8vydeHrliuz/x2qx7e1aOLl9ckqfLZI6hloTyfaWlNGYdeA1kkPBnV/duP6pdPH9Y9W7o1PhnV6oVBfe1ta3V1e8OLrr0HEFPoz9OSmlJto6EIkBFGwxE9sOOo/ndTl+7e0q2RcEQLK4r1wcuX63VrF2pZbVlSn+/tFzXr2w/t1b/csU2/+OAlno+tBLUstaK+TOv39XpdBoA5iEadHt93XL986pB++2yX+kcnVFVaoDeft1jXn7tAa5sqZUZAA2aitSGgZw72eV0GgNMYHJvQ77Yd1R2bunT/9pBGJyKqLMnXa89ZoNdG++grAAAc3ElEQVStWajzWqrmLUAV5efpE1e36s9+/LR+u+mIrnvJgnl5nkQR1LLUiroy/fKpwxoen6TbG5BBnHPaemRQv3zqkH719GEd6R9TSUGerm6v1/VrFurS5TV0qwPmoK0+oN88c4TxEUgjvcNh3b21W3ds6tKDO3sUjkRVFyjUG9ct0qtWN+j8JVUpW9r/ujUL9Y0/7NG/3bld15zV4OmYy1+oLLU83lBkd2hIL1lU4XE1AM5kd2hId2zq0i+ePKSdR4f+//buPLrN67zz+PcCBAnuBEmAlEiRFMVNm23JWizJtmRJTmynJ0uzNm7ixBnb8bSZxE3TepozZyaZmZ522maSTJImbjzZ68ZN0540k8W2NsuLJMvypoWLSGqXCHDfie3OH4BpSfECmRQBAr/POe/B9lJ4zhXAh8+99713+sLoB29v4dZlFeRl69e1yGxoqozlx/aeEVbVeJIcjUjm8o9M8tiRWHH2bFcfkailqiSXj22o5fYVlayu8SRl6qHTYfjz21r45Pef45EDp/j4hro5j+FVyvxpqrEiNme3o0eFmkgqikYtL58d4rdHLvDYkQt0BsYAWFvn4X+8dwV3rFxAaX52kqMUST8t8UKt7YIKNZG5ZK2lMzDKY0d7ePxoDy+eHsRaqC/P576b67l9xQJWVBWlxJT+Lc1e1i8u5es7Ovj91b+7SfZcUaGWpmpL83A5jRYUEUkhoUiUfV19PHYklqQuDE/idBhuqC/lro11bF9awcKS3GSHKZLWFnnyyHU5aevRgiIiV1skajl0aoDH48VZd2+sU3JlVTEPbG/incsraaooSIni7GLGGB68vYX3fesZvru3i89tb0pKHCrU0lSW08Hi8nyO+5WIRJJpbCrMnvYAjx25wI5WPyOTYXJdTjY3eXnH8gq2tvgoydPImchccTgMTRUFtGnlR5GrYiIYYW9HgMeP9rCz1U/fWBCX03BDfRl3b6pj+7IKFhSnfqfkqhoPd6ys5B+e7OLO9bV4C2e2/P/boUItjTX6Cjl8bijZYYhknHODE+xo9bPzWA9Pd/YRDEfx5Ll45/JK3rm8kpsay9/WZpwiMjuaKwvZ2epPdhgiacM/MsnOY36eOObnqeMBJkNRCt1Z3NLs49ZlFWxu9lLkdiU7zCv2p+9o5rdHevg/Ozv48ntWzPn7q1BLYw2+An59+DyToYj+KBS5iqJRy0tnBtlxzM+OVj/Hzg8DUFOax53ra3jHskrW1nm0GbVIimiuLOLRg2foHZ2ifIab5IpkImstR88Px/LesR5eOhMbGFhY7ObDaxZx67LYSo3ZWfM779V7C/jI2kX84/5T3L1pMXXl+XP6/irU0lhjRQFRC12BMZYtLEp2OCJpZXQqzN72ADta/exu89M7GsTpMFxf6+Ev7mhha0sFS7z5KTfvXkSgueK1BUXKG1SoiSRiMhRhX1ffdHF2bmgSgGsXlfD5W5vYtrSCpQsK0y7vfXZ7Iz8/dJa/fayNb3x09Zy+twq1NNbgi6/86B9RoSYyC7p7x9jd5mdnq599XX2EIpYidxZbmn1sW+pjc5NX15uJzAPNF638uKmhPMnRiKSu3tEpdrbGCrO9Hb2MByPkupzc2FjOZ7c3ckuLD1+hO9lhXlW+Qjf33LSYr+88zr03D87pauoq1NLY4vJ8HAaOa+VHkbdlMhRhf3c/u+KjZif6xgGo9+bzyU2L2dbi4/paTWkUmW+8hTmU5WdrQRGRy1hr6fCP8vjRHnYc6+GF+BL6lUVu3reqiu1LK9iwpCzjLqm55+Z6frz/FH/161Z+8h/Wz9mooQq1NJaT5aSuLJ+OHhVqIok6MzDOrrYAu1v9PNPZx0QoQk6Wg41Lyrj7xsVsafJRU5aX7DAlxRlj3MCTQA6xXPsza+1/TW5UcrGmikJatUS/CMFwlAPd/TxxrIcdrT2c7p8AYkvof3ZbI9uXVrB8YWrsb5YshW4Xn9nawJf+/Sh72gNsafbNyfu+7UJNSWh+aPAVcDygQk3kjQTDUQ6e7Gd3W4Bdrf7pvQcXlebyoTXVbGnxsaE+83oPZcamgK3W2lFjjAt4yhjza2vtvmQHJjHNlYU8evA00ajF4cjcP0AlMw2OB9ndFuDxYz082RZgZCpMTpaDGxvKuX9zA9uW+qgoSu8pjVfqzvW1DI6H5s3URyWheaDBV8DOVj/BcHTer7wjMlsuDE2yu83PrjY/Tx/vY3QqjMtpWL+4jA+vXcQtLT7qy7UQiLx91loLvNpL5oofNnkRyeVaKgsZD0Y4MzChUXLJCN29YzxxtIcnjvVw8OQAkailvCCHd12zgG1LK7ixoZzcbHVKvpHsLAcP3Dq3G1+/7UJNSWh+aKwoIBy1nOwbozG+ypVIpglFohw6ORCb0tjmpzV+XcrCYjfvvm4hW5q8bGwopyBHs8Fl9hhjnMDzQAPwTWvt/stevxe4F6CmpmbuA8xwTfEFRVovDKtQk7QUjkQ5dGqQHcd6ePxYD12BMSDWSXH/5iVsX1bBNVXFGlFOYTP6q+StklD8HCWiJGr0xRJRh39UhZpkFP/wJLvbY4XZ3o5eRibDZDkMa+o8/OfbW7ilxUejr0CjZnLVWGsjwHXGmBLgX40xK6y1hy96/SHgIYA1a9aoo3OONcVzYnvPCO9YXpnkaERmx8hkiL0dvTxxtIddbX4GxkO4nIYb6su4a0Md25b6qPaoY2K+mFGh9lZJKH6OElESLfEWYLTyo2SAcCTKC6cH2d3mZ3dbgCPnYptOVxTl8K6VC9jS7GVTQzmFbleSI5VMY60dNMbsAm4DDr/V+TI3CnKyWFSaOz3CLjJfnRkYZ8cxP08c65neOqYkz8XWZh/bllZwc5Ny33w1K/N8lIRSV262k2pP7vQCCSLpxD8yyZ62ALvbA+xtDzA8GY5tOl3j4c9ua2ZLky8tN9+U1GeM8QKheH7MBW4F/jrJYcllmisKtUS/zDuRqOXF07EpjTtbX5vOX1+urWPSzUxWfVQSmicavAV0aAliSQPhSJQXTw+yuy3A7nY/h8/GRs28hTm8c3klt7T42NRQTnGueg4l6RYAP4hfIuAAHrXW/jLJMcllmisL2d0WYCocISdLiyhI6hqdCvNUR4AnjvnZ1eqnbyyI02FYW+fhi3csZdtSH/XegmSHKbNsJiNqSkLzxPKFxexpD/DLl8/xe9csTHY4IlekZ3iSPe0B9rQHeKqjl6GJEA4D19d6+MI7m9nc5M34/V0k9VhrXwZWJTsOeXPNlUWEo5auwBhLFxQlOxyRS1w8pXF/Vz/BSJQidxZbmn1sW+pjS5OP4jx1TKazmaz6qCQ0T9y3uZ59XX38p0deIByxvHdVVbJDEnlDwXCU508OTBdnx86/Nmq2fWkFt7R4uanBq+QkIjPWHF9QpO3CiAo1SbpQJJb/drX62XnRvp715fnctbGWrS0VrKnz4NKUxoyhtagzQKHbxQ/uXsfd33+OBx59kXDU8oHrq5Mdlsi00/3jPNkRYHdbgGeO9zIWjEyv0Pjnt7Wwucmra81EZNbVe/MpyMni23s62dhQhq9QG/zK3OodnWJPW4CdbX6ebA8wMhnb13Pd4lI+vHYRW1s0pTGTqVDLEPk5WXz/k+u454cH+cLPXiIcifKRddouQZJjbCrM/u4+nmzvZW9HgM743i5VJbm8Z1UVm5u8bFxSplWqROSqcjkdfOvO1dz3o+f5wN8/y48/tV57qslVFY1ajpwbZmern51tfl4+M4i1sVkjt6+oZGv8WmvlPwEVahklN9vJd+9aw30/ep4Hf/4KoajlYzfUJjssyQCRqOXIuSH2dvTyZHuAQ6cGCEUsbpeDdYvL+Oj6WjY3eVnizdeomYjMqZubvPzknvXc/f3neP+3n+GHd6/TNEiZVf1jQfZ2xKbz7+3oJTAyhTFwbXUJD2xvYmuLj2ULirTxtPwOFWoZxu1y8tDHr+ePfnKI//JvhwmFo9x94+JkhyVp6NzgBHs7AjzZ0cszx3sZGA8BsGxBEXffuJibG71cX+vB7dJKayKSXKtrPPzzfRv42MMH+NB3nuX/fmIta+tKkx2WzFPhSJSXzgyypy3Ano7e6VEzT56LGxu9bGnysrnZS3lBTrJDlRSnQi0D5WQ5+dad1/OZRw7x5V8eJRyNcu/NS5Idlsxzg+NB9nX180xnL08f752ezugrzGFrS2zDzU0N5UpMIpKSGisK+dn9G/j4wwf42MP7+dadq9naUpHssGSeOD80wZMXrVA8PBnGYWBVjYfPbWtic7OXlVXFODVqJldAhVqGys5y8I2PruZzP32Rv/xVK6GI5Y9uaUh2WDKPjAfDHOju59nOPp7u7OXIuWGshVyXk3WLS/mDdTXc1OilqaJA0xlFZF6o9uTx6Kc38InvHeCeHz7P337wGt63Sotvye8anQqzv6uPp47HOifbe2IrNFYWubl9xQJubvJyY0O5ViiWGVGhlsFcTgdf+/B1uByGv/ltG8FwlM9tb9Qf1fK6guEoL5wa4JnOPp7p7OXF04OEIhaX00z3GG5sKOPa6hKys7R0sIjMT+UFOTxyzw3c+8PneeCnLzE4HuKTm3SJQKZ7NQc+3dnH08djOTASteRkOVi3uJQPXF/N5iafOidlVqlQy3BZTgd/96HryHI6+NqODsLRKH/6jmb9khEmQxFePD3Ige5+DnT38/zJASZCERwGVlYV86kb69nUUMaa2lJys3WdmYikj0K3i+99ci2f/acX+NK/H2VgLMgDtzYpN2aQaNTSemGEp4/38nRnL/u7+l/LgdUlfHpzPZsaylldo2ut5epRoSY4HYb/9f5rcDkN39zVyVQoyp/d1qJRkQwzNhXm+ZMD04XZi6cHCUaiGAMtlUV8eO0iNi4pY319GcW5msohIunN7XLyzY+u5ov/epiv7zxO31iQL79nha4xSlOvFmb7u/vY39XPgRP99I8Fgdh+ex9cU82mhnJuUA6UOaRCTQBwOAz/870rcTkdfPepbn5z5AJ/fEsDv7+6WgVbmhocD3LwxAAHTvSzv7ufw2eHiEQtTodhRVUxn9hUx/rFpaypLdUcexHJSFlOB3/1/pV48rP59p5OBidC/O8PXae8mAbCkShHzg1zoLuf/d19HOjuZ3gyDMT29NzS5GVjQzmbGspYUJyb5GglU6lQk2kOh+FL717OLS0+vvpEBw/+/BW+seu4CrY0EIla2ntGOHRqgBdODXLo1ABd8VUZs50OrltUwv2bl7C+vpTVNR7yc/SrQUQEwBjDg7e3UJrv4i9/1crxnlE+vaWe37tmIS6n8uJ8MRWOcPjsEPu6XpvOPzoVK8wWl+dz+4oFrK8vZd3iUqo92vRcUoOx1s7Zm61Zs8YePHhwzt5P3j5rLbvbA3z1iQ5eOj1ItSdXBds8MjgenC7IDp0a4KXTQ9MJqTQ/m9U1Jayq8XB9rYfrFpVofr3MOmPM89baNcmOY75QfpwffnP4Al95vI32nlEWFrv51E31fGTtInVupRhrLeeGJnnh1ACHTsZy4dFzwwQjUQAafQWsry9l/eIy1i0upaLIneSIJdMkmiNVqMmbmi7YHm/npTNDKthS0EQwwtHzQ7xyZohXzg7zwunXRssc8evLVteWsLrGw+oaD7VlebogXq46FWpXRvlx/ohGLbvb/Xx7TxcHuvspznXx8Q213LWxTvtEJslkKDZadihemL1weoCe4SkA3C4H11SVsKq2hFWLPKyt81Cm/ydJMhVqMqustexuC/DVJ1SwJdN4MMzRc8O8cnaIV84OcfjsEMf9o0TjX+PygmyurS5hda2HVTUlXFtdop5eSQoValdG+XF+OnRqgO/s6eSxoz1kOx18cE0199xUT21ZfrJDS1tT4QjtF0Y5cm6Iw+dinZRHzw8TisQSYU1pHqtqXuucbFlQqCmqknJUqMlVcXnBVlWSy7uuWcCWJi9r6kpVtM0Say2B0SnaL4zS1jPCkXhh1hm4uCjLYWVVESurillRVcw11SVUFOVotExSggq1K6P8OL91Bkb57t4u/uX5s4SjUW5fsYD7NtdzTXVJskOb18amwhw7P8zhs0McOTfM4XPDdPSMEI4nwsKcLJZXFbGqxsOqRbEp/d5CjZZJ6lOhJlfVqwXbw091s7+7j1DEkpftZOOScrY0e9nS7NXFuAkaGg/R1jNCe/xouxC7HRgPTZ/jLcyZLshWxg8VZZLKVKhdGeXH9OAfnuR7z5zgx8+eZGQqzLWLSti0pIwNS7Tn5JsJR6Kc6h+nwz/Kcf8obRdGOHxuiO7eMV79M7UsP5vlVcWsWFjE8oXFrKgqYpEnD4e2S5B5SIWazJmxqTDPdPaxu83P7rYAZwcnAGjwFbClycvmZi/rFpeSk5W5CSociXJucJITfWOc7B/nRO/YdGH26jx6iPUONlYU0FxZSFNFIc0VhTRWFKqHUOYdFWpXRvkxvYxMhnjkwCl+c/gCL58ZIhy1uJyGa6tL2LCkjA31ZayuzbyNkidDEbp7xzjuH6XDP0qnf5QO/wgnesenF/qA2PL4yxYWsSJekC1fqM5JSS8q1CQprLV0BsbY3eZnT3uA/V39BCNRcl1ONi4pY0VVMfXefJZ4C6j35pOXnT7XT02GIpwZGOdk3zgn+sY52TfGyfjtmYGJ6akaELu4ucFXMF2MNVXGbhcUu5WIJC2oULsyyo/pa2wqzHMn+tnX1c+zXX28cmaQqI1vjVJTwob62IhbOqzAa62lbyzImYEJzgyMT9+eHZigu3eMU/3j09P3HSZ2PVmDr4AGX2H8toAl3nwK3dq7U9KbCjVJCePBMPu6+tjdFmBvRy8n+l6bxgCwsNhNvTf2izl2GyvgUqlgiUQtfaNT9AxP0TM8Sc/IJD3DU/iHJ2OP48/3jQUv+bnCnCzqyvOpKcujriyP2rJ8akvzqCvPx1eonkFJbyrUrozyY+YYmQxx8MQAz3b18WxnH0fODRG1scKlsshNtSeP6tJcqj15LPLEb0tzqSxyk5XERTEmQxH6x4KXHOeHJi8tyAYnmAxFL/m5kjwX1Z5cakvzWeIroDFekC0uz5/3hanI23XVCzVjzCLgh0AFYIGHrLVfe7OfUSKSyVCEE31jdAXG6PSP0tU7RmdglK7A2PQ+XwB52U58hTkU5booznVR5HZRlJtFUfx+ca4rfj+L4lwXOVlOLHa6CLSW6ceWWC+fjT8fikQZmQwzMhl67XYqHL9/6fOD4yF6R6eIXvY1MSa2mEdlkZuKohx8RW4qCt3UluXFj3w8eS4VY5KxVKhdGeXHzDU0EeK57n5ePjsUK3r6Y0XP+eHJSzo2sxyGBSVuqkvyWFDipiAni1yXE7fLSW62k1xX7HBfdD8320FOlpNQJEooYgmGowQjEYLhKFPhaPxx/DZ+DE6EGBgL0jcWZGA8SN9o7HY8GHnd+D15rlhx6cml2pNLVUnudLFZVZKr0TGR15FojpzJvLMw8Hlr7SFjTCHwvDHmcWvt0Rn8m5Lm3C4nLZVFtFQWXfK8tRb/yNR00dYZGKVvNMjQRIjhyRDnBicYmggzPBG6ZB77bMnJclDozqLQ7aLQnUVBThbl5fkU57qoKHLHC7EcKorcVBS5KS/ITmrPpoiktrfTmSmZqTjXxfZlFWxfVnHJ88FwlPNDE5yOF26n4yNXp/vH2dfZx0QowkQo8jsjWDOVl+3Ek5dNWUE2nrxsGrwFlOZn48nPpuyy24qiWMEoIlfH2/52WWvPA+fj90eMMceAKkCFmlwxY8x0EbRxSfmbnjsZijAcL+BeLd6mwlGMARP/t2K38YPYC6++5nIaitwuCnKyYkWZOyujFzoRkatCnZkyI9lZjtiU+bfYky0atUyGI0wEXy3cIkwEoxcVchFcTkO200l2liN2OB1kZ1323PTz6oQUSRWz0g1ijKkDVgH7X+e1e4F7AWpqambj7STDueNTPXxF7mSHIiLyutSZKXPF4TDkZWel1eJcIhIz424TY0wB8C/A56y1w5e/bq19yFq7xlq7xuv1zvTtRERE5pU36sw0xtxrjDlojDkYCASSEZqIiKSwGRVqxhgXsSLtJ9ban89OSCIiIunhzToz1ZEpIiJv5m0Xaia2nN3DwDFr7VdmLyQREZH5T52ZIiIyEzMZUdsEfAzYaox5MX7cMUtxiYiIzFvqzBQRkZmayaqPTxFbSE9EREQu9Wpn5ivGmBfjz/2FtfZXSYxJRETmES0RJCIiMsvUmSkiIjOlzTJERERERERSjAo1ERERERGRFKNCTUREREREJMUYa+3cvZkxAeDkDP+ZcqB3FsJJd2qnxKmtEqN2SpzaCmqttdocLEGzlB9Bn71EqZ0So3ZKnNoqMWqnmIRy5JwWarPBGHPQWrsm2XGkOrVT4tRWiVE7JU5tJcmiz15i1E6JUTslTm2VGLXTldHURxERERERkRSjQk1ERERERCTFzMdC7aFkBzBPqJ0Sp7ZKjNopcWorSRZ99hKjdkqM2ilxaqvEqJ2uwLy7Rk1ERERERCTdzccRNRERERERkbSmQk1ERERERCTFpGyhZoy5zRjTZow5box58HVezzHG/DT++n5jTN3cR5l8CbTTnxhjjhpjXjbG7DDG1CYjzlTwVm110XnvN8ZYY0xGLh+bSDsZYz4U/1wdMcb841zHmAoS+O7VGGN2GWNeiH//7khGnJJ+lB8TpxyZGOXHxCg/Jk45cpZYa1PuAJxAJ1APZAMvAcsuO+c/At+O3/8I8NNkx52i7XQLkBe/f38mtlOibRU/rxB4EtgHrEl23KnYTkAj8ALgiT/2JTvuFG2nh4D74/eXASeSHbeO+X8oP856W2V8jlR+nNXPU8bnxytoK+XIBI5UHVFbBxy31nZZa4PAPwHvueyc9wA/iN//GbDNGGPmMMZU8JbtZK3dZa0djz/cB1TPcYypIpHPFMB/B/4amJzL4FJIIu10D/BNa+0AgLXWP8cxpoJE2skCRfH7xcC5OYxP0pfyY+KUIxOj/JgY5cfEKUfOklQt1KqA0xc9PhN/7nXPsdaGgSGgbE6iSx2JtNPFPgX8+qpGlLresq2MMauBRdba/zeXgaWYRD5TTUCTMeZpY8w+Y8xtcxZd6kiknf4b8IfGmDPAr4DPzE1okuaUHxOnHJkY5cfEKD8mTjlylmQlOwCZG8aYPwTWAJuTHUsqMsY4gK8An0hyKPNBFrHpHVuI9T4/aYxZaa0dTGpUqecPgO9ba//OGLMB+JExZoW1NprswETkUsqRb0z58YooPyZOOTIBqTqidhZYdNHj6vhzr3uOMSaL2LBp35xElzoSaSeMMduBLwLvttZOzVFsqeat2qoQWAHsNsacAG4AfpGBF0wn8pk6A/zCWhuy1nYD7cQSUyZJpJ0+BTwKYK19FnAD5XMSnaQz5cfEKUcmRvkxMcqPiVOOnCWpWqg9BzQaYxYbY7KJXQz9i8vO+QVwV/z+B4CdNn5FYgZ5y3YyxqwCvkMsAWXqXGl4i7ay1g5Za8uttXXW2jpi1yq821p7MDnhJk0i371/I9ZbiDGmnNhUj665DDIFJNJOp4BtAMaYpcSSUGBOo5R0pPyYOOXIxCg/Jkb5MXHKkbMkJQu1+Jz6PwZ+CxwDHrXWHjHGfNkY8+74aQ8DZcaY48CfAG+4nGy6SrCd/gYoAP7ZGPOiMebyL0pGSLCtMl6C7fRboM8YcxTYBXzBWptRvfUJttPngXuMMS8BjwCfyNA/lmUWKT8mTjkyMcqPiVF+TJxy5OwxahMREREREZHUkpIjaiIiIiIiIplMhZqIiIiIiEiKUaEmIiIiIiKSYlSoiYiIiIiIpBgVaiIiIiIiIilGhZqIiIiIiEiKUaEmIiIiIiKSYv4/VWijcIZwXXIAAAAASUVORK5CYII=\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7ff760362290>"
+       "<matplotlib.figure.Figure at 0x7f4a2d4b6690>"
       ]
      },
      "metadata": {
@@ -502,9 +252,9 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7ff75fd87550>"
+       "<matplotlib.figure.Figure at 0x7f4a2d4b6990>"
       ]
      },
      "metadata": {
@@ -514,9 +264,9 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7ff760552290>"
+       "<matplotlib.figure.Figure at 0x7f4a2ce43ed0>"
       ]
      },
      "metadata": {
@@ -538,7 +288,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 74,
+   "execution_count": 30,
    "metadata": {},
    "outputs": [],
    "source": [