diff --git a/doc/common_macros.tex b/doc/common_macros.tex new file mode 100644 index 000000000..73648c6a4 --- /dev/null +++ b/doc/common_macros.tex @@ -0,0 +1,124 @@ +\global\long\def\Vector#1{{\bf #1}} + \global\long\def\Matrix#1{{\bf #1}} + + +\global\long\def\eq#1{equation (\ref{eq:=0000231})} + + +\global\long\def\eye#1{\Vector{I_{#1}}} + + +\global\long\def\leftsparrow#1{\stackrel{#1}{\leftarrow}} + \global\long\def\rightsparrow#1{\stackrel{#1}{\rightarrow}} + \global\long\def\chain{\mathcal{M}} + + +\global\long\def\define{\stackrel{\Delta}{=}} + + +\global\long\def\argmin#1{\mathop{\textrm{argmin \,}}_{#1}} + + +\global\long\def\Norm#1{\Vert#1\Vert} + \global\long\def\SqrNorm#1{\Vert#1\Vert^{2}} + \global\long\def\Ltwo#1{\mathcal{L}^{2}\left(#1\right)} + + +\global\long\def\Normal#1#2#3{\mathcal{N}(#1;#2,#3)} + + +\global\long\def\LogNormal#1#2#3{ (#1-#2)^{T} #3^{-1} (#1-#2) } + + +\global\long\def\SqrMah#1#2#3{\Vert{#1}-{#2}\Vert_{#3}^{2}} + + +\global\long\def\SqrZMah#1#2{\Vert{#1}\Vert_{#2}^{2}} + + +\global\long\def\Info#1#2#3{\mathcal{N}^{-1}(#1;#2,#3)} + + +\providecommand{\half}{\frac{1}{2}} + +\global\long\def\Mah#1#2#3{\Vert{#1}-{#2}\Vert_{#3}} + \global\long\def\MahDeriv#1#2#3#4{\biggl(\deriv{#2}{#4}\biggr)^{T} #3^{-1} (#1-#2)} + + +\global\long\def\argmin#1{\mathop{\textrm{argmin \,}}_{#1}} + \global\long\def\argmax#1{\mathop{\textrm{argmax \,}}_{#1}} + + + + +\global\long\def\deriv#1#2{\frac{\partial#1}{\partial#2}} + + +\global\long\def\at#1#2{#1\biggr\rvert_{#2}} + + +\global\long\def\Jac#1#2#3{ \at{\deriv{#1}{#2}} {#3} } + + + + +\global\long\def\Rone{\mathbb{R}} +\global\long\def\Pone{\mathbb{P}} + + +\global\long\def\Rtwo{\mathbb{R}^{2}} +\global\long\def\Ptwo{\mathbb{P}^{2}} + + +\global\long\def\Stwo{\mathbb{S}^{2}} + \global\long\def\Complex{\mathbb{C}} + + +\global\long\def\Z{\mathbb{Z}} + \global\long\def\Rplus{\mathbb{R}^{+}} + + +\global\long\def\SOtwo{SO(2)} +\global\long\def\sotwo{\mathfrak{so(2)}} +\global\long\def\skew#1{[#1]_{+}} + + +\global\long\def\SEtwo{SE(2)} +\global\long\def\setwo{\mathfrak{se(2)}} +\global\long\def\Skew#1{[#1]_{\times}} + + +\global\long\def\Rthree{\mathbb{R}^{3}} +\global\long\def\Pthree{\mathbb{P}^{3}} + + +\global\long\def\SOthree{SO(3)} +\global\long\def\sothree{\mathfrak{so(3)}} + + +\global\long\def\Rsix{\mathbb{R}^{6}} +\global\long\def\SEthree{SE(3)} +\global\long\def\sethree{\mathfrak{se(3)}} + + +\global\long\def\Rn{\mathbb{R}^{n}} + + +\global\long\def\Afftwo{Aff(2)} +\global\long\def\afftwo{\mathfrak{aff(2)}} + + +\global\long\def\SLthree{SL(3)} +\global\long\def\slthree{\mathfrak{sl(3)}} + + + + +\global\long\def\stirling#1#2{\genfrac{\{}{\}}{0pt}{}{#1}{#2}} + + +\global\long\def\matlabscript#1#2{\begin{itemize}\item[]\lstinputlisting[caption=#2,label=#1]{#1.m}\end{itemize}} + + +\global\long\def\atan{\mathop{atan2}} + diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx new file mode 100644 index 000000000..38b601d23 --- /dev/null +++ b/doc/gtsam.lyx @@ -0,0 +1,3760 @@ +#LyX 2.1 created this file. For more info see http://www.lyx.org/ +\lyxformat 474 +\begin_document +\begin_header +\textclass article +\begin_preamble +\usepackage{times} +\usepackage{listings} + +\usepackage[noend]{algpseudocode} +\usepackage[usenames,dvipsnames]{color} +% This is the color used for MATLAB comments below +\definecolor{MyDarkGreen}{rgb}{0.0,0.4,0.0} + +% For faster processing, load Matlab syntax for listings +\lstloadlanguages{Matlab}% +\lstset{language=Matlab, % Use MATLAB + frame=single, % Single frame around code + basicstyle=\small\ttfamily, % Use small true type font + keywordstyle=[1]\color{Blue}\bf, % MATLAB functions bold and blue + keywordstyle=[2]\color{Purple}, % MATLAB function arguments purple + keywordstyle=[3]\color{Blue}\underbar, % User functions underlined and blue + identifierstyle=, % Nothing special about identifiers + % Comments small dark green courier + commentstyle=\usefont{T1}{pcr}{m}{sl}\color{MyDarkGreen}, + stringstyle=\color{Purple}, % Strings are purple + showstringspaces=false, % Don't put marks in string spaces + tabsize=5, % 5 spaces per tab + % + %%% Put standard MATLAB functions not included in the default + %%% language here + morekeywords={normpdf,normcdf,Pose2,Pose2SLAM}, + % + %%% Put MATLAB function parameters here + morekeywords=[2]{on, off, interp}, + % + %%% Put user defined functions here + morekeywords=[3]{FindESS, homework_example, gtsamSharedNoiseModel_Sigmas}, + % + morecomment=[l][\color{Blue}]{...}, % Line continuation (...) like blue comment + numbers=left, % Line numbers on left + firstnumber=1, % Line numbers start with line 1 + numberstyle=\tiny\color{Blue}, % Line numbers are blue + stepnumber=1 % Line numbers go in steps of 1 + } +\end_preamble +\use_default_options false +\maintain_unincluded_children false +\language english +\language_package default +\inputencoding auto +\fontencoding T1 +\font_roman ae +\font_sans default +\font_typewriter default +\font_math auto +\font_default_family rmdefault +\use_non_tex_fonts false +\font_sc false +\font_osf false +\font_sf_scale 100 +\font_tt_scale 100 +\graphics default +\default_output_format default +\output_sync 0 +\bibtex_command default +\index_command default +\paperfontsize 10 +\spacing onehalf +\use_hyperref false +\papersize custom +\use_geometry true +\use_package amsmath 1 +\use_package amssymb 1 +\use_package cancel 0 +\use_package esint 0 +\use_package mathdots 1 +\use_package mathtools 0 +\use_package mhchem 1 +\use_package stackrel 0 +\use_package stmaryrd 0 +\use_package undertilde 0 +\cite_engine natbib +\cite_engine_type authoryear +\biblio_style plainnat +\use_bibtopic false +\use_indices false +\paperorientation portrait +\suppress_date false +\justification true +\use_refstyle 0 +\index Index +\shortcut idx +\color #008000 +\end_index +\paperwidth 7.44in +\paperheight 9.68in +\leftmargin 1in +\topmargin 1in +\rightmargin 1in +\bottommargin 1in +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\paragraph_indentation default +\quotes_language english +\papercolumns 1 +\papersides 1 +\paperpagestyle default +\tracking_changes false +\output_changes false +\html_math_output 0 +\html_css_as_file 0 +\html_be_strict false +\end_header + +\begin_body + +\begin_layout Title +Factor Graphs and GTSAM: +\begin_inset Newline newline +\end_inset + +A Hands-on Introduction +\end_layout + +\begin_layout Author +Frank Dellaert +\begin_inset Newline newline +\end_inset + +Technical Report number GT-RIM-CP&R-2014-XXX +\end_layout + +\begin_layout Date +September 2014 +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand input +filename "../common_macros.tex" + +\end_inset + + +\end_layout + +\begin_layout Section* +Overview +\end_layout + +\begin_layout Standard +In this document I provide a hands-on introduction to both factor graphs + and GTSAM. + This is an updated version from the 2012 TR that is tailored to our GTSAM + 3.0 library and beyond. +\end_layout + +\begin_layout Standard + +\series bold +Factor graphs +\series default + are graphical models +\begin_inset CommandInset citation +LatexCommand citep +key "Koller09book" + +\end_inset + + that are well suited to modeling complex estimation problems, such as Simultane +ous Localization and Mapping (SLAM) or Structure from Motion (SFM). + You might be familiar with another often used graphical model, Bayes networks, + which are directed acyclic graphs. + A +\series bold +factor graph, +\series default +however, is a +\emph on +bipartite +\emph default + graph consisting of factors connected to variables. + The +\series bold +variables +\series default + represent the unknown random variables in the estimation problem, whereas + the +\series bold +factors +\series default + represent probabilistic constraints on those variables, derived from measuremen +ts or prior knowledge. + In the following sections I will illustrate this with examples from both + robotics and vision. +\end_layout + +\begin_layout Standard +The GTSAM toolbox (GTSAM stands for +\begin_inset Quotes eld +\end_inset + +Georgia Tech Smoothing and Mapping +\begin_inset Quotes erd +\end_inset + +) toolbox is a BSD-licensed C++ library based on factor graphs, developed + at the Georgia Institute of Technology by myself, many of my students, + and collaborators. + It provides state of the art solutions to the SLAM and SFM problems, but + can also be used to model and solve both simpler and more complex estimation + problems. + It also provides a MATLAB interface which allows for rapid prototype developmen +t, visualization, and user interaction. +\end_layout + +\begin_layout Standard +GTSAM exploits sparsity to be computationally efficient. + Typically measurements only provide information on the relationship between + a handful of variables, and hence the resulting factor graph will be sparsely + connected. + This is exploited by the algorithms implemented in GTSAM to reduce computationa +l complexity. + Even when graphs are too dense to be handled efficiently by direct methods, + GTSAM provides iterative methods that are quite efficient regardless. +\end_layout + +\begin_layout Standard +You can download the latest version of GTSAM at +\begin_inset Flex URL +status open + +\begin_layout Plain Layout + +http://tinyurl.com/gtsam +\end_layout + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset CommandInset toc +LatexCommand tableofcontents + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Factor Graphs +\end_layout + +\begin_layout Standard +Let us start with a one-page primer on factor graphs, which in no way replaces + the excellent and detailed reviews by +\begin_inset CommandInset citation +LatexCommand citet +key "Kschischang01it" + +\end_inset + + and +\begin_inset CommandInset citation +LatexCommand citet +key "Loeliger04spm" + +\end_inset + +. + +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/hmm.pdf + scale 60 + BoundingBox 40bp 37bp 400bp 150bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:unrolledHMM" + +\end_inset + +An HMM, unrolled over three time-steps, represented by a Bayes net. + +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:unrolledHMM" + +\end_inset + + shows the +\series bold +Bayes network +\series default + for a hidden Markov model (HMM) over three time steps. + In a Bayes net, each node is associated with a conditional density: the + top Markov chain encodes the prior +\begin_inset Formula $P(X_{1})$ +\end_inset + + and transition probabilities +\begin_inset Formula $P(X_{2}|X_{1})$ +\end_inset + + and +\begin_inset Formula $P(X_{3}|X_{2})$ +\end_inset + +, whereas measurements +\begin_inset Formula $Z_{t}$ +\end_inset + + depend only on the state +\begin_inset Formula $X_{t}$ +\end_inset + +, modeled by conditional densities +\begin_inset Formula $P(Z_{t}|X_{t})$ +\end_inset + +. + Given known measurements +\begin_inset Formula $z_{1}$ +\end_inset + +, +\begin_inset Formula $z_{2}$ +\end_inset + + and +\begin_inset Formula $z_{3}$ +\end_inset + + we are interested in the hidden state sequence +\begin_inset Formula $(X_{1},X_{2},X_{3})$ +\end_inset + + that maximizes the posterior probability +\begin_inset Formula $P(X_{1},X_{2},X_{3}|Z_{1}=z_{1},Z_{2}=z_{2},Z_{3}=z_{3})$ +\end_inset + +. + Since the measurements +\begin_inset Formula $Z_{1}$ +\end_inset + +, +\begin_inset Formula $Z_{2}$ +\end_inset + +, and +\begin_inset Formula $Z_{3}$ +\end_inset + + are +\emph on +known +\emph default +, the posterior is proportional to the product of six +\series bold +factors +\series default +, three of which derive from the the Markov chain, and three likelihood + factors defined as +\begin_inset Formula $L(X_{t};z)\propto P(Z_{t}=z|X_{t})$ +\end_inset + +: +\begin_inset Formula +\[ +P(X_{1},X_{2},X_{3}|Z_{1},Z_{2},Z_{3})\propto P(X_{1})P(X_{2}|X_{1})P(X_{3}|X_{2})L(X_{1};z_{1})L(X_{2};z_{2})L(X_{3};z_{3}) +\] + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +vspace{-3mm} +\end_layout + +\end_inset + + +\begin_inset Float figure +placement H +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/hmm-FG.pdf + scale 60 + BoundingBox 30bp 40bp 340bp 130bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:HMM-FG" + +\end_inset + +An HMM with observed measurements, unrolled over time, represented as a + factor graph. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + This motivates a different graphical model, a +\series bold +factor graph +\series default +, in which we only represent the unknown variables +\begin_inset Formula $X_{1}$ +\end_inset + +, +\begin_inset Formula $X_{2}$ +\end_inset + +, and +\begin_inset Formula $X_{3}$ +\end_inset + +, connected to factors that encode probabilistic information on them, as + in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:HMM-FG" + +\end_inset + +. + To do maximum a-posteriori (MAP) inference, we then maximize the product + +\begin_inset Formula +\[ +f(X_{1},X_{2},X_{3})=\prod f_{i}(\mathcal{X}_{i}) +\] + +\end_inset + +i.e., the value of the factor graph. + It should be clear from the figure that the connectivity of a factor graph + encodes, for each factor +\begin_inset Formula $f_{i}$ +\end_inset + +, which subset of variables +\begin_inset Formula $\mathcal{X}_{i}$ +\end_inset + + it depends on. + In the examples below, we use factor graphs to model more complex MAP inference + problems in robotics. +\end_layout + +\begin_layout Section +\begin_inset CommandInset label +LatexCommand label +name "sec:Robot-Localization" + +\end_inset + +Modeling Robot Motion +\end_layout + +\begin_layout Subsection +Modeling with Factor Graphs +\end_layout + +\begin_layout Standard +Before diving into a SLAM example, let us consider the simpler problem of + modeling robot motion. + This can be done with a +\emph on +continuous +\emph default + Markov chain, and provides a gentle introduction to GTSAM. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/FactorGraph.pdf + scale 80 + BoundingBox 40bp 585bp 300bp 625bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:OdometryFG" + +\end_inset + +Factor graph for robot localization. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + The factor graph for a simple example is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:OdometryFG" + +\end_inset + +. + There are three variables +\begin_inset Formula $x_{1}$ +\end_inset + +, +\begin_inset Formula $x_{2}$ +\end_inset + +, and +\begin_inset Formula $x_{3}$ +\end_inset + + which represent the poses of the robot over time, rendered in the figure + by the open-circle variable nodes. + In this example, we have one +\series bold +unary factor +\series default + +\begin_inset Formula $f_{0}(x_{1})$ +\end_inset + + on the first pose +\begin_inset Formula $x_{1}$ +\end_inset + + that encodes our prior knowledge about +\begin_inset Formula $x_{1}$ +\end_inset + +, and two +\series bold +binary factors +\series default + that relate successive poses, respectively +\begin_inset Formula $f_{1}(x_{1},x_{2};o_{1})$ +\end_inset + + and +\begin_inset Formula $f_{2}(x_{2},x_{3};o_{2})$ +\end_inset + +, where +\begin_inset Formula $o_{1}$ +\end_inset + + and +\begin_inset Formula $o_{2}$ +\end_inset + + represent odometry measurements. +\end_layout + +\begin_layout Subsection +Creating a Factor Graph +\end_layout + +\begin_layout Standard +The following C++ code, included in GTSAM as an example, creates the factor + graph in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:OdometryFG" + +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/OdometryExample.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/OdometryExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:OdometryExample},language={C++},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Above, line 2 creates an empty factor graph. + We then add the factor +\begin_inset Formula $f_{0}(x_{1})$ +\end_inset + + on lines 5-8 as an instance of +\series bold +\emph on +PriorFactor +\series default +\emph default +, a templated class provided in the slam subfolder, with +\series bold +\emph on +T=Pose2 +\series default +\emph default +. + Its constructor takes a variable +\series bold +\emph on +Key +\series default +\emph default + (in this case 1), a mean of type +\series bold +\emph on +Pose2, +\series default +\emph default + created on Line 5, and a noise model for the prior density. + We provide a diagonal Gaussian of type +\series bold +\emph on +noiseModel::Diagonal +\series default +\emph default + by specifying three standard deviations in line 7, respectively 30 cm. +\begin_inset space ~ +\end_inset + +on the robot's position, and 0.1 radians on the robot's orientation. + Note that the +\series bold +\emph on +Sigmas +\series default +\emph default + constructor returns a shared pointer, anticipating that typically the same + noise models are used for many different factors. +\end_layout + +\begin_layout Standard +Similarly, odometry measurements are specified as +\series bold +\emph on +Pose2 +\series default +\emph default + on line 11, with a slightly different noise model defined on line 12-13. + We then add the two factors +\begin_inset Formula $f_{1}(x_{1},x_{2};o_{1})$ +\end_inset + + and +\begin_inset Formula $f_{2}(x_{2},x_{3};o_{2})$ +\end_inset + + on lines 14-15, as instances of yet another templated class, +\series bold +\emph on +BetweenFactor +\series default +\emph default +, again with +\series bold +\emph on +T=Pose2 +\series default +\emph default +. +\end_layout + +\begin_layout Standard +When running the example ( +\emph on +make OdometryExample.run +\emph default + on the command prompt), it will print out the factor graph as follows: +\family typewriter +\size small + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/OdometryOutput1.txt" + +\end_inset + + +\end_layout + +\begin_layout Subsection +Factor Graphs versus Values +\end_layout + +\begin_layout Standard +At this point it is instructive to emphasize two important design ideas + underlying GTSAM: +\end_layout + +\begin_layout Enumerate +The factor graph and its embodiment in code specify the joint probability + distribution +\begin_inset Formula $P(X|Z)$ +\end_inset + + over the +\emph on +entire +\emph default + trajectory +\begin_inset Formula $X\define\{x_{1},x_{2},x_{3}\}$ +\end_inset + + of the robot, rather than just the last pose. + This +\emph on +smoothing +\emph default + view of the world gives GTSAM its name: +\begin_inset Quotes eld +\end_inset + +smoothing and mapping +\begin_inset Quotes erd +\end_inset + +. + Later in this document we will talk about how we can also use GTSAM to + do filtering (which you often do +\emph on +not +\emph default + want to do) or incremental inference (which we do all the time). +\end_layout + +\begin_layout Enumerate +A factor graph in GTSAM is just the specification of the probability density + +\begin_inset Formula $P(X|Z)$ +\end_inset + +, and the corresponding +\series bold +\emph on +FactorGraph +\series default +\emph default + class and its derived classes do not ever contain a +\begin_inset Quotes eld +\end_inset + +solution +\begin_inset Quotes erd +\end_inset + +. + Rather, there is a separate type +\series bold +\emph on +Values +\series default +\emph default + that is used to specify specific values for (in this case) +\begin_inset Formula $x_{1}$ +\end_inset + +, +\begin_inset Formula $x_{2}$ +\end_inset + +, and +\begin_inset Formula $x_{3}$ +\end_inset + +, which can then be used to evaluate the probability (or, more commonly, + the error) associated with particular values. +\end_layout + +\begin_layout Standard +The latter point is often a point of confusion with beginning users of GTSAM. + It helps to remember that when designing GTSAM we took a functional approach + of classes corresponding to mathematical objects, which are usually immutable. + You should think of a factor graph as a +\emph on +function +\emph default + to be applied to values -as the notation +\begin_inset Formula $f(X)\propto P(X|Z)$ +\end_inset + + implies- rather than as an object to be modified. +\end_layout + +\begin_layout Subsection +Non-linear Optimization in GTSAM +\end_layout + +\begin_layout Standard +The listing below creates a +\series bold +\emph on +Values +\series default +\emph default + instance, and uses it as the initial estimate to find the maximum a-posteriori + (MAP) assignment for the trajectory +\begin_inset Formula $X$ +\end_inset + +: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/OdometryOptimize.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/OdometryExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:OdometryOptimize},language={C++},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Lines 2-5 in Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:OdometryOptimize" + +\end_inset + + create the initial estimate, and on line 8 we create a non-linear Levenberg-Mar +quardt style optimizer, and call +\series bold +\emph on +optimize +\series default +\emph default + using default parameter settings. + The reason why GTSAM needs to perform non-linear optimization is because + the odometry factors +\begin_inset Formula $f_{1}(x_{1},x_{2};o_{1})$ +\end_inset + + and +\begin_inset Formula $f_{2}(x_{2},x_{3};o_{2})$ +\end_inset + + are non-linear, as they involve the orientation of the robot. + This also explains why the factor graph we created in Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:OdometryExample" + +\end_inset + + is of type +\series bold +\emph on +NonlinearFactorGraph +\series default +\emph default +. + The optimization class linearizes this graph, possibly multiple times, + to minimize the non-linear squared error specified by the factors. +\end_layout + +\begin_layout Standard +The relevant output from running the example is as follows: +\family typewriter +\size small + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/OdometryOutput2.txt" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + It can be seen that, subject to very small tolerance, the ground truth + solution +\begin_inset Formula $x_{1}=(0,0,0)$ +\end_inset + +, +\begin_inset Formula $x_{2}=(2,0,0)$ +\end_inset + +, and +\begin_inset Formula $x_{3}=(4,0,0)$ +\end_inset + + is recovered. +\end_layout + +\begin_layout Subsection +\begin_inset CommandInset label +LatexCommand label +name "sub:Full-Posterior-Inference" + +\end_inset + +Full Posterior Inference +\end_layout + +\begin_layout Standard +GTSAM can also be used to calculate the covariance matrix for each pose + after incorporating the information from all measurements +\begin_inset Formula $Z$ +\end_inset + +. + Recognizing that the factor graph encodes the +\series bold +posterior density +\series default + +\begin_inset Formula $P(X|Z)$ +\end_inset + +, the mean +\begin_inset Formula $\mu$ +\end_inset + + together with the covariance +\begin_inset Formula $\Sigma$ +\end_inset + + for each pose +\begin_inset Formula $x$ +\end_inset + + approximate the +\series bold +marginal posterior density +\series default + +\begin_inset Formula $P(x|Z)$ +\end_inset + +. + Note that this is just an approximation, as even in this simple case the + odometry factors are actually non-linear in their arguments, and GTSAM + only computes a Gaussian approximation to the true underlying posterior. +\end_layout + +\begin_layout Standard +The following C++ code will recover the posterior marginals: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/OdometryMarginals.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/OdometryExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:OdometryMarginals},language={C++},numbers=left" + +\end_inset + +The relevant output from running the example is as follows: +\size footnotesize + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/OdometryOutput3.txt" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + What we see is that the marginal covariance +\begin_inset Formula $P(x_{1}|Z)$ +\end_inset + + on +\begin_inset Formula $x_{1}$ +\end_inset + + is simply the prior knowledge on +\begin_inset Formula $x_{1}$ +\end_inset + +, but as the robot moves the uncertainty in all dimensions grows without + bound, and the +\begin_inset Formula $y$ +\end_inset + + and +\begin_inset Formula $\theta$ +\end_inset + + components of the pose become (positively) correlated. +\end_layout + +\begin_layout Standard +An important fact to note when interpreting these numbers is that covariance + matrices are given in +\emph on +relative +\emph default + coordinates, not absolute coordinates. + This is because internally GTSAM optimizes for a change with respect to + a linearization point, as do all nonlinear optimization libraries. +\end_layout + +\begin_layout Section +Robot Localization +\end_layout + +\begin_layout Subsection +Unary Measurement Factors +\end_layout + +\begin_layout Standard +In this section we add measurements to the factor graph that will help us + actually +\emph on +localize +\emph default + the robot over time. + The example also serves as a tutorial on creating new factor types. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/FactorGraph2.pdf + scale 80 + BoundingBox 70bp 550bp 300bp 630bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:LocalizationFG" + +\end_inset + +Robot localization factor graph with unary measurement factors at each time + step. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In particular, we use +\series bold +unary measurement factors +\series default + to handle external measurements. + The example from Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sec:Robot-Localization" + +\end_inset + + is not very useful on a real robot, because it only contains factors correspond +ing to odometry measurements. + These are imperfect and will lead to quickly accumulating uncertainty on + the last robot pose, at least in the absence of any external measurements + (see Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Full-Posterior-Inference" + +\end_inset + +). + Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:LocalizationFG" + +\end_inset + + shows a new factor graph where the prior +\begin_inset Formula $f_{0}(x_{1})$ +\end_inset + + is omitted and instead we added three unary factors +\begin_inset Formula $f_{1}(x_{1};z_{1})$ +\end_inset + +, +\begin_inset Formula $f_{2}(x_{2};z_{2})$ +\end_inset + +, and +\begin_inset Formula $f_{3}(x_{3};z_{3})$ +\end_inset + +, one for each localization measurement +\begin_inset Formula $z_{t}$ +\end_inset + +, respectively. + Such unary factors are applicable for measurements +\begin_inset Formula $z_{t}$ +\end_inset + + that depend +\emph on +only +\emph default + on the current robot pose, e.g., GPS readings, correlation of a laser range-finde +r in a pre-existing map, or indeed the presence of absence of ceiling lights + (see +\begin_inset CommandInset citation +LatexCommand citet +key "Dellaert99b" + +\end_inset + + for that amusing example). +\end_layout + +\begin_layout Subsection +Defining Custom Factors +\end_layout + +\begin_layout Standard +In GTSAM, you can create custom unary factors by deriving a new class from + the built-in class +\series bold +\emph on +NoiseModelFactor1 +\series default +\emph default +, which implements a unary factor corresponding to a measurement likelihood + with a Gaussian noise model, +\begin_inset Formula +\[ +L(q;m)=exp\left\{ -\frac{1}{2}\SqrMah{h(q)}{m}{\Sigma}\right\} \define f(q) +\] + +\end_inset + +where +\begin_inset Formula $m$ +\end_inset + + is the measurement, +\begin_inset Formula $q$ +\end_inset + + is the unknown variable, +\begin_inset Formula $h(q)$ +\end_inset + + is a (possibly nonlinear) measurement function, and +\begin_inset Formula $\Sigma$ +\end_inset + + is the noise covariance. + Note that +\begin_inset Formula $m$ +\end_inset + + is considered +\emph on +known +\emph default + above, and the likelihood +\begin_inset Formula $L(q;m)$ +\end_inset + + +\begin_inset Note Note +status open + +\begin_layout Plain Layout + of +\begin_inset Formula $q$ +\end_inset + + given +\begin_inset Formula $m$ +\end_inset + + +\end_layout + +\end_inset + + will only ever be evaluated as a function of +\begin_inset Formula $q$ +\end_inset + +, which explains why it is a unary factor +\begin_inset Formula $f(q)$ +\end_inset + +. + It is always the unknown variable +\begin_inset Formula $q$ +\end_inset + + that is either likely or unlikely, given the measurement. + +\end_layout + +\begin_layout Standard + +\series bold +Note: +\series default +many people get this backwards, often misled by the conditional density + notation +\begin_inset Formula $P(m|q)$ +\end_inset + +. + In fact, the likelihood +\begin_inset Formula $L(q;m)$ +\end_inset + + is +\emph on +defined +\emph default + as any function of +\begin_inset Formula $q$ +\end_inset + + proportional to +\begin_inset Formula $P(m|q)$ +\end_inset + +. +\end_layout + +\begin_layout Standard +Listing +\begin_inset CommandInset ref +LatexCommand vref +reference "listing:LocalizationFactor" + +\end_inset + + shows an example on how to define the custom factor class +\series bold +\emph on +UnaryFactor +\series default +\emph default + which implements a +\begin_inset Quotes eld +\end_inset + +GPS-like +\begin_inset Quotes erd +\end_inset + + measurement likelihood: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/LocalizationFactor.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/LocalizationExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:LocalizationFactor},language={C++},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In defining the derived class on line 1, we provide the template argument + +\series bold +\emph on +Pose2 +\series default +\emph default + to indicate the type of the variable +\begin_inset Formula $q$ +\end_inset + +, whereas the measurement is stored as the instance variables +\series bold +\emph on +mx_ +\series default +\emph default + and +\series bold +\emph on +my_ +\series default +\emph default +, defined on line 2. + The constructor on lines 5-6 simply passes on the variable key +\begin_inset Formula $j$ +\end_inset + + and the noise model to the superclass, and stores the measurement values + provided. + The most important function to has be implemented by every factor class + is +\series bold +\emph on +evaluateError +\series default +\emph default +, which should return +\begin_inset Formula +\[ +E(q)\define h(q)-m +\] + +\end_inset + +which is done on line 12. + Importantly, because we want to use this factor for nonlinear optimization + (see e.g., +\begin_inset CommandInset citation +LatexCommand citealt +key "Dellaert06ijrr" + +\end_inset + + for details), whenever the optional argument +\begin_inset Formula $H$ +\end_inset + + is provided, a +\series bold +\emph on +Matrix +\series default +\emph default + reference, the function should assign the +\series bold +Jacobian +\series default + of +\begin_inset Formula $h(q)$ +\end_inset + + to it, evaluated at the provided value for +\begin_inset Formula $q$ +\end_inset + +. + This is done for this example on line 11. + In this case, the Jacobian of the 2-dimensional function +\begin_inset Formula $h$ +\end_inset + +, which just returns the position of the robot, +\begin_inset Formula +\[ +h(q)=\left[\begin{array}{c} +q_{x}\\ +q_{y} +\end{array}\right] +\] + +\end_inset + + with respect the 3-dimensional pose +\begin_inset Formula $q=\left(q_{x},q_{y},q_{\theta}\right)$ +\end_inset + +, yields the following simple +\begin_inset Formula $2\times3$ +\end_inset + + matrix: +\end_layout + +\begin_layout Standard +\begin_inset Formula +\[ +H=\left[\begin{array}{ccc} +1 & 0 & 0\\ +0 & 1 & 0 +\end{array}\right] +\] + +\end_inset + + +\end_layout + +\begin_layout Subsection +Using Custom Factors +\end_layout + +\begin_layout Standard +The following C++ code fragment illustrates how to create and add custom + factors to a factor graph: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/LocalizationExample2.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/LocalizationExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:LocalizationExample2},language={C++},numbers=left" + +\end_inset + + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In Listing +\begin_inset CommandInset ref +LatexCommand vref +reference "listing:LocalizationExample2" + +\end_inset + +, we create the noise model on line 2-3, which now specifies two standard + deviations on the measurements +\begin_inset Formula $m_{x}$ +\end_inset + + and +\begin_inset Formula $m_{y}$ +\end_inset + +. + On lines 4-6 we create +\series bold +\emph on +shared_ptr +\series default +\emph default + versions of three newly created +\series bold +\emph on +UnaryFactor +\series default +\emph default + instances, and add them to graph. + GTSAM uses shared pointers to refer to factors in factor graphs, and +\series bold +\emph on +boost::make_shared +\series default +\emph default + is a convenience function to simultaneously construct a class and create + a +\series bold +\emph on +shared_ptr +\series default +\emph default + to it. + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +and on lines 4-6 we add three newly created +\series bold +\emph on +UnaryFactor +\series default +\emph default + instances to the graph. +\end_layout + +\end_inset + + We obtain the factor graph from Figure +\begin_inset CommandInset ref +LatexCommand vref +reference "fig:LocalizationFG" + +\end_inset + +. + +\family typewriter +\size small + +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +The relevant output from running the example is as follows: +\family typewriter +\size small + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/LocalizationOutput4.txt" + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Subsection +Full Posterior Inference +\end_layout + +\begin_layout Standard +The three GPS factors are enough to fully constrain all unknown poses and + tie them to a +\begin_inset Quotes eld +\end_inset + +global +\begin_inset Quotes erd +\end_inset + + reference frame, including the three unknown orientations. + If not, GTSAM would have exited with a singular matrix exception. + The marginals can be recovered exactly as in Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Full-Posterior-Inference" + +\end_inset + +, and the solution and marginal covariances are now given by the following: +\size footnotesize + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/LocalizationOutput5.txt" + +\end_inset + + +\end_layout + +\begin_layout Standard +Comparing this with the covariance matrices in Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sub:Full-Posterior-Inference" + +\end_inset + +, we can see that the uncertainty no longer grows without bounds as measurement + uncertainty accumulates. + Instead, the +\begin_inset Quotes eld +\end_inset + +GPS +\begin_inset Quotes erd +\end_inset + + measurements more or less constrain the poses evenly, as expected. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Float figure +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/Odometry.pdf + width 80text% + BoundingBox 70bp 310bp 525bp 500bp + clip + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Caption Standard + +\begin_layout Plain Layout +Odometry marginals +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\align center +\begin_inset space ~ +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\align center +\begin_inset Float figure +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/Localization.pdf + width 80text% + BoundingBox 70bp 310bp 525bp 500bp + clip + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +\begin_inset Caption Standard + +\begin_layout Plain Layout +Localization Marginals +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:CompareMarginals" + +\end_inset + +Comparing the marginals resulting from the +\begin_inset Quotes eld +\end_inset + +odometry +\begin_inset Quotes erd +\end_inset + + factor graph in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:OdometryFG" + +\end_inset + + and the +\begin_inset Quotes eld +\end_inset + +localization +\begin_inset Quotes erd +\end_inset + + factor graph in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:LocalizationFG" + +\end_inset + +. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +It helps a lot when we view this graphically, as in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:CompareMarginals" + +\end_inset + +, where I show the marginals on position as covariance ellipses that contain + 68.26% of all probability mass. + For the odometry marginals, it is immediately apparent from the figure + that (1) the uncertainty on pose keeps growing, and (2) the uncertainty + on angular odometry translates into increasing uncertainty on y. + The localization marginals, in contrast, are constrained by the unary factors + and are all much smaller. + In addition, while less apparent, the uncertainty on the middle pose is + actually smaller as it is constrained by odometry from two sides. +\end_layout + +\begin_layout Standard +You might now be wondering how we produced these figures. + The answer is via the MATLAB interface of GTSAM, which we will demonstrate + in the next section. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +\begin_inset CommandInset label +LatexCommand label +name "sec:Pose2SLAM" + +\end_inset + + +\begin_inset CommandInset label +LatexCommand label +name "sec:WithMarginals" + +\end_inset + +PoseSLAM +\end_layout + +\begin_layout Subsection +Loop Closure Constraints +\end_layout + +\begin_layout Standard +The simplest instantiation of a SLAM problem is +\series bold +PoseSLAM +\series default +, which avoids building an explicit map of the environment. + The goal of SLAM is to simultaneously localize a robot and map the environment + given incoming sensor measurements +\begin_inset CommandInset citation +LatexCommand citep +key "DurrantWhyte06ram" + +\end_inset + +. + Besides wheel odometry, one of the most popular sensors for robots moving + on a plane is a 2D laser-range finder, which provides both odometry constraints + between successive poses, and loop-closure constraints when the robot re-visits + a previously explored part of the environment. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/FactorGraph3.pdf + scale 80 + BoundingBox 40bp 585bp 330bp 710bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:Pose2SLAM" + +\end_inset + +Factor graph for PoseSLAM. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + A factor graph example for PoseSLAM is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:Pose2SLAM" + +\end_inset + +. + The following C++ code, included in GTSAM as an example, creates this factor + graph in code: +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/Pose2SLAMExample.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/Pose2SLAMExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:Pose2SLAMExample},language={C++},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + As before, lines 1-4 create a nonlinear factor graph and add the unary + factor +\begin_inset Formula $f_{0}(x_{1})$ +\end_inset + +. + As the robot travels through the world, it creates binary factors +\begin_inset Formula $f_{t}(x_{t},x_{t+1})$ +\end_inset + + corresponding to odometry, added to the graph in lines 6-12 (Note that + M_PI_2 refers to pi/2). + But line 15 models a different event: a +\series bold +loop closure +\series default +. + For example, the robot might recognize the same location using vision or + a laser range finder, and calculate the geometric pose constraint to when + it first visited this location. + This is illustrated for poses +\begin_inset Formula $x_{5}$ +\end_inset + + and +\begin_inset Formula $x_{2}$ +\end_inset + +, and generates the (red) loop closing factor +\begin_inset Formula $f_{5}(x_{5},x_{2})$ +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename figures/PoseSLAM/example.pdf + width 80text% + BoundingBox 30bp 170bp 610bp 630bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:example" + +\end_inset + +The result of running optimize on the factor graph in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:Pose2SLAM" + +\end_inset + +. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +We can optimize this factor graph as before, by creating an initial estimate + of type +\series bold +\emph on +Values +\series default +\emph default +, and creating and running an optimizer. + The result is shown graphically in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:example" + +\end_inset + +, along with covariance ellipses shown in green. + These covariance ellipses in 2D indicate the marginal over position, over + all possible orientations, and show the area which contain 68.26% of the + probability mass (in 1D this would correspond to one standard deviation). + The graph shows in a clear manner that the uncertainty on pose +\begin_inset Formula $x_{5}$ +\end_inset + + is now much less than if there would be only odometry measurements. + The pose with the highest uncertainty, +\begin_inset Formula $x_{4}$ +\end_inset + +, is the one furthest away from the unary constraint +\begin_inset Formula $f_{0}(x_{1})$ +\end_inset + +, which is the only factor tying the graph to a global coordinate frame. +\end_layout + +\begin_layout Standard +The figure above was created using an interface that allows you to use GTSAM + from within MATLAB, which provides for visualization and rapid development. + We discuss this next. +\end_layout + +\begin_layout Subsection +Using the MATLAB Interface +\end_layout + +\begin_layout Standard +A large subset of the GTSAM functionality can be accessed through wrapped + classes from within MATLAB +\begin_inset Foot +status open + +\begin_layout Plain Layout +GTSAM also allows you to wrap your own custom-made classes, although this + is outside the scope of this manual +\end_layout + +\end_inset + +. + The following code excerpt is the MATLAB equivalent of the C++ code in + Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:Pose2SLAMExample" + +\end_inset + +:` +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/Pose2SLAMExample.m" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/matlab/Pose2SLAMExample.m},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:Pose2SLAMExample-MATLAB},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Note that the code is almost identical, although there are a few syntax + and naming differences: +\end_layout + +\begin_layout Itemize +Objects are created by calling a constructor instead of allocating them + on the heap. +\end_layout + +\begin_layout Itemize +Namespaces are done using dot notation, i.e., +\series bold +\emph on +noiseModel::Diagonal::SigmasClasses +\series default +\emph default + becomes +\series bold +\emph on +noiseModel.Diagonal.Sigmas +\series default +\emph default +. +\end_layout + +\begin_layout Itemize + +\series bold +\emph on +Vector +\series default +\emph default + and +\series bold +\emph on +Matrix +\series default +\emph default + classes in C++ are just vectors/matrices in MATLAB. +\end_layout + +\begin_layout Itemize +As templated classes do not exist in MATLAB, these have been hardcoded in + the GTSAM interface, e.g., +\series bold +\emph on +PriorFactorPose2 +\series default +\emph default + corresponds to the C++ class +\series bold +\emph on +PriorFactor +\series default +\emph default +, etc. +\end_layout + +\begin_layout Standard +After executing the code, you can call +\emph on +whos +\emph default +on the MATLAB command prompt to see the objects created. + Note that the indicated +\emph on +Class +\emph default + corresponds to the wrapped C++ classes: +\size small + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/whos.txt" + +\end_inset + + +\size default + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In addition, any GTSAM object can be examined in detail, yielding identical + output to C++: +\size small + +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/print.txt" + +\end_inset + + +\size default + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + And it does not stop there: we can also call some of the functions defined + for factor graphs. + E.g., +\end_layout + +\begin_layout Standard + +\size small +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/calls.txt" + +\end_inset + + +\size default + +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + computes the sum-squared error +\begin_inset Formula $\frac{1}{2}\sum_{i}\SqrMah{h_{i}(X_{i})}{z_{i}}{\Sigma}$ +\end_inset + + before and after optimization. +\end_layout + +\begin_layout Subsection +Reading and Optimizing Pose Graphs +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/w100-result.pdf + width 80text% + BoundingBox 30bp 170bp 610bp 630bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:w100" + +\end_inset + +MATLAB plot of small Manhattan world example with 100 poses (due to Ed Olson). + The initial estimate is shown in green. + The optimized trajectory, with covariance ellipses, in blue. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +The ability to work in MATLAB adds a much quicker development cycle, and + effortless graphical output. + The optimized trajectory in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:w100" + +\end_inset + + was produced by the code below, in which +\emph on +load2D +\emph default + reads TORO files. + To see how plotting is done, refer to the full source code. +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/Pose2SLAMExample-graph.m" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/matlab/Pose2SLAMExample-graph.m},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:Pose2SLAMExample-graph},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Subsection +PoseSLAM in 3D +\end_layout + +\begin_layout Standard +PoseSLAM can easily be extended to 3D poses, but some care is needed to + update 3D rotations. + GTSAM supports both +\series bold +quaternions +\series default + and +\begin_inset Formula $3\times3$ +\end_inset + + +\series bold +rotation matrices +\series default +to represent 3D rotations. + The selection is made via the compile flag GTSAM_USE_QUATERNIONS. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/sphere2500-result.pdf + width 70text% + BoundingBox 60bp 150bp 610bp 610bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:w100-1" + +\end_inset + +3D plot of sphere example (due to Michael Kaess). + The very wrong initial estimate, derived from odometry, is shown in green. + The optimized trajectory is shown red. + Code below: +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/Pose3SLAMExample-graph.m" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/matlab/Pose3SLAMExample-graph.m},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:Pose3SLAMExample-graph-1},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Section +\begin_inset CommandInset label +LatexCommand label +name "sec:Landmark-based-SLAM" + +\end_inset + +Landmark-based SLAM +\end_layout + +\begin_layout Subsection +Basics +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/FactorGraph4.pdf + scale 80 + BoundingBox 50bp 590bp 290bp 710bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:SLAM" + +\end_inset + +Factor graph for landmark-based SLAM +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In +\series bold +landmark-based SLAM +\series default +, we explicitly build a map with the location of observed landmarks, which + introduces a second type of variable in the factor graph besides robot + poses. + An example factor graph for a landmark-based SLAM example is shown in Figure + +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:SLAM" + +\end_inset + +, which shows the typical connectivity: poses are connected in an odometry + Markov chain, and landmarks are observed from multiple poses, inducing + binary factors. + In addition, the pose +\begin_inset Formula $x_{1}$ +\end_inset + + has the usual prior on it. +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename figures/PlanarSLAM/example.pdf + scale 47 + BoundingBox 90bp 220bp 520bp 555bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:PlanarSLAMExample" + +\end_inset + +The optimized result along with covariance ellipses for both poses (in green) + and landmarks (in blue). + Also shown are the trajectory (red) and landmark sightings (cyan). +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +The factor graph from Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:SLAM" + +\end_inset + + can be created using the MATLAB code in Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:PlanarSLAMExample" + +\end_inset + +. + As before, on line 2 we create the factor graph, and Lines 8-18 create + the prior/odometry chain we are now familiar with. + However, the code on lines 20-26 is new: it creates three +\series bold +measurement factors +\series default +, in this case +\begin_inset Quotes eld +\end_inset + +bearing/range +\begin_inset Quotes erd +\end_inset + + measurements from the pose to the landmark. +\end_layout + +\begin_layout Standard +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/PlanarSLAMExample.m" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/matlab/PlanarSLAMExample.m},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:PlanarSLAMExample},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Subsection +Of Keys and Symbols +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + The only unexplained code is on lines 4-6: here we create integer keys + for the poses and landmarks using the +\series bold +\emph on +symbol +\series default +\emph default + function. + In GTSAM, we address all variables using the +\series bold +\emph on +Ke +\emph default +y +\series default + type, which is just a typedef to +\series bold +\emph on +size_t +\series default +\emph default + +\begin_inset Foot +status open + +\begin_layout Plain Layout +a 32 or 64 bit integer, depending on your platform +\end_layout + +\end_inset + +. + The keys do not have to be numbered continuously, but they do have to be + unique within a given factor graph. + For factor graphs with different types of variables, we provide the +\series bold +\emph on +symbol +\series default +\emph default + function in MATLAB, and the +\series bold +\emph on +Symbol +\series default +\emph default + type in C++, to help you create (large) integer keys that are far apart + in the space of possible keys, so you don't have to think about starting + the point numbering at some arbitrary offset. + To create a a +\emph on +symbol key +\emph default + you simply provide a character and an integer index. + You can use base 0 or 1, or use arbitrary indices: it does not matter. + In the code above, we we use 'x' for poses, and 'l' for landmarks. +\begin_inset Note Note +status collapsed + +\begin_layout Plain Layout +, and use the resulting keys +\series bold +\emph on +i1 +\series default +\emph default +, +\series bold +\emph on +i2 +\series default +\emph default +, +\series bold +\emph on +i3 +\series default +\emph default +, +\series bold +\emph on +j1 +\series default +\emph default +, and +\series bold +\emph on +j2 +\series default +\emph default + to create the factors in the correct way. +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +The optimized result for the factor graph created by Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:PlanarSLAMExample" + +\end_inset + + is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:PlanarSLAMExample" + +\end_inset + +, and it is readily apparent that the landmark +\begin_inset Formula $l_{1}$ +\end_inset + + with two measurements is better localized. + In MATLAB we can also examine the actual numerical values, and doing so + reveals some more GTSAM magic: +\end_layout + +\begin_layout Standard + +\size small +\begin_inset CommandInset include +LatexCommand verbatiminput +filename "Code/PlanarSLAMExample.txt" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + Indeed, the keys generated by symbol are automatically detected by the + +\series bold +\emph on +print +\series default +\emph default + method in the +\series bold +\emph on +Values +\series default +\emph default + class, and rendered in human-readable form +\begin_inset Quotes eld +\end_inset + +x1 +\begin_inset Quotes erd +\end_inset + +, +\begin_inset Quotes eld +\end_inset + +l2 +\begin_inset Quotes erd +\end_inset + +, etc, rather than as large, unwieldy integers. + This magic extends to most factors and other classes where the +\series bold +Key +\series default + type is used. +\end_layout + +\begin_layout Subsection +A Larger Example +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/littleRobot.pdf + width 90text% + BoundingBox 0bp 200bp 612bp 600bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:littleRobot" + +\end_inset + +A larger example with about 100 poses and 30 or so landmarks, as produced + by gtsam_examples/PlanarSLAMExample_graph.m +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +GTSAM comes with a slightly larger example that is read from a .graph file + by PlanarSLAMExample_graph.m, shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:littleRobot" + +\end_inset + +. + To not clutter the figure only the marginals are shown, not the lines of + sight. + This example, with 119 (multivariate) variables and 517 factors optimizes + in less than 10 ms. +\end_layout + +\begin_layout Subsection +A Real-World Example +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename figures/PlanarSLAM/Victoria.pdf + width 90text% + BoundingBox 0bp 0bp 420bp 180bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:Victoria-1" + +\end_inset + +Small section of optimized trajectory and landmarks (trees detected in a + laser range finder scan) from data recorded in Sydney's Victoria Park (dataset + due to Jose Guivant, U. + Sydney). +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +A real-world example is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:Victoria-1" + +\end_inset + +, using data from a well known dataset collected in Sydney's Victoria Park, + using a truck equipped with a laser range-finder. + The covariance matrices in this figure were computed very efficiently, + as explained in detail in +\begin_inset CommandInset citation +LatexCommand citep +key "Kaess09ras" + +\end_inset + +. + The exact covariances (blue, smaller ellipses) obtained by our fast algorithm + coincide with the exact covariances based on full inversion (orange, mostly + hidden by blue). + The much larger conservative covariance estimates (green, large ellipses) + were based on our earlier work in +\begin_inset CommandInset citation +LatexCommand citep +key "Kaess08tro" + +\end_inset + +. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +Structure from Motion +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/cube.pdf + width 80text% + BoundingBox 60bp 90bp 612bp 380bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:SFMExample" + +\end_inset + +An optimized +\begin_inset Quotes eld +\end_inset + +Structure from Motion +\begin_inset Quotes erd +\end_inset + + with 10 cameras arranged in a circle, observing the 8 vertices of a +\begin_inset Formula $20\times20\times20$ +\end_inset + + cube centered around the origin. + The camera is rendered with color-coded axes, (RGB for XYZ) and the viewing + direction is is along the positive Z-axis. + Also shown are the 3D error covariance ellipses for both cameras and points. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + +\series bold + Structure from Motion +\series default + (SFM) is a technique to recover a 3D reconstruction of the environment + from corresponding visual features in a collection of +\emph on +unordered +\emph default + images, see Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:SFMExample" + +\end_inset + +. + In GTSAM this is done using exactly the same factor graph framework, simply + using SFM-specific measurement factors. + In particular, there is a +\series bold +projection factor +\series default + that calculates the reprojection error +\begin_inset Formula $f(x_{i},p_{j};z_{ij},K)$ +\end_inset + + for a given camera pose +\begin_inset Formula $x_{i}$ +\end_inset + + (a +\series bold +\emph on +Pose3 +\series default +\emph default +) and point +\begin_inset Formula $p_{j}$ +\end_inset + + (a +\series bold +\emph on +Point3 +\series default +\emph default +). + The factor is parameterized by the 2D measurement +\begin_inset Formula $z_{ij}$ +\end_inset + + (a +\series bold +\emph on +Point2 +\series default +\emph default +), and known calibration parameters +\begin_inset Formula $K$ +\end_inset + + (of type +\series bold +\emph on +Cal3_S2 +\series default +\emph default +). + The following listing shows how to create the factor graph: +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/SFMExample.m" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/matlab/SFMExample.m},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:SFMExample},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +\begin_inset ERT +status open + +\begin_layout Plain Layout + + +\backslash +noindent +\end_layout + +\end_inset + + In Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:SFMExample" + +\end_inset + +, assuming that the factor graph was already created, we add measurement + factors in the double loop. + We loop over images with index +\begin_inset Formula $i$ +\end_inset + +, and in this example the data is given as two cell arrays: Z{i} specifies + a set of measurements +\begin_inset Formula $z_{k}$ +\end_inset + + in image +\begin_inset Formula $i$ +\end_inset + +, and +\begin_inset Formula $J\{i\}$ +\end_inset + + specifies the corresponding point index. + The specific factor type we use is a +\series bold +\emph on +GenericProjectionFactorCal3_S2 +\series default +\emph default +, which is the MATLAB equivalent of the C++ class +\series bold +\emph on +GenericProjectionFactor +\series default +\emph default +, where +\series bold +\emph on +Cal3_S2 +\series default +\emph default + is the camera calibration type we choose to use (the standard, no-radial + distortion, 5 parameter calibration matrix). + As before landmark-based SLAM (Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sec:Landmark-based-SLAM" + +\end_inset + +), here we use symbol keys except we now use the character 'p' to denote + points, rather than 'l' for landmark. +\end_layout + +\begin_layout Standard +Important note: a very tricky and difficult part of making SFM work is (a) + data association, and (b) initialization. + GTSAM does neither of these things for you: it simply provides the +\begin_inset Quotes eld +\end_inset + +bundle adjustment +\begin_inset Quotes erd +\end_inset + + optimization. + In the example, we simply assume the data association is known (it is encoded + in the J sets), and we initialize with the ground truth, as the intent + of the example is simply to show you how to set up the optimization problem. +\end_layout + +\begin_layout Section +iSAM: Incremental Smoothing and Mapping +\end_layout + +\begin_layout Standard +GTSAM provides an incremental inference algorithm based on a more advanced + graphical model, the Bayes tree, which is kept up to date by the +\series bold +iSAM +\series default + algorithm (incremental Smoothing and Mapping, see +\begin_inset CommandInset citation +LatexCommand citet +key "Kaess08tro,Kaess12ijrr" + +\end_inset + + for an in-depth treatment). + For mobile robots operating in real-time it is important to have access + to an updated map as soon as new sensor measurements come in. + iSAM keeps the map up-to-date in an efficient manner. + +\end_layout + +\begin_layout Standard +Listing +\begin_inset CommandInset ref +LatexCommand ref +reference "listing:iSAMExample" + +\end_inset + + shows how to use iSAM in a simple visual SLAM example. + In line 1-2 we create a +\series bold +\emph on +NonlinearISAM +\series default +\emph default + object which will relinearize and reorder the variables every 3 steps. + The corect value for this parameter depends on how non-linear your problem + is and how close you want to be to gold-standard solution at every step. + In iSAM 2.0, this parameter is not needed, as iSAM2 automatically determines + when linearization is needed and for which variables. +\end_layout + +\begin_layout Standard +The example involves eight 3D points that are seen from eight successive + camera poses. + Hence in the first step -which is omitted here- all eight landmarks and + the first pose are properly initialized. + In the code this is done by perturbing the known ground truth, but in a + real application great care is needed to properly initialize poses and + landmarks, especially in a monocular sequence. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\begin_inset CommandInset include +LatexCommand lstinputlisting +filename "Code/VisualISAMExample.cpp" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},caption={Excerpt from examples/VisualISAMExample.cpp},captionpos=b,frame=single,identifierstyle={\\bfseries},label={listing:iSAMExample},language={Matlab},numbers=left" + +\end_inset + + +\end_layout + +\begin_layout Standard +The remainder of the code illustrates a typical iSAM loop: +\end_layout + +\begin_layout Enumerate +Create factors for new measurements. + Here, in lines 9-18, a small +\series bold +\emph on +NonlinearFactorGraph +\series default +\emph default + is created to hold the new factors of type +\series bold +\emph on +GenericProjectionFactor +\series default +\emph default +. +\end_layout + +\begin_layout Enumerate +Create an initial estimate for all newly introduced variables. + In this small example, all landmarks have been observed in frame 1 and + hence the only new variable that needs to be initialized at each time step + is the new pose. + This is done in lines 20-22. + Note we assume a good initial estimate is available as +\emph on +initial_x[i] +\emph default +. +\end_layout + +\begin_layout Enumerate +Finally, we call +\emph on +isam.update() +\emph default +, which takes the factors and initial estimates, and incrementally updates + the solution, which is available through the method +\emph on +isam.estimate() +\emph default +, if desired. +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\end_layout + +\begin_layout Section +More Applications +\end_layout + +\begin_layout Standard +While a detailed discussion of all the things you can do with GTSAM will + take us too far, below is a small survey of what you can expect to do, + and which we did using GTSAM. +\end_layout + +\begin_layout Standard +\begin_inset Note Note +status open + +\begin_layout Plain Layout +\begin_inset Float figure +wide false +sideways false +status collapsed + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename figures/SAM/FactorGraph.pdf + scale 80 + BoundingBox 40bp 600bp 300bp 792bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:Filtering" + +\end_inset + +Factor graph explanation of Filtering. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Plain Layout +The factor graph for landmark-based SLAM is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:Filtering" + +\end_inset + +. +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Subsection +Conjugate Gradient Optimization +\end_layout + +\begin_layout Standard +\begin_inset Float figure +placement h +wide false +sideways false +status open + +\begin_layout Plain Layout +\align center +\begin_inset Graphics + filename images/Beijing.pdf + width 70text% + BoundingBox 100bp 240bp 500bp 550bp + clip + +\end_inset + + +\begin_inset Caption Standard + +\begin_layout Plain Layout +\begin_inset CommandInset label +LatexCommand label +name "fig:Beijing" + +\end_inset + + A map of Beijing, with a spanning tree shown in black, and the remaining + +\emph on +loop-closing +\emph default + constraints shown in red. + A spanning tree can be used as a +\emph on +preconditioner +\emph default + by GTSAM. +\end_layout + +\end_inset + + +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +GTSAM also includes efficient preconditioned conjugate gradients (PCG) methods + for solving large-scale SLAM problems. + While direct methods, popular in the literature, exhibit quadratic convergence + and can be quite efficient for sparse problems, they typically require + a lot of storage and efficient elimination orderings to be found. + In contrast, iterative optimization methods only require access to the + gradient and have a small memory footprint, but can suffer from poor convergenc +e. + Our method, +\emph on +subgraph preconditioning +\emph default +, explained in detail in +\begin_inset CommandInset citation +LatexCommand citet +key "Dellaert10iros,Jian11iccv" + +\end_inset + +, combines the advantages of direct and iterative methods, by identifying + a sub-problem that can be easily solved using direct methods, and solving + for the remaining part using PCG. + The easy sub-problems correspond to a spanning tree, a planar subgraph, + or any other substructure that can be efficiently solved. + An example of such a subgraph is shown in Figure +\begin_inset CommandInset ref +LatexCommand ref +reference "fig:Beijing" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +Visual Odometry +\end_layout + +\begin_layout Standard +A gentle introduction to vision-based sensing is +\series bold +Visual Odometry +\series default + (abbreviated VO, see e.g. + +\begin_inset CommandInset citation +LatexCommand citet +key "Nister04cvpr2" + +\end_inset + +), which provides pose constraints between successive robot poses by tracking + or associating visual features in successive images taken by a camera mounted + rigidly on the robot. + GTSAM includes both C++ and MATLAB example code, as well as VO-specific + factors to help you on the way. +\end_layout + +\begin_layout Subsection +Visual SLAM +\end_layout + +\begin_layout Standard + +\series bold +Visual SLAM +\series default + (see e.g., +\begin_inset CommandInset citation +LatexCommand citet +key "Davison03iccv" + +\end_inset + +) is a SLAM variant where 3D points are observed by a camera as the camera + moves through space, either mounted on a robot or moved around by hand. + GTSAM, and particularly iSAM (see below), can easily be adapted to be used + as the back-end optimizer in such a scenario. +\end_layout + +\begin_layout Subsection +Fixed-lag Smoothing and Filtering +\end_layout + +\begin_layout Standard +GTSAM can easily perform recursive estimation, where only a subset of the + poses are kept in the factor graph, while the remaining poses are marginalized + out. + In all examples above we explicitly optimize for all variables using all + available measurements, which is called +\series bold +Smoothing +\series default + because the trajectory is +\begin_inset Quotes eld +\end_inset + +smoothed +\begin_inset Quotes erd +\end_inset + + out, and this is where GTSAM got its name (GT +\emph on +Smoothing +\emph default + and Mapping). + When instead only the last few poses are kept in the graph, one speaks + of +\series bold +Fixed-lag Smoothing +\series default +. + Finally, when only the single most recent poses is kept, one speaks of + +\series bold +Filtering +\series default +, and indeed the original formulation of SLAM was filter-based +\begin_inset CommandInset citation +LatexCommand citep +key "Smith87b" + +\end_inset + +. +\end_layout + +\begin_layout Subsection +Discrete Variables and HMMs +\end_layout + +\begin_layout Standard +Finally, factor graphs are not limited to continuous variables: GTSAM can + also be used to model and solve discrete optimization problems. + For example, a Hidden Markov Model (HMM) has the same graphical model structure + as the Robot Localization problem from Section +\begin_inset CommandInset ref +LatexCommand ref +reference "sec:Robot-Localization" + +\end_inset + +, except that in an HMM the variables are discrete. + GTSAM can optimize and perform inference for discrete models. +\end_layout + +\begin_layout Section* +Acknowledgements +\end_layout + +\begin_layout Standard +GTSAM was made possible by the efforts of many collaborators at Georgia + Tech and elsewhere, including but not limited to Doru Balcan, Chris Beall, + Alex Cunningham, Alireza Fathi, Eohan George, Viorela Ila, Yong-Dian Jian, + Michael Kaess, Kai Ni, Carlos Nieto, Duy-Nguyen Ta, Manohar Paluri, Christian + Potthast, Richard Roberts, Grant Schindler, and Stephen Williams. + In addition, Paritosh Mohan helped me with the manual. + Many thanks all for your hard work! +\end_layout + +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\begin_inset CommandInset bibtex +LatexCommand bibtex +bibfiles "../refs" +options "apalike" + +\end_inset + + +\end_layout + +\end_body +\end_document diff --git a/doc/images/Beijing.pdf b/doc/images/Beijing.pdf new file mode 100644 index 000000000..57f11822f Binary files /dev/null and b/doc/images/Beijing.pdf differ diff --git a/doc/images/FactorGraph.pdf b/doc/images/FactorGraph.pdf new file mode 100644 index 000000000..13b0c494b Binary files /dev/null and b/doc/images/FactorGraph.pdf differ diff --git a/doc/images/FactorGraph2.pdf b/doc/images/FactorGraph2.pdf new file mode 100644 index 000000000..df8d47e5c Binary files /dev/null and b/doc/images/FactorGraph2.pdf differ diff --git a/doc/images/FactorGraph3.pdf b/doc/images/FactorGraph3.pdf new file mode 100644 index 000000000..affa329b3 Binary files /dev/null and b/doc/images/FactorGraph3.pdf differ diff --git a/doc/images/FactorGraph4.pdf b/doc/images/FactorGraph4.pdf new file mode 100644 index 000000000..cba5ad2a3 Binary files /dev/null and b/doc/images/FactorGraph4.pdf differ diff --git a/doc/images/Localization.pdf b/doc/images/Localization.pdf new file mode 100644 index 000000000..aded83c63 --- /dev/null +++ b/doc/images/Localization.pdf @@ -0,0 +1,101 @@ +%PDF-1.4 +%쏢 +5 0 obj +<> +stream +x͘ϊ$7 uLQlKw gg  a&׏,Y!,Ȯ,~ݵOyu 1aٓJߦK"~bRȪ?m$@!Cʼ(1G¶>]QdiysW?}>=3ob}>^K BNPN9(a߸並_^8J^؎ {%H_ۯ/)URM` pMEn V唨d-T TATPŕȸB*`TQ&єIB (9/L^Rd T TA`Y]%t)ZTQ&єI䴺l]R MD ե`]*Q0 0ML%B '0D(hJDxD+qRKڈ+Mڍg]RED3-j*E^qi6ž_ jUV7bH +-Q2ahןVh ͨd "o 4 9TDP%P6AF~iĹuD+@k( ьD&7硤Py-lNi`2 +n0ͨdv40M XDD%D6^"wN4 LDe4&ץ</GT}PTHYн}+B3VtN[O`#g< +Dxħ`>?y@cJjDzF\Qe^).{c*r(Or[F(YQ<<"R%FQNxډdSEh%4՞?=e>ҵ]_rȭ&=>MsqqT\YD9v^|Eԕ +g%ynBFW+DU~O%Ϸ=a殤61NA(X9b0Ql|賱bO<z2iV /AaNZzqO%/}kqG^TP> +/Contents 5 0 R +>> +endobj +3 0 obj +<< /Type /Pages /Kids [ +4 0 R +] /Count 1 +>> +endobj +1 0 obj +<> +endobj +7 0 obj +<>endobj +9 0 obj +<> +endobj +10 0 obj +<> +endobj +8 0 obj +<> +endobj +11 0 obj +<> +endobj +12 0 obj +<>stream + + + + + +Artifex Ghostscript 8.54 PDF Writer + +/private/tmp/tpfd5bb1cf_55d8_447e_8f97_d6b24a262922.ps + + + + + +endstream +endobj +2 0 obj +<>endobj +xref +0 13 +0000000000 65535 f +0000001664 00000 n +0000003341 00000 n +0000001605 00000 n +0000001446 00000 n +0000000015 00000 n +0000001426 00000 n +0000001729 00000 n +0000001829 00000 n +0000001770 00000 n +0000001799 00000 n +0000001909 00000 n +0000001967 00000 n +trailer +<< /Size 13 /Root 1 0 R /Info 2 0 R +/ID [<0E15732D337F57A9CB2C0954A12E8EF8><0E15732D337F57A9CB2C0954A12E8EF8>] +>> +startxref +3722 +%%EOF diff --git a/doc/images/Odometry.pdf b/doc/images/Odometry.pdf new file mode 100644 index 000000000..a9adf2ced Binary files /dev/null and b/doc/images/Odometry.pdf differ diff --git a/doc/images/cube.pdf b/doc/images/cube.pdf new file mode 100644 index 000000000..6314d7e4e --- /dev/null +++ b/doc/images/cube.pdf @@ -0,0 +1,559 @@ +%PDF-1.3 +% +4 0 obj +<< /Length 5 0 R /Filter /FlateDecode >> +stream +xUK0 D=ŜiGXvE*D$~3+DQY1Z*A4 .uVG [- UR ")ApYpzW> +endobj +6 0 obj +<< /ProcSet [ /PDF /ImageB /ImageC /ImageI ] /ExtGState << /Gs1 11 0 R >> +/XObject << /Im1 7 0 R /Im2 9 0 R >> >> +endobj +7 0 obj +<< /Length 8 0 R /Type /XObject /Subtype /Image /Width 1539 /Height 972 /ColorSpace +12 0 R /BitsPerComponent 8 /Filter /FlateDecode >> +stream +xYtUusvu[FQ..++}! !BZEP +6`"" =H}gM{o"|sdf9?k.VoES@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@ gq=rx^p|?X7+ +( +( +( +4=9h <cyx!%:FP/Mo"P@P@P@P@I>MnWN2(vBBW x ޅCS%\ׄhL7a2ŪEP@P@P@Pi4$Yì>^aT6CK)&x'|d| 3`&|~\¯pӧq466j[ +( +( +( +ؚC}_QoR + y|ŧ)'ӱ\:X K`)R%Y `N͋vR+ +( +( +( +[3l)di_q1J1ќ +y-ByLldnEI&Yd a=lubY.9,e$)M- Ϯ +( +( +(loRiɧeۊWS/"*>fSɲBbcM)f=LҐ,6沮Y֜EYXؙeנsP@P@P@P \,aw)˘[δ|PּP2ƶR,">+LG]+XhH#Lve;=Yɦ!/]_u%jɲVԵВ%/伥AiP@P@P@P҆26T _UQ[ުdB%#+՚L,criz"feyac6۲ؕ,fs ls9ǁ|Ђ--Y_ +VVv,fm;6aW9GZX`t +( +( +( +-QɊ*vWkUmJoë]Δ22XZ65]91iP> +8ԌChhJoǪ,H] K+;{8^jto^wUP@P@P@4 bC5 ў:V5Q*&eR%Wi93RYќؚϮP,p,cym"p1SliφNŠ,N]V<ڞlACvtYЃvܹ +( +( +( +(pnx% Yс9#w<_ͫռSJrQ_š"6a_ ?x' 8UBX G8Xj6ueC|=Jc~ '6tY~}>P@P@P@xTrMaVGħ5[˝Չߑ7:~5Vufq+KY_"vryT>q99QVP;nl~1=>,y[1lcϽU@P@P@P@*$*ӑ5_Wڅ703jӉ:f>*dA_kJTLC +9J85\sΔrm8֖9PÞx-k/KQ+6pQ.W'S@P@P@P@GFwNj݅i]ywe\u^Zt% +X^κl-aW +9Z U1*gC}i.q˅\.r aD'tablgX7J0ꇱj8u(s9NA^* +( +(Z`|0F³z~m|Gb%; SfWwaxgFw&u|VU̯dIXƎRs3͸ϕf\)J1WJؚsm9݁9ҝ0)Xov=ɶ8uY54Ս`(Vbh`Ps\y̷bVP@P@P܂aKXbnc +4#gFCHD|׌۰ӟ]ҍI]y1n46V[WMUR_ljΖ(Xg (]iy:q+GJA{gg_OZ7UhuX:c~[ưc$qr$ct _P@P@Z WZsEaO!:YO13z^0^zq]У<DO30Fx܅{ pϓx&ĔDbR"b"14HH_9-H,H$p͉ĮD18HO$Kڿ%AP)[q-gs3ǻsa{9:ூ1q<[Ʊc4Frr{p, +( +( +(}$0ޙ+m9׊-f[s,Y|$&y#I%$& !B! x.B +LSJyvb:yYFW^΄WjxS:E5XPɲ +֕ݥ4x!Cwxh؀ A˹8ܓÎcEPO׊sP@P@P@AyZ~xk=ܑk2 Ybj&of2>ň)fDI+Bjw(8bXi;Mc5;] _ufJ&u a\nߞ/m[aykֵbk)9Xĉ{m*.TA] Q<Ξx0C=Z5?A7+BAjNP@P@PLѐtu\0Qڰ#vEmy|ûټŘ,d?œ)JLA@F@AH~U@kq +NYh:̉SUv?vr5ԑQެI?c;JGjJVue hO18ٌ y\ɧjN\ APp9փC=5gK1ɢQԏ!MаǗ{ +( +( +DS^#M,QontR :rmޖ,\^axf//16!9 ,e2$ `l2]"72>1|c9$3ْKC{sXµAwd)YŲv̪Ӂ:0cr{ުfJ; +l)fW\.x: +](KAqGqa=Ʈ>lY?5X>%q|,kDZya( ?5n +( +( +(͈ˁ^'K4(=.ZO.D7;#Y]ɒ +U)B&b>#e34)ƦLW'?SS;PX˺fl.=e4h%ۥG]m8H܄8ߚ=YUɜLk{ռZjFV3IU|P|SN-E,@G9MJ,*]n{'r{[EV;& p0N`~*&V1my+\'|]RMьtvzc?>5:qgZruױ(;`SlxX9! ~8F~4[Fs$95Kҭݛ +( +( +(д@_}D4En r-rgzхXU*aF9b,BF\X˘^L^K1)NB!PH7#0M|Lf2EYQĺ6Pޜ+Os#L4ܦ},=x[w8=ޒrffj&UBV0W[N9199ѐϾ\p2+ڧF$r8^jݓle D@U@$uԅS<7guM dMDmϰ{s)tG9^~vJbQOd8>o0L.s!΂_ğ᫄_#P@~>={o. +*T }L {h YV|_Ŧpۍ]7rt'Ώx!Lx +4-`Ns>iL(fx1c[Jo1/ .~[YldW)x8Ǒf3˗+ifK aVq/+f6xtG&s4r{(̅BOB%,fa. rXR, ?S׌t"(£W ! +W]W +(@S͍[͂&W* LFSѲT4;6 RNPtMn,̜d +jū#37ˁry5IYɇt9􈰛@! +_.l3+aQ Z^Zׁ]0;co_h-'qz s50}H>'~7ߓ<*0^!c!/6KO^13!0RlH-]M8<6@ dG9*ԞkXݝ'uXx:hÓl}=9܋3ݹV{I wqcnυS<'| +ZP R|oZҒU~]QM BOQYН(P@?g֣~kMJP^ +%ڗmʌ2oRg}P%ќx>!-ɢ>^cDc o2%/#b$`'ރaؾ籷]u[-kۧGe. o?̪b[z!vT ۘūr{(TœPR{*aMk[ߗ>ԅ" 5N +qPN!>9ް4=sP&ǯ ͇(%YڬhaV43}BKqa7r)gP(a]ueA :E;>Lw PƗDžA +x>x-7sx73$ŴPLw:] aP@VYPV,hv +wec֛ qdrjg'rm.OA4hiA@vA麸0}ސ,ejdq*aQ.X asMJ;lv汽[Z%k[-VvM7u ;qK-M܃yɅ^0Yd AP}Y C)4/\+65+3ldK2n,cc1XSVY;¥ +( +w6{;@! +49#Ѷhev 3MMFoVC,gsI>zì̯afU1yJYfry"(ipˆ0X]KUg"[ҁ'{;0/hȩW9&G\ƍ0D z..7(-|'dHqI^M.|Dwzv +B,NC-=,lfs +Yۂ-oE]kaEU:hc5 ߖ\nυ~~;c>,L6l,MG=[ڰ5نeG;vT l$[-܌yLoLEr% +(` ͇(д.LEsYT4=}L5CP˾iШu][Ì|VU+e q\,fi/Rro9(,3ߕ:|)0R ZK:;acoc3LKz3r~ +>tn̊  ZGu|5A 43 E `< oq=Ch{L8(2NXka]8皯]s[:U@"+pB/@! NtԳmՖ=U K5{۳/bOvfW+v{`{![٘Ú=B} +hs +(MM>w_AwChZWgE볣hn*KFaB\ƹП?}8[zC,®̮az>J&Rc@q99ʁrd0'ckx8̊p.Nu9oP@}1u,bY'V Q6aePGq©8>?\(-ˁ6mi_n-$B_c MNGAP(M)ad PLR,J7aY mH-`/Bnc93c9$;{QwAwChZT&եYѧq\˹|$;zQV?NLfJ[ޮVPn4^' ŔT<.,C (y!dahf~fy6Yˊ,mI]gyV?vfqd'r]N\oQh+QHI@x:#qP(cP8UDHaXH"ޜqx +ܞ ] K@P̍IfҐ@)ZsJw>?>.\r+h1s(9dG<^Xg\3fA +(P`S| +4!k!?Ehf2)0NAMhpP@~K!Ϭ@7W_~ϟ;egh_At0:]"o^٤  X <ʿ$ĕts%'D@7Rʍkk\z.ײ%"+a^ÁŶlm;9Ϯbz>.grK_fKA/gzA>?L|khX + YTv,Qaol)uN }i\BTGh[h5D 9wARE<}| 018WڞtBOD[ʁ (] fq#ɵۂ#( Y/z/W@~>[cwM?Ob['7'+!Q\A@APw6԰1|܊ɥL,f|sF0<9Lo'>K[Ĝ ¬assA⊠tTʂ2jaI;װzI98Ozsq#}_ %ڔ=St^t :G}uX{ъ(ow} ,;a7N9 7PӜgk] ݁s Dž\ϳ +VAۇ0U}6o(wLPnL37ݍ-9P +$O{ù439O'ۻ#+bN%L,b|a:ǘlgzFߛmŸ+&61;L0'+b^ Z2U0fEg<ԗϰcp:jǑ81os=NgD_lD=挨!ˊD#/6EM@_ cBO( + +bp!dAtaWV:`-?<Rq+y\IOv6Kq(ɾ$a "#(|^<4 7z\ +(+w++po~:[7s8ޗa=X\|U'ׂ/`T.óbB2[09Fݜ8,A&69gN!sZ0yekͼ6, }܏9}#92f\nNߡK͹ԌK\|grӍPRN%5I$脊AjP@d+d%]-7y׉Fqcq bC4tfS;TyQʧżל7 +,LL}tXf%ɷq4-Sœ2fn%ua\Xjuq$q9 ӗpy`ٓEC&SL(|ϠЕA]{}"P@Zcp?}n:5hpGaowjA +˙ߒ|VLFLdx^qQP(ο9wX֢6137)fV. +9mKf+W=kP?>Gμ72smzz”aqE6}DG8Yo~(»$plE]i0.C= '9p&=r8˩t8՜Ӆ*D!GqyeW YlbM$%-C > +(},';)po܈ZG@vv`S[֕S_"ao3 hH2=Ap;VQP(οUIf׹|BfM +[XWlE[?qxpz<_ҤtEPOOC;fE85<<|Z u}MK}\j7/ۭpZ2YL+`J1 aqK1o)6e/SLbz.E|]. +Z؊ebCG6wc{Ov=NW{Yhξ04аxhX +CBEDcgg YAzǟaVS2,.(ID;>{BOB/ M46@ۜ݅(`[[XXbNCq +>< +(IVsiVOamɵJNUr/eeBcj6oewT{yÞǞqX֞g=xcݙǻ4MhrB  B!@2( !!P@B$9g=W]*[UoT]us>{7`f3lWz礃؋F b jAܜMw,F^,NÒt,gX)kcsvv^?H _+OƳ(yeob6?Df7c5l'cA?eP!(M4zlу%m2-gkB0ep6(<|tw,ׇq0?`o6vfaK&6&obyTjZJ@ (%ETj,=H xn}" ?-BlؖuXea|na&-(XؼaA:e`qa +R쌽=qnhKOJTD[¬aK!_Co{Z@%p_/+= q 6ai5=uAl +aK:g`W&dR\|G^Ǟ\llƺLvAsǀ'UJ^%WJ@ ( +QKZ7͍۪ey_p20M!,i A Gv,9E(iѼ " +Ay ַŶvSݨ'0\+P<!A(̓|Ya,6!Ѓ7"S|Z!=ÀFvA61OCXalll|va{>w[bُXUn&e!, bÈxejgUJ@ (%V J6ɢV19qIr˙<-7aD3!v:xjAA|O &pgq~.?cP*B4WِEc}*M$$g +A لZFL>x'&|!|UawY +>dž|wM^9n/eƂ> Jm*$hJ@ (%@ dd%ϲ\,7w{G|Gѿ8sS/zާ FNNJ01gpwĩn8(QA!h*j3Z;Fb QID@$jLʽx]} +G> ^ËƗX醡Գ*ϱq>V0UAtdc UAohhĝAܫPJ@ (%Tz`z%KMDh ߑQAtEi)̦|Iw4lLǮ0fhNNWl0ʇj4jƣiOlDVw%B]ID srݸS5r yXƢLD \O>/r +s 2me&>cVoR#g&iUPJ@ +A~l-/ D~99Vt61M5=@Aǀ8dδ=QCP@<>z)ߊՔ@KRG=<{6勗l;ix?Q&f|88elx=Vhut7kZꕕPJ@ +RJ^@݀o3|i5ĽZ1B+;x+ HNf\AI;TtBMwìE#J(*d"ݽo9 xSvA +;foeblgcϷf&^+aŒ خ2,8e2[ί*%P-A@TA GXMƑit/@(0XlvJPd+{,."uDwfRS}nexwfX9/4Ӄx!/]8Kx!υ1=it +GFb>\WJ@ (%bN@#*$#Т,1V') D2IIO+Oޅ0C=‡SmL jϔ7krSCD/0vs0YML}rT (%-bSϦ@KjH>Z!ݍ[z$ 4 DwƗ.&@y~ŘrW#⿯F.q1nH%PJ VTI=HVqX6oő^H a$""-s+r`.0x>|_KgqάRJ@ (% +APϠ@|VHV@tϐ9-^`O̱Գ)%h6NR@<-H:.QӺ֫'nUӡTJ@ (%A@f@ӯ(!y;!-IӚƓ@tg5ZJ >^^J@ (%pTJ&+xhy{:k)Ƕʨi^[Jn-DF˱3+%hKVFq[Zj}[-ݵFMKTMϙn-Z_-WOPJTj<+=R Vsy-U![j+VJOooq8@K(%/HPLu'_r[kݛMںٵ/[:mꮣ#nBJ@ (%A@{я@ÌV+)Z&a4zpƳ::I[PJnT}_ (عfiev%p_O [HA~;ёNP>$BUx L&c@Umu߲nu8Z%!pKR_([:j*J@ (%n!B-@(o빸i8nm\/S (!7r U(ٻf~X${kb@o'US$>?ut$~W(%@2P!(Zu뇺Ψl|\0N@Xgkm̱&"0x zD/ `0 + ToC$>d-h-+_/3mΩgDPH@m 3!!! C P_B4 X|UJ麯V4IZq%t B7L wJ@ (%TJ]2.U4ȣ BP'TBPNg`;ұ!UA, `7IF/X!AE z= L^i+ N@'BBqJ.6-@ꪧ/'uhɔPJ eUJsu?/v&c'֕o:@W| @P"Bн$gd[A,́y222Q7FG\is8ؒӰXQy; /w|g=PdT;cO'2Zюh% 7 ١r\ѩUP2 )o%\]g ЙR2vRYR$N}]!N 2J@ (%p*JU!!!! !!yӐ!Q;}P:Rf0} {l5FZ>b \wKЎoLz=%EQ&u=HJ hqs6!h"iC!/#.llV1eHϛ(Ќ=ą;Xt>_^c? A66n#6NL+]=QCQ5 +5Ov2g@S6i~d#d0Ag =K /P +"O +[U=qu:FZ%nwiXzI%@P!G%xAd?$=Dt9d* B^"~+EY˅8Uy؝->+= {$5BP1w<#H1ѤSUƗ cMl`g8,\hK]p7n  :F~}j+W,n9 GS(>K o\;G_8j9BKö iZ^ (%7olK3z#sR?NIMw) %yr5]4 +!2 zjb{JWmp( +#͋ AÀ~# 񝇁ǀ +A3w vP0eXW$e7zd+?'Q32ΈA65QѺ@!((eè'n$뽭Q- $A-Fqs1ЌS$GiF+J@ (":VP!(V$[a0 +AtF(HO;yz%/ DğyoF UzzqDǥ!&R#4!ߛ[&W!Q;FzDW 3B-|h38y hBO&DWh%&؞8KY(Eig*Ǣ)LG+gh +V(^1eZ.W(IeԶNq$ċ@Ҍxܟ@tܿ[$L-JϬjA*mX"DސiR;NjJ56R)W? Aی]rcc'P=5ϣuԿgR}ƸFlȎ ʩ4W*ɒ + +Aݤz=zW*Ay +D-_Oדrɮc~ϕP M@nsEfL%1Hi\$u@3~knʰI1(~WB?ڹZ͎,5A,9om +u #"üA=eLh8ю - +4|L8V:;2jԾ:Ff08[ui-]~ ˉ )YR/NL@t~@J@DH╺=IEWJ@ & >w{e婚-J +"DFJ]?$RKFg ¨+z♄* +AP<|?ꁣqBPvfbSV!^(1S#ESi 5zO +All68Rp ~('Q j^B훨 )i!O!(S.dKqA+|׋q5%t}h5Vn9k=kkD>y_%"RL[6CPW掯Ipa\}p`[OBW AB)~a HёL7ƖXXo8'p.FWsWyB[zzQZ d. zJUHG"cDkz{gJ?<ώ@5?o򍨜:0GKYˠh +O{INE#y^I"P28$rA?!V@A+nrI(Q0.^8;Pec=BXE]â #B /@! +A^Lʰ6Iwewde!v 9#B(u]M"@G:9#lTr W/M:K?& +\m yg^q449Fk'&~/z%@ ܢ5拍wdcǴZ-m'D./r=,QzP6% ZyBP{j}Tlm_F A/*k +At +E; `%2! ;s éN8tsrk˨}gnDCr"_εf7-8"oi-@WOy':9}O 4 8i9yc"@!>oj;Є:J|8LX:\jOP)K +O#KY>"EfWʳZXΥQ[лv LeWP,*B(kCqi©.8F!(?fBІ(}ac!0䂧z0_ičcF67b|| +yօ9;y8S.ǵP*Ơj[WPK _Cl3ώ˙VwR_jGL0GSEA'Z#A 0!/&-ho,,[Pb8ZqG  S߆IZv%@RhӘcFBWbfcnT?VϨlKW$q1ƸN (%:)^$A/rjdt9M*[vB6@V@@2KLT@$ÍX=gT0օ\e~^7BSc&CwelY7^b `c:eaOXGꆳF: %PkEVb YN-!Y FTuځR7Z()pItf)@?h%Ԥw xB-F\r27y +A/oO@i[FJ+T޷M b'ƐbVoZ0% {K=T]$Yc4P)r$S.\+l]*u"F!Aq#@vgbskC&&c&_dbw\!ȳ ؖ0XblJ,á!\\E'C5gQkDÐspRF! Ǥ_1IEP|zNY3V!BЫ"?[_Z-<A\O(WyA&XQOڵ"-~w n|sB@ORBHyP{Qc7M,2BPubHe_@n&Խ_UzaLd,N!( 2CkBX?5Bh!c D +AK!ȳfq[N{؞mpvɞ8#(',f53PG!ȳZ +Yi]#kiR#ABW~j-N˓ibq$q X,k =!h0A4by*B+; PZk8ԹOFJodM)jYǛa CgcDtc +AOy h0%' +>w|&"hH$R.Br,MekԾQ,ʟrcTkCrXG;᧶Ç>7wް,PK! xY̯xA]-PY Aq+NA8 WE(sP55ϡ5lэR%ՅRMH="3E>E +A:-eF8"vWse?XZ( "qBPG;oreG+įU^wVOFJݷn 9ղ0h +A9'ucVJ Hq>[iR3NOB-~e+;ȗo%TNCDG\!jo\3q"3ӱ:/Xg϶,.>q, xa|sP5A>>mgsFFqnayԿy) jf^1B*Pj{IR7^ꟕ7D>Ya:-gJr8h4On7&"w5̳XM ^xe[v>)T{?^!h +sZ#i{Cn A>k&]PbD2?JˤP R!(a:Ԍ!RS$RKA9'!ET<(ALqNBk -b,`5ޘ4f~A}L6yטc,3 *Kk?t3ϝF6 +% ^Pzլ\!hMtA̔vRGj'9g|"DV'Lc%lAuNM % +A?siƕiބVvA ׃ =@a/#-6_],yJ<@&ף.xj ~FX7'lgESF㞕'y"u$sU%hAO:&(UvSWgHI\d~nTʧD:W(l!NH{]Â*QˈL@759GP;bL+6i"N36a{`}0/G_"A}DMZ&,󯛌ρoYtd f%cn2#11h4L<y d3At ARY$fkT?A*ڷo-ARPA45ז-h On'ˡD_FԎ(-5BNJdM|D7{xAVeˢ 7X5V[Ĥ oT-(mWSJ@ 4'$h0%RbAuPE-qk_w $ Õ)d<6 *]G#A|?_k`[:vgpi4 7F1+L:N#s !nF[jY%,W*:K~TjOE>(NS EpeG#OC#Oo?51i"-8َq wIe[n2kXTvR;B'LyGBăNcH2)RN_3\N{4àe ˠj-J+ҌBP+re(GgWq aY A4q#i%mR7f 1ZM,>I ,x i+U7hT (%*X!gnu^g +AAFKI({%."A'8dcQVXfq~3f3L@_ +Aeh0.u,ؚ]y;DK]!t*G-g /R̅,| p +TKu''zF%@ cq;ݵ.Ȇ(!- yUQ8JGP\W8/.F5]fqU(h۩A6IM/7hmMW.(N+RFD @P;JZ&L^EGԁrƛL +.~L9-\[@A̬Ro(%Z +A=p-(yao\P*Ơt~Ƞ=E +t, ӰQBEГfw>B@Z  ΁\:|幆a[v@kt/r8jFÐskA)ɖvRݤw 't*4= P0 "iOEЛ 1UN {[}S5c6AmܰQL]7Zhߎgqv iƏ|pӋ&ߎTkλ2-'`9a4l5,lnL OkLdTUJ@ $"n-3oE\7F]djǡQ C \J@=Q#8.-7IrEg}XZ ouf=f-ϖ؛Cmp=u•n((a\Ü\׈VD.ŹR^*K@cZ[֩xtG}GԴAe&EЩװ&Hc`4SNꭾ)#4 + J4 DװpzqFUirP+4 hWdE=PYK40 tCt;Zu5-ZY"|r"hqj~ز.3aIKH*%MSbȇFz 225#Q6\Z.8'lѤSIsm hi~b|SRjkBnq ֏Vɐ3{'Yvg@v W{n2FԌEgtKt:(R%M]}~<:o' +2g!1sDDE[1 o6t6!-DY:rPWnGT jTAJ@ >}:w @{o> rrCA"!ptEmYi4OM +9k% iVs]hYVAI7\-¹BW9=署9\xȇ4႔ڛ𡝌=0~'> n4F |{kuAlIǮLW:ZӴꌫ=]!|Ah  y2 XfְJEP~3iܙ Tgw{522ʵTK!(axYNn! /U41gZipmaA(닚BTfJN`vdaS: `91ZZugU)1e+%88_QQ=uPGװP?!}g-` +񀳝Vk)\X'o +FMl9AA B +#y*+?&qp1 opQPdps`/p +AAmk KWgb0_}=B (%bC15,ZWEYOPq&BPm72q1Gӱ7- +"Qx_O|.TBn.h+,:BY8SXP5=Q0&Íf@^ykmE}7b>y$u~bvOEPe!nZ&.p"QaKL@wLh +Ao9#,Lng,tfrCi( |~4aY~e߲lfDE' Ze-j t 4JU淡~S (_'QC|50J@ (&P!I|q@- 7{p:kúng,qtA@aAL8At ڐ;ػ@Oy тw#BΧrSI.* PBװ5+J@ @>w֑M!RJ@ 4 +AM3=wn]Ƽvo ۏ+D MtA7>MNK/L[b"B ch +A(Q 8BbpiOsphtFqˆ!;J@ (D&:/'u+qHKF&5gݛxSAڱ,Ŵmy3^3 !MhB|s AsL|!:l;pnbz +AAԄP@\]%K FǿmĒ%}5H*%LSť@䛿yFG7sa`7X,3)9A{BPgc Fȳk-"aZk"b(Uj|J@ $d}%=,Y,X (%D*5X2OFnMFJ@ (%@$ĤĹbRf=PJ&fTDf@K;TkPJ  aNBbB rIP AnoFTj$>A:J@ (%NKմJ@ ߌ hI}v'YjuPJ@ (%g:3pPILno +-ɾ$kPPJ@ (%L@qSJ M@BP3%Wd QJ@ (%@ |2rJ@ $75y*=$> +J@ (%h]:l]zu%-=ԛ{|tG2M='7>J@ (%U-$J@ $yqJ5Ii~Oi<< = FどwR`ϪiPJ@ (%|B@ 4C (!40iI3+r6i8 6+e<]`&0%~ rPg# +cI 5}`b Nq9KmUJ~SJ@ (%@4^zPJ4Ria-P@=eTvGu P.ǁj #PyxΈfm|e;ՂN(z%bISϥx0P{у]SSCV@A>7PGe +jǣf7Jz\nS8ؔ*Q? AShΫ vAi)1єhWCsTg\k}qs;Iȳn e>Kw*Ŵ'ɔPD:̚hbM1Γ>e$ >O3l| b}vT@A]> BA7U8 dmԽ{5ap u8!߅<076H8ywؿv*1;D1R┛V 2i3{)4un80>*,`h.d)j ֥WWJ@ (#LbIkf:xةr& ƫTx x!׃’VcSq1ZPµ8 WJ QIWĬ49CAp5 Q!BEГ(}p;NwƑ13]!hI>A;ZWXN+}AxU >M!J0vr^Cp NƹA<Ǡt6BːYO*[6ٲۖ#ir6S%J@ (%oLp@wf_ib[mODx9Cg6-a 8&A⬴J@ (]DrsrNi;jP Li~ +pQŕ8{@g- V,,1Ng<@!Z=sA{!O06cU J3F ATs唀Hm(?lQ>RVJJI#!-Yk? Au9TL'Q=Kq/Nt + Vby&c^o!f!X 1'2+ +AƊ |ٮE8'z`KcqATT<N5ĖȎkt&MȵRJ@ (%;ˁ/LEF!r-Q5+sˡس+!C0>4d=BY /uSJş-q +lvR/W3\HɾleõXfuTi(b0#p!=q+a[;llrMk3?ҺqsscM:1jt(("1 fqK2ufcs.HTO qJϠETZ}db*W,v@`PNˍR>Ldp +VU (%G`IU? &)|7)%Y`>@l?ZΟZ7/]- aㅱ*8zjAj;z&%@3DȋfDkvTz{+r<(m7z8l)?A~/,] Cqz[:`}[7Y< Q=C.0&ò`ybL%91j4D(bg}t|E*krP8{\\|WFLA| 5QGE,{[d˅l/7H`|\'O (%` X | } ^CK!C-h.>AtL19ArY%oc"(;=! YRClL-PFTMNR5JʆJIoV$ t A[v@60ꗡv>mQ2 (\xg!vw֎kEFb͗QPgLFf1/jg44ZJ;? At4۔8Pq;Dža4Wč(}寣j6j]!ѭm~mnː#rfNmT pkZ;I_ -PJ@ 2 lz} ~Cixr (c#YΟ1Xghd%b.3akVnXp) pPwTW/(%ΐIR?$X:əD;((yg!.<!,S +Am`1 +#M6iE +QS"ĞEPP +BL|os!b;3]qkti+]p>kc-6ieSXvȁ6rP.uRKR?k)PJ q8 ? 5b+Uki9Ԃ'}e`A&Rmt|~6>ucmeRzy%,i8į#uN6?$# +/Wb0^~!;XKhQ*(Ɲ|Կ!uϻ2գj)7:ɥB9#'@ >P*P]b_(Eb,N±~8A? Ag*X3&0դs["5=!tl|XWG;L&(>Q+Qw:(h': A)CƑWnN(QJ@ (%Ndӱ+ml]1ˡV-bD ƎM0+-]&\l1X&3z[(x.w+/cY,%=vE=~5?iAjK@P!O~Ծ,5fT}FgVet!YV*XEzA@;62 +A4u:5Gc/EPEЗ!7-(dX-3dtwh N) 󳱌F8H\O9ܜTUsQȮv aّ-x/kݤ R?Cߕe +z}%he8ÙؓalNA JHK!>b  A kGNkF o@ܰzV&p6 +\ .X {>av_Y19]q'o/ +:*]!HUVn|PJT+8}/vRzL*IiM.ʐaٖ^>T*TEZ`GY6-J&BUZ  6+U9,37.4B6;l yyB4#yA\!ȳ=Lg\腋qyQ<gٕrɮ–c;>W>ߝ=]޻=ߖ]-{sٮ˷a 2()3@%$D93_OO!@Tӭ.Ttӝ 'T<©6Z&-"@tr! @$Pfk78Yqgy~5L zH vP +H$Gc~ bQ,D#9 +IX8" kMYLP7oN! (A)Q69CD[Vm>5OTGè4^'t~vե"hK{h="PA72=pт3NS~lʣ@8;le8;򀙵tm< wu&lu^+CQwPQI׭774n3477su#ݰR`zH/M U:6h>Dn?KJ H |N 7~O\Q85x$wݺoj(qAxg뮸₋& bSbtJGnQ8?"++񅌯k^,P=Zd˾J <[N8aXqX5X˯8ŪEap, GJ(c?za;p: n E@DPo'*$ AQjA:*"4^УiqeXιsiܴͩq*Z0v44(CetA{A?*A2?<+;E;qCq޵&l$x!"(x"hzvE:CVC>c1휉2)J0SEP9W#ZMGb7{o_ȒP YuqGd .Ϸ|N`)4J*hk| +:U#nVm((4If_"Pj{;ܐL*2g)a:%X7b),i5q6|5}ia7!Я 7^wb} `A8+F[j q؞c[,DcSZ5h]V`Y |`Xވ}_ot0A(B& " DՈ {*&Q,DU#㇇xɩaCQDP"N 3636m5533ιPr)߇ +*1T=gS8"!ɏ=G%q1`Vb!O|Np$:vCVAF23Xk]<@04Ơe4S@@irsZRP̕Ph a{'Jߍr_Ζki|r,-c~Kjy$$cy(քq>ۣ;YXN%\"'B.&|t NFp P p*o,q\ZU}Ÿ@C@DP/DtMqװԴQ4Ce1zDw|l9^mZk"hsFƕŨjn? oǠ(OcPN c;O֋f^85L.xEPQ\,:]MW+ƺeN kM[[YBrTegEcP; ; B@.p8ȵ[l+bb|f(,b&:=:a3Ypkr^'F/Q(4F瀖6>b`z qߌt jrf~h_8l"Qja@oQ;f-o DŽuXdc}(cp1#8uY]6rXG=1G#4q *=r+2q PPƣm$"hv߲@OxhDFՈ A;h~R;29\8>-3eɴB8e]do];B?GL.Dr,2q-9 ȋW_wHdG + 8}͊&6g_~&3RAi{! @! "E c[DW}'nTgTOoP* ]vγ{~榍U"hfq d 7 ~rG"y~":RXMWZE"pDv~JDϹFPqj5"mQ'5$5GY!`!E [wuVpqhag# +7S\NqT bX8jEf#v;^(?`4Ek 6djnqA }<hyZ PBc-P@\Ww/K Xl"wzc8`(N|2"zq; x<ǣ8cq?wP0`d/N 72csnz,/3(! AFK< dE1꒨Z JE&lUzvP1MmwQEvD -"HAqq,=?Hpz~ߑtʿ)Bo븺 Z0W"#5lJBQĩa3"iyKa~ٍr<)#X*MՓQiO aKG,v@X4D&Aj%g,,'kXhۛ nSF:?SN3Ou +%8dMF4 NYl/C?S(Zu4ڦP+]DЀ:scYeP;mѲ=Pk*#`;{a?qh%.D׵t^!X!п ,mZiQ U-_<|7p5#.^8?X?pAc~(uZ|^&7+.n?^]&Asz[DcNN&ӍH3apWq=nFp(D,cPXǢ&UxϯXhޡ(^0^/ +D?r-#F3497)"諈d! @̵%v SX4w +wCU=xrab,ۜ;5Q"hʹ}G]5A,D#"oa7tNA;u5"!$S|uSFo爠UM-;-mt7㽨ПבT@5y +,4DڽCdBH=m:-0 + (ƛp "WdnZoR#usEP԰;,N VvXQsjͱ:,8{NAĿ&5LAjװj 1[Q'3~qs/].m,StJ9TI|e0XEfka0ɯB@Q@`_ +XMDXT@YDe(_A\eXZSN6|3p:z]_<`TaV/z͜ wJz;ZoF b~5/)*B P Fmky 5̥)T9ʣTڛzz2 6*@WTIT`V hN^X$԰ +"J1԰Z԰C錙2tB`*W*c)S+JWD{INdžD0hh3k`_<(h xGP<2AQҵzqZ0Ae6h.:)|aFpˇa\F?4TMju&lBAY&0Q*o4Up u'm2ڦj]'%ǂACs(ZzTPlD!pد= $Bԫ{đ nՖLM~"U'RE&ȅyf[s[EPAA )zN AE3LM 毖$ .ZO G0AL.|+7p\1$Hf}ViA/8"(%( XSSfSnΙ誉違7TLè-QsRQBWw,\#,jׂ^i1(Iīh<ã ziu*.e;G9EF[z#9cǭjl{7uahDЬ?>G@6E!CxN c#[Qz/yÁbJѰTاEpM4BSFC[Zق:#*xNjm%G=,B@tA݆{f:LUmՖD#FRYph5"~d6Mmja䈠"H"rލYUA8ݡN"ܳE1?,kGxBDL97! +@1U ˌk[=F:jFr;&zhTCAJ-dAD#7_"#}AvA:yaS!# ťƖq#׌_;˸O[A!h ŝ' !  ~&?os޹֊V@-Ü_|6;[ V@ +#.6M8] {'{%-j_]Q~id! 1"z gt/D>SI1f3Ao_7]662644m2h"P?WAUP: + xkŢA,ƹ)h^YqALo:bģˍ`k Ux#<"UTFfk +k m[ v`l#噩J/<5F5'RT/ F?;! @#E;׋^{*l:KAP9 +ejzvA' ):ŤSZgu_S͑`y/d%3r-Zb'J"io@G! ~ 8-EW{{ȮFJ\"'pp8 )b4ʿS/u׏\OJ$WV (k֪$"諈d! @Oԓ?D}6N1TOmSO*4Sޞ]ַѷ7B&4Bb8RXx<V,S" jhpTA6CA6"#>N)Ef1qC /UUSC5id[D3XG^! >AEvh`Km6~ø0qmnf8Svqb['t)Sf 'eAKXAFPƄ.x`Kw@`ع6! #sj&J:=Zh4T @ʟ)ʟ+ʿRPT(q0S8:&ksĸP&OԙQa pZ[~uD}L I"zgY!MTMaTDE>ԃ=h;ChمMhZMqX8<`55,=uG]; rqAAx7t,Fv H ctWA,,P1Z_5I_ꛗi鄞.)kY衕^zRQS(&m +Qg|Ǣ|ab, {*ڦ kF"48\7\3A @@Fk<7k|G!Wc{ɤ"hی8h9=9*Q: l^b')@h@"jNS2(3ESE?!Hagh!:ĵ9((J}Ǹt(6_37p'|+Ձ>*6ɠCWNYZϟ7 (2eEB! @'#LSꔉWieڸ@P `a?,X,R_Y.hfFH46>(u+a|ѯUD2B1_["+6Z)$^Q 7ttMaSQ=Uq(īp< Ž` +5_{a*IoÁOyaZ0Za:}^ ZUtSA\,A0U&l,n*ږVSt.mGLUEP}P> oP䇇\5;2\q' D-%O +P-B>U|\Ⲗ/#~APu8q ɸ8T;?Gjʃo/j GW*"@!cD.,h GQ[5Q`zI驕Y覙2M܁~h݁ hJEc2n +jF""ax:p|E|(:G8? +LҢ8ŃÁ:0:ꦖb~@YZuv" )  +:AFLYʷ R5ytFOL ')E`:TBCj#>~xn(LjD*j A@|`i%9 8( wA+|4\qɭќ<ϝP*O4x%ma~a n(Ƌ@WSsff6 -J:P\D ɉCw|K è%꽨ʕJܙ]V:G6C +4-B,MF(TƢbJ9wM\8dnp7f/25@l"|H sqU#qIQ: Qj ia0K2e#0#9QjܩXDȪ󿿟F>?7jD4GaQ懷P䊧&5"ǀzUj*Nth ^s] ! ~<oZ&~rG&vA'j05'>Yρm>lI-m lQ]&mGq:ڬʑ(U޸#^hWVR\PW(4B@&I ԍg%4S?׮DMtÉ2謑p7.}+֢e*2O$TDe*{sw/\Yn8䊝 .q4 s~o ia[gqW\;nR]3ACTTrA7 0NBMtZOW tHY9;k!XO,G|#p؇5 >;7YFuH8 h`|`g@(wO߸x\! Tf'2˂wDM(Мl` UGB%m1ږAc\~20uQ='bKQax+nTԮ]D+_B`p"~?4jg*"7zJ要2 t֠]zڤQ2sMjC?<ll;c˥~Z +pjDsX (fĝX-2k7a-8,wy!7b]-̘SÖ:D^Ag<=gygVJVD|'n+hBxՔZ}ylHkg >?P^{}"kB@JG3c0TG> c4S89hY$$u ZCӱ)hJFCvlMCx x4}"JQ9XuA,95llDv.vu` {Y! ?)kn¹8Ӏ'nxPATpɨ٨hdUgP +t5+Qx KQf>gt<1(yWa'.w Y? o9Ϲ{g(sQXZqqoa­ƣe$bQ!(+O<}Ҡ,pZ;5V h4t6?Z[ ʿrl=RXi/FU"edB &@uA-j9҂M=0$QdB@! Vw>}s(͉ǁ[\φe4Gdʦ|&b/A2T-G +T* ]U(_(Mûxj^(cq;9Ð v9"wn=efB@OGkEu~!WcRaD~G0T)x5x1^/Û4J]ūux/Vr89`¸4Wfm8(B@?0 pOqv9#6H8.G}D~B@! zπnx#k(rcq{' MeFx5J>B@! On7\qșspq{)ns*Y5Pn­Td/G2d&dMōq!xf T{h8ڟlC|j~GaJ7MY_> GB@!0`<hdB$\U $d/ᰟThî!;Y+pu92!#YdGx9;-wύH Bph_^kL +! @!pF r k +2g!c2 # }V@]Y帶YIȝ3Q0Il~D~B@t///{D֋jۋeB@! (ûPDm<&dJFA9+XTٹ; M k%@"?'-rc@! B+]񣇎?z]LF! |N|~dm\mB@! wC=pBles\m0B@! ":"2B':.[-B@& F'_B@5~kk+-:-e&B@! 8d9pl@g@r   L)*`3G#uB7(hE[㺿Hf.['BdŲB@ 4@#0Wlw+T`|XkTD M0X +c{M8b XqQC& QG($(<Wf&Jb9עa3ZwiN蚙g$),B@|7F~7:B/ԗN\c̤5 ;_s<"\q,ggt.#vخqFX +qu .Ä XbJ 6a'{\ŝëx3sQۨonhg1Y+eY龕^YʽgPRB@^' ^B@A@DЏw)ᄈ/&D4@}#Q1 %CP'x0!8e!Wt!g2 j=„8}ЌV/^鋃8 ! ÍHq#P;M@A@ɠՠbzo?%`Y! @7@voWgh:̶-@,4LGdQ(J<ŕ` qvAq' Npڀ #ʄf,b; Jolǎ`a871ȉG<fd,}js6K^k^tmӣz@U#e7v7! ܐ>bVCCFZ<17DVS81Bn[D=O?V!ЋD"X\{w.bhsm1v.*gTO1x8bq+ +Cp"'pr0Nyκ)M9b;ج5Os+# }6;q* +J푸?L04.4p\ojxثOT@O T3&N5! A'8j!OŞ HŁ8<OMПh2٘=)ot˙w3MULMshhWY'`OY ! @ԭ8ݷGڜ֟} Z6a-ꖣ& vDk13a89qgp-d ]k.8 c^& LXc ++=10be 6P(EfnBW連*:WT^ӫwqs+Cz݉czP,9D:6N! @_#݈Mfuj/` EpDlMm~$þCSNN30gʹR\*'k,Kl} -7g:):>2peB@^" "buy,]4 }a}>4oC:ԧr)Jz>^ix0 pc)g#p&ȳ.%\vE32 .Р\5ȀF1a [XoJ7,o$cE օ`0#8ˉof*+S]ymܰǯp`鐶0CGѳIv&UΣ$4 JBB@M;K.6b1 }0 C0c0? G#yեP2]DpY! &0U)NnHj_ Ě hGH,&OvZ09eKt536ءxPN*/*Y]+ Kmk̴H7pЀ8dH9 vl~݇vnrnT`\v-PU[QoVh%<ܟ;S;W }\$.!}.sOo\@MA ÂnX4/,|$#u(ևc[$h<Ύ1IS/0ϳOqJY[ͿaopӑЖ3m"Y1t{=OϧQ\JD.!*B@M`*Ј436X;;`wvEbgVN +u+'O1-j^8ut+fzU7)߃i⟫*Y)Յ6恲2({ZSC@DPrC{ڝʽ7=n; gU=p P 6ZLœ%(\s799p.q)WBk>D7qK 4KFqC1/߂]VluOEX>18S#>Yp{2O?a|3\6۵"ɽrWZ6heˌ tw=FsB@D{+,PӴFS]4U8zETB7({-ӽ岥ᜥAKn[\^m0Xmz`"}<(:qq .%J 2#p-׃냛;&C nD jgb;vzby#Y Ar(R#> +/G{+9H?Mhht|%^U+}j6mnt,lr=Tvu}3X~|. ZWY]cqT5M􌻮GQA +~ك3=j/Wv+?j-vK/띟r*\aؐ9squ&ҧ }<.BFn[pЦ#-g.%سF`:=GoSr5%蔔]!ugޛE~JRInys+unRRTr_ܺysww4M4 2[X~ +-v/#0;v>}l,l_t "t$~oi'mu7WMg_LO*)F2 2鲞 izm'%MǸDTu +zroTuhD4+bbrhk*x.COx`;0e5Zmh'sUOA?r|:L)툖Ɇ|<^9ytz6wW:=u5U1x:LR9Bi _#+`FoHR&P`\qKL[au+<0w zB%aҖY}:JQ(S>!{1 :JlɾTbw bbYGo(1Y"T)o\-wIYF&]i~6YoY7Oҕct.NaBGƏxj-柛M=66m<쿢 8ߚt;Cc<eB$_T uvhB9^Uzh^m9IB"C!Gi+B`KQ[q'qEnysII2T2Buml*'LSճ_ݷZF"6HK:y.)ͥv0#XR9^eACL1e)+LasNsł<_b, I"#e-Xê8E)Q>%4K5,]&g-"Irn f=q&1Fq2zn[FNa?_O-/TV$#0C A+f oF.҅4:{N$ӡ]펠wcJRv=\Bo ?ZLio :DR*RZt #0_Uh4Bƌ0eYs`Xsƺ<bK &Ҿ(iO#֠kQdO61I,/ Tbu$O_ř1i)?_(+`fF#fb6Sy|.D +Niw,m״m46/;.V=7Sh5rȝ=7Uהݗ ;6Hꏢ0Bz^uExmވ.D +^Jx9 +x6u5.Z"'t[ÒqʅexHK +^Jke"o  T1LQϜlxc]Gn<5/ - CN'㔦QʯI0#bdDM%k &͵{uYolP  &+!|x:B27)!-İ(ˉ{D}'-hQbD,O+D}Yuh"[>$WZ>7aoU0'xj`36@JMWk'ϞgP +}Li{fk&f B}=n]Wv_Vt7hMo:)?U&AFyQ#zqG#mj/Zx#Zr)!CK8c[G#R]5/_Cɳ 0yg?Z9DTGLSSg,g/g/u\}躑)U9vEBJޣ#0W%SSԚƔ=f% +Gh04aX&th&Y ,FMEKGB8yk(+>jA7%>EID}j#=3-U5E+zlDs AS~*GV`ˏbF; HD6M"/})̦75:{_CghIڝ8T*A/lBP,dܝ o=ߔW\\PTuhpF=^YU*tSazGBP 8kaHqιsW۾|:Th4VƩFU'̴B% ۥ;9y؋VW+ҩCt')ͦKe1#9džxl +Kދ}q3<0'!(?Q1P8;8(FpHRd&V2+_33)!fS~.,9AL/ ATbUъXPd)s> g"smZ0 /AqgmG)͇t6]ʤ3u:x]6;oŬ +]i[w_ٯlBPpۦ}7TW:.5֟W'0*P{hAڶvk=^shV' _+P,!^9X5Rml'pYw8GO + 2 +7)#Qʁ8cd:&$Zo<7ZZiO(3qt5Ӕޥ4[FQ2䛡Mwn¤/0(`#4V'u@A&^omB6b+՛53liAD#%&׈9:NTDu&N|(LGI{cSB-;#bm7n F2e8R֨TGr:MGoс+ :ّTP8_n7[oCˑ{黩꾦츬h=oД_RR}+ODATD2 5A^:I;eڔh7@E}"b."J""IDMqK!  OI䁯4_4PV,o 5lWF*?)Uc'Lf/Z.^Yɴ_ĕ Bm t$EӍ8l+V9#0? +{P57H&19Xdž ǖs ГCx!R{tnxd2N:Ղ^#aXQCMDy(xŝh(Hn,Z#e?'>Z0 0!Dl>QL5TS@Wc:ަWi9MwfgkTP<_a?Wb;o=x@YIwq 3Tc-!< +A0ANxi&+2G +Ѓ3DE"QHċDUD'"FDgD"."G:XD,DNDne8K6{dc}M - AZ!h,.ҍ؟jfF!P@>T8 ( b c| #):'hг[Ns[, Y/y= ψ}bx^ )q1둲R>B*CX 9Na;Ĭ#`B.34ՠBהꄠ;tN:љ~p%j)dwmb\3\lۦ=7TWm 4T$OA:-!Hݼj6Cu-PKDG"QH!B>G9#͕{+-U^_PU%PM3{Ipj%Ӷہtc#^|/5 +X4noR@> hS#7Ű%&0EADrXYo:ƽhrA/jCK'c8fNb4ӰqW9@/^Խl)BF$(BG9(<,Y[8(9 "dq8'#l"NdgceGcdǢ/EH%E/ w2Dw|u!֙Ý0&/Mtc7ҍR\@Щ:z\}4ݧ6:>\XP4ȳyh9~w{OOIgqyEs!E&Y"I +Euj[FGP-&hU5A.F+\A1 [pE4H ^g!H+e PÞpŻ8aqiӹ ꥫVl7i-q5Ջ1_)?B#b#>#O @&(P` A6J 1?b`#g Zi$#t8ᨉCatEI b&0}r #sYw^)Nn)B[rIhx#ArHp@oH'bb]q8iu$N'DaB9MΈDDCVgW`K]m^9FQ0!hYjJ)/r1˧=:p_xsbZ끕冠ZJv6yVtO+ft7j9-oL%KuA[k=P{4 +aB--J$^KT-s*=d +B-qGmo8-]nD"QHT_ ʻ#h0Q9Λ/_\iClZDk]i;c^tşn9Y?:pBSRMp[VȵEh[ a40SX=eޖ<=Z.B?Q[4M'~=+ظ}As hn~g +SP ;H5&:M"y[= ^FG}"QH(UD"h(əpIJw={*/c5 A;j|ưgJdF`B7Gu+d7 *Pt.ҹ:>黫ݩɫm+1/Cj}\lJN=5z]U-e5E%yYTqᶲ [j|/mh=xe $QVj  + uB +LRptB3.r7<^\KH&RKǍT\QofY64ϖims}nt“Śa.3_phsH A8,G'LqZsVl낇xO6= pҵӲtF\FFI{tZu:Je>7t*ih\k],ea=[Cxq;q4N!GhK d'_DhWEhR$Bw4ZbPhq$]  ҃r7t92L=͖ߣXF`gԘdne~ٺXi_6+_Pa t.sEt*С,>Cwi;mZ[jsːZ*2y^=]d6o:HQm yeY9TiQI/B5L,Al $QT5C^B +plx;ui\$[WZ/xQ^,Wjzo/ͷmi}D'] A7:/Md H9&C!R8jD5ppWq Y~x.Q\w@D|('UL63L5f4_M-i^:lBה_++hZ3$z}p$kؼ,hzT-Y?+B$hAID"E߉4DZy0̆c$}hDC$"0"5Ky_d{ ifj͌#3 k1!3GԼݦNJz ].t:?MM͞4mkbV_$-3&όGr(tBA9YSTAQ\ujt1`[BfhR9Y,+18HBt_L\ 5R [$i'\vMw䉷GZ'ɻc#ɣsBOh }iG;A':I7|<" u:p !1Hp[7n+Ƹdalq 'ܐ手!xb>R&J-댕P RNś,%m$5,e+z׆evɞZә?qկCW>/cS{dC\䤛첷^?n"; '>E;!8bG5!$ZD"61aJH&M +6!dz80ax#!*!AH Do*υ[{u+-8wAXsF$/1!O'ټ݆uPB7J](3&H鿴szׇZVW꼗muBjh4O1cAMYSz %5\y4a.s@-'E/d&=4A+IQ$5VRddk;\{'boi~5X.{+;(="[J1X?MSX;G!p:n!C (<"_|9+@,]kdHu1W$xNBN$rII2NQOaD#6GmI;zٞuN̙6^{:B5? +zϏ&12=]o\A3QvW枴~}y#wy=O/??["^} 4G R%:mmr HAc3X D8 $q|S.hÄkWg ]iV)Ff~yB_"J"Bv6/o !}|3lUt9}J'aUͻ oS7D6{-W9/.Z̖&K F뿻'}u]~k9AAEiCjP:{۠ fpK +A/uBP qxBrg[*\19sDȧ9 \I֋YTmbA 8Zp +" zM$"00 4|p q'iu&ܑ[_&+`~dT{h|`Ȅπ3aΰ 5FZIKlOGo˚g7{OntYo?AU.Kev%s&SBP}{7qgД#>(TusA;h0 QuC^gx$G7qgpB,.wX=҅ջE&)TyK$A0Ptbd󨔞tCzGTgFM,7]o7gjsfL_-mZ%x%E UR=(Uy6ȱ]Gd;z8+>b DoyĦ`is+5&a!X+kB":KXHߧiNltTj9_d2]$/c wГKh;h8Dy0Hn׹Cj-P)j#TQJ1ʁb x` +\S N qa-r.Hz%%8n-4}zŐ6*BI[;]T s vot.C(5orco +Bڭ~N{C oPMf\ʭP \qW}pHCB$NDsgtwE1.!UDHv'wy8uϕ+^7}h/-˛Հ|Q:躯PRV?3yYj;K{JTMKTc3bJZt $=iѻ$bB !}/AqX \ 0胷x2Hr[%2X΄/j][vl1A ;z3z˄π3a3K+t+t1K'ӑ tfOFȵ +疋{f*'> ǻ轆h?chL@]"P*oсQgZkXJ=pL+P,

