{ "cells": [ { "cell_type": "markdown", "metadata": { "colab_type": "text", "id": "view-in-github", "tags": [ "no-tex" ] }, "source": [ "\"Open" ] }, { "cell_type": "code", "execution_count": 1, "metadata": { "id": "JoW4C_OkOMhe", "tags": [ "remove-cell" ] }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "Note: you may need to restart the kernel to use updated packages.\n" ] } ], "source": [ "%pip install -q -U gtbook\n" ] }, { "cell_type": "code", "execution_count": 2, "metadata": { "id": "10-snNDwOSuC", "tags": [ "remove-cell" ] }, "outputs": [], "source": [ "import math\n", "import numpy as np\n", "import matplotlib.pyplot as plt\n", "\n", "import plotly.graph_objects as go\n", "try:\n", " import google.colab\n", "except:\n", " import plotly.io as pio\n", " pio.renderers.default = \"png\"\n", "\n", "import gtsam\n", "import gtsam.utils.plot as gtsam_plot\n", "\n", "from gtbook.display import show\n" ] }, { "attachments": {}, "cell_type": "markdown", "metadata": { "id": "nAvx4-UCNzt2" }, "source": [ "# SLAM\n", "\n", "> SLAM is *Simultaneous Localization and Mapping*, a key capability for mobile robots.\n", "\n", "\"Splash" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "When an autonomous vehicle explores a new environment, it should be able to simultaneously build a map of this environment, and localize itself relative to that map. That capability is known as *Simultaneous Localization and Mapping* or **SLAM**. SLAM is a bit like a chicken and egg problem: if we knew the map, we could use the localization techniques we studied in Section 4.4, e.g., Monte Carlo Localization. Conversely, if we were already localized, it would not be too hard to create a map: if we have a LIDAR sensor, we could simply transform the points from the LIDAR frame into the world frame. But now we have to do *both* at the same time! Is that even possible? " ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "In this section we show that this *is* possible, and we expand upon two different SLAM techniques: *PoseSLAM* and *SLAM with landmarks*. In the former we concentrate on estimating the robot's motion from a rich sensor such as LIDAR, and building the map is generated as a side effect. In the latter, we truly optimize for both the location of the vehicle and the location of a observed landmarks, which leads to a sparse map of the environment. Before investigating these two SLAM algorithms, we review the math of vehicle poses in 2D, and discuss ICP, a seminal algorithm for aligning two point clouds, and which we use as a building block in PoseSLAM." ] }, { "cell_type": "markdown", "metadata": { "id": "gsB-xgTtlV-6" }, "source": [ "## Poses in 2D and 3D\n", "\n", "> SE(2) generalizes to SE(3).\n", "\n", "In both SLAM variants we need to optimize over the pose of a vehicle.\n", "To keep things simple, we will concentrate on poses in the plane for now. \n", "Recall from Section 6.1 that a 2D pose\n", "$T\\doteq(x,y,\\theta)$ is an element of the Special Euclidean group $SE(2)$,\n", "and\n", "can be represented by a $3\\times3$ matrix of the form\n", "\n", "$$\n", "T=\\left[\\begin{array}{cc|c}\n", "\\cos\\theta & -\\sin\\theta & x\\\\\n", "\\sin\\theta & \\cos\\theta & y\\\\\n", "\\hline 0 & 0 & 1\n", "\\end{array}\\right]=\\left[\\begin{array}{cc}\n", "R & t\\\\\n", "0 & 1\n", "\\end{array}\\right]\n", "$$\n", "\n", "with the $2\\times1$ vector $t$\n", "representing the position of the vehicle, and $R$ the $2\\times2$\n", "rotation matrix representing the vehicle’s orientation in the plane.\n", "\n", "Below it is important to understand what coordinate frames are involved, and hence we insist on always annotating the transformation matrices with indices indicating the reference frame as superscript and the frame under consideration using subscript. This convention also\n", "provides a reminder to how points in one frame are transformed into the other. \n", "As an example, the following illustrates how points in the frame $b$ are transformed into the reference frame $a$ by referring to the pose $T^a_b$ of frame $b$ in $a$:\n", "\n", "$$\n", "P^a = \\left[\\begin{array}{cc}\n", "R^a_b & t^a_b\\\\\n", "0 & 1\n", "\\end{array}\\right] P^b = T^a_b P^b \n", "$$\n", "\n", "A good rule to keep in mind, illustrated above, is that the superscript $b$ of the point $P^b$ on the right-hand side is \"canceled\" by the subscript $b$ in the pose $T^a_b$, and so the left-hand side $P^a$ only retains the superscript $a$, indicating it now lives in the reference frame $a$. This rule is quite useful when implementing these types of transformations in code, as well. Also, keep in mind that we are talking about the *same* point $P$ in both cases: it is simply the *coordinates* that change by expressing them in a different frame.\n", "\n", "Note that this representation generalizes easily to three dimensions,\n", "but of course $t^a_b$ will be a three-vector, and $R^a_b$ will be a $3\\times3$\n", "rotation matrix representing the 3DOF orientation of the vehicle. The\n", "latter can be decomposed into roll, pitch, and yaw, if so desired, \n", "but we will not need that until the next chapter." ] }, { "cell_type": "markdown", "metadata": { "id": "QpwKGbRylV-7" }, "source": [ "## The Iterative Closest Points Algorithm\n", "\n", "> ICP is a seminal method to align two point clouds.\n", "\n", "**Iterative closest points** or **ICP** is a method to align two point clouds, e.g., two successive LIDAR scans, and it is a crucial component in the PoseSLAM algorithm we will discuss next. Leaning into the notation re-introduced above, we use superscripts $a$ and $b$ to distinguish the two point clouds, and the points therein. Under the assumption that we have a good initial estimate $\\hat{T^a_b}$ for the relative pose $T^a_b$ between the two point clouds, ICP iterates between two steps:\n", "\n", "1. Find closest point correspondences between the two clouds.\n", "2. Use these point correspondences to re-estimate the relative pose $\\hat{T^a_b}$ between the two point clouds.\n", "\n", "These two steps are iterated until convergence, hence the name *iterated* closest points. Below we explain both steps in more detail." ] }, { "cell_type": "markdown", "metadata": { "id": "iVRcg3fslV-7" }, "source": [ "### Finding Closest Points\n", "\n", "The first step is the easiest: for each point $P^a_j$ in the first point cloud, we define $P^b_j$ to be its closest point in the second point cloud. Stated formally, for each point $P^a_j$, we solve the following minimization problem:\n", "\n", "$$\n", "P^b_j = \\arg \\min_{P^b_k} \\| P^b_k - P^a_j\\|^2\n", "$$\n", "\n", "We prefer using indices $j$ for points as we use $i$ for poses below, making it easier to associate notation with geometric concepts. Two things about the above minimization are worth noting: \n", "(a) it can be solved using a linear search over all points $P^b$, \n", "and (b) rather than computing the distance we can save the computation of a square root by minimizing the square, which is just as good as they are monotonically related. \n", "\n", "The linear search problem above is known as the **nearest neighbor** problem, and solving this problem for all points is the **all nearest neighbors** problem.\n", "Iterating over all points in the second cloud can be quite slow, and indeed finding all nearest neighbors that way has quadratic complexity. However, very fast *approximate* nearest neighbor algorithms are available. Many of these use specialized data structures, such as \"KD-trees\" or \"Oct-trees\" (in 3D). While the details are beyond the scope of this book,\n", "intuitively these data structures recursively divide up the point clouds into sub-clouds, such that sub-clouds unlikely to contain the nearest neighbor can be quickly excluded. We build this data structure once for the second cloud, and then use it for all nearest neighbor searches, leading to complexity which is approximately $O(N \\log N$),\n", "for point clouds of size $N$." ] }, { "cell_type": "markdown", "metadata": { "id": "tTVEYMjdlV-8" }, "source": [ "### Estimating the Pairwise Transform\n", "\n", "The second step is the more interesting one: given a set of closest point pairs $\\{(P^a_j, P^b_j)\\}$, how can we estimate the relative pose $\\widehat{T^a_b}$ between the two point clouds? This is known as the **pose alignment** problem.\n", "\n", "Let us first assume that the two point clouds only differ by a rotation $R^a_b$. When this is the case, and assuming we have corresponding points $P^a$ and $P^b$, then each point $P^a$ in the first cloud can be expressed as a function of a point $P^b$ in the second cloud:\n", "\n", "$$\n", "P^a = R^a_b P^b\n", "$$\n", "\n", "One might be tempted to think that therefore \n", "\n", "$$\n", "R^a_b = P^a (P^b)^{-1}\n", "$$\n", "\n", "but, of course, there since $P^b$ is a vector, it does not have an inverse. So this would not work.\n", "Interestingly, though, if we form the matrix\n", "\n", "$$\n", "H = \\sum_j P^a_j (P^b_j)^T\n", "$$\n", "\n", "by summing over at least 3 point pairs $(P^a_j, P^b_j)$, it turns out that the rotation matrix $\\widehat{R^a_b}$ closest to $H$ in the least squares sense *is* the best possible estimate for the unknown rotation $R^a_b$. In addition, using the *singular value decomposition* from linear algebra, it is *very* easy to compute.\n", "The singular value decomposition of the matrix $H$ is defined by $H=U\\Lambda V^T$, in which $\\Lambda$ is a diagonal\n", "matrix of singular values, and both $U$ and $V$ are orthogonal matrices.\n", "The optimal estimate for the rotation matrix is given by\n", "\n", "$$\n", "\\widehat{R^a_b} = U V^T\n", "$$\n", "\n", "Interesting aside: this problem is known as the *orthogonal Procrustes problem* and its solution via SVD has been known since 1966, from a 1966 paper by Peter Schönemann {cite:p}`Schoenemann66_procrustes`. Procrustes was a mythological greek villain who either stretched or cut his victims to size to fit their bed, analogous to how we make the rotation matrix above fit the data." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The above solves the problem when there is only rotation, but we must also consider relative translation between the two point clouds.\n", "Fortunately, it turns out that the best possible translation estimate will always align the *centroids* of the two point clouds. Hence, when there is translation present, we simply compute the matrix $H$ from the *centered* points, \n", "\n", "$$\n", "H = \\sum_j (P^a_j-C^a) (P^b_j-C^b)^T\n", "$$\n", "\n", "where the point cloud centroids $C^a$ and $C^b$ are computed as \n", "\n", "$$\n", "C^a = \\frac{1}{N} \\sum_j P^a_j\\text{ and }C^b = \\frac{1}{N} \\sum_j P^b_j.\n", "$$\n", "\n", "Given the estimated rotation $\\widehat{R^a_b}$, the translation estimate $\\widehat{t^a_b}$ can then be estimated from \n", "\n", "$$\n", "C^a = \\widehat{R^a_b} C^b + \\widehat{t^a_b},\n", "$$\n", "\n", "and the final relative pose estimate is given by $\\widehat{T^a_b} =(\\widehat{R^a_b}, \\widehat{t^a_b})$. By the way, all of the above math is identical for both the 2D and 3D case." ] }, { "cell_type": "markdown", "metadata": { "id": "Vc_L-6rElV-8" }, "source": [ "## PoseSLAM\n", "\n", "> PoseSLAM is SLAM with pose priors and relative pose constraints only. We can derive those from Iterative Closest Points (ICP).\n", "\n", "As we discussed at the beginning of this section, in SLAM the goal is to localize a robot using the information coming\n", "from the robot’s sensors, while simultaneously building the map.\n", "We have already covered the localization problem in chapter 4, \n", "using Markov localization, Monte Carlo localization, and the Kalman filter.\n", "The additional wrinkle in SLAM is that we do\n", "*not* know the map a priori, and hence we have to infer the unknown map\n", "while simultaneously estimating the robot's location with respect to the evolving map.\n", "\n", "**PoseSLAM** is a variant of SLAM that uses pose constraints (using an algorithm such as ICP) as a\n", "basic building block when optimizing over the unknown vehicle\n", "poses. \n", "In PoseSLAM we do *not* explicitly optimize over a map.\n", "Instead the map is reconstructed after the fact. \n", "This can only work if (a) the sensor is sufficiently rich to make the pose constraints very accurate, \n", "and (b) we can build a sufficiently good map using this sensor data. LIDAR satisfies both of these assumptions, \n", "making LIDAR-based PoseSLAM a very popular technique.\n", "\n", "In a nutshell, the PoseSLAM problem can be stated as:\n", "\n", "> Given a set of noisy relative measurements or **pose constraints**\n", "> $\\tilde{T}_{ij}$, recover the optimal set of poses $T_{i}^{*}$ that\n", "> maximizes the posteriori probability, i.e., recover the MAP solution.\n", "\n", "In the case of mapping for autonomous driving, these relative\n", "measurements can be derived by performing ICP between overlapping\n", "LIDAR scans. If available, we can additionally use GPS and/or IMU measurements \n", "to decide which scans overlap, so that we do not have to do this $O(n^{2})$ times. \n", "Depending on the situation, we can optimize for 3D or 2D poses, in the way we will\n", "discus below. Afterwards, we can reconstruct a detailed map by\n", "transforming the local LIDAR scans into the world frame, using the\n", "optimized poses $T_{i}^{*}$." ] }, { "cell_type": "markdown", "metadata": { "id": "7iG14QP4lV-9" }, "source": [ "## The PoseSLAM Factor Graph\n", "\n", "> Factor graphs expose the sparse set of constraints tying absolute poses together.\n", "\n", "In our factor-graph-based view of the world, a pose constraint is\n", "represented as a factor. As before, the factor graph represent the\n", "posterior distribution over the unknown pose variables\n", "$\\mathcal{T}=\\{X_{1}\\dots X_{5}\\}$ given the known measurements:\n", "\n", "$$\n", "\\phi(\\mathcal{T})=\\prod_{i}\\phi_{i}(\\mathcal{T}_{i}),\n", "$$\n", "\n", "where $\\mathcal{T}_{i}$ is the set of poses involved with factor $\\phi_i$. \n", "In this way, the factor graph encodes which factors are connected to which variables,\n", "exposing the sparsity pattern of the corresponding estimation problem.\n", "\n", "
\n", "
PoseSLAM factor graph example.
\n", "
\n", "\n", "An example is shown in Figure\n", "1.\n", "The example represents a vehicle driving around, and taking LIDAR scans\n", "at 5 different world poses, represented by $T_{1}$ to $T_{5}$.\n", "The factors $f_{1}$ to $f_{4}$ are binary factors representing the pose\n", "constraints obtained by matching successive LIDAR scans using ICP. " ] }, { "cell_type": "markdown", "metadata": { "id": "ZJEBb4d6lV-9" }, "source": [ "The factor\n", "$f_{5}(T_{5},T_{2})$ is a so-called **loop closure** constraint:\n", "rather than derived from two successive scans, this one is derived from\n", "matching the scan taken at $T_{5}$ with the one at $T_{2}$.\n", "Detecting such loops can be done through a variety of means. The final,\n", "unary factor $f_{0}(T_{1})$ is there to “anchor” the solution to the\n", "origin: if it is not there, the solution will be undetermined. Another\n", "way to anchor the solution is to add unary factors at every time-step,\n", "derived from GPS." ] }, { "cell_type": "markdown", "metadata": { "id": "b0Jg1ajElV--" }, "source": [ "## MAP Inference via Least-Squares\n", "\n", "> Linear problems with zero-mean Gaussian noise lead to least-squares problems.\n", "\n", "When measurements are linear functions of continuous variables,\n", "finding the maximum a posteriori (MAP) solution can be done via\n", "least-squares optimization. \n", "Earlier in this book we have discussed MAP inference for discrete\n", "variables, and we have discussed probability distributions for\n", "continuous variables, but we have never put the two together." ] }, { "cell_type": "markdown", "metadata": { "id": "bxUUPn_rlV--" }, "source": [ "In the case of linear measurements corrupted by zero-mean Gaussian noise, we can\n", "recover the MAP solution by minimizing a sum of squared differences. \n", "Recall that a univariate Gaussian density **with mean** $\\mu$ and **variance** $\\sigma^{2}$ is\n", "given by\n", "\n", "$$\n", "\\mathcal{N} (x; \\mu, \\sigma^2) =\\frac{1}{\\sqrt{2\\pi\\sigma^{2}}}\\exp\\left\\{ -\\frac{1}{2}\\left(\\frac{x-\\mu}{\\sigma}\\right)^{2}\\right\\} .\n", "$$" ] }, { "cell_type": "markdown", "metadata": { "id": "xqwl7FV2lV--" }, "source": [ "An example can help explain this more clearly.\n", "In particular, if we focus our attention in PoseSLAM on *just the x coordinates*, then we\n", "predict relative measurements $\\tilde{x}_{ij}$ by\n", "\n", "$$\n", "\\tilde{x}_{ij}\\approx h(x_{i,}x_{j})=x_{j}-x_{i}\n", "$$\n", "\n", "and, taking $\\sigma=1$ for now, each factor in\n", "Figure\n", "1\n", "could be written as\n", "\n", "$$\n", "\\phi(x_{i},x_{j})=\\frac{1}{\\sqrt{2\\pi}}\\exp\\left\\{ -\\frac{1}{2}\\left(x_{j}-x_{i}-\\tilde{x}_{ij}\\right)^{2}\\right\\} ,\n", "$$\n", "\n", "By taking the negative log,\n", "maximizing the posterior corresponds to minimizing the following sum of\n", "squares, where them sum ranges over all $(i,j)$ pairs for which we have a\n", "pairwise measurement:\n", "\n", "$$\n", "\\mathcal{X}^{*}=\\arg\\min_{\\mathcal{X}}\\sum_{k}\\frac{1}{2}\\left(h(x_{i},x_{j})-\\tilde{x}_{ij}\\right)^{2}=\\arg\\min_{\\mathcal{X}}\\sum_{k}\\frac{1}{2}\\left(x_{j}-x_{i}-\\tilde{x}_{ij}\\right)^{2}.\n", "$$\n", "\n", "Linear least squares problems like these are easily solved by numerical\n", "computing packages like MATLAB or numpy." ] }, { "cell_type": "markdown", "metadata": { "id": "aUlUTv34lV-_" }, "source": [ "## PoseSLAM is Nonlinear !\n", "\n", "> Nonlinear problems need nonlinear solutions.\n", "\n", "Unfortunately, in the PoseSLAM case we cannot use linear least squares,\n", "because poses are not simply vectors, and the measurements are not\n", "simply linear functions of the poses. Indeed, in PoseSLAM both the\n", "prediction $h(T_{i},T_{j})$ and the measurement $\\tilde{T}_{ij}$\n", "are relative poses. The measurement prediction function $h(\\cdot)$ is given\n", "by \n", "\n", "$$\n", "h(T_{i},T_{j})=T_{i}^{-1}T_{j}\n", "$$\n", "\n", "and the\n", "measurement error to be minimized is\n", "\n", "$$\n", "\\frac{1}{2}\\left\\Vert \\log\\left(\\tilde{T}_{ij}^{-1}T_{i}^{-1}T_{j}\\right)\\right\\Vert ^{2}\n", "$$\n", "\n", "where $\\log:SE(2)\\rightarrow\\mathbb{R}^3$ is a variation of the logarithm function\n", "that maps a pose in $SE(2)$ to a\n", "three-dimensional local coordinate vector $\\xi$;\n", "we will describe this in more detail below." ] }, { "cell_type": "markdown", "metadata": { "id": "-iVbbFVFlV-_" }, "source": [ "There are two ways to deal with this nonlinear problem. The first is to\n", "realize that the only nonlinearities stem from the $\\sin$ and $\\cos$\n", "that are associated with the unknown orientations\n", "$\\theta_{i}$. \n", "Recognizing this, we could try to solve for the\n", "orientations first, and then solve for the translations using linear\n", "least squares, exactly as above. This approach is known as **rotation\n", "averaging** followed by linear translation recovery. Unfortunately this approach is\n", "suboptimal, as it does not consider the orientation and translation\n", "simultaneously. However, it can serve to provide a (very) good initial\n", "estimate for nonlinear optimization, discussed below.\n", "\n", "Indeed, we will prefer to take a second route, which is to use\n", "**nonlinear optimization**, which we discuss below." ] }, { "cell_type": "markdown", "metadata": { "id": "FUtgFjvhlV_A" }, "source": [ "## Nonlinear Optimization for PoseSLAM\n", "\n", "> Linearize, solve, repeat...\n", "\n", "At first glance, minimizing the measurement error might seem to be a straightforward\n", "nonlinear optimization problem: simply use your favorite nonlinear optimizer, e.g., with\n", "an initial estimate provided using the method in the previous section.\n", "This approach might well succeed in finding matrices $T_i$ that minimize the error,\n", "but, unfortunately, there is no guarantee that $T_i \\in SE(2)$, since\n", "this approach does not ensure that the upper right submatrix is a valid rotation matrix.\n", "\n", "Instead, we will locally linearize the problem and solve\n", "the corresponding linear problem using least-squares, and iterate this\n", "until convergence. We do this by, at each iteration, parameterizing a\n", "pose $T$ by \n", "\n", "$$\n", "T\\approx\\bar{T}\\Delta(\\xi)\n", "$$\n", "\n", "where $\\xi$ are local coordinates\n", "$\\xi\\doteq(\\delta x,\\delta y,\\delta\\theta)$ and the incremental pose\n", "$\\Delta(\\xi)\\in SE(2)$ is defined as\n", "\n", "$$\n", "\\Delta(\\xi)=\\left[\\begin{array}{cc|c}\n", "1 & -\\delta\\theta & \\delta x\\\\\n", "\\delta\\theta & 1 & \\delta y\\\\\n", "\\hline 0 & 0 & 1\n", "\\end{array}\\right]\n", "$$\n", "\n", "which you can recognize as a small angle\n", "approximation of the $SE(2)$ matrix.\n", "In 3D the local coordinates $\\xi$ are 6-dimensional, and the small angle\n", "approximation is defined as \n", "\n", "$$\n", "\\Delta(\\xi)=\\left[\\begin{array}{ccc|c}\n", "1 & -\\delta\\theta_{z} & \\delta\\theta_{y} & \\delta x\\\\\n", "\\delta\\theta_{z} & 1 & -\\delta\\theta_{x} & \\delta y\\\\\n", "-\\delta\\theta_{y} & \\delta\\theta_{x} & 1 & \\delta z\\\\\n", "\\hline 0 & 0 & 0 & 1\n", "\\end{array}\\right]\n", "$$\n", "\n", "With this new notation, we can approximate the\n", "nonlinear error by a linear approximation:\n", "\n", "$$\n", "\\frac{1}{2}\\left\\Vert \\log\\left(\\tilde{T}_{ij}^{-1}T_{i}^{-1}T_{j}\\right)\\right\\Vert ^{2}\\approx\\frac{1}{2}\\left\\Vert A_{i}\\xi_{i}+A_{j}\\xi_{j}-b\\right\\Vert ^{2}.\n", "$$\n", "\n", "For $SE(2)$ the matrices $A_{i}$ and $A_{j}$ are the $3\\times3$ **or\n", "Jacobian matrices** and $b$ is a $3\\times1$ bias term. The above\n", "provides a linear approximation of the term within the norm as a\n", "function of the incremental local coordinates $\\xi_{i}$ and $\\xi_{j}$.\n", "Deriving the detailed expressions for these Jacobians is beyond the\n", "scope of this document, but suffice to say that they exist and not too\n", "expensive to compute. In three dimensions, the Jacobian matrices are\n", "$6\\times6$ and $16\\times6$, respectively." ] }, { "cell_type": "markdown", "metadata": { "id": "higUZ3jvlV_A" }, "source": [ "The final optimization will—in each iteration—minimize over the local\n", "coordinates of all poses by summing over all pose constraints. If we\n", "index those constraints by $k$, we have the following least squares\n", "problem:\n", "\n", "$$\n", "\\Xi^{*}=\\arg\\min_{\\Xi}\\sum_{k}\\frac{1}{2}\\Vert A_{ki}\\xi_{i}+A_{kj}\\xi_{j}-b_{k}\\Vert ^{2}\n", "$$\n", "\n", "where $\\Xi\\doteq \\{ \\xi_{i}\\}$, the set\n", "of all incremental pose coordinates.\n", "\n", "After solving for the incremental updates $\\Xi$, we update all poses\n", "using the update equation above and check for convergence. \n", "If the error does not decrease significantly\n", "we terminate, otherwise we linearize and solve again, until the error\n", "converges. While this is not guaranteed to converge to a global minimum,\n", "in practice it does so if there are enough relative measurements and a\n", "good initial estimate is available. For example, GPS can provide us with\n", "a good initial estimate. However, especially in urban environments GPS\n", "can be quite noisy, and it could happen that the map quality suffers by\n", "converging to a bad local minimum. Hence, a good quality control process\n", "is absolutely necessary in production environments.\n", "\n", "In summary, the algorithm for nonlinear optimization is\n", "\n", "- Start with an initial estimate $\\mathcal{T}^{0}$\n", "\n", "- Iterate:\n", "\n", " 1. Linearize the factors\n", "$\\frac{1}{2}\\Vert \\log(\\tilde{T}_{ij}^{-1}T_{i}^{-1}T_{j})\\Vert ^{2}\\approx\\frac{1}{2}\\Vert A_{i}\\xi_{i}+A_{j}\\xi_{j}-b\\Vert ^{2}$\n", "\n", " 2. Solve the least squares problem\n", " $\\Xi^{*}=\\arg\\min_{\\Xi}\\sum_{k}\\frac{1}{2}\\Vert A_{ki}\\xi_{i}+A_{kj}\\xi_{j}-b_{k}\\Vert ^{2}$\n", "\n", " 3. Update $X_{i}^{t+1}\\leftarrow X_{j}^{t}\\Delta(\\xi_{i})$\n", "\n", "- Until the nonlinear error\n", "$J(\\mathcal{T})\\doteq\\sum_{k}\\frac{1}{2}\\Vert \\log(\\tilde{T}_{ij}^{-1}T_{i}^{-1}T_{j})\\Vert ^{2}$\n", " converges." ] }, { "cell_type": "markdown", "metadata": { "id": "X6OG5ulXzTRe" }, "source": [ "## Optimization with GTSAM\n", "\n", "> GTSAM rocks PoseSLAM.\n", "\n", "For SLAM we typically use specialized packages such as GTSAM that \n", "exploit the sparsity of the factor graphs to dramatically\n", "speed up computation. \n", "Typically\n", "measurements only provide information on the relationship between a\n", "handful of variables, and hence the resulting factor graph will be\n", "sparsely connected. This is exploited by the algorithms implemented in\n", "GTSAM to reduce computational complexity. Even when graphs are too dense\n", "to be handled efficiently by direct methods, GTSAM provides iterative\n", "methods that are quite efficient.\n", "\n", "The following code, included in GTSAM as an example, creates the\n", "factor graph from Figure\n", "1\n", "in code:" ] }, { "cell_type": "code", "execution_count": 3, "metadata": { "id": "A6gJFN6lzM3k" }, "outputs": [], "source": [ "graph = gtsam.NonlinearFactorGraph()\n", "prior_model = gtsam.noiseModel.Diagonal.Sigmas((0.3, 0.3, 0.1))\n", "graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), prior_model))\n", "\n", "# Create odometry (Between) factors between consecutive poses\n", "odometry_model = gtsam.noiseModel.Diagonal.Sigmas((0.2, 0.2, 0.1))\n", "Between = gtsam.BetweenFactorPose2\n", "graph.add(Between(1, 2, gtsam.Pose2(2, 0, 0), odometry_model))\n", "graph.add(Between(2, 3, gtsam.Pose2(2, 0, np.pi/2), odometry_model))\n", "graph.add(Between(3, 4, gtsam.Pose2(2, 0, np.pi/2), odometry_model))\n", "graph.add(Between(4, 5, gtsam.Pose2(2, 0, np.pi/2), odometry_model))\n", "\n", "# Add the loop closure constraint\n", "graph.add(Between(5, 2, gtsam.Pose2(2, 0, np.pi/2), odometry_model))\n" ] }, { "cell_type": "markdown", "metadata": { "id": "z_Tt0j9DlV_B" }, "source": [ "The first block of code creates a nonlinear factor graph and adds the unary factor\n", "$f_{0}(T_{1})$. \n", "As the vehicle travels through the world, it adds\n", "binary factors $f_{t}(T_{t},T_{t+1})$ corresponding to odometry measurements.\n", "Note that the final line of code models a different event: a **loop closure**.\n", "For example,\n", "the vehicle might recognize the same location using vision or a laser\n", "range finder, and calculate the geometric pose constraint to when it\n", "first visited this location. This is illustrated for poses $T_{5}$\n", "and $T_{2}$, and generates the (red) loop closing factor\n", "$f_{5}(T_{5},T_{2})$.\n" ] }, { "cell_type": "markdown", "metadata": { "id": "-tN-kF1BwpXS" }, "source": [ "Before we can optimize, we need to create an initial estimate. In GTSAM, this is done via the `gtsam.Values` type:" ] }, { "cell_type": "code", "execution_count": 4, "metadata": { "colab": { "base_uri": "https://localhost:8080/" }, "id": "uxyN7AKH0T-7", "outputId": "7bd94eee-b3e5-4304-9efe-acd1fdd4e315" }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "Values with 5 values:\n", "Value 1: (gtsam::Pose2)\n", "(0.5, 0, 0.2)\n", "\n", "Value 2: (gtsam::Pose2)\n", "(2.3, 0.1, -0.2)\n", "\n", "Value 3: (gtsam::Pose2)\n", "(4.1, 0.1, 1.5708)\n", "\n", "Value 4: (gtsam::Pose2)\n", "(4, 2, 3.14159)\n", "\n", "Value 5: (gtsam::Pose2)\n", "(2.1, 2.1, -1.5708)\n", "\n", "\n" ] } ], "source": [ "# Create the initial estimate\n", "initial_estimate = gtsam.Values()\n", "initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))\n", "initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))\n", "initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, np.pi/2))\n", "initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, np.pi))\n", "initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -np.pi/2))\n", "print(initial_estimate)\n" ] }, { "cell_type": "markdown", "metadata": { "id": "8WNeRXHurTzX" }, "source": [ "We can use this initial estimate to show the factor graph below:" ] }, { "cell_type": "code", "execution_count": 5, "metadata": { "colab": { "base_uri": "https://localhost:8080/", "height": 281 }, "id": "qkkjavZTl6nT", "outputId": "7ddf8253-e311-480c-c473-76c06c969a62" }, "outputs": [ { "data": { "image/svg+xml": [ "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "var1\n", "\n", "1\n", "\n", "\n", "\n", "var2\n", "\n", "2\n", "\n", "\n", "\n", "var1--var2\n", "\n", "\n", "\n", "\n", "factor0\n", "\n", "\n", "\n", "\n", "var1--factor0\n", "\n", "\n", "\n", "\n", "var3\n", "\n", "3\n", "\n", "\n", "\n", "var2--var3\n", "\n", "\n", "\n", "\n", "var4\n", "\n", "4\n", "\n", "\n", "\n", "var3--var4\n", "\n", "\n", "\n", "\n", "var5\n", "\n", "5\n", "\n", "\n", "\n", "var4--var5\n", "\n", "\n", "\n", "\n", "var5--var2\n", "\n", "\n", "\n", "\n" ], "text/plain": [ "" ] }, "execution_count": 5, "metadata": {}, "output_type": "execute_result" } ], "source": [ "#| caption: Factor graph with odometry and loop closure constraints.\n", "#| label: fig:factor_graph_with_loop_closure\n", "show(graph, initial_estimate, binary_edges=True)\n" ] }, { "cell_type": "markdown", "metadata": { "id": "MNip0x6GniL_" }, "source": [ "Optimization is done using non-linear minimization, as explained above. In GTSAM, this is done via a `NonlinearOptimizer` class. The specific optimizer we use below is `GaussNewtonOptimizer`, which exactly implements the pseudo-code given above, but exploiting sparsity in the factor graph to do this very efficiently. The optimizer only needs a graph and an initial estimate, both of which we already created, and hence the code below is quite simple:" ] }, { "cell_type": "code", "execution_count": 6, "metadata": { "colab": { "base_uri": "https://localhost:8080/" }, "id": "KaXSwH2fm1Zc", "outputId": "17874473-7408-482a-babb-0720c25e1888" }, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ "Final Result:\n", "Values with 5 values:\n", "Value 1: (gtsam::Pose2)\n", "(-1.56939e-20, -3.01399e-20, -1.15741e-20)\n", "\n", "Value 2: (gtsam::Pose2)\n", "(2, -6.66836e-20, -1.64505e-20)\n", "\n", "Value 3: (gtsam::Pose2)\n", "(4, -3.42174e-11, 1.5708)\n", "\n", "Value 4: (gtsam::Pose2)\n", "(4, 2, 3.14159)\n", "\n", "Value 5: (gtsam::Pose2)\n", "(2, 2, -1.5708)\n", "\n", "\n" ] } ], "source": [ "# Optimize the initial values using a Gauss-Newton nonlinear optimizer\n", "optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate)\n", "result = optimizer.optimize()\n", "print(\"Final Result:\\n{}\".format(result))\n" ] }, { "cell_type": "markdown", "metadata": { "id": "eQ2j-vBvoYEo" }, "source": [ "We can also inspect the result graphically. Looking at the result as printed above only gets us so far, and more importantly, it only shows us the maximum a posteriori (MAP) solution, but not the uncertainty around it. Luckily, GTSAM can also compute the **posterior marginals**, which show the uncertainty on each recovered pose as a Gaussian density $P(T_i|Z)$, taking into account all the measurements $Z$.\n", "\n", "In code, we do this via the `gtsam.Marginals` object, and we can plot marginals with a special function `plot_pose2`:" ] }, { "cell_type": "code", "execution_count": 7, "metadata": { "colab": { "base_uri": "https://localhost:8080/", "height": 279 }, "id": "TUJSyFCFmOLf", "outputId": "3ea084d8-829a-4104-a4a7-38bbc7c9ce09" }, "outputs": [ { "data": { "image/png": "iVBORw0KGgoAAAANSUhEUgAAAjUAAAGwCAYAAABRgJRuAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMywgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/NK7nSAAAACXBIWXMAAA9hAAAPYQGoP6dpAACEdUlEQVR4nO3dd1hT1/8H8HcCBGSjKIIsUcSFioBbXCgiiq17a9XWWWe1WvfWuvfo1z2KE3HgABUcOFgKDqqIAiqiKLJncn5/9AetdTGSnIzP63nyVDG5501IyTv3nnuPgDHGQAghhBCi5IS8AxBCCCGESAOVGkIIIYSoBCo1hBBCCFEJVGoIIYQQohKo1BBCCCFEJVCpIYQQQohKoFJDCCGEEJWgyTuAPEkkErx69QoGBgYQCAS84xBCCCGkBBhjyMjIgIWFBYTCL++PUatS8+rVK1hZWfGOQQghhJAySExMhKWl5Rf/Xa1KjYGBAYC/nxRDQ0POaQghhBBSEunp6bCysip+H/8StSo1RYecDA0NqdQQQgghSuZbU0doojAhhBBCVAKVGkIIIYSoBCo1hBBCCFEJVGoIIYQQohKo1BBCCCFEJVCpIYQQQohKoFJDCCGEEJVApYYQQgghKoFKDSGEEEJUApUaQgghhKgEKjWEEEIIUQlUagghhBCiEqjUEEIIIUQlUKkhhBBCiEqgUkMIIYQQlaDJOwAhhBA+GGN48+YNcnNzi//+7/8CgLa2NszMzKChocElIyGlQaWGEEJUGGMMjx8/xpMnTxAXF4e4uDg8ffoUcXFxePbsGXJycr65DU1NTVhaWsLGxuaTm4ODA6ysrOTwnRDybVRqCCFExbx//x4BAQE4f/48zp8/j9evXwP4e69L9erVUaNGDXTo0AF2dnaoXr069PT0Pnq8QCAo/nNOTg4SEhIQHx+P+Ph4PH78GAEBAUhKSiq+j5WVFVq1aoXWrVujVatWqFevHoRCmt1A5I9KDSGEqICIiAicOXMG58+fx+3btyGRSODo6IjBgwejY8eOqFu3LszNzaVWNvLy8vDixQtER0fj+vXruH79Oo4ePYrCwkIYGxujZcuWaNWqFdq2bYsmTZpQySFyIWD/Pniq4tLT02FkZIS0tDQYGhryjkMIIeUiFotx6tQprFq1CiEhITAyMkLHjh3RuXNneHh4wNLSUq55srKycOfOneKSExISgszMTFhbW6Nv377o168fnJycPtoTREhJlPT9m0oNIYQomezsbOzduxdr1qxBbGws3NzcMHXqVHh6ekJLS4t3vGKFhYUICQmBj48Pjh49ipSUFNSqVQv9+vVDv379UKdOHd4RiZKgUvMZVGoIIcrsw4cPWLduHTZv3oz379+jZ8+emDp1Kpo2bco72jcVFhbi0qVL8PHxwYkTJ5Ceno4GDRqgf//+GDZsGKpWrco7IlFgVGo+g0oNIUQZMcbg4+ODyZMnIyMjAyNGjMCkSZNgZ2fHO1qZ5Obm4vz58/Dx8cGpU6cgFovRr18/TJw4EY0bN+Ydjyigkr5/08wtQghRYM+fP0fnzp0xYMAAtG7dGo8fP8aGDRuUttAAgI6ODr777jv4+Pjg5cuXWLJkCYKCguDs7Aw3NzecOnUKEomEd0yihKjUEEKIAmKMYe/evWjQoAFiYmJw5swZHD16FNWqVeMdTapMTEzwyy+/4OnTpzh27BjEYjG6d++OBg0aYP/+/SgoKOAdkSgRKjWEEKJg0tLS0KtXLwwbNgw9evRAVFQUvLy8eMeSKU1NTfTs2RM3btzAtWvXYGtriyFDhqBWrVrYsWMHCgsLeUckSoBKDSGEKJDXr1+jbdu2uHTpEo4dO4Y9e/bAyMiIdyy5atWqFc6cOYN79+6hWbNmGDVqFBo1aoQLFy7wjkYUHJUaQghREE+fPkXLli2RnJyMa9euoWfPnrwjcdWgQQP8+eefCA0NRaVKldC5c2d07twZ9+/f5x2NKCgqNYQQogAiIyPRsmVLaGpqIiQkBI6OjrwjKQwXFxcEBQXhxIkTiI2NRcOGDTFq1CgkJyfzjkYUDJUaQgjhLCgoCG3atIGVlRWuX78OW1tb3pEUjkAgwPfff4+HDx9i9erVOHLkCGrWrIlly5aVaFFOoh6o1BBCCEcBAQHw8PBA06ZNcfnyZVSuXJl3JIUmEokwadIkxMbGYsSIEZg7dy7q1KmDgIAA3tGIAqBSQwghnDx58gR9+vRB+/btcfbsWRgYGPCOpDQqVaqEdevW4cGDB6hRowY6deqEUaNGISMjg3c0whGVGkII4SA9PR3du3eHmZkZfHx8IBKJeEdSSrVq1UJAQAA2b96MgwcPwtHREZcuXeIdi3BCpYYQQuRMIpFg8ODBePnyJfz8/NTulG1pEwqFGDt2LKKjo1G9enW4u7tj7NixyMzM5B2NyBmVGkIIkbP58+fj9OnTOHToEBwcHHjHURnVq1fHpUuXsHHjRuzduxeOjo64cuUK71hEjqjUEEKIHB0/fhyLFi3CkiVLVP4qwTwIhUKMHz8eUVFRsLKyQvv27fHzzz/TGVJqglbpJoQQOUlOToaDgwM6deqEw4cPQyAQ8I6k0iQSCTZt2oQZM2bAwcEBx48fV+qFQNUZrdJNCCEKZsaMGdDQ0MDWrVup0MiBUCjEhAkTcPPmTaSnp8PFxQXnzp3jHYvIEJUaQgiRg5s3b2LPnj1YunQpKlWqxDuOWmnYsCHCwsLQsmVLeHl5YcGCBZBIJLxjERmgw0+EECJjYrEYrq6uEAqFuH37NjQ0NHhHUksSiQRLly7F3Llz4enpiQMHDsDExIR3LFICdPiJEEIUxPbt2xEZGYnNmzdToeFIKBRi9uzZ8Pf3x82bN+Hs7Iy7d+/yjkWkiEoNIYTI0Nu3bzFr1iyMGDECTZs25R2HAOjcuTPCw8NhbGyM5s2bY9++fbwjESmhUkMIKReJRIKMjAwkJSXh9evXSEtLQ35+PtToyPZXLVy4EACwbNkyzknIv1WvXh03btxA//79MXToUPz222/0mlUBmrwDEEIUD2MMb9++xZMnT4pvsbGxSElJQUZGBjIyMpCeno6MjAxkZmZ+9s1AKBRCV1cXFSpUKL6ZmprCxsbmk5u1tTX09PQ4fKey9eHDB+zevRu//PILLVSpgCpUqICdO3eiXr16+OWXX5CUlIQdO3ZAS0uLdzRSRlRqCFFzWVlZuHPnDkJCQnD//v3iEpOenl58n2rVqsHe3h5mZmaws7ODoaEhDAwMYGBg8NGfGWPIycn55JadnY2cnBy8efMGz58/x/Xr1/Hy5UuIxeLiMUxNTVGrVi24uLjA1dUVrq6usLe3h1CovDuUd+/ejfz8fIwaNYp3FPIFAoEAU6dORdWqVTFs2DC8efMGR44cUcmSrQ7o7CdC1Ex6ejquXr2KS5cu4erVq7h37x7EYjEMDQ3RqFEj2NvbF99q1qyJmjVrQldXV+o5CgsL8fLlSyQkJCA+Ph7x8fF48OABQkNDERsbCwAwNDSEs7MzXF1d4eLigubNm8PS0lLqWWRBLBbD3t4eLVq0wIEDB3jHISVw8eJF9OzZE/Xq1cOZM2dgamrKOxL5fyV9/6ZSQ4gaSExMhI+PD06cOIHQ0FCIxWJYW1ujXbt2aNGiBVq0aIG6desqzF6R1NRUhIeHIzQ0FGFhYQgNDUViYiIAoH79+vDy8oKXlxeaN28OTU3F3OF86tQpdO/eHXfu3IGrqyvvOKSEwsPD4enpiYoVK+L8+fOwtbXlHYlABUvN1q1bsXXrVjx//hwAUK9eveJrDZQUlRqiTlJSUnDs2DEcOnQI165dg46ODrp06QIPDw906NABdnZ2SnVV2+TkZAQHB8Pf3x/+/v54+/YtTExM4OHhAS8vL3Tu3FmhPlm7u7sjKysLN2/e5B2FlFJsbCw8PDyQk5OD8+fPo0GDBrwjqT2VKzWnT5+GhoYGatasCQDYu3cvVq5cicjISNSrV69E26BSQ1RddnY2fH19cejQIVy8eBGMMXTs2BEDBgxA9+7dVeZ1L5FIEBYWhrNnz+Ls2bMIDw+HQCBAixYtMHToUPTt25fr93r//n04Ojri0KFD6N+/P7ccpOySk5PRpUsXxMbGws/PD23btuUdSa2pXKn5nIoVK2LlypUYMWLEZ/89Ly8PeXl5xX9PT0+HlZUVlRqiclJTU7F582asX78eKSkpaNGiBQYMGIDevXujSpUqvOPJ3OvXr3Hu3DkcOXIEFy9ehI6ODnr16oXhw4fDzc1N7nukJkyYgGPHjiE+Pp7OpFFiGRkZ6NmzJ65evYozZ87A3d2ddyS1VeKdEkwJFRYWsj///JOJRCL24MGDL95v3rx5DMAnt7S0NDmmJUR2Xr58yaZOncr09fWZjo4OGzt2LHvy5AnvWFwlJiayJUuWsBo1ajAArEaNGmzx4sUsMTFRLuNLJBJmY2PDxo8fL5fxiGzl5uayzp07swoVKrCgoCDecdRWWlpaid6/larUREVFMT09PaahocGMjIzY2bNnv3r/3NxclpaWVnxLTEykUkNUwl9//cVGjhzJRCIRMzQ0ZDNnzmSvX7/mHUuhSCQSFhwczIYOHcp0dXWZUChkXbp0YZcvX2YSiURm496/f58BYOfOnZPZGES+srOzmbu7O9PT02M3btzgHUctlbTUKMapDiXk4OCAu3fv4tatWxgzZgyGDh2Khw8ffvH+2traMDQ0/OhGiDL78OEDxo8fjzp16uD06dNYtGgREhISsHTpUpiZmfGOp1AEAgHc3NywZ88eJCUlYdu2bXjx4gXat2+Ppk2b4tixYx9dJ0dazp49C11dXZqDoUIqVKgAPz8/ODs7w9PTE6GhobwjkS9Q6jk17u7uqFGjBrZv316i+9NEYaKsGGM4cOAAfvnlF2RnZ2P+/PkYN24cdHR0eEdTKowxXLhwAb///juuXLkCe3t7zJo1CwMHDpTaqeFubm4wMTGBn5+fVLZHFEdGRgY8PDzw6NEjXL58GU5OTrwjqQ21WKWbMfbRRGBCVNH9+/fRtm1bDBkyBO3atUNMTAymTp1KhaYMBAIBOnfujMuXL+POnTuoU6cOhg0bhtq1a2P37t0oKCgo1/ZTU1MREhICLy8vKSUmisTAwADnzp2Dvb09OnbsiOjoaN6RyH8oTan57bffcO3aNTx//hzR0dGYNWsWgoKCMHDgQN7RCJGJrKwsTJs2DU5OTnj9+jUCAgLg4+ODatWq8Y6mElxdXeHn54eIiAg0aNAAw4cPh6OjI86fP1/mbV64cAFisRhdunSRYlKiSIyMjHDhwgVYWVmhQ4cOePToEe9I5F+UptQkJydj8ODBcHBwQIcOHXD79m2cP38eHTt25B2NEKl79OgRmjRpgk2bNmHBggWIioqi00llxMnJCSdOnEBkZCTMzc3h6emJbt264cmTJ6Xe1tmzZ9GwYUOlWcqBlI2JiQkCAgJgZmaG9u3b4+nTp7wjkf+n1HNqSovm1BBlcPjwYYwYMQLW1tY4fvw46tSpwzuS2mCM4fjx45g6dSqSkpIwefJkzJ49GwYGBiV6vI2NDfr06YOVK1fKOClRBMnJyWjdujUEAgFu3ryJihUr8o6kstRiTg0hqiQ/Px8TJkxAv3794O3tXTzng8iPQCBAr169EBMTg9mzZ2Pjxo2oVasW9u7dC4lE8tXHfvjwAQkJCWjUqJF8whLuzMzMcPbsWaSkpKBnz57Iz8/nHUntUakhRAEkJCTAzc0N27Ztw+bNm3Hw4EHo6+vzjqW2KlSogLlz5yImJgZt2rTBsGHD0LJlS/z1119ffMz9+/cBgNYJUjP29vY4efIkQkJC8NNPP0GNDn4oJCo1hHAWHh4OZ2dnJCUl4fr16xg7dqxSLTSpyqytreHj44Pg4GC8f/8eTk5O2LJly2ffuKKjo6GpqQkHBwcOSQlPrVu3xs6dO7F3714sXbqUdxy1RqWGEI5u3ryJ9u3bo0aNGoiIiECTJk14RyKf4ebmhsjISPzwww8YN24cunTpgqSkpI/uEx0djdq1a0MkEnFKSXgaNGgQ5s2bh9mzZ+Pw4cO846gtKjWEcBIcHIyOHTuiYcOGCAgIQKVKlXhHIl+hq6uLzZs3w9/fH3fv3kX9+vVx/Pjx4n+PioqCo6Mjx4SEt3nz5mHgwIEYOnQoQkJCeMdRS1RqCOHg4sWL8PT0RPPmzXHu3LkSn11D+PP09ER0dDTatWuHXr16YejQofjw4QPu379PpUbNCQQC7Ny5E66urujevTvi4uJ4R1I7VGoIkbMzZ86gW7duaNeuHU6fPg09PT3ekUgpmZqa4ujRo9i3bx9OnjyJBg0aIC0tjSYJE2hra8PX1xdGRkbw8vJCamoq70hqhUoNIXIUFBSEHj16oGvXrvD19aWlDpSYQCDA4MGDce/ePWhpaQEAXr58yTkVUQSmpqbw9/fH69evMWzYMDojSo6o1BAiJ8+ePUOvXr3g5uYGHx8fmlCqImxtbTFr1iwAwOjRo7F06VJ6EyPF1zc6deoU1q5dyzuO2qBSQ4gcZGRkwNvbG8bGxjh8+HDxJ3uiGrKysiASiTBnzpziVb9zcnJ4xyKceXt7Y+rUqfj1119x69Yt3nHUApUaQmRMIpFgyJAhiI+Ph5+fH53lpILevXsHU1NTLFiwAEeOHMHJkyfh5uZGh6MIli1bBhcXF/Tt2xfv37/nHUflUakhRMbmz58PPz8/HDx4EPXq1eMdh8jAu3fvistq7969cf36dbx+/Rqurq64d+8e53SEJy0tLRw+fBiZmZkYOnToN5fbIOVDpYYQGTpx4gQWLVqEJUuWoFu3brzjEBl59+7dR4sZNm7cGGFhYbCwsEC7du0QFhbGMR3hzdraGvv27cOZM2ewZs0a3nFUGpUaQmTk3bt3GD16NL7//nvMmDGDdxwiQ+/fv//ksKKZmRkuXboEBwcHdOjQgeZUqDkvLy9Mnz4dM2bMoAvzyRCVGkJkZOrUqSgoKMCWLVtoLScV9+/DT/9mZGSEixcvokGDBujYsSOuX7/OIR1RFIsXL0bTpk3Rt29fpKSk8I6jkqjUECIDgYGB2Lt3L1auXImqVavyjkNk7L+Hn/7NwMAA58+fh6urKzw8PHDlyhU5pyOKQktLCz4+PsjJycHQoUPp1H8ZoFJDiJRlZ2dj1KhRaNOmDUaMGME7DpGDzMzMry51oaenhzNnzqBVq1bo0qULLl68KMd0RJFYWVlh79698Pf3x//+9z/ecVQOlRpCpGzBggV4+fIlduzYQYed1IRAIPjmp25dXV34+fmhQ4cO6NatG4KCguQTjigcLy8vjBgxAlOmTMHz5895x1EpVGoIkaKoqCisXr0ac+fORa1atXjHIXJSklIDADo6Ojhx4gRat26N77//HjExMXJIRxTRmjVrYGJighEjRtBp3lJEpYYQKZo3bx5sbW0xbdo03lGIHJW01ACASCTCsWPHUK1aNXTp0gVv3ryRcTqiiAwNDbFr1y5cvnwZ27Zt4x1HZVCpIURKIiMjcfLkScyZM4eWQVAzQqGwVJ+2jY2NcfbsWeTk5MDb2xvZ2dkyTEcUlbu7O8aMGYNp06bh2bNnvOOoBCo1hEjJggULYG9vj4EDB/KOQuRMJBIhPz+/VI+xsbHBmTNnEB0djUGDBkEsFssoHVFkv//+O0xNTTFq1Cg6G0oKqNQQIgUPHz6En58fZs2aBU1NTd5xiJxVqFChTAtYOjs7w8fHB35+fpg+fboMkhFFp6+vj23btiEgIAD79u3jHUfpUakhRArWrFkDCwsL9O/fn3cUwkFZSw0AdOvWDevXr8eaNWvwxx9/SDkZUQaenp4YOHAgJk+ejOTkZN5xlBqVGkLK6fXr19i/fz8mTpwIkUjEOw7hoDylBgDGjx+PUaNGYcKECXjw4IEUkxFlsW7dOmhoaGDChAm8oyg1KjWElNP+/fshFArx008/8Y5CONHT00NmZma5trFmzRrY2dmhf//+yM3NlVIyoixMTU2xbt06HDlyBIGBgbzjKC0qNYSU05EjR+Dl5QVjY2PeUQgn5ubmePXqVbm2oaurCx8fHzx+/JguCaCmBgwYgJYtW2Ly5MkoLCzkHUcpUakhpByePn2KsLAw9OnTh3cUwlG1atXw8uXLcm/H0dERq1evxqZNm3D69GkpJCPKRCAQYN26dbh//z7NryojKjWElMPRo0dRoUIFeHl58Y5COKpWrRqSkpKkcmXYsWPHwtvbGz/88EO59/4Q5ePi4oJhw4Zhzpw5+PDhA+84SodKDSHlcOTIEXTt2hV6enq8oxCOLC0tUVhYKJWrAwsEAuzcuRPa2toYMmQIXUJfDS1ZsgS5ublYuHAh7yhKh0oNIWX05MkTREZGom/fvryjEM6qVasGAFI5BAX8PWl0//79uHTpEnbu3CmVbRLlYWFhgd9++w0bN27E48ePecdRKlRqCCmjY8eOQU9PD56enryjEM6kXWoAoH379hg6dChmzpyJ9+/fS227RDlMnjwZ1apVw9SpU3lHUSpUaggpo+vXr6NVq1bQ1dXlHYVwVqVKFWhqauLFixdS3e7y5cuRn5+POXPmSHW7RPFVqFABK1euxJkzZ3Dx4kXecZQGlRpCyoAxhjt37qBp06a8oxAFIBQKYW5uLtU9NQBQtWpVLFiwANu2bcPdu3elum2i+Hr16oXWrVvTKd6lQKWGkDKIj49HSkoKXF1deUchCkJap3X/1/jx41G7dm2MHz+eFjxUMwKBAGvXrsWjR4/wv//9j3ccpUClhpAyuHPnDgBQqSHF7O3tERMTI/XtamlpYePGjbhx4wYOHjwo9e0Txebs7Ix+/fphyZIlyMvL4x1H4VGpIaQMQkNDYWNjAzMzM95RiIJo1KgRoqOjIRaLpb7t9u3bo3fv3pg2bRrS09Olvn2i2GbPno2XL19i7969vKMoPCo1hJTBnTt3aC8N+UjDhg2RnZ2N2NhYmWx/1apVeP/+PTZu3CiT7RPFVbduXfTu3RtLly5FQUEB7zgKjUoNIaXEGENERARcXFx4RyEKpGHDhgAgswm91tbWGDlyJNauXVvuxTOJ8pk9ezbi4+Oxf/9+3lEUGpUaQkopPT0dmZmZsLW15R2FKBBTU1NYWlrK9CylX3/9Fenp6di6davMxiCKydHRET169MDSpUvpTKivoFJDSCklJycDAM2nIZ9o1KiRTEuNtbU1hg0bhlWrViEnJ0dm4xDFNGfOHDx9+hR//vkn7ygKi0oNIaVEpYZ8SaNGjXDv3j2ZjjF9+nS8ffsWBw4ckOk4RPE0atQI3t7eWLx4sUwmpKsCKjWElBKVGvIlDRs2RFJSUvFrRBZq1qyJ7777DmvWrKHFLtXQnDlz8PjxYxw5coR3FIVEpYaQUkpOToaWlhZMTEx4RyEKplGjRgAg8701U6dORUxMDPz9/WU6DlE8Li4u6NKlCxYtWkSl9jOo1BBSSsnJyahSpQoEAgHvKETB2NnZwcDAAOHh4TIdp0WLFnB1dcX27dtlOg5RTHPmzMGjR49w+vRp3lEUDpUaQkrp7du3qFy5Mu8YRAEJhUK0bNkSQUFBMh1HIBBgyJAhOH/+PFJSUmQ6FlE8zZo1Q9OmTbF582beURQOlRpCSkkgEEAopP91yOe5u7vj2rVrMr+kfZ8+fcAYw9GjR2U6DlFM48aNQ0BAAB4/fsw7ikKh38yElJJIJEJ+fj7vGERBdejQATk5Obh586ZMx6lSpQo6duyIQ4cOyXQcoph69+6NSpUqYdu2bbyjKBQqNYSUEpUa8jUNGjSAqakpAgMDZT7WwIEDcf36dcTHx8t8LKJYdHR0MGLECOzevRvZ2dm84ygMKjWElBKVGvI1QqEQ7du3l0up+e6776Crq0t7a9TUqFGjkJaWBh8fH95RFAaVGkJKiUoN+RZ3d3eEhoYiLS1NpuPo6+uje/fuOHjwIBhjMh2LKB47Ozt4enpi8+bN9PP/f1RqCCklKjXkWzp06ACJRCLzs6AAoH///njw4AGePHki87GI4hk3bhwiIiJw584d3lEUApUaQkpJJBIhNzeXdwyiwOzs7FC9enVcunRJ5mO1bdsWQqEQwcHBMh+LKB4PDw9Ur14dW7Zs4R1FIVCpIaSUzM3NkZmZifT0dN5RiALr0KGDXObVGBgYoHHjxrh69arMxyKKR0NDA6NHj8bhw4fpmkWgUkNIqdnZ2QEA4uLiOCchiqxjx4549OgRnj9/LvOx3NzcqNSoseHDh0MikdDq3aBSQ0ipUakhJeHp6QkdHR25XBzPzc0NCQkJdGq3mjI1NUWnTp1w+PBh3lG4U5pSs2zZMri6usLAwABVqlTBd999h7/++ot3LKKGTE1Noa+vT6WGfJWBgQG6dOkilzea1q1bAwDtrVFjffr0wY0bN5CYmMg7CleavAOUVHBwMMaNGwdXV1cUFhZi1qxZ6NSpEx4+fAg9PT3e8YgaEQgEsLOzo1IjBUwiQXba/88D0NUFOC8SqqulK9WFSvv27Yu+ffsiNjYWNWvWlNp2/6tixYpwdHREcHAwBg8eXPYNMQYowIXcGGPILvg7h66RKQS0LMk3de/eHSKRCMeOHcPkyZN5x+FGaUrN+fPnP/r77t27UaVKFYSHh8PNze2zj8nLy/to/RWa2EmkhUqNdGSnpUB/gxnvGMUyZ2ZCTyS9D0leXl7Q1dXF0aNHMXPmTKlt93Nat26Ny5cvl28j2dmAvr50ApUnhhagP+vvP2dOSIaeSRW+gZSAkZERPD09cfjwYbUuNUpbf4sualWxYsUv3mfZsmUwMjIqvllZWckrHlFxdnZ2ePr0Ke8YRMHp6emhW7ducjkEVa9ePTx9+hRisVjmYxHF1LdvX9y+fVsuk9MVlYAp4WUIGWPo3r07UlNTce3atS/e73N7aqysrJCWlgZDQ0N5RCUqau/evfjhhx+QkpLy1WJNvo5lZiK7osHff0lOBjgfSpb24ScA8PX1RY8ePRATEwMHBwepbvvfzp8/D09PTzx//hw2NjZl24iCHH7Kys8q3oOXOSMDetr89x4pg4yMDFSpUgULFizA9OnTeceRqvT0dBgZGX3z/VtpDj/92/jx4xEVFYXr169/9X7a2trQ1taWUyqiTtzc3MAYw40bN9CtWzfecZSWQCCAXsH//0Wk9/dNxXTu3Bn6+vo4fPgw5s6dK7Nx/n1WXplLjUDAvVgCALT+9WfO86yUiYGBAby8vHD48GGVKzUlpXSHn37++WecOnUKV65cgaWlJe84RE3Z2trC0tKSzjYh31ShQgV0795d5oegbGxsIBAIaK6Xmuvbty8iIiIQGxvLOwoXSlNqGGMYP348Tpw4gcuXL6N69eq8IxE1JhAI0KZNG7o0PSmRvn374uHDh3jw4IHMxtDW1oaVlRXN9VJzXl5e0NPTU9tr1ihNqRk3bhwOHDiAQ4cOwcDAAK9fv8br16+Rk5PDOxpRU25uboiIiEBGRgbvKETBderUCSYmJtizZ49Mx6Gz8oiuri48PT1x9uxZ3lG4UJpSs3XrVqSlpaFt27YwNzcvvqlrGyX8ubm5QSwW4+bNm7yjEAWnra2N4cOHY9euXTL9IEalhgCAu7s77ty5o5aXMVGaUsMY++xt2LBhvKMRNeXg4IDKlSvTIShSIqNHj8b79+9x5MgRmY1hYmKilm9k5GPu7u4Qi8Vq+btJaUoNIYpGIBDA3d0dp0+f5h2FKIGaNWvCw8MDW7ZskdkYIpEI+fn5Mts+UQ52dnawsbGRyyrxioZKDSHl0L9/f0RHRyM6Opp3FKIExo4dizt37iAsLEwm2xeJRCgoKPj2HYlKK/rAdenSJd5R5I5KDSHl4OHhgYoVK+LgwYO8oxAl4OXlBWtra2zdulUm29fS0qI9NQQA0KFDBzx48ABJSUm8o8gVlRpCykEkEqF37944dOgQJBIJ7zhEwWloaGD06NE4dOgQUlNTpb59OvxEirRv3x4Ayr8emJKhUkNIOQ0cOBCJiYnfvMI1IQAwYsQIiMVi7N69W+rbplJDipiZmaFBgwZqN6+GSg0h5dSyZUtYW1vj0KFDvKMQJVClShX07t0bW7dulfrePZFI9NF6d0S9dejQAZcuXYISLvFYZlRqCCknoVCIAQMG4OjRo/QpmZTI2LFjERsbi4CAAKluNysrC7q6ulLdJlFe7u7uSExMxJMnT3hHkRsqNYRIwaBBg/D+/XscP36cdxSiBFq0aIHGjRtjxYoVUt1ucnIyzMzMpLpNorxatGgBAAgNDeWcRH6o1BAiBfXq1YO7uztWr16tVrt6SdkIBALMmTMHV65ckepcLCo15N+MjY1ha2uLu3fv8o4iN1RqCJGSqVOnIjw8nFbuJiXi7e0NR0dHLFq0SGrbpFJD/qtRo0ZUagghpefh4YF69eph5cqVvKMQJSAUCjFnzhxcvHgRt27dkso2qdSQ/2rUqBHu3bunNnuQqdQQIiUCgQDTp0/H2bNn1eqTESm7nj17om7dulLbW0OlhvxXw4YN8fbtW7W5CB+VGkKkaMCAAbCzs8PixYt5RyFKQCgUYvbs2fD39y/30gkSiQRv376lUkM+0qhRIwBQmw9aVGoIkSJNTU389ttvOH78OO7fv887DlECffr0Qa1atcq9t+bx48cQi8Wwt7eXUjKiCmxsbGBkZESlhhBSNoMHD4atrS1+++033lGIEtDQ0MDs2bNx6tQpREZGlnk7d+7cAQC4uLhIKxpRAQKBQK0mC1OpIUTKRCIRVq5cidOnT8Pf3593HKIE+vfvjxo1apTrsGVoaCgcHBxgZGQkxWREFVCpIYSUS8+ePdGhQwdMnDiRLltPvklTUxOzZs3CiRMnyvzmc+fOHTRp0kS6wYhKaNiwIWJjY5Gdnc07isxRqSFEBgQCATZs2IDnz59jzZo1vOMQJTBo0CDUrl0bkydPLvXpt/n5+bh79y5cXV1llI4oM1tbWzDG8PLlS95RZI5KDSEyUrduXUyYMAGLFy9GYmIi7zhEwWlpaWHNmjUICgrCyZMnS/XYqKgo5Ofn054a8lnVqlUDALx48YJzEtmjUkOIDM2bNw8GBgaYNm0a7yhECXh6eqJz58745ZdfSnXY8tatW9DU1ETDhg1lmI4oq6JSQ3tqCCHlYmhoiN9//x2HDx/G5cuXecchSmDNmjWIj4/H+vXrS/wYX19ftGvXDjo6OjJMRpSVnp4ejI2NqdQQQspv0KBBaNWqFUaMGIG0tDTecYiCq1OnDsaOHYvFixcjOTn5m/dPTk5GUFAQ+vTpI4d0RFlVq1aNSg0hpPyEQiH279+P9+/fY8yYMWqzBgspu/nz50NLSwuzZ8/+5n1PnDgBoVCI77//Xg7JiLKiUkMIkRpbW1ts374df/75J/bt28c7DlFwFStWxIIFC7Bz585vXpDv8OHDcHd3R6VKleSUjigjKjWEEKnq168fhg0bhnHjxuHJkye84xAFN2rUKNSuXRuTJk364t69pKQkXL16lQ49kW+qVq0anf1ECJGujRs3wsLCAv3790d+fj7vOESBaWlpYe3atbh69SqOHz/+2fscO3YMmpqa+O677+QbjiidatWq4fXr1xCLxbyjyBSVGkLkSF9fH4cOHUJUVFSJ5ksQ9ebh4QEvLy9MnjwZ6enpH/0bYwy7d++Gh4cHTExMOCWULsYY8vPzkZmVWfy13NxcSCQSjqlUQ5UqVSAWi/HhwwfeUWRKk3cAQtSNi4sLlixZgunTp6NVq1bw9vbmHYkfXV0gM/OfP5NPbN68GfXq1cPMmTOxefPm4q9fuXIFkZGR+P333zmmKz2xWIz4+Hg8efIEjx8//ugWHx//z6E2rb//YzrfFABQqVIl1KpV65NbzZo1oUuvnW+qUKECACAnJ4dzEtkSMDU6FSM9PR1GRkZIS0uDoaEh7zhEjUkkEvTu3Rvnz5/H1atX4ezszDsSUWAbNmzAxIkTce3aNbRq1QrA3xfqS0pKQmRkJAQCAeeEX5eamorz58/jzJkzOHfuHFJTUwEA2traqFmzJmrVqgV7e3tUr14durq60NbWhpaWFsRiMfLy8pCXl4ekpKTi8vPXX38V73HQ1NRE69at0bVrV3Tr1g329vYcv1PFFRQUhHbt2uHx48dK+RyV9P2bSg0hnGRnZ6N9+/aIj4/HrVu3YGNjwzsSUVBisRitWrVCamoq7t69i7/++guNGjXCvn37MHjwYN7xPuvJkyc4deoUzpw5g2vXrkEsFsPJyQldu3ZFy5Yt4eDgACsrK2hoaJR624wxvHv3Do8fP0ZkZCT8/f1x6dIl5OXlwcHBobjgtGrVqkzbV0W3bt1C8+bNERUVBUdHR95xSo1KzWdQqSGK5s2bN2jWrBl0dXVx/fp1GBsb845EFNSDBw/g5OSEadOm4eHDh4iOjkZMTAw0NRVnFgFjDJcuXcKqVatw4cIF6OjooEOHDujWrRu8vLxgaWkps7GzsrJw6dIlnD59GmfOnMHr169Ro0YNTJkyBcOGDVP7Q1T37t1Do0aNcPv2baVcI6zE799MjaSlpTEALC0tjXcUQoo9evSIGRsbsw4dOrC8vDzecYgCW7BgARMKhQwA27NnD+84xfLz89n+/ftZw4YNGQDm5OTEDh48yLKysrjkEYvFLCQkhPXr148JhUJWqVIlNmfOHJacnMwljyK4f/8+A8Bu3LjBO0qZlPT9m85+IoSz2rVr4+TJk7h69SpGjx5NVxwmXzRjxgzo6elBJBKhZ8+evOMgJycHq1evhp2dHQYPHgwLCwtcunQJ4eHhGDBgALe9I0KhEM2bN8eff/6Jp0+fYtCgQVizZg2sra0xatQoxMXFccnFU9G8K1X//UKlhhAF0KZNG+zatQu7d+/GnDlzVP4XDymbY8eOISMjA2KxGIsXL+aa5fz588VnZXXo0AHR0dHw9/dH+/btFWrisq2tLdatW4eEhATMmzcPp06dQr169bB48eJSrYSu7ITCv9/uVf53ixz2GikMOvxEFN3vv//OALBff/2VSSQS3nGIAklJSWGVK1dmvXv3ZkuXLmVCoZDdvHlT7jlevnzJ+vTpwwCwDh06sL/++kvuGcojMzOT/frrr0xTU5PVrl2bXblyhXckuYiJiWEAWHBwMO8oZUKHnwhRQtOmTcOaNWuwYsUKTJ06VfU/VZESmzp1KgoKCrBhwwZMmzYNLi4uGDx48CcX5ZMVsViMjRs3onbt2ggKCsKBAwcQEBCAWrVqyWV8adHT08Py5csRERGBihUrol27dhg6dCjevn3LO5pMFV3AsGiPjapS7e+OECU0efJkbNq0CWvXrsXPP/9MV1MlCAwMxN69e7Fq1SpUrVoVmpqaOHjwIJKTk/Hjjz/KvPw+fvwYzZo1w4QJEzBgwADExMRg4MCBCnWYqbQcHR1x7do1/PHHHzh9+jQcHBzg4+PDO5bMvH//HsDfi6WqMio1hCigcePGYceOHdiyZQtGjRpFxUaNZWdnY9SoUWjbti2GDx9e/PWaNWti165dOHLkCLZt2yaz8c+cOQNXV1dkZGQgJCQE27ZtU5llGYRCIUaOHImYmBh06tQJ/fv3x9SpU1FYWMg7mtS9e/cOgOqXGppTQ4gC27NnDxMKhWzo0KGssLCQdxwiZxKJhP34449MW1v7i3NXxo8fz0QiEQsPD5fq2GKxmC1YsIABYN7e3ir/e1MikbD169czDQ0N1r59e/b27VvekaRq165dDIDSXjZCZnNq9u7di7Nnzxb/ffr06TA2NkaLFi0QHx8vtbJFCAGGDh2KAwcO4MCBA+jRowcyMjJ4RyJytGXLFvzxxx/YsmXLF+eurFq1Co6OjujduzfS0tKkMm56ejp69OiBefPmYcGCBfD19VX5C5YKBAJMmDABgYGBiI6OhouLCyIiInjHkpp3797BwMAAIpGIdxSZKnWpWbp0afHCWDdv3sSmTZvw+++/w9TUFJMnT5Z6QELUXf/+/XHq1ClcuXIFLVq0wLNnz3hHInJw+fJlTJw4EZMmTfrosNN/aWtr48iRI0hJScHIkSPLPb8mJiYGTZo0wZUrV3D69GnMnTtX5SeX/lvbtm0RFhYGU1NTtGzZEgcPHuQdSSrevXuHSpUq8Y4hc6V+pSYmJqJmzZoAgJMnT6JXr1746aefsGzZMly7dk3qAQkhQJcuXXDr1i3k5OTA1dUVwcHBvCMRGYqLi0Pv3r3Rvn17rFy58pv3t7Ozw65du3Ds2LGPVvIurbCwMDRv3hxCoRChoaHo2rVrmbelzKytrXHt2jX07dsXgwYNwooVK3hHKrf3799TqfkcfX394glHFy9ehLu7OwBAR0dH5Zc0J4SnunXr4vbt22jQoAHc3d2xY8cO3pGIDGRkZMDb2xsVK1bE4cOHS7y2U8+ePTFhwgRMnToVYWFhpR43NDQU7u7uqF27Nm7evKl0p2pLW4UKFbB7927MnTsXM2bMwPLly3lHKpd3796p/iRhAKVeCa1jx44YOXIknJyc8PjxY3h5eQH4e7E1W1tbaecjhPxLpUqVcOHCBUyePBmjRo1CdHQ01q5dq1CLGpKyy8/PR//+/ZGQkIDbt2+X+iyjlStX4ubNm+jTpw8iIiJKvEDqnTt30KlTJ9StWxfnz59X+fkzJSUQCLBgwQIIBALMnDkTjDHMnDmTd6wyeffuHapWrco7hsyVek/N5s2b0bx5c7x9+xbHjx8v3p0VHh6O/v37Sz0gIeRjWlpa2LRpE7Zu3Ypt27ahU6dOePHiBe9YpJxyc3PRo0cPBAQE4OjRo6hTp06ptyESiXD48GF8+PABvXv3RkFBwTcfc+fOHXTs2BH16tWjQvMF8+fPx/z58/Hbb79h6dKlvOOUSUJCAiwsLHjHkD25nIulIOiUbqJqrly5wiwsLJixsTHz8fHhHYeUUWZmJnN3d2cVKlRgFy9eLPf2Ll++zDQ1NdmPP/741eU2bt26xQwNDVmLFi1Yenp6ucdVdfPnz2cA2OLFi3lHKZX09HQGgO3evZt3lDIr6ft3ifZZR0VFoX79+hAKhYiKivrqfRs0aFDuokUIKZm2bdsiOjoaY8aMQb9+/XDq1Cls2rRJZS6Opg4yMjLg5eWFyMhInDt3Dm3atCn3Ntu1a4c//vgDP/zwA+zt7TFt2rRP7hMZGYlOnTrB0dER586dg4GBQbnHVXXz5s2DQCDA7NmzIRKJPvu8KqIHDx4A+PsqyiqvJA1JIBCw5OTk4j8LhUImEAiKb0V/FwqF5a9jMkR7aoiqkkgk7ODBg8zIyIhZWlqywMBA3pFICaSmprJmzZoxQ0NDFhISIvXt//bbb0wgELDjx49/9PXXr18zKysr5uzsTHtoyqDoeT116hTvKCWyY8cOJhQKWXZ2Nu8oZVbS928BY9++qEF8fDysra0hEAi+eYE9GxsbKdUt6UtPT4eRkRHS0tLouDFRSYmJiRg2bBguX76MSZMmfXRdKaJYnj17hh49eiAhIQEXL16Es7Oz1MeQSCQYMGAATp06heDgYLi6uiI/Px/t27dHbGwswsLCYGlpKfVxVZ1EIkGvXr0QGBiIW7duoW7durwjfdWECRNw8eJFxMTE8I5SZiV9/y5RqSkpxphCL3BGpYaoA4lEgg0bNmDGjBmwtrbGunXr0KVLF96xyL+cOXMGgwcPRsWKFXHy5EmZHhbIyclB+/bt8ezZM9y6dQtLly7F3r17ERQUhObNm8tsXFWXmZmJ5s2bIycnB3fu3FHo06XbtWsHU1NTHD16lHeUMivp+3epz34aPHgwMjMzP/n68+fP4ebmVtrNEUKkTCgUYtKkSYiIiIClpSW8vLzQtWtXPHnyhHc0tVdYWIjffvsN3bp1Q5s2bRAeHi7zeQ4VKlSAn58fdHV10bJlS/zxxx/Ytm0bFZpy0tfXh5+fH1JTU9G3b1+FXQSTMYaoqCj1mE+DMpSahw8fwtHRETdu3Cj+2t69e9GwYUOYmZlJNRwhpOzq1q2LS5cu4dixY7h//z7q1auH6dOnIz09nXc0tZScnIxOnTrh999/x4oVK+Dr61vi68iUV5UqVTBv3jy8evUK1tbWGDx4sFzGVXV2dnY4evQorly5orCThpOSkvD+/Xu1KTWlPqW7oKCA/frrr0wkErGZM2eyXr16MX19fbZz584yTP2RL5ooTNRVdnY2W7hwIatQoQIzMzNju3fvZmKxmHcstREQEMDMzc1Z1apVWVBQkNzHf/78OatUqRJzcnJimpqabNCgQbTquxRt3LiRAWB79uzhHeUTvr6+DAB79uwZ7yjlUtL37zJfp2bu3LlMIBAwLS0tmczalwUqNUTdxcfHs759+zIAzNXVlV24cOGr1zEh5fPy5UvWr18/BoC1a9eOvXr1Su4ZCgsLmZubG7OxsWEpKSns8OHDTCgUsuHDh1OxlRKJRMJ++OEHpqenx2JjY3nH+cjIkSNZrVq1eMcoN5mVmvz8fDZlyhSmra3NfvvtN+bm5sbMzMzY2bNnyxxWXqjUEPK3q1evsiZNmjAArFmzZuzcuXNUbqSooKCArV27lhkYGLDKlSuzvXv3cnt+V65cyQQCwUd7iPbv388EAgEbM2YM/dylJCMjg9nZ2bEWLVoozF4wiUTCLCws2OTJk3lHKTeZlZoGDRqwmjVrsps3bzLG/n7Sli9fzrS1tdmYMWPKllZOqNQQ8g+JRMLOnz/PmjdvXrzn5tixYwrzC1lZXb9+nTVo0IAJBAI2duxY9v79e25ZoqKimEgkYlOnTv3k33bu3MkAsIkTJ1KxkZLr168zoVDIli5dyjsKY4yxiIgIBkAlrlsls1IzfPhwlpmZ+cnXIyMjWb169Uq7uVIJDg5mXbt2Zebm5gwA8/X1LdXjqdQQ8imJRMIuXrzI2rZtywAwe3t7tn37dpaTk8M7mlJ58OABGzRoUHFBDA0N5ZonPz+fOTk5sXr16n3xZ7l161YGgE2fPp2KjZTMmDGDaWlpsejoaN5R2KJFi5iBgQHLy8vjHaXcZD6n5nNyc3OlublP+Pv7s1mzZrHjx49TqSFEBm7fvs169uzJBAIBq1SpEps4cSK7d++ezMYTi8UsLy+PFRQUKO2b6q1bt1j37t0ZAFatWjW2bds2hdjbtWzZMiYUCr9ZrtavX88AsDlz5sgpmWrLzc1lderUYU2aNOH+OmjWrBnr2bMn1wzSItW1n74kJyfnk1VgtbW1y7PJr/L09ISnp2eJ75+Xl4e8vLziv9OprIR8XZMmTXDs2DE8efIEO3bswL59+7B+/Xo4Oztj+PDh6N+/f4nXlcrNzUVERARiYmKQmJhYfEtISMCLFy+QlZUF9p9rf4pEIpiZmcHKyqr4Zm1tDVtbWzRp0kRhLhvBGMPFixexfPlyBAUFwcHBAbt27cLAgQMhEol4x8Pjx48xf/58TJkyBS4uLl+974QJE5CXl4fp06dDJBJh9uzZckqpmrS1tbFz5060bNkSGzZswOTJk7nkePv2LW7fvo2dO3dyGZ+XUl9ROCsrC7/++iuOHDmCd+/effLvYrFYauG+RiAQwNfXF999990X7zN//nwsWLDgk6/TFYUJKZmCggL4+/tj165dOHv2LDQ1NdGjRw8MHz4c7du3h1D4z6WukpOTERISgpCQENy4cQPh4eHIz88HAFStWvWjomJpaQkDAwNoaWlBU1MTEokEBQUFyMvLQ1JS0kclKDExsXg7NWrUQIsWLdCyZUu0bNkSdevW/SiDrKWmpuLEiRPYvHkzIiMj4eLigpkzZ+K7776Ta46vYYyhbdu2ePnyJaKioqCrq1uixy1evBhz5szBsmXLMGPGDBmnVH0TJ07EH3/8gQcPHqB69epyH3/fvn0YOnQokpKSULVqVbmPL20lXhGgtLuAxo4dy+rUqcOOHj3KKlSowHbt2sUWLVrELC0t2YEDB8qyV6lMUILDT7m5uSwtLa34lpiYSIefCCmjpKQk9vvvv7PatWszAMzc3Jz179+fDRs2jDVu3JgBYACYlZUV69evH9uwYQMLDw8v92FpiUTC4uPj2eHDh9mECROYi4sL09DQYABYlSpV2Pjx49mNGzdkdvgqKyuLHT58mHXv3p2JRCImFAqZh4cHCwwMVMhDZkePHmUA2MWLF0v92Hnz5jEAbMqUKXS6dzllZGQwCwsL1rdvXy7jt2rVirVp04bL2LIgszk1VlZW7MqVK4wxxgwMDNiTJ08YY4zt27ePeXp6lj5pGZWk1PwXzakhpPxSUlLY9OnTmaWlZXGREQqFrH79+mzu3Lns8ePHMs+QmZnJLl++zKZMmcKqVavGADAbGxv266+/srt375Z7+/n5+czf358NGjSI6evrMwCsSZMmbN26dVyuNVNSeXl5rGbNmuX6XbxhwwYmEAjYwIEDVWKCKU9FZ5jdvn1bruOGh4czAJ+szq7MZFZq9PT02PPnzxljjFWrVq34hxUXF8f09PTKELVsqNQQIl/Pnj1j48aNYzo6OkwoFLKOHTuyXbt2sYiICLZhwwbm4eHBtLW1i8+gGjduHNu7dy978OCBTCdMisViFhQUxEaNGsUqVarEALBWrVoxf3//Eu9JEYvF7O7du2zNmjXMy8uruMjUrl2bLVy4sPjDm6LbuHEjEwqFLCoqqlzbOXLkCBOJRKxjx44sPT1dSunUT2FhIatfvz5r06aNXPfqDRs2jFlbW7OCggK5jSlrMis1jo6OxRdx6tixY/H1D9avX8+qVatWhqhlQ6WGEPl48OABGzx4MNPQ0GCVKlViixYtYq9fv/7sfTMzM5mfnx/76aefmIODQ/GeHH19fdamTRs2depU5uPjw54+fSqTX/L5+fnM19eXNW3alAFgjRo1Yj4+Ph+VKolEwl68eMEuXrzIFixYwDp37syMjIwYAKatrc06dOjAlixZwiIjIxXy8NKXfPjwgZmamrLhw4dLZXuXL19mhoaGzNnZ+Ys/b/Jt/v7+DAA7deqUXMZLTk5mIpGIrVixQi7jyUtJ379LPVF47dq10NDQwIQJE3DlyhV4eXlBLBajsLAQa9aswcSJE0uzuVLJzMxEbGwsAMDJyQlr1qxBu3btULFiRVhbW3/z8SWeaEQIQUxMDGbOnImTJ0/C0tISv/zyC0aOHAk9Pb0SbyMtLQ3h4eEIDQ0tviUkJAAAjIyMYGtrCxsbm8/eKleuDIFAUOrcjDFkZ2fj7NmzWLlyJcLCwmBsbAx7e3vk5eUhNjYW2dnZAABjY2M0b968ePJx8+bNoaOjU+oxFcGsWbOwdu1aPH78GJaWllLZ5r179+Dp6QldXV1cuHABNWrUkMp21QljDO7u7khKSkJUVBQ0Nct10vE3LV68GEuXLsWLFy9QsWJFmY4lTyV9/y51qfmvhIQEhIWFoUaNGmjYsGF5NvVNQUFBaNeu3SdfHzp0KPbs2fPNx1OpIeTbsrOzsWTJEqxcuRKWlpaYPXs2Bg0aJLVTld+8eYOwsDBERUUhPj7+o1tWVlbx/UQiEfT09FChQoXP3nR0dJCdnY309HRkZGQgIyOj+M8SiaR4OwKBADo6OsjJyYG5uTkGDRqEVq1awcHBAfb29gpz1lJ5vHjxAvb29pgyZQqWLFki1W0/f/4cHh4e+PDhA/z9/eHs7CzV7auD8PBwuLi4YMeOHfjxxx9lNk5BQQFsbGzQrVs3bN++XWbj8CC3UqNMqNQQ8nVnzpzBzz//jFevXmHmzJn49ddfUaFCBbmMzRjD+/fviwvOy5cvkZWVhZycnM/e8vLyoKurCwMDAxgYGMDQ0PCjPxsaGqJ69eqws7NDhQoVEBAQgHHjxuHZs2eYOnUq5syZU6q9TopsxIgROHXqFJ4+fSqT320pKSno2rUrHjx4gMOHD6NLly5SH0PVDRo0CJcuXUJsbKzMXncHDx7EoEGDEB0djfr168tkDF5kdkq3MqM5NYR83suXL4uvitupUye5nMHEQ05ODlu4cCHT1tZm1tbW7MyZM7wjldvjx4+ZUChkGzZskOk4mZmZzNvbmwkEArZgwQI65buUnj17xkQiEVu+fLlMtp+ZmcmsrKyYt7e3TLbPG5dlEhQdlRpCPhUYGMiqVKnCqlatyo4cOaJUk2PLKjY2lnXu3JkBYL/88gvLz8/nHanMxo4dy6pUqSKXtbrEYjFbtGgREwgEzMvLi+tincpoxIgRzMLCQianys+cOZNpa2uzp0+fSn3bikDqpSYxMbHcoXijUkPIP/79BuXu7s6Sk5N5R5IriUTCVq9ezTQ1NVmrVq3YixcveEcqtZSUFFahQgW2YMECuY577tw5ZmJiwuzs7FhkZKRcx1Zm9+/fZwCkfqHav/76i2lpabF58+ZJdbuKROqlxsjIiO3bt6/cwXiiUkPI396+fcs6d+7MBAIBmzdvHveF93i6fv06q1atGqtcuTILCAjgHadUlixZwrS1tdmbN2/kPnZcXBxzcnJiOjo6Sv/eIE8eHh7MyclJantEJRIJ8/DwYNWrV2fZ2dlS2aYiknqp2bx5MzMwMGA9evRgKSkp5Q7IA5UaQhiLjo5mVlZWzNTUlF24cIF3HIXw5s0b1rFjRyYQCNjKlSt5xymR3NxcVrVqVfbjjz9yy5Cdnc1++OEHBoCNHTuWrkBcAhcuXGAAiq/MX14nTpxgAJifn59UtqeoZDKnJi4ujrVr146ZmZkp5RNIpYaou1u3bjETExPWqFEjlTikLE2FhYVsxowZDACbOXOmws8t2rNnDwPAHj58yDWHRCJhO3bsYCKRiDVr1owlJCRwzaPoJBIJq1+/PuvWrVu5t5WZmcmsra1Zly5dFP71Wl4ynSi8ceNGpqmpyRwdHZmTk9NHN0VGpYaos0uXLjE9PT3WsmVLlpqayjuOwlq1ahUDwMaMGaOwZ/hIJBLWoEED1qVLF95Rit2+fZtZWVkxQ0NDtnPnTpV/ky2PXbt2MQDsr7/+KvM2JBIJ69OnD9PT01OaZTzKo6Tv36W+tGF8fDyOHz+OihUronv37jK/OiIhpPz8/PzQt29ftG3bFsePH1eZ67PIwtSpU2FsbIyffvoJ6enp2L17N7S0tHjH+sjly5cRFRWFNWvW8I5SrEmTJoiKisLkyZMxYsQIHDt2DH/88QeqVavGO5rCGTBgAGbOnIl169Zhy5YtZdrG8uXLceTIERw7dgw1a9aUckIlVpqmtGPHDmZgYMC+//57LhPTyov21BB1dOjQIaahocF69epFcx5K4ciRI0xLS4t5e3sr3PPWvXt31qBBA4XdG3LmzBlmbm7OjIyM2J49exQ2J08LFy5kFSpUYB8+fCj1Y8+cOcMEAgGbM2eODJIpJqmv/dS5c2fcuXMH69atw5AhQ2TbtGSErigsW4wxvH79Gi9fvkRSUhJevXqFpKQkvHv3DgUFBSgsLIRQKISmpib09PRgbm4Oc3NzWFhYwNzcHDY2NtDW1ub9bagUf39/eHt7Y9CgQdi5cyc0NDR4R1Iq58+fR/fu3dGzZ08cOHBAIZZUSElJgbm5OdasWYOff/6Zd5wvSk1NxaRJk7Bv3z54eXlhx44dsLCw4B1LYbx48QLW1tbYuXMnfvjhhxI/LiYmBk2bNkXbtm3h6+urEK9JeZD6MgkdO3bE7t27pbZQGg9UaqTr5cuXuH37NsLDw4tvKSkpxf8uFAphZmYGU1NTiEQiaGhogDGGwsJCZGRkICkp6aO1fjQ1NVG/fn04OzvD2dkZLi4ucHJyokOcZXTr1i106NAB7u7uOH78OD2PZXTs2DH06dMHEydOxJo1a8q0yKY0bd26tXgpiypVqnDNUhKnT5/GTz/9hNzcXGzYsAGDBg3i/hwqivbt20MoFCIwMLBE9//w4QOaNm0KDQ0N3Lp1S63ex2jtp8+gUlM+EokEEREROH36NE6dOoW7d+8CAMzNzYuLSKNGjWBtbQ0LCwtUrlz5m3sGMjIy8OrVK7x69QoxMTHF5ej+/fsoLCyEiYkJunTpAm9vb3Tu3Jl+biUUFxeHpk2bwsHBAQEBAXJbv0lVbd68GePHj8e6deswceJErllatWoFQ0ND+Pv7c81RGu/fv8eECRNw8OBBdO7cGatXr0bdunV5x+Ju586d+PHHH/HixYtv7sVKT0+Ht7c37t27hzt37sDe3l5OKRUDrf30GTSnpmweP37MpkyZwiwsLBgAZmxszAYOHMh8fHzYq1evZDJmTk4OCwkJYXPmzGENGzZkAJiWlhbr3LkzO3HiBCsoKJDJuKogNTWV1alTh9WsWVNprymliH755RcmFAq5rhcVFxcnkyvSyoufnx+zs7NjGhoabMyYMWp3Fev/Sk1NZdra2mzVqlVfvd/r16+Zk5MTMzIyYteuXZNTOsVCaz99BpWakissLGQnT55knTp1YgBYxYoV2cSJE9mVK1e4rJPz/PlztnHjRta8eXMGgFWrVo0tXLhQZqVKWYnFYta5c2dmbGzMYmJieMdRKYWFhczb25vp6+tzuzbM4sWLmZ6eHsvMzOQyvjTk5uay1atXMyMjI2ZgYMCWL18ul3WrFFXPnj2/ejmUp0+fsho1ajBzc3N27949OSZTLFRqPoNKzbcVFhayPXv2MFtbWwaANW3alO3du1ehLr8dERHBfvzxR6arq8s0NTXZiBEj6EJy/2/lypUMAF0pWEYyMjJY7dq1WcOGDVlubq5cx5ZIJKxOnTps4MCBch1XVt6+fct+/vlnpqGhwWxsbNiff/6plmdJFV0R+MGDB5/82927d1nVqlWZvb09i4uL45BOcVCp+QwqNV8mkUiYn58fq1evHgPAevbsycLCwnjH+qrU1FS2atUqVqlSJaajo8OmTZvG3r17xzsWN+Hh4UxLS4v98ssvvKOotIiICCYSidiUKVPkPi4A5u/vL9dxZe3Ro0esW7duDABr1qwZu3HjBu9IcpWbm8uMjY3Zb7/99tHXr1y5wgwNDZmzs7PaH6ZjjErNZ1Gp+bx79+6xFi1aMACsXbt27Pbt27wjlUpaWhqbO3cu09PTY0ZGRmz16tVqt0BjZmYmc3BwYE5OTgp3TRVVtHr1agaAnT9/Xm5jTpkyhVWuXFll55NdunSJNWrUiAFg7du3ZwEBAWqz5+bHH39kNjY2TCwWs/z8fDZv3jymoaHB3N3dWXp6Ou94CoFKzWdQqflYfn4+W7hwIdPS0mL16tVjFy5cUOpfIq9fv2Zjx45lAoGANW/eXK3mlBQdjlOn75knsVjMOnXqxMzMzOT2KbpGjRps9OjRchmLl8LCQnbkyBHm5OTEADAXFxd2/Phxlf+QEhAQwAAwX19f5urqyjQ0NNj8+fO5zF9UVFRqPoNKzT/u3bvHnJycmIaGBps1a5bc5wfI0rVr15i9vT3T0dFhq1atUvlfiCdPnmQA2B9//ME7ilpJSkpilStXZl27dpX5h4HY2FgGgJ08eVKm4ygKiUTCzp8/z9q2bcsAMDs7O7Z27VqV/d2dlpbGtLS0mKamJrO3t2e3bt3iHUnhUKn5DCo1f9uyZQvT0tJi9evXZ6GhobzjyERWVhabPHkyEwgErG3btuzt27e8I8lEVlYWs7KykssbK/lU0SRPWZeNzZs3M01NTbX83XX79m02YMAApqmpyQwMDNiECRNYVFQU71hSIZFI2NmzZ5mDgwMTCATM2tqaZWVl8Y6lkKjUfIa6l5r8/Hw2evRoBoCNHz9epfbOfElQUBCrXLkys7W1VcnTIefOnctEIhGLjY3lHUUtSSQS1qlTJ2ZnZyfT05K9vb2Zm5ubzLavDF68eMFmzZrFKlWqxACwevXqsUWLFinlCtV5eXls9+7drH79+gwAa926NZsxYwbT0tJiGRkZvOMpJCo1n6HOpebt27esTZs2TEtLS+0OU8THx7NGjRoxPT09duLECd5xpObZs2dMR0eHzZw5k3cUtfbw4UOmqanJli5dKpPt5+XlMX19fbZkyRKZbF/Z5OXlsdOnT7MBAwYwPT294rk3q1atUvhLO6SmprLly5cXX8i0W7duLDg4mEkkEhYTE8MAsNOnT/OOqZCo1HyGupaap0+fsurVq7MqVaqo7dUoMzMzWe/evRkAtnr1at5xpKJnz57MwsKCPtkpgEmTJjE9PT324sULqW87KCiIAVD4SyzwkJWVxY4cOcK+//57pq2tXbzXY82aNSw0NFQhzhTLzc1lgYGBbPz48UxfX5+JRCI2cuTITy7gKJFImI2NDRs/fjynpIqNSs1nqGOpiYmJYdWqVWP29vbs+fPnvONwJZFI2IwZMxgAtmjRIt5xyuXSpUtKfbl8VZOamsoqV64skwvjzZw5k1WuXJmJxWKpb1uVfPjwge3Zs4d17ty5uODo6emxDh06sHnz5rHAwEC5fQB4+vQp27x5M+vatSvT1dVlAJi5uTmbNWsWS0pK+uLjfvrpJ2Zvby+XjMqmpO/ftKClCnvy5AnatGkDExMTBAYGwtzcnFsWxhiyC7IBALpaulxX6V28eDHmzJmDRYsWYfbs2dxylBVjDC4uLtDW1saNGzeUesVjRXpdlNf//vc//Pjjj4iIiICTk5PUtuvi4gIHBwccPHhQattUeIwB2X+/LqCrC5TydZGXl4eIiAhcu3YN169fx40bN/D+/XtoaGjAyckJLi4usLW1hY2NTfGtatWqEAqFpRrnw4cPePr0KeLi4hAXF4fY2FgEBwfjyZMn0NTURKtWrdC5c2d4enrC0dHxm6/vEydOoGfPnoiLi0P16tVLlUXV0Srdn6FOpSY+Ph6tW7eGnp4egoKCYGZmxjVPVn4W9JfpAwAyZ2ZCT6THNc+iRYswd+5crFq1ClOnTuWapbQuXrwIDw8PBAQEwN3dnXecclG010V5FBYWolatWmjSpAl8fHykss23b9/CzMwMe/bswZAhQ6SyTaWQlQXo//26QGYmoFe+14VEIkFMTAyuX7+O69ev4+7du4iPj0d6enrxfUQiEaysrGBjY4OKFSsWf/2/b5GFhYV48eIF4uLikJqaWvx1Q0ND1KhRA02aNEHnzp3Rvn37Ur/PpKWloVKlSti8eTNGjRpVxu9WNZX0/VtTjpmInGRkZKBr167Q1NTEpUuXuBcaRTR79mxkZ2fjl19+gZ2dHb7//nvekUpsxYoVcHZ2RocOHXhHIf+iqamJX375BT///DOWLFmCGjVqlHubt27dAmMMbdq0kUJC9SUUClG3bl3UrVsXP/30U/HXP3z4gPj4eMTHxyMhIaH4zx8+fPhor8p//+zk5ISePXvCzs4ONWrUgJ2dHUxMTMq9p9HIyAiNGzdGSEgIlZoyolKjYiQSCYYMGYL4+HjcvHkTFhYWvCMpJIFAgKVLl+Lp06cYPHgwQkJC0KBBA96xvik0NBSXL1/GkSNHlPpQjar64YcfMH/+fKxatQpbt24t9/ZCQ0NRuXJlWFtbSyEd+S9jY2MYGxujYcOGvKMUc3FxQXBwMO8YSqt0BxCJwps/fz78/Pxw8OBB1KtXj3cchSYQCLB7927Y29uje/fuSElJ4R3pm1asWIGaNWuiR48evKOQz6hQoQImTpyI3bt3Izk5udzbCwsLg6urKxVYNeLi4oJHjx4hMzOTdxSlRKVGhfj6+mLRokVYsmQJunXrxjuOUtDT04Ofnx+ysrLQu3dviMVi3pG+6PHjxzhx4gSmTZsGDQ0N3nHIF4wdOxZaWlpYv359ubbDGENYWBhcXFyklIwoAxcXFzDGEBkZyTuKUqJSoyLevHmDH3/8Ed9//z1mzJjBO45Ssba2xtGjRxEcHIx169bxjvNFW7ZsQeXKldVrwqgSMjExwU8//YTt27cjPz+/zNtJTEzE27dvqdSombp160JHRwdhYWG8oyglKjUqgDGGsWPHQiAQYNu2bbSrugzatGmDiRMnYvbs2fjrr794x/lEYWEh/vzzTwwcOBA6Ojq845BvGD58ON6/fw9/f/8yb6PoTc3Z2VlasYgS0NTUhJOTE5WaMqJSowKOHDmC48ePY8uWLahSpQrvOEpryZIlsLKywg8//KBwh6EuXryIN2/eYPDgwbyjkBKoV68eGjVqhAMHDpR5G2FhYbCwsKDJ/mrIxcWFSk0ZUalRcikpKRg3bhx69+6N3r17846j1HR1dbFr1y7cunULGzZs4B3nI/v370fdunXRqFEj3lFICQ0ePBinT5/+6FompUHzadSXi4sLHj9+jLS0NN5RlA6VGiW3ZMkSFBQUYNOmTbyjqIRWrVph9OjRWLhwYZnfjKQtPT0dJ0+exODBg+nQohLp378/CgsLcfTo0VI/liYJq7ein3tERATnJMqHSo0Si4+Px5YtWzBt2jQ67CRF8+bNQ0FBAVasWME7CgDg+PHjyMvLw8CBA3lHIaVgbm4Od3d37N+/v9SPffXqFVJTUxXq+ilEfhwcHKCtrY2oqCjeUZQOlRolNnfuXJiYmGDy5Mm8o6gUMzMzTJkyBevXr8fLly95x8HRo0fh5uYGKysr3lFIKQ0aNAjXr1/Hq1evSvW4p0+fAgBq1qwpi1hEwWloaKB69eqIi4vjHUXpUKlRUvfv38f+/fsxd+5c6JVzXRTyqV9++QV6enpYsGAB1xx5eXkIDg6Gl5cX1xykbDp37gwAuHTpUqkeV/RmRosaqq8aNWpQqSkDKjVKauXKlbC2tsbIkSN5R1FJhoaGmDFjBvbs2YPXr19zy3Hr1i1kZ2cr/cKV6qpy5cpo1KgRAgMDS/W4uLg4WFhYoEKFCjJKRhSdnZ0dlZoyoFKjhFJSUnD48GGMHTsWIpGIdxyVNXLkSGhqamLnzp3cMgQGBqJSpUo0t0KJubu7IzAw8JPVnr8mLi4OdnZ2MkxFFF1RqSnN64ZQqVFKu3fvBvD3Bb6I7BgbG2PgwIHYvn07CgsLuWQIDAxEhw4dIBTS/6rKyt3dHa9evUJMTEyJH0OlhtjZ2SE3N5frnmJlRL8plYxEIsG2bdvQp08fmJqa8o6j8saMGYPExEScPXtW7mOnpaXhzp07dOhJybVq1QoikahUh6CePn2KGjVqyDAVUXRFP/+iSeOkZKjUKJnLly8jLi4OY8aM4R1FLTRu3BhNmzbF9u3b5T52cHAwJBIJOnToIPexifTo6emhRYsWJZ4snJmZiTdv3tCeGjVXNEmc5tWUDpUaJePr6wtbW1s0a9aMdxS1MWDAAAQGBiI9PV2u40ZGRsLU1JTOgFEBTZo0KfGqy8+ePQMAKjVqTldXF1WrVqVSU0pUapQIYwynT5+Gt7c3XVlWjrp164aCggJcvHhRruNGR0fD0dGRftYqwNHREQkJCSW67H1RqaEyS+gMqNKjUqNE7t27h8TERHh7e/OOolaqV68OR0dHnD59Wq7jFpUaovyKfo7379//5n3fvn0L4O/TwYl6q1KlClJSUnjHUCpUapTIqVOnYGRkBDc3N95R1I63tzfOnj0rt7OgcnJyEBsbS6VGRdSuXRsaGhqIjo7+5n1TU1NhaGgITU1NOSQjiszExERh1qBTFlRqlEhgYCDc3d2hpaXFO4ra8fT0xLt373Dv3j25jPfo0SNIJBLUr19fLuMR2dLW1katWrVKtKcmNTUVJiYmckhFFB2VmtKjUqMkxGIxIiMj0aRJE95R1FLjxo2hoaGB8PBwuYxX9Im+Xr16chmPyJ6jo2OJ99RQqSEAlZqyoFKjJB4/fozMzEw4OzvzjqKWKlSogLp168qt1Dx58gSWlpYwMDCQy3hE9urUqYPHjx9/835UakiRolJDVxUuOSo1SqLozbRx48ack6gvZ2dnuZWa5ORkmJuby2UsIh9Vq1bF27dvIZFIvno/KjWkiImJCQoKCpCdnc07itKgUqMkwsPDYWdnR7/sOHJ2dkZUVBTy8/NlPtabN29QpUoVmY9D5KdKlSoQi8XfPJxApYYUKXod0CGokqNSoyRiY2NRp04d3jHUWp06dVBQUIDExESZj0WlRvUU/TzfvHnz1ftRqSFFqNSUHpUaJZGUlAQLCwveMdRa0fP/6tUrmY+VnJwMMzMzmY9D5Kfo55mcnPzV+1GpIUWo1JQelRol8erVKyo1nBXNcUlKSpL5WLSnRvWUdE9NRkYGDA0N5RGJKLii10FJrkRN/kalRgmIxWKaOKoAjIyMoKOjI/M9NdnZ2cjKyqJSo2IMDQ0hEom+uaemsLCQLrxHAKD4dSAWizknUR5KV2q2bNmC6tWrQ0dHB87Ozrh27RrvSDJXdMYElRq+BAIBzM3NZb6nJisrCwCgr68v03GIfAkEAujr63/zTBaxWAwNDQ05pSKKrOh1QKWm5JTq48Dhw4cxadIkbNmyBS1btsT27dvh6emJhw8fwtramnc8mSn6JajU1yz593UWsrKAAn5RAAC6ukAZFoo0MDCQ+emVRb/A1OLTuoq8LkpKU1Pzq0ttFJ3uLRTy+bzJGEN2gQKcPpyfBfz/hdN1GYO6LulKpab0lOq35po1azBixAiMHDkSALBu3TpcuHABW7duxbJlyz65f15eHvLy8or/np6eLres0lT0S1Cp3+T+XQTMzPi/eWVmAnp6pX6YlpaWzNd/Uomfd0mpyOuipL5VaorevHjtqckuyIb+MgXZQzjr7/9kFmRDDwqSSc6o1JSe0hx+ys/PR3h4ODp16vTR1zt16oSQkJDPPmbZsmUwMjIqvllZWckjqtQVvaAFMvwESUpGKBTK/BdM0ad1+nmrHoFA8NWL7xVdOZZ+9gT453VAVxQuOaX5KJiSkgKxWPzJaa5mZmZ4/fr1Zx8zc+ZMTJkypfjv6enpSllsVGGymK6RKTIn/D1BUneqbHfxlyyQbpkeJo9JnKrw8y4pVXldlJRYLP7q66fok/m3rjosK7pausicmcll7I8wVrwXT9fIlHMYfopeBzTHquSUptQU+e8nGMbYFz/VaGtrQ1tbWx6xZKpoVW55XMlWVgRCIfRMlP9snvz8fJmXmqJfYLI+zKUIVOV1UVLfKsVFc2l4FVqBQAA9kewOv5WKtnoecvq3otcBrzlWykhpnilTU1NoaGh8slfmzZs3Kn+RskqVKgH4e28V4evt27cwNZXtJ8eiEltQwHuCCZG2goKCr5YagUDwzUNURH3wnmOljJSm1IhEIjg7OyMgIOCjrwcEBKBFixacUsmHgYEB9PT05HIlW/JlBQUFePv2rcwvgmhkZASBQIB3797JdBwiXwUFBUhLSyv+kPIlGhoaanHokXwblZrSU6rDT1OmTMHgwYPh4uKC5s2bY8eOHUhISMDo0aN5R5M5CwsLuVzJlnxZcnIyGGMyLzUaGhowNTX95pVniXIp2tP6rYsq6ujoIDc3Vx6RiIIreh2owjQKeVGqUtO3b1+8e/cOCxcuRFJSEurXrw9/f3/Y2NjwjiZz5ubmtKeGs6JSKY+LIJqZmX3zyrNEuRT9PL91uNzY2JjW+iEA/lnzidYCKzmlKjUAMHbsWIwdO5Z3DLmrVq0aEhISeMdQa0Wrc1erVk3mY1WpUoX21KiYop/nt/bUmJiYUKkhAKjUlIXSzKlRdw0aNEBUVBRNIOQoMjISZmZmqFy5sszHolKjeop+nt96/VCpIUWo1JQelRol4eLigoyMDDx58oR3FLUVHh4OZ2dnuVwYrUqVKnT4ScUkJydDX18fut+4Fg6VGlKESk3pUalREo0bNwbw9xsrkT/GWHGpkQdLS0skJCTQlURVSEJCQokOXVKpIUVSU1NhYGCgHkumSAmVGiVRsWJFVK9enUoNJy9fvsSbN2/kVmrq1auHzMxMmkelQu7fv4/69et/835UakiR1NRU2ktTSlRqlEizZs0QHBzMO4Zaunr1KgCgSZMmchmv6M0vOjpaLuMR2YuOjqZSQ0qFSk3pUalRIl5eXggPD8fLly95R1E7p06dgrOzs1xO5wYAKysrGBkZUalREcnJyXj79i0cHR2/ed+iUkOHHgmVmtKjUqNEPD09oaGhgTNnzvCOolby8/Nx7tw5eHt7y21MgUCA+vXrU6lREUU/x5KWmvz8fGT//4KORH1RqSk9KjVKpGLFimjdujVOnTrFO4pauXr1KtLT0+VaaoC/D0Hdv39frmMS2bh//z50dHRQo0aNb963aDLxixcvZB2LKLjExES5XBdLlVCpUTLe3t64dOkS0tPTeUdRGydPnoSVlRUaNmwo13EdHR0RExODvLw8uY5LpO/evXuoW7duidbwKSo+T58+lXUsosAYY4iLiytRESb/oFKjZHr37o3CwkIcPHiQdxS1kJ2djYMHD6Jfv35yuT7Nv7Vs2RIFBQW4efOmXMcl0hccHIyWLVuW6L4WFhYQiUSIi4uTcSqiyF6/fo2cnBzY2dnxjqJUqNQoGUtLS3h7e2PLli00kVAOfHx8kJaWxmXR1AYNGsDU1BSBgYFyH5tIT1xcHJ49ewZ3d/cS3V9DQwO2trZUatRc0c+fSk3pUKlRQmPHjsX9+/dx/fp13lFUGmMMmzdvhqenJ5dfLEKhEB06dKBSo+QCAwOhoaGBNm3alPgxdnZ2VGrUXNHPv3r16pyTKBcqNUqoffv2qFWrFrZs2cI7ikoLDQ1FREQE1wVU3d3dERoaig8fPnDLQMonMDAQTZo0gZGRUYkfU6NGDZpTo+aePn2KqlWrQk9Pj3cUpUKlRgkJhUKMGzcOR48epbWgZGjZsmWoUaMGOnfuzC2Du7s7JBIJrly5wi0DKTuxWIxLly6V+NBTkaI9NXSIWX3FxcXRoacyoFKjpH766SeYm5tj9uzZvKOopJs3b+LkyZNYsGBBic5YkRVbW1vUqFEDAQEB3DKQsrt79y7ev39fplKTnZ1NK7WrMSo1ZUOlRknp6OhgwYIFOHLkCK0HJWWMMcyYMQMNGjRA//79ecdBly5dcPLkSYjFYt5RSCkdP34cJiYmaNasWakeV/RmRvNq1BeVmrKhUqPEhgwZgjp16mDmzJm8o6iU8+fP4+rVq1i2bBmEQv7/iwwaNAhJSUm4fPky7yikFCQSCQ4ePIg+ffpAJBKV6rE1atSAQCDAo0ePZJSOKLIPHz4gKSkJ9vb2vKMoHf6/sUmZaWpqYunSpQgICICfnx/vOCohNzcXU6dOhZubGzw9PXnHAQC4urqiVq1a2L9/P+8opBSuXr2KhIQEDB48uNSP1dPTQ+3atWkvrJqKiIgAADg7O3NOonyo1Ci57t27o2vXrhg9ejTev3/PO47SW7BgAZ4+fYotW7bI/WJ7XyIQCDB48GCcOHECWVlZvOOQEjpw4ACqV6+OFi1alOnxLi4uCAsLk3IqogzCwsKgr6+PWrVq8Y6idKjUKDmBQIDt27cjNzcXEydO5B1Hqd25cwe///475s+fj3r16vGO85GBAwciKysLvr6+vKOQEsjJycHRo0cxaNCgMpdjFxcX3Lt3D/n5+VJORxRdWFgYGjduzPUkBWVFpUYFWFhYYP369Thw4AAtdllGubm5GDZsGBo3boxp06bxjvOJ6tWro1WrVnQISkmcPn0a6enpGDRoUJm34eLigry8PDx48ECKyYgyCAsLg4uLC+8YSolKjYoYPHgwunbtipEjRyIhIYF3HKUzZcoUPH36FLt374ampibvOJ81fPhwBAQEICYmhncU8g2bNm1CixYtynX4oFGjRhAKhXQISs28e/cOz549o1JTRlRqVIRAIMCuXbugq6uL7t2709yLUti2bRu2bt2KTZs2oX79+rzjfNGAAQNQtWpVrFy5kncU8hUhISG4du0apk+fXq7t6Orqol69elRq1EzR5HAqNWVDpUaFVK5cGadOncKTJ0/www8/0NVISyA4OBg///wzxo8fjx9//JF3nK/S1tbG5MmTsX//frx8+ZJ3HPIFK1asQJ06ddCtW7dyb4smC6ufsLAwGBkZoUaNGryjKCUqNSqmQYMG2LdvH44ePYrFixfzjqPQnj17hp49e8LNzQ1r1qzhHadERo0aBV1dXaxbt453FPIZDx48wKlTpzB9+nSpXOPI1dUVUVFRyM3NlUI6ogzCwsLg7OysENfIUkb0rKmgHj16YOHChZg7dy62bdvGO45CevnyJTp27AhjY2McOXIEWlpavCOViKGhIcaMGYNt27YhNTWVdxzyH7///jssLS0xYMAAqWzPxcUFhYWFxdctIaqNMYbbt2/ToadyoFKjombPno2JEydizJgx2LVrF+84CiUpKQkdOnRAfn4+AgMDUalSJd6RSmXixIkoKCjA5s2beUch/xIfH49Dhw5hypQppb6C8Jc4OTnByMiI1v5SEw8fPsSrV6/Qvn173lGUFpUaFSUQCLB27VqMGTMGI0aMoD02/y8xMRFt2rRBZmYmLl++DFtbW96RSq1q1aoYNWoUVqxYgaSkJN5xyP/79ddfYWpqKtW5WZqamnB3d8eFCxektk2iuC5cuAAdHR24ubnxjqK0qNSoMIFAgM2bNxfvsVm4cKFaTx6OiopC69atkZ+fj6tXr6JmzZq8I5XZ/Pnzoa2tTet+KYjg4GAcPnwYy5cvh76+vlS37eHhgdu3b9PhRjVw4cIFuLm5oUKFCryjKC0qNSquaI/NokWLMG/ePPTt21ctT/f29fVFixYtYGxsjGvXrin96rcmJiZYsmQJ9u7di9u3b/OOo9bEYjEmTpyIJk2alGmdp2/x8PCARCLBpUuXpL5tojhycnJw9epVeHh48I6i1KjUqAGBQIDZs2fjxIkT8Pf3R6tWrRAfH887llwwxrBo0SL06NEDnp6euHHjBqysrHjHkoqRI0eiUaNGmDBhAiQSCe84auuPP/7AvXv3sGHDBpmcsWJtbY3atWvTISgVd/XqVeTm5lKpKScqNWrk+++/x82bN/Hhwwe4urqq/Mrer1+/xnfffYe5c+di4cKFOHLkCPT09HjHkhoNDQ1s2LABd+7coeUTOElNTcXs2bMxbNgwNG3aVGbjeHh44OLFi2p9+FjVXbhwAdWqVUPdunV5R1FqVGrUjKOjI0JDQ9GsWTN89913GDhwIN69e8c7llQxxvDnn3+iXr16uHnzJvz8/DBnzhyFWXVbmlq3bo1+/fph2rRpeP36Ne84amfKlCnIz8/HsmXLZDqOh4cHEhIS8Ndff8l0HMLPhQsX4OHhoZK/p+SJSo0aMjU1hZ+fH/bt2wd/f3/Uq1cPJ0+e5B1LKl6/fo0ePXpgwIAB6NixIx4+fAhvb2/esWRq/fr1EAqF+OGHH+gwlBwdPnwYe/bswYYNG1C1alWZjtWmTRtoa2vTISgVlZiYiIcPH9KhJymgUqOmBAIBBg8ejIcPH6JJkyb4/vvv4e7urrSXZM/IyMD8+fNhb2+PGzdu4NixY/Dx8YGpqSnvaDJXpUoV7N27F+fPn8eGDRt4x1EL8fHxGDVqFPr27YuhQ4fKfDxdXV24ubnh9OnTMh+LyN+ZM2egoaEBd3d33lGUHpUaNWdubg4/Pz/4+fkhKSkJrq6u6N27Nx4/fsw7Wonk5eVh/fr1sLOzw/LlyzF69GjExMSgZ8+evKPJlYeHByZPnoxff/0V9+7d4x1HpYnFYgwaNAhGRkbYtm2b3A4X9O3bF5cvX8arV6/kMh6Rn4MHD6Jjx46oWLEi7yhKj0oNgUAggLe3N6KiorB7927cvn0bdevWRd++fREcHKyQkxOTk5OxdOlS2NvbY8qUKfD29saTJ0+wcuVKtf3FsGzZMtSpUwf9+/dHdnY27zgqa+nSpQgJCcGBAwdgbGwst3F79uwJLS0t+Pj4yG1MInvPnj3DjRs3MGjQIN5RVANTI2lpaQwAS0tL4x1FoeXk5LCNGzcyBwcHBoDVrVuXbdq0ifvzJpFI2LVr11j//v2ZlpYW09HRYcOHD2cPHjzgmkuRPHjwgOno6LAhQ4YwiUTCO47KuXTpEtPQ0GBz5szhMn7Pnj2Zk5MTl7GJbCxevJjp6uqyjIwM3lEUWknfv6nUkC+SSCQsMDCQ9ejRg2loaDCRSMQ6d+7MtmzZwhITE+WSITc3l50/f56NHTuWWVlZMQCsZs2abM2aNezdu3dyyaBsDhw4wACwZcuW8Y6iUh49esSMjY1Zp06dWEFBAZcMJ06cYACoyKsIiUTC6tSpwwYMGMA7isIr6fu3gDEFPLYgI+np6TAyMkJaWhoMDQ15x1EqL168wLFjx3D69GkEBwdDLBbDyckJbm5ucHZ2houLC2rVqgUNDY1yjfPu3TuEh4cjPDwcd+7cQWBgIDIzM2FjYwNvb2989913aNu2rUwucqZK5s6di0WLFuHo0aPo1asX7zhKLyUlBc2aNYO2tjZCQkJgZGTEJUdeXh6qVq2KsWPHYsmSJVwyEOmJjIxE48aN4e/vD09PT95xFFpJ37+p1JBSS01Nxfnz53H27Fncvn0bsbGxAAA9PT00bNgQVlZWsLCwgLm5OczNzVG5cmVoaWlBU1MTEokEhYWFyMjIQFJSEpKSkvDq1SskJSXh0aNHeP78OQDA0NAQjRs3hru7O7y9vVG/fn26fkMpSCQSDBw4EL6+vrhw4QLatGnDO5LSysrKQvv27fH8+XPcvHmT+xIbP/30EwICAvD06VMq90pu6tSp2L9/P169egVNTU3ecRQalZrPoFIjGx8+fEBERATCw8MRFRWFly9fFpeV9PT0Lz5OU1MTVatWLS5ANWvWLN7rU6NGDfqFXU55eXnw8vJCWFgYrl69igYNGvCOpHQKCgrg7e2N69evIzg4GI0bN+YdCcHBwWjbti2uXbuGVq1a8Y5DykgsFsPKygq9evWiSzGUAJWaz6BSI3/Z2dlISUlBYWEhCgoKoKGhAU1NTejp6aFSpUpUXGQsPT0d7dq1Q0JCAi5cuKAQb8rKIicnB3369MGFCxfg7++vMNcQkUgksLW1haenJ7Zv3847DimjwMBAdOzYEbdu3ZLpEhuqgkrNZ1CpIero/fv38PT0RExMDM6cOYPWrVvzjqTwMjIy4O3tjdu3b8PX11fhrvQ6b948rFq1Ci9evICJiQnvOKQMunfvjqdPnyI6OpoOrZdASd+/6WMyISquYsWKCAwMhIuLCzp16gR/f3/ekRRaSkoK2rdvj4iICFy8eFHhCg0AjB07FoWFhdixYwfvKKQMHj9+jNOnT2PKlClUaKSMSg0hasDAwABnz56Fh4cHunfvjsOHD/OOpJBevnyJNm3aID4+HkFBQQo7Z8XMzAyDBg3Chg0bkJ+fzzsOKaV169ahcuXKGDBgAO8oKodKDSFqQkdHB0ePHkW/fv3Qv39/LF68mBbA/Jdbt26hefPmyMjIwLVr1+Dk5MQ70ldNmTIFr169wpEjR3hHIaXw7t077NmzB+PGjYOOjg7vOCqHSg0hakRLSwt79+7FnDlzMHfuXHh5eSElJYV3LK4YY1i/fj3c3NxgaWmJkJAQODg48I71TfXq1YOHhwfWrFmjkEuZkM/bvn07GGMYM2YM7ygqiUoNIWpGKBRiwYIFOH/+PMLCwuDk5ISbN2/yjsVFeno6+vTpg0mTJmH8+PEICgqCpaUl71glNmXKFERGRiI4OJh3FFICeXl52LhxI4YMGYLKlSvzjqOSqNQQoqY6deqEyMhIWFtbw83NDWvXrlWrw1GRkZFwcXHBxYsXcezYMaxZswYikYh3rFLp2LEj6tevjzVr1vCOQkrg8OHDeP36NSZNmsQ7isqiUkOIGrO0tERQUBAmTJiAKVOmoHnz5oiIiOAdS6bS09MxefJkuLi4QE9PD+Hh4ejZsyfvWGUiEAgwZcoUnD59GjExMbzjkK+QSCRYvXo1unTpgjp16vCOo7Ko1BCi5rS0tLB69Wpcu3YN2dnZcHV1xYQJE5CWlsY7mlQxxnDkyBHUqVMHO3bswLJly3Dnzh3UrFmTd7RyGTBgAKytrTF79mzeUchXHDlyBFFRUZgxYwbvKCqNSg0hBADQqlUrREREYOXKldi9ezccHBxw8OBBlTgkFRMTAw8PD/Tt2xdNmzbFo0ePMH36dGhpafGOVm7a2tpYvHgxjh8/jpCQEN5xyGfk5eVh5syZ8Pb2potfyhiVGkJIMS0tLUyZMgWPHj2Cm5sbBg0ahPr162Pv3r0oKCjgHa/UIiMj0adPH9StWxexsbE4c+YMTpw4AWtra97RpGrgwIFo2LAhpk2bRmdCKaAtW7YgISEBy5cv5x1F5VGpIYR8wtLSEkeOHEFISAhq1qyJYcOGoWbNmti0aROys7N5x/sqxhiuXr0KT09PNG7cGOHh4di6dSsePnwILy8v3vFkQigUYuXKlQgJCcHJkyd5xyH/kpqaikWLFmHkyJE0l0YOaO0nQsg3RUdHY/ny5fDx8UGlSpUwbNgw9O/fH40aNVKYy7ynpKTg+PHj2Lt3L27evIn69etj5syZ6NOnDzQ1NXnHk4vOnTsjLi4ODx48UIlDa6pg+vTp2LJlC2JjY1G1alXecZSWyq39tGTJErRo0QK6urowNjbmHYcQteLo6IiDBw/iyZMn6Nu3L3bt2oXGjRujbt26WLhwIZ48ecIlV0ZGBg4cOAAvLy+Ym5tj3LhxMDAwwKlTp3Dv3j0MGDBAbQoNAKxYsQKxsbH4448/eEchAOLj47Fhwwb88ssvVGjkRGn21MybNw/GxsZ48eIFdu7ciQ8fPpR6G7SnhhDpKCgoQGBgIP7880/4+voiMzMTDRs2hJubG1q0aIGWLVvCyspK6uNmZWXhzp07uHHjBm7cuIHg4GDk5OSgZcuW6N+/P3r37o0qVapIfVxlMmzYMPj7++Pp06cwMDDgHUetDRkyBBcvXsSTJ0/oZ1FOJX3/VppSU2TPnj2YNGlSiUpNXl4e8vLyiv+enp4OKysrKjWESFFOTg7Onj2LM2fO4MaNG4iNjQXw97ycli1bwtHREVZWVsU3S0vLr655I5FIkJycjMTERCQmJuLFixeIjY3FzZs3cffuXYjFYhgZGaF58+Zo3749+vTpAxsbG3l9uwovMTERtWrVwrhx47Bq1SrecdRWSEgIWrVqhS1btmD06NG84yg9KjUA5s+fjwULFnzydSo1hMjOmzdvEBISgpCQENy4cQN//fUX3r1799F9KleuDH19fWhpaUFLSwtisRgFBQXIy8tDcnLyR2da6ejowNbWFk2aNEHLli3RokUL1K1bF0Kh0hw9l7sVK1bgt99+w61bt+Dq6so7jtrJzc2Fk5MTDA0NERISAg0NDd6RlB6VGtCeGkIURXZ2Nl68ePHR3pesrCwUFBSgoKAAGhoa0NLSgkgkQtWqVT/as1OpUiWFmYysLAoLC9GkSRMUFhYiLCxM6ZZ/UHZz5szBihUrEBERgfr16/OOoxJKWmq4zqD70p6UfwsNDYWLi0uZtq+trQ1tbe0yPZYQIj26urqoVasWatWqxTuKWtDU1MTOnTvh6uqK5cuXY+7cubwjqY179+5h+fLlmD17NhUaDrjuqUlJSUFKSspX72Nra/vR8ffS7Kn5L5ooTAhRJ7NmzcLvv/+O27dvo3HjxrzjqLy8vLziw320h0y6lGJPjampKUxNTXlGIIQQlTVv3jz4+/tj8ODBCA8P/+oEbVJ+c+fORUxMDEJDQ6nQcKI0M+0SEhJw9+5dJCQkQCwW4+7du7h79y4yMzN5RyOEEIUkEomwf/9+PH36FL/99hvvOCrt2rVrWLlyJRYtWoSGDRvyjqO2lGai8LBhw7B3795Pvn7lyhW0bdu2RNugw0+EEHW0du1aTJkyBb6+vvjuu+94x1E5ycnJcHFxga2tLYKCguhsJxlQ2bOfyoNKDSFEHTHG0KdPH5w/f754CQkiHXl5eWjfvj2ePXuGsLAwWFhY8I6kklRumQRCCCFlIxAIsGfPHtjZ2cHb2/uT6waRsmGMYezYsQgPD4evry8VGgVApYYQQtSAnp4e/Pz8kJGRgT59+nx0gUNSNhs3bsSuXbuwY8cONG3alHccAio1hBCiNmxtbXHs2DFcvXoVU6dO5R1HqV26dAlTpkzBlClTMGTIEN5xyP+jUkMIIWqkTZs22LBhAzZu3Ij//e9/vOMopadPn6J3797o0KEDVqxYwTsO+Reu16khhBAif2PGjMG9e/cwduxYmJmZoVu3brwjKY1Xr17B09MTpqam8PHxgaYmvY0qEtpTQwghamjjxo3o1q0bevbsiVOnTvGOoxRevnyJtm3bIjc3F+fOnYOJiQnvSOQ/qNQQQoga0tLSgo+PD7y9vdGrVy/4+fnxjqTQXr58iXbt2iE3NxdBQUGoUaMG70jkM6jUEEKImtLS0sKff/6J7t27o3fv3lRsvqBoD01eXh6CgoJgZ2fHOxL5Aio1hBCixrS0tHDo0CF0794dvXr1wsmTJ3lHUigvXrxA27ZtkZ+fjytXrlChUXBUagghRM0VFZvvv/8evXv3xsGDB3lHUgiPHz8uLjS0h0Y5UKkhhBACLS0tHDx4EAMGDMCgQYMwdepUFBYW8o7FzZkzZ+Dq6gpNTU0EBQWhevXqvCOREqBSQwghBMDfxWbPnj1Yt24d1q9fDw8PD6SkpPCOJVcSiQQLFy5Et27d0LZtW9y5c4cKjRKhUkMIIaSYQCDAxIkTERgYiKioKLi4uCAyMpJ3LLlIT09Hjx49MG/ePCxYsAC+vr60+LGSoVJDCCHkE23btkV4eDhMTU3RokULHDhwgHckmYqJiUHTpk1x5coVnD59GnPnzoVQSG+RyoZ+YoQQQj7L2toa165dQ58+fTB48GD07NkTL1684B1LqvLz87Fs2TI4OTlBIBAgNDQUXbt25R2LlBGVGkIIIV9UoUIF7NmzB3/++Sdu3LiBOnXqYP369SoxifjatWtwcnLCnDlzMH78eNy5cwe1atXiHYuUA5UaQgghXyUQCNCvXz/ExMRgyJAhmDx5Mpo0aYI7d+7wjlYmKSkpGD58ONzc3GBoaIjw8HCsXLkS+vr6vKORcqJSQwghpESMjY2xefNm3Lp1C4wxNGvWDGPHjlWaQ1K5ubnYtm0bateuDV9fX2zbtg03btxAw4YNeUcjUkKlhhBCSKk0adIEoaGhWLNmDQ4dOoTq1atjyJAhuHfvHu9on/Xu3TssXrwYNjY2GDt2LDp37oyYmBiMGjWKJgOrGPppEkIIKTVNTU1MmjQJCQkJ+P333xEUFIRGjRrBw8MDAQEBYIzxjoi4uDj8/PPPsLa2xpIlS/D9998jJiYGBw4cgJmZGe94RAYETBFeeXKSnp4OIyMjpKWl0bUHCCFEigoKCnD06FGsXLkSd+/eRYMGDTBgwAB07doVdevWhUAgkEuOt2/f4ty5c/D19cWpU6dgYmKC8ePHY+zYsahSpYpcMhDpK+n7N5UaQgghUsMYw5UrV7Bp0yZcuHAB2dnZqF69Orp27Ypu3brBzc0N2traUh3vwYMHOH36NM6cOYObN2+CMYYmTZpg2LBhGDp0KHR1daU2HuGDSs1nUKkhhBD5yc3NxZUrV3DmzBmcPn0aiYmJ0NfXR5MmTVCrVq2Pbra2ttDS0vrithhjSE5OxuPHjz+6RUZGIiEhAXp6eujUqRO6du2KLl26oGrVqnL8TomsUan5DCo1hBDCB2MM0dHROHPmDCIjI/H48WM8efIEOTk5AP6eo2NlZQVdXV2IRCJoaWlBLBYjPz8feXl5SEpKQkZGBgBAKBTC1tYWtWrVQp06deDh4YE2bdpAR0eH57dIZKik79+acsxECCFETQkEAjRo0AANGjQo/ppEIsHLly+L97o8f/4ceXl5yM/PR35+PjQ1NSESiSASiVClShU4ODigVq1asLOzk+ohLKI6aE8NIYQQQhRaSd+/6ZRuQgghhKgEKjWEEEIIUQlUagghhBCiEqjUEEIIIUQlUKkhhBBCiEqgUkMIIYQQlUClhhBCCCEqgUoNIYQQQlQClRpCCCGEqAQqNYQQQghRCVRqCCGEEKISqNQQQgghRCVQqSGEEEKISqBSQwghhBCVoMk7gDwxxgD8vYQ5IYQQQpRD0ft20fv4l6hVqcnIyAAAWFlZcU5CCCGEkNLKyMiAkZHRF/9dwL5Ve1SIRCLBq1evYGBgAIFAIJcx09PTYWVlhcTERBgaGsplTEVFz8U/6Ln4Bz0X/6Dn4h/0XPyDnou/99BkZGTAwsICQuGXZ86o1Z4aoVAIS0tLLmMbGhqq7Yvxv+i5+Ac9F/+g5+If9Fz8g56Lf6j7c/G1PTRFaKIwIYQQQlQClRpCCCGEqAQqNTKmra2NefPmQVtbm3cU7ui5+Ac9F/+g5+If9Fz8g56Lf9BzUXJqNVGYEEIIIaqL9tQQQgghRCVQqSGEEEKISqBSQwghhBCVQKWGEEIIISqBSo0cLVmyBC1atICuri6MjY15x5GrLVu2oHr16tDR0YGzszOuXbvGOxIXV69eRbdu3WBhYQGBQICTJ0/yjsTFsmXL4OrqCgMDA1SpUgXfffcd/vrrL96xuNi6dSsaNGhQfGG15s2b49y5c7xjKYRly5ZBIBBg0qRJvKPI3fz58yEQCD66Va1alXcshUelRo7y8/PRu3dvjBkzhncUuTp8+DAmTZqEWbNmITIyEq1bt4anpycSEhJ4R5O7rKwsNGzYEJs2beIdhavg4GCMGzcOt27dQkBAAAoLC9GpUydkZWXxjiZ3lpaWWL58OcLCwhAWFob27duje/fuePDgAe9oXIWGhmLHjh1o0KAB7yjc1KtXD0lJScW36Oho3pEUHyNyt3v3bmZkZMQ7htw0adKEjR49+qOv1a5dm82YMYNTIsUAgPn6+vKOoRDevHnDALDg4GDeURSCiYkJ+9///sc7BjcZGRnM3t6eBQQEsDZt2rCJEyfyjiR38+bNYw0bNuQdQ+nQnhoiU/n5+QgPD0enTp0++nqnTp0QEhLCKRVRNGlpaQCAihUrck7Cl1gsho+PD7KystC8eXPecbgZN24cvLy84O7uzjsKV0+ePIGFhQWqV6+Ofv36IS4ujnckhadWC1oS+UtJSYFYLIaZmdlHXzczM8Pr1685pSKKhDGGKVOmoFWrVqhfvz7vOFxER0ejefPmyM3Nhb6+Pnx9fVG3bl3esbjw8fFBREQEQkNDeUfhqmnTpti3bx9q1aqF5ORkLF68GC1atMCDBw9QqVIl3vEUFu2pKafPTeb67y0sLIx3TO4EAsFHf2eMffI1op7Gjx+PqKgo/Pnnn7yjcOPg4IC7d+/i1q1bGDNmDIYOHYqHDx/yjiV3iYmJmDhxIg4cOAAdHR3ecbjy9PREz5494ejoCHd3d5w9exYAsHfvXs7JFBvtqSmn8ePHo1+/fl+9j62trXzCKCBTU1NoaGh8slfmzZs3n+y9Iern559/xqlTp3D16lVYWlryjsONSCRCzZo1AQAuLi4IDQ3F+vXrsX37ds7J5Cs8PBxv3ryBs7Nz8dfEYjGuXr2KTZs2IS8vDxoaGhwT8qOnpwdHR0c8efKEdxSFRqWmnExNTWFqaso7hsISiURwdnZGQEAAvv/+++KvBwQEoHv37hyTEZ4YY/j555/h6+uLoKAgVK9enXckhcIYQ15eHu8YctehQ4dPzvD54YcfULt2bfz6669qW2gAIC8vD48ePULr1q15R1FoVGrkKCEhAe/fv0dCQgLEYjHu3r0LAKhZsyb09fX5hpOhKVOmYPDgwXBxcUHz5s2xY8cOJCQkYPTo0byjyV1mZiZiY2OL//7s2TPcvXsXFStWhLW1Ncdk8jVu3DgcOnQIfn5+MDAwKN6TZ2RkhAoVKnBOJ1+//fYbPD09YWVlhYyMDPj4+CAoKAjnz5/nHU3uDAwMPplXpaenh0qVKqndfKtffvkF3bp1g7W1Nd68eYPFixcjPT0dQ4cO5R1NsfE9+Uq9DB06lAH45HblyhXe0WRu8+bNzMbGholEIta4cWO1PXX3ypUrn30NDB06lHc0ufrccwCA7d69m3c0uRs+fHjx/xuVK1dmHTp0YBcvXuQdS2Go6yndffv2Zebm5kxLS4tZWFiwHj16sAcPHvCOpfAEjDEm/ypFCCGEECJddPYTIYQQQlQClRpCCCGEqAQqNYQQQghRCVRqCCGEEKISqNQQQgghRCVQqSGEEEKISqBSQwghhBCVQKWGEEIIISqBSg0hRC0JBAKcPHmSdwxCiBRRqSGEcCEWi9GiRQv07Nnzo6+npaXBysoKs2fPlun4SUlJ8PT0lOkYhBD5omUSCCHcPHnyBI0aNcKOHTswcOBAAMCQIUNw7949hIaGQiQScU5ICFEmtKeGEMKNvb09li1bhp9//hmvXr2Cn58ffHx8sHfv3q8WmgMHDsDFxQUGBgaoWrUqBgwYgDdv3hT/+8KFC2FhYYF3794Vf83b2xtubm6QSCQAPj78lJ+fj/Hjx8Pc3Bw6OjqwtbXFsmXLZPNNE0JkhvbUEEK4Yoyhffv20NDQQHR0NH7++edvHnratWsXzM3N4eDggDdv3mDy5MkwMTGBv78/gL8PbbVu3RpmZmbw9fXFtm3bMGPGDNy7dw82NjYA/i41vr6++O6777Bq1Sps2LABBw8ehLW1NRITE5GYmIj+/fvL/PsnhEgPlRpCCHcxMTGoU6cOHB0dERERAU1NzVI9PjQ0FE2aNEFGRgb09fUBAHFxcWjUqBHGjh2LjRs3fnSIC/i41EyYMAEPHjxAYGAgBAKBVL83Qoj80OEnQgh3u3btgq6uLp49e4YXL1588/6RkZHo3r07bGxsYGBggLZt2wIAEhISiu9jZ2eHVatWYcWKFejWrdtHhea/hg0bhrt378LBwQETJkzAxYsXy/09EULkj0oNIYSrmzdvYu3atfDz80Pz5s0xYsQIfG0HclZWFjp16gR9fX0cOHAAoaGh8PX1BfD33Jh/u3r1KjQ0NPD8+XMUFhZ+cZuNGzfGs2fPsGjRIuTk5KBPnz7o1auXdL5BQojcUKkhhHCTk5ODoUOHYtSoUXB3d8f//vc/hIaGYvv27V98TExMDFJSUrB8+XK0bt0atWvX/miScJHDhw/jxIkTCAoKQmJiIhYtWvTVLIaGhujbty/++OMPHD58GMePH8f79+/L/T0SQuSHSg0hhJsZM2ZAIpFgxYoVAABra2usXr0a06ZNw/Pnzz/7GGtra4hEImzcuBFxcXE4derUJ4XlxYsXGDNmDFasWIFWrVphz549WLZsGW7duvXZba5duxY+Pj6IiYnB48ePcfToUVStWhXGxsbS/HYJITJGpYYQwkVwcDA2b96MPXv2QE9Pr/jrP/74I1q0aPHFw1CVK1fGnj17cPToUdStWxfLly/HqlWriv+dMYZhw4ahSZMmGD9+PACgY8eOGD9+PAYNGoTMzMxPtqmvr48VK1bAxcUFrq6ueP78Ofz9/SEU0q9IQpQJnf1ECCGEEJVAH0MIIYQQohKo1BBCCCFEJVCpIYQQQohKoFJDCCGEEJVApYYQQgghKoFKDSGEEEJUApUaQgghhKgEKjWEEEIIUQlUagghhBCiEqjUEEIIIUQlUKkhhBBCiEr4P8KkPcmKer8uAAAAAElFTkSuQmCC", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#| caption: The optimized trajectory with the estimated covariances.\n", "#| label: fig:optimized_trajectory_with_covariances\n", "marginals = gtsam.Marginals(graph, result)\n", "for i in range(1, 6):\n", " gtsam_plot.plot_pose2(0, result.atPose2(i), 0.5,\n", " marginals.marginalCovariance(i))\n", "plt.axis('equal'); plt.show()\n" ] }, { "cell_type": "markdown", "metadata": { "id": "1oyymz-A0e4D" }, "source": [ "The result is shown graphically in Figure\n", "2,\n", "along with covariance ellipses. These covariance ellipses\n", "in 2D indicate the marginal over position, *over all possible\n", "orientations*, and show the area that contains 99% of the probability\n", "mass (in 1D this would correspond to three standard deviations). The graph\n", "shows in a clear manner that the uncertainty on pose $T_{5}$ is now\n", "much less than if there would be only odometry measurements. The pose\n", "with the highest uncertainty, $T_{4}$, is the one furthest away from\n", "the unary constraint $f_{0}(T_{1})$, which is the only factor tying\n", "the graph to a global coordinate frame." ] }, { "cell_type": "markdown", "id": "7fb32b85", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "## SLAM with Landmarks\n", "\n", "> Take PoseSLAM, add landmarks.\n", "\n", "So far we optimized over one type of variable, but often we build a landmark map *simultaneously* with the trajectory, i.e., this is *true* SLAM. In the next chapter, we will more thoroughly examine the full 3D case, whereas here we will model landmarks with 2D points in the plane. That does not mean that they cannot represent real 3-D entities in the environment: they can be the location of trees, poles, building corners, the sides of windows, the location of a stop sign in traffic, even moving pedestrians in more advanced applications.\n", "\n", "How do we measure such landmarks? The most typical *type* of measurements are either **range** measurements, **bearing** measurements, or **bearing-range** measurements. The details on how to obtain them are typically application-dependent, and below we will abstract away the sensor preprocessing details. For example, in the case of a LIDAR sensor, \n", "bearing-range measurements can be obtained by preprocessing every LIDAR scan, detecting prominent vertical structures for example. A real-life example that we will discuss below involves detecting and measuring the bearing-range to trees.\n", "Radar is another often-used sensor for autonomous driving, and it can often be modeled or idealized to give \n", "bearing-range measurements as well." ] }, { "cell_type": "markdown", "id": "e4d82d22", "metadata": { "slideshow": { "slide_type": "-" } }, "source": [ "To illustrate SLAM with landmarks, we build a small toy example with 3 bearing-range measurements to two different landmarks:" ] }, { "cell_type": "code", "execution_count": 8, "id": "e7f12785", "metadata": {}, "outputs": [], "source": [ "slam_graph = gtsam.NonlinearFactorGraph()\n", "slam_graph.add( gtsam.PriorFactorPose2(1, gtsam.Pose2(0.0, 0.0, 0.0), prior_model))\n", "slam_graph.add(Between(1, 2, gtsam.Pose2(2.0, 0.0, 0.0), odometry_model))\n", "slam_graph.add(Between(2, 3, gtsam.Pose2(2.0, 0.0, 0.0), odometry_model))\n" ] }, { "cell_type": "code", "execution_count": 9, "id": "f6943c7b", "metadata": {}, "outputs": [], "source": [ "# Add Range-Bearing measurements to two different landmarks L1 and L2\n", "measurement_model = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2]))\n", "BR = gtsam.BearingRangeFactor2D\n", "l = {k:gtsam.symbol('l',k) for k in [1,2]} # name landmark variables\n", "slam_graph.add(BR(1, l[1], gtsam.Rot2.fromDegrees(45),np.sqrt(4.0 + 4.0), measurement_model)) # pose 1 -*- landmark 1\n", "slam_graph.add(BR(2, l[1], gtsam.Rot2.fromDegrees(90), 2.0,measurement_model)) # pose 2 -*- landmark 1\n", "slam_graph.add(BR(3, l[2], gtsam.Rot2.fromDegrees(90), 2.0,measurement_model)) # pose 3 -*- landmark 2\n" ] }, { "cell_type": "markdown", "id": "858637d5", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "When we have an initial estimate, we can look at the structure of this factor graph:" ] }, { "cell_type": "code", "execution_count": 10, "id": "1f365542", "metadata": {}, "outputs": [], "source": [ "slam_initial = gtsam.Values()\n", "slam_initial.insert(1, gtsam.Pose2(-0.25, 0.20, 0.15))\n", "slam_initial.insert(2, gtsam.Pose2(2.30, 0.10, -0.20))\n", "slam_initial.insert(3, gtsam.Pose2(4.10, 0.10, 0.10))\n", "slam_initial.insert(l[1], gtsam.Point2(1.80, 2.10))\n", "slam_initial.insert(l[2], gtsam.Point2(4.10, 1.80))\n" ] }, { "cell_type": "code", "execution_count": 11, "id": "f10793f5", "metadata": {}, "outputs": [ { "data": { "image/svg+xml": [ "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "var1\n", "\n", "1\n", "\n", "\n", "\n", "var2\n", "\n", "2\n", "\n", "\n", "\n", "var1--var2\n", "\n", "\n", "\n", "\n", "var7782220156096217089\n", "\n", "l1\n", "\n", "\n", "\n", "var1--var7782220156096217089\n", "\n", "\n", "\n", "\n", "factor0\n", "\n", "\n", "\n", "\n", "var1--factor0\n", "\n", "\n", "\n", "\n", "var3\n", "\n", "3\n", "\n", "\n", "\n", "var2--var3\n", "\n", "\n", "\n", "\n", "var2--var7782220156096217089\n", "\n", "\n", "\n", "\n", "var7782220156096217090\n", "\n", "l2\n", "\n", "\n", "\n", "var3--var7782220156096217090\n", "\n", "\n", "\n", "\n" ], "text/plain": [ "" ] }, "execution_count": 11, "metadata": {}, "output_type": "execute_result" } ], "source": [ "#| caption: Factor graph with odometry and range-bearing constraints.\n", "#| label: fig:factor_graph_with_range_bearing\n", "show(slam_graph, slam_initial, binary_edges=True)\n" ] }, { "cell_type": "markdown", "id": "98dfeb0a", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "We optimize again using Levenberg Marquardt, and show the marginals on both robot position and landmarks, as before:" ] }, { "cell_type": "code", "execution_count": 12, "id": "b16128fd", "metadata": {}, "outputs": [], "source": [ "optimizer = gtsam.LevenbergMarquardtOptimizer(slam_graph, slam_initial)\n", "slam_result = optimizer.optimize()\n" ] }, { "cell_type": "code", "execution_count": 13, "id": "ad5f9406", "metadata": {}, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#| caption: The optimized trajectory with the estimated covariances, with bearing-range measurements to landmarks.\n", "#| label: fig:optimized_trajectory_with_covariances_and_landmarks_br\n", "marginals = gtsam.Marginals(slam_graph, slam_result)\n", "for k in [1,2,3]:\n", " gtsam_plot.plot_pose2(0, slam_result.atPose2(k), 0.5, marginals.marginalCovariance(k))\n", "for j in [1,2]:\n", " gtsam_plot.plot_point2(0, slam_result.atPoint2(l[j]), 'g', P=marginals.marginalCovariance(l[j]))\n", "plt.axis('equal'); plt.show()\n" ] }, { "cell_type": "markdown", "id": "e651f559", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "## A Larger SLAM Example" ] }, { "cell_type": "markdown", "id": "4baffa99", "metadata": { "slideshow": { "slide_type": "-" } }, "source": [ "Below we optimize a piece of the (old) [Victoria park dataset](http://www-personal.acfr.usyd.edu.au/nebot/victoria_park.htm), which involves a truck driving through a park in Sydney, extracting the position of trees in the park from LIDAR scans, just as we discussed above. The factor graph for this example is created from file and shown below:" ] }, { "cell_type": "code", "execution_count": 14, "id": "03f76695", "metadata": {}, "outputs": [], "source": [ "datafile = gtsam.findExampleDataFile('example.graph')\n", "model = gtsam.noiseModel.Diagonal.Sigmas([0.05,0.05,2*math.pi/180])\n", "[graph,initial] = gtsam.load2D(datafile, model)" ] }, { "cell_type": "code", "execution_count": 15, "metadata": {}, "outputs": [ { "data": { "image/svg+xml": [ "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "\n", "var0\n", "\n", "0\n", "\n", "\n", "\n", "var1\n", "\n", "1\n", "\n", "\n", "\n", "var0--var1\n", "\n", "\n", "\n", "\n", "var7782220156096217232\n", "\n", "l144\n", "\n", "\n", "\n", "var0--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var2\n", "\n", "2\n", "\n", "\n", "\n", "var1--var2\n", "\n", "\n", "\n", "\n", "var1--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var3\n", "\n", "3\n", "\n", "\n", "\n", "var2--var3\n", "\n", "\n", "\n", "\n", "var7782220156096217225\n", "\n", "l137\n", "\n", "\n", "\n", "var2--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var2--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var4\n", "\n", "4\n", "\n", "\n", "\n", "var3--var4\n", "\n", "\n", "\n", "\n", "var7782220156096217198\n", "\n", "l110\n", "\n", "\n", "\n", "var3--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var3--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var3--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var5\n", "\n", "5\n", "\n", "\n", "\n", "var4--var5\n", "\n", "\n", "\n", "\n", "var4--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var4--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var4--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var6\n", "\n", "6\n", "\n", "\n", "\n", "var5--var6\n", "\n", "\n", "\n", "\n", "var5--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var5--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var5--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var7\n", "\n", "7\n", "\n", "\n", "\n", "var6--var7\n", "\n", "\n", "\n", "\n", "var6--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var6--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var6--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var8\n", "\n", "8\n", "\n", "\n", "\n", "var7--var8\n", "\n", "\n", "\n", "\n", "var7--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var7--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var7--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var9\n", "\n", "9\n", "\n", "\n", "\n", "var8--var9\n", "\n", "\n", "\n", "\n", "var8--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var8--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var8--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var10\n", "\n", "10\n", "\n", "\n", "\n", "var9--var10\n", "\n", "\n", "\n", "\n", "var9--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var9--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var9--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var11\n", "\n", "11\n", "\n", "\n", "\n", "var10--var11\n", "\n", "\n", "\n", "\n", "var10--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var10--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var10--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var12\n", "\n", "12\n", "\n", "\n", "\n", "var11--var12\n", "\n", "\n", "\n", "\n", "var11--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var11--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var11--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var13\n", "\n", "13\n", "\n", "\n", "\n", "var12--var13\n", "\n", "\n", "\n", "\n", "var12--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var12--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var12--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var14\n", "\n", "14\n", "\n", "\n", "\n", "var13--var14\n", "\n", "\n", "\n", "\n", "var13--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var13--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var13--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var15\n", "\n", "15\n", "\n", "\n", "\n", "var14--var15\n", "\n", "\n", "\n", "\n", "var14--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var14--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var14--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var16\n", "\n", "16\n", "\n", "\n", "\n", "var15--var16\n", "\n", "\n", "\n", "\n", "var15--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var15--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var15--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var17\n", "\n", "17\n", "\n", "\n", "\n", "var16--var17\n", "\n", "\n", "\n", "\n", "var16--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var7782220156096217205\n", "\n", "l117\n", "\n", "\n", "\n", "var16--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var16--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var16--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var18\n", "\n", "18\n", "\n", "\n", "\n", "var17--var18\n", "\n", "\n", "\n", "\n", "var17--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var17--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var17--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var17--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var19\n", "\n", "19\n", "\n", "\n", "\n", "var18--var19\n", "\n", "\n", "\n", "\n", "var18--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var18--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var18--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var18--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var20\n", "\n", "20\n", "\n", "\n", "\n", "var19--var20\n", "\n", "\n", "\n", "\n", "var19--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var19--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var19--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var19--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var21\n", "\n", "21\n", "\n", "\n", "\n", "var20--var21\n", "\n", "\n", "\n", "\n", "var20--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var20--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var20--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var20--var7782220156096217232\n", "\n", "\n", "\n", "\n", "var22\n", "\n", "22\n", "\n", "\n", "\n", "var21--var22\n", "\n", "\n", "\n", "\n", "var21--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var21--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var7782220156096217218\n", "\n", "l130\n", "\n", "\n", "\n", "var21--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var21--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var23\n", "\n", "23\n", "\n", "\n", "\n", "var22--var23\n", "\n", "\n", "\n", "\n", "var22--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var22--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var22--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var22--var7782220156096217225\n", "\n", "\n", "\n", "\n", "var24\n", "\n", "24\n", "\n", "\n", "\n", "var23--var24\n", "\n", "\n", "\n", "\n", "var23--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var23--var7782220156096217205\n", "\n", "\n", "\n", "\n", "var23--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var25\n", "\n", "25\n", "\n", "\n", "\n", "var24--var25\n", "\n", "\n", "\n", "\n", "var24--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var24--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var26\n", "\n", "26\n", "\n", "\n", "\n", "var25--var26\n", "\n", "\n", "\n", "\n", "var25--var7782220156096217198\n", "\n", "\n", "\n", "\n", "var25--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var27\n", "\n", "27\n", "\n", "\n", "\n", "var26--var27\n", "\n", "\n", "\n", "\n", "var26--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var28\n", "\n", "28\n", "\n", "\n", "\n", "var27--var28\n", "\n", "\n", "\n", "\n", "var27--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var29\n", "\n", "29\n", "\n", "\n", "\n", "var28--var29\n", "\n", "\n", "\n", "\n", "var7782220156096217200\n", "\n", "l112\n", "\n", "\n", "\n", "var28--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var28--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var7782220156096217234\n", "\n", "l146\n", "\n", "\n", "\n", "var28--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var30\n", "\n", "30\n", "\n", "\n", "\n", "var29--var30\n", "\n", "\n", "\n", "\n", "var29--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var29--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var29--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var31\n", "\n", "31\n", "\n", "\n", "\n", "var30--var31\n", "\n", "\n", "\n", "\n", "var30--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var30--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var30--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var32\n", "\n", "32\n", "\n", "\n", "\n", "var31--var32\n", "\n", "\n", "\n", "\n", "var31--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var31--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var31--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var33\n", "\n", "33\n", "\n", "\n", "\n", "var32--var33\n", "\n", "\n", "\n", "\n", "var32--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var32--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var32--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var34\n", "\n", "34\n", "\n", "\n", "\n", "var33--var34\n", "\n", "\n", "\n", "\n", "var33--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var33--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var33--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var35\n", "\n", "35\n", "\n", "\n", "\n", "var34--var35\n", "\n", "\n", "\n", "\n", "var34--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var34--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var34--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var36\n", "\n", "36\n", "\n", "\n", "\n", "var35--var36\n", "\n", "\n", "\n", "\n", "var35--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var7782220156096217217\n", "\n", "l129\n", "\n", "\n", "\n", "var35--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var35--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var35--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var37\n", "\n", "37\n", "\n", "\n", "\n", "var36--var37\n", "\n", "\n", "\n", "\n", "var36--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var36--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var36--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var36--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var38\n", "\n", "38\n", "\n", "\n", "\n", "var37--var38\n", "\n", "\n", "\n", "\n", "var37--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var37--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var37--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var37--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var39\n", "\n", "39\n", "\n", "\n", "\n", "var38--var39\n", "\n", "\n", "\n", "\n", "var38--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var38--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var38--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var7782220156096217220\n", "\n", "l132\n", "\n", "\n", "\n", "var38--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var38--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var40\n", "\n", "40\n", "\n", "\n", "\n", "var39--var40\n", "\n", "\n", "\n", "\n", "var39--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var39--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var39--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var39--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var7782220156096217224\n", "\n", "l136\n", "\n", "\n", "\n", "var39--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var39--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var41\n", "\n", "41\n", "\n", "\n", "\n", "var40--var41\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var40--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var42\n", "\n", "42\n", "\n", "\n", "\n", "var41--var42\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var41--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var43\n", "\n", "43\n", "\n", "\n", "\n", "var42--var43\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217218\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var42--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var44\n", "\n", "44\n", "\n", "\n", "\n", "var43--var44\n", "\n", "\n", "\n", "\n", "var43--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var43--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var43--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var43--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var43--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var45\n", "\n", "45\n", "\n", "\n", "\n", "var44--var45\n", "\n", "\n", "\n", "\n", "var44--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var44--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var44--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var44--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var44--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var46\n", "\n", "46\n", "\n", "\n", "\n", "var45--var46\n", "\n", "\n", "\n", "\n", "var45--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var45--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var45--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var45--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var45--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var47\n", "\n", "47\n", "\n", "\n", "\n", "var46--var47\n", "\n", "\n", "\n", "\n", "var46--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var46--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var46--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var46--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var7782220156096217233\n", "\n", "l145\n", "\n", "\n", "\n", "var46--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var46--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var48\n", "\n", "48\n", "\n", "\n", "\n", "var47--var48\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var7782220156096217226\n", "\n", "l138\n", "\n", "\n", "\n", "var47--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var47--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var49\n", "\n", "49\n", "\n", "\n", "\n", "var48--var49\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217200\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var48--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var50\n", "\n", "50\n", "\n", "\n", "\n", "var49--var50\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var49--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var7782220156096217299\n", "\n", "l211\n", "\n", "\n", "\n", "var49--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var51\n", "\n", "51\n", "\n", "\n", "\n", "var50--var51\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var50--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var52\n", "\n", "52\n", "\n", "\n", "\n", "var51--var52\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var7782220156096217221\n", "\n", "l133\n", "\n", "\n", "\n", "var51--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var51--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var53\n", "\n", "53\n", "\n", "\n", "\n", "var52--var53\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217234\n", "\n", "\n", "\n", "\n", "var52--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var54\n", "\n", "54\n", "\n", "\n", "\n", "var53--var54\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var53--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var7782220156096217302\n", "\n", "l214\n", "\n", "\n", "\n", "var53--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var55\n", "\n", "55\n", "\n", "\n", "\n", "var54--var55\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var54--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var56\n", "\n", "56\n", "\n", "\n", "\n", "var55--var56\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var55--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var57\n", "\n", "57\n", "\n", "\n", "\n", "var56--var57\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var56--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var58\n", "\n", "58\n", "\n", "\n", "\n", "var57--var58\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217217\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var7782220156096217229\n", "\n", "l141\n", "\n", "\n", "\n", "var57--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var57--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var59\n", "\n", "59\n", "\n", "\n", "\n", "var58--var59\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var58--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var60\n", "\n", "60\n", "\n", "\n", "\n", "var59--var60\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var59--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var61\n", "\n", "61\n", "\n", "\n", "\n", "var60--var61\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var60--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var62\n", "\n", "62\n", "\n", "\n", "\n", "var61--var62\n", "\n", "\n", "\n", "\n", "var7782220156096217204\n", "\n", "l116\n", "\n", "\n", "\n", "var61--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217220\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217224\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var61--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var63\n", "\n", "63\n", "\n", "\n", "\n", "var62--var63\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var62--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var64\n", "\n", "64\n", "\n", "\n", "\n", "var63--var64\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var63--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var65\n", "\n", "65\n", "\n", "\n", "\n", "var64--var65\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var64--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var66\n", "\n", "66\n", "\n", "\n", "\n", "var65--var66\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217226\n", "\n", "\n", "\n", "\n", "var7782220156096217227\n", "\n", "l139\n", "\n", "\n", "\n", "var65--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var65--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var67\n", "\n", "67\n", "\n", "\n", "\n", "var66--var67\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217229\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217299\n", "\n", "\n", "\n", "\n", "var66--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var68\n", "\n", "68\n", "\n", "\n", "\n", "var67--var68\n", "\n", "\n", "\n", "\n", "var67--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var67--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var67--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var67--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var67--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var69\n", "\n", "69\n", "\n", "\n", "\n", "var68--var69\n", "\n", "\n", "\n", "\n", "var68--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var68--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var68--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var68--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var68--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var70\n", "\n", "70\n", "\n", "\n", "\n", "var69--var70\n", "\n", "\n", "\n", "\n", "var7782220156096217202\n", "\n", "l114\n", "\n", "\n", "\n", "var69--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var69--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var69--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var69--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var69--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var69--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var71\n", "\n", "71\n", "\n", "\n", "\n", "var70--var71\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var70--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var72\n", "\n", "72\n", "\n", "\n", "\n", "var71--var72\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var7782220156096217219\n", "\n", "l131\n", "\n", "\n", "\n", "var71--var7782220156096217219\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var71--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var73\n", "\n", "73\n", "\n", "\n", "\n", "var72--var73\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var72--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var74\n", "\n", "74\n", "\n", "\n", "\n", "var73--var74\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217227\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217233\n", "\n", "\n", "\n", "\n", "var73--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var75\n", "\n", "75\n", "\n", "\n", "\n", "var74--var75\n", "\n", "\n", "\n", "\n", "var74--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var74--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var74--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var74--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var7782220156096217307\n", "\n", "l219\n", "\n", "\n", "\n", "var74--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var76\n", "\n", "76\n", "\n", "\n", "\n", "var75--var76\n", "\n", "\n", "\n", "\n", "var75--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var75--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var75--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var75--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var75--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var77\n", "\n", "77\n", "\n", "\n", "\n", "var76--var77\n", "\n", "\n", "\n", "\n", "var76--var7782220156096217202\n", "\n", "\n", "\n", "\n", "var76--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var76--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var76--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var76--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var78\n", "\n", "78\n", "\n", "\n", "\n", "var77--var78\n", "\n", "\n", "\n", "\n", "var77--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var77--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var77--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var77--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var79\n", "\n", "79\n", "\n", "\n", "\n", "var78--var79\n", "\n", "\n", "\n", "\n", "var78--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var78--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var78--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var78--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var80\n", "\n", "80\n", "\n", "\n", "\n", "var79--var80\n", "\n", "\n", "\n", "\n", "var79--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var79--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var79--var7782220156096217302\n", "\n", "\n", "\n", "\n", "var79--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var81\n", "\n", "81\n", "\n", "\n", "\n", "var80--var81\n", "\n", "\n", "\n", "\n", "var80--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var80--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var80--var7782220156096217307\n", "\n", "\n", "\n", "\n", "var82\n", "\n", "82\n", "\n", "\n", "\n", "var81--var82\n", "\n", "\n", "\n", "\n", "var81--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var81--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var83\n", "\n", "83\n", "\n", "\n", "\n", "var82--var83\n", "\n", "\n", "\n", "\n", "var82--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var7782220156096217206\n", "\n", "l118\n", "\n", "\n", "\n", "var82--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var82--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var84\n", "\n", "84\n", "\n", "\n", "\n", "var83--var84\n", "\n", "\n", "\n", "\n", "var83--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var83--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var83--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var85\n", "\n", "85\n", "\n", "\n", "\n", "var84--var85\n", "\n", "\n", "\n", "\n", "var84--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var84--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var84--var7782220156096217221\n", "\n", "\n", "\n", "\n", "var86\n", "\n", "86\n", "\n", "\n", "\n", "var85--var86\n", "\n", "\n", "\n", "\n", "var85--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var85--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var87\n", "\n", "87\n", "\n", "\n", "\n", "var86--var87\n", "\n", "\n", "\n", "\n", "var86--var7782220156096217204\n", "\n", "\n", "\n", "\n", "var86--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var7782220156096217213\n", "\n", "l125\n", "\n", "\n", "\n", "var86--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var88\n", "\n", "88\n", "\n", "\n", "\n", "var87--var88\n", "\n", "\n", "\n", "\n", "var87--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var87--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var89\n", "\n", "89\n", "\n", "\n", "\n", "var88--var89\n", "\n", "\n", "\n", "\n", "var88--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var88--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var90\n", "\n", "90\n", "\n", "\n", "\n", "var89--var90\n", "\n", "\n", "\n", "\n", "var89--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var89--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var91\n", "\n", "91\n", "\n", "\n", "\n", "var90--var91\n", "\n", "\n", "\n", "\n", "var90--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var90--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var92\n", "\n", "92\n", "\n", "\n", "\n", "var91--var92\n", "\n", "\n", "\n", "\n", "var91--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var91--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var93\n", "\n", "93\n", "\n", "\n", "\n", "var92--var93\n", "\n", "\n", "\n", "\n", "var92--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var92--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var94\n", "\n", "94\n", "\n", "\n", "\n", "var93--var94\n", "\n", "\n", "\n", "\n", "var93--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var7782220156096217210\n", "\n", "l122\n", "\n", "\n", "\n", "var93--var7782220156096217210\n", "\n", "\n", "\n", "\n", "var93--var7782220156096217213\n", "\n", "\n", "\n", "\n", "var94--var7782220156096217206\n", "\n", "\n", "\n", "\n", "var94--var7782220156096217210\n", "\n", "\n", "\n", "\n", "var94--var7782220156096217213\n", "\n", "\n", "\n", "\n" ], "text/plain": [ "" ] }, "execution_count": 15, "metadata": {}, "output_type": "execute_result" } ], "source": [ "#| caption: Factor graph for a more realistic example, derived from a real-world dataset.\n", "#| label: fig:factor_graph_real_world\n", "show(graph,initial, binary_edges=True)\n" ] }, { "cell_type": "markdown", "id": "8246d94a", "metadata": { "slideshow": { "slide_type": "slide" } }, "source": [ "This is a much larger factor graph than any we have encountered before, and we can distinguish several features:\n", "\n", "- There is a prominent backbone of truck poses, connected via odometry measurements.\n", "- There are about 20 landmarks, some of which are seen briefly, while others are seen for longer periods of time.\n", "- The graph is very sparsely connected, and hence optimization will still be quite fast.\n", "\n", "Optimizing with `gtsam.LevenbergMarquardtOptimizer`, again..." ] }, { "cell_type": "code", "execution_count": 16, "id": "b90abaa8", "metadata": {}, "outputs": [], "source": [ "initial_poses = gtsam.utilities.extractPose2(initial)\n", "for i in range(initial_poses.shape[0]):\n", " initial.update(i, initial.atPose2(i).retract(np.random.normal(scale=0.5,size=(3,))))\n", "optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial)\n", "result = optimizer.optimize()\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Below we plot both the initial estimate, which was created by adding random noise on top of the ground truth, and the optimized trajectory:" ] }, { "cell_type": "code", "execution_count": 17, "id": "542c8588", "metadata": {}, "outputs": [], "source": [ "initial_poses = gtsam.utilities.extractPose2(initial)\n", "fig = go.Figure()\n", "fig.add_scatter(x=initial_poses[:,0], y=initial_poses[:,1], name=\"initial\", marker=dict(color='orange'))\n", "final_poses = gtsam.utilities.extractPose2(result)\n", "fig.add_scatter(x=final_poses[:,0], y=final_poses[:,1], name=\"optimized\", marker=dict(color='green'))\n", "fig.update_yaxes(scaleanchor = \"x\",scaleratio = 1);" ] }, { "cell_type": "code", "execution_count": 18, "metadata": {}, "outputs": [ { "data": { "image/png": "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" }, "metadata": {}, "output_type": "display_data" } ], "source": [ "#| caption: Initial and optimized trajectories for a more realistic example.\n", "#| label: fig:initial_and_optimized_trajectories\n", "fig.show()\n" ] } ], "metadata": { "colab": { "collapsed_sections": [], "include_colab_link": true, "name": "S64_driving_perception.ipynb", "provenance": [] }, "kernelspec": { "display_name": "Python 3.8.12 ('gtbook')", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.9.18" }, "latex_metadata": { "affiliation": "Georgia Institute of Technology", "author": "Frank Dellaert and Seth Hutchinson", "title": "Introduction to Robotics" }, "vscode": { "interpreter": { "hash": "9f7376ced4243bb13dfcffa8a3ba834e0602aa8334cd3a1d8ba8d285f4628083" } } }, "nbformat": 4, "nbformat_minor": 1 }