diff --git a/crocoddyl/actuation.py b/crocoddyl/actuation.py
index 24dba758145b94cd49c510f92b6049ed238b4b5b..52dd89714607528090bcf7f76e85aed0e9ffd321 100644
--- a/crocoddyl/actuation.py
+++ b/crocoddyl/actuation.py
@@ -51,7 +51,7 @@ class ActuationModelUAM:
     We implement here the simplest model: tau = S.T*u, where S is constant.
     '''
 
-    def __init__(self, pinocchioModel, quadrotorType, rotorDistance, coefM, coefF):
+    def __init__(self, pinocchioModel, quadrotorType, rotorDistance, coefM, coefF, uLim, lLim):
         self.pinocchio = pinocchioModel
         if (pinocchioModel.joints[1].shortname() != 'JointModelFreeFlyer'):
             warnings.warn('Strange that the first joint is not a freeflyer')
@@ -73,17 +73,30 @@ class ActuationModelUAM:
         self.d = rotorDistance
         self.cm = coefM
         self.cf = coefF
+        self.uLim = uLim
+        self.lLim = lLim
 
     def calc(self, data, x, u):
         d, cf, cm = self.d, self.cf, self.cf
-        S = np.array(np.zeros([self.nv, self.nu]))
+        uLim, lLim = self.uLim, self.lLim
+
+        # Jacobian of torques with respect motor vertical forces
+        J_tau_f = np.array(np.zeros([self.nv, self.nu]))
         if self.type == 'x':
-            S[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
+            J_tau_f[2:6, :4] = np.array([[1, 1, 1, 1], [-d, d, d, -d], [-d, d, -d, d], [-cm / cf, -cm / cf, cm / cf, cm / cf]])
         elif self.type == '+':
-            S[2:6, :4] = np.array([[1, 1, 1, 1], [0, d, 0, -d], [-d, 0, d, 0], [-cm / cf, cm / cf, -cm / cf, cm / cf]])
-
-        np.fill_diagonal(S[6:, 4:], 1)
-        data.a = np.dot(S, u)
+            J_tau_f[2:6, :4] = np.array([[1, 1, 1, 1], [0, d, 0, -d], [-d, 0, d, 0], [-cm / cf, cm / cf, -cm / cf, cm / cf]])
+
+        np.fill_diagonal(J_tau_f[6:, 4:], 1)
+        # Actuation function - tanh
+        range = uLim - lLim
+        range = uLim - lLim
+        f = lLim + range / 2 + range / 2 * np.tanh(u)
+        d_f = range / 2 * np.tanh(u)**2
+        J_f_u = np.zeros([4, 4])
+        np.fill_diagonal(J_f_u, d_f)
+
+        data.a = np.dot(J_tau_f, f)
         return data.a
 
     def calcDiff(self, data, x, u, recalc=True):
diff --git a/examples/notebooks/kinton/quadcopter_mission.ipynb b/examples/notebooks/kinton/quadcopter_mission.ipynb
index 9070e399eb4eb9a808eca18a2b4f7eb959f6c9b1..f532ca00a844ad84c8ce379890a98faab4a3a678 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": 31,
+   "execution_count": 9,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -14,7 +14,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 32,
+   "execution_count": 10,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -30,7 +30,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 37,
+   "execution_count": 17,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -78,8 +78,8 @@
     "    uLimCost = CostModelControl(rmodel, \n",
     "                                nu=robot.\n",
     "                                model.nv-2,\n",
-    "                                activation = ActivationModelInequalityCont(np.array([0.1, 0.1, 0.1, 0.1]), \n",
-    "                                                                    np.array([10, 10, 10, 10])))\n",
+    "                                activation = ActivationModelInequality(np.array([0.1, 0.1, 0.1, 0.1]), \n",
+    "                                                                    np.array([5, 5, 5, 5])))\n",
     "\n",
     "    # Then let's add the running and terminal cost functions\n",
     "    runningCostModel.addCost(name=\"pos\", weight=0.01, cost=goalTrackingCost)\n",
@@ -102,7 +102,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 38,
+   "execution_count": 18,
    "metadata": {
     "scrolled": true
    },
@@ -131,7 +131,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 39,
+   "execution_count": 19,
    "metadata": {
     "scrolled": true
    },
@@ -176,7 +176,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": null,
+   "execution_count": 20,
    "metadata": {
     "scrolled": true
    },
@@ -186,44 +186,216 @@
      "output_type": "stream",
      "text": [
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\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",
+      "   0  2.19793e-01  2.82170e-03  5.13687e+00  1.00000e-08  1.00000e-08   0.0020     0\n",
+      "   1  2.19793e-01  2.82204e-03  5.13714e+00  1.00000e-07  1.00000e-07   0.0020     0\n",
+      "   2  2.19793e-01  2.82540e-03  5.13980e+00  1.00000e-06  1.00000e-06   0.0020     0\n",
+      "   3  1.82700e-01  2.85885e-03  2.80245e+00  1.00000e-06  1.00000e-06   0.5000     0\n",
+      "   4  1.72132e-01  6.98676e-04  6.86336e-01  1.00000e-06  1.00000e-06   0.5000     0\n",
+      "   5  1.99085e-01  1.45051e-04  2.65010e-02  1.00000e-07  1.00000e-07   1.0000     1\n",
+      "   6  1.97153e-01  2.93350e-06  8.42567e-03  1.00000e-07  1.00000e-07   0.5000     1\n",
+      "   7  1.94673e-01  1.87375e-06  4.48305e-03  1.00000e-08  1.00000e-08   1.0000     1\n",
+      "   8  1.93497e-01  2.13372e-06  5.24922e-03  1.00000e-08  1.00000e-08   0.5000     1\n",
+      "   9  1.92935e-01  1.35144e-06  3.16197e-03  1.00000e-09  1.00000e-09   1.0000     1\n",
       "iter \t cost \t      stop \t    grad \t  xreg \t      ureg \t step \t feas\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",
+      "  10  1.91723e-01  2.78168e-06  6.96713e-03  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  11  1.91227e-01  8.39122e-07  2.00024e-03  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  12  1.90919e-01  4.66741e-07  7.15792e-04  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  13  1.90668e-01  5.65125e-07  1.11825e-03  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  14  1.90339e-01  1.65213e-07  5.80916e-04  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  15  1.90301e-01  9.16991e-08  3.40028e-04  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  16  1.90203e-01  5.24014e-08  1.47559e-04  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  17  1.90186e-01  6.51201e-08  2.60875e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  18  1.90181e-01  2.23352e-08  7.24686e-05  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  19  1.90148e-01  1.36209e-07  7.69946e-04  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",
-      "  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",
+      "  20  1.90139e-01  1.79946e-08  6.23730e-05  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  21  1.90120e-01  9.32969e-08  5.02698e-04  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  22  1.90101e-01  1.06761e-08  4.54366e-05  1.00000e-09  1.00000e-09   0.5000     1\n",
+      "  23  1.90092e-01  4.32226e-09  1.01882e-05  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  24  1.90088e-01  2.52620e-09  6.05586e-06  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  25  1.90088e-01  4.38477e-09  2.26492e-05  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  26  1.90086e-01  5.00655e-09  2.61031e-05  1.00000e-09  1.00000e-09   0.1250     1\n",
+      "  27  1.90083e-01  1.21993e-09  2.87732e-06  1.00000e-09  1.00000e-09   1.0000     1\n",
+      "  28  1.90083e-01  1.20381e-09  4.64485e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  29  1.90083e-01  1.20530e-09  5.05983e-06  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",
-      "  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"
+      "  30  1.90082e-01  1.26406e-09  5.61674e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  31  1.90082e-01  1.32343e-09  6.33826e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  32  1.90082e-01  1.44942e-09  7.25168e-06  1.00000e-09  1.00000e-09   0.2500     1\n",
+      "  33  1.90081e-01  1.58158e-09  8.39141e-06  1.00000e-09  1.00000e-09   0.1250     1\n",
+      "  34  1.90081e-01  3.91073e-10  9.16725e-07  1.00000e-09  1.00000e-09   1.0000     1\n"
      ]
+    },
+    {
+     "data": {
+      "text/plain": [
+       "([array([0., 0., 0., 0., 0., 0., 1., 0., 0., 0., 0., 0., 0.]),\n",
+       "  array([-3.06865942e-08,  3.44297617e-04,  8.39738253e-03, -4.09661670e-02,\n",
+       "         -1.24107082e-05, -3.20571572e-04,  9.99160483e-01,  0.00000000e+00,\n",
+       "          0.00000000e+00,  2.80226343e-01, -2.73184232e+00, -8.27612159e-04,\n",
+       "         -2.13774207e-02]),\n",
+       "  array([-6.02108757e-08,  2.48181051e-03,  2.59832153e-02, -7.79900946e-02,\n",
+       "         -1.28827741e-05, -2.89230440e-04,  9.96954092e-01, -8.07108996e-06,\n",
+       "          1.12641502e-03,  5.90643055e-01, -2.47278245e+00, -9.10328535e-04,\n",
+       "          2.07031922e-03]),\n",
+       "  array([ 1.58799534e-07,  7.48579971e-03,  5.24273913e-02, -1.05324132e-01,\n",
+       "         -1.66602459e-05, -2.56181547e-04,  9.94437912e-01, -1.27075709e-05,\n",
+       "          3.07560724e-03,  8.97222753e-01, -1.83003091e+00, -9.52233146e-04,\n",
+       "          2.15213739e-03]),\n",
+       "  array([ 6.89257766e-07,  1.60338019e-02,  8.70069179e-02, -1.23478781e-01,\n",
+       "         -1.94921206e-05, -2.25819634e-04,  9.92347187e-01, -1.25113810e-05,\n",
+       "          1.54662138e-02,  1.18731161e+00, -1.21832607e+00, -7.13351955e-04,\n",
+       "          1.97755194e-03]),\n",
+       "  array([ 1.46350612e-06,  2.84213856e-02,  1.28708048e-01, -1.34073264e-01,\n",
+       "         -2.08947285e-05, -1.97998119e-04,  9.90971402e-01, -1.39824361e-05,\n",
+       "          4.41936386e-02,  1.44942546e+00, -7.12232515e-01, -4.83109188e-04,\n",
+       "          1.82211732e-03]),\n",
+       "  array([ 2.38110123e-06,  4.47166232e-02,  1.76621348e-01, -1.38677212e-01,\n",
+       "         -2.11583938e-05, -1.72420777e-04,  9.90337620e-01, -1.83724564e-05,\n",
+       "          9.14268254e-02,  1.68447633e+00, -3.09824673e-01, -3.07690329e-04,\n",
+       "          1.68545772e-03]),\n",
+       "  array([ 3.34243606e-06,  6.47721188e-02,  2.29724267e-01, -1.38675184e-01,\n",
+       "         -2.06428167e-05, -1.48773064e-04,  9.90337907e-01, -2.46080756e-05,\n",
+       "          1.56606765e-01,  1.88563865e+00,  1.36567806e-04, -1.84563175e-04,\n",
+       "          1.56604831e-03]),\n",
+       "  array([ 4.26154670e-06,  8.83761022e-02,  2.87212055e-01, -1.35185085e-01,\n",
+       "         -1.96384460e-05, -1.26663076e-04,  9.90820355e-01, -3.09863274e-05,\n",
+       "          2.37450043e-01,  2.05784827e+00,  2.34885930e-01, -1.02816774e-04,\n",
+       "          1.46902771e-03]),\n",
+       "  array([ 4.98659620e-06,  1.15290801e-01,  3.48473753e-01, -1.29136607e-01,\n",
+       "         -1.73459376e-05, -9.78366980e-05,  9.91626808e-01, -3.57059206e-05,\n",
+       "          3.30790348e-01,  2.20579343e+00,  4.06800873e-01, -5.62320916e-05,\n",
+       "          1.92368131e-03]),\n",
+       "  array([ 5.70557019e-06,  1.45266732e-01,  4.13033966e-01, -1.21334351e-01,\n",
+       "         -1.65245135e-05, -8.35540123e-05,  9.92611690e-01, -3.04556516e-05,\n",
+       "          4.33083272e-01,  2.33282781e+00,  5.24279475e-01, -1.66295532e-05,\n",
+       "          9.48689121e-04]),\n",
+       "  array([ 6.20235086e-06,  1.77958510e-01,  4.80353147e-01, -1.11746229e-01,\n",
+       "         -1.53753681e-05, -6.78022056e-05,  9.93736774e-01, -3.25876711e-05,\n",
+       "          5.40664630e-01,  2.43532156e+00,  6.43596237e-01,  3.27587818e-06,\n",
+       "          1.04737790e-03]),\n",
+       "  array([ 6.55849969e-06,  2.11516809e-01,  5.42323645e-01, -1.02445187e-01,\n",
+       "         -1.39210163e-05, -4.98006127e-05,  9.94738650e-01, -2.92914707e-05,\n",
+       "          6.53047417e-01,  2.25655174e+00,  6.23658656e-01,  5.31128604e-06,\n",
+       "          1.19843652e-03]),\n",
+       "  array([ 6.84958623e-06,  2.45526509e-01,  5.97122078e-01, -9.37255043e-02,\n",
+       "         -1.25013907e-05, -3.23320139e-05,  9.95598076e-01, -1.73256883e-05,\n",
+       "          7.55248940e-01,  2.01281271e+00,  5.84130771e-01,  4.58620890e-06,\n",
+       "          1.16291737e-03]),\n",
+       "  array([ 7.06762333e-06,  2.79989545e-01,  6.44984057e-01, -8.55523691e-02,\n",
+       "         -1.11461277e-05, -1.52143901e-05,  9.96333675e-01, -3.63442972e-07,\n",
+       "          8.45445307e-01,  1.77490157e+00,  5.47079617e-01,  1.22596453e-06,\n",
+       "          1.13940638e-03]),\n",
+       "  array([ 7.19422289e-06,  3.14988689e-01,  6.86670164e-01, -7.78683959e-02,\n",
+       "         -9.88333808e-06,  1.73103418e-06,  9.96963647e-01,  2.11677562e-05,\n",
+       "          9.24747184e-01,  1.56101413e+00,  5.13984894e-01, -4.50889087e-06,\n",
+       "          1.12769581e-03]),\n",
+       "  array([ 7.20975672e-06,  3.50598077e-01,  7.23006557e-01, -7.06454289e-02,\n",
+       "         -8.73422673e-06,  1.86799579e-05,  9.97501490e-01,  4.69435849e-05,\n",
+       "          9.94511485e-01,  1.37366481e+00,  4.82865334e-01, -1.20901572e-05,\n",
+       "          1.12765134e-03]),\n",
+       "  array([ 7.09604237e-06,  3.86865217e-01,  7.54763505e-01, -6.38826698e-02,\n",
+       "         -7.71184345e-06,  3.58065793e-05,  9.97957416e-01,  7.67343129e-05,\n",
+       "          1.05588834e+00,  1.21125950e+00,  4.51874898e-01, -2.08291316e-05,\n",
+       "          1.13924026e-03]),\n",
+       "  array([ 6.83682148e-06,  4.23811629e-01,  7.82630581e-01, -5.75962264e-02,\n",
+       "         -6.82153915e-06,  5.32855216e-05,  9.98339958e-01,  1.10394969e-04,\n",
+       "          1.10983301e+00,  1.07138704e+00,  4.19872157e-01, -3.00176412e-05,\n",
+       "          1.16253685e-03]),\n",
+       "  array([ 6.41756436e-06,  4.61437593e-01,  8.07216018e-01, -5.18095951e-02,\n",
+       "         -6.06198708e-06,  7.12938577e-05,  9.98656979e-01,  1.47864384e-04,\n",
+       "          1.15717324e+00,  9.51626967e-01,  3.86354469e-01, -3.90070260e-05,\n",
+       "          1.19772820e-03]),\n",
+       "  array([ 5.82508730e-06,  4.99727341e-01,  8.29050762e-01, -4.65463987e-02,\n",
+       "         -5.42637961e-06,  9.00131622e-05,  9.98916125e-01,  1.89168181e-04,\n",
+       "          1.19865736e+00,  8.49691012e-01,  3.51305243e-01, -4.72501113e-05,\n",
+       "          1.24512001e-03]),\n",
+       "  array([ 5.04712187e-06,  5.38653903e-01,  8.48593063e-01, -4.18251868e-02,\n",
+       "         -4.90368149e-06,  1.09631579e-04,  9.99124938e-01,  2.34422393e-04,\n",
+       "          1.23497990e+00,  7.63424330e-01,  3.15055466e-01, -5.43250802e-05,\n",
+       "          1.30514268e-03]),\n",
+       "  array([ 4.07187116e-06,  5.78183389e-01,  8.66233374e-01, -3.76559534e-02,\n",
+       "         -4.47989661e-06,  1.30345913e-04,  9.99290755e-01,  2.83836497e-04,\n",
+       "          1.26679228e+00,  6.90800832e-01,  2.78168843e-01, -5.99490654e-05,\n",
+       "          1.37835794e-03]),\n",
+       "  array([ 2.88755874e-06,  6.18278661e-01,  8.82299981e-01, -3.40380727e-02,\n",
+       "         -4.13932092e-06,  1.52363772e-04,  9.99420525e-01,  3.37715707e-04,\n",
+       "          1.29470562e+00,  6.29936833e-01,  2.41347291e-01, -6.39844026e-05,\n",
+       "          1.46546621e-03]),\n",
+       "  array([ 1.48196718e-06,  6.58902336e-01,  8.97065725e-01, -3.09593828e-02,\n",
+       "         -3.86575666e-06,  1.75905786e-04,  9.99520628e-01,  3.96462898e-04,\n",
+       "          1.31928981e+00,  5.79120847e-01,  2.05354550e-01, -6.64391384e-05,\n",
+       "          1.56731500e-03]),\n",
+       "  array([-1.58043561e-07,  7.00019113e-01,  9.10756144e-01, -2.83961616e-02,\n",
+       "         -3.64366765e-06,  2.01207934e-04,  9.99596727e-01,  4.60580652e-04,\n",
+       "          1.34107151e+00,  5.36858521e-01,  1.70956758e-01, -6.74632478e-05,\n",
+       "          1.68490850e-03]),\n",
+       "  array([-2.04706476e-06,  7.41597511e-01,  9.23559968e-01, -2.63137684e-02,\n",
+       "         -3.45926121e-06,  2.28524027e-04,  9.99653707e-01,  5.30673870e-04,\n",
+       "          1.36053211e+00,  5.01952483e-01,  1.38878202e-01, -6.73418159e-05,\n",
+       "          1.81941870e-03]),\n",
+       "  array([-4.20179993e-06,  7.83611232e-01,  9.35645658e-01, -2.46677864e-02,\n",
+       "         -3.30148014e-06,  2.58128368e-04,  9.99695671e-01,  6.07453297e-04,\n",
+       "          1.37810631e+00,  4.73707308e-01,  1.09767808e-01, -6.64851387e-05,\n",
+       "          1.97219810e-03]),\n",
+       "  array([-6.64215093e-06,  8.26040857e-01,  9.47197281e-01, -2.34056153e-02,\n",
+       "         -3.16285820e-06,  2.90318651e-04,  9.99726009e-01,  6.91740316e-04,\n",
+       "          1.39418125e+00,  4.52580858e-01,  8.41690568e-02, -6.54123695e-05,\n",
+       "          2.14479441e-03]),\n",
+       "  array([-9.39374587e-06,  8.68877887e-01,  9.58514977e-01, -2.24684390e-02,\n",
+       "         -3.04011634e-06,  3.25419105e-04,  9.99747500e-01,  7.84473852e-04,\n",
+       "          1.40909678e+00,  4.42346046e-01,  6.24948574e-02, -6.47234288e-05,\n",
+       "          2.33896743e-03]),\n",
+       "  array([-1.24957567e-05,  9.12137579e-01,  9.70331963e-01, -2.17911817e-02,\n",
+       "         -2.93414834e-06,  3.63789947e-04,  9.99762478e-01,  8.86722383e-04,\n",
+       "          1.42314764e+00,  4.57320033e-01,  4.51615339e-02, -6.51025795e-05,\n",
+       "          2.55710697e-03]),\n",
+       "  array([-1.80324622e-05,  9.55895802e-01,  9.84868231e-01, -2.09122904e-02,\n",
+       "         -1.76673215e-06,  4.52458046e-04,  9.99781212e-01,  9.99729232e-04,\n",
+       "          1.43659041e+00,  5.46373945e-01,  5.86061045e-02, -7.23147160e-05,\n",
+       "          5.91087302e-03]),\n",
+       "  array([-1.05718807e-08,  9.99711941e-01,  9.99880260e-01, -4.10434724e-06,\n",
+       "         -1.35024700e-08, -5.16445972e-07,  1.00000000e+00,  1.26018929e-03,\n",
+       "          1.44985714e+00,  5.30879352e-01,  1.39398075e+00,  1.17734566e-04,\n",
+       "         -3.02005120e-02])],\n",
+       " [array([ 7.07638729,  3.62814392,  7.07430333, 10.50701244]),\n",
+       "  array([7.42870946, 7.76131752, 7.42456446, 7.10899509]),\n",
+       "  array([7.35059898, 8.15998316, 7.35083856, 6.54151384]),\n",
+       "  array([7.11000621, 7.88052264, 7.11087322, 6.34022993]),\n",
+       "  array([6.73076678, 7.36826143, 6.73150895, 6.09390136]),\n",
+       "  array([6.37333678, 6.88018977, 6.37386597, 5.86691368]),\n",
+       "  array([5.94837972, 6.33875522, 5.94872496, 5.55826269]),\n",
+       "  array([5.60255737, 5.89817832, 5.6027632 , 5.30707175]),\n",
+       "  array([5.33136899, 5.54802493, 5.33146303, 5.11513748]),\n",
+       "  array([5.11495177, 5.26252849, 5.11499874, 4.96671353]),\n",
+       "  array([4.86102773, 5.01129365, 4.86104433, 4.71085013]),\n",
+       "  array([1.4599985 , 1.43493149, 1.45995818, 1.48513497]),\n",
+       "  array([0.69670841, 0.64690315, 0.6966562 , 0.74643566]),\n",
+       "  array([0.79334347, 0.74665979, 0.79328922, 0.83995581]),\n",
+       "  array([1.10753723, 1.06583794, 1.10748077, 1.14917154]),\n",
+       "  array([1.44799252, 1.40878338, 1.44793436, 1.48714346]),\n",
+       "  array([1.76459389, 1.72555128, 1.76453518, 1.80358622]),\n",
+       "  array([2.04738485, 2.00707242, 2.04732701, 2.08765637]),\n",
+       "  array([2.29635   , 2.2541357 , 2.29629446, 2.33853434]),\n",
+       "  array([2.51333567, 2.46919936, 2.51328372, 2.55745447]),\n",
+       "  array([2.70034926, 2.65470835, 2.70030196, 2.74598648]),\n",
+       "  array([2.85947289, 2.81303769, 2.85943101, 2.90591942]),\n",
+       "  array([2.99305465, 2.94670936, 2.99301865, 3.03942724]),\n",
+       "  array([3.10386621, 3.05857275, 3.10383619, 3.14920366]),\n",
+       "  array([3.19524859, 3.1519718 , 3.19522432, 3.23858657]),\n",
+       "  array([3.27150697, 3.23115885, 3.27148785, 3.31193371]),\n",
+       "  array([3.33942399, 3.3028216 , 3.33940912, 3.37612253]),\n",
+       "  array([3.4137344 , 3.38156191, 3.41372251, 3.44602042]),\n",
+       "  array([3.53570053, 3.50847768, 3.53569009, 3.56305404]),\n",
+       "  array([3.83547242, 3.81372333, 3.83546161, 3.85736922]),\n",
+       "  array([4.73814355, 4.75627604, 4.7381176 , 4.72242218]),\n",
+       "  array([3.46588252, 5.13424821, 3.46633772, 1.77173109])],\n",
+       " True)"
+      ]
+     },
+     "execution_count": 20,
+     "metadata": {},
+     "output_type": "execute_result"
     }
    ],
    "source": [
@@ -233,16 +405,16 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 29,
+   "execution_count": 21,
    "metadata": {
     "scrolled": false
    },
    "outputs": [
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "iVBORw0KGgoAAAANSUhEUgAAA2QAAAKGCAYAAAAlE1j1AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAIABJREFUeJzs3Xd4lfXh/vH352TvPSCEMILsHUBAqbt1r6po3VrUujt+rbV+u3etdbXWuhdutG7rFpkh7L3JIOMEMk4g+/P7IwlSyghwznnOOblf1+VVyHk4545X5cn9fJax1iIiIiIiIiL+53I6gIiIiIiISE+lQiYiIiIiIuIQFTIRERERERGHqJCJiIiIiIg4RIVMRERERETEISpkIiIiIiIiDlEhExGRgGc6PGmM2WmMWeB0HhEREW9RIRMRkT2MMVuMMc3GmPR9vr7YGGONMf268R5XG2NmeznaccCpQB9r7UQvv7eIiIhjVMhERGRfm4FLu35jjBkJxPrrw40x4fv5ch6wxVrb4KX3ExERCQgqZCIisq9ngSv3+v1VwDN7X2CMSTLGPGOMqTLGbDXG/MwY4zLGDAUeASYbYzzGmJqDXd/52tXGmK+MMfcZY6qBX+zzWdcBj+31nr/s/Pp3jTEbjDE7jDH/Nsb03uvPWGPMzcaY9cD6zq8NN8b8p/P6CmPMTzu/7jLG/MQYs9EYU22MedkYk9r5WrQx5rnOr9cYYxYaY7K8969aRER6OhUyERHZ1zwg0Rgz1BgTBkwHntvnmgeBJGAA8A06Ctw11trVwI3AXGttvLU2+WDX7/V+k4BNQBbw270/yFr7+D7v+XNjzEnA74GLgV7AVuDFfTKe1/m+w4wxCcBHwPtAbyAf+Ljzuls7r/1G52s7gYc7X7uqM3cukNaZY/fB/uWJiIgcDk3jEBGR/ekaJfscWA2Udr2wV0kbY62tB+qNMfcCVwCP7/tG3by+zFr7YOevW7uR7zvAE9baos7PuAvYaYzpZ63d0nnN7621OzpfvxQot9be2/laIzC/89c3ArdYa0s6r/0FsM0YcwXQQkcRy7fWLgMWdSObiIhIt6mQiYjI/jwLfAH0Z5/pikA6EEHHqFSXrUDOAd6rO9cXH2a+3kBR12+stZ7O6Y45wJb9vGcusPEA75UHzDLGtO/1tTY6Ruue7fyzLxpjkukYKbzbWttymHlFRET2S1MWRUTkf1hrt9KxuccZwOv7vOymY+Qob6+v9eXrUTR7mNfv788cStne72eMiaNjJOtA71lMx3TJ/SkGTrfWJu/1T7S1ttRa22Kt/aW1dhgwBTiL/15fJyIiclRUyERE5ECuA07ad2dDa20b8DLwW2NMgjEmD/g+X68zqwD6GGMiu3n9kZgJXGOMGWOMiQJ+B8zfa7rivt4Gehlj7jDGRHXmmNT52iOd2fIAjDEZxphzO399ojFmZOe0yzo6imX7/j5ARETkSKiQiYjIfllrN1prCw/w8q1AAx0bccwGXgCe6HztE2AlUG6McXfj+iPJ9hFwD/AasB0YSMc6tQNdX0/HOWZnA+V07Lx4YufL9wP/Bj40xtTTsalJV1nLBl6lo4ytpmNN3bNHmltERGRfxtrDnSUiIiIiIiIi3qARMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHKJCJiIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHKJCJiIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHKJCJiIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHKJCJiIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHKJCJiIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIpMcxxmwxxjQbY9L3+fpiY4w1xvTrxntcbYyZ7eVcI4wxHxhj3MYY6833FhEROZQAvj9eZYxZZIypM8aUGGP+ZIwJ9+ZniDhJhUx6qs3ApV2/McaMBGL99eEHuJG0AC8D1/krh4iIyD4C8f4YC9wBpAOTgJOBH/ork4ivqZBJT/UscOVev78KeGbvC4wxScaYZ4wxVcaYrcaYnxljXMaYocAjwGRjjMcYU3Ow6ztfu9oY85Ux5j5jTDXwi30DWWvXWmsfB1b65lsWERE5pEC8P/7DWvultbbZWlsKPA9M9cl3L+IAFTLpqeYBicaYocaYMGA68Nw+1zwIJAEDgG/QcYO6xlq7GrgRmGutjbfWJh/s+r3ebxKwCcgCfuuT70pEROToBMP9cRp6eCkhRPNvpSfregr4ObAaKO16Ya+b0BhrbT1Qb4y5F7gCeHzfN+rm9WXW2gc7f93qm29JRETkqAXs/dEYcy1QAFx/5N+eSGBRIZOe7FngC6A/+0zHoGOeegSwda+vbQVyDvBe3bm++GjCioiI+ElA3h+NMecBvwdOsda6u/NnRIKBpixKj2Wt3UrH4uUzgNf3edlNxyYbeXt9rS9fPyXcdxfEQ12/vz8jIiIScALx/miM+RbwL+Bsa+3yQ10vEkxUyKSnuw44yVrbsPcXrbVtdOx4+FtjTIIxJg/4Pl/Po68A+hhjIrt5/SGZDtFAZOfvo40xUUf37YmIiByRQLo/nkTHRh4XWmsXHOX3JRJwVMikR7PWbrTWFh7g5VuBBjoWGs8GXgCe6HztEzoWFJcbY9zduL478oDdfL1QeTew9jD+vIiIiFcE2P3xHjo2BXm3c/dGjzHmvcP5fkQCmbFWs6hEREREREScoBEyERERERERh6iQiYiIiIiIOESFTERERERExCEqZCIiIiIiIg7xycHQ6enptl+/fr54axERCSCLFi1yW2sznM4RLHR/FBHpObp7j/RJIevXrx+FhQfaKVVEREKFMWar0xmCie6PIiI9R3fvkZqyKCIiIiIi4hAVMhEREREREYeokImIiIiIiDhEhUxERERERMQhKmQiIiIiIiIOUSETERERERFxiAqZiIiIiIiIQ1TIREREREREHBL0hayqvolFW3fS1NrmdBQREZGgtaK0lvrGFqdjiIj0OOFOBzga6yvqueTReexoaCYy3MXoPkmMz0tlQr8UxuelkBwb6XREERGRgPdKYTE/enUZuakxPHzZOEb1SXY6kohIjxG0hWxb9S4uf3w+YS7DfZeMZvX2ehZu2cHjszfxyOcWgGOy4ino11HQCvJS6ZMSgzHG4eQiIiKB4/0V2/nxa8uY0C+FsppGLvzHHH56xlCuntJP90wRET8IykK2vXY3lz02j6bWdl6aMZnB2QmcP7bjtd3NbSwtqaFwyw4Kt+7krSVlvDB/GwBZiVGcPDSLH39rCEkxEQ5+ByIiEgqMMXcC1wMWWA5cY61tdDZV9325vorbZi5hTG4yT187kebWdn74ylJ++dYq5m2q5k/fHq37pYiIjwVdIXN7mvjOY/Op2dXCC9+dxODshP96PSYyjGMHpHHsgDQA2tot6yrqKdyyg/mbd/DywmI+X1vF36aPYUK/VCe+BRERCQHGmBzgNmCYtXa3MeZlYDrwlKPBumnR1p3MeGYRAzLiePLqicRGhhMbCf+6soDHZ2/mD++t4cwHvuShy8YxJldTGEVEfCWoNvWo3dXCFY8voKxmN09cPaFbc9zDXIahvRK5YnI/HrpsHK/eNIXwMMMl/5zLff9ZR2tbux+Si4hIiAoHYowx4UAsUOZwnm5Zvb2Oa55cQFZiFM9cN5Gk2K9HwYwxXH/8AF6+cTLWwkWPzOGJ2Zux1jqYWEQkdAVNIfM0tXL1UwvYWOnh0SsKmNj/yEa3xuQm885tx3Pe2Bzu/3g9lzw6j+Idu7ycVkREQp21thT4C7AN2A7UWms/3Pc6Y8wMY0yhMaawqqrK3zH/x2Z3A1c8voC4qHCeu34SmQnR+71uXN8U3rntOL5xTCa/ensVNzy7iNpd2oVRRMTbgqKQNba08d2nC1lWUsuDl41l2jEZR/V+8VHh/PXiMdw/fQzryus54/4v+ffSoHioKSIiAcIYkwKcC/QHegNxxpjL973OWvuotbbAWluQkXF096+jtb12N5c/Np92a3n2ukn0SYk96PXJsZH868rx/OzMoXyyppIzHviSJcU1fkorItIzBHwha25t53vPFzFvczX3XjSabw7P9tp7nzsmh3dvP578rHhum7mYH76yFE9Tq9feX0REQtopwGZrbZW1tgV4HZjicKYDqvY0cflj86nb3cIz104kPzO+W3+uawrjKzdOBjqmMD6uKYwiIl4T0IWsrd1y58tL+GRNJb89byTnjc3x+mfkpsbyyg2Tue2kfF4vKuGsB75kqZ7+iYjIoW0DjjXGxJqO/eFPBlY7nGm/6hpbuOrJBZTs3M3jV09gRE7SYb/H2L4pvHvb8ZwwOJNfv72Ke95c4YOkIiI9T8AWsvZ2y09eW8Y7y7Zz9xlDuWxSX599VniYi++fNpiZ3z2W5tZ2LvzHHB75fCPt7Xr6JyIi+2etnQ+8ChTRseW9C3jU0VD7sbu5jeufKmTN9noeuXz8Ea/BBkiKjeDRK8Zz7dT+PDdvG28v03R/EZGjFZCFzFrLr95exSuLSrj95EF8d9oAv3zupAFpvHf7NE4bnsUf3lvDlU8soEFTGEVE5ACstT+31g6x1o6w1l5hrW1yOtPeOqb9L2Lh1h3cd8kYThySedTvaYzhrjOGMCY3mbteX66NsUREjlJAFrJ7P1zHU3O2cP1x/bnjlEF+/eyk2Agevmwcv79gJHM2urnlhSJtjS8iIkHHWssPXlnKp2ur+N35Izl7dG+vvXdEmIsHLx0LFm57cTEtuk+KiByxQxYyY8xgY8ySvf6pM8bc4atAu5vb+GRNJZdO7MvdZw6lY1q+fxljuHRiX3593gg+XVvFPW+u0OJlEREJKqu31/PW0jJuO3kQl070/rT/3NRYfnvBSBZvq+FvH63z+vuLiPQU4Ye6wFq7FhgDYIwJA0qBWb4KFBMZxks3HEtsZLgjZWxv35mUx/aaRh76dAO9k2K49WT/jtaJiIgcqYq6RgBOGOy7rfbPGd2b2eur+PtnG5k6MJ0p+ek++ywRkVB1uFMWTwY2Wmu3+iJMl4ToCMJczpaxLj847RguGJvDvf9Zx6uLSpyOIyIi0i1Vno7lbBnxUT79nF+cM5z+6XHc8dISqj0BtYRORCQoHG4hmw7M3N8LxpgZxphCY0xhVVXV0ScLEMYY/nDhKKbmp/GT15bx5frQ+d5ERCR0uTvLUbqPC1lsZDgPXjqWml0t/OjVZZriLyJymLpdyIwxkcA5wCv7e91a+6i1tsBaW5CR4bvpEU6IDHfxj8vHk58Zz03PFbGyrNbpSCIiIgflrm8mLjKMmMgwn3/W8N5J3HXGED5ZU8mTX23x+eeJiISSwxkhOx0ostZW+CpMIEuMjuCpayaSEB3ONU8upLRmt9ORREREDsjtaSIjwbejY3u7eko/ThmayR/eW8OKUj24FBHprsMpZJdygOmKPUV2UjRPXTOR3S1tXP3EAmp3tTgdSUREZL+q6pt8Pl1xb8YY/vTt0aTERXDbzMU6x1NEpJu6VciMMXHAqcDrvo0T+AZnJ/DPK8azpbqBGc8W0tTa5nQkERGR/+H2+LeQAaTGRXLfJWPYXN3AL/690q+fLSISrLpVyKy1DdbaNGut5iAAUwam85eLRjN/8w5++Moy2tu1gFlERAKL29NEekKk3z93ysB0bjkxn1cWlfDmklK/f76ISLA53F0WpdO5Y3L4yelDeGtpGX98f43TcURERPZoaWtn564Wv4+Qdbn95EGMz0vh7lkr2Fa9y5EMIiLBQoXsKNwwbQBXHJvHP7/YxNNztjgdR0REBIAdDc2A77e8P5DwMBf3Tx+DMXDri4tpaWt3JIeISDBQITsKxhh+cc5wTh2WxS/eWsk7y7Y7HUlERISqev+cQXYwfVJi+eOFo1haXMNfPljrWA4RkUCnQnaUwlyGB6aPpSAvhTteWsxnayudjiQiIj1c16HQGQ6sIdvbGSN7cdmkvvzzi018vLpHnpojInJIKmReEBMZxmNXTWBQZgI3PreIhVt2OB1JRER6MLfH2SmLe/u/s4YxvHcid760hOIdWk8mIrIvFTIvSYqJ4JnrJtI7KYZrn1rIyjJtSCkiIs4IhCmLXaIjwvj7d8Zhge89X6TjYkRE9qFC5kXp8VE8e/0kEqLCufLxBWyq8jgdSUREeiC3p4nYyDDiosKdjgJAXloc9140muWltfz67VVOxxERCSgqZF6WkxzDc9dPAuDyx+ZTWrPb4UQiItLTOHEo9KGcNjybGdMG8Ny8bTqfTERkLypkPjAgI56nr51IfWMrVzw2f8/iahEREX/oKGTObuixPz/65mAm9EvhrteXs76i3uk4IiIBQYXMR0bkJPHENRMoq93NlY8voHZ3i9ORRESkh3DXNwfcCBlARJiLhy4bR2xkGDc9X0RDU6vTkUREHKdC5kMT+qXyyOXjWV9Zz3VPLWR3sxYyi4iI77k9TaQnBF4hA8hKjOb+6WPZVOXh7lnLsdY6HUlExFEqZD52wuBM/nbJWIq27eTG5xbR3NrudCQREfESY8xgY8ySvf6pM8bc4WSm1rZ2duwKzBGyLlPz07nzlGN4Y0kZz8/f5nQcERFHqZD5wZmjevG780fy+boq7nxpCW3tehooIhIKrLVrrbVjrLVjgPHALmCWk5l27GrGWsgIwDVke7v5xHxOGJzBr95axfISHRUjIj2XCpmfTJ/Yl5+eMYR3lm/np69rioaISAg6Gdhord3qZAh3feAcCn0wLpfhvovHkB4fyU3PL6J2l9Zai0jPpELmRzOmDeSWE/N5qbCYBz7e4HQcERHxrunAzH2/aIyZYYwpNMYUVlVV+TxEVefOvhkBuoZsbylxkTz8nXFU1DXyg1eW0K4ZJCLSA6mQ+dkPTjuG88fm8LeP1/Hpmkqn44iIiBcYYyKBc4BX9n3NWvuotbbAWluQkZHh8yzu+o5CFugjZF3G9k3h7jOG8tHqSh79cpPTcURE/E6FzM+MMfzu/JEMyU7k9hcXs7W6welIIiJy9E4Hiqy1FU4H6Tr7MlB3Wdyfq6b048xRvfjzB2uZt6na6TgiIn6lQuaAmMgw/nn5eIwx3PDsIm2HLyIS/C5lP9MVneD2NBEd4SIuMszpKN1mjOGPF44iLy2W22YuZmdDs9ORRET8RoXMIX3TYrl/+hjWVtRz1+vLtMmHiEiQMsbEAacCrzudBcDt6djy3hjjdJTDEh8VzkOXjmPnrmZ+9sYK3RdFpMdQIXPQCYMz+X7nOSxPz9nidBwRETkC1toGa22atTYg9m53e5qCZv3Yvob1TuTOU4/hneXb+ffSMqfjiIj4hQqZw24+MZ9Thmbym3dWs3DLDqfjiIhIkKuqD95CBnDDtIGMz0vhnjdWsL12t9NxRER8ToXMYS6X4a+XjCE3NZbvPV9EZV2j05FERCSIuT3NZCQE9qHQBxPmMvz14tG0tlt+9MoybYUvIiFPhSwAJEZH8Mjl4/E0tvK954tobm13OpKIiAShtnbLjobgHiEDyEuL4+4zhzJ7g5tn5zl6zraIiM+pkAWIwdkJ/OnboyjcupPfvrPK6TgiIhKEdjQ0026D5wyyg7lsYl9OGJzB799bzcYqj9NxRER8pluFzBiTbIx51Rizxhiz2hgz2dfBeqKzR/fm+uP68/TcrcxaXOJ0HBERCTJdZ5BlBNEZZAdijOFPF44iOiKM77+8lNY2zR4RkdDU3RGy+4H3rbVDgNHAat9F6tl+cvoQjh2Qyl2vL2dlWUBs2CUiIkFiz6HQITBCBpCZGM1vzhvB0uIa/v7ZRqfjiIj4xCELmTEmCZgGPA5grW221tb4OlhPFR7m4qHLxpEcE8mNzy2iZpcOxxQRke75upAF76Ye+zprVG/OHdObBz5ez/ISPagUkdDTnRGy/kAV8KQxZrEx5rHOQzD/izFmhjGm0BhTWFVV5fWgPUl6fBT/uHwcFbVN3P7iEtq0w5SIiHSDu77jIV56CExZ3NuvzhlBenwUd768hMaWNqfjiIh4VXcKWTgwDviHtXYs0AD8ZN+LrLWPWmsLrLUFGRkZXo7Z84ztm8LPzxnG5+uq+P27q7FWpUxERA7O7WkiMtxFQlS401G8Kik2gj9fNIoNlR7+/MFap+OIiHhVdwpZCVBirZ3f+ftX6Sho4mOXTezLVZPzeGz2Zu77aL3TcUREJMBVeZrIiI/CGON0FK87flAGV07O4/HZm5mz0e10HBERrzlkIbPWlgPFxpjBnV86GdC+7H5gjOHnZw/n4oI+PPDxeh7+dIPTkUREJIC5Pc0htX5sXz85fQj90+P40SvLqGtscTqOiIhXdHeXxVuB540xy4AxwO98F0n25nIZfn/BKM4d05s/f7CWx77c5HQkEREJUFX1wX8o9MHERobz14tHs712N7/8t54Ni0ho6NYkc2vtEqDAx1nkAMJchnsvGk1zazu/eWc1URFhXHFsntOxREQkwLg9TYzKSXI6hk+N7ZvCzSfm8+AnGzh1WBbfGpHtdCQRkaPS3REycVh4mIv7p4/llKGZ3PPGCl5eWOx0JBERCSDt7ZYdDc0hcSj0odx60iBG5CTy01nLKa3Z7XQcEZGjokIWRCLDO84oO35QOj9+fRlvLil1OpKIiASInbuaaWu3Ib2GrEtkuIu/XTKWltZ2rntqIZ6mVqcjiYgcMRWyIBMdEcajVxQwqX8q3395Ke8t3+50JBERCQBuT2ieQXYg+ZnxPPydcayv9HDbzMU6s1NEgpYKWRCKiQzj8asmMCY3mVtnLubj1RVORxIREYe5PU0AIb2px76mHZPBL84ZzidrKvndu6udjiMickRUyIJUXFQ4T14zgWG9E7npuSK+WFfldCQREXFQTyxkAFccm8fVU/rx+OzNPD9/q9NxREQOmwpZEEuMjuCZaycyMDOeGc8WMm9TtdORRETEIVX1HYUso4cVMoB7zhrGiYMz+L83V/Llej2gFJHgokIW5JJjI3nuuonkpsRy7VMLKdyyw+lIIiLigCpPE5FhLhJjunWiTUgJcxkevGwcgzLj+d7zRWyorHc6kohIt6mQhYC0+Ciev34SWYnRXPbYfGYtLnE6koiI+Jm7vpm0+EiMMU5HcUR8VDiPXz2BqPAwrnlqIdWdUzhFRAKdClmIyEyM5tUbJzOubzJ3vrSU376zita2dqdjiYiENGNMsjHmVWPMGmPMamPMZKeyuD1NPW792L5ykmP415Xjqaxr4oZnF9HU2uZ0JBGRQ1IhCyFp8VE8e90krpqcx7++3Mw1Ty2kZlez07FERELZ/cD71tohwGjAsa3+3J6mHnEo9KGM7ZvCvRePpnDrTn7y2nKs1Xb4IhLYVMhCTESYi1+eO4I/XjiSeZuqOffhr1hXobn0IiLeZoxJAqYBjwNYa5uttTVO5ekYIQv9Q6G746xRvfnBqccwa3EpD32ywek4IiIHpUIWoi6Z0JcXZxxLQ1Mb5z/8FR+sLHc6kohIqOkPVAFPGmMWG2MeM8bE7XuRMWaGMabQGFNYVeWbHQDb2y3VnuYeP2Vxb7eclM8FY3O49z/reHtZmdNxREQOSIUshI3PS+WtW6eSnxnPDc8u4v6P1tPerqkbIiJeEg6MA/5hrR0LNAA/2fcia+2j1toCa21BRkaGT4LU7m6htd2qkO3FGMPvLxzJhH4p/ODlpSzettPpSCIi+6VCFuJ6JcXw0g2TuWBcDvd9tI6bnl+Ep6nV6VgiIqGgBCix1s7v/P2rdBQ0v9tzKLTWkP2XqPAw/nlFAVmJ0Xz3mUI2uxucjiQi8j9UyHqA6Igw7r1oNPecNYz/rKrgwr/PYVv1LqdjiYgENWttOVBsjBnc+aWTgVVOZKnqKmRaQ/Y/UuMieeLqAtotXPTIXFZvr3M6kojIf1Eh6yGMMVx3XH+evnYi5XWNnP3QbL5Y55u1DCIiPcitwPPGmGXAGOB3ToSoqu8oZBmasrhf+ZkJvHzDZMJdhkv+OZciTV8UkQCiQtbDHD8og3/fMpXsxGiufGIBP521nLrGFqdjiYgEJWvtks71YaOstedZax35Sd/t6TjiRGvIDiw/M55XbpxMalwklz82n9nr3U5HEhEBVMh6pLy0ON64eSrfPb4/Ly7Yxml//YKPVlU4HUtERI6Q29NEuMuQFBPhdJSAlpsay8s3TqZvaizXPrWQD7UDsYgEABWyHiomMoy7zxzG69+bSlJMBNc/U8htMxdT3bkOQUREgoe7von0+ChcLuN0lICXmRDNizOOZVjvRG56vojXi0qcjiQiPZwKWQ83JjeZt249jjtPOYb3VmznlL9+zhuLS7FW2+OLiAQLt6eJ9ARt6NFdybGRPH/9JCb1T+X7Ly/lmblbnI4kIj2YCpkQGe7i9lMG8c5tx9MvPY47XlrCtU8tpKxmt9PRRESkG9w6FPqwxUWF88TVEzh1WBb/9+ZKHv50gx5GiogjVMhkj2OyEnj1xin831nDmLdpB6f+9XOenbtFh0mLiAQ4t6dJhewIREeE8ffvjOP8sTn8+YO1/OG9NSplIuJ3KmTyX8JchmuP68+Hd05jXF4K97y5kumPzmNjlcfpaCIish/WWhWyoxAR5uLei0Zz5eQ8/vnFJn46awVtehApIn6kQib7lZsayzPXTuTP3x7FmvI6zrj/S15eWOx0LBER2Uft7hZa2qwOhT4KLpfhl+cM55YT85m5YBu3v7iY5tZ2p2OJSA8R3p2LjDFbgHqgDWi11hb4MpQEBmM3Ft60AAAgAElEQVQMFxXk8o3BGdz50hL+32vLWLBlB78+dwQxkWFOxxMRETqmKwJkJGiE7GgYY/jhNweTEB3O799bQ3ltIw9dNo7spGino4lIiDucEbITrbVjVMZ6nsyEaJ65dhK3nTyI14pKOO/hr9hQqSmMIiKBoKpeh0J70w3fGMiDl45l9fY6znzgSx0gLSI+pymL0i1hLsP3Tz2Gp6+ZSJWniXMfms2/l5Y5HUtEpMfrGiFTIfOes0f35s1bjiMtPpIrnpjP/R+t1wZXIuIz3S1kFvjQGLPIGDNjfxcYY2YYYwqNMYVVVVXeSygBZdoxGbxz23EM7ZXIbTMX87M3ltPU2uZ0LBGRHktTFn0jPzOeN26eynljcrjvo3Vc/dRCdjQ0Ox1LREJQdwvZcdbaccDpwM3GmGn7XmCtfdRaW2CtLcjIyPBqSAksvZJimDnjWGZMG8Bz87bx7X/MZVv1LqdjiYj0SG5PE2EuQ3JMhNNRQk5sZDh/vXg0vzt/JPM2VnPmA19StG2n07FEJMR0q5BZa0s7/7cSmAVM9GUoCXwRYS5+esZQHr1iPFurGzjzwS/5cGW507FERHocd30zaXGRuFzG6SghyRjDZZP68vr3phAeZrj4kbk8MXuzzisTEa85ZCEzxsQZYxK6fg2cBqzwdTAJDqcNz+ad246nX1ocM55dxG/fWUVLm7YKFhHxF51B5h8jcpJ4+5bjOWFwJr96exU3v1BEfWOL07FEJAR0Z4QsC5htjFkKLADesda+79tYEkxyU2N59abJXHFsHv/6cjOX/Wue1pWJiPhJlaeJdK0f84uk2Aj+deV47jp9CB+srOCch75iTXmd07FEJMgdspBZazdZa0d3/jPcWvtbfwST4BIVHsavzxvBPWcNY+GWnSwvqXU6kohIj+Cub9Kh0H5kjOGGbwzkhesn0dDUynkPf8UL87dpCqOIHDFtey9eNXlAGgCV9U0OJxERCX3WWtyeZjI0ZdHvJg1I453bjqcgL5WfzlrOVU8uZHvtbqdjiUgQUiETr8pM7PihoLKu0eEkIiKhr66xlea2dq0hc0hGQhTPXDuRX587nIWbd3DafV/wSmGxRstE5LCokIlXpcZGEu4yGiET8bPWtnae/GqzNhnoYfYcCp2gKYtOcbkMV0zux/t3HM/Q7ER+9Ooyrn+6UA8mRYKYv/dCUCETr3K5DBkJUSpkIn72wcoKfvnWKl4pLHE6iviRu/Pv2oz4aIeTSF5aHC/OOJZ7zhrG7A1uTr3vC95cUqrRMpEgM3PBNs64/0sq6/33UEWFTLwuU4VMxO9eK+ooYnM2uh1OIv7k9jQDGiELFC6X4brj+vPe7cczMCOO219cwo3PLaJK90SRoPDywmLuen05fVJiSYyO8NvnqpCJ12UkRGuqhogfVdU38fm6KiLDXMzftINWnQXoV8aYLcaY5caYJcaYQn9+9p4pi1pDFlAGZMTzyo1TuOv0IXy6torT7vuct5eVOR1LRA7i1UUl/Pj1ZRw/KJ1/XjGe6Igwv322Cpl4XWaiRshE/OnNJaW0tVu+d+JA6ptaWVaqYycccKK1doy1tsCfH+r2NOEykBKrEbJAE+bq2B7/nVuPo29qLLe8sJibXyhiR0Oz09FEZB+zFpfwo1eXMnVgOv+6ssCvZQxUyMQHMhOi2NHQTHOrntKL+MNrRaWM7pPElZP7AfDVek1b7Cmq6ptIjYsizGWcjiIHMCgrgddumsKPvjmYD1eWc/es5U5HEpG9vLmklB+8vJTJA9IcKWOgQiY+kJnQsbi8ayqNiPjOqrI6Vm+v48LxfUiNi2RYr0S+0joyf7PAh8aYRcaYGfu+aIyZYYwpNMYUVlVVefWD3R4dCh0MwsNc3HxiPicPyWJ9pcfpOCLS6a2lZdz50hIm9EvlsasKiIn0fxkDFTLxgayus8g0bVHE514rKiEizHD2qN4ATM1Po2hrDbub/btlbw93nLV2HHA6cLMxZtreL1prH7XWFlhrCzIyMrz6wVWeZjIStH4sWGQlRlGhNdYiAeHd5du546UlFOSl8sTVE4iNDHcsiwqZeF3XCJluOiK+1dLWzptLSjl5SBYpcR2jJFPy02lua6dw6w6H0/Uc1trSzv+tBGYBE/312e76Jm3oEUSykqKpb2xlV3Or01FEerT3V5Rz28zFjM1N5olrJhAX5VwZAxUy8YFMjZCJ+MUX66pwe5q5YFzOnq9N7JdKRJhh9gZNW/QHY0ycMSah69fAacAKf3y2tVZTFoNMdmLHA8vyWj2wFHHKhyvLueWFIkb1SeLJayYQ73AZAxUy8YG0uEiMgSqNkIn41OtFpaTGRXLC4Mw9X4uLCmdsbgpzNlQ7mKxHyQJmG2OWAguAd6y17/vjgz1NrTS1tmvKYhDJ6ipkuj+KOOKjVRXc/EIRw3OSeOraiST48ayxg3G+EkrICQ9zkRanre9FfKl2Vwv/WVXBZZP6Ehn+38/WpuSncf/H66nZ1UyytkP3KWvtJmC0E5+951BoTVkMGl2FrLJO90cRf/t0TSXfe76Iob0SeebaiX49+PlQNEImPpGZoEIm4ktvLSujua2db4/v8z+vHZefjrUwb5NGyUKZDoUOPtlJGiETccKcDW5ueHYRx2TH8+y1k0iKCZwyBipk4iNZiVFU1uuGI+IrrxWVMDgrgeG9E//ntdG5ycRFhmkdWYirqlchCzbxUeHERYZpDZmIH1lr+c07q8lJieG56yaRFBtYZQxUyMRHMhOiqdCUDBGf2FjlYfG2Gi4cn4Mx/3sgcESYi4n9U7WOLMTtGSFL0LTUYJKVFK0HliJ+tLy0llXb67h2ar+AncavQiY+kZkYRbWnibZ263QUkZAzq6gUl4HzxuQc8Jqp+elscjdQVrPbj8nEn9z1TRgDqQH6A4bsX3ZitEbIRPxo5oJioiNcnDv2wPdMp6mQiU9kJkTRbqHao1EyEW9qb7fMWlzK8YMyyOzcIGB/puanA/CVpi2GrCpPM6mxkYSH6VYeTLITNYNExF8amlr595JSzhrVO6A28diX/hYXn8joPBxaG3uIeNe8TdWU1uzmwv1s5rG3wVkJpMVFMmejpi2Gqo4zyLR+LNhkJkZTUddIu2aQiPjcW0vLaGhu49KJuU5HOSgVMvGJrw+H1rQMEW96taiEhOhwThuWddDrXC7D5IFpfLXBjbX6wS8UuT1NWj8WhLITo2htt+zY1ex0FJGQN3NhMYMy4xnXN8XpKAelQiY+obNWRLyvoamV91eUc9aoXkRHhB3y+uPy06msb2JjlccP6cTfNEIWnPZsfa91ZCI+taqsjqXFNVw6se9+N8AKJCpk4hMZnT8kaJ68iPe8v6KcXc1tXDju4NMVu3StI5u9XuvIQpG7vnnP37USPLrWflboLDIRn3px4TYiw11cMC5wN/PookImPhEZ7iIlNkJTFkW86LWiEvLSYhmf172pF7mpseSmxvCV1pGFnIamVna3tJGeoEIWbLL3FDI9sBTxld3NbcxaXMoZI7IDdqv7vamQic9kJkRrUw8RLymt2c3cTdVcMLbPYU29OC4/nXmbqmlta/dhOvE3HQodvDISojAGyjVCJuIz7y7fTn1jK9Mn9nU6Srd0u5AZY8KMMYuNMW/7MpCEjszEKBUyES+ZVVSCtRz21IspA9Opb2xleWmtj5KJE/YcCh0f+E9+5b9FhLlIj4+iQmvIRHxm5oJtDEiPY1L/VKejdMvhjJDdDqz2VRAJPRkJUVTpCaDIUbPW8lpRKZP6p5KbGntYf3bKwDQAbX8fYr4uZBohC0ZZiVEaIRPxkfUV9RRu3cn0ibkBv5lHl24VMmNMH+BM4DHfxpFQkpXYMWVRZ62IHJ3FxTVsdjcc8uyx/UmLj2Jor0QdEB1iqjwdW6ZnaA1ZUMruPItMRLzvxYXFRISZbm+AFQi6O0L2N+D/AQdchGCMmWGMKTTGFFZVVXklnAS3zISOs1Z26qwVkaPy2qISoiNcnD4i+4j+/NSBaRRu3UljS5uXk4lT3J3TwVPjNGUxGGWpkIn4RGNLG68VlXDasGzSgmgGwSELmTHmLKDSWrvoYNdZax+11hZYawsyMjK8FlCCV2ZC51lkWkcmcsQaW9p4a2kZ3xqeTUJ0xBG9x9T8dJpb2yncstPL6cQpbk8TKbERRIRpb65glJUYzc5dLXpIIuJlH6wsp2ZXC5cGyWYeXbrzN/lU4BxjzBbgReAkY8xzPk0lISEzsePJhAqZyJH7eHUldY2tRzRdscvE/qmEuwxfbdS0xVChQ6GDW9fW91W6P4p41YsLislNjdmzfjpYHLKQWWvvstb2sdb2A6YDn1hrL/d5Mgl6mZ1rGyo1LUPkiL1WVEJ2YjRTBqYf8XvERYUztm8yc7SOLGS4Pc1aPxbEspI6Cpk29hDxns3uBuZuqmb6hL64XMGxmUcXzXUQn9GURZGjU1nfyOfrqjh/XA5hR3lzmTIwneWltdTuavFSOnFSVb1GyIJZ1whZuba+F/GaFxduI8xluOgoZpQ45bAKmbX2M2vtWb4KI6ElJjKMhOhwjZCJHIHK+kaueXIhBrxyc5man067hbmbtP19KNCUxeCW1TmlXxt7iHhHc2s7ry0q4eQhmWR2PvAIJhohE5/KTNDh0CKHa7O7gQv/MYdNVQ3866oCBmTEH/V7jslNJjYyjDlaRxb0djW3squ5jfQE7bAYrJJiIogKd6mQiXjJR6srcHuauXRScG3m0SXc6QAS2jITolXIRA7DkuIarn2qY2TsxRnHMjo32SvvGxnuYmL/VJ1H5gPGmDCgECj1xywSd33HUSIaIQtexhiyk6Ipr9P9UcQbZi7YRk5yDNMGBedO7xohE5/KTIyisl5PAEW649M1lVz66DziosJ49aYpXitjXaYOTGdjVYPWrXjf7cBqf31Ylafjh/gMFbKglpUQTYX+WxQ5asU7djF7g5uLCvoc9Xprp6iQiU9lJkRRWdeEtdbpKCIB7ZXCYq5/ppCBmXG8ftNU+qfHef0zpuR3bAOsUTLvMcb0Ac4EHvPXZ7o7C5lGyIJbVlI0FXpgKXLUXlpYjAEuLsh1OsoRUyETn8pMiKaptZ26xlano4gEJGstD32ynh+9uowpA9N4ccZkn21nPjQ7kdS4SJ1H5l1/A/4f0H6gC4wxM4wxhcaYwqqqqqP+wD2FTGvIglp2YhTltY16YClyFFrb2nllUTEnDM6kd3KM03GOmAqZ+NSew6G1cFnkf7S1W/7vzZX85cN1nDemN49fNYH4KN8t7XW5DJMHpjFnQ7V+CPQCY8xZQKW1dtHBrrPWPmqtLbDWFmRkHP36hq41ZGlxGiELZlmJHQ8sa3frKAqRI/Xp2ioq6pqYPiF4R8dAhUx8TGeRiexfY0sbNz9fxLPztnLDtAH89eIxRIb7/q/kqQPTKa9rZGNVg88/qweYCpxjjNkCvAicZIx5ztcf6vY0kRwb4Zf/v4jvZCXqcGiRozVzwTYyE6I4aUim01GOiv42F5/aM0KmefIie9TuauHKxxfw/spy7jlrGHedMRSXnxYiH5efDqDt773AWnuXtbaPtbYfMB34xFp7ua8/V4dCh4bspI5CVqGdFkWOyPba3Xy2tpKLC3IJDwvuShPc6SXgZSZ0TVnUDUfEWsuK0lou+uccFhfv5IFLx3Ldcf39mqFvWix9UmK0sUcQ6zgUWuvHgl125wiZdloUOTIvLSym3cIlQT5dEXQOmfhYfFQ4MRFhmrIoPdr22t28sbiMWYtLWFfhISEqnKevmciUztEqf5s6MJ33Vmynrd0G7RbBgcZa+xnwmT8+y+1pYkROkj8+Snyoa/MeTVkUOXwzF2zj4U83cOLgDHJTY52Oc9RUyMSnjDFkJkZRoRuO9DANTa28v6Kc1xeXMGdjNdbCuL7J/Oa8EZw1qhfJsc6NcEwdlM5LhcWsKK31+lln4ntuT7OmLIaA6IgwUmIjdH8UOQwtbe38+u1VPDN3K984JoO/TR/rdCSvUCETn8tKiNYImfQIbe2Wrza4mbW4lPdXlLO7pY2+qbHcdtIgzh+bQz8fnC12JKYM7DyPbKNbhSzINLa04Wlq9dnRCOJfWYnRKmQi3bSjoZmbny9i7qZqZkwbwI+/NSRkZnmokInPZSRGsaqszukYIj7R2NLGspJaPlpdwRuLS6msbyIxOpzzx+VwwdgcxuelYExg3TDS46P41bnDmdAv1ekocpiq6rsOhdYaslCQnRStKYsi3bCmvI7vPlNIRV0Tf714NBeM6+N0JK9SIROfy0yI4jPdcCQEWGsp2bmbom07WbythqJtO1lVVkdruyXcZThhcCYXjsvhxCGZREeEOR33oK6c3M/pCHIE9hwKrSmLISErIZoVpXpgKXIwH6ws586XlhAfFc7LN0xmTAjO7FAhE5/LTIimobmNhqZW4nx46K2It3WNfhVt20nR1p0sLq7ZM0IRExHG6NwkZkwbwNi+KUzol+LoujDpGdyejkOhVchCQ1ZSNNUNTbS0tRMR5Nt2i3ibtZYHP9nAX/+zjtG5yTx6xfg95/eFGv10LD63Z+v7+ib6q5BJgGppa2ddRT3LS2pZVlrL8pJaVm/vGP0CyEuL5bj8dMb1TWZs3xSGZCcE/bknEnySYiI4bVgWvZJD84eSniY7MRprO6ai9k6OcTqOSMDY1dzKD19ZyrvLy7lgbA6/u2BkwM88ORr66Vh8rutw6Iq6RvoHyKYG0rO1tVs2VHpYVlLD8tJalpXUsmp7Hc2t7QAkRIczqk8S3502gHF9UxjbN1kjEhIQJvZPZWJ/rf0LFVmJX299r0Im0qFk5y6++8wi1pbXcfcZQ7n++P4Btxbb21TIxOe6hpe106I4paKukUVbd7Jo606WFtewsqyO3S1tAMRFhjEiJ4mrJucxsk8yo3KSyEuLDfm//EXEeXvuj1pnLYK1ljkbq7lt5mKa29p54uoJnDA40+lYfqFCJj63Z8qibjjiB61t7awpr6do204Kt3SUsNKa3QBEhbsYmZPE9Im5jOqTxMicZAakx+EKkW1zRSS4ZCd1FLLyWt0fpedaV1HP20vLeHvZdja5GxiQEce/rixgYEa809H8RoVMfC4pJoLIcNeezRBEvKmusYWirR2bbizatpMl22poaO4Y/cpKjKIgL5Vrj+tPQV4KQ3slEhmudV8iEhhSYyOJCDOU1+n+KD3LpioPby/bztvLylhX4cFlYFL/NK47vj/njskhvoftOdCzvltxhDGGjPgoTVkUr2hpa2dJcQ1frqvii/VulpXU0G7BZWBor0QuHN+H8XkpjM9LISc5RlMPRSRguVyGzAQdDi09Q/GOXby9bDtvLS1j1faO4x4m9Evhl+cM5/SR2WQm9NzNilTIxC8yE6OorNcNRw6ftZat1bv4cn1HAZu7sRpPUysuA6Nzk7nlxHwmDUhjdG5yj3uiJiLBLysxSoVMQlJjSxsry2op3LKTd1eUs7S4BoAxucn87MyhnDmqF72StJkNqJCJn2QlRLOhyuN0DAkStbtbmLvRzRfr3Xy5voriHR1rwPqkxHD26N5MG5TOlIHpJMVGOJxUROToZCdFs6a83ukYIkela/fipcU1LCmpYWlxDWvK62nrPDpmRE4iPzl9CGeO7EVuaqzDaQOPCpn4RWZiFHM2up2OIQGs2tPE+yvLeW95OXM3VdPWbomPCmfywDRmHD+A4wdlaPdDEQk5mQnRfL62yukYIt1mraWstpGlxR3Fa0lxxxEyuzrXbydEhzMmN5mbvjGQ0bnJjO6TRGaIHujsLYcsZMaYaOALIKrz+lettT/3dTAJLZkJUdQ1ttLY0hbSB/vJ4XF7mnh/RTnvLt/OvE3VtFvonx7HDdMGcOKQTMbkJhOhw5dFJIRlJ0XT0NyGp6lV064l4LS1Wza7G1hZVsuqsjpWltWxsqyWnbtaAIgMczGsdyIXF+QyOjeJ0X2S6Zem3YsPV3f+y28CTrLWeowxEcBsY8x71tp5Ps4mIaRroWZVfZOGqnu4yvpGPlhZwbvLtjN/c0cJG5Aex/dOyOeMkb0Y2itBo2Ai0mNkJ3699X1+Zs/Z5lsCT1NrG+srPKwsq2VFaUfxWlNev2fkKzLMxeDsBL45PJvhvRMZnZvMkGztXuwNhyxk1loLdC3+iej8x/oylISejMTOs8jqG1XIeqAdDc28vayMd5ZtZ8GWHVgLAzPiuOXEfE4f2Ysh2SphItIzdR0OXVGnQib+095u2eT2sHhbDUtLalhaXMua8jpa2jp+xI+LDGN47yQuLshleO9EhvdOYlBWvGat+Ei3xsaNMWHAIiAfeNhaO38/18wAZgD07dvXmxklBHQdDl2hs1Z6DGst8zfv4IX523h/RTnNbe3kZ8Zz60mDOHNkL47JilcJE5EeL6vzgaUOhxZfqqhrZMnea75KaqlvagUgPiqcUX2SuO64AYzI6ShfeamxmnboR90qZNbaNmCMMSYZmGWMGWGtXbHPNY8CjwIUFBRoBE3+S9cTwEpt7RvydjQ089qiEmYu2MYmdwMJ0eFcNqkvl0zIZWivRKfjiYgElOykzhEyHQ0jXtLWblm9vY55m6op3LKTJcU1lHf+/BXuMgzplcA5Y3ozJjeZMbnJDMiIJ0zly1GHtXrUWltjjPkU+Baw4lDXi3RJjY0k3GV0OHSI2t9o2Pi8FP5yYj5njuxFTKQ2chER2Z/YyHASosOp0AiZHKG9C9i8TTtYsLmausaO0a/c1Bgm9k9ldG4yY3KTGN47SZurBaDu7LKYAbR0lrEY4FTgjz5PJiHF5TKkx0epkIWYfUfDEjtHwy6d2JfB2QlOxxMRCQpZidF7RjBEDuVgBaxfWixnjOzFsQPSmDQgVQcvB4nujJD1Ap7uXEfmAl621r7t21gSijITVchCxYZKD498vpF/Lymjua2dgrwUbj6xY5dEjYZJT6KjYcQbshOjtcZaDsrtaeLTNZV8sqaSrza4VcBCTHd2WVwGjPVDFglxmQlRlOzc7XQMOQrLS2r5+2cbeH9lOVHhLqZPzOU7k/I0GiY9mY6GkaOWlRjNxo1up2NIALHWsraino9XV/LR6gqWFNdgbccmMN8akc3kgWlM6p9G72QVsFCgEwjFbzISoinaVuN0DDlM1loWbN7Bw59t5It1VSREh3PzCflcM7UfafFRTscTcZSOhhFvyE7qmEHS1m61uUIP1tTaxrxNO/h4dQUfr66ktKbjIfaoPknccfIxnDw0k+G9E7VDcQhSIRO/yUqMYkdDM82t7TpEMAhYa/l0bSUPf7qRRVt3kh4fyf/71mAuPzaPxOgIp+OJBIxDHQ2jY2HkULISo2lrt1R7msjs3JVYegZPUysfriznw5UVfLm+iobmNqIjXByXn8EtJ+Vz0pDMPTtVS+hSIRO/yUzo+AvF7WnSEHsAa2u3vLt8O3//bCOrt9eRkxzDr84dzsUFudqZSWQ/DnU0jI6FkUP5+nBoFbKeoKWtnS/WVfHGkjL+s6qcxpZ2shOjOXdsDqcMzWTKwHTdb3sYFTLxm67DoSvrVcgCUVu7ZdbiUh76ZD1bqncxMCOOv1w0mnPH9CYiTCOaIoeio2HkSGV3lrDyukZGkuRwGvEFay2Li2t4Y3Epby/bzo6GZlJiI/j2+D6cPzaHcX1TNBWxB1MhE7/JTOwsZNraN+DM2eDmN++sZtX2OkbkJPLI5eM4bVg2Lq1lEDkoHQ0j3pC1VyGT0LKpysMbS8p4c0kpW6t3ERXu4pRhWZw/Jodpx2RoCYcAKmTiR11TFrX1feDYUOnh9++u5uM1leQkx/DApWM5e1QvPaUT6T4dDSNHLT0+EpfRA8tQUdfYwqyiUl5fXMrS4hqMgSkD07jlxHy+NSKbBK3Dln2okInfpMdHYnTDCQjVnib+9tF6XliwjdiIMH78rSFcM7Wf5qyLHCYdDSPeEB7mIiMhivJa3R+D2fqKep6eu4XXi0rZ1dzGsF6J3H3GUM4e3ZvsJK0NlANTIRO/CQ9zkRanw6Gd1NjSxlNztvDwJxvY1dLGZRP7cscpg7R9vYiIw7ITozVlMQi1tVs+Wl3BM3O38NWGaiLDXZw9qjdXTcljVJ9kp+NJkFAhE7/KTFAhc4K1lreWbeeP762htGY3Jw/J5K4zhpCfqQOdRUQCQWZiNFurG5yOId20s6GZlwqLeXbuVkprdtM7KZoffXMw0yfk6iGnHDYVMvGrzMQoKuv1BNCfirbt5Ndvr2LxthqG9krkT98exdT8dKdjiYjIXrITo1mweYfTMeQQVpTW8szcLby5pIym1nYmD0jjnrOGcsrQLMK1I7EcIRUy8avMhChWldU5HaNH8DS18qf31/DM3K1kJkTxp2+P4sJxfQjTzokiIgEnOyma2t0tNLa0aT1vgLHW8tm6Kv7+6QYWbtlJTEQYF47vw1WT+zE4WzNN5OipkIlfZSZE4/Y00dZuVQx86LO1ldw9awVltbu5Zmo/fnjaYOKi9J+7iEig6jqrs7y2kX7pcQ6nEegoYp+ureT+j9aztKSWnOQYfnbmUC4qyCUpRjslivfoJzTxq8zEKNptxy5/mYnaccjbdjY08+t3VvF6USn5mfG8euMUxuelOB1LREQOoWsXvoo6FTKnWWv5eHUlD3yynmUltfRJieEPF4zkgnF9dG6Y+IQKmfjV3meRqZB5j7WWd5eX8/N/r6BmVwu3nZTPzSflExWuaS8iIsEgW4dDO85ay0f/n707j4+quv8//jqTbZKQhaxAgCTsILthxwXF1l3UquCKgGK1Lm39unT51VZrW9vaat1FBEFxw32vCiogQthlU5YQQyAbkIRA9vP7I8FSqjLAzNxZ3s/Hg4fJzM3cd+4j8eQz59zPWV/KAx99xZfbq+iUEst9F/bn/MFZROn+MPEhFWTiVxmJLUsyWhp7JDkbJkSUVNXy29e+5IN1JaGx0+AAACAASURBVPTLSuKZScPo0yHR6VgiInIEMg+aIRP/stbywboSHvzoa9YWV5GdGsd9P+nP+YNUiIl/qCATvzqwRr60Sq3vj5W1lhfzv+Get9dT39jMnWf0YvLoXHV5EhEJQgkxkcRGRbCzUuOjv1hreX9tSyG2bkdLIfa3iwYwbmAHjaXiVyrIxK/SDxRk2ovsmBRW7OOOV1azaHMFQ3NT+MuF/cnVPQciIkHLGEO7JDcl2hrGL1Z9s4ffv7mW5YV7yE2L5+8XDeA8FWLiEBVk4lcxkREkx0VpScYxmLusiN++/iUuY7hnXF8uHdoZlzpWiogEvczEGEoqNT76UmlVLX95byNzlxeR1iaGv1zYjwsHd1QhJo5SQSZ+l5EQoxmyo7CvvpH/9/paXl5WxNDcFP55yUA6JMc6HUtERLwkM9HNsm27nY4RkmobmnhqwVYembeJhibLdSd15YYxXUlwq329OE8FmfhdZqJbBdkR2rizmhueW87msr3cdEo3bjq1u97NExEJMe0S3ZRW1WGtxRitfPCGlvvEdvLHd9bzza79nNYnk1+f2VtbC0hAUUEmfpeeEMPm0r1OxwgK1lpeWPoNv3tjLQnuKGZNGsbo7mlOxxIRER/ITHRT39TM7n0NpMRHOx0n6K3fUcUf3lzH51sq6JHZhtmTNYZKYFJBJn6XkeCmbK/eATycvXWN/PrVNby+sphR3VL5xyUDv93HTUREQs+BzaF3VtaqIDsGFXvruP/fXzFnSSGJsVHcfd5xTBjaWStLJGCpIBO/y0iIoaHJ6h3AH7C2uJKfPbeCbRU1/PK0Hlw/phsRatwhIhLSMlv36iypqtV+kkehudny3JJC/vLeBvbVN3HliBxuGdud5Dj9rSGBTQWZ+F3GQQOOCrL/Zq1l9heF3P3WOtrGRfHcNcMZ3iXV6VgiIuIHmYnaHPpoFVbs4/a5q/l8SwUju6by+3OPo3tmgtOxRDyigkz87sCyu9LqOnq3dzhMAKmqbeDOuWt4e80OTuqRzv0XDyC1TYzTsURExE8OjI87VZB5rLnZMmvxNv787gYiXIY/XdCP8UM66ZYICSqHLciMMZ2AZ4BMwAJPWGsf8HUwCV0HlmSUasD51sad1VzzTD7b9+znjjN6ce0JXbS3mIhImImOdJEaH60ZMg8VlNdw29zVLNm6ixN7pPOnC/qRpe1gJAh5MkPWCPzSWrvcGJMALDPG/Ntau87H2SREHTxDJjBvQyk3zllBXHQEL04dzvHZKU5HEhERh2Qmuimp0vj4Q5qbLTMWFXDf+xuIinBx30/6c9HxHTUrJkHrsAWZtXYHsKP142pjzHogC1BBJkclNjqChJhIysK8ILO2ZUC5+6119G6fyLSr8mifpHf2RETCWbskNzsrNUP2fbaU7eW2l1eTv203p/TK4N7z+33bnVIkWB3RPWTGmBxgEPDFdzx3LXAtQOfOnb0QTUJZemIMpdXhO+A0NjXz+zfXMWvxNk7rk8k/LxlIfIxu6RQJJlrSL76Qmehm1Td7nI4RcJqaLdMXbOVvH2wkJtLF3y8awAWDszQrJiHB478AjTFtgLnALdbaqkOft9Y+ATwBkJeXZ72WUEJSRkJM2C7JqKpt4IZnl/PZ1+VMPbELt5/eS/eLiQQnLekXr8tMjKGipp66xiZiIiOcjhMQNpft5daXVrGicA9je2dy7/l9yUjUrJiEDo8KMmNMFC3F2LPW2ld8G0nCQUaCmxXf7HY6ht8VVuxj8sylbC2v4S8X9uOSIZpNFglWWtIvvtCutdAoq66jY9s4h9M479UVRfz61S+JjnTxwPiBnDugg2bFJOR40mXRAE8B66219/s+koSDzMQYSqvqsNaGzf9Y8wt2ce2sZTQ1W56ZPJSRXdOcjiQiXqIl/eItmUn/2YssnAuy2oYmfv/mWuYs+YahOSk8OGGQ7hWTkOXJDNko4ApgjTFmZetjv7LWvuO7WBLqMhLc1DU2U1XbSFJslNNxfO61Fdu57eXVdEh2M33iELqkt3E6koh4iZb0izdlHtiLrDI8l/VDS+OO659dzoad1Vx/cld+cVoPIiNcTscS8RlPuiwuAMJjCkP8JqN1L7Ky6tqQLsiamy3//PArHvx4E8NyU3js8uNpGx/tdCwR8RIt6Rdva3fQDFk4enNVMXfMXU10pIunrx7CmJ4ZTkcS8Tm1dRNHpCe0FGQlVXV0y0hwOI1v1DY08cuXVvH26h1cnNeRe8b1IzpS7/CJhAot6RdfaBsXRXSkK+wKstqGJu55ex2zFxdyfHZb/jVhEB20ybOECRVk4oj/bA4dmgPO3rpGpsxcyhdbd3HHGb2YemKXsLlXTiSMaEm/eJ0xhszEGHaGUUG2raKG659dztriKqae2IVbf9yTKC1RlDCigkwccWDJYmkItr7fs6+eq55eypfbK/nHxQMZNyjL6Ugi4gNa0i++kpkQPptDv7tmB7e9vBqXyzDtyjzG9sl0OpKI36kgE0ckxEQSGxVBaXVoFWRl1XVc8dQXbCmr4ZHLBvPj49o5HUlERIJMZpKbdcX/0x8mpNQ1NvGndzYwY1EBAzol8/Clg8K6q6SENxVk4ghjDBmJMSFVkBXv2c/l075gR2UtT03M44Tu6U5HEhGRINQu0c3H60tDdmuY0upaps5axorCPUwalcsdZ/TSPdYS1lSQiWMyEmIoDZE18gXlNVw27Quq9jcwa/JQ8nJSnI4kIiJBKjMxhv0NTSG5NcyGnVVMnpHPrpp6Hr1sMGf0a+90JBHH6e0IcUxGgjskZsg27qzmosc/Z199I3OuHa5iTEREjklmYmvjqxB50/KAeRtL+cmjn9PY3MxL141QMSbSSgWZOCY9BGbIVhft4ZInPsdl4MWpI+ibleR0JBERCXLtWguyUOq0OHNRAZNnLCU7NY7Xbxit8VLkIFqyKI7JSIyhpr6JmrpG4mOC70dxydZdTJqxlOS4KJ6bMpzOqboZWUREjt2BGbJQ6LTY2NTM3W+tY+bn2xjbO5MHxg8MyjFfxJf0GyGOyfx2L7I6coPsf87zN5Zy3exlZCXH8uyU4bRLcjsdSUREQsSBMSXYN4eurm3gxjkrmL+xjGtOyOWOM3oT4Qq9JiUixyq4/gqWkPKfvchqyU2LdziN595ds4Obnl9B94wEnpk8lLQ2MU5HEhGREOKOiiApNoqSIN6rs2j3PibPyGdT2V7uPb8flw7r7HQkkYCle8jEMe1b3wHcVLbX4SSee23Fdm54bjn9spKYc+1wFWMiIuIT7RLdQXsP2YrC3Yx7eBHFlfuZefVQFWMih6GCTBzTNb0NPTMTmL24EGut03EO641VxfzixZUMzU1h1uRhIdeKWEREAkdGYkxQLll8e/UOxj+xmNhoF69eP5LR3dOcjiQS8FSQiWOMMUwancP6HVUs3rLL6Tg/6J01O/j5CyvJy0lh+sQhuiFZRER8qmPbOLaU1VBT1+h0FI9Ya3l43qZvV5G8dv0oumUkOB1LJCioIBNHnTcwi5T4aKYv3Op0lO/1/tqd3DRnBYM6JfP0xCHERasYExER37ooryN76xqZs6TQ6SiH1dxsueuNtfz1/Y2cN7ADs6cMI1VL+kU8poJMHOWOiuCyYZ35cH0J2ypqnI7zPz5cV8LPnltOv45JPH21ZsZERMQ/Bnduy4guqTz52RbqGpucjvO96hubueWFlcz8fBvXnJDLPy4eiDsqwulYIkFFBZk47vLh2US6DE8vLHA6yn+Zt7GU659dTp/2icycNJQEt+4ZExER/7l+TFdKqup4Zfl2p6N8p331jUx5Jp83VhVzxxm9+PVZfXCprb3IEVNBJo7LTHRzdv8OvJT/DVW1DU7HAeDTr8qYOmsZPdq14ZlJw0hUMSYiIn42ulsa/bKSePyTzTQ1B1bzqz376rls2hcs+LqMv1zYj+tO6up0JJGgpYJMAsKkUbnU1Dfx4tJvnI7Cwk3lXPNMPl3T2zB78jCS4lSMiYiI/xljuP7krhRU7OOdNTucjvOtnZW1XPz456wtruKRy47nkiFqay9yLFSQSUDo1zGJoTkpzFhU4Oi7gIu3VDB55lJy0+J5dsowkuOiHcsiIiLy4+Pa0TU9nkfmbw6ILWK2lO3lwkcXUbynlhlXD+H0vu2cjiQS9FSQScCYNDqHot37+fe6EkfOv7RgF5NmLKVT2zhmTxlGSryKMRERcZbLZbjupK6s31HF/K/KHM2ypqiSix77nNqGJp6/djgju2qPMRFvUEEmAeO0Pu3o2DbWkRb4y7btZuL0JbRLcvPsNcNIU7teEREJEOcNzKJDkptH5m1yLMOizeVMeHIx7qgIXrpuBH2zkhzLIhJqVJBJwIhwGSaOzGHJ1l18ub3Sb+dd+c0eJk5fQkaimznXDCcjwe23c4uIiBxOdKSLa07swtKC3Swt2OX387/35Q4mTl9Kh2Q3c386ki7pbfyeQSSUqSCTgHLxkE7ER0f4bZZs8ZYKLp/2BW3jo3nummFkJqoYExGRwDN+SGdS4qP9Pkv2wtJCrn92OX2zEnlx6gjaJWmcFPG2wxZkxpjpxphSY8yX/ggk4S3RHcVFeZ14c1UxpVW1Pj3XxxtKuGr6EtonuXlx6gjaJ8X69HwiEno0Roq/xEZHMGlUDvM2lrGuuMrn57PWcv8HG7l97hpO6J7ObDW6EvEZT2bIZgCn+ziHyLcmjsyhsdkye/E2n53jzVXFXPvMMnpkJvCC3vETkaM3A42R4idXjMihTUwkj36y2afnqW1o4ubnV/Lgx5u4OK8jT16ZR1x0pE/PKRLODluQWWs/Bfy/YFnCVk5aPKf2ymT2F4XUNjR5/fXnLCnkpudXMDi7Lc9do26KInL0NEaKPyXFRnHZ8M68vbqYgvIan5yjYm8dl0/7gjdWFXPb6T35y4X9iY7UHS4ivuS13zBjzLXGmHxjTH5ZmbNtWSX4TRqdw66aet5YWezV133i083c+coaTu6RzjOThpLg1qbPIuJbGh/FmyaPziUywsXjn3p/lmxT6V7Of2QRa7ZX8vClg7n+5G4YY7x+HhH5b14ryKy1T1hr86y1eenp6d56WQlTI7qk0qtdAtMXbvXKRpjWWv7+wUbufWcDZ/Vvz+NX5OGOivBCUhGRH6bxUbwpI8HNxXkdmbtsOyVevNd60eZyLnhkIfvqG5lz7XDO6t/ea68tIj9Mc9ASkIwxTBqdy4ad1Xy+ueKYXqu52fL7N9fxr483MX5IJx4cP0jLL0REJGhNPbErTdYy7bMtXnm9F/O/4cqnlpCZ6ObV60cxuHNbr7yuiHhGf5VKwDp3QAdS46OPqQV+Y1Mzt768ihmLCrjmhFz+dEE/IlxafiEiIsGrU0oc5/Rvz7NfFLJnX/1Rv05zs+W+9zZw28urGd4llZd/OpJOKXFeTCoinvCk7f0c4HOgpzGmyBgz2fexRMAdFcFlw7P5aEMpW4/i5uW6xiZueG45ryzfzi9O68GvzuyttfAi4lUaI8UpPz25G/vqm5ixqOCovr62oYkbn1/BI/M3M2FoJ56+eghJsbqvWsQJnnRZnGCtbW+tjbLWdrTWPuWPYCIAlw/vTJTLxYwjnCXbV9/IlJn5vL+2hN+d04ebTu2uYkxEvE5jpDilZ7sExvbOZMaiAmrqGo/oa8v31jHhycW8vXoHd57Ri3vP70dUhBZNiThFv30S0DIS3JwzoAMvLSuicn/DDx5b39jMos3l3PvOek7/52cs3FTOX3/Sn6tH5foprYiIiP9cP6Yre/Y1MGdJ4WGPbW62rN9RxZOfbmHcwwtZV1zFo5cNZupJXfWGpYjDtMufBLyrR+Uwd3kRLy79hmtO7PJfz5VU1TJ/YynzNpSxYFM5e+saiYowDMtN5ffnHseYXhkOpRYREfGtwZ3bMrxLCtM+28oVI7KJifzv7sHFe/azYFM5C74uZ9Hmcsr3ttxv1jMzgYemDmZgp2QnYovIIVSQScDrm5XEsNwUZiwq4MqR2awpqmReaxG2bkcVAO2TWmbSxvRMZ2S3NNrE6EdbRERC3/Und+PK6Ut4bcV2zujXns83V7BwUzkLNpWzpazl/uu0NjGM7pbGqG5pjO6eRvukWIdTi8jB9FerBIVJo3OZOmsZg/7wb/bVNxHhMhyf3ZbbT+/FmF7p9MxM0JILEREJOyd0T6NfVhJ3vbGOO19ZQ7OF2KgIhnVJ4dKhnRndPU1jpEiAU0EmQWFs70zOGdCB6AgXY3qlc0L3dHWDEhGRsGeM4Vdn9ubBj77m+Oy2jO6exqDOyf+zfFFEApcKMgkKES7DvyYMcjqGiIhIwBnRNZURXVOdjiEiR0ldFkVERERERByigkxERERERMQhKshEREREREQcooJMRERERETEISrIREREREREHKKCTERERERExCEqyERERERERByigkxERERERMQhKshEREREREQcYqy13n9RY8qAbcf4MmlAuRfihDpdJ8/pWnlG18kzuk4tsq216U6HCBYaH/1O18ozuk6e07XyjK5TC4/GSJ8UZN5gjMm31uY5nSPQ6Tp5TtfKM7pOntF1EqfoZ89zulae0XXynK6VZ3SdjoyWLIqIiIiIiDhEBZmIiIiIiIhDArkge8LpAEFC18lzulae0XXyjK6TOEU/e57TtfKMrpPndK08o+t0BAL2HjIREREREZFQF8gzZCIiIiIiIiFNBZmIiIiIiIhDHC/IjDGnG2M2GmM2GWPu+I7nY4wxL7Q+/4UxJsf/KZ3nwXX6hTFmnTFmtTHmI2NMthM5nXa463TQcRcaY6wxJmxbsnpyrYwxF7f+XK01xjzn74yBwIPfvc7GmHnGmBWtv39nOpFTQo/GR89ofPScxkjPaHz0nMZIL7HWOvYPiAA2A12AaGAV0OeQY64HHmv9eDzwgpOZA/g6jQHiWj/+qa7Td1+n1uMSgE+BxUCe07kD9VoB3YEVQNvWzzOczh2g1+kJ4KetH/cBCpzOrX/B/0/jo1evU9iPj55eq9bjwnqM1Pjo9WulMdKDf07PkA0FNllrt1hr64HngfMOOeY8YGbrxy8DpxpjjB8zBoLDXidr7Txr7b7WTxcDHf2cMRB48vMEcDfwF6DWn+ECjCfX6hrgYWvtbgBrbamfMwYCT66TBRJbP04Civ2YT0KXxkfPaHz0nMZIz2h89JzGSC9xuiDLAr456POi1se+8xhrbSNQCaT6JV3g8OQ6HWwy8K5PEwWmw14nY8xgoJO19m1/BgtAnvxM9QB6GGMWGmMWG2NO91u6wOHJdboLuNwYUwS8A9zon2gS4jQ+ekbjo+c0RnpG46PnNEZ6SaTTAcS7jDGXA3nASU5nCTTGGBdwPzDR4SjBIpKWZRkn0/KO8qfGmH7W2j2Opgo8E4AZ1tq/G2NGALOMMX2ttc1OBxOR/9D4+MM0Rh4RjY+e0xjpAadnyLYDnQ76vGPrY995jDEmkpbpzgq/pAscnlwnjDFjgV8D51pr6/yULZAc7jolAH2B+caYAmA48EaY3rTsyc9UEfCGtbbBWrsV+IqWASiceHKdJgMvAlhrPwfcQJpf0kko0/joGY2PntMY6RmNj57TGOklThdkS4HuxphcY0w0LTclv3HIMW8AV7V+/BPgY9t6Z2AYOex1MsYMAh6nZbAJ17XMP3idrLWV1to0a22OtTaHlnsJzrXW5jsT11Ge/O69Rsu7fxhj0mhZorHFnyEDgCfXqRA4FcAY05uWwabMryklFGl89IzGR89pjPSMxkfPaYz0EkcLstY17z8D3gfWAy9aa9caY/5gjDm39bCngFRjzCbgF8D3tmkNVR5ep78CbYCXjDErjTGH/kKEPA+vk+DxtXofqDDGrAPmAf9nrQ2rd989vE6/BK4xxqwC5gATw/CPYvEyjY+e0fjoOY2RntH46DmNkd5jdE1ERERERESc4fSSRRERERERkbClgkxERERERMQhKshEREREREQcooJMRERERETEISrIREREREREHKKCTERERERExCEqyERERERERByigkxERERERMQhKshEREREREQcooJMRERERETEISrIREREREREHKKCTERERERExCEqyERERERERByigkxERERERMQhKshEREREREQcooJMRERERETEISrIREREREREHKKCTERERERExCEqyERERERERByigkzCjjGmwBhTb4xJO+TxFcYYa4zJ8eA1JhpjFng513hjzEZjTKUxptQYM9MYk+jNc4iIiHyfQB0fD3n9j1qzRPrqHCL+poJMwtVWYMKBT4wx/YA4f538ewaShcAoa20S0AWIBO7xVyYRERECc3w88NxlQJS/soj4iwoyCVezgCsP+vwq4JmDDzDGJBljnjHGlBljthljfmOMcRljegOPASOMMXuNMXt+6PjW5yYaYxYaY/5hjKkA7jo0kLX2G2tt+UEPNQHdvPpdi4iI/LCAGx8PvAbwO+A2r3/HIg5TQSbhajGQaIzpbYyJAMYDsw855l/Agdmqk2gZoK621q4HrgM+t9a2sdYm/9DxB73eMGALkAn88btCGWNGG2MqgWrgQuCfx/qNioiIHIGAHB+Be4FHgZ3H9u2JBB6tv5VwduBdwE+A9cD2A08cNAgNtNZWA9XGmL8DVwBPHfpCHh5fbK39V+vHjd8VyFq7AEgyxmQB1wAFx/pNioiIHKGAGh+NMXnAKOBmoKNXvkORAKKCTMLZLOBTIJdDlmMAabSsU9920GPbgKzveS1Pjv/G02DW2u3GmPeA54HBnn6diIiIFwTM+Ni6tPER4GZrbaMxxpP8IkFFSxYlbFlrt9Fy8/KZwCuHPF0ONADZBz3Wmf+8S2iP8Pjv+prDiQS6HuHXiIiIHJMAGx8TgTzgBWPMTmBp6+NFxpgTfvg7EQkOKsgk3E0GTrHW1hz8oLW2CXgR+KMxJsEYkw38gv+soy8BOhpjoj08/rCMMZcZYzq3fpxNyzr6j47puxMRETk6gTI+VgIdgIGt/85sffx44Iuj/eZEAokKMglr1trN1tr873n6RqCGlhuNFwDPAdNbn/sYWAvsNMaUe3C8J/oAi4wxNbS0wN9Iy31kIiIifhUo46NtsfPAP6Cs9akSa239EX5bIgHJWHukq6hERERERETEGzRDJiIiIiIi4hAVZCIiIiIiIg5RQSYiIiIiIuIQFWQiIiIiIiIO8cnG0GlpaTYnJ8cXLy0iIgFk2bJl5dbadKdzBAuNjyIi4cPTMdInBVlOTg75+d/XKVVEREKFMWab0xmCicZHEZHw4ekYqSWLIiIiIiIiDlFBJiIiIiIi4hAVZCIiIiIiIg5RQSYiIiIiIuIQFWQiIiIiIiIOUUEmIiIiIiLiEBVkIiIiIiIiDlFBJiIiIiIi4pCgLsistfzj319x5fQl3P/BRuZtLGXPvnqnY4mIiPjE/I2lnHb/J+ysrHU6ioiIeEmk0wGOlrWWP769nmkLttI5JY4FX5fRbFue65Iez6BObRmcncygTm3p2S6BCJdxNrCIiMgxinS5+Lp0L1vLa2iX5HY6joiIeEHQFmT//PBrpi3YylUjsrnr3OOoqW9iddEeVhTuYUXhbuZtLGXu8iIA4qMj6N8xmcHZyZzcM4MhOSkOpxcRETly2alxABRU1DCia6rDaURExBuCsiB7/JPNPPDR11x0fEd+d85xGGNoExPJyK5pjOyaBrTMoBXu2seKwj0sL9zNisI9PPbJFh6et5krR2TzqzN7446KcPg7ERER8VyH5FiiI1wUVNQ4HUVERLwk6AqyWZ8X8Kd3N3B2//b8+cL+uL5nKaIxhuzUeLJT4xk3KAuAffWN3P/BV0xbsJXFWyp4cMIgerVL9GN6ERGRoxfhMnRKiaWgXAWZiEioCKqmHi8vK+K3r69lbO8M/nHJwCO+LywuOpLfnN2HmZOGsqumgXMfWsjMRQVYa32UWERExLty0+LZVrHP6RgiIuIlQVOQvb16B7e9vIrR3dJ46NLBREUcffSTeqTz3i0nMKprKr97Yy2TZ+ZTsbfOi2lFRER8Izs1noKKGpqb9WaiiEgoCIqC7OMNJdz8/AoGd27LE1ce75V7v9LaxDB94hDuOqcPCzaVc/oDn/HpV2VeSCsiIuI7OWnx1DY0U1qtNxJFREJBwBdkCzeVc93s5fTpkMj0q4cQF+29296MMUwclcvrN4wiOTaKK6cv4Z631lHX2OS1c4iIiHhTbmo8AFt1H5mISEgI6IIsv2AXU2bmk5saz8yrh5LojvLJeXq3T+TNG0dz5Yhspi3YyvkPL2JT6V6fnEtERORYHGh9v02dFkVEQkLAFmRfbq/k6qeX0i7JzawpQ2kbH+3T87mjIvjDeX158so8dlTu5+x/fcbzSwp9ek4REQkOxpjpxphSY8yXBz2WYoz5tzHm69b/tvVHlgOt77eqIBMRCQkBWZB9VVLNFU99QWJsFM9OGUZGgttv5z6tTybv3XIiedkp3PHKGp75vMBv5xYRkYA1Azj9kMfuAD6y1nYHPmr93OcOtL7fVq5OiyIioeCwBZkxpqcxZuVB/6qMMbf4KtD++iaufGoJUREunrtmGB2SY311qu+VmehmxtVDGNs7g7veWMsHa3f6PYOIiAQOa+2nwK5DHj4PmNn68UxgnL/y5KbFa3NoEZEQcdiCzFq70Vo70Fo7EDge2Ae86qtAsdER/O6cPjw7ZRjZrTcuOyEywsWDEwbRr2MyNz2/guWFux3LIiIiASnTWruj9eOdQOZ3HWSMudYYk2+MyS8r80433wOt77WPpohI8DvSJYunAputtdt8EeaAM/q1p3tmgi9P4ZG46EieuiqPjAQ3U2bmU6COViIi8h1sS2X0ndWRtfYJa22etTYvPT3dK+c70Pq+pEqt70VEgt2RFmTjgTnf9YQv3gEMBGltYpg5aSjWWq56eok2kBYRkQNKjDHtAVr/W+qvE+e0dlrU1OmIbQAAIABJREFUskURkeDncUFmjIkGzgVe+q7nffEOYKDITYvnqYlD2FlZy6SZ+eyv1z5lIiLCG8BVrR9fBbzurxPntC7p18oNEZHgdyQzZGcAy621Jb4KE8gGd27LgxMGsbpoDzfOWUFTs9bti4iEC2PMHOBzoKcxpsgYMxn4M3CaMeZrYGzr535xoPV9QYU6LYqIBLsjKcgm8D3LFcPFj49rx13nHMeH60u46421uplaRCRMWGsnWGvbW2ujrLUdrbVPWWsrrLWnWmu7W2vHWmsP7cLoMwda32uGTEQk+EV6cpAxJh44DZjq2ziB76qRORTv2c/jn24hq20s153U1elIIiIShnJS1fpeRCQUeFSQWWtrgFQfZwkat5/ei+LKWv787gbaJ7k5b2CW05FERCTM5KTFs2hzBdZajDFOxxERkaN0pF0WBXC5DH+7qD/DclO49aVVLNpc7nQkEREJMzmpcexvaKK0Wt1/RUSCmQqyoxQTGcETV+SRkxrP1FnL2Liz2ulIIiISRnLSWjotbtV9ZCIiQU0F2TFIiotixqShxEZFcPXTS9hRud/pSCIiEibU+l5EJDSoIDtGWcmxPH31EKpqG7l82hfaOFpERPyiQ3IsURFGre9FRIKcCjIvOK5DEk9dlUfR7v1MfHop1bUNTkcSEZEQ19L6Pk4zZCIiQU4FmZcM65LKY5cfz/odVUyemU9tQ5PTkUREJMTlqvW9iEjQU0HmRWN6ZXD/JQNZWrCL659dTkNTs9ORREQkhGWnxrOtYh/WWqejiIjIUVJB5mXnDujAPeP68vGGUm59aRXNzRokRUTEN3LT1PpeRCTYebQxtByZy4ZlU7m/gfve20iCO5K7z+urTTtFRMTrslP/0/o+M9HtcBoRETkaKsh85PqTu1G5v4HHP9lCUmwU//fjXk5HEhGREJPbuhfZtooahndJdTiNiIgcDRVkPnTH6b2o2t/Iw/M2k+iOYupJXZ2OJCIiIeRA6/ut5Wp9LyISrFSQ+ZAxhnvG9aW6toE/vbuBxNgoJgzt7HQsEREJEQda329Tp0URkaClgszHIlyG+y8eyN66Rn716hoS3JGc3b+D07FERCRE5KbGs1V7kYmIBC11WfSD6EgXj152PEOyU/j5CyuZv7HU6UgiIhIi1PpeRCS4qSDzk9joCKZNzKNHZgLXzV7G8sLdTkcSEZEQoNb3IiLBTQWZHyW6o5g5aSgZCW5+OnsZpdW1TkcSEZEgd6D1fYGWLYqIBCUVZH6W1iaGx684nsr9DfzsuRU0NDU7HUlERILYgdb3BWrsISISlFSQOaB3+0T+fEF/lmzdxZ/f3eB0HBERCWLtk9xERRgKKtT6XkQkGKnLokPGDcpi5Td7eGrBVgZ0SubcAeq8KCIiRy4ywkWnlDgtWRQRCVKaIXPQr87szZCcttz+8mo27KxyOo6IiASpnNR4zZCJiAQpFWQOio508fClg2njjuS6Wcuo3N/gdCQREQlCOanxbKuoUet7EZEgpILMYRmJbh69bDBFu/fzyxdX0tyswVRERI5MTloc++qbKFPrexGRoKOCLADk5aTwm7N68+H6Uh6et8npOCIiEmRyWlvfb9V9ZCIiQUcFWYC4amQO4wZ24P4Pv2L+xlKn44iISBA5UJBt031kIiJBRwVZgDDG8KcL+tOrXSI3P7+Sb3ZpUBUREc90SG5pfb9Ve5GJiAQdjwoyY0yyMeZlY8wGY8x6Y8wIXwcLR7HRETx2+WCstUydtYz99U1ORxIRkSAQGeGiU9s4tqkgExEJOp7OkD0AvGet7QUMANb7LlJ4y06N54Hxg1i/s4pfv7ZGHbNERMQjOWnxbC3X6goRkWBz2ILMGJMEnAg8BWCtrbfW7vF1sHA2plcGN5/anVeWb2f24m1OxxERkSCQnRqn1vciIkHIkxmyXKAMeNoYs8IYM80YE3/oQcaYa40x+caY/LKyMq8HDTc3ndKdU3tl8Ie31pFfsMvpOCIiEuBy0+LV+l5EJAh5UpBFAoOBR621g4Aa4I5DD7LWPmGtzbPW5qWnp3s5ZvhxuQz3XzKQjm3jmDRjKV9ur3Q6koiIBLBstb4XEQlKnhRkRUCRtfaL1s9fpqVAEx9Lio1i9pRhJLijuOKpL9i4s9rpSCIiEqBy1fpeRCQoHbYgs9buBL4xxvRsfehUYJ1PU8m3spJjee6aYURHurhs2mI2l+11OpKIiASgDsluIl1qfS8iEmw87bJ4I/CsMWY1MBC413eR5FDZqfE8O2U4AJc+uVhtjUVE5H9ERrjonKLW9yIiwcajgsxau7L1/rD+1tpx1trdvg4m/61bRhuenTKc+sZmLn3yC7bv2e90JBERCTDZqXFqfS8iEmQ8nSGTANCzXQKzJg+jqraBS59cTElVrdORREQkgOSkxav1vYhIkFFBFmT6ZiUxc9JQyqvruPTJxZTvVXtjERGnGGN+boxZa4z50hgzxxjjdjKPWt+LiAQfFWRBaHDntjx99VCK99Ry+bQv2F1T73QkEZGwY4zJAm4C8qy1fYEIYLyTmQ60vi9Qp0URkaChgixIDc1NYdpVeWwpr+HK6Uuo3N/gdCQRkXAUCcQaYyKBOKDYyTAHWt8XaC8yEZGgoYIsiI3qlsbjlx/Php1VTHx6CXvrGp2OJCISNqy124G/AYXADqDSWvvBoccZY641xuQbY/LLysp8mulA6/sCdVoUEQkaKsiC3JheGfxrwmBWF1UyacZS9tc3OR1JRCQsGGPaAucBuUAHIN4Yc/mhx1lrn2jtVJyXnp7u00wHWt+rIBMRCR4qyELA6X3b8Y9LBpJfsIurpi+hQo0+RET8YSyw1VpbZq1tAF4BRjqciezUOArU+l5EJGioIAsR5w7owAPjB7GqaA/nPrSQtcWVTkcSEQl1hcBwY0ycMcYApwLrHc5ETlo8BWp9LyISNFSQhZBzBnTgpetG0GwtFz66iDdXOXpvuYhISLPWfgG8DCwH1tAypj7haCggJ7W19b1WS4iIBAUVZCGmf8dkXv/ZKPp2SOLGOSu4770NNDXrXVIREV+w1v7OWtvLWtvXWnuFtdbxKign7UCnRS1bFBEJBirIQlBGgpvnrhnOhKGdeGT+Zq55Jp+qWrXFFxEJBzmpcQBq7CEiEiRUkIWo6EgX957fj7vH9eXTr8oY9/BCNpftdTqWiIj4WFZybEvre+1FJiISFFSQhTBjDFcMz2b2lGHs2dfAuIcXMm9jqdOxRETEhyIjXHRKiWNbhZYsiogEAxVkYWB4l1Te+NkoOrWNY9KMpTz2yWZ13xIRCWE5qXFs1QyZiEhQUEEWJjq2jePln47gzH7t+fO7G7j5+ZXaRFpEJERlp8azTa3vRUSCggqyMBIXHclDEwbxfz/uyZurizn/kYWsKdJ+ZSIioSY3LZ4atb4XEQkKKsjCjDGGG8Z0Y/rEIeyqqWfcIwv507vrqW3QbJmISKjIbu20qPvIREQCnwqyMDWmZwb//sVJXHR8Rx7/ZAtnPPAZi7dUOB1LRES8ILd1LzLdRyYiEvhUkIWxpNgo/nxhf56dMoymZsv4Jxbz61fXUK09y0REgtqB1vfbtBeZiEjAU0EmjOqWxnu3nMCU0bnMWVLIj/7xKR9vKHE6loiIHKUDre8LyrVkUUQk0KkgE6Cl4cdvzu7DK9ePItEdxaQZ+dz8/AoqdEO4iEhQylbrexGRoKCCTP7LwE7JvHnjaH4+tgfvrNnBaf/4lNdXblfrZBGRIJOj1vciIkFBBZn8j+hIFzeP7c7bN51A55Q4bn5+JVNm5mu2TEQkiOSkxqn1vYhIEFBBJt+rR2YCc386kt+c1ZvPNpVz1oMLWLZtl9OxRETEAzmtnRY3l2rZoohIIPOoIDPGFBhj1hhjVhpj8n0dSgJHhMsw5YQuvPLTkcREubjk8cVM+2yLlsCIiAS4fllJJMRE8oe31rG3rtHpOCIi8j2OZIZsjLV2oLU2z2dpJGD1zUrizRtHc2rvDO55ez1TZy2jcr/a44uIBKrUNjE8dNlgviqp5qY5K2hsanY6koiIfActWRSPJbqjeOzy4/nt2X34eEMpZ//rM9YUVTodS0REvsdJPdL5/bnH8fGGUu55e73TcURE5Dt4WpBZ4ANjzDJjzLXfdYAx5lpjTL4xJr+srMx7CSWgGGOYPDqXF6aOoLHJcuGji5i9eJuWMIqIBKjLh2czZXQuMxYVMGPhVqfjiIjIITwtyEZbawcDZwA3GGNOPPQAa+0T1to8a21eenq6V0NK4Dk+uy1v33QCI7qm8pvXvuSWF1ZSo3sUREQC0p1n9ua0Ppn84a11fLyhxOk4IiJyEI8KMmvt9tb/lgKvAkN9GUqCQ0p8NE9PHMKtP+rBm6uKOfehBXxVUu10LBEROUSEy/DA+IH06ZDIjc+tYF1xldORRESk1WELMmNMvDEm4cDHwI+AL30dTIKDy2X42SndmT1lGJX7GznvoYW8srzI6VgiInKIuOhInrpqCImxUUyeuZSSqlqnI4mICJ7NkGUCC4wxq4AlwNvW2vd8G0uCzciuabxz02j6dUziFy+uYmu59r0REQk0mYlunrpqCFX7G5g8cyn76rXUXETEaYctyKy1W6y1A1r/HWet/aM/gknwyUh0c/vpPQEoqFBBJiISiPp0SORflw5iXXEVNz+/kqZmNWUSEXGS2t6LV2UkuAEoq6pzOImIiHyfU3pl8v/O7sO/15Xwp3fUDl9ExEmRTgeQ0JKeEANAabXuTRDxt9qGJtxREU7HkCAxcVQuBRX7mLZgKzlp8Vw+PNvpSCIiYUkzZOJV7qgIkmKjKNEMmYhfbSqtpv/vP+Czr7UPpHjut2f34ZReGfzujbV88pV+dkREnKCCTLwuIyFGM2QifvbC0m+ob2zmg7XaY0o8F+EyPDhhED0yE7jh2eX8e12J7ikTEfEzFWTidRmJMZRWa4ZMxF8am5p5bWUxAAs3lzucRoJNm5hIpk/Mo218FNc8k8/Jf5vHY59sZldNvdPRRETCggoy8bqMBDelWrIo4jefbSqnrLqOoTkpbCmrYUflfqcjSZBpnxTLx788mYcvHUyHpFj+/O4Ghv/pI37x4kpWFO7GWs2aiYj4igoy8bqMhBjKqus0gIv4ydxlRbSNi+LXZ/UGYOGmCocTSTCKinBxVv/2vDB1BB/8/ETGD+nEB2tLOP+RRZzz0AJeWFrI/vomp2OKiIQcFWTidRmJbuqbmqnc3+B0FJGQV7m/gQ/WlXDugA70y0oiJT6aRZu0bFGOTY/MBP5wXl8W/+pU7h7Xl/rGZm6fu4Zh937I3W+tY0vZXqcjioiEDLW9F6/LaG19X1JVR3JctMNpRELbO2t2UN/YzAWDO+JyGUZ0TWXh5nKstRhjnI4nQa5NTCRXDM/m8mGdWVqwm2c+L2DmogKeWrCVsb0zuGVsD/pmJTkdU0QkqGmGTLwuQ3uRifjN3GVFdMtoQ/+OLX8Uj+6WRklVHZvLahxOJqHEGMPQ3BQeunQwi+48hVvGdmdpwW7O/tcCps7KZ/2OKqcjiogELRVk4nUZiW4ANfYQ8bGC8hryt+3mwsEdv50NG9U1DYCFWrYoPpKR4OaWsT347PYx3DK2O4s2VXDGA59xw7PL+aqk2ul4IiJBRwWZeN1/ZshUkIn40ivLizAGzh+U9e1jnVPj6Ng2VgWZ+FyiO4pbxvZgwe2ncOMp3Zi/sZQf//NTbpqzgs26x0xExGMqyMTr4mMiiY+O0JJFER9qbrbMXb6d0d3SaJfk/q/nRndL4/MtFdrgV/wiKS6KX/6oJwtuP4XrTurKh+tLOO3+T/jFCyspKNfSWRGRw1FBJj6RmejWDJmIDy0p2MX2Pfu5cHDH/3luZLc0qmsbWbO90oFkEq7axkdz++m9+PS2MUw5oQvvfLmDU+//hP97aRWFFfucjiciErBUkIlPpCfEUFqlGTIRX5m7rIg2MZH8+Lh2//PcyK6pgO4j8wdjTLIx5mVjzAZjzHpjzAinMzktrU0MvzqzN5/eNoarRuTw+qpixvx9Pjc/v0LNP0REvoMKMvGJDM2QifjMvvpG3lmzgzP7tSM2OuJ/nk9rE0Ovdgks2qyCzA8eAN6z1vYCBgDrHc4TMDIS3Py/c/rw2W1jmDw6lw/XlXDGA59x9dNLWLJ1F9ZqSa2ICKggEx/JSIihtKpOA66ID7y/dic19U1c8B3LFQ8Y1S2NpQW7qW1o8mOy8GKMSQJOBJ4CsNbWW2v3OJsq8GQmuvnVmb1ZdMep3PqjHqwuquTixz/nwkcX8e91JTTrXkcRCXMqyMQnMhJi2N/QxN66RqejiIScucu207FtLENzUr73mFHdUqlvbGbZtt1+TBZ2coEy4GljzApjzDRjTPyhBxljrjXG5Btj8svKyvyfMkAkxUXxs1O6s+D2U/jDecdRWl3HNc/k8+N/fsrcZUU0NDU7HVFExBEqyMQnMhLV+l7EF3ZU7mfh5nIuGNwRl8t873FDc1OJdBndR+ZbkcBg4FFr7SCgBrjj0IOstU9Ya/OstXnp6en+zhhwYqMjuHJEDvNvPZkHxg8kwmX45UurOPmv83l64Vb21euNPBEJLyrIxCcyErQ5tIgvvLpiO9bChYOzfvC4NjGRDOyUzMLNFX5KFpaKgCJr7Retn79MS4EmHoiMcHHewCzevfkEpk/Mo0Oym9+/uY4T75vPW6uLteRdRMKGCjLxicxvZ8jUaVHEW6y1zF1WxJCctmSn/s/KuP8xslsaa4r2ULm/wQ/pwo+1difwjTGmZ+tDpwLrHIwUlIwxnNIrk5euG8lL142gfZKbnz23gikz8ynes9/peCIiPqeCTHwiXTNkIl63qqiSzWU1P9jM42CjuqbSbGHxFs2S+dCNwLPGmNXAQOBeh/MEtSE5Kbx6/Uh+c1ZvFm2u4LT7P2HGwq3a5FxEQpoKMvGJRHckMZEuzZCJeNHcZUXERLo4q397j44f1LktsVERLNJ9ZD5jrV3Zen9Yf2vtOGutuqgco8gIF1NO6MIHPz+R43NSuOvNdVz46CI27NQeZiISmlSQiU8YY8hIjFFTDxEvqWts4s3VxfzouHYkuqM8+proSBdDc1N0H5kEpU4pccy8egj/vGQghbv2cfaDC/jb+xu1lYOIhByPCzJjTERrW9+3fBlIQkdGgltLFkW8ZN6GUvbsazhsM49DjeqWyqbSveys1Gy1BB9jDOMGZfHhL07i3IEdeGjeJs584DMtwxWRkHIkM2Q3A+t9FURCT0ZCjJYsinjJy8u2k54Qw+huaUf0dSO7thy/aLOWLUrwSomP5v6LBzJr8lAamy3jn1jMHXNXU7lPDWtEJPh5VJAZYzoCZwHTfBtHQklmoltLFkW8oGJvHfM3lnL+oCwiI45spXmf9om0jYti4SbNKEjwO6F7Ou/fciJTT+zCS8uKOPX++cxYuJW6Ri1jFJHg5enI/k/gNqD5+w4wxlxrjMk3xuSXlZV5JZwEt/SEGKprG9lfr4FS5Fi8saqYxmbLhR52VzyYy2UY2TWNRZvLta+ThITY6AjuPLM3r98wiq7pbbjrzXWc8rdPeGFpIY1N3/tniohIwDpsQWaMORsotdYu+6HjrLVPtHaayktPT/daQAleGQnai0zEG+YuL6JvViI92yUc1deP7JbKjspatpTXeDmZiHP6ZiXx/LXDmTV5KGkJMdw+dw1j7/+E11dup1lt8kUkiHgyQzYKONcYUwA8D5xijJnt01QSEjISW/ci07JFkaO2cWc1X26v4oJBRz47dsCoA/eRqf29hBhjDCd0T+e160fy5JV5uKMiuPn5lZzxwGe89+VOzQqLSFA4bEFmrb3TWtvRWpsDjAc+ttZe7vNkEvS+nSFTp0WRozZ3eRGRLsN5Azsc9Wtkp8aRlRyr+8gkZBljOK1PJu/cdAL/mjCIhqZmrpu9jHMfWsj8jaUqzEQkoGkfMvEZLVkUOTaNTc28umI7J/fMILVNzFG/jjGGUd1S+XxLBU1ayiUhzOUynDOgAx/8/ETu+0l/dtXUM/HppVz8+Ocs3lKhwkxEAtIRFWTW2vnW2rN9FUZCS9u4aCJdRksWRY7SjEUFlFXX8ZPjj2zvse8yqlsalfsbWFtc6YVkIoEtMsLFxXmdmHfrydx93nFsq9jH+CcWc9aDC5j1eQFVtWqXLyKBQzNk4jMulyEjIYaSKs2QiRwJay1/fX8D97y9nrG9MxnbO/OYX3NE11QALVuUsBId6eKKETl8etsY7h7XF4Dfvr6WoX/8kFtfWsWybbs1ayYijot0OoCEtvREN2WaIRPxWENTM796ZQ0vLStiwtBO3H1e3yPee+y7ZCS46ZmZwKLN5fz05K5eSCoSPNxREVwxPJvLh3VmzfZK5iwp5I2Vxby8rIgemW0YP6QzFwzOIjku2umoIhKGVJCJT2UkxFBYsc/pGCJBYV99I9c/u5z5G8u4+dTu3DK2O8YYr73+yG6pzFlSSG1DE+6oCK+9rkiwMMbQv2My/Tsm8+uz+vDWqmLmLCnkD2+t48/vbeDMvu2YMLQzQ3NTvPq7JyLyQ1SQiU9lJMSQX7DL6RgiAa9ibx2TZuazpmgP957fj0uHdfb6OUZ1TePphQUsL9zNyNZW+CLhqk1MJOOHdmb80M6sLa7k+SXf8NqK7by2spgu6fGc3b8Dp/XOpG9WooozEfEpFWTiUxkJbnbva6C+sZnoSN2yKPJdvtm1jyunL6F4z34eu/x4fnRcO5+cZ1iXFCJchkWbKlSQiRzkuA5J3D0uiTvP7MXbq3fw0rIiHvr4ax786GvaJboZ2yeD0/q0Y3iXFGIiNbssIt6lgkx8KiOxpVV32d46spJjHU4jEni+3F7JxKeX0tDUzLNThpGXk+KzcyW4oxjQMYmFm8u5lZ4+O49IsIqLjuSivE5clNeJir11fLyhlA/XlzB32XZmLy4kPjqCk3qmc1qfTMb0zNA9ZyLiFSrIxKcyWwuykqpaFWQih1jwdTnXzV5GojuSOdeMoHtmgs/POapbGg/P20RVbQOJ7iifn08kWKW2ifm2OKttaGLR5nL+va6lQHtnzU4iXIa87Lac1ieTcwd2ICPB7XRkEQlSWkMmPnVggCqtUqdFkYO9vnI7V89YQlZyLK9cP8ovxRjAyK5pNFv4Yovu7RTxlDsqglN6ZfKnC/rxxZ2n8toNo/jpSV2p3N/APW+v56T75nPfexuo3K/9zUTkyGmGTHwqI6F1yWK19iITOWDaZ1u45+31DM1N4ckr80iK9d9M1eDsZNxRLhZuKue0Pse+v5lIuHG5DAM7JTOwUzK3/rgnm0r38uBHX/PI/M3MXryN607uytUjc4mN1r1mIuIZFWTiU6ltYnAZKNVeZBLmqmsbePfLnbyyvIjFW3ZxRt92/OOSgX5vPx8TGcGQnBQWbS7363lFQlW3jDY8OGEQ153Ulb99sJH73tvI0wsLuOmUblwypLMaWonIYakgE5+KcBlS28RoyaKEpcamZhZsKueV5dv5YN1OahuayUmN484zejHlhC5EuJxppT2qWxp/fncDpVW1ZCTqvhcRb+jTIZHpE4ewtGAX9723gd++vpYnP9vKz0/rzrkDshz7fReRwKeCTHwuIyGGUi1ZlDBhrWXdjipeXd6yn1H53jqSYqP4yfEdOX9QRwZ3TnZ8T6NRrS3vF22uYNygLEeziISaITkpvDh1BPM3lnHf+xv5+QureGz+Fv7vxz05tXeG47//IhJ4VJCJz2UkxFCiGTIJcSVVtby2YjuvrtjOhp3VREUYxvTM4ILBHRnTKz2g9i7q0yGR3LR4qmvVgEDEF4wxjOmVwUk90nlrzQ7u/2AjU57JZ3DnZO4Z148+HRKdjigSVj7eUMK2in1cPSrX6SjfSQWZ+Fxmops126ucjiHiNdZaiitrWVG4m+Xb9rC8cDeri/bQbGFQ52TuHteXs/u1p218YO5RFOEyfPzLk/ROvYiPuVyGcwd04Iy+7Xgpv4i/vr+Bu95cy4tTRzgdTSRsVO5v4JcvrqKusZmJI3MCcuxTQSY+l5EQQ0VNHY1NzURG6OZmCT61DU2sLa78tvhaXrj721lfd5SL/lnJ/OyU7pw/KIvctHiH03omEAckkVAVFeHi0mGdWV20hw/WlTgdRySsPDxvE7v3tawIKa4MzH1xVZCJz6UnurEWKmrqyVQDAQlw1loKd+1jdVElKwpbCrC1xZU0NFkAOqXEMrxLKoM7t2Vw57b0ap9AlN5oEBEPdEmPZ1dNPXv21ZMcF5gz6CKhpLBiHzMWFtAzM4GNJdV8XVKtgkzC04G9yEqr6lSQSUCx1rJ9z37WFFWyently3+L9lBV2wj8Z/Zr0uhcBnduy6DOyd9udi4icqRy09oAsKW8hsGdVZCJ+Npf3ttAhMvwwISBnP7Pz9hUupeTe2Y4Het/qCATn/u2IKuuBZKcDSNhraSqllXf7GHN9kpWF1WyZnslu2rqAYiKMPRql8jZAzrQPyuJfh2T6JGp2S8R8Z4u6S1LmreW1TC4c1uH04iEtmXbdvH2mh3cMrY7vdolktYmmq9L/n97dx4fZXX3//91sk2WmUDCzIRASEggIDsCioqAexWtWrfWqq1Lpdra3q3eXexy3/3ddre128/Wal1rtVptXepaWy0gCLLvkJCEBBKy7yHLzJzvHwnUWpVBkrkmM+/n45EHk8yV6/pwHjM587nOOZ/T4XRY70kJmQy5Q/scaXNoiaRAMMTOA+2sr2xmbUUz6/Y2s7/lINBf1KLY7+asKX5m5I1kVt4IJo/2RFUlRBGJPeOy0klMMJQ1ROeHQpFYYa3ljr/uICfTxdJFRUD/Ju4lde0OR/belJDJkPO5+0fIatu0F5kMnbbuPjZUtrCuool1lc1srGyhszcIQE6mi3kF2Vy3YDzH52cxNTeTtBQlXyISWSlJCeRnp1Pe0OlEQeFzAAAgAElEQVR0KCIx7fnNNWysauHOy2aSntKf7hT7PTyzcT/W2qgrbKWETIZcSlIC2RkpGiGTQdV6sI9VexpYUdrA2opmdtW2Yy0kGJiSm8mlc/OYW5DF3IIsxo5Mi7o/viISnwq9GZTVKyETGSrdfUF+9NJOpuZmcumcvMM/L85x094doK49+moaKCGTiPB7XNRpc2g5BoFgiE37Wli2u4HlJfVsrOrf98vtSmJOQRbnTc9l3vgsZo0bidulP20iEp2KvBm8WdpAKGRJSNCNIpHB9uCbFexvOcidl838t/fYRH9/UZ2S2g4lZBKffB4X9e2asihHp7Kxi2Ul9SwvqWdlaSPtPQESDMzMG8ktp09k4SQfs8eNVOENERk2Cn0Z9ARCVLceJC8r3elwRGJKQ0cPd79eyllT/Jwy0ftvzxX7PQDsrm3n1GLve/26Y5SQSUT4PamU1mkRs3ywQDDEqrJGXtl2gOUlDext7AJg7Mg0LpiVy8JiH6dMGKX9e0Rk2CoaKH1f3tCphExkkP38td109wW5fcmU/3jO605hZHoyJVH4eVQJmUSEP9NFfXuPpmjIf+gLhli5p5GXttTwyrYDNHf1kZ6SyCkTRnH9gkIWFnsp9GZoDZiIxIRDpe/L6jtZWOxzOBqR2FFS285jqyu55qQCJvjc//G8Mf0VlkujsNLiERMyY0wqsAxwDRz/lLX2f4c6MIktfo+LQMjS1NWLd6DqosSvvmCIN0sbeHFLDa9ur6Wlq4+MlETOmprDkhm5LJ7kIzVZVRBFJPb4PS4yUhJVaVFkkH3/xR1kuJL4r7Mmve8xxTkeXthcE3WVFsMZIesBzrDWdhhjkoEVxpiXrLVvDXFsEkMOLZ6sa+tRQhanegMh3tzTwIub+5Ow1oN9uF1JnDXFz5IZuSxSEiYiccAYQ6Evgz310TdtSmS4Wl5Sz+u76vnGkuPIznj/ZQ3FfjetB/to6OjF54mez6NHTMistRY49FcjeeDLDmVQEnv8Ay/6uvZuppLpcDQSSdur23h8TSXPbaqm9WAfHlfS4ZGwhcVeJWEy7BljEoG1wH5r7QVOxyPRr8jrZn1ls9NhiMSEYMjyvRd2MC47jU+fMv4Djz1U2KOkrn14JWRwuLNZB0wE7rbWrn6PY5YCSwHy8/MHM0aJAX7PwAiZ9iKLC129Af66qYbH1lSysaqFlKQEzps+mo/OHMPCSV5cSUrCJKb8F7ADdLdJwlPozeD5zdV09wV1U0rkGD21roqdB9q5+5Nzjvj5ojinf21ZaV0Hp0yInkqLYSVk1togMNsYMxL4izFmurV267uOuRe4F2DevHkaQZN/48/svwtRr4Qsph0aDXtmw37aewJM9Lv5nwumcsmcsaqMKDHJGJMHnA98D7jV4XBkmCjyZWAt7G3sYvJoj9PhiAxbnT0BfvLqbuYWZLFkxugjHu/3uPCkJlFSG11Tho+qyqK1tsUY8zpwLrD1SMeLHJKanIgnNYm6Nu1FFmsOjYb9YU0lmwZGwy6YkcuV8/OZV5AVVYtmRYbAz4GvAu/7qVozSOTdDpW+L6vvUEImcgx++8891Lf38Ntr5ob1eeNQpcWSKKu0GE6VRR/QN5CMpQFnAz8a8sgk5vg9LmrbNEIWK0pq23l4VQXPbKimoydAsUbDJM4YYy4A6qy164wxp73fcZpBIu9WeKj0vSotinxoNa0HuXd5GR+dNYY5+Vlh/16x38Pfd9YOYWRHL5wRslzg4YF1ZAnAk9bavw5tWBKLcjJTqWvXCNlwt6mqhbtfL+XV7bWHR8M+OT+fuRoNk/izALjQGLMESAUyjTGPWmuvdjguiXJuVxJ+j0ul70U+pIaOHr761GZCFr76kclH9bvFOW6eWFtFU2fvB1ZkjKRwqixuBo6PQCwS4/weF2v3qqrUcGStZVVZI79+fQ8rShvITE3ii2cWc+0p46Pmj5lIpFlrbwduBxgYIftvJWMSriJfBmUqfS9yVIIhy2NrKrnz5Z109Qb5n49OZVx2+lGdY6L/X4U9TizMHoowj9pRrSETORb+zFTq2nuibjM+eX+hkOUfO+u4+41SNlS24HW7uP2847jqpALcLv35EBH5sAq9bl7eWuN0GCLDxqaqFr797FY272vl5KJR3HHxNCb6j34NZnHOv0rfKyGTuOP3uOgNhGg7GGBEerLT4cgHCARDvLClht+8sYedB9rJy0rjjounc/ncPJVoFnkP1to3gDccDkOGkSJvBs1dfTR39pKlmQYi76u1q48fv7KTx9ZU4nW7+MUnZnPhrDEf+ub+mBGpZKQkRlWlRSVkEjG+d2wOrYQsOvUEgjy9bj/3/HMPlU1dTPS7ueuKWXx01hiSExOcDk9EJGYUvaOwx1wlZCL/IRSyPL1+Hz98aSfNXb1ce8p4vnz2JDJTj+0zpDGGiVFWaVEJmUTMoc2ha9t6Dg8XS3Sw1vLcpmp+/PIu9rccZGbeCL6xZC7nTM0hIUHTS0VEBluhdyAhq+9gbkH4FeJE4sHOA218+5mtvF3RzNyCLH5/0XymjskctPNP9HtYXlI/aOc7VkrIJGIObQ6tSovRZW1FE3e8sINNVS1Mzc3k+5fMYFGxV+v8RESG0LjsdJISjCotirxDR0+An/1tNw+trCAzNYkfXzqTy+bmDfrN4eIcN0+v30drV19UzNpSQiYRk5PZP0JW1669yKLB3sZOfvTyTl7ccgC/x8Wdl83kkjl5JGpETERkyCUnJpCfnU5ZvRIyiV+9gRBb9rewuryJNeVNrK1oprM3wCdOyOerH5k8ZOsriw9VWqxvZ26B84U9lJBJxLhdSaSnJFKnzaEd1drVx6/+UcLDqypISkjgS2cVs3RREekp+nMgIhJJRb4MjZBJXOnqDbCh8lAC1siGyhZ6AiGgP0m6cPYYrpg3jtnjRg5pHJMOVVqs7VBCJvHH73FpyqJD+oIhHn1rL7/4ewmtB/u4fG4et50z+fDIpYiIRFahN4NlJQ0EQ1azEyTm9AZCVDZ1UVbfwbq9zawub2Lr/lYCIUuCgWljRnDV/AJOLMzmhPFZjHK7Ihbb2JFppCYnUFIXHZUWlZBJRPk9qZqyGGHWWv62vZYfvLST8oZOFkwcxTeXTB3UxbEiInL0inxuegMhqlsOHvXmtiLRoC8Yoqqpi72NXZQ3dFLR2Hn43/3NBwnZ/uNSEhOYNW4ESxcVcWJhNnMLsvAcY7XEY5GQcKjSohIyiUO+TBfbq9ucDiNuVDR08o2/bGHlnkYm+t08cO08Tp/sV8EOEZEocLjSYkOnEjKJWh09Aaqauqhs6jr8797GLioaO9nXfJDgoawL8LiSGO/NYPa4LD42eywFozIo9GUwNTcz6vYxLfZ7WF3W6HQYgBIyiTC/x8XrbZqyONQCwRAPvFnOT1/dTUpSAndcNI0rT8wnSXuJiYhEjUN7kZXXd7B4ks/haCReWWupbeuhrKGDqqYuqpoOUvmOBKyxs/ffjve4ksgflc70MSO4YGYu40dlUOjNYLw3g1EZKcPmpu9Ev5u/bNhPe3efo6N1oIRMIiwnM5Wu3iAdPQHcLr38hsKOmja+9vRmNu9r5eypOXz34ulaJyYiEoV8bhduVxJlKuwhEdDRE6C8vpOyhg7K6jspa+ikrL6D8oZOunqDh49LTDCMHZlGfnY650wbTX52+uGvcdlpjEhLHjZJ1wc5VGlxT33nkBcRORJ9IpaI8nsG9iJr68btczscTWzpCQS5+x+l/PqNPYxMT+buT85hyYzRMfFHU0QkFhljVGlRBl1bdx87a9rZXt3K7rqOw0lX7TuqXCcYyMtKp9CbwYmF2RT53BSOyqBgVDq5I1LjYkZN8eFKi+1KyCS++D3/2ousSAnZoFm3t5mvPb2Z0roOLjl+LN++YOqQ7d0hIiKDp9CbwdqKZqfDkGEoFLJUNXexo6aN7TXt7KhpY0dNG/uaDx4+ZmR6MkXeDBYW+yjyZVDkdVPkyyA/Oz3q1nRF2risNFKSEiiNgsIeSsgkovyZAyNkqrQ4KLp6A9z5yi4eWllBbmYqD153AqdP9jsdloiIhKnI6+bZjdV09wXj/gOyvD9rLXvqO1m/t5kt+1vZXtPGrgPtdPQEgP4Rr0JvBrPHjeST8/OZkpvJ1NxM/B6XZsq8j6TEBIq8GVFRaVEJmUTUO6csyrFZUdLA1/+8mX3NB7nmpAK+eu5kxxeliojI0Sk8VNijoZMpudqORPp19QbYVNXK+spm1u1tZn1lMy1dfQC4XUlMyfVwyZyxhxOvSTke0lKU0B+t4hwPG6ucH6FWQiYRNSItmZSkBI2QHYPOngD/9/x2nlhbRaE3gyeWnsT8olFOhyUiIh9CkVcJWbyz1lLd2t2feO3tT8C217QdLic/wZfBOVNzmFuQxdyCLIq8bhK0kfigKPa7eX5TNV29AdJTnEuLlJBJRBlj8LldGiH7kHbUtPH5x9ZT3tDJZxcX8eWzJmmKi4jIMHZ4L7J656dNSeS0dvWxorSB5SX1LC9pYH9L/7qvtOREZo8byc2LJzC3IIvj80cyMl1rwofK4UqLdZ3MyBvhWBxKyCTicjJdGiE7StZaHl9TxXee38aItGT+8Jn5nDLB63RYIiJyjDJcSYzOTFXp+xgXCIbYWNXCspIGlu2uZ/O+FkIWPKlJLJjg5caFhcwbn81xoz1xUeEwWhTn9CdkJXXtSsgkvvg9qZTqTmDY2rv7+MZftvL8pmoWFnv52cdn43W7nA5LREQGSaFXpe9jUVVTF8tK6lm2u56VpY209wRIMDBr3EhuOaOYxZO8zMobqQTMQQWjMkhKMI4X9lBCJhHnz3Sxck+D02EMC1v3t3LLY+upbOriKx+ZzM2LJ2jeuIhIjCnyZfDXzTVYa1URbxiz1rKtuo0Xt9Tw8rYDlNX3J9ljRqRy/sxcFk3yccqEUZqCGEWSExMo9GZQUquETOKM3+OirTugEr8fwFrL79/ay3f/uoPsjBT+uPRkTizMdjosEREZAoXeDFoP9tHc1Ue29pAcVqy1bNnfygtbanhpywEqm7pITDCcVJTN1fMLWDTJxwRfhhLtKDYpx8O26lZHY1BCJhF3eHPoth7yR6U7HE30aT3Yx9ef3sxLWw9w+mQfP71itjpoEZEYNsHXv46lrL6D7AzdfIt21lo2VrXw0tYDvLilhn3NB0lKMJwy0cvnTpvAOdNGq98eRib63by0tcbRgQIlZBJxvsObQ3crIXuXTVUt3PL4empaurn9vOO4cWGRpiiKiMS4w5UWGzqZN14JWTSy1rK+soUXt9Tw0pYaqlu7SU40LJjo5YtnFnPO1BxNRRyminPchCyU1XcydYwzW08cMSEzxowDHgFyAAvca639xVAHJrEr59AImSotHmat5YE3K/jhSzvwe1J54rMnM7cgy+mwREQkAvKy0khONIfXHEn0qG/v4c/r9/HE21WUNXSSkpjAwmIvt50zmbOm5DAiPdnpEOUYFfs9QH+lxahNyIAAcJu1dr0xxgOsM8b8zVq7fYhjkxjlPzRCpr3IAOgJBLn96S38ecN+zpqSw08un6m7bCIicSQpMYH87HTKG1SBOBoEgiGWldTzxNtV/H1HHYGQZV5BFjedNoFzp48mM1VJWCwZ700nMcFQ6mClxSMmZNbaGqBm4HG7MWYHMBZQQiYfSnZ6CkkJRiNkQFNnL5/9/Vrermjm1rMn8YUzJmrhr4hIHCr0ujVC5rCqpi6eXFvFn9bu40BbN6MyUrj+1EKumDeOiQMbCEvscSUlUjAq3dFKi0e1hswYMx44Hlj9Hs8tBZYC5OfnD0JoEqsSEgxetzaHLq1r5/qH1lLb1s2vrjyej84a43RIIiLikAm+DJbtricYsiRq7XDEdPcFeWXbAZ5cW8WbpY0kGFg8ycd3LpzKGcflkJKkPcLiQbHfTUldu2PXDzshM8a4gaeBL1lr2979vLX2XuBegHnz5tlBi1Bikj/TRW0cT1lcXlLP5/6wHldSAn9cehLH52u9mIhIPCv0ZtAbDLG/+aAKXkXAgdZuHlpZwR/frqSlq4+8rDRuPXsSl83NY8zINKfDkwgr9nt4bUcdvYGQI0l4WAmZMSaZ/mTsD9baPw9tSBIP/B4X+5oPOh2GIx59ay//+9w2iv1ufvfpeeRlqeMVEYl3RYdK3zd0KCEbQjtq2rhveRnPb6omGLJ8ZNporppfwCkTRqmqcRwrznETDFkqGjuZlOOJ+PXDqbJogPuBHdbau4Y+JIkHPk8q6ytbnA4jooIhy/de2MEDb5Zz+mQfv7zyeDxaGCwiIryj9H19J6dNdjiYGGOtZXlJA/ctL2N5SQPpKYlcNb+A6xcUKvkVgMNrBHfXtkdnQgYsAK4BthhjNg787BvW2heHLiyJdTmZLpo6ex0bGo60jp4AX3x8A//YWcd1C8bzzSVTSEqM/f+3iIiEx+tOwZOaRHmDCnsMlt5AiOc2VfO75WXsPNCO3+PiKx+ZzFXz81XNWP7NBJ8bY3CssEc4VRZXABrDlUHlH9iLrKGjJ+bnau9vOcgND71NSV0Hd1w8nWtOKnA6JBERiTLGGIq8GZSp9P0xa+3q47E1lTy0spzath4m53i487KZXDh7DK6kRKfDkyiUmpxIfna6Y6Xvj6rKoshg8XsG9iJrj+2EbGNVC595eC09fUEeuPYEFk/yOR2SiIhEqSKfm9VljU6HMWw1d/Zyz7I9/H7VXrp6g5w60cuPL5vFomKvtpSRI3Ky0qISMnFEPGwO/eq2A3zh8Q34M108fuN8ih2YkywiIsNHoTeDv2zYT1dvgPQUfUQLV1t3H/cvL+f+FeV09ga4cNYYli4qYtqYEU6HJsPIRL+Hf+6upy8YIjnCy0r0bhdHHJqyWBuje5E9u3E/tz65ieljR/DAp+cxyu1yOiQREYlyRb7+wh4VDV1MHZPpcDTRr6s3wMMr9/LbZXto6erjvOmj+fLZkxwpyiDD36QcN31By97GrohvBK6ETBzhdadgDNTH4AjZY6sr+eYzW5hfmM3vPn0CbpfeZiIicmSHKy02dCgh+wDdfUEeX1PJ3a/voaGjh9Mn+7jtnMlMH6sRMfnwiv39iXxpXbsSMokPSYkJjMpIoS7GRsjuW1bG917cwWmTfdxz9VxSk7V4WEREwnMoISuvV6XF99IXDPHUun386u8lVLd2c1JRNvdcPYd547OdDk1iwAR///uvpLaDc6dH9tpKyMQxfk9qzCRk1lp+/loJv/h7CefPyOVnH58dF+X8RURk8KSnJJE7IpUylb7/N8GQ5blN+/n5ayXsbezi+PyR/OTyWZwy0et0aBJD0lOSyMtKo8SBSotKyMQx/kwXde3Df8qitf0bPv9uRTmXz83jh5fOJDFB1ZxEYp0xZhzwCJADWOBea+0vnI1KhrsiX4YSsndYXdbId57fzo6aNqbmZvLAtfM4fbJfVRNlSPRXWlRCJnHE73GxvbrN6TCOSTBk+dYzW3h8TRXXnjKe/7lgKglKxkTiRQC4zVq73hjjAdYZY/5mrd3udGAyfBV6M3h2YzXW2rhOOqpbDvKDl3by/KZqxo5M41dXHs/5M3LVx8qQKs7x8OaeRoIhG9Gb60rIxDF+TyoNHT0Rf9EPlr5giNue3MRzm6r5/OkT+O9zJsd15ykSb6y1NUDNwON2Y8wOYCyghEw+tCKvm/buAI2dvXjjsEJvd1+Q+5aV8es39hCyli+dVcxnF00gLUVrsmXoTfS76Q2EqGrqYvzAms5IUEImjvFnughZaOzowZ+Z6nQ4R6W7L8gtj23gtR21fO3c47j5tAlOhyQiDjLGjAeOB1a/x3NLgaUA+fn5EY1Lhp/CgdL35Q2dcZWQWWt5dXst331hO1VNB1kyYzTfWDKFvKx0p0OTOFI8UF2xpK4jogmZqg6IY/yegc2hh1lhj86eADc8/Dav7ajljoumKRkTiXPGGDfwNPAla+1/zMO21t5rrZ1nrZ3n8/kiH6AMKxO8/R8Iy+ojv47FKaV17XzqgTV89vfrSEtO5LHPzOfXV81VMiYRN/FwQtYe0etqhEwcc2hUrLate9jsHdJ6sI/rH3qbDZXN/PTyWVw6N8/pkETEQcaYZPqTsT9Ya//sdDwy/I3NSiMlMSEuCnu0dffxi9dKeHhlBekpiXzno1O5+qQCkhI1XiDO8KQmkzsilZLayN4QUUImjpngc+NKSuC1HXWcOSXH6XCOqK27j0/dv5rtNW3c/ck5nDcj1+mQRMRBpn/R6P3ADmvtXU7HI7EhMcFQMCqdshjei8xay1Pr9vGjl3fS2NnLJ07I57/PmcSoOJqiKdFrot8d8REy3YIQx4xIS+aSOWP58/p9NHf2Oh3OB2rv7uPTD6xhe00bv7lqrpIxEQFYAFwDnGGM2TjwtcTpoGT4K/RmUB6jI2RVTV186oE1fOWpzeRnp/P8Lafyg0tmKBmTqFHs91Ba10EoZCN2TY2QiaOuW1DI42uqeGxNJZ8/faLT4bynzp4A1z34Npv3tXL3J+dw1tToH80TkaFnrV0BqLSqDLpCXwav76ojEAzFzPS9UMjyyKoKfvzKLgxwx0XTuGp+gcrYS9SZW5BFZVMnHb0BMlOTI3JNJWTiqEk5HhYWe3lkVQVLFxWRHGUdT1dvoH/NWFULv/zE8Zw7fbTTIYmISIyb4HXTF7TsbzlIwajIVXobKnvqO/j605t5u6KZRZN8fP9j01WwQ6LW+TNzOX9mZGdCRdenX4lL1y8opLathxe31Dgdyr852BvkMw+v5e2KJn728dkRf3OKiEh8OlT6frivIwsEQ/zmjT2c94vl7K7t4CeXz+Lh605QMibyLhohE8ctnuSjyJvBAyvKuXDWmKjYXLm7L8jS369lVVkjd10xiwtnjXE6JBERiRNFA/sflTV0crrDsXxY26vb+OrTm9i6v41zp43m/y6eht8zvPYcFYkUjZCJ4xISDNctGM+mfa2sr2xxOhx6AkFuenQdK0ob+PGlM/nY8SptLyIikZOdkUJmatKw3IusJxDkrld3ceH/v4IDrd38+qo53HPNXCVjIh9ACZlEhUvm5JGZmsQDb5Y7GkdvIMTn/7CeN3bV84OPzeDyeeMcjUdEROKPMYYin3vYVVrcUNnMBb9cwS//UcqFs8bwty8vZomqEosckRIyiQoZriSuPDGfl7ceYH/LQUdi6AuG+MLj63ltRx13XDydT5yY70gcIiIiE/1utuxvpbGjx+lQjqgvGOKnr+7i0t+spKMnwIPXnsBdH59NVkaK06GJDAtKyCRqfOqU8QA8sqoi4tcOBEN86Y8beWVbLd/56FSuOakg4jGIiIgccuPCIrr7gvx/z293OpQPVFrXwSW/Xsmv/lHKJXPyeOXLizj9OL/TYYkMK0rIJGqMHZnGudNG8/jqSrp6AxG7bjBkufXJTbywpYZvnT+FaxcURuzaIiIi72XyaA9fOKOY5zZV8+q2A06H8x+stTy8soLzf7mcfc1d3HP1HH5y+ayI7dskEkuUkElUuf7U8bR1B3h6/f6IXK8vGOLWJzfy3KZqvn7ecXxmYVFErisiInIkN582gSm5mXzrma20dvU5Hc5htW3dfPrBt/nf57Zx8oRRvPKlRZw7XWvFRD6sIyZkxpgHjDF1xpitkQhI4tuc/Cxm5Y3gwTfLCYXskF6ruy/IzY+u59mN1Xzt3OO4afGEIb2eiIjI0UhOTODOy2bS2NnLd1+IjqmLL26p4SM/X8aa8kbuuHg6D157Av5MVVAUORbhjJA9BJw7xHGIAP2Vpa4/tZCy+k7+ubt+yK7T2RPg+ofe5rUdtdxx0TRuPk3JmIiIRJ/pY0dw0+Ii/rRu35D2i0fS1t3HrU9s5HN/WE9BdjovfHEh15xUEBV7h4oMd0dMyKy1y4CmCMQiAsB503PJyXQNWQn8lq5ervrdalaXN/Gzj8/impPHD8l1REREBsMXzihmot/N7U9vpr078lMX3ypr5LyfL+fZTdV88cxinrr5FCb43BGPQyRWDdoaMmPMUmPMWmPM2vp65+7gyPCXkpTAp04ez/KSBnbXtg/quevau/nEvW+xvbqN31w1R5s+i4hI1EtNTuTHl82kpq2bH728M2LX7e4L8oMXd3DlfW+RnGj4000nc+vZk0hOVAkCkcE0aO8oa+291tp51tp5Pp9vsE4rcerKE/NxJSXw4CCOku1r7uKKe1ZR2dTFg9edwDnTRg/auUVERIbSnPwsblhQyKNvVbJqT+OQX2/lngbO/fkyfrusjCtPzOfF/1rInPysIb+uSDzSLQ6JStkZKVwyZyx/Xr+fps7eYz5faV0Hl9+ziqbOXh79zHwWTPQOQpQiIiKRc9s5kykYlc7Xnt48ZNvDtHb18bWnNvPJ+1YTsvDoDfP5/sdmkJ6SNCTXExElZBLFrl9QSE8gxONrKo/pPFv3t/Lx366iL2h54rMn6w6fiIgMS2kpifzo0plUNnXx01d3D+q5rbX8dXM1Z971T55av4/PLi7ilS8t4tRi3cAUGWrhlL1/HFgFTDbG7DPG3DD0YYlAcY6HhcVeHllVQW8g9KHOsbaiiSvve4vU5ET+dNPJTMnNHNwgRUREIuikolFcc1IBD7xZzrq9zYNyzuqWg9z4yFpueWwDo0e4ePbzC7j9vCmkpSQOyvlF5IOFU2XxSmttrrU22VqbZ629PxKBiQBcf2ohtW09vLS15qh/d9nueq65fw0+t4snbzqZQm/GEEQoIiISWV877zjGjEjjq09torsv+KHPEwpZHllVwdl3/ZMVpQ18c8kUnvncAqaPHTF4wYrIEWnKokS1xcU+inwZ3L+iHGvD2yi6rbuPx1ZXcsPDb1PozeDJm05m7Mi0IY5UREQkMtyuJH5wyQz21Hfyy7+XfKhz7K5t57J7VvI/z25jTkEWf/vyYm5cVESSKiiKRJxWaEpUS0gwXLegkGnkjzQAAAbNSURBVG8/s5X1lc3MLcj+j2OstZTUdfD6zjpe31XH2opmAiHLvIIs7r/2BEakJTsQuYiIyNBZNMnHFfPy+O2yMs6bnsuMvCOPagWCIcoaOnl+UzX3/HMPblcSP/v4LC6ePVYbPIs4SAmZRL1L54zlzpd38sCKisMJWVdvgJWljby+q443dtWzv+UgAMeN9nDjoiJOn+xnTv5I3ekTEZGY9c3zp/LGrnq+8tQmnrvlVFKS/tXndfcF2V3bzrbqNrZVt7J1fxs7D7TR3de/Jvtjx4/lW+dPYZTb5VT4IjJACZlEvfSUJK6cn899y8q4+/VS3iprZHV5E72BEOkpiZw60cstZ0zktMk+ckdoaqKIiMSHEWnJfO9jM7jxkbV874XtjPdmsK26ja37Wymt6yAQ6p/q73ElMXVMJlfNL2DamExm5o1kot/tcPQicogSMhkWPnXyeO5fXs6dr+xigi+DT51UwOnH+Zk3PgtXkqpAiYhIfDp7ag4XzR7Dw6v2AuB1u5g2JpMzp/iZNmYE08ZkMi4rnYQETUkUiVZKyGRYGDsyjeduORW3K4n8UelOhyMiIhI1fnjJTC6fO45JOW78malOhyMiR0kJmQwbU8doDzEREZF3S0tJ1AbOIsOYKh6IiIiIiIg4RAmZiIiIiIiIQ5SQiYiIiIiIOEQJmYiIiIiIiEOUkImIiIiIiDhECZmIiIiIiIhDlJCJiIiIiIg4RAmZiIiIiIiIQ5SQiYiIiIiIOMRYawf/pMbUA3uP8TReoGEQwol1aqfwqa3Co3YKj9qpX4G11ud0EMOF+seIU1uFR+0UPrVVeNRO/cLqI4ckIRsMxpi11tp5TscR7dRO4VNbhUftFB61kzhFr73wqa3Co3YKn9oqPGqno6MpiyIiIiIiIg5RQiYiIiIiIuKQaE7I7nU6gGFC7RQ+tVV41E7hUTuJU/TaC5/aKjxqp/CprcKjdjoKUbuGTEREREREJNZF8wiZiIiIiIhITFNCJiIiIiIi4hDHEzJjzLnGmF3GmFJjzNff43mXMeaJgedXG2PGRz5K54XRTrcaY7YbYzYbY/5ujClwIk6nHamd3nHcpcYYa4yJ25Ks4bSVMeaKgdfVNmPMY5GOMRqE8d7LN8a8bozZMPD+W+JEnBJ71D+GR/1j+NRHhkf9Y/jURw4Sa61jX0AisAcoAlKATcDUdx3zOeCegcefAJ5wMuYobqfTgfSBxzernd67nQaO8wDLgLeAeU7HHa1tBRQDG4Csge/9Tscdpe10L3DzwOOpQIXTcetr+H+pfxzUdor7/jHctho4Lq77SPWPg95W6iPD+HJ6hOxEoNRaW2at7QX+CFz0rmMuAh4eePwUcKYxxkQwxmhwxHay1r5ure0a+PYtIC/CMUaDcF5PAHcAPwK6IxlclAmnrW4E7rbWNgNYa+siHGM0CKedLJA58HgEUB3B+CR2qX8Mj/rH8KmPDI/6x/CpjxwkTidkY4Gqd3y/b+Bn73mMtTYAtAKjIhJd9Ainnd7pBuClIY0oOh2xnYwxc4Bx1toXIhlYFArnNTUJmGSMedMY85Yx5tyIRRc9wmmn7wBXG2P2AS8CX4hMaBLj1D+GR/1j+NRHhkf9Y/jURw6SJKcDkMFljLkamAcsdjqWaGOMSQDuAq51OJThIon+aRmn0X9HeZkxZoa1tsXRqKLPlcBD1tqfGmNOBn5vjJlurQ05HZiI/Iv6xw+mPvKoqH8Mn/rIMDg9QrYfGPeO7/MGfvaexxhjkugf7myMSHTRI5x2whhzFvBN4EJrbU+EYosmR2onDzAdeMMYUwGcBDwXp4uWw3lN7QOes9b2WWvLgd30d0DxJJx2ugF4EsBauwpIBbwRiU5imfrH8Kh/DJ/6yPCofwyf+shB4nRC9jZQbIwpNMak0L8o+bl3HfMc8OmBx5cB/7ADKwPjyBHbyRhzPPBb+jubeJ3L/IHtZK1ttdZ6rbXjrbXj6V9LcKG1dq0z4ToqnPfeM/Tf/cMY46V/ikZZJIOMAuG0UyVwJoAxZgr9nU19RKOUWKT+MTzqH8OnPjI86h/Dpz5ykDiakA3Meb8FeAXYATxprd1mjPk/Y8yFA4fdD4wyxpQCtwLvW6Y1VoXZTncCbuBPxpiNxph3vyFiXpjtJITdVq8AjcaY7cDrwFestXF19z3MdroNuNEYswl4HLg2Dj8UyyBT/xge9Y/hUx8ZHvWP4VMfOXiM2kRERERERMQZTk9ZFBERERERiVtKyERERERERByihExERERERMQhSshEREREREQcooRMRERERETEIUrIREREREREHKKETERERERExCH/D5WxHphPY1OBAAAAAElFTkSuQmCC\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7f4a2d4b6690>"
+       "<matplotlib.figure.Figure at 0x7fd46d2d4e10>"
       ]
      },
      "metadata": {
@@ -252,9 +424,9 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7f4a2d4b6990>"
+       "<matplotlib.figure.Figure at 0x7fd46d2d4cd0>"
       ]
      },
      "metadata": {
@@ -264,9 +436,9 @@
     },
     {
      "data": {
-      "image/png": "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\n",
+      "image/png": "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\n",
       "text/plain": [
-       "<matplotlib.figure.Figure at 0x7f4a2ce43ed0>"
+       "<matplotlib.figure.Figure at 0x7fd4744a8350>"
       ]
      },
      "metadata": {
@@ -288,7 +460,7 @@
   },
   {
    "cell_type": "code",
-   "execution_count": 30,
+   "execution_count": 23,
    "metadata": {},
    "outputs": [],
    "source": [
@@ -297,10 +469,32 @@
   },
   {
    "cell_type": "code",
-   "execution_count": null,
+   "execution_count": 35,
    "metadata": {},
-   "outputs": [],
-   "source": []
+   "outputs": [
+    {
+     "name": "stdout",
+     "output_type": "stream",
+     "text": [
+      " [[0.58002566 0.         0.         0.        ]\n",
+      " [0.         0.92934918 0.         0.        ]\n",
+      " [0.         0.         0.99013396 0.        ]\n",
+      " [0.         0.         0.         0.99865905]] [0.58002566 0.92934918 0.99013396 0.99865905]\n"
+     ]
+    }
+   ],
+   "source": [
+    "u = np.array([1,2,3,4])\n",
+    "\n",
+    "uLim, lLim = 5, 0.1\n",
+    "range = uLim - lLim\n",
+    "f = lLim + range/2 + range/2*np.tanh(u)\n",
+    "v = np.tanh(u)\n",
+    "d_v = np.tanh(u)**2\n",
+    "J_f_u = np.zeros([4,4])\n",
+    "np.fill_diagonal(J_f_u, d_v)\n",
+    "print J_f_u, d_v"
+   ]
   },
   {
    "cell_type": "code",