76ǁE}@YJ8o$^Pz)L+ +ufMYomCz|7M/>7\ek%z%(ƦMLp G ]"m1!%& J1OuC#Ql6j5RpSؾ߾fY#| 2L h;6#BP͐҇RZ* R:OkQHx~_1Ű-zfgm8rGTG^C L1„&4ĔUbУF%Zmh9 Op |.I$HR<1F#bV@,_:bBrM5=ywrf@,N:CW<|6p #$ 䚴X[U{ͼk޺+(&y禳/嫥kRv [ +ABG@F`%~ FHR`R+X⊰Džuҿ0@Yq# l6c.Xߞ{ ;w*(}D7r:N_p +?Zi~}Lm q:z΢$ڒ| Ѩ AQ:!k/M`:#H&W%z(q@H-u.qTH01C'-pq/nX>٣DWn7}MyP9&$͕j.U*`~70@[^徨 T +q{[ YcS6{0eiL` ݋76hCj \wϏ("9.9%IK"T"@$"bSAkٟ=3vo!46^?:Kiw5;'9lL ){ڞm,my%o۷~~n2- +ZtD,xiCF ÄAt[ ak,Z-!( c nrBQR3<0E-y;W|Tb~F "})lv#l:yFɧ4ݤK7:uw7Fmt{;T[.\zfx|2K5\tZ1 +B _BTkza1PwL(e)[[R\ +$+1ENq5m\H@sŨ;=MGp^hG(עST|&0tU,bQԅ)X&1kY+Ŭf՘3Ì-0k7hs@3Wƽ +|\vf$=\r&Rz"FO%bz'yĦW&A<{O>7~!`z՜P0ZL_ҡ俓@rk0?o̢p߫:ޱwxF޹w]{x~i&x^Pj\b (ktIf8LH8h.@P4X&1lwV6C J)))@8Mf]n{lٌ`v$|>|;(ަKt"]D4G!5>pC~T +сQoMTâ +=m|aSXg@Vm\NqDX+q@=8mt5n Qa&{qõ ݠxN@,]?օ oB`)=>kJFM" ꅿG;Ř'\1X5bsFaNg;W>3 IV$#Lz)R`ZG`ZD;H]wޭVMF:un-GY{ռ_=>G-yIxXP _̗->~ $LA;f1&j 娒ᡰXx r;fnKĐ#}Bݥť?ߧKMj?G7t6NDС Ker|dRrsw3$9|HE23mhG6OE)* C m@Ou*}Wb!Yr@J\T +U(0EF%0KXf .wf`w2KXt +Z."Ρ jO1q='h8dF‚;O6Gǒ1IG!gwRq\GR'){,*!M?AdDqȞt$Vm_N[;#^}ƎNϦ.f<xDhӇ % mW(6HMJzxv޻*>C`wN}{zM'K f s s2,Ȁ"49M4qЄa]+N ʪ>V!W 1hW O [~/v7#0 %O'?s'i;t_ˮn6oOw#.Y/:FifrZjrDTx>3:G{]Q um\%V(2G PlxQa?@I GL%)pZ+ +d)@*ރ>v?NXZbB䳃lRf1uK<}wБ曨@UT"ϡ4:R}<8LE`.XŢoa.wŌ{/zq]\[R+yW(Tz7B%+=MdGaQ${QJCj>jZ2k۾KGM &ӏe9/+7v맰~Xzw WaC5kx$l:'-A?`y~so>^z坏-bv6 cESt֖Y[i۳٨ڨUUz˅#5̜Iƀ0k8qj-QfB7OK#IB%%Q+DBQ!fWbv5Nx'x:7w5`Ncb_ZK{4K".ja)4ņŖs(Z&>tZPp==y7TbK,? >S &s3$d_3x˩XNADj/{bNCMarhS +&y]aKƞbFH#ozd%,3v%,i:lLh!mm6H׫5+Xś4LxF0 Nëڬu +TJQʡ%_s)8p8!R` %HC#\2V`@c&}jb %'ùwJrǨ}h֫踄s?&a2qBC,cOel>:->Oۓ| qAQnz";EHADJ%fMbu>Յ#.mĭM<3so#ߍ"oZEiWfVF6=˼4:{o6>c2wP`+zŻ +1;xbB{>)GJɈh:/`FusXƻkcD9ڕBGwC +Tog[[\۰1LcDFtM߁w߀vWZiʰQXu,^|*f0uƀ/Nkix(Gr9x%҅@: q@@AbJ,N{Xj)ް |^-Պ^' ( +mD=4AMt\Cw:/` #)Hl< bp,`9 ?&0 zA՛*'Q[t"8NE1>NL5by o&.]qIH3kГV7t`c0?x|0{ }|p괠j +ޯjݛxRbB{zϑ Aâk9'b"a?Qw|p@5^RqfFe|3%:ްcEMHmh h h.6~ X>Ol Bc#{PBE5=)n @\/@4 .C|8DTݝpTȖM7X7Zm2X3\PR`MAkT\[BT1%K;;}WOcf`> h,G`9 t0&0 /zr\/W +¹GQX.NA<(41L,~m_N^vO\OzN_c-wo\Ů0 wENV,NχuQm|+> +A強Vwi(TlZhiG3WPs +z/$)H@b1A_~Xertu3}H;9u|9/ 4UdȻN|N +iZx*ޫ]K5X6=*Oٚk^tfuEq=1xnvA-ڴ¶b@Y\YI[+>0.%j_\ڥ0v[, z4XҵaUt/Q%A)̈H +-lӭ}'0٢} ]џ.fzJ㾥2iqx7yoīxyE~M)^ud6_et*a> X:ee61A !?`_pу^1t%uxHsaxZT&1*lƠ' AAQ8r-摏F)1X+q{D]L,U3"h3sW햲lמPފ3VFhiAf/yYsyޭwm坛xǗ%vu +dYgVxdX_󀫿+ E/1Qh D'*Ql'#I@_f4=d=aKžwӻĆ3cOl+AkX<_2g;}%VUEfLO=70s=X8#X:ea>:,o+7-DcJ4߈E'D"QHT"=D7EK"i(Y$:".D"CP$ &bEhdU,< ZeBG)'P`@k50x.ޮԶȺYU#EuA},_Gy&QU"bQ*oNȷA7/E_aF9~i'k`P1 {fH?xjz6:ZC#cˢ1>d}yvTe%fŪBgҎ|1C&Fafh-b2$Ď>M%%F + ƴ$dn=|@»55M9U%-Ez\Wzs! 71~31?$C#Fbg!Hȅ=O ;xj<B*w%Lz6\v<\~8J$gps(+!l4tu=fjwI^lp$ZN 5RB wqRW~̖$d$ܙ7]]]4M. , uCAd\@EEEQDV7YewOuZo.u>Ϲw]TrpA}w\cnmn}'mm /Q + iCm5DSs1HLAn"PTq3O_7'0".F@%oG\/wOoYqc.saɨ'ON$oEzz996TDynxGeP*wݣ˷-╵.}7cN&FI{)CEG>7 / +MvE,<>ԂKo?s֛Lr cY2S_9e^-sYSLOo/~d4fr2! PSR _ᚯ4 M6-'ݡ1{ƕoXiu.|aK羙p*±胉g&ڙxlk Ak}W$z,It^sUDцDlvn7G_=eAxs3:(rƂ [ܧSu:]?~kZ4P5c/IL8{81zOlK ۘx`mw{&.I_h:Q.߸0ι{?fWc&Nwj|ޙ1ѳtvXqYهt~St:xvwբd Ҍ5e?g CS=4#_ _9<yGk?G@ BIn''C  + 7W2_Ov$wewjŎW6ϸ~5]Z1’)N&&M);nJ<>qĽ+ݿMt\h*Q6QaaO -n|[?djKy''=> }w DottՖn֗~zofާ5qC<7롼y}=4o#-h#:Ne>"J% 4SR;^'&A  + 7W2_Ov^dw|7bJ7}eK߽vqٴ󋧜NL:xPbij;İ O_, +4neDѺ/l_wFic/睰q AOi:mA`S}t#]tt֮Z]z^Ռ2PiAk=D胠tv*&zX) M/œMɹ @.t҉asԯ'GKTwr;Z7+Squo]^=.,v61DÉ L<-1bcuɖѽW$6aywfQ~~Mm{ɮY{g4=~drc'z>z9 ȩa:=DglutҡA[;imW-/{蓞Ko_ Єz>;H'w~Gtq$J+4S<^'Al  + 6W2_OW^q^sgoWlSy7..}WN%^>Sb̞3;mI ݐ6DNKmW$Xdg6~\;fd􂃓G_?66ɑ:aK,zXL?G:YN[;hmG-/j^7CoܣɽBo=Gu[/_b~cRRxwJÛg+rdlr. Aab~Նq1ftr +Ns^wtfW||e߹+f^\%O3Xbҡĸ}vћO_gE˒De+5_Ym|x묢3V G=N<#:Ggz:EG:&ˁ~jֶӲuֻ]z7]{htOK3{kuzi=:_'JW_+W 1x508j8k3WB:T9fz*qSoݮ*}PiNWWuis_;)G~JޛxrgbĐJtYh$bU5[q54hMvN+3)~`|cGGF?#4ȉu Stv:V?Rk[ki[}NuЬY/vs]B7]i~7-]cwI +ޫ7V} +;.#G  +61s%Cc]t;;jEAWly|ì2zWL?d/O?u Ğİ$}ĝK͗|Y?.Z~ +6ψo y=dtlۮr:A`+h=%|V>h7vAܥFG,vvй@i4xFJOAx޹c Aat~Նq}\NHrbeYnuvƷJϸbȯv~ٔ3K^:xܱs#oK۔>iMDɒ.hb^ +͎oeZcwuh9j]}Yf՞V]M7ӗ%m[jR+n[kjknmf@ tu2+os}?AP_4 +!M!J_t^qfoWnYҵӯzqMξLq&/u*V?_˞s;c??uOD_o:KsdhD}?Fǵe ֈ"[{kswmꬍ6ך@󔰴'9QĨ걨KsHB2J_.5 O覌#@n +sY {,DNugtGǺcܺ'*?VdK^+GiSZ;\? 1;Cuw VkY4O%M&HHIOH/qQ\r-@ j(i^V}jr(<6wv+T.\do^ꞳXOWu^^Z2FKъG!Okљ;ku}FZ}Y iޗfHGp"ƽ xKLE(ic {A7q6F+fslvGn]?wvuKڟ]g~zmmF7|wcY- P-}Y^Di^\-i4ZzT'$@9~p܎ @ 55/@= +F19T\Ýt]+,_ҺlQ˟8?%4;4 +wψ|]['kx5Oh#Z1XKՒnZAO|sl Q\kFLS+ !ɔg%̚K(Ɛ@ rn9]VVL#'q#p+^6E ++Wy<@'gL/k)l#Z?XknZ!Q/ +QމhzF<@_)n\Bus@ jHm^ ]V}IrQ~(t+ Be~h*GWf:;Y^Ա1:4RОG~m =}Gn顧#_Ksה3edd_2i6B9.PNF ʽ9C/O!'V͗+7[n*_Q.?#tAOՑQZDEmy&5wjj +pܪGK,y]&S9%mS֣N=b桸rs9kYPg1rs9[NU1@J{+@ ʝLC-[POo0慲L{'&AY ynsrG ,EL1Ni\^=;;F ;7Mxn)޹'2g@=s悑dwJ&cdLƆ @Ȃaޢ #zbN0M;i dYPOeޢs^;[Lj +pk@rJ,( 2SY} +@x};w@ M@~zyrlf֙@ۧy @2V,(coss9:pA %Õ @ go3j:L& pd0  bx %O3kg&1 S9ϩdoGv GH@us599ބG7 YnQLTbRfh)w]lɦ\@2GSdɂ2aC /-٩ R0Ii4MzK@gAȂv~A;d\9˂ZFUsetr2 'pMsͷ6I Tljosm9~@!)FJ/HWyBfS/<]r 膴 wP( ׇ9Hfc ^,(<@x[6Z/Oҽ#ҳXeɚYς I :B],Rii,TN @RaNmS[S ~7xA !oޓ׷(rnk&I!ȂI}dkĬ_YT]eA/Ȳ 5b:8A5-wPv+g аE@5C_]m|N#~mkWޓDs%-SSZj/uz,=!,ֈ׈YRw; ө<]դ毹yv97@Fas?H% %  y}(rR EA]}]P_"D H`uA~A-uA+Swi n,`N@1n\`P,dc3@~9Jpˤښu,a]> ?"6HF W$"K J)_I rFE@|_TQOYPO jC=} eR^~E؝ai$H[ R.(/X5b5_#m5xMx2 @ + WG@VB7ଽ8 yM)'^n& , @"}?hY_g>)1UeA-HAl3D5@  ah! y'7u~'ږ͕>&uU(撓A@ȂJ~ލg(-nJۥ1."]h+-uʺ*5|qO=/t> x, HHJK(Q$NT]-KA ,;,EirVbZ+QN,g @Ȃ҈ˡsI7j--fJ+ <](ԕf*k|HqgM{C]yrnp]c˸zӯ^X? lCy[fA)Y* 7 K,;,hdK̬h@7ʲ\v9C@&@6ZCϚɶ7å'gs+ =߉kiC: .I*/Qŝ"[n#(hr͖Pn\,k$OeYt_dk, lDz `X +duAqU +Y]п:XOTς,J֗sC ܘa@t Koų`m=w}/yٯ%<+-VITUeU g {FQL>^#9{&K/1RuA <{G>J'⠾=g4Vt/@G1%  J/Gjއzz[JM}<'+nfHJL˥('tٲPE[Uv勂R(:*7Kn/ +ZG])9{lEY],U_dY}Rkz [ V0t4Ȯ^4g|K9{$s Q,(:xNT"XA+,FNrgaUhY;JLeMUJUyQr^9r}E+%goꂬ}Z_C,'oE;zX&r>ʱyt@HYPq9t +>.EUf*V5Ww +Hn!AϮܼqI}QeA|UU,I$>mJc׭}aB?3(3F@ dA(pƂ mKoYdq}ʶ!{iob_fK boIǥ 2:_TFTi*h}QPj|fٕ7UViTvuYh%=/T-XiYek-I~vA7y+|s G,(=5kx!-#m=TQR+Ɩ }WUu +OsE=JREU-)7VnG޶ gWJn8BCgA+_xI,hR1lVyo_vl1cA.&7oܝo@ goC1hkEAz|,+V_a–X4tt* +,Yob쓻XQ.*S]+ +(7w + gWJn8t>1T]]QVE>b5bYQZ,j,#zFbF7-Rn9g @Ȃ%qN7>)+ǒ=Z< -*luߏw/#Ku^2[FitH:Յ])VK>ȥ~e7Niuβh2 -Y֧,hBKn/H{^z7,ȮXZJmܼr{9{@(@F\-,r:/+xHn$H#m#>H0j9fc/걢҉bJ[Nmf{RNA.{*Jϲ [#f5fK-sK[huA]zF+ck3] GoLƇ @ȂB|Q0o"#"iZw`L'X&rUA=U9@ΊF&ׅXr#QlY%_l +U  J.3pl'wkݜڧ@^XOFQ|S]~0[Swka9X+xK 1EAet)**Ve)(2cH9}tk̂* UjbLg,.f_dmbft2}r  +1;=u?je']m+uP"UdWJNAVc>/.@A`ɚu@}XK_d5B>~):l4:|}S#/TTmTQ=ASɍt1[#f5E[]ӱ,TCs㫆Gk@@ mBmά*TVdOQmj]TVbamKM)Ȋ|HwTQPG)Uj=JzSŎY]tJlTvGr0ׅ֫V[u3~@nA,xj ;fUާ^*﬊֪lϱ*ӦGۇَ`Mm?PGw kGI_E|[!q7uZ7DVq>L:gAPJ%)/];ÿ!pP@@ȂnR{g>l\*YrMu53qio,Yd;+}Qlw_E$+ +l0 zHH߿{4E/ +cnT-9޹ pC݊E@: +.{g|Nw$W/xrW/۞ۚ x? 5^Vo#ISXg_dEA o"dۇ-MJkm(PT' Hn~]p܈g ~5OD@ ->~8+x)8Y %IULl\ljmmwl={gdU?)/ +HGET_U8dEAVt) ?"&n0cE@ dA!@]W&='{lh&P1l 6,_cm( 0n$H"Y4d(Id+ +zGInKɊl:\8N.2ؐS k! dA9~;#.rMS:l`(Kr;t@gmcn%\VNAV3ӗK??~$aͥ֒mC/=(=拂&JcHnR޹E0Mn?# @ ++' 3eޓ)7En3rY~*全}4ŘH&)۪ kclHXcTF[QPFTcqpjlB0I @ ʮl~S*몫t.1鄒Wْ갧/+ +#u(X"d[YQi/ +"u~}*!pc( S,(;xם)_4UnHU>U_jg]i͒N%;;'YaHg}QА}SEA|]P_WOOsܞ?S׊= 4YP0""LrV4KnDEAVtUݺ^[\3*}H:l_e[۟~_0G*ZJ:eʉy>a=ƞS8+ @ ʍy,Δ+yrȽ!gȏKY!ҞYb3)ԑɗ^Z[F7zC,j/km](Ȋl0[f8Ȋ2?n!gYS5@ ʱ ]w>REA;Ԃ:_3~={uY~yYҦ1EA[:eEX3wnYhB;u @0 XtJF{Z.)FT}5,󉵱gBn,TN @'rDdA!9"'hN!RB@ +ݔ' #'ܙkδB@_)@+x |b)@@0 .@ 2@@@ GȂrd9M@~';\>rȍ{Jy  udAב [A3WKTBw*+wCrɍ$ʝk3E@ @ r8ZMtHeqPi UeGz{PnܓdAp9p  P\ _sn|Ӑ/k!dAPE:F#1`6щ:LgKtQE{UvVTUqpL@@ Kj;5tkSk0EyE@F j)HH?D)q*("-mKmUNeUazrς7  d@uSGjT|M(( иA럾WZZ"-jULkڔ1&ThNֺZݭ{2## %Jx?k[{~mG2a |ʼ AYy|(}"-똖iuǴ!-Y=LЉ:RT]*,ם6AYyEpR  |5Q50_Hx@L ʄY1.)#/}gQ-ۨ%YuPiWS-֡23Lu8  c5C_diɂB] ѧ0^ MHh2 TZ(}7Zך$EebuΗJsV  @]Ix=^,y9@K>4J'$MސfIIs Oieq-kE:T'&JW"JpL@~TsMsͷ +=^†/+"4APKO8hdB/K}4Dz i/ Zwebqm/B.q\.1C@ETs}R[S_/@[ g~^t4@zAä@) (M+fJ}u'dQAzG\:TY޲GA@rC xv">0 P/Aظ uJ8t4TzLzگWj{Q͋jaT b>PlcL;b&:^LԸɫ# @Ry/'>= ' c  #@t;zͤ;.R7W$ q=+=WM+lO1[&QjLZզiW>)P&*c@@<\H0YPAK $8UUc~;n$Hl)fADںYikςVE.1ƚI^@'+k6aFdAPLB݇`¬ +dB~$Hw8VJRMߒ>PrsE7ҊG >$ @us/jj\_e00@Au˄,6şE?ɏ5 oI㠿 F=Ŭɖ*YduAJ Z-LXƀ >ީ5 t33[!l'E rOʍ{Yur->*a[GhkdQmٷG`TYi5bYi˂Iػeg@9  6r`fS1R]-QyKTGa {gA^%ܗr֧=" +e̶σ_EKuDJ, ?5'؏?^J3>: @@ dAi MK]Qӱ|.PiwRe~rCF=#7Vn >Fnf=|<Ϧ~eol=lS#-#CVcY 8zG2Vd?n-, ѶLֈ8 +  @ eݔrB P/o.bږq)bmmtvSeOr=&xWޖPnbg'쇛$$M˻,zJ +' odȲ +J1kdYe̞`KI~Y0~@@ dAi J[eߘݨ>jA]L?ĵP{ uH'LKk̂ʻY4@2-g ĬY;YB@P^ ]cV3]y(_?#\z@Ȳ d@ A$#FjdAo@@ ;Ȃc9 /T^+՘f xռ<}ӷqk}\;gYPN4י:NW;Y [ 6Nn_ 'r @lYP}R6}lUL#V J8ȖY ˂lC?,Ȃ t޲ {ꂲs@@HYPy@ͦ+/زEf4/_ 8_k׮B+ҡm3wuWiU Z 6U-r_5|Ne0CUHJJs ˂"AA$xo +fَbDȖYclC?,gA,Ȟ0U@@@,( &S@: րŊ."ST/ZdiL_Ǵ"1mkg5:Z, n=$gYsr/M >EA+^)ʶFJH_I y\eAVfA% ˂:?ڪRY_F qA&mf  f4sxDR[ʂl5MeAOG|Tz5Ooa7 ӪMXі:ytԅr !ʧUr3}Qu^GL~L+l?"biςޒqPHP t4(m$n}|Q?= ~"yE@@ dACnAJ):Z +J,RkĬOȨF5%fAQ-jm"Zʹݩuž**/|Qr_dSD>?ziW-AAo>-#A4(5D &0 z-%!˅SC@,@f`!m-VX5ƚk{dUQPYPTG5/YӪP-%\ZX訳]uWU>"Xɾk{re7 vsuAMlXH`AM#A<(<->w +KAvZ1[KFT Y,(̳@}׺kb;.=,IEC +كC|{^[ f͂&E}FiYiCS(־bmu.][U_v{M&>/u0O{T6Kk4Y + >5ȚH4o(dj2.N[˵E@p  @ȂN @# h]}]+,_c}T"dmxgT{!=MV"m*֏Ssj{w)g;Y@yIroPHSy/{X':ZњMikTb>gADVYd٥;_C [̘yLj@@B)@ic P,iokNLVdQWB0ۆJ,o,JAU_z%;b_MVjCm;EA[R[, rȍۇ>6%wN:WMu6x4hG6Ǵ:PIK|נ/\o"t_,.]nZ7@@Ȃ@V\Ou났AD>\HǑ#Eߊ F-d_1˚Ӹky\ +źFosSYG=(g]M3{LuŶJLsBjbA?HWu jC1[&fYEY,iYZ*C@YP'!#ϗ^YP² [#4m-걕bV"_D?YDߍ <͵󵤪kb-; δӥTfA/t>G;х6t+o#tjwvD]IeUbL˂ +K_6  @Ȃ @ Z[XyU]4y#_F+;dqdbgQ{15@jsv5M.;J'Թt*z JFz8\G즊N*KW:b{kӶm z7/G ׈Y] ΂lo&[ f(XueeYՇQ-jqLŵGBǬK[gv. < w*EY[&Z'DP\,YJ]D +t#NC@HYPZy98ԋ@ys]h-u2(&uTɽjdYS , 8Yh@UQ fEA,;bl0J>O_Y + +צviI˹r%A2Ywr% VJAUCbGovڞb:RESY~#P]  "MCE 7:]iӾ␭j]ڒyZ7U[r , ^XO , +$ ~o"feB5eVEAQ},:V}E:VMIrgaU A=u.w%k0F[:j ckW@@t +Sc# tWAgYkk1m,(*ۉkid ZGH0o"fS͂jvEBV,dy8fyvvOl-:2    J+GE[&7EnBuAt][g;ԝ:RJ;,~U Ħ?V=<  օ#uK ìŐ\@@@ dA?F@fɽ%{7MW*/;E;Dj}%irZ+-=|9L;پ`OKAXC*ѐ&Ha   pdAnO @= |$7GM9 zQcfA#Tӕ>]g;d;i-Yrض|mVI+=ւA}dt@@YP# , zWndqr=*t߭3wd[mC͒]iNZ!ٞ_%=5QXt2օ-uEA<@@YPA@Bs͖{/Ϫ U`]=tjؑ:T+Q7yѕnQLs-f^&ZXSМfH@@@ mdAi P%Wn/ +Z!Al5T>@t.uЅ:uGr+E\ ,__i~4|ա?   o,T{d @z~,}VFUQs(aU RٽMW:RKkcE:P]hۇE(@@@ CnRsKOP.UrTu +zw +z^IrVY{]m+E:|R@@@ ddA!0@SAK徐'gEA3Vu +zTn**:.4' 43f@@YP8Q"aM[[QCG)   @8Ȃ1O@@@P    @8Ȃ1O@@@P    ,{hGm0     PpdA0 @@@I'H&#YP&c@@@@>>jē% jD|^@@@I(uv=(N((   d@mOm75<   Y#P[SxdAK#   @x2YP    jo% j)`    Rτ$ ʄY`     :ϐ$ ʐ`    .33" IaH    >oCb> @@@rM:",dAa)Ɖ   #P.Z ݀3g     :MF@@@,@Tg:~@@@YP覌#   u 3?   N,(tSƀ@@@@: ՙD@@@B'@)c    @ȂL"    +ݔ1`@@@@dAu@@@@ n0    Pg:    @ȂB7e @@@YPA@@@@ tdA2   Y,t     :MF@@@,@Tg:~@@@YP覌#   u 3?   N,(tSƀ@@@@: ՙD@@@B'@)c    @ȂL"    +ݔ1`@@@@dAu@@@@ n0    Pg:    @ȂB7e @@j{?_ @j +/5  4@m578 @Ȃ8k@@ $9}Sc ! +d1T@@ -ҹFdx@ MI,E@5INm9 9 - 疸x2  @jty!ϑ7 k!z @@.pMS۷y!yaT @ ''SC@+P[s=yCd @)c  @xOrnߎ: ɆI2?f]WECU 08DxNycqyrR  @Xg( @gA|n,V 2J*I @.|)]~ݪA+ +]zjv +x  @rew{%5xO9'P.bt9Q'.J& Aީ'@TkWQP*v{˙Ա/_ @Ob1>mM4S&ީ'@;TKqLFn|0H}],q2[:QS @H%G{'O(X ?%TvSy5Nkqښ63n'G= 8Xۓ*O*I @yɷPGI] @@<˳73 -8zsj=g2 @97g @@ b}O X(.b pZ4  @X 2§ezB]mWГ @yҎW)frq/M  @99w @*^uA; +bO@Dz}(z5kL9#\V  @S?;zyyZJ ϖUkUڍ^> +V6qdMە&5j"@X-\nF<ql +Vz8JN_HO/_ +JxZUWInwE<\v/L{r缠! @cuE(# G\K1W +Tsu1c7^> + @ oxSt7Q&fγl|@|s&ms̴>W! @7 Xn{wafNg;q&yl;S˸˚uVc7 v%#%@o@5yܧ7Yk b;VS/QE{f8kJ`K + @Uvo0/񟺄qC^/sx5Ҝio+e @xZ^oF0m9<*&@Hͼfepf-4۶imݙVc/˪Cv  @zi;$r <ȵx +9 @O7K鎜x;Om 2 @/[ȯۃMxwSç*K4߶ C @d,ߞ?rnUkx+h=̘m>ͷ- @J{df}袊  @|*>w{M?hra 155U O%bz,gj3Q, @ 0[ -Gg_bvyEݍ~gmw;jmL%0ݴZK @k\Ry7ԛ.tϛaoHWmL%0Gmu] @ ++8]+/⸩>/jWM%xPx>V OmzRإeUv  @T²WvCT˭Vw;n@[^!@ @`w;I׫I[Y׏7TaS٠݇zJ5 @+R?I=y^/ -O\ǴAR/n #@ @䆽zMV.>{n̂h 2 @?Ho(?Ë;7w/r>Zח{ @ \߿xpWO4{T y7m>.'@ @eSPSy5AЧeI} @Mz${((8-4 Л]?a,_Cf|.A @`XxC52I p @@+'d @ pNh]eg%py7=^ @(b%JY G98/Dt- @|*o"D m&Ń䳸?] m5݂~ |ۂ  @>tVJfrG~wq"z^d/bCV扒 @8!Pqqn͌':SދGgh/8or/mVQSb2 @.|)Rġ^> +Y A 8̗q9^Y0vA"C&@ @B"Ź,r$;lG\ +xx@9Eq9^Y0ee 2 @'Wd[ִWm^ +Tj7FG @~"zܥ;]/(SY".ԛz8Q@ @7|km& Y Dccj^/6*v{R @~+W%nN'?2hˣ9nkVTPlj @@ .#Iu@+P7m:mvLKT zt @ s\=pe%C5m& @ @k6?DTj7:G:A,:PFJ @J:Q}QNhAG @ @(+|q/V>Sҵq5:d @ E9Q @ @L|ȇtfKZv @ E`ljKn&RPK @V""Vơ0:v @ @DD2Ԯ޹#OeYF @ 0CS+܍^~F'I @ p\ m>s$;xgT @ @O@姞*YΔezFL @ pO;dhA @ 0&̸YG  @ @&Jݴ[ @ @@'N?! @ @zXP +84}&@ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ pDd3L +endstream +endobj +8 0 obj +109042 +endobj +9 0 obj +<< /Length 10 0 R /Type /XObject /Subtype /Image /Width 1539 /Height 29 /ColorSpace +12 0 R /BitsPerComponent 8 /Filter /FlateDecode >> +stream +xЁ Pa 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0` 0`N? +endstream +endobj +10 0 obj +606 +endobj +11 0 obj +<< /Type /ExtGState /OPM 1 >> +endobj +13 0 obj +<< /Length 14 0 R /N 3 /Alternate /DeviceRGB /Filter /FlateDecode >> +stream +xwTSϽ7" %z ;HQIP&vDF)VdTG"cE b PQDE݌k 5ޚYg}׺PtX4X\XffGD=HƳ.d,P&s"7C$ +E6<~&S2)212 "įl+ɘ&Y4Pޚ%ᣌ\%g|eTI(L0_&l2E9r9hxgIbטifSb1+MxL 0oE%YmhYh~S=zU&ϞAYl/$ZUm@O ޜl^ ' lsk.+7oʿ9V;?#I3eE妧KD d9i,UQ h +A1vjpԁzN6p\W p G@ +K0ށiABZyCAP8C@&*CP=#t] 4}a ٰ;GDxJ>,_“@FXDBX$!k"EHqaYbVabJ0՘cVL6f3bձX'?v 6-V``[a;p~\2n5׌ &x*sb|! +ߏƿ' Zk! $l$T4QOt"y\b)AI&NI$R$)TIj"]&=&!:dGrY@^O$ _%?P(&OJEBN9J@y@yCR nXZOD}J}/G3ɭk{%Oחw_.'_!JQ@SVF=IEbbbb5Q%O@%!BӥyҸM:e0G7ӓ e%e[(R0`3R46i^)*n*|"fLUo՝mO0j&jajj.ϧwϝ_4갺zj=U45nɚ4ǴhZ ZZ^0Tf%9->ݫ=cXgN].[7A\SwBOK/X/_Q>QG[ `Aaac#*Z;8cq>[&IIMST`ϴ kh&45ǢYYF֠9<|y+ =X_,,S-,Y)YXmĚk]c}džjcΦ浭-v};]N"&1=xtv(}'{'IߝY) Σ -rqr.d._xpUەZM׍vm=+KGǔ ^WWbj>:>>>v}/avO8 +FV> 2 u/_$\BCv< 5 ]s.,4&yUx~xw-bEDCĻHGKwFGEGME{EEKX,YFZ ={$vrK +.3\rϮ_Yq*©L_wד+]eD]cIIIOAu_䩔)3ѩiB%a+]3='/40CiU@ёL(sYfLH$%Y jgGeQn~5f5wugv5k֮\۹Nw]m mHFˍenQQ`hBBQ-[lllfjۗ"^bO%ܒY}WwvwXbY^Ю]WVa[q`id2JjGէ{׿m>PkAma꺿g_DHGGu;776ƱqoC{P38!9 ҝˁ^r۽Ug9];}}_~imp㭎}]/}.{^=}^?z8hc' +O*?f`ϳgC/Oϩ+FFGGόzˌㅿ)ѫ~wgbk?Jި9mdwi獵ޫ?cǑOO?w| x&mf +endstream +endobj +14 0 obj +2612 +endobj +12 0 obj +[ /ICCBased 13 0 R ] +endobj +3 0 obj +<< /Type /Pages /MediaBox [0 0 612 792] /Count 1 /Kids [ 2 0 R ] >> +endobj +15 0 obj +<< /Type /Catalog /Pages 3 0 R >> +endobj +16 0 obj +(Mac OS X 10.7.4 Quartz PDFContext) +endobj +17 0 obj +(D:20120614050627Z00'00') +endobj +1 0 obj +<< /Producer 16 0 R /CreationDate 17 0 R /ModDate 17 0 R >> +endobj +xref +0 18 +0000000000 65535 f +0000113547 00000 n +0000000242 00000 n +0000113320 00000 n +0000000022 00000 n +0000000223 00000 n +0000000346 00000 n +0000000475 00000 n +0000109685 00000 n +0000109707 00000 n +0000110481 00000 n +0000110501 00000 n +0000113283 00000 n +0000110547 00000 n +0000113262 00000 n +0000113403 00000 n +0000113453 00000 n +0000113505 00000 n +trailer +<< /Size 18 /Root 15 0 R /Info 1 0 R /ID [ <4e77d5a96b07c7a3f06a11c13456bf6a> +<4e77d5a96b07c7a3f06a11c13456bf6a> ] >> +startxref +113622 +%%EOF diff --git a/doc/images/hmm-FG.pdf b/doc/images/hmm-FG.pdf new file mode 100644 index 000000000..e522f8cc3 Binary files /dev/null and b/doc/images/hmm-FG.pdf differ diff --git a/doc/images/hmm.pdf b/doc/images/hmm.pdf new file mode 100644 index 000000000..38c8f0623 Binary files /dev/null and b/doc/images/hmm.pdf differ diff --git a/doc/images/littleRobot.pdf b/doc/images/littleRobot.pdf new file mode 100644 index 000000000..e19fc0edf Binary files /dev/null and b/doc/images/littleRobot.pdf differ diff --git a/doc/images/sphere2500-result.pdf b/doc/images/sphere2500-result.pdf new file mode 100644 index 000000000..9175f4ea1 Binary files /dev/null and b/doc/images/sphere2500-result.pdf differ diff --git a/doc/images/w100-result.pdf b/doc/images/w100-result.pdf new file mode 100644 index 000000000..d09607a06 Binary files /dev/null and b/doc/images/w100-result.pdf differ