From 9edd4e1de6b0be7064c3460ae348e403f5b67f9a Mon Sep 17 00:00:00 2001 From: yao Date: Fri, 10 Jun 2016 11:26:56 -0400 Subject: [PATCH 001/197] Added several files for gtsam.lyx. --- doc/common_macros.tex | 124 + doc/gtsam.lyx | 3760 ++++++++++++++++++++++++++++++ doc/images/Beijing.pdf | Bin 0 -> 319555 bytes doc/images/FactorGraph.pdf | Bin 0 -> 5768 bytes doc/images/FactorGraph2.pdf | Bin 0 -> 5608 bytes doc/images/FactorGraph3.pdf | Bin 0 -> 6281 bytes doc/images/FactorGraph4.pdf | Bin 0 -> 4294 bytes doc/images/Localization.pdf | 101 + doc/images/Odometry.pdf | Bin 0 -> 4295 bytes doc/images/cube.pdf | 559 +++++ doc/images/hmm-FG.pdf | Bin 0 -> 6870 bytes doc/images/hmm.pdf | Bin 0 -> 7242 bytes doc/images/littleRobot.pdf | Bin 0 -> 19836 bytes doc/images/sphere2500-result.pdf | Bin 0 -> 35928 bytes doc/images/w100-result.pdf | Bin 0 -> 23250 bytes 15 files changed, 4544 insertions(+) create mode 100644 doc/common_macros.tex create mode 100644 doc/gtsam.lyx create mode 100644 doc/images/Beijing.pdf create mode 100644 doc/images/FactorGraph.pdf create mode 100644 doc/images/FactorGraph2.pdf create mode 100644 doc/images/FactorGraph3.pdf create mode 100644 doc/images/FactorGraph4.pdf create mode 100644 doc/images/Localization.pdf create mode 100644 doc/images/Odometry.pdf create mode 100644 doc/images/cube.pdf create mode 100644 doc/images/hmm-FG.pdf create mode 100644 doc/images/hmm.pdf create mode 100644 doc/images/littleRobot.pdf create mode 100644 doc/images/sphere2500-result.pdf create mode 100644 doc/images/w100-result.pdf 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 0000000000000000000000000000000000000000..57f11822fc4e6267c48a898f7d7541a2ff332bfb GIT binary patch literal 319555 zcmXt9WmH>D*KMIlOR=KGi)$(FZUqVy30m95 z!o}(DvXQl{?X|FG0=LGz##U5t0xUcS!{k`;Bk=r1&V3#LPs)#_i_eEA9X?N29gj(m zb3QPi=PRKnC+)3@CaJpvDM77@t%~QTiUlN}VTC7H$J4maBdO2h%5$pEqt7$Q=TY~0 zYW8W^=V@*i{J^2vruESUJbC|k@x1g&?$g#22_jv~!^}AL*OY6p)A7m-Q;hQ=41S76 zWVS-73A_5_#7xe+0o(o=#EZyP_(&A^;~E@u5g?wC5i^+`^-I>!eD;vtiWcqv51sSnUIw& zelDe@d<3-9?5I`U-gKNeUrM17rGYf<@E*a5wQa@CTJ@JB^No zeYvrN$yS2puojGbVdA`OMM!|UiC&ItQhAJZ$J8u_f9T`l$d`x!wa&CERA|j7I95}{hpB0ZZ{nJ~ zY=@lMo#Ly5m)#(e@BvccBox!{Pe6#N4JZG%84`UjD;WEtXLW+FF=%&J;kX=ZKB^m| zDdL|R5sCK^wyeqEV*c^*P;Eg|XfU4QUc=Ydo5pA9hl&Vk(y^2EvbNa4Vs(vW{$uTG zqWA3M5qK%J>#lM6fn!H2Bhtw)OlSzmwAq2(ec6AgtoMkMyU01J`W~kG-nwJwN0_fI z@U;dms=+l?ZK&Q6IJ8v)DAL;AYfE(wO)kNIo?bILGG3bUY&wZTk#4VnlIO6T-iFN!@%rPzlV z{~MbuiNgsd930E3l}oIIC*O}DPE!Y->OhV%PnoGRobM5}tF2l<{W+meW(*&uNpAu6 zjS##o{yFNfIyVbHEweRNziub~oHPvh!YJEfH?jcV`R8nCAV%&OJKt^BnxEE`Fd64m zP^Rzqp4Plu!2G=aviQ<97;;w6wH-gyJYKN)IFdB`M8c)J7KX&C>t;$u`d+&iY)qgj zt4w7vpKC3L$vwGp|9C>^a%E3kJUmit(F?e2P*ti52bCJP3{!Icx5BSwW!VV?w9Zp6w%0IPpY>8>X=rf7! z9Lg}sW6K0*vL;W0Sg*$zI9gjSNd@ho0Z{oT5d1w00WD%f4fBd-k&)08JHV7j*J-r)W{(xDI z#_O+Uoo{;VU9WZLL2Ed-dHZuf210dLZKFP3o0LdczLn+!6r$3KcMWPViMd!%NV*LJ zKTBjWUB-2bi4Q{>pd-)^a@AR@bH5Om510dEMP`{kLDi>ywfRsEH8ry;#WToY2)W7I z?#k^BU}M}L{kTB=9Gk(!-;z=2Xy&`0J{Ya&G2FEUTP)*9TiF)5+I zMvHC6P2P82AqYwa=_*}>Qf2<=Xi6#%uM^{f5%7+V>N9HXOA3hv%`gmaeRUtZoAVA= zfhF;n(zOo0kx`d$TE7JYV5p?{-|7Z);%kkd$kQWtvvPh16>qnNhY&2JTF!kXbR zsT_9OK-R3u)a<0>|Lu6sxFZ_FfNYQHnA#ppQUv&^?JP!i4ZVho+^bSv0VSujF&K>< zgjcKhAuSD+n_1O^S1_ExZI4zlDR!Ia)7{ie`)EIFF7J0~5&+m0=fwpi6f0g?EF2qO zVE*R{j(KAFytE|$bx50=`^oE>2_3#$^mp(|hzjYr> zV_Y=O971~Ir1LT}ok!kAFo@Xm& z&g{A#m`5+O!%^z6Uzd~UmTT?pyca^GJ4DhECeCu}Y=)l|Iatj5FmA9(-&9Z+CMaY^ zW|wbfrCrso7$)x*5sR@h9UIaxeH3DI!r%Oc^=Iy+Cc=9Rau1>E*AICf;B!>SS!C%% z-ui;-!2A7tX3qkbeEVk6B9A>Jv*Zt!f-&B~Ou^dkQvv}`Rix=wIU*y`2_r?*0(|H1 zBhW>s`9E0Id|%YXX@M zWP!h*OWPvv8eYJ&PqYS@cvz{j_HV1ph$%NnxfV7lI5K|x z?VC!E2>=%hDkfNN43>hRc}L9(*#8}mo3a>r;#T}Bu4908*pYrlsW4^#uFA^xcjr|a zGwVf{T37Ip{9)c3LBZfEi>}AWT{fnGJ>flvE4;fELNA=Sc9AJHLpjsDWp1T}q}pk{ zt_`&?s5HYMM7#w4fkTHS`|hpg<15rW4&6KuX9+EHJG0}+=R%V&Ueub*bH#$)LNa3N zVk#GsUc|e=KedIE(T0_#QKqnFs=413UdR)RAJ7R!Cbyde>B8k3(gR~_y(4zuno;wi zbyK)OOrzem+e!{F-rumd!(kq$G7T53MepBgx(O{nyyxpgAd@DaJ&8N5UO9a^UL~33 zS^D1IWg227ZvN~3sB znn+4|WedqR&AZB?j)hi$$QtVin28C5%#1#oiV#I4_e@`0m zfz9R2C?o;;B$lb-D{2k3QEeNEm2R{*g12FL|1gy>K7H>Iupn zWi~*nNlz}-yJqbmxiX{X~EuG^;A7qx#3RwC$F7v>K3{19Cj=qO+^>y zJfpWbI!<+#b1y?>Bu-H3ZBYNP`%3Yoc-k&+WhiG(#`i2bO}vPy$wW)9LL@Wkk)I;ql+9to)7sWC=}7XpV8Z8c1<{v>Ua6YKMml+%!C&4cXN{^# z94XWdfD$8onc1`f3$Uq2F(E8{$#Gwc4|yP*#G5=LB*Ioubwm9@E9w7k7uQ9MrhD)2 zrm9){C~kb?dN+?r5>??|u#_qm17b{=7pr zFqd>s-QP>DC@Ij*R|B{$z0%yL1w<$}wjdkv1Owwkq(Ht%`e zzrC0bknJy;g08QvEZal)!H{nNnojLZT5SPds02vCcqb>$@%R z1b+JJ4wSo;)SQN5wN6p&*Ph#(b06Zs&DaQJst6V3mrJHCkZ0}pcO)Iu64z)^Z49s# z18r8wa{KRRd5Er=Fea0l4Ztq=t^r(34%!~}liiujl{@hLh6LwLQSiuafk;Pp09!Am zce{82A${dchOeBSu@E_aO7wJ%{cR+TB~;R^^_~Abi!8 z?)c=nz|aP|bX8_UpIF#4g*VERQruenbr6Bdo44%!ebw3L!rPKb7#K#2Z{4+_LBq~q z5Q&k~A_f`Q{psx?KDJvL6U9Q4w+k0m&ZVgkFi=A0AMv_|jD9?i3-5TL)`Pcb3cO^= zr99_NIDW%3!?LTB6g9fR#EHUS`iaMgfJOqi=F!NGK-!~eD-qOk2cUIm6Dcddw;XQF zSm7NVcZzOlE1PtFmV{^G=;Za(x}jS19~CHOkfJ}hjv?h~;Z^D|u79UrDa111#gH6W z!K=f<{nIyEWo+hp(W^h?tvi+Ty01y3tT;D6L)k5K)lB zMA|7g;MHK-E6*8tejeo=Po>jNBE*XK@v-P`=1gu|V~A-iCp*w@fVI;?d%Dc}ERtC) z{d(uPVvX)34*pbq0^K#I{=*9ZzHC_G&!l zqaeJM`EZvvV2kzArwE{F15RR@O@|UlAa~w6@ypeSVM~(s^kchjLCaN%pnk%o`cOq~ z_Gu}j2nN`kMpJW|!|;`{NXm=-4S$-IAs`C{*_-vUSj?8Y?EgLeE1PB);7h20Z<-#< z_FF^Tt*O$%o9dHGiErnIa+D8_1x}!5A^+LIN0!02Xg=TMh43l86WJu}T`{HRE}6R# z>E1Xi4!M?KbtoOpP32yB`?Tn^j*5=B!xEO>vEo1~G>ABJ$MNo^n_)&P)-!>K%@U*k0*7zx2OLD1%LicLqQAfXAJ6P#BI0_%Cl4B)F|+Hz_bh=;(6tvzvpHhuUDb{**5Ph<1PH6dU!@oDg^wdr~ceCT5za zmN@kxZev4{8K4zEBhUOC;8g#(;l*ohK)Uqoq^r(tVERxj<4NXPaB!!5g_UQ7wS2^F zq3qnqGuHm>)z5YaB8K08y-;i+v6V=>7a#>NMzWf7qxxTD&U_j+X+C}U>r`C;1XK89 z#^!RIx_xd!g1V4C#9355T4Lnz4x0X(vnXbi&hqb2<{xV5K);Z#&<-ZiLN0}EtYnZe zk!83rtWZkLT8$krA|Ov{9K3p)ro6D7tXo=FX5`^!mE2vTG#SJ2LGL+Oe6Ml(-hL|2)%qVK$AojkGZU?OB^aamIrMB;Ku zpoF2Qr>$#oES``cTdM7GRmy1L8bYIg^9s=Nh2dxOtEm4t7C@~cKpg_9^Y~f)KhHBn zv@X3FgeiKF>mlB}$>*prr`&sW+aQd#U+Sx)0v*HzzpCKAu9}7CN#IGAaniUj63i)I zk+ZK=$#_g+sd^i{N)pEw`RMib#kb+6Nk=7lmgt=!VxfiB25hPqy|z^0IKu(06d`8t zg%b4LF+5%o$BgLxp(Xb?FRZw{P80!0Dj;XH&${)$*W-bFyl5}ULio^Zw#>mx!eCl+ zSs!g(YQxk^4IWLfS;Kw)B_N$vqEDDZSn94wA*OhaD!US6vtTVA^w*7+y}PwA+RY@6 zre9p#6EvRTdu!#iQ{a@sXFX>Pmd$WVWWCuuDrZL8m(WuLgtrvaoKQLRw~%^UP9A?g z9z+-7H2>#8wfA&*(g1c^#*!GP+tbI z?`U(QHgf!*!8%n5%HYNP7*QM*v5*^YAZN%de59*@LevufX5l&`?u6F~aw8q#S+c&Q@X~>N^@my!0;-o-yS=MX2O=ZZVB>iUHoyDN9 zmr^mi{%U<~JBN^sRjk{^ivK&YFh{lGOfDqQU~vm`<1@y_=W+aoe{3nv^F@SV0CkIS z{F(gB8@gRug!Pl=Z#Xe@JY%bNc09WHv)FB#eR`ayA=ENv{^}}Xx^(NwNE_ud-9Qq! zr5E-WGv#7+udflPQn#MdSQz0l#5-ia@4&*r zM2wiG)JzK~JHkBHKNtpS6`gtG^B(?km!O%ku5# zQUVQ!kC0Ul*`C_c3dkm6@jzOFmO$k6=dk^d+Kyh29@4i0v@2Eed_SRxi>@^J8Q^Qc=A7X^LGQNiLsvU z9{kCQ!=Z1N=t4(-SwNQIlZ~UnGlrTipmkJDwqnD*DrJu$c?CnWZs;wqjg@Epb+yd> zGNfp9#DVSxe>FjCS&L6Zhgv4kbwOW)R~a*k@axh;J(j2>;CMZ@TeWOLS})?(ztt%Nby;;R zHtcuK@Op;nwkP2UzvR6Z5|L%%gD&sE`{oPfQmX$wZYq~W6)Jny^K{z#e45%DGNKTC zyT^aK_ev;(Mu>R5sQbau6O6j!6p$sa{(Hq!ig^r0{K-yI{tpE&Hs*YENM}$;r?=!A zPKh_IARKh@H$lW&W1yEzD3}87?cZ~QFkIDXpYAjD+C+-)YZ&ZD9EX|B${rV3PFra+ zZO(jRoDn_J{%hW0u;fCv;Y#ahjKf{F@;XDNVhlt{5lMD3hRKZc203>}{V}&bU0j^5_sA zIN9NS6Z?%mi8IG4^E?I<-&v>n=u{s%=WG=-7=6+FIN*Cv^EdOK%G-Po1k~|)#80{{ z{kM}64f<4s1y>XPD3`15`&|<5wpApH`A9cn=++bduo5J$y{=LB39lSL$7sqj=#>j| z({ ztJLP_87wz(RIlGLcmyW4iZZ7F)fWCDoY(J&|GxL_(OqY??tC`=3z?<}wr`zo^}0}7 z4#wK5_+^=*%7K0vg|CT;&66kDOZS@_jiqbn4^Yx)wD+61L1#S5v3Ujz&qFYz%w+?u zH;LEi{49Mx18>mZ9g({3#VQ;A!(JTf`IE>xArGB*UYxfSVUOVTy(>}c@PUe ztIL*al!6n)v>IoUaV-6nsdgxGB{((?qSblUf@V2w;O=}0MKkRlEP3v$2tP@zbZOhM zSxu13adOS`*7^~|XYyHUN0)I;ZWGtKeZ8_!3>FxsW>E>pK%T|q!X;eiQ%g=vCV1#) z_c%-$$cVu8DK(m@tGif8U8K>sNp46>7I4Yw`JHMNqha<1s{i`O4#SekK64d;z$K;l z3C*#BInO~qDq!ji~I1O;>!9}XR zE)!TGyX|8!Nf1M>+%D^Y4ziD0?;@QkUTgs0k>q8+wRrFnvX2Psf0cs1OXm@(L?Q=L zhxiDQtmt$`=YPL!J(zvmc120kWXK9tX+_Hk|{2@Nj z{v?Cd+_qB2vQlqwVi zSnOtADd=}m)1g?-4O@I<_o;Qlmouatz7I*8G2uKP%x3d%kCX`x0Y2VNUyDvJK=oyMCHja$5fU2qJF;8ABZ6>mKCz zt-V*bqxtq=mup{ZI>W-4;KCg~3JsNFic?T(D8^z15)19eSZg5# zJKfa$Q z*gx2ZRhU~6LVcSDi2-2swLe{zy;`a-dINBK;o1M#u~PQ}Y@dw@N*Y>q1DxEI6abu( z7gK(A?~Ruvnk-b`oR88ft-z|L)+(-kbgEthf+qbJWV8y-kL*7rx>Wen`535ip7?d! zEJ8@tOJpqXtq#5Qho#DtF2*M>t$__{MPE~80E22>p$;o>9}vh=roEB+-}cyc&m*4* z*)U=H^ps6*{Tj4HyX(pDS|1a%qseNlQdpd)vEIb;7$k!B{X=RL4w0MrRVfl9`_Ybwyy)N?FdmC>!K##Gxq{mutz7ZH-4o^PDaeqrmjgunurfBa#mR24LU}ch!>&d zn<1{I-5_z!7EjujM$0LDzQ;o; z;pz`ss(|A+5GCuEgQNL5J;`&>7{Ih7SLN_L`Twz5QUsAh1gWLJ`H0RcYWiy+N~GwN z&JLkC`ANCdA41d)QBx>KXdQxet=D0}J7SE6EJ*b5k^lw^LGgqLZXG~8VXgLf zaL9kxz=ILv;#ZoRC>F|_n>*3c^<^oF!ROJtP^L-`^{&^>QiaFWi9ht8XMtaqh&iQG z%9|*xKeDP|RCjhy>)y%#nwQ9nzjc%^`eU1ug|DPbX20Bb@NFVykwA2yIy`G~qQO>3 zKQ}8T{rPoQtmLr%u;@ET(IbN}@$&1%EFGk2J={hin#&I0NhLzN!MXB#O@e5gOwt-! zSH$ilbAMG=e>K;5Ro9EE-)WVzvE%d6PGVi z67Xz`QxX`gn60N7=@(zV;e|gK&>5|&bFH(b%X)IiZO?_|hmO;cq}o#~`tEsIs- zTyuWaa7x(TyYnH7v=b|z|AzD8`1I}FCS<2DR#ONImJ{#U1O5uMVp<=myid^Xo5!Li zy?BaJj_=?(VJKkA6|?E1>_E!!>-cgJdA% zoy~UN{$(=E6D+8Vu&<87?8)d7>>d>1xdR&`Y;-bwZ*n`T)P;F4o=nG6XU%-F$MjU? zQoiW+lMj6?0f-K1E8?+KXq$TUa=#;a!-GlZx44CJnSU@6A~a?Ivr9G}N~g(ub%$K6 zbz!{8pH*t}wfRQx;jFJ;(jj~7%G6doimmV4od{>ky|xY+eK3BWV~2 z&CZaS@8F;y%>fZeq-((ccx~Mm7T!j_f042|t0AZ?UHj_DQ0jDO`bU1n6C$}syt7AX zYj>QDqt^uj2f0B*@UjWZa#qDX+ONJ>n@-2S@9{X;7WSL<(7KCKeA5n}PoYdz-HNdk zJ%%tW4(hF<5QL4yq+t&+H?;w{0k|k+h;{1C$hT>S>pi4Th>;tZH;uKV3neX?nZutz zCrC3~-@SzX$3(pF4?7}P@G3$IAky4>eGq8}(>m8qYDKHQyT;9wv0O?^>~C!(cDuv! zdP}+Sc;j;JKG8OI{(QNr?_0#WiLjPRv@&dztK9OTJfkBwfVL~4f;;;npA%WH=xf~q zWu$T%LW-6p8%0uRR%Q->4-CkV|0d#xT}U=j@2k^L7XbcN?ss=)hGOP}1dCNhV>!98 zpSL!TYu#_yH8_wbT&pmwlk1+uE!wJ~kAz#~TVg#=qRy?<_>E^W&)Z;P?fE_4pH^UeUc$R~t-f zO=+eOt$~m4Jd%3a8^o-2g$sB%5L^u@a&?<1D1f*1tk>9Xyj9*P@73piWCJt3AvV0E zCU2cxRRxxB64Du4x>Y(Ta9stc?6KZZ*~gb@iqAf_Dj+X-o{o<~qdm72Jx@m3mz4jE z@CNkUpL8qdTcU@1YnTL$A7?KR^SAh$x=b88XD*G^K+T=`#;tc2h}r*wr-v^=Z+&fS z?eD>+>oRh^5suHDrADD_XZ=z1Ov>j+s2k@y-dY>YWx z{UFVgh%xpg%Tly=XVTJfaPNMH zoCHE=Y}$|Qm2oZ>=AWQsZDLzy{VGk-REpkIO6GD!=aRTtUcJZ>*K!@xf@nXNX+QV% zm|$4j-{awNF>y0XyuQGi&?j5FK^zAup6GP?PQrX_!+Kfm zBMDntt13=8$JMsnp0J8z-F#zW=?_8?Sx8A8#<`R3XWjB1`r2hv%fjaZ&_AcXUZo*zVfB>`DECLIqSk+EwBHr@ zHc+Qz4PSE`zp2tpnHZONjQG&LV8~DM>G8Ft-jSiZT_;3J0nce7`A%m+3K&jyf%O|$ zriCXp+kD>T8k-M?SGTj0;tjLZMY``g+daV{yM+2?uCMMa>AvOUkRWw11RTk^1 zyQQ!;jr+mOb4az^bc9RCHDOUm$e13|_36Xw`kD7D2e>w`Uc|?>V^45*N9NGQ=XNRQ zShP+KHK`7jR>T#DW3vt)2a95wLy{%G*c@V|aT9DmVH1FQ8f&{qPZA04S`4zg(S$ zIP|ElY^|<*FH6`IQ^2vc&9QZTSPlQj>}zD=MJ$W@R>&Wt?FQBL#H4h=D=S=ER}g2_N+oB@q7NO}>-=!+tyPgAB&hh&$T&ECfN7 ze=t@k`y!_f@iE&9SxZV&b$y(jWC+Glf@`ItfyI7`3rSNMcG3n^Iv&K6nhP_yRkLz2>7^PILPzp35n}A z-7k8PY@H{wC)aTLCp7##)$AAg=G5w`ceU*CjH5=fH3L&+!37$6=CjjNjMePnOmbxw z%-PK&KY<#}rZ%{)HHNCI%-09)Q+xjP8bvPwOvipNyyonSf>}F6!R@TZUuj21U?r;J zvmn_AJNd@HBsrY`=- zwfB}zGKZ}8J?Y<~xd7qw?`A-opyUP9HB;rEjV!yNfH-0bQj?A9PnRoYaf$ z+y~8+$4b=CaRmt%<65&)N9jPnDm)=l-HyJk0Z-=x>4q^WsU0^hDE0J=S*4;)_e-t? zbBL|ERf?{8hCRbtIgux3+mb>Y#n+{d%?eCoDk~A@v(@be%(j_03#xt{X}Lw) z?j3fybV!_^HVJh~{Z91g-t+RLdAj4=_Y!uO;TyZhQ0HqaK3KiKC$y^_Ofleq53>nB z)s1*Ic)(i|`uIF}tMJ>0^(p>LH{dU{(ShtUihEsr1^9B1@4bN<8kdT#yIZA+ZR#!Q zh|G#+Ms>w~bj@}pj&2{>i!HHn925hOx!8Fmh`!!FZ86YbZ(7xRxh1$AG4`}HYYz=yI?-O<5E{^xybJ!+J5>S@MBo|mo9rmn^UO^cCZy2^KhFt(^0Tm zV;4ij-0)HzbQ8z=`W?Dk;LaKj$?3a|EBpV-c6QaHH;7k!xyM+ISb1yb6R~XqT-0sA0k+DMbzc_p$x!v z$<#&xb~|{v#mv;kSZeFCP=TO|9W>dAJ-cBX5zi5sx+hVQrq|FqgzXFE0PqHA@EU6r z4(}8Xe3bgw(|m;GFZ02I!7WKOtX;FbDe<1-9`flPk~KLeKdJUYQHxB@orSccg|tVR zUe5fxOtF0X?nb9i$DX3($37oK-Qs`A&A+m5(|F5svhJX+HebI?FWp5+m&}L|U!WI< z{r;CV2f=t$!v!uY8FXo4OR#5v9?WR z_u}cHugSQQV2^jH15T?)*B)Ub$GY@|c{vkFn54JVItXz2!W!(5EXjTZ_{;(tmygqbwgq&gQtM|1m=Mt3eVBtb+QI<9I zay;$^wnig@I)!T-$C06^Eg@=uVwKrL>qh)c>FVHk^gd`+&Td+-b9-R7bYaq=9qp#f zVH!txf8I3}6_RW~bTm9h& zC~uB5x%U~vTF)2`o@q28t8qG+GW-VORqw5b8(&d$^iqYxs0av6Pth(;PU>Qn!lCfdj)C||}H0zA)%XqEA z-RmP9Zf7%hN36#Rqo%2Tc3ASPi{kP9rRTa*_bBA0R7onM2X)E;9bw-1%D-o-pFQu| z<%GN=lzmezhyX|Od`k_XaftaXE4D>iY(W{l)i0x+e{!_TUlCejAkp!F2Xt7_f&>a? zI+vcaH1yz*^YrU)hEg&^l%4NmJo{EosTA8b$6*QREyE%Tu318cg6v73E2WO#>pY&N zJ$B#w1)}K6ZBbmzTtYXb=sc{MH?Axay(ix28wR3W3QF^6W8O$}HkzNmj;&wYin2=Qn9yPKB(UL>03vPEj4szc< zC3WNA5R5KBGA@8M2xI1oRyr@{^VHcyQ}<@l&R0O%!b3=Fk6d<_H0g5Y_vHu2t-MNG zJ|;hBg^?qb!-3LEY2)T=7V(&zW*SMzNcX^x;kzP=k_76;VMLerBDFzv8|0LW} z{&Vnl?u>B=`;|dWroYUz|;2G+C){~ zh+4gbl2XSByL7kJA;(fT=EQ4FW~}eASxNZh>$M(Cjo{6RaQmmbae`o%_qa+$BGB6<%LI(oJ@1d(y25K+xPa1d+m=_@<&e-1L0a?%a1ah1rQ<{)eVb9GYdMBiZHy z`}hEY(8S?Ohgf#k8-j_a zw)z#T@2s<7-q5wE;H{|tqg=<#<>oh5ul#EF3=4-XKAla>@ zdD{l^Y+}6~Hd?u}v_B0%)gYWC2rY9;&e^|SDyxM5h%fC>&SbirqbHdwR8Jxgas0oN|qEmO+7;v{I$P&UMN@( zah5<{i%--RyaeXZkS@e$jfZuPkd9aW+>xK|baC_IP6oc?E!XiCNz-BJ|%T*M!vHMN9A-|ufDc~c`_-*d6DK@f%bWqx5ya^9~|M`p@S;@+=ygr$K# zpLW;ePv#bb_C8QQ*K>XRCs&vAZrlq%1umVc$)5+6sgaKn*6;P_vmIg2!wu;v0&Rfx zIx*9ZTV;=5YX$3iU!N5Hj5Y-Ol43eJE|+sLp)?^!UNaMj6A|oNj7T^Z}h}b=bE~_eY*(4^?`Jbvmwb98elc z#`&KMTk1pK-V<1e#Xp}R?yZn{B&lx@?Ms==Z5ekT#%1b{W^a&?G5b@Rw+nx9r`6Hy z%kL0Tsn#vUOzK3r=Rb_Hwk3qHWNh+9G(eu1 zEMvDeUdvw|>$-jCHAHhPZozmZ+RvN%tI};+rAP5f>{8uJr*;+^MaC8;k58lsunfZ8 znjP_R7H9vB5BPj6{=JA>4t~*8MOEW;H4}yHdC_}LU=jmidjgS zLT631I?T6BZrES63Mm}`U0*Xwd*U7GNZEz_(%kfmRt4#dtc$ZmV@<}d(-GFG zPYaXxmc$&IegS$NdyG{USOlL1Zdw$J4{vndcEoQEHStfF<` z{hwwb5@7IV#wk0t(yR3jKkxTbRar{<`9>&#!`gGrJ^75>0hbrW(!j1)I;y_j1gG-B z#MWs|r9g6mbF4abjR+o`ALS#ggLKk*`C> zUhfZgibPre#IV$$;mx0Ld*AN9Qs~nTyn!b{-kz5@_F%AWmc5o3=K?VXqW>Cpa8Leq%tXE~gj6D{wHe&+*RoAXd8Ut+%E0p z!5vktYs;01xyo1e0Y)B><@^881adUd7Ju$YtJF&LAj1#c*@Y`(DJr^Q+*P+Htu zpjauTxI4uu?(P=cwa`L~ySrPEBEhw|ThQPT+(HP>m-g3p=KJHFcjnH{*=uJ=xU=`} z*>kRQh3^X}0J%ZAIq=9@bhefO9&K9Mxyk=m$)t&Rl&BSr5|?`V&BITRDy@^(kkp^*0X}wRBL;7qZ(iOYwLbRLB#V{iO$>iT4jZ-jP~7}74|jwc;13pkG|?w z@JN}&wDgF8aNK$Adar`&_wJuAw#8gz&M4HhX9ylh+kH|R>&#%nHi3k4UH-aO*9q>Z za>WfR+TP1xWrgkHw*}(b70|%tP51ak4q|EywE9$T{zDPM6Y_=5TE4j>(H33!nSYg7 zne6Z*Qy`q3cS1=n`^_c^Cj%2Gpzynhu7Oj3dVg&!-y*IA;98)14oT2DJ3E_@R_7YU zP2goQEHvA=Q>#YldgHv531Ojyp7WbOZJtvxQml^}44V1bCU|yw=#Tgsi_<`n$JqUv zWm0KMknVsJr{M0A3(L*_s}<^syIR4x;^MZtDs?{=wuwLOc&R9Awzd6=B;5+*n)Yy* zAcy4F0sA{lY6=VfzRmMH)7vDcVQQI8k$qnW1$XBoAr5={_KCpy$MapO8K+1!MU$Kp z#M-KVA4m6{F z%@MO&6!n9I5Kx?<%7iatxhC;0=Eww~VXUgK0$KclxZF)u*b=m!}AlZaj@|E~0ckA|i zAdJiL;LQN)SpIvGa2Y%zWno_(&c4&!y=P(%wNv}PQ=?nwNQN4GC-Ff?O4e9_L8h_x zxc1BZzGmmq+hs7(v+3slu+w&ScLXMy2KSQL_9mq>>4dp??@8%V6#2MIC55?3=vuU# zrkZ4W#sq8+IKH|9UY$mc@GY6D4oR$(NpLTp4|x0*q4fsDj%s&KH&I{u89&sI>RxB` zoZP`JC%{KEw*mmhp#5ALi(N0^Yum$(Tm9U^?!2S8Tdlgw`%%V}yHgb3xSP2>4%wCP z1YaW3TEAIBY+V5@$!&L7IR2}*q@!t%Qhi~8$2#NLhYAA6-K zgjz{^%VU>J$MCfXnIo|CRz)dJ5!VfALFdP}o}EC7##z4x6t?b2e&|-q9OmZaNIa;v zMW%dwVEVsieQEAI1~IL1rF{(WeBqQdry|iumh0dd!VR)Zz53&!W<#?sQ4E{ik7YV% zDjfrIJIkKxK9xFb&K(2)s1+;X&s&sju6siKBY6f+-s5Nr=-|R|{FMs{LR?V2&QS82 zUYV8%oX~3udmVr9uz+a}_Pg7{gQK13ji{lC*91??Z%Q7Ycl`)nciHy*v{WQeQ^eB> zYp-Gvod(Y6)I7cW#zS>N9_?4f{cHi#OCfD5yLIjBZQgCRRm=^%zf^AV_jMr6_$tqD z9z3vN%_8_UXT#IhXDC`k>T@SlFTqHH6FQ$Jxf>kLb`aIVQ%oY-MYZ5SG;?)!aB)`IZ#E^&&Llp+5SZ`3&8(A*t}HgOB@Uf>*SAr8iA zoK<@ETV?9~52awS7IZm+?S2>r2~Ffo^fwla@Xr zbNP@9U$J)U*FD&W&K0`wcatfIE|`$#3dX1p)ayjxBy*!KT-xoyA z@Wi-yd*1&FB&8gE!0?lAd7siH)h_LnEdZBA={TWq7J7rN6TZt=fr@jhFar*F&M+g8lftz>;zYxKCuWygYXk5W?bFIbmS2z>ZW80%dkv=ds=xyI`tuk@3^1}7OG~*($2`@B)4XgpR37b5xvOSV zNin_4HI7--f@N4qZh6^dQ<$cpLowQK9q0PM>qYuuw3%rl7@{2G5HTIik z2jiCXZRUcvpVy?fIczK|R;erN-&rr5P5eTsJM^?!5Y=(7PRcAWhl&p?PW*zEn$ue^ z4C;X4n4@owJdoLt82z@|-!AgUC-dQ&*4os(qPjoOGM}nFrh_j$WEaG*pPjXoyw*#w zq;nODhXsb?oDC(mH&0HrT`f`Uva<_p5YP@kKOC;5tFL1SMdlHliI4bQh*20Y-<0b( ziQ{Zmz1sfxzyz|JTP2SCN34Pw#4E~2qVN*;`}wRrJB``kDq1o>W@ZQYEI+u33KIb% z%KIeRk`mvatFTf_g|Y`PsXegc1agh1ms<`uHJ#C`g8&vf$z`|2;h_~(w=F`DT498Soz zKd8Gz~f$oc!EtV12^ZHC={nB{OF*8gAS#9_w-TQwf?riU?DyJkf&TXtBp4qREm&B8**Efc# z^vFqJmp8jw*|^*ZM0)(M?mMz7Tu226d@_;u+Lf-it*1SvUK`hTGhUwDF$D$3rSlCA z&&ZQdp3aK-=|!GuHdr-S`KaPjw0(0#&_*YSr+?u`SKnh^q~zNOm7+KDcq{_Sg{~K` z)jJp>=*#>GxYaY4mJ(NW2Jt76ba^4+${xb364}31yp+(B(XNgbp;x@M2qLrIq^jQ> zqiQa=$YpT=P}|Dc);xJn3&KwV?TC!(h9g5CHjJ%iyI$&kL36(3RH^^MJdvKFhXzN+ z5&%VuHwOqwcNj}qz`HBs+AYOMFXwGlRddwI`?iR8Vi{*w58jumozB7nFl1T3uQki| z&w>Mif`dTU%wkuHxJvOUPS%7{nnTV|0z?*;J?zq#0{WG$SPGSI zU4G9#bZneLaHn?g^@XMcB-2#MF`k|{Ix#KGT*)z(ewR-3`{8rIIVv(d^NT*^Dg^)b z=tY-kzzdAlESpEjXDKfIj&W0cw}GO=Pz5LM4Dhru@j#JX17oP&kk@9*S zm`~qs_BufIE)lxoT76^CpqNZ~&XvLcPE|uH4r?jl#w1it_3L(^zyHaPuvS!SZtN)I zRguW2HAyEiVa*S-@6c!c*EF*)y<`1i2+`{r9$%KN`p$hmSBG>N14l?eVWl7z7_he z-B~hcu_G{~hOF?2-?tCbwa3>AhDrTa*h}D<(|$z~tk!DB^~I6BzyX=$^Ya>wYLFbN zE%CVbV(EYi86KJcautD4(~)dJKs)9PqZY;+*Y@DsT;hw;PW42S{qiedGq2{yDKwf$ z{lnE|;jY)8WQ%28u6}LIEJ2_*TQU#@XE|+AlWFG2lKAmA#uIobytkL`IwSswr_aad zx5eZR)(3qiDzCV`&%*_-d$aD|DftTvTw`bXN?iQofZ0f#6e)1a@gCi}2no!+24ACS z*ufR#uB$kDL|yZ(8}v^l^Hwv0xQRT516mbiR2)YZ8&LrA~jOvWov!OT0$2h-n}BaaF?;MI%50;v}ih&IILlfG-aPRS69p z@Os09l;un_BE%2HO};EsCD08!9Gz7fKTwY+YutZF*d&Mj1^*_ajN{_>L(_(rK>M`s znu5H6d7eX)eG^9h8?IKzzxVAQo5bgya0~ntpIL~sAmcTA8|rHlKd@eIs1v_**?tw) zy^Xcw`bGGqF7rqmh9gaM%>L;}*BxyENCVscTV?_{jF;l!3}R`$L|31T0fcg20IN;c7uhkPP1j#Q)jh3Y?L zHt>@N{L8L41z68mVoS$}wFgy1D4t4%F69I`v^=)hW_F~qYiY^|@G3by9J`>KR@(JU zYNpqjWN?hfL%q%gl+vJGFaggjj8WK{7p1^>{LUXR3pxn9YuQ|70MGOMz5X8t54eQV z94-2j{TkQ8&7{w3l`)ex0^2I7182R&NkukmXmv>kFB%Igdmg3EFExFo>6vh97NHI8 z_AIh}5za_t5HM|JxVMEOvG)3-s}k@+z6hVlCru9Fvs!lAY?)4UaiO z_MK1Q*q?+BjBEoU1Rht~gU-aitJ7IPJ==p97Z2>S3_Vfm#eJ+or51CA>cr8GzGN@v z#<`bNP>@=OUQXa(*NOYs{28oqw+a|o+-_NUIP#+ySG)P@i!J7}A8qhJ8;TbW*4rHK%kuz9kw<9fqX*P`b_t8eGghH$5MDZ|AO7h1 zd!toU@1*~ssj3l2`zy~AyR(;3cAjZfXsno0TyI4^b=IQZk~s;aIEN==%=7$GX845{ z8iPF$8~Hn##|RH&1Or2UE%16PP=@?tDhi=fr?+G0QyeWN9If9^!g-BE0d8KH7ul@m=$K#98ZB|1PCv|GnZ|t8;m9W_J=y#UC@hkKO(2 zi`x^L#1@qI(UQke1HNX$>oC(a{&6AW=siR*WOccA z_Nr&BHQJL-<*rNT|Txmir z!KGBiXXRq$UFrR3Y0Y|t+m+v{a^(>QE!xsK!Jm#rQoHT<*CE5qi^HEuYJv(_aY!LVxl9p=vjGdK0{ z5A^F1q^ZC3323e^Eq|__s$(HA)oJq_+L~gxD#xG;Mo}luL#7&!`#c95)LP44 z4sN$;xBQEjiK={r@i(q0{%+Zsh|?!-zV~f4pto5GjI_JG_C#5{_C$)E@M5I>zMQK;@~@R@?10<9JzE zty*&3f8|SkVE-T-PxwowN}rQpb4r%nfyS(?YO+pvx|7dY_-H@znuBZ5T59tE_+*^# ziPIyjwth8(My=yRj?sY4_f#exRla=IEH7t8N4yn}1CL09`9&=B_!1$5n@O*em!U=j zr~|Yws7XOTI=Z9QbmGShKWzQbUEqw&nlDZNfqtz$3-y|69ban9t~WG4(v-O+0Q-Nh zH+*xXsrAQ9tows%->OgfOBG+{(TK5LF>#D%+zOJ2MuxQhQd05D4w%C8el>R7KBMXc zRmx>K22})ES}1+#X~*~i8I#;c#;&8~1|&v8T`ZUXJ4d0f$jy#*YTo_4sQ!CFuJA5Mn+JKgpPr)Cen1iv8cq_n|FfZHM@j;JegDW5i+myTpf&I5|Hdu^ zouln*}O+BZ3>G#q$pA4c#+j36$nM)^B9pgl_qb>UcL7InAKNyTDFKngI z2vmBuQiV?ghf8Tuo_q#RpqzKT;+_nozqYr_<2*!B`t^9pcYb+t+P_g(moY)fp;Gl^gBztc@MhMXlYeY^?Nj|G9_X}E#{F} z_|)u4R_hlg4U6w4?dYdOVhL02$FN3<5w*}%lkqim_CP9PUzAr^4R1Bd-?Fys>;w97 zjzG0Ow5F`YzM=Cr(jEL_dfe)_58qs;bWFBC-*lgu=zh1V^zUa1NIqSr)nxVz5XBiQ zn*EJ|-ZVx$4(?75R4<6KY`w_u7>Y1~u*0(IwwAOlnxpL9pHtSnw)j7qefIPtat#u& zvWA61Q}}G=zmP&A?T--Dss-N?^ZKUqmI?WZ%?%E9lp&`|nvEe&w43jC8na=+09#lO zi@|JEyH!-|!LxrZnwMtd;QDt`)xyO?uy{J+Rk`X;S~>lkz=iK)A19GjkgfmjA@=g# zjhsP#Bp*f%VWv4(2}ck)adZW3E0w-x#1{Mlf_8vIthY){Pdl?cOPAn8mZO`QxB6yz zyuqQ@TY};?ilPylgZP{1&0E=n&K#~17eAA>*C4GzJH6*ICzWiR!Ftc$2&JH1i#TMa zbKz>7(?gG5HCy9O9XwO`tmh8PM1kwHB5N4duilsDd{*~~F<6Y8+yCc|Nm2eMCuy~V z8FT++p&AFb{0+XVG>y+EIdA#eoc?c@cyFAiGY(3EVzIOITm23sKcx1IJ~I8cex^nm zos5h%?2!T15+m+zDOZXiVgv66yi`IrXd7geA84`Ky2^?ZlyY`ObpoO;W{VW75mMJ# z<&}C=RdENH=cux*jIZlf=6J0?3MX29amFS(C{T44@KtJ=;r#-|kJ~<1q3^qAD?aBB zx7!~!*+STBJ>UA!i_sqt$xN%6c=-AA%knpf-Js2%V2q7>%hv$1zSl2HQM91`Jm+Jg zWQC1gd|bC*U+`@hOoK68kKQnfl3qz;nH>@tj(5F3EU+5u_7(eqj=}M&p9I(Q(D>)+ zQDcvR+5J=HB|Cq+vwHRj%m2Pzjb7{;V~1;Xi0os5iw+D0sA74Or=JiLn-zG(de=$V za)qOw@g+bjSzH4@N*YR~b=-cvna~LaGY}rnX!8^kjf_k3R%zaxFMbl2r}|x0myN~q z%`frwrdOT2QL*@e(qaFnNH2la8gNN~jM9g(WxY;*&BsHiJz+_9nA_87+yS&SF{kqE zdxjI1yfJ?CygAE;q)py{RnqgNtAdhx!bZ`Vle~zrVL$kIY>-f+uQ12`9!e79C42q_ zN{6hqt6!jsNz4-(eTVxOcG&Rx2PP@Lb}PYGp+Y9y@&V$c7!~U`+zz)72a9hAET5LwSuUHOe$l>$*m!b2N^(G1=Z!v51 zMG#qh83GfUhcuQ0N4L>!X<3$FSLkFbCTnlE2;}x?IAmiLbmGvGjWYwBL{36oRnI{} zbc5L>>?uG6y>@O9!u_CBJDhJtl7x5dJcI_Zsm ztgh~m+yhg6wIn9%cLjBPp*TobIt=&e&Ep4 zWhKh=vJzjnfsFp*-_y9?YAMiZ1y;r!c}l#qyB?=Bbl(1T|Jc-HKKY>4G@yMJZ&}gj z02;KQZ)Pv(jQ3J!`Y4qdWe1GX>byu+WtTUG{;cwQEG(iqUg{=j2@BlirFl6`1ZU5S zsth$LfcO!DWR44c9Y!7b1G~Dk9hWPk&l*>uSq3IKz|xMFK({qeRQr$Fg)f$>!th$E zZ^R%}bd;M?2~g7g@A)Zaccmky#)c~1EEOYx)i(b6L&abj4iV}5z^f7Ci++F5w52qo zwFpX>^u^6CbaK%knJKgG5tJnZxpWdU^ikLI%sehBu4cjxh>`PMtUaJBj^iUCtBh6y?_w0>2Vww#}JWVn@W z!*%3ztu~uV#$<#%`qycEGckVy- z?S}`v-JJuR-gI!~7|~#U$hrCLh5O;kY3NH^3CjJySH+O(EqpVA(kJHuaY|+U=Z)Gc!Bqy2EGg!|A?G1(%Fw{&7H8fLUJ|l4nGE= zz)QrCb!`()K7%ocGH;3DYM7JHzo4Dh(s(S1=1}i1adxZi=TqycIpT&z(K_kve;Us}T_pBr0K`R_CV5J}@YKdGudh7-R2MY|;**H%ozaqyl$=SCj~tvy zk@(a6=^`=Y0Ip4j562LkO_pK-)#iO(pW9=lEk#w88~RLYwp$wb>_(?pJoBp?pu;Qz z(=BbTl)60gV4wt;l+1x)Kkr7x0|a*>9eJuYdWdUVlE_TtK>imq#k1PNgK~o8Iy5Jax5^F1A_+993>!Gj19%MjPbT6C&BVSgO?@(Xdn; z^(DI8@X*>y@FU{l-jtEXVk-Z^RjUOUb~ju5ePQvI?z<`JPIb|S)Q(bbOH1)D2#>*l zC`HOv>m|j89S^S;g5kL_R@%C-KX|I_pf(c_oRt{iYM*+_WL$4q?45o|gEEH90hXvm z$JImC6RWx2&e8lkDu3Tko3=x;)GeqiBY1hdhk5LNODPntNl{+Ju}{6DteXxP3l8^k zWW)Wi(bX%^_yfaULMjr;lKmYVSaqHgJ$*Pe&o&OapQ;_?^{0S6#RL=>)fo}m9*P1} zk1vwYKIPWS2w2f8wiWl*>B}!k)@8~s4c28!{AvDlk=WmXoWO;Rb!8$v5g&FQ#{8N8 zut^e>ZRB(KMDvbXvURbphP;+Pi~K&k6Ulx`GO_p`x$Rbc&R&cL*%Nwt7HG`GBVPO2 z2-Dn>%%o*(7Wj9&Tr@aPc$glw22NSR?LB@biv^{?p zs(nLVw2>2%EMA%&pWWd~8InSDN82w_rLi>w8DCEaLo9ZGIKEh=r$AK7U2OX42$wuZ z*S+aV@{cJzvD@RbZ=R`IE(~rjelYZACI90DaBjFhL@N5Vkvryj) zOI812bv?ZEs;NjfTb7YE_2?ujs2LqZW50@6<{f-tg%3k2tnrN-{PMai+h?$9alaLH z|0`r^sL#$s=k~!t=FCp5)~@df8ZUK;h0xh)YeFt)x#|?Y@!*qxB(n&fh^hVW{`h3V znsA|pq-M%V)X|-bjq$;6y0b?Hz0N2eS+Z7G2am%WC^ukPYRhQ&H{TK)UT=JmUy858 z=IbG~wE`<8Fac{q3Za11=;oNxII9mNfb&wdoI(*S=T zgnRn2Rk7~CC0m73=jdTKvk2<4U0s zXGA2wyb{?f%1o6|Ij{b?aHf8!({}F{Ya38#oKZBu9 z$NJMV_-&Fa|H;~t7sl!s|E~K=7YK&ap6M}h)EevnrSRoH$@$;VmHWzBVB{|%rd)Qh)R~;ZvfIclQ^bIb?*1EvVzoG|Jkgzz%g$G-Vk@hJl}75tV!OlRaCM<-*P-vUhU$TnA> zJq}%I_I12^NIa{G2%z}`5kFpbQst3m=8-P$-wZ7|`0pU}tF75EHp!St4is@U8BCc& zdFPaHU5O{UsgWuEA-M7<(+%~+nn)K2&cBcn8b9iTt*0SM37+qR<>{rTjYM637iVh} zMmae-K64}jz6Z^+z_5)MfaTgs9k*-??e6kYnV$O!+y~uPpLLXvFI85-YC6RR5!8$Z zM!C*K41~2je=i0?cHX}iBjF~Uj<{r_x$^ryWT>;>sXwSIs{W{uYvHizfQ1yY4)wO!4zSjzK)T(!hdtl(;`voK{2=mR zuGpV+m3sT>kE+2ADAgT_i`FNN)!+t~xh*`a@4JACK^h6UN&Tw* ztdEi&e#R70PQ&h|3Y1YbPrMYeuKLmh+_MQQTZNm7UKg~BkXD=qhd#a-4L_&mWvu~! zJ1nT)w;9ZA37Xb=Yk2+q4U~DS5Jy(1{{_vyg=sUTT1VjiT>L(f^8MQ~P>`C3>YBR3 zHJPSh3FTky-EBo^B`(=2bs3&s@yqPYY|Emtih?F4+sdJ|^0*zQiY83kO0l%^>OUrv z^&j-tP8sefr?c6OV8_tD?*QZ-jutMCR_Bw0!6)H7Mm5X!aV_^TE!fVWY-gmW%r&gP zTf9p7`1CxKITF1lxvwUvb%9Ybkt?Myv%l)LRSzN-$^M&$ikBz9{}c5BT~ZZ25g zn-w116`oEq=pb3B=jKNT@@mGeCmF`qoWiH$Yk@aIPdX5G{^xs-<10(FgHb*5LASiU z9;iR_9>%6EYKLzf=p`HZ*CKvs3YIrWAE?t|;=T!c`UK-yP#GUH0o~2cHb3jRiS}y} zxZK@PRY~4h4o$-W1y0E=b3@36#1dnMVIS9fP2ikbg-db`OO+`~1Lc6T4|foDK*vtJ zpPgou!e#_?Z3SJ8I8Y3{zQu_Xn?S5Ts{vlmZsmU}ulHV5IYv2@6_acMKN4T^?!&<; z{L82GpF5tW+tG{S8tESjz1^0bBAaFfEFr@UB=;Or%gp?-=tx;# zcF6IUgvMFBS4VIkuC?Re_pXNBw@JZ2L7qijpdP%Lo7iK1G|eP)&P(%%#!gXelf%)h zdGfjjwC%{a_@0Y;n^&*FMk85xrJTYT_H_P2XDKH%Zb6=-pMS-U(UAQ? z=Ih_!08QI77;yf_aGoNqIL{uDar$o7{P%H&p@ zvvJ|w>G8c;7rIA6ib9#mMo367VZ+=TZV(ADb0iZ(9Yw1zi{L!ZmZffx7m+9;=|3-*e9aJsFd3pSvrYm~FG z3EiQnE8X^VhqSc`eQB|dk7y4D8%x^$aBr(J{`dpXqmm8*#6tkR0MG(}yLM^x=+eU7 zC;jkJi@qj@pTkoIDnR9(90TylwfaVrXr0!RWame z{RgE8zkD9PPj**LDWLRQ8}-_a0AM*tbt?lkwyhQ~cL1c;TBNd5J~4h}%aY2TNojmz zTR%b~DatjRarW$)q>~7()Ng{p|9zw7)6!Env-J-x>|!IhA1Pg13ueRyEuXP6G8$jM zK*I`2mR7iqXxU=_mVEW)69wzGXaAK?7aZc)rUAiaEpm-jyqj3XDQ+_we>qNe95Bb^@j{DyA*fAu;oY&6=j={4|t&?Qf12^l8rHxJ+Z)$8~N zcG7E*Zyd4NZ?&GY>D(}FTlz;ryuPTQ))fti)GVO(HukNw3;JE^h`Vd|K&jr9(fV45l&{)OsQ04Q|yJPs~?Wy(An9Lh&s; zbkG=5=2Nknr6ufkkwOr^5f^98N`fy-iUkgkJ2V|SpRRLQ0rEL>Ub0@jzc}%~@en?0p?ZMeJ|2hqA$mG) z*H`cB{=)Yy*$uBvX-)LLeKKg(Q_NL0~l zZy>7BWs(JeVJ?VNY@ZAO*j|X z>t@OZ(bD^Cy8c1+xRbQGW%X@9$3D8+xaq*qn&U5LjF2#|GJ?j2=EL7L2h;ua%_xx5 z@HN|B)FV_WJib1}MpmDqG}^oWh$Kb(vO-EysDDaPKNsv=-p@7TdOdn3Kg(14SO;;!9ZOtz}g4l^^hVI^9^uJBWC>wu^*3M02|4_G@H}pK2Pd@c2;!5l}8E8GhZ-?x|L%rB;{n7|)=$ zZ1dpY_SpaAlLC*Vq!Mb!;SHtV*^Ld5H5$Q%yu$ys|2Lz7apl&TtUB7Sod?>6>ssNm z^2k$ocLdJu!#tjC2*bi(Qd$VDHKY20_369O0!A1Tl2BL(EjOc@v3Flhr($} z?#JHxd^6dA{JpIKzgmfq`+ehEpioi*0(;=g_=edG&{3F2kK^)RNQ4(3k+O>+ElA3?lbPs0ctJWfXv91&{~LY`3YU2i72ei z__?}eW6BBSnW?R02wz+Ludo-*np#@zFq?KwlnMfpJs*~GS;df8$mUVcg(*AQ2};iWX5hC^`QLwfVoOoidqcC6 z3n{`5h^z&7U%Q82!BZdWt?m=_spbpYdf4h_e=U_&RW|r9zUd;J@YY(yo zAC%dlW<|+#BlK7OGN4-f~%#gsO%z??a;o%jhic9zBCTgZyzzI+Fn`??}$0=*cv(r}hY)$01)QcEeW1 zc2Ab}6e#LcZW^lrgoqo~Yk%GgyfVppJt015_bzSIPf%YNq6n+lX`4@b7?aZ+L-Ij~ zeb2Vrubd5iQ(1)|MA^sTO0eF7#=`yft51f$O{_cr?e#&3`uSFkt&<+lbj9n##+%>f zgSOQ**gTGP&ti2ZVLB8ZqJZXWc)f10hSNfS>W%zK$gM~J{d?{~90D{%?UzFL66r}m zV|If1YqTSeo_k-bqc5>}yawWqtKKb971VxnKz94+ddQ7oozHA@WXHG%arh$>Okp_n zx@h}`-MuP@sH)p6GcPw;C^y+)0!s-&i^_H}MbUN`VsQDq?GUZ))HV9w?BAonAZut{ zY!f`9?05&jPQ+(VByOBaJJb34<7!Oy2YURT%8zrVAx}#c;>Jp#-E~Wu+}!tMBc0=t z2u%=dh)>vEA#>jryVoo;+AE-vq_4ToQaHcrf?T!0b*}kh#O9mOhaKaS!JbcU^`|HM z#tyJ*kk`CVDdnZXa?gsK_q?tbi-6i+7kWfBpFO|A^e0qj!An_yh#yc*UVwwH^(-Fe zn<3WYgJCl?dZckkDUVh>TOyY@G%xp4wNu0>(y7xWVA;GkVg^p(&5MH1gfAOA+BS|3 zSWFhmkkT92yN?WEQ3d;&J<*?t(tO%QM}sjw891ZsiNc85P|xJ1m7n{xJO zm77+~vVm=g!|}1W{{p@YsZlk~tt7hLd=gxm{y%;k)Q};Vp`O9RN!7pWxN=TOlEcwi zUTjy(&HQ&q!!|xGAsT}IBZ#2T%GYe3e^L zd6l{UQ@T!*uv7mnxT#rZFuqyg$Nbuda-NnFof()P;=P8hOBzA*D0mrQ3jlF~7Se|8 zN4FbxKIytN0h^Y=%NBp(rL-k`1+4^?(Nh1LRe*BRl3nK!*P1(-V>))@GP)iBISm8^{cmN8hdn{U032CpKAcvim! z--O0QvI#rIclHZOJv8n z8sh))=eVhxm$7eLe{3@Xt^a+YvC|SY=yAql-m9gpVb*@&xayX6!biXAMz~tID8nlc z(=WdLkU2nHZu(dkQmwM#&<<tDsJy8MIS4XHN{amc%zzbI4xl5htd8CTCdbTGw;-`mPwr4H)OB7H& zn?X4y{rb24`A^-mpB0=l|63?2=vOKX5;PFOh4&|zO1kxyk)#iJ5dRiHg5TEY{gU`m zp{!=Ho8wzG@F#})jPQOBt^(aF#N*KG3NtCZG6_*iII6AXFmG7i8~u6P*4lsj6^1Tr zxFYjIFb;j)u6F;GYTdCg2ev+bUHN{>z3YfSsf93kEmhP4ZqH$X(J2F_77~Gq54w(I zZGMM*l<)Sde$Hly#%37r_R`2nUhF@6em9UVMt9Wo$Dc;t^*FCa&&pOebiXB~ReGvr z@Yfqy_G01igo8g4u_|1PKGLrT2B>vwgo|Ng0*wWy$e1s-S2tA!l2?t!zHIqEIA6An zu_y{3=%V$ad}Ih;J4?};%fQB03;c<)fKS&1o?aCAk4Bk1`Z;zk!3OdsA)Q4c4Tg#- zYYo?ZlnFViKq15v>iCc;;O_q)dHH8^L)3Hq^fu7YghczK(=|xX*7_{qCqlRXQ2-t@JWR~SO7Rrh_5+7 z9;r({SxZYh$QceHT7nrA37*hF-3^PH{`yRy!{7M8$>ppLms%RlyNm0UM5xN~eX(zP z3LFlr2wmLbXB^6Z>3(TkTnjC-7+y8k*QIRy@6Y|6 z8w2^EoQ=qs}lDeIk_ zSDBc1UnPjVk0Xfu*}9>I!B|iY_-q=UThlv9jPZ;kX>*jX8sTZ0Zr^EB-k_F$eET`- zQc?Dyr~ci=IzzKD9&9#DXb&gNAsg<{PiDBHA9Ug}bG=%u%XaC^+$XdeCi<>u-l2CM zH~n!>Bcg3NtY#c!@^`f&%QTTQ7(j%YpdFcWQZ%IPd!_f0wlsg1F}x2$dEZRRJ&=EC zIdeh(>e?G}Wd^b78*pyyV86eU8uR(`U#MjPuX|ltc$Ju*mlQy9B-T?#Ip!;~WN#-O z=>(o3I$<}`O7l5$@=q##J*d~3-b5cPhO+3;G3VxdE%&?k~1Y(U$+cIZvSuA zjZ$!r#E&DV}qCyTenS?o@q+!8c*VnE#ZvIX4J6Lh&y8vFO_!TC!nv1{S50I z*?CVEA0%!P91PRlGCA+`D_jEluTyIMY>F@43jpQJp1baYJ6T83yO#siK%ZSMxB#qw z=5V+|7ozOwurQ5KtbJgsC9kD4lr^M2U+)lZ*~H(e?Oj&)aUiktPY=Sn;_UN{XSZ2z zSUUv@AKs3)AJ}><8+;n}u7#}FA-I?BN8QDHAd`+B9Lw0)9zN_pO-@_d7LFYnZqtt* zEOHrvR@jqs@taGN_DZB`bw!7kE>!e$K;VX-POp!4?`>+TYZL7N z^C|sjCk5O4N|YCi2^Q=mE2qQshQsur1Wk)!dVZ2zy0P{;vA~J}uBrhG=3m!gcJcl9 zi)VASoFR7NR7rVcQ-Oy2b0wi8{~uLX85Py{wN(TJq)Qs4yQDh?kd$tQ9HhHTksKQ7 zZjkN{=`QIOkdC37;T`?)|M0GL*R1Pi7I@D+v7gxI+&(BA#T5wZI0^dst@30c?5+uM z+@CizTY$KhN|lO2m$Q|{Tv$|?>LRIIPax(b)fm|FaTY2#e@G8faq#E?-OgfBP3^b; z5$c?1_1FrjWg88|cWWL>G_Al9!<&cR*=x^4JG!Mo2!hhDMljG#^6cR3KoDqI!>XQp zt>cqX@`&i>>A1By@}ge>JQ|d=Eyc^>8-fYRj)XA(4Q-!mtq7@~O|UD6!Jp)4h6V4rJg!RIudJ>PVbn>wQb&Z(@zIgzfO@H)dbPH0719bX zq_j80&AuYJedi$2b6Z2`s`mStYI_QXiv-K>j~CoC^m_*$%@u) zTksdgs$j>CSc@J#=#;eb0{bs-5XE){XMGk#;~e?-ynnMH4aEq+z4UX$$L~v2F#nzwKFC*Mh$l3e=&Bx(H=hLu>O zL&`jhl&6ZZ>Gj~oJ>RwK3U4tTWN-LJJy-*GT%Ha%`>%9Y`x-ZYSS>`Ut;#_ju?B}U zlDC>^hFx%nT}BfQIEG!4x4J&EDcd&L&!aerXtS{Ym2RHez9p?4QLoOrd9|-Y@@lPq zaE9<&lQ*8BcJQa3U21onzlnlBLdY-E^E!P#$vS5+QIsOvkH@Q3Fn zbc{+NKH?6+Gm^6YovxY%iOcKDJh@rwqx1U{K2JoUoriJYeUj>c8|<4x%#fB239nlz zu`)f5PY<{#mg{Td$jz0eKU@DQK<^B2G>8Cj1tz3Kn(Y6jm8|<-`3Eq1SAUL6RZRbT zIS?>cp*_bsbvf*uzT+U%RDM37;9c@@uJ5eoBZmv~J6ZRdZr|`& z*bT}sCPyLjNOG!3kWi%=mCNl(&YcD+@#dw!L}A1^!$Zti%M_;U?FD>=On z{34TXReQ@@4hwhf-af$gc2?cB!V1XL+_lBQ{l%rv-Ceu&zc6rZuC`rw5GB<3{6gbg zd_w3_A82JzWHKd@V>O6E{r8Phon=kE>v(R6YHw<*!)65^-%~9=iH0>-?V>729@K(a zsO0rVf$C|$w)J1+*y19Ar!%|goC`{(LGg=Uu)o*YN11jI?lZvhNg0*@M{rM zbLO+YI7;Iqc1Z*LnJcRA*l%7fbC0cgNXad5w2Qd2-6i>hdm-!{oLS^&yYF^hp`40m zQw~VAngr=g>xHFQDRVMgmIFrXK65fJ>V8l&;t25qQwBAfvXx!$89m3n7z-`OOZJTPd z4C1zRBI<8rnz}UD;r`&qTI1U~<Q*J?60sp$vtrzH9zxu3 z;OV9hDL6}nA^()Y7Tw{lMO8qEE_PqZoVI>8<6246$xv3kw;5W zvjkrD0UWo#chiko(KNlrU9bVT0%5m*Y#AM|ahvYJ%Z0eNm(BWzK?@F3FV16r1!wZk zaPIXjk=EY1MTMJX=h1J}y6JFQFTM{`Is9!oX`drR%h}-+p(u_Gr#0GT(Ux^&4-^u{&CN;$Ah?6y73&=5EzAOLI7oh(c{5 zv6qUT23NmgdLF{bf4{7&->(Tl6O~QPh}-atev>DUM2sSEj8erxkF2@-Pyk&shCop* zhrGg*1x5N+^#j)7gc9g4!Si>%+)S5i_vT?@DDzoe$U(3;LccG!A+yO>Y=rdczyxEm zqnm#1C+qL*{bprYoX7A_NA)6pOq}K(4egIUjyql{aAmr>y|4_Xt#m`UV#Bti@t$GT z1{X5LusY1Jx})B@#IWjv3&CcYN5#KD!nY6MhK}}k+}`jIJ#BBUc|WZ5t@%8x^sg1F z>wUOOw~gaRZ~;XN3liFEphgR~+8g_{dZD>e{UFJTR@*?JR#D8B9+7s?j2oHfh^HGE zkPh82|MREeL4P~<;=jj{fP+>bJdw>9E`C1Pu2fhduKzV^l-j}mtF5H`mD6j)%(H~45~bTicmq4W{NP^#f*eE)D^RD`Yi&Up zB>Kx{ggmN0xczoA-fXkMXw;+S(hzYPEv43lF&i|tDkO1b+a#t_JF(sqD#Aed8%KA} zXFc07)#k^Iaw5FX(oS27-wp(tk~x{!&djmsu@q8ftV^$C12iYwdAv=vQoqiBit~W7 zK3s1pM}dwI^-a|1nCkgBYpbv> zqhwI_DO0J!?GWvvQ@M_rYpd{~Bw9O&<_}Acl+Q1on@)wGMU!fXgI2lkQ%@C7+kUF- zIk1&>Ux|1R7e9lYU&3%{fBS>lc z8dNwt1{tS47E8jnrJ5>5IR8>v-Lu`&6>N7Ot$7Ov7QzYMvW~C80kqHy{opR52s9*L zk@ppqzd&ys_2{2dKi6R94(Cs;6H8+W-KTyn+`bnQ>O_|n;yaN!onDvRlSYaeZ*YiYJ0I6R^Kdb> zdn&(liYE9XnL|Dq2FCd&ACj{&eWQPw^OvfCy@JsU6FqZ1r;6Q@ms@=T*Gl!!`#Dfm zXRg#82eEwuvAKqxPca(O(}_kVFDJK>PfDS|_K)%NX`77Z@hRK$TBY;aM32QCk42jd z*GyV7vv&Q1%!-8#0W0{{to}LoNIO9QrHC<6=>%IWbRSpa?N+7l?)uco_wVSVlJ#Lji`Ul=;7_yqFnCN!n#`1A1<{uGLT%5kL4 z*6}>|8i^c8)CHzc@Jixvpy4pP_1E7XYyC^p;vIgsy8*4tzI$Bzgg;bh{k$8y7pS-_ ztDj^GF`F_~s%>a(4;vE9y*VnW$5j%mI870;jOVn?1nkU+6kK}Ujul+u#cNa7eE_tS z{NSorK?BkUSHyK|3>`C?UB_21$u9WhAGWKY>HZ6A4y`i+ZV}C*<(t7Evc(6x{nTeTWPRxMX>Eb z_Pyu4jnLtg=lrne{LW?NlIOgS(16CQb)3cHZuT0+uoHZbTRCB6o5t^SJ6`W&i*slB zbLTh@{%sF_>kPEazr1VO_8!x@^VqrbqF}nPlGDXSS&7D7xX?{C{>>3^`#>`*qT~Li zC8}fThKKC$Bx(JS8s&F>>PF;uedUltD5O}_uRaSmuh$tsjnjyKB9^^tNyKABq450A;2!BwNA^BpsGE!Dq2YURZ z`{9#Uf2P|(TFsLf&a}=C{oFCag2zS3GC2Rtz0h|j^n3+)zGNfUDj*GXo3sqfa<1=5 zeO#Fnth#?Vvsx=(szaM#RP1;h%}L1dtr5N*opJU`cJ`ugZX0QCOR{AxUn<$V;@`W{ zarR1g@#0!B&~MP@eDp3yB?)frVjti;BWgMJv4wVGaj+rYAezH8Rbibdspkt zK8=4pQ^5y+Z&PeDVbO!Dz2?WQwOg|5t{MKCAFB_WNQP4pxt}A1`fbba`qMSme1#vE zNyR{f38u%k92F4W~afpqXKEZU~Zh`^N50UW#+<3_&|&e$?O$^ zmr~*Bll`GsLL9kYlyb-^?=S+_azDR*mxMi1_AG7~j+4}Ji9EE-gkYv`d>HStwS&wN z2EG>J-F%}dQhU6QDi326(sVn5d#~~L6Yr#PGcGo1?-E^Br<3fiyU*D@Gif!0%OgFl z7BE-D>*95b&WM3VkNC7Bi zP2my>9=vi*ftExqV-qP=Pxa>-D0>sRN{M@_D-CWwceS}s6{&}O8JV|=jH3fe&V39u zQ^SX~N=}Aplkes17K^DTmW1p)mr{?x5Vg?rIYSq1#|{hnmPy7 zoJJkp8TUr{rR?45q~ppPoV0Y}kFTiu)t_%G&{^}{Qj(XB@v6Txh!+&<|5lEP!B;8A z$of=)oyhY)n!qm?aY^NHO6O>*U%-1gC&?C4XgHyyl5~_l=il4^M(8)v&LdlG-DVC4 znAG29bIl*Ne0=sM+{N$Mw)iXu7XTBe+2$)N?hj-U_nQouy~h@nZZ+AzrE#e_)}BLI zQ`1T|2|DjA@2`7;o7p?rs-nIq^^!WYEYdzDQvS9(;M>6I`0#L;T(qpwxnE*cba`7eCOpyh-6+19sU3Ej~)!(+eVyf&|2C{Ue`XC(L`-D6|< zVWfefM*z5$Ua>Ef{ViLp-mS}ne_v22$>6#gBDZ>3osBFGq|)GOB|@RQviIHeIvPN; zVQM4iMCPOdL)R(8zN^Wj0ix^!C*a6|!v7>jgQIlkRkq5MK^= z-aX`g&i$T^@+-A+v{hLvUvhl`UF_oNR?^J#+C6&S-&kS(D`JRmJ=b62QR*Uoa)`G^ zu8dE?D)PedS5`+hSDos;wx?QQfs9o(LVIb8!JNLS^w9MLDyX~01Yr~9!fh?r@x4x{ zm&tpE!`u8m-4orf8+EQBEbe2hW|yWHu8k zJd!9T(^_+`t>3Eu?E_BPJ$4Gs(OojXft}WjgHsLN2sf(uhhu*lj;lO+ikeIsWDa8` zW#_LL5lV2Vh1dUkjAD!OV2#PDvf#2D4U4;x(0S?)0-8V9ChjQfpzO{1JYULmC+}=$ zjYdS3da{<#4*P!OzsEjk5#a{`{Qy%%^wWgvw0k6NI;-|$e-S3cGiSB{5~HJu(XD+J zy$IK7BPQh7nuT#&6R;Q3^HV6NDMBNJ2k&d>K{y?9bujLGct*)d8SEa2>$dwdtd6&s zLT*lUv|3u^=!z3=-~BC`3qUjq9HoJLS6B^GST#>=O;uQ3p&!m44kcj+g zeYVc6T}P}(BBCmCdvS9HExylN9bBAQb}%nELa;<9SvH%xn~|Riay?3R%A%ETyQhC* zaJHB1Xp$Cax7CvIRW9{!U1Dlyu}AB;xT)Kz-$L!Udh7d;&c3k(v2B~}hpOBY5mpHS z!8NDyF(4C(HFRIbPw8J7Mzo~gwVXiu``Cd9G_e*q@J+!-RPb;zlb^pJ3S}KVw=;^p ziIhA2JH9#LgjH*X`9ma@P>NfGdjVXPzkGhta!8m_Av;#w1;|;eI4k+^UwzE{hZ;!m zwua~6KCKF%Ge$kBRvMn3YF2S^dA(;eZPL&toz=_3^>jWFwLxUYvIkX(M+w_hD~%J` z6?GH(4PTdU1h|4SyR~Y}wlc~1_HjIDXJ_w_A%1>C3Dr@28n|?SEM{f}e>GM?=ZEFm zraOD8+`-kEl6!DD-#oA)@>piMC_mIC{u7sY+*0nKeL8Oj-<9uSm+!&P*_R=wId^ld zIE>mhf->z#4eTQvBcz@=p{|{M zP8TsfGDEWhlSQ(sx?!}u{-?sth;#W?hw3>JF}UQH^i;@a#qOJ}#CB<#8xh~tb)UQU zewBZCS7SQ08%Y+BPXToryYX3|F-(?87sia?o3Ho_CE|6yl? z1=&NSJU@?1Vtgo6X}l_L?H!#a?=4FLj1DlbYpqNZ!ZLvx$=%Z|`XR@by{zB+~HzDqavG8Fo@p$=r~?gkik*Y78=;hlU9 zJrf3>{f?S}o))u`U|HU_G*ip>hyDDE`IxUiLw;Zmu@9_1;aJ^**ZbF8XTvmROxuOX z=$yj{6D6CC)Hm;kySj?;-U_;I?%$#u8?g+>dfi#%l6tvx%$GDSxz=mCsH1!3tEx4& z!6!?9l6O4cz|Z>`oOia_%7GxSM<<~iJrMQ%eRSaG0FuhATFvJdw6NA!8VmAyG&LeE z>|2_n2{ODJ4U64W9s}d*!$&}2&iY=PT<}z^d5g2=v>hTq7fVo`j$$* zTM%EhX#EYT)tu?$GxzFeKXB6>GvdN&;RoxJ^p?Z-f*dF)jxBQJ#Hv1Gf?+|_-ttIe zKGBeE_u-Wb$fv_zJ=#O8X!4h|MwGvIyE>#1zI?&92%eHmeuG*n3*LK4L#+d4aZ`R) z|KLhqwUh_dB_dg|!dqdxykTPvs-s7C&?MsFW?a@7&Da`d_b;HA9^PJWuvd8qpHqBY|{ zSP!y>8)W>6UF&ABu2^Bu+{^f)*9Kz!bb@cbpbaxECtM&sXl~9Casb#Nc^CyBXd>T- zAT5o&DP-4$r%}{O6d(fJ=>Pn)wgktJ`2)tK5ZHn%xf*l$v+-|1fcn-Qn4l zlVSgY6mR>P3j-=yr35o4_4}#dP#Ke{d_o4lZ$%OT_&oCiBqegt{ZoAsElC2;49aLS zuU@hT&Gld@W`uo?R_@)0KfyuQ-Uq6EzVD7d6L9qpT_n}fAi(!yTyBS?NS7g{pemn7 zb0>{raz%M9-P(2;lc3t&wun#jtDzN8?i1T-9c-$CI(e~kppGa{v9v1sAH_5@fQU;` zDT%rBzLI63-~Dx%hx){9EUTp#jHSB7a>#W|BRN#fhsjM%E^j-}c|bfm*!EBMqL1H+{>FUrLy=|{i+FRV494M3b&-9G zKOiY50WQ~xCa|cSm&tLHA}m(@^Ce0q56PdoJe^ zf`!r|d8JSkX_2Ic(WT|@4NYMU$}6P*`A936?CxZ5 zrYkEhgg9w^#!YyR_k;V8L`@MkA)d4~#hC<3y-uX})%u=_RgbyQ9e0y^RL(PCZ$+Sa z3^3%)EhrX_;w*xxzpF!T?KMaD!pFbnT_0?2CJC^u+!VyNN6EYB9|GUv4$EoKUc2$* zbbXQ*vR=MpQ9?$>L&5KR`W4ehAe?CMLUS~X;6x>dyc;D%92}fuwEBCP-S?SPefOlU zairbmbI`kF$Hi^Mdjyu1_#}X>WiKx9OBdzI*HKN-7=;GyH|%9PBjX0ne4LywMuZw3 zhdsZ|E7{@|QiJ`9n~TZrFkE5t%RN@&8K_#MV8_w=b*%nP#BzbqgTey*gZ}kNL#)1x za`ej8i3b}vr)>+eFOU0QQ`x!S*W5VYxw+qiO++!nvy6DMhoW&J#S-n=Th`x2|76c$ zYqjM?m`}5-CyJbWK>>5Y_FisUPhRq1r0nFQdOU10b;fInHBw-778xw9zW2wXy~3i+ zL0o9@f!bZGYYg@d1yt@H&<23!Bc2#GdOT&nPnz0)a*||vhck?!RUYs@aEala*6wSX zp)5LNEZnzwjYsRaZyVIvo>hV%rPeT|JU=F3Oy7zYr8K^M2k)-#R`=Ah&(1_#e0En2 z+eJ0_0;?iAH^;8tgAB}4qKjsUfr3v7fe-tq(m|F>b(Hzx7EwaJN2dPbrJX5r%;GW1 z70v7={g&DsCMQ_%1lmH%F9>lWep2}+Y70HTn@VxNL5V6w1Xl=U0?XCqj|zir~)r{=JnA=M0(mQ=1pW6)q|HWvH@%{bgc>p0vv& zYy2ff;{>{aw)dc!232RJo{^!f=M^%fZ|Cm2OP4TEr+0NJi)d5()2_;u=NxjsZ$*#uhsG zz|XE*F(V-$xctig>!I#6!;K4In z$q_$-4eMcE*W)?{P^zua{7@Mptb+OWQ_H0&tbR_=MAEq-e&M884-^2rKJ4>lt2t9r zR%xjz5antYP21IG1e*;Dgio;qEGw!Dx+T@Mk^jMg_rQVuGl5z4;xo*b?EdUJQ!hVw zw5SIQ_9>nQ2qyRo252O~-H2^L>NQC6q&uwFZd!ac8luQNR)D>X9=pIe8`uZ`^3}wL z@(U@h*VwYM$_&nf5>F}#!O(nND2rzEGiP-*$$Y=}4I64RX#0zlb^4u2-%I}rk&hHx zi)D+6ykE8PORgTNm9WcZ+CMr7e4TIIf^g_Al`ZlhzM1^7*s%R^!>)X1{eJH#6iJQJ zG_B(sT>XWe0SbuJm0iTs`}Y@}wLvycV~<#?q3?RsN{*u*vBPInnwPIO-8hx1*D`1q zAS2%ouj6Pj|8+T!*ovzwyUHj_0kZIbcv3$U#JH8;4k^*skM7bdN0ey0`HYS_q@~#j zJFeU=riFzC!an?|?*z`Cj=ZiDEm_irQoJEQc+$NqiZahC9C0O?-A0OL&gSp3+I+CD z+iQAGuW$RXbQ6;F`(!2i7S*MABw0^{tU(RdPAmZ?Kd(iz-S_C+A>hk^cx7PBypE^xi`O`S9IFQwtG(wu zY{o1#{(}vp-PJAC3Z8n>8As}ZFOJ!-)?ksGBWY^bgl#P{SoxUqjxFUVIFk~(G;(G2 z*95uELMNnI(UMi22PWDPI-0twMem01a0cyiyD)C|T_|%pW5IhYW?We`{!X;LZCOrz zUh76>vyR*&&~iOJ*Vb-O9vqi3>0}jLH^mrrPgowjoE1X8ekZ74fob~pOvp&8;2e0n z8~WY)=gyOcb#r_weO+Lt0I41THYh%7h`^hCCRKdzbpiBA3S z$B(*AQSh{R(b+|`KDn==R{gjj!2Mfcuczn+&a;z0ntrE$GJOR5uloAeDuji%e~&5Z zMqF!k{D^cU1A0y8M*+dXKv{LVi&xqRpO$m7WR2iVc2iw>io#8Uie*2@9NLCB3iToM z-N3lzlWgO^HB?>q!~H#cCmowYUY%Sy8U=6+>t`TQi#dFV_=srfUhCPkIZQ8g8wciG-08C7c&|Sd?7$NpgFO(6E=a7BJQ{YH-9S$ zlkRv#8E5{XjNojxhI@+W;GEqP6%oZ2JFVu;W127(sth_#mdFSgk;#$4`Gb2diOede ztOrK`>GycfJ5iZlKcGCJgO`E>y65$XWyA!cdVU+e%2LIlawYv}gn`q$ZA^|4nfYJ8 z!WZ`ai2meWr%qSrKK|8eI?Q^MS|OEO%o7xSYaGlfb;+z^__#uE8oDKiOEal5#JQL0p4Ji zzZ`6p7CXNd%kx@tSPOuNSe}_S;jM6RZ${0B#wMbJ&6wtsx@O$JzD#NWF*e?iS>qro z$LRj}wPJs(56&5&wnuOhhP72$$n5ECtANW<@unv71Cz(K(^yMpf}4mC#8+qaG41Tw ze6S_cY4x$T^?uLengd#`5>i}=&b0~*p{FZgai^zp#4l8bp3=y&IVeyA#B$D}aL%Z4 z0Q_6ELn6;gC3<>r4H&(NaCliy^{;`KC}UT<%`+yM2n-@H1=(tqCw6p;+Mfv{ z%rdie?m8N-+L^~a>Q5n%Uht$)&i?WZFVf;;>v7=RbjjN0I zvG%H67AzIB7njgc(n3*st&WC~qY7c9;LGM0&>tgi&h0NVl}qA73cs+@9vJs@&!5w+q!c4QXHEKvo`u&`6_h&`k7odxo^YEIweED!e z=S7lWKT*on5%k!^_c!0S(#Ebcux=e%j(gW!DV#S($uUn2T5F$T&I~^l0K=5MU!zPy zI8Hu{kGlbFvuApV$7_@F+D*9H@qLRmk7$X;rpK74mC)Nl0?wO}3&Q)6v#L$LrIb}w zVeZmT>){zPkca(c)id$g>s~b9mO!4@o@zZ`bbLVXMJJgm`KZGCexg>>Su-Nhq$t8r z9TPHr5w;5aD9$w%c|NB`_ zZ@wfuRzJ$O1mauT=36RAE6c7pb#rY5<0?Gh;y?&ZJCjaWG&%6nl&hfMCI<@*g*RDVvyx7uMpNBn8; zvKg2nV6*6=I`=+JM8cK;r{Rl-Gb&LJ9J=LoQt;}}o)})Rf6p;HJrfSt_#3Z1jS$Z> zj<}25)EJa3`YJ17(D;FlmzwyM6bfsW#vNyxARec|Cs=aHBZs@iFOq)yW+E(#1m}gekd>j=(f#hn68b5KL_#P_LqrExw!wUd%nulKd4R!n) zgDeTix086d>v7pvG8i2wZt7Tt1SAHgkMqng@a87T+&Fe+a27ts@6wyx)3dxqwYyf< zFl~Vuk~(TNsGwuG^q|)$uvIY*_f~EJ`~XXfj@KDE{@GH$f`u=Gp5WYBKff2YXMbZ* zL(G8f9-U01Kk=5P+^zs-e)$mEMNUVE{CZ^Y6h;95U28VvVf`IkbX5^FWf^;4`@E%U9g3 z59)CdqX!%=Y;{);w~C_5>s3g>_$Bxl|BpFzzl4I#5}#R=r>+~9u3)Z3F$X!d;BT)$ z*7d2yCVdc!`WcQpNywL$FwoSvE)qN$sK%v=cH&-bN8o46XZ(xYO9 zy(&eNN!hf|ke{K!Cu`Pc zl%_K}Y1M1!Y_?ACG;EszFF+iWh-OCa8*2ctqSNewpR zd2T2<*Ba0r^bNxqY!}}J2mCjueFi6e+;>ymw89NnS6=K?)rl#H#&KU6b%*tT)DvQf zNjcN+_9{Vz{KytJ8K9m7GNxWTHVm|5XzdjQy!MNb!kc@|v6mIl{mt77e+i~6plVbk z!0SFTGo15oW5X?`B3&Ge&*y1j)?W7Yt##4^7m#bkmjJqi|8V{ypFe z{av87((BAN_cE0L$LkwA($`s|ZWXL?QhDH)&_4)(#bK zdg)?$5v+J*j2As?`Cv(vEcb`#;1hdZc80s8qxDlEHiyQj9P*a*hs{$7@P@syJ0ZyH znPm@-=p)Vw!~e0;K|tsd(WH*gswkLzstqHTi`K%+8mT=0@TlUm3SAVf$-_!Hr!Of* zuF6N?s}s) z-Q;TB34^S!wQ~S28^51%XM6{vG>3-oYDPPVYcpWVpelNdDOg{7))LV{N{WU)aw4Ej zCt(mRmY_fpR`d*uw$cFRYQGKhFNpnnI!f1aTHB-7BTY2M*q${-DL0IC#^eZ%(xJt5 z0)rDbl|?BzZ>yP$X}ncL4RS1x6dB?gU?INM)3GI9IpSs#x6MbAi+2WS>9PJBF(S1Z zzrX$zO%Y@cDR^s)KpyuwnwOalc>=VRU^E5UuO%mA_*?eQ`e{G6PJ!W)b7; zGV%-{t~kxB&vbOQKg(UnkhMN~HOQ?5-@zazd}y1l$|qs4v6n0J{io-#sLYq{MJUdZ z?AO(V{8%EW`PH`*Z=5f9w~#!ehCCzp=0>c|v7HDd;#Tt5n7sS2<20pkuLN`hQM>r{Mh}e=yfmTP0pOy8$L9lA~k@-Vt}FuQ%MtT|t;JT*89Zt_j<9x*^$aG%nf z(1!zGz0 zgdThYQoqMyE!uu_Y?`gI;zj)>(&Wd4+@pHmV&I#S_UD1vkP&))sYUztHiC$5L$uN*My>yZ^1^)u~ct7 zUXieq8iNqz^K9s3IW{Q%s&#+~qM|V2Ko|~DpX4x5o5#DLmW?dSVg1d0E6EKHUz1L= zh&!eP!H)+$*gQZK8VW39q-|;T6G;;q{(J$;2P>lHR)O z9iMV(iLq~rV8QcQYpKBgR)AL z6BES7NIQA(%~S|TaLtT?>z`uFYcx1$dr7x)puB+`vSi0=B!o==%BDhkp^P*Ty^cuH zwqrful1`b&83?I#VvT1=HQC8#lpN2(>qDL21;WTpb?cJm7xD%mgWUK?u#IxK6M1tz z%p8mP4D20fn73anqJkrT_gr);gqN0h4}1+pJm*!wq4Iu1FE0pKr^$Ij>mc|qXJcjf zXfk>fLSytJx_#+$@%ttoV}*@`y2)AuSSurQ*oV>OLFfo4Ub8c81OLN?4SyW2M>dBn z8C>sRYCW%9Xl^;7jdfEZTV(Tf_&XDLIxHkv3&rth(gcbXA&F+MAm@g+^z^MvfSA`p zOcF!?)v=}CptbDg_I)sUFC{ZjZ!nu@nhbD?v$Y64V$AWw0vHZ?2i1O`8y2Il5&=;q(<3c*C>qq_B4K zxucr}WB9uCu93M`O_LonkX|#9Uf&<(guQy#?#(!gTbp+1FYSPd{&vT)FQ`prTxaDA! z*}dcc%dL_Dby-HnYILdL_UkxzG}f2E9n>$fC7Xm-N4)(oGCCT@M5 zZ_K1muKDwI`aE+mZR$)E$4qD7Ow@Y00!L*K?#E6?tWpB3{wq?mB%wu6oa0BQB&+5n zx)KV~@v+d7ZAp5lV`|C4<`3*cmtzMrYIkX?e>m)h@@mr7u`sHAcSb& zxLv)(_%2;X@H68<|MKN;7a%=YZXGUSa`riuN9Yo3U^Y&hu(`qF-skV0dHdS=mq<-7 zezKM=4nU;xWIU%5bM)A7-Tg~xR^dLH)W2oquuqSy(p-zjvDv{G#P6t_r8s6GC_K%e zn4_|D;W7}eM5`QaGzm~fB=@X)(ARPPk5)0b*kNo3!yw+*h7MgKPOMLA4V@B0az42WHv7TU9~d)IPa0b2w7brY)UW)iuW<@bX(u8 zbX2$4O?moWHD_HjlJc}4;X;7&_XrPW;<>zs$kQ7svYCW;KFicQGbtVgtyymGuMpcr z1k6%8=kB}I@m)0alw^M|+xt9#?H{)qp^kcf1m(1VIjcs}ToXK){x)UrLtyut4RjVA zJY2f!vf~@T<|x*Y)M?=87U~WIWwInx3GF+2VfzS50#Vuyrz#V6ptt5@bDJ9nEC-6y zeUei8Zk1Sq*xvdsD~~V+&cJMi8gQ;UM^c8)Jf}aWj~2a$t?Tymvp2?EcufuK?IX1@ zji;~Jh(od7)sN#>>SJ^F19s96xw1aPb_oQ(G|5=e)xAp(6yslYX<^{SWPdG)v)jDEOhIcC-Cn zu15}09dgIDYIlRz8a+-5bVx7=p|1U=@U{7HX|d&Q9H9+Y39Ozx)l3~`$0MYml0sa0 z-i#%p=xCUdZD8AT`=~9H1J;5nHdt=FbIlFsh?Sp7MCj2rs!vVuc%f7Mes?!YL{EF0 zA~p{{yK8q7BY-d_fh)pqP>3~qM|4DT5Z$<)(YVisM?67{zV1MKeX6=E*gR0;BQ^3F z!)=@VkqS=e8Z7qw@WsNrw0CltNQD)zVo4^|K!J1qvW#~wk?S*>irBG_k4LU>{j-mg zcKsoKv$mA|ndz3*-$tx@dx4?k{i&F3*n@DPe&W2qD2FJ?>aG^}O_pAb;zehAnJWXR zO8X_-p6nPOsXm>&sjA+0;|LU zjv}8S%wuZlfo2f(o$D~BN*uk!Fea&LBpWitR~rjJeA4TG62T6WG0A%`MA;*~%7BG& zGgw*NoEav165VMw-GESS5RR}AV8Iv!3wQjlaN6lTp-<=`76pNUCANVjJZlwfXciI} zCa~s8rieTGFkQy=Lf%NDr-6@Jj~7Yi>Y)QY_2_L(N1(VNN~B$k9X-@OLoC@@;-(MK#8Tp ztY+GYz~(K;S-HkD|C+c$DW z9#A!-9&W?cqql5sGGyh!KOCAo!zf?TtGpkD7jUf2JE5S{v1OT$&)t$Z+V)?u`+HmF z(b%%RK3hx4xpVjPBk=BKrtD_MPK2OEq>Q-F`1ba(WgXJ-6-5d?uc!lG>ZeY`0PNrq zL`Nk5rx?qhI@`%W1T<6I!chNKtC6oCB*Ci$PA9Wx&wX0C$qOA)s=hRKaVqC|GxYJ{ zr>F4D_QH<{hm8CV34*>*PVy4#4*o?rzaBy?JbDAqx$7c>=4o#|vz3TmI#zS_kb`+X zGi&v>Wm0Z~Sx&m`N5eCvJa|f4a79b^cr<~c3~cA71F*kx4qa@3QO&8#b81J4t$r2b zHoP!|J(6~@u&bl?aGjOXK23J^i&pTwBoV5$B{VkOdbyUV6wa>XtZNV^2X(e`NU7sp z)*-fKMytUK)(z_}>$RBOfQ6guct>@1SAiShS!{3g35X?LBO8Gd5>dZ}mcXP?jy_iK zQV&K1#j8EThiBrks4aam?9wd|iahv$deOClVTd_SGHFjPfs}U@L>Di_UMk; z7o!ud>(S%GWgdfFq{-F?Cz#N+d9C8?&1Re%v{ok|@NWx_?Um*p<$jftDXCsTMMUh1 zykNl0{O-rZLi*iMmmx>5op=usQ7s-%@5LcOFTdH+7eB&~n1_+W+sMt}Cydobx~pGN z!Mp|j&7VHJ^?6`v`$8&PUx;z@sx2Z*(-|Wph1y+!qpwAxW~ z*(>9jkWo51CAE103;V+Dob=vIb-gg7PBoon5&FNCJS(ToFthD=90}TK%O>g$ew$EWGT!<4}{{ zzbz28-bICsB@mT&@{tZa+B@n>`V44>7rJ%1nS^+r%xZXa3wd;hQ_Id%%dS8r9ojWK zR#T~UXCNEj8j#)W!)RO$bG)y3YQ>xLfSEh=LyLFU9N}S~@dZCw2K$R9KYqf43QgdP zTeD$)QN=Mmybpc<;TxT9Eli@kZFn9R`Sr+2cXZlSJ?@9eu>zKI5n3{n>r8l6FVKG> ztdUkN!!Eq4=p2f=5cs6;&7CkeCZ-<^s6!uJT@xZ!Yf^DpCPN}Nk-dv8Y+X2y z8~JQYt9;QMmSUpa;thOeq=83#~& z4m&yE+2T>UXkh%dk7(dU{KKmDnHK@2eTHmnG(lg??J)6ltcPTjmH{7Z%A1`etTMei zgVoP%V9zy#__gw}i_nn<|IFh`3w}5GRdLj?c`!T*HdFI*Ng#iT$l=YwR7TYJ`XB3E z!7&S#yHasj-%-|ykegN4J{}20=v(<}`8ApS6+af*%M8=?HFUhAv}(gEnCveF$e_bx z!yttfL0(!ulRL~F6X4ZxBuZbNyS6w@*4^vdF&{>cWzS$HK|8gGEf!;UBxA*C+RnP- zWM$q}UTOJ?Qf?W;92szq80mUEU>!i=8L$bzPmR^{pND8v@K{%mNv~*?apOWMjkUiw z)IHF5#>40H&$}ROohez;+T)`)cHAY&T48{yeKT?<*pVrGkCt(h8LubmBNskzqJ_s# z#zpsTKH5nTTw04B1%4mc5Fad;HjRuEn=GLJc{< z^&M<#lPygf_%lcl+>jcB#1L93F3QgS^F37_Y9Cs$BQg{46?U%z4*Y^_8&DwmT^8Lh zgiW`2)&I3aLp)Ag9uFM&<*Haab|bm(w<1P5Z-`6prUc0b4}n!V3If`;BTQ@z;R3M# z4*X0f{lH?P@SGKAYb?cCx#1K+&0;iDyaBQ#OIT*YDL&Zd&V?Rf)b{J-3 z9qHH+kEFg|&tiERTfP#qQMx%1TEB^FO7}ivzur*3Q!x>h-kc_3;j=rRIKEmo<=HaeB#R%SX->4yt zP$trg9Eq~kF(`rQhNlAftbTM}nkI16P``cQ%uTr@@xN@uZREFzEzgbP1@FG)T6X{X zQQ+%P^x_thSim0gNe|#Ha%Sz09_d5*Qn89 zLRlY8tLc6t=MNwGqECmlWKy&yy0cN+&?vCQaew_e?fGWibT_X;ldTfY-4Ry#dePPC z07`>8b|#_%N=1A2w}n2wGym-X(&$%3GCC^)oI$Bl25l*_;j`KEZ$|vPD=Z8+KPsAP zxbUys6@OS4Ubi_n^vX$GQh}v0cZnOmEwo4qNeLe1yg_lW!)s_}u8yjWsA67Qo2K&E z<3W-Nt7vB(XRxd_)Qb3v@Z(|?K;EK{7GAxX{65G;(Ri>D%=->z7v@8XtyZlZ3`$>?{m_~ zgkn*}-64lW4Dcep#`2EcoA`4Af`QQ71q(VD0=s{c?Nm7u^*}@~a-Ezs$h4#BPXukm z0a|ODH{{Q{<^xcfn5kQ{;PQuxm&&TM^M|yT%DQc#H`6&6#YpnHVl;D(aVRl{ZzJcV zUL4RYEDs57CMLR%UXNyQZxp3gvfA&cY5X(aZomyrTp9OA(q55PUxKUgL=zu4JsKqzUR zG4oM=7{jGmxtau;iMofTfB^YxtX<~^g!zr=_BK{e6`AfC~ zCZ7qPgcEf8T>LXe(RgQ>DWhBcebaw*Cx44A9adMr zdKjVw-U(S7soR=ok{g+mp}T#YinYb3vNvU@WnB`_y#$B1=^bP9Qxr^a>vqpc82=|Y zehu>a!Gv#MgulSD`6am|5&Z5Va6mP!1zk;jp8QJW1zhxla_HQyE3?AE~z8 z+Qe`;3+D9T4jdl)L>cW46N=Gak|O_g{8LfyKvLJ^D<&D4O8(@X`bfS<)P>UIDJAv# z_z73a^&b*X(V?7=LA=lk4?$=+5%9fzX2}hlE>HZJ&HAi`EuHY& zep_^=yYOD8F1M?f?Yuac_+}J|1t!mZ?nHf6`#kCP=;<+BV?qHFbz zWK`yr7ndrFICPGjwsUbNMn#OgBb-spQFwjn$Yj|gpH zVe6=Hvp^bDtjh=_|?`P;ja67?rV z&w;Uz)muEN$;`dr`vi?ZcSqqWW(c%^n-_^5Yo*C*J#uP-s=DNyu&-DL&ugluocsW zV&B7s@)mK%$pnWHidSNaS1RMTByq;MioB^q${I-ZpI%f{-AV8x->FI=C@8jDV*Ed| z&Z2=+g+s;Bm1|`_fUQ;%!Z-apyq7czk#jw5kPF1hKvuzT+^W~5ciniRzQamsGWl%n zH>uBt;|akF3wQVcnf}q?J$Vcz>oasC-f+YO3|KbFbQPz31cW`IK*V8#{{GZ}?{D6YohMG#FoA;) z@;2O_tIWwc?H{WZX9N|gg1b%&Q4J^;W;R`wM;JZQEILZas5#x*N&-_Nn!9ajM&1iK zx0dApu7_Ra^V;wVx5M$9(}&*U-XLx^z5D~13!Na$a24dY*W!va(Y5lWEZl>XWG)$s zB*=e~8-sS_fF19<@(>`M z&mLleTnfYzs%~<+MI(>{&zf|Gwwr@T#!(-_v&WebQK4GIqXN;Bphas^@u-rxP~RdS zj-z|NKRoiJr!PNVAss<5{O$^yS1o-)KwLeV?Sf0!@$_^)KNPg#bqe+IkK@a}pNF|# z9TI4i4g6}&*VANt+z$I*V!2kmHTRw5(HzSXcgFYYM)PV9S)nC9B^hC_kB{{TjSR-` z=4#bV+dYiy>|1s{9CBfcu@d4MviAAtrpAm_49>Fl*XgIE!?a)jb^V(Y@Z&GLJDZp! z^3inoJGM~s@13&kE;yWw(|0ei37IMuq!{F5q0k&B96i9bp_&ZQu~4E-abw0NIsg7V zJrVWX(E~@;o}*m^v%8WQN{Zf~WxS86Q7LF%oiO)3nz#)(`@V=&vgcY69s09&N$>yS zTIPRHYDDPbmz|ez#!~Cn{12_sg+;(#UbXFXQ}iMLOOP#>QzDOhfk?mZ^r_6RAAglA zp54ObgqT=)zY)l6Qw=hX=iO)&6$Byejr&BDiAiwhM|LSl#|TbD^f)35=yeA&E)woN z+36ozsu{$|H%<4ldiP>B2lzPY6D@J(ENu_j#>@YK@{6_+g zJk6oXs_14mNIR0sYY10dx*aStZkD8xt5nE5^V7s_ta-XsNp}0~NzQrnoJQ0x=&)}I znn?hPG16QGXfsUb0Dz-Bm;$!~Gl2lSIgHpXO38H5Tj@dRRjv_^7%%xC)xO5&5O$uK z(0ylg%P-Vj8RK7UU6FI|Z|(xb^lv26KK^L7?>#>K6^BWzNf`|YP|c4An#`iM3jp@n5I zQf>H7b~x)q@q=bl6&0P7m}-*2oO!W|D54glhv3S-@#6o%x%77+x6pm6Iz?-Wgo#~3 zAqA;JRuqIA-8;7l{vRVB>ddn_#`w|PmC>ttnGjBC-<$|7$t2A33gv13pP~z+sw$ky zu&GmlxL}#6%9;z4OB~jl@>N$S{msy5b}RW^TV}N*XL74da`4rLclTM@@kG<zQ-oNp+p6c#jU4tdYeT!_-+=?dBJbqS|Qt7W9WBW>LY7B!SMNCkM8scezI3nDc*}@EoML zMwPZH;hga7>6(Tvm7?lthLyEEb*pDG8TMq+=uN^{;V=*t%p~2^(kweLg(8w-BA>$! z4Z~r+Loojr7D7n?ZZCxULv9)}Y}0uL_3J>I-!!FIf9B3*P>{0q)N^iX2PX#nZB6Y| z)G4rGBsVSEdI@hoZ>16Xk;r68ft=@JQFfQJ2J^95!gS3BSpgIq`tUJfvhC#aJ~UnxSIdhQT^N zoSQ?lZ6|`s%Z{=mK!w+6@T>sSA^%hvpui~=g9rnX%du#Jy6kO&;Svree%662b; z`Vy|;K5KqYwEhP~VZQ*++us`Qb!!NNf`av)a=B9Thbr(c4ErH?aRqpi}T|3(96T^blC zz<^oP&$1(3rj4+J_0ui0f0D{{64lSEKduJm%ATA7&@egtfeT6lR`(W7%%q?G1g@VR zGjo$$7M!X8g$e~Jtcbr5x&)I}_=Y5+-s=i*16rKuC8 zVu=<;C;_egvp+eZ00MFK0!V}4x{W-`7F@xpL0kFySh|XxF`Om}mjaZ(3h7qg8PhPPebGyfMZ3v6{ z0I1MQz+Ij3qMjpge5}hcC7Ds9{#BH2MZmDdi8{lDIiaYU+`50+7qGixG5JA6BD|MS z*&z2lhNygyrY7kmNE#KfDKaGk^M4D7j%4RPJ3s@iE7#SlH#c!dBjFBB7Zp^_Qy^bK z_+`}q8+vlUk<*& zFLYs7;o^cNJd??}LMx-_+TQ(- zua z=*Fi2*DmQ5gqI<+MW6|m4ZwZ>mR|Rr}}p8 zALL9ZQi|wgmq+;qxm010F6I+uZ?t@S>(;nFy2!yCldZ|szbSZfK|hxW1F=?fJchfk zkLY?=ue6>Yw&2pwLxXf+6Y4uA|O1(?#7p$b!j+G)M zzm?t(#XLF1Ur6EH{*NV*V9}20k_03#pEzJHfr)gOcJ%9+xbgI zy7*c2?(`A2?bP~BiE7<^GOql&kTF%szKrPG{vP{oLe73C+HW$r9Lb&!=b!^fNFISOiyu&87^_ zj6+`5v0`4%xd}|95M>b@`Zq$)>w;qknl@5zQ*6nnqcO(+^OL2?5#7ggmWF(T+C||( zy=Pg#Ucs<~mT2xWL$so=GGlzh>6hMoN531^AW_CXE1vn5-Y`4oE#73)5X6+*oaBZY z>sIfpJRMW#J6g9YPrP<2y&UtV9#WF&Q!iJ%C)ed~7bJNgQFPRGS3F))M2q^r2v4yK z(YK8ODnvjM$V9!xAC;!(ij?RNkpe?Xo+Eu9yc?}bF2;E zuS`CGWCj;1cra`!sd3t}NU98-QQGB3_m=P}@o)YKo+}1K{7_<(8%mi{Ps3gTfAhNQ&Mn>zx58BWY%1qhlQ7j76DKx@EDR% zQIxQB#^qpP2NAK#=EcF3>Uz&qYV{}BfAj*}UcFu@+h`-Ys+wBvsCQmY@8nT-+Al;8DIT(Ar@yp(_;QGf7)3A(B3FNL2`!iErz8>*B_K$&=HY z55JQTN&CO-W<0X!f7Iwyca#zjz;WvNhPP7O+Z#EA zsb|!kXA$J3_n*Jt?jclJF{aF8m|ue0JRW^6L0&-6X zcXYkuIqIA@X&ckQIJY!z0L|>GZod?1=*mnIF+hlP$I#4DAnEL7A%SpXc_|4>@2IFWBUNY2HjNeqd731%ga7P8hM< z#7liFqpOy$GPD*waB|d%m#?A?t{KmB{jFwsj3o!)V;?D^(SIT+Z4p=ogtCPO#Q0&c zj)#Z{euP7X3Xz|A#~o@Ait&a5$M|ON81}7$6f1tHSBB3(<~iJ(^9Wj`vYL1X&hiav zfE)dw2Je53Zt(MfNZAl}*#I_Jh!7h8aj%O%KrZCMn|0UOe z4YWy6VLwHLK!)OO{$!9U$oaK>emtJp%GxdqxJ%S%w5QKb@1bjHqeUsJk&rfx{Uz2^ z^Erb~$@MpTQXFkKnev5Lc#TB34+~-4JLe~p*rdymSvD}`$yQxWy>W|KXhr44#8tm} zlZa_~(4|iN)fVq@zb4}ObpG^b(42}1OuzY^-5m{gZ3UV2D}+N{Wp3Z2vchBXb+_NL zT3o~Hhs@yDc7cLx{?~B**YrD8{H8nGfzndq(PualZRSUd-FR|0JDE=LWW8KzKe1%n znF258LrmQV($;HK-3QiI=WvGgJn2;9_(b}QTAHU0veGLg58=H=qBCyRW41Gn*h6`f zinh{er?5Mo1a7->MAmULnSI_pkwOlshD^WS>=SyK&2D9mo%u!RDndv`f9(CZKCP3bHeT6iy!wk`lz>S;vd`xWp~wz$x2B&taBu`p)AGO zEHXyHFa~ekHZ9?jK~-7>H-?@+54tN-7^M$(2LBOzWq6vkJY&Zpnq_ zL`!VUz}s2bL3-T*PK3GdzY*oXY!5X9ha@+`en1vS4Cohfej{+L>+j68v4k1vee&jL^$1x}$ACPb&29(OsO3oenfA7{C`Eti9^2JTlcCQF0gYhFG;Nn9AtlD0p$^;=u5{QU z^PqheS+Rz9tZr&)=hZZ3!U)U^dOisn^Tiv93_+_E=9tWCGh-@2v_Oh0)P2vpYf(O! z2DNV{326ED#kfrL8!V_iayDDT@RFHCAjvFrZY_-*mEqOm4>69{(1eDgUtc6SsQL4S{c_ z21{&0wMDKBZ!DC9>#2{|Bwt%r=+(%EFU@uat2F?Hu`jg4pufVX{}Dc2|3Y36)Q-*GfGVAMA(a*KIo$f5A9C%*B>ZCgV1gU(~xL-4`vXFDkp! zHnMw_Z$2re9kp&>&{EDqKPN#;>QUC=)H1?3F`Q9eYZ^YR*$hWbIz*)A|Hy80WkXzf zf#(iI^TRoYx?f|9eBg0}4HM|DUwP5`PYz|U-z_(n=VI-rIABEUQZz zw`Gks*O*8-#w3m6EiVDsgLmjlxRe@E5AY9SU>zV!qQ1}mwDFG86z9zJhn+fX00Sp~BA zaXP7ZNcGDYPJaDnBPiB9An1b@>*~Tts-TQxs8dLMcA!@n2=%Fuvk_S$*_x8!KhecO zar%J*QDu$t>={WXc;Cs-M-8oj7?r}Pj-PajORqZS?7P;M4qqkz&g@8YzlQTr0nY>7 zxb2SfGC^B4wc)qEo_a5YVMzWhepP%++TABgSz^K(ka91C+?)oCzgIKpDp%$2EOF54 zsCe!yv%IS;G;B)?KDWXJUo2G?ZvDGx{BPvn#Y$xhhv6&hgPonxll8Safs-uZ0a5O& z-v0IPtSQw{rCE$26uYk zqtTr$b|+8pdGOXFWZ!MT)+1V;*6jmq{b{C#{g7#Hfcb;f6u zF7A#%9(xn2;k5N;aU{Ime&l_^Hizg04QKl^2adDYf3pD{C;={BSs+g>3u(zW&- zcPbvWgGh!JAGo40C7u75^ZU7m-N#b>AOAiNe|8(a#)3mrqiVz-N@Ew;f*yG2pcZisk`nq%=@T_LHP9+F;;+11Y6;|M)uQcX zJAwU`5}_a`H%y%f zC{SmKa*$DKU!EXXrBfcJux=5S?N;)6I3Hm2KH+zlnTS$)DFsiKRti7tsE2_); z@p7foYs%Tk53T5qK?a(TO7HMk=J*lph6T+v0UVuhjPv?tlLdPKmby7xmCE5%Nvl{&jQOc$Ev z8?bvGcIa>ASv$3|Lj``DqzwFOa20knLI*#o_fy&&#?zg~YZ6A-L>$Kx@Vnx~&IXy? z_EQdjZY`EK`f|Ij!nry{@PwI_6;EdE=Pmr$JvRIhFb+zqBZQ zh+I7I0_2qq%-|Y&&3kh*w2dfkv7~1^2}E33yZ^8zStY531*8KcjBa`}9Ejo$s%*zK z-S%ua_H6u^%$Katm%`+e54fqc+38@cTxe9Sm;TsiDr9mxwZ zOdCR<>Iw>k7Bt6g^46Dgo%uIQNnC>>_-F; z{MizYxzskU`r|Y@q{0596}Y5M>aX?aCPuZ@i$_YBc#87y)q6VrY%@L+gmRE4Lqv^D zPV!it#)PA}5Gc4b*!C&8h5~`ys+TQ@lO}nhZ^Z=e;Y&4&1J1wi;qbb#H>=tQ5Jf4X z8XF+ey61t_bsydhTT?_qw1qs}$Q}9WW8C}oJfAv?O~RSZL<>gW5m0CT55m&{MuL>J z3*~C%9%<{`+>CPt#Tk(5k~tX&1*z1hc>O`)F%P*Rng7?ziSX${$VvxtgEo6Z&Xj+luEW=q3x4Bc~YLlTaz;l z;{|>)ueHdAQ0!6evr!BsCEI}YwblKNGOzr!*1A4bk>~#FL`@V$pb3d{KXzSedHmYL z_BO?8=)`;7x<&A2%`Ax(X}S)C|jR% zls7RKwGLJBPGO)U6YGJwFZ!##28YqQMI2%p@2wCh3IZw4(suQrF>6?^Ttwmu?d&HJ z#_belc0#VYo7~bCLvJukUVSE`NuqM2PtX1wD(F=ZLq96Nl$xNp=%UZ2Y4$&usajom zZ5sE6=0~ElhHfK%xb9s7Xbe-+N zl^9z;hHg}r$oLU0H8?zUPDlUE;0+TF`vW;O<>#Ii#Pw;!?IkV#hnaX>%=g{;h*#np zak*7#IcYOxfMrugQsF1JG0R(Vxwhntr13&9S_4mctd4%DJhqcOj~=SdRgzpc##mmr zNHKf^I_NL&stSPqJ=PTs`q#6+1!MF=QiTv+lu$>gQ$C8qeh}0P|EICEr@^#Wv(g+w zuZ81`xiMRane5Zj?Hjy$;*9~Jh_Gc-z4RYyI7MwJg)_RTJtXNOc_Ru0s?(IbW(*MEFYYqqTqAh7ban(;mJn9GQ6_?{H!#YrjFBK~5Dt zSJ~icR$#8jgeyC7$jlC<*;-?J-jsQ}0*6T^OLhB#&aqValLb93(2^EdLKV6A<$VuZ z+J=+UN371w`?T9+wf0SU&sDow1JS+}^{gWuW~RlWa>4>q6)@y&WH_1*T|6S$)w%@F zp4>^(f~;6tci? zKcb{6?j45(?hoA>CDf9Of953V)$a$7s)E&Ht=8Slg&URR*1AvhS#@^n$JDnb{-)=d{l;YQX?edvE)=Zzo3ZLnRvWIU7 ztJ-{oUS;CT+I(4FWg({(gq=;EOB+YPC2hV@@M%q({_pJN@bqssdNmMO-PIxYT0UEx zwQumWa-@F+c$!U`JzUkNMhl4Z+ql)p;naY7C1_BIAJBP806WoBVdB`C?u+;s(KbKX zOgzzf<52w`zcWBJa%aZ*Lel^^>N4apCoNv1b(7wGv{1q!I!e> z0V0?;A%tKR%(7-&b69JyrnxOpBs6_~6z_zPL;STa1i=v6kvc&YrI&y96&-&*fn=MC zoZ>nkMXR&wp~+p5=C9thO5&Z;&9;8_BAf4mlSJWLm#}gnGwm|F(yzO(T0W}sC+ zmOZDT&qOw@R8cEG8BF+2?7fZOZ@KN9BP*t`OHwJ)byks8)0g3epVMl3>%$Hd+e(lO z=%=z9nVH>nR*4|>Ue{ES#T>jKB@&X~cG1v0UpK6S&2i=@D1aa02F2iBex39j*~ge` z_|lg)H@=HK)oRLfL~shMuC^a22ii?3_T;7e;8ze??I-(GmF?a|j6Ao#1Gb=MJTY^s zf2deyB0s{x#+fOopTxR zZBHfltGx0_f{suriRh)2tq!p|k|HuL9HDSo7DG%7`}7PuCE zxqQIP{f=qJk_302J^5*T1dyZ?yg9Vnur_Ahl05IoShcICH`Y;}s4AX^ z|2V8S@v^v$<(p3?L3P9JDc@d4&nQtF`D?#p|BsL@b;3tcDlRx*(~zdG2TV^=%Aw%C zEOxQEyx;1s?#KUR1^keAf_x$Wl%fI+%CU7&Jp06~T@u|li48jt?T{5;&34|V%qZvh zX{~SFediI!W1<9SH{0XH1^45`fA1>OttjR&QVC1E#DNH{D7e1b@I&-h8%qTAu@Rw+ zF$r=)`ZS@45urGZ@(@cK`wvPK@NWuW!ZJkN5Z-APAIM5Ekrn-s^ghR6_U4xA%~CbWnm6KYY9on&=HBL>jI32*z}%q* zwGJiuYZY>SaI9d~121SJZ{RJSMn}Jqz|6X?2D8Xo-=|*p&w+}cAk>|M?hRoKIfXb8 zi1CpF?a>3fF?9ba&h!Io#sgX&PY}5P7Ep~hy@2%Dzh+W^d7+3DB^NpCb1rPU6B2wZ zm*Ru6a3I~aQWv5WZ%WZ}6N-em`9nGATSl1=9{SE|OrSyMO4IufqWIG%t1&;wv`<%u zRdr}vLBc2whaZBP%C6LA7BhmPR!s#b(DGf1FeI% z(pIuve(B%7#DpmXQwZP#4IYLIUF?;!qb{b-&wXDBx%@$WH41ApcP6pXFuNEDWc}z= zfZ>BPA%1wN?FSw@y$JDkY;wH_^LA`Z#^9lFL!c4w_5c<5xHC}g&djU#XMDW2irtlu zZ%N+pi@i27=#=IpeMwl+Vz3k7&IXE!tFt46aWh74Df|APV^yRV*q=D$*PrMQaQ(@m z56O=Q9B)fXgcIlO_#M!NB3y+ljL;cEZw1kh5CbExDEE7Lzs4<{mIMw(MJ!dQ@RPp{ z^;X|3`fqjx_%6zS&e|$aZcI&hn!oHa%0>x7&;{h}Z%fgchs#`Q>j~w$gtf1zV}lPf z#<02(uXCpmj??#DV|M~lWWe_A_Jp<1U~x5pSlU&S+t0Bg=iM0N4uk3&5lk9)CcokA zi~15edM94^$ygvW-(4VeJ2d~klUo36;r@q{nQK@SuWl;!S=F#}b7I_0-&G<;$(Hxa zFT9&CM)*vr910vE>#FJU6HdXV>r4m@>=dhP-aPtUh7QylglQ%kd=>uq zX(nVQdDd{I)_(!Pd16@u#zRHyYXbE^oyeHjsB)qC*zK+joo>RYnrwJiv56mdWwu|z zBQqJHx4$FvJMixI+^mr7Ry29v>6JsZdu;KDLu8u3J_J@)utxhEDq#(#+G(zf?l2)L zMm$-@_&M(}qNVMM5g6PIDtem#1vB>Af1Mh3EM4D3qjpli8aC*?(;k~9`bdWQqH3s- z6p)|9*t6+A%e_w_W0{BMe(|N*eJEP?Wyi9JB?%%mcqv&6@6Z{dkbq(1e05jgpCDGx zbYeAkA0f&WSVj?del|fun!qAz}VRCz&aspkN@?4F>>_0fgG3?Ec z_H`54M2~IzCSq*WN`){wlOyk>9cT1gO48~iUTWM5E5musm03b2$C{)zjL6QV_dcTA zEQN0;a8L0HG&M9UO>$@qU>+~fYc)3)%yNi!3TA#rLOpt_RM0@<=@L2+t<@ zqD!}Ib;&_;dPEVB5F@o1lLdxKNWerr-gA6DK!YEE-f)9Iv^;d%3sI5E9ns=>d5CN!oJ{E8e zOAJ4Ias_0Jt8o<=vx)yLWJWnHv3x;9dNRe|gIUnQn7t;(BncMU`PAC@q-P337YaNk zW49Q+Dx~BI;JDsqZ`M!;-y@P!?(b*osJh>t8%4dB9F?~?D353z*}Lm1L=89Wg&(#u z=p_U5XkiGx&s$QHwS9*RaO4_CCyAjW4?s!D1+wyzL~Z@^N(>SxsE4e3+#pZ!r#MhO zYIKr68VvT#p`^R)vOHRlJG$39OuU2yFAMqpIANA}nqr8o;1`ZGC;aq0eH1arB0S_@9rV^V;|&;0FL=6;gAkOMm>@;pq-(?#*lbiVgz ze1!KC9%Zc|ocdxs9K#Y!I0`mEe$bJJe?f%(#FQ_d{-58s%fCZ*@M_WV3OtIWi?})}e`PYG z!cjsHR8fB3<@9Jz-6e$*da3X$OyZ0ViE;)jgo-$9G>SaIdwclt5z3gND22b+3-NWN z;TgT~l;`3os9_6HFEa6cC_M>`TqX5vg+()&~7J2Ri zs=&r);CXi${L+?JL2D;e)nMA%GyoFzrAlK``%b`(gN=oq7UF#(3WW(Aa|*8H&nin? zhQY^KKd=P*8_v6vkC?cBkcz55I_0{%r z(@F$Gz;6jHr4JGe3GVLe`27zJB8#V9Qf|J<)g(k18J(T~4tX`BL2G;EPwfCHl)Yvx z+e`3%jjVX&)T5{IX>VG-Mka6kFpa)l{S3kD6$SlfMdNCm4^6vjB`oWDHIoPmSNAT z+%E>uXPm>B4Oynp<&luAYk<12Fxdkb;#Q-dBE~%1AxQZ4t~4)JA6iDa<-O#Bo}xs&MC>WZc3H!A@0WAwsg+sr>?X; zmWX7o47%@|V%~jo4m0@cJgoA~%Ek}0e9-ocp;h<9M&*S=MGyCU&PlaKl_%kU&MzW= zqzLSPK~ryq1kB@tUWyItERC9?!sL4EE^sX2W~`PT^MX5)aT~d5oE6Iq&-MByxjJr( zEXx+^!9;SdRX6cB0|J`hsQb+>aHLq|y>E^Df_m9x)yv33T6TF=v^>RMEZgL~#%x{i zXAZ{K^g}{WRo#x<=uaJ_bTOt)bpp38)Qq2&a-`kIC(Y9Txox}=?6;Ikcd-N8@j>3vLsxvGSA1Dhx7GVzcUL}3S3bO1 z=Xt!FLs$3wC-?kM_u$|F47tz>f*l#GIRb$=_BSZIeCiO71th;28{DVmOP_&hOB0J8 zyr4Df`%aUxP~#An=}C;wi+{A(U+p6}w>ipZItd6*S7X7aXbZ+&-xSMG^GML?wZ-OS z1nAUTzQfNVb&i%uVPYZ|qn;6=hQ;a!L?2MceuO;F? zXH&RPC%_A_9N*jsCExtmx*t_;Qz5i(Eu~D z&UvDTJZV^5iJ{VjQ@UEm{q)sEUC`x7i(I$>$?4R#-7UNR1&OiY#Kl#GZLx=?!)H(I zNL{`jSm{@lOewI{Z%@X8062*faTOm?oqXiKau8VX)SD5w(f-PgP;LAJ#o**SRaof3SVRZEqr5 z!IMq}a6c}1m2@Tm4yNFKT7yJjQtKu)G(pA1Sya~!q$p*Axm}4o+MfyXwI$NNM}Wm8*Qd^0#;`E#=ci{zZdhwtQf>zDuVv-vj#i32gwJ}<^ImmO3sOYT$!YyeEiuyCR{ zNny-_cmbP5QMd9qz3N%STHL_&JZ-@QO~I)mH6kip3VmnfUm2aE=9j0$4OiMGuuBoK z^s6lf2AN=YuJ~8={?^i!{fP%Q2tSH1#CXbZDIPT$bto&u zP#zra8p=AfJ5j2H zuOpI*j<1qDh&%b$1*)%LAH3Y_Bd-fZ=kvYR(*BZ^O!6OZ=04YQGUQH;Q8VUDqup?f zIny-n8Y54=`pW^!w3ihGkY1iWQUE0&QIXRtsKd+J{dS@HtYT|jyRWq=l$A(P1B`T# z&o_k1ORgXR$3Y@?DxRD)x~TCCiI#A_e5dNhBdNv?gNHD0M@@TwZHc!p1#AMc5&L6RJa=v;Nlqk^q8?zh zS*&K3$eHBTBlPTl=_>5OZ5#8w>?iL!N`O`HCD^X!NEpgaEc6oeXeE7vVx>BDSiR94(PR4Hmnr%Z?KsjE?6~`4Q#kp&~K_|B*68Pg9^c+W1e~d_IYPU z-B0nK0v8{6^ty6~DlFn2iIEc?p*tabz5zN_Ap11uwSLr*SQNeIj&_mO$=v4{cG0HV zQm?BB#tubYx*c{BXmJCiyr12vpI4OACYYL2D~UK&VF_wp>`>crSUI99s)*XREc-7# z#)$&4)E1Z)tD~_u$UZ?65OFLJIvtJeXBM&99|l#|$liY$)9vH%V+V6hUBvUZ$+yUS zmSO%>AsZL<-H#B`g@ShP1;0Pe{zCwJdIjHT-GyNcw}YM$H?TA49-%ihHn$?*M*zb( zD$6Zs;FD!(bz4r$4@9wp+(q@8tf>UPsk<)nrOKL*3N-Ocv9TifILxJgR}j=+VWfmH zJqR!S6q3Ve>zQ{*bs+t?`}Ru67l~a(HjMGLPl5BF{qx)4hCm0v#5lGzC!2;L^&cNh z()c>LetgBM;OhiWUJ5S@9{$C!0W}l4Y`_OHB_sph0r=6}>c_h(Y7azx3T4A<+GesU&V{RiY zYapQ|uEvYJ&zeIXl5gbrT@ECkR$&~rVtxA6@1bU58Zk4J$;~-swp^`b3zgT-wN7yb z>SfV%5#~g3(>m-8W4DbVhlLe*cBnzX(H{_jZnut#hZ4Joi(!|pD9 z%6hx?R_kGR02b{*0oL_)oj2-oU_B@9pdh;8NJKTG|S!lPwa1APqZ#8 z(LTbMarU57yNoW}NyS|L{5@-c|iGH|XWRO>iZUqL+zfiY`Yz14Z zxawV>$^o1_P7<(#U$s`8qepv#V+fZe7?&md%t+U3W6zc)nr!j~YGd_kV_(L_T1`pU z>tcDIL34^nR8%g01CDmIJ=rg*hc)+I{7?Gfug7z*^H2KguVybzA+Hs8n^`X$S6wZy zrJw=5!!og&&HcIDrK)nO;62{IMEvYmfc7GT#f(yFmrx}_junT zM+Y{;$F+5klU9>ifF>P`bOjL%JoTySriN?ku-UG*}6WRkw%bUvqF6on}Xt4 z7Z$bBJFWfiKSMr2oZe@RO3LF?X(L)uVKPQ71m|-ZiwLtlTrYjDFL+#R^n0uvb~}Br zouX^=sGG`&MRa@z%8zSuOS`MI>s;1y5#|UQxX~vU_siw>OG}mJ!OYvpm8YQ%`o%z3 zr~q{@{5xg@Ev-ubDXm5x=InPYda%d#7WG@poQ+4k?%4Avhu_k;8PrnE0Mc=JT zpK;16UQ!T+&pylz$i#07bXTMKGzwh?oJ8#Z&=!WNX#jw(tc7&nViCH$KAKd_;7gIP@;aerh4YVA~}qDiUI z3$Ahf+Gy*BIbPW%YHzw~XS!-{+A;XWVW!yjTgZ(yYNY{cr9Udm9cg?$DCuF4`BBIu z(RoBf_iFkuDVtQ)Y_lrp3Y}#=-f%6eF?M;8}jq;Cb}zdgj#|kAK7& zEgPkHOAxAC|M!*weEd%*+=kf!t^h@wT_Z_Sn&xe4;i2~sAAHZNQ0&i~2(PonCHX{4 z?rS+wThY(Xg%AEAiiVm826wGX?h){8+}ZnaZ2nHm9v5}x!Sc##IQjT8u_#;yTmoz( zILg3D+tc1DfKfAB&#wsnGjO($?H+^Lc=pq;XAWmoT@c+nLeO=cvi&hL%m2&xRJP=F^p3^59nf}#+6<-_5(&mV z5WgG&lMK8bgJ=DW)!3?ZyO&EQmw+s-d^;r|{M{z+xB!}b1B(6-u?DJk&^ElP#P{!S zL>x2M%T7igacZta(%qntt8T6AXBXKLyE$kmkM9>{#1=;>VAD}8WBYmNGJd_bEP%CS z4&DA2JK&bx@%jS@0Z#iKkI|%70)gAOu2ARgp(7==w!&kn)tug~lJ%RPSE`e^j}B=u z4ZLB}ly$U66az5>9^bHu;YSu#6aEyZKS3p>3OR*l%;)Sn`u|fSdrp1Ka-TZ8+#jvt zDe9Wc@pbEY%>1nRWt`a6ugf)%EP|tyKXQl3KCn6B93fM~KJb8PbCb2N-jD^zXpqF>XTv>1Wx0Q5+~ z1Fl4{w;XD{@qOk%j$bq`TxSCLH_Dc|C6v(6GbKlLfIQP$^~E5QKXcYg6!&ZwhaA%qnCBT6S!AE5>%rss>+`Kah=AQfzkWW7svf zo>0LX+-GAJe~rVS(}=PUu#$JlEp^4FY5`flkWWEs`Nl_DL)10TvnqJH+*iOPgbkG% z`8@4(!FDEGa%yCK_;sCywzQ0PCQp5>n17eG4@?-3mDp-UZzcf{43FpVFosRUs1~Lt zmtyD~xo@|k=Ku&~Eq3Fk{(;nWpcCbKg&>IZs4y*tE@7v%l0cOj5Km%6Ikdpf_MGz^^6MZJbz&dx|eJ#c?u#llw?m#2lur0Ak;< zOulQ+q1~YwtkATx9&pn2sbMsS**ZAg+D$(ZoLfKs5TKh# z;i|T2Bg!JcrSZ$J|H}tefCYsTB|x|^Oe(xo*Ny5m$glqeQ_$Y z7^ONj-czq_oEK!3MLuziZQa3GA(;Rb`YLTZ4%arT?<5AqKHzdS&i21~-!9Tg!`xT- z7{P!N{RQVk6XnmfCvgoNIQddeibh3BDkKdm#V|&glK>MbvzK}tMh?`uo5`6xAD7_K zRgeuUD*k)-N+wWnQsIHfI8z@!eIZIlLz54$!jmOYf2c43wZ^_G^e<2Q&2!tf*0N?; z&Fj@N3gefvf=eAK4QBeG;8_IVM@D~up~uD3`;Rt@JT$rvWHX-Pm<&f^V@gMM)yqRDk3BK+BW_+GP zt7|=S{A>4+&cd%I-4mbHWloJfW4C=njvCzSj^A}x4)45%W){u!xkjHse8dx`6l1R; zM}38f6Ez7T@k7i@oX6Hdaa3BH8-WA$VcGaBXZ2w^6Rs9kJ!@fn!ma?H*N>e& zH9cdr&8X3D_IE0uEGwT5Dg#(1#OIRF=2Lb6MY3=PoK z*hCq_{ky2}JD2Nj$ixzXki9$Skwpna@q*GyKGuttq}|7o0}ryZSe1-_x1>Vg+leG3 zfNKq2Sh>%ye&OTTEd%$yv^9PaGI7Oc$z@z6O0=U905Yr6^k?F1ydvb6IIMYoRUDQg zoG!faRb z@~eJXjFOs%3>VtB@(yP545 z3r%ipj$onRRHOJ?CIso9$Z`wPw8ONW=8dV(C*w>lHI0w1+O}Sgdd!82K=81{E6{GB zb+(V34|Yv#>E$7BP4!;Dhqx7Sue&^} z$7*H(vY{6NfY~2^@J4wihVFvcWszLh=@bnwRgT3=bltNMgFX;DTW?NAqPM8_wMRsG z;$WlktW9r=F5wJ z=mCo+cz>pv&}+P>x7e}q01wf^x=1PGy>J`4et1gjJrpR0J? z)4w}TMTJ=Oi7wWv@IL)HjSQ@Zez#e0>=RHAiq;9SFvu-hGiQpTxdv|P-jMaRF0Fo> z7x-4O$>PlzI-1Pbe;_80S#Ciz;d9Y>Z}F0>(bfnyNE{ljZ#X_{Nq)a*6c~wY3gwK=(u}Dt^zEhJ4#GJ|4-*D+< zH~#qmO6t$e^!y9D@#{s$b%gG3friSv2&VQ5o!um24=`P*I|!m#Dggur%L(2NCl8Wa zMcbmw^XWSdhXG%W-DVN{+KWO>LFQC&25B=nNvtR-triQ^^+)~30hlcCZQMazMegXWg`m*Z zBydgOcLHuKYqnouNNIKpmg^bQ*66B~cU5BUth#-;GePy}!o)r7pt5_jby^O5e0#j* zuW{ffskR0i-8)qakf3@Y$tl`BDc0#gc#F|WIVL8&9>-d(>Xuh2qw}-r07LRp`7?T4 zqs74W2eCipq4>@p$hh+b`#l;>T93PJ1p+h$$xThU$xW_y(u(4~Iv0cN?G>9@mHL{(yg2zfKxWeDf3`h(wW3r6N!`QV>48y8O& zTl}tm#8muKg+=~hFfMD~?>)AS7c%L@?TnuYSLOVUVuYtYqZia}aD_ z6PBPBi)krU)+G=9iU6v*bulYadL4Z@peV9gGU#-sPkgBsp+chFoX&u~KmRMrJ;P9u zV(YM@!{X?_LhIPC`TQ*am6i;rp1=fqUs`tCt#cQ8aCSzdTq%9F_>e;ukeW6K#0gIJ zpMRHy!| zOyce#~NeL0snPmH$OMlWL0vvYCSB0deBYs^6laAQ5Q^} zXb!5W{iS-@0On<(3vnOd>(yWanGfS^>7DNk?uh@94dJf8Buvlf{-;$(bzA4a8%dNe z!st~(=;baA3FKJB0$L=AHB<|d0V;ah1@gG79aLQgQu(2IwlTa@!{qnE(23A&r~mX^ zc-5K=dy+vJ=tY)1d_=$CuC<-|1qW(uD$&k*97KR73YOd-G9bxk0kFrEKQ$ng#$?$i z6#Aa7gLRLwx`?#V-+M4z7h-x(oUCpW(gmi3qzV^b`l=pYkSQ6uuM&BYEvI90*flO zmJ_knX7SZ#de7y!?0@wbS3vhS%7;lk63cSs}SL?D9`AhBNM#!M4&=zG!)fN?Hg@$^YBBYiZUxKc_f^tgDGeOF zG7M8^PZKvrm3v>0KMUW50hHS1pEbqlZ`SG8Uf%!STw4&mu=@&tn;%}`6xXB`7asp3 zl=d`q)EFjz50MEK|mwSFuBswWs4B{PXcxq%b+Y|9l1j* zc|80u`*XiyIsSRjsWnI;@ROMTlIPKz&EWR8u9UYF0^n ztl7UbuGsLNoz17^*E+>=4a9O;R@OeqMy2j^X{Q-u&`<9%`wkDD_ZRxF@r2{XQl<-) z;$R7wj#u^{Y=qoMlAEj2rE^GWlwydHYxLqvYOwc*P(J*x@R_3MD4tE8R&^Y^$#NRJ&9&+1)6a#`#I~QMbxbh9rJE= zcse2nN!3F|*Cjb3a|Kc}frTr)z1Rbh!rv$g2v?pb<}^Z(yCj z7ls*S5vf16HBlQj&iB)*p|tI9wGYU&AY#QjxWa=-^_7pzI+E8nZ)85=y6(it{&|{# zgG?V0KlVSY=hlTDY+x7Id+?WCy^mfL<_?dV-b_QNHjROPl#jmF&~WglN4Em9pvrdA z2dTIZ7Jlv;hm1XuE8GOLoI-SeLF$B_GXE@ju^Icn)P;9oN5Vz_Vgh(i^Q?LbWdZdOUL($fGO;OU>{{nHxhm_{PTY8=D)XQplV$;WB-ZD-GbXSGax(r9NleiIyT;=-0``U?Q7g~Ela7@uOb@} z;Z*5_75UCwQe4*-vhelOHbi7Tzte@@qwSWGIN0u%pou%&uGQ3(aNB=_8h>Etgv7zY zbF;-e8!O1D`9Mi7tx0F)T6eoXk>#%fBl8gwlLxTng9rikE*LV-(ze_4CQW|SHa#t3 zv!q7At4fWf4;JD1m=ebS zFcRl#uU8H!S%mTWewlNyC~?#_(u6tZz!@go(Plt%E^Zd1Cn;7{I~LRho+^i=E#zD{kv>Em|RZasu)tOIu0QeXkuTD_AIP zL*7geHR_Gb zJ^b1;1k2>H2vziXRfB^2CZ>S3PbCvnHg+*%d4J&XVi-dWm*ik8RI)s0^+5$3~Fd!TYTs`&k5F zyjejN{*`9>>nF(P^N`w4YLJAuwnQSgQgGKtIdH%=G3NzaBRU<4#f7C}{r<6P3REi{ zz(<$s!LB5RXEI3h0vY=t4W=GjH*CH8x(!jlhCXKAar#vIK*LWru66wV8BA#j^Gon0 zRxAwDF7+`+?YgiCr{7=!ob)a;gA~2p&_O;*R>NZaDm4{4Fz5 zW1j^}B8C4r5dt{>Nm?%1&s_ga^rl7O87n&+=?wXphrUDw$?!h49WQ?onSS?P;&44<6Jx zk6Y3n48`xDwZoVch!7a)R+r<-i2ts?#p?DZ$CZ>8zb|3%#&Pgw(|4}y(d5Ua^fy|` zLD;Y-R*+!v!O}D9pkWgu2WgX?)a`S@J5~Qh;tWCw$tEN8eHD3@I5z{<(b5_3IZb~f zcqoGQ@qUt;PLZ`bcu!K(4MeYMD51Q)LmV6=JzyBA8l z2o7?iRWEUnvLc4jsO1r=*h$+ke|QjV7XDR%meE*GT95FxAJcYY zF+@doj`E{MdB9tHKD$w+p)(XbN-*&KH@20$-^kV1BD1M#;474(XB!)q%IcQJFaJ(8 zE7qThl20Ttxw@Bw>3r^r`4)}>Wo#T)0V*XX=G4fGu?d z0u>9oe00UVI2i&aOn2A%Qnzc5-H*4TUou;jsj|-<^%_qF<*Rbs8{}6Rh(MWP!N$6B zO5XR3tzT=Wtml)FAD_x16ss@3I{+vK1d(bg!0;&zeLhAxDZ4zznMx>yVFu8KL2^kt zi9buDl5r+O5m1)l>D&UnWq(M{ii74p?3N_|f+Qo3W*;%-Z>O^)mK+VA+_&Zc6KSj$ z9rSr2+ar)?A6aJcZAP1M;`j|yHgi$euc%z+Y1iKv%&oPa$|w@r5~g&+@?w8i z{A?60utV7mnH)N}EQ6D1Cd$Xk$44U4eUqsJbr-N}wn`===q z#mIu~$BVa=1ho-1cPIj}0ZgJeHn4a`$tqY!_5)gdE!TQ~dXSBSo?@3OdG ziYL8O>f=DAtio5YbtSH}yWP2; z^SrMOt)oRFHqilSm7pt?0sD?B9cN1~Be2$de_=v41MQXLkxK)bVILOmgu{tnB*7`e zn4b9^Tgd|qc>?XFyT~KeYrWiPz*X%S!6H8~N|1VQaj>FGKaIq3-Y(^T1jLM%X=;{8 zb?{dz(bvL?Ad(M0CS+Kj|4sa7b0yW_#RB&}@PB%k@lP(L{R~qrmwsEDI`Kf=5u()! z#~PGhD`EjGCBMsgaxgWgHFe*WtHqTi$-;b23die;YTrUvg(>1hvVf)u@*RZ@&nl&# z5vU5eIA2QET^~iiCI?E_#jP7i+YVe}U72x}#}~H!d@p_5+IP|D22Y7>7glufQ!1FH zK-N(cg|>yGH?8XELQ=igyoC1-nuA?NYlaH_?Xq}~oK(Tn(8r2>6}*2i$`WXIN^vRk z1b!#)Oe@a?fJCBbWb?FYTP`j?H^;c?M7wpl+6IY8)5*T)LB^}#d9Tu68=8*7;;uPJ z#h?*ot;xyYdJ$^-o}zy+;%?_3At|l=>&jm}E>POGeQiu|p}JSvf^FTMbo?O@_e3Xt z=**bfzk@oWro}#b{iq;0FF5?(=sS=~q$~E}oiS*YDk8<;z2wd>o156y`a}FoARB9q ziJ^Aa=YFcNIW~-zHl`OkVdB1QKd_7J#=s;~lp3@=BDQa42}@nL&u z);7~qh3O=M*fI827O8N)TnDI1p0agYTwf#>D zipr6VW)njyH_R$Sbf*hh7a(vFXKto#lrU$I+(i)g2`0q{>+=yGHO4fZ@$pIhk12$?c5L;JvwWXVf=EZS2l1xOJm-NX1CG|BGAtN8h{3 zd1wjqk3EROt|rhTPz5-?w{ChwszDQN0z+H3J<1`-Fg!>G6J#}c8iExXXcO}-^Xt5N zuk|j5B96st9?T+_6xzT3fFzgqiv;#y&Ta0Dk9F)VwS_hGd%SV(%jCJs#{7J1WmJ=1 zpcSaJl3|S_vrY~U;ew@O_}haB7o=OgbRO*I5T3Q!yS7>rP#L>oNO4rfwNp$$zpQ9h zZXJ!z1^(3qoAK|nt&;4;c8FzRrb&8F689={+xrBVzN1It{va48^M)QPu7TahNvOd} zO=hV85=zZk*UOZ$3Le$lRnE=CAX=aV#UL=rE<1!X|6&ot68YpR#ZBvJVThR=XH(jX zYn$;Ife91?{fM?cTqmiqg-ZT*GB*=+s)*(qc;d-u3}Hg!3P;#Y#1ey5oX&+ZW_e>T zbAt4o^$hjhR0CNddf+lthClmAj$w6dyf2=m5~O(ZcD^h>N8n5Nf(!!USDPTDEhIdL>rW~W4YhXtb_sqZobh{sy-)-Z7i2IdT)=6mr~ z5x%4OTuZHO{yzmx)>Xmu^f&@!;EZ5{?bowx# zePd1kkv%GCMrZCTX+0e9oG7_Ch*Lf&fG02U>lJ^e{%D^Fq0~xfWFTku?#0}*Z-8eD zsAA^2QRVjFnTK#hlZPC~8hWdD$^r zB5FiTz3k~1yox*GN~bfp83j`k9NaliWJ+kc%8|oyn&90Kx@n}j%=GCL`0c?q7cT0U z-B>60R)$`vXkEc%S?DPvxfUpEW50A9b}37srgVXo^B~MAFWze&E#Q}hc;<|%Cz7q?3MZPb8v_Dq6L$dq@=_}bE z45v7|Zik=rN1mdT(mQ#^o@_=Xe{y!6BtJOPUQzQ-c+7B$=0MjldpqHeb?@x8ocGks zdSyL`p=ZCz9-R6Bd!eFaHHk+t;gy9Ym+VE#ZvR|8o<}Yan16z zkzIPTi5upG`zC|qvt)8;DaI$Q_quSO8Drk8G9kRop}g}sh46L~O>+NV;j!X^4zSaD z*E5&rxRRp_bZpRQsV8>X=$n%d4MiPtFXVt*Ap?i4<$ogNb4tax39uB>SjK{i?yueo zAY-`3>b_AMXQ$$QYep+VN-e*L&K2&18#j!qWb4-yus+5C_^awnKEgg*S=hT1a6J5s zl%VFnLus~*z%XPYkXx`2^-j6lUH(t20*6_>m@cqQ6y!zYWEi|g{3xMXdC$B)rC z3}GWN{X4FSkTjk?P%f`uqDdN?gfxfMo__TOQO_ZrEt6lV&+|8NPvd1_1^l24{HYk- z=abs!i|y3831iic*m9Dj>AGe?;4B`!9eG6;c|ixg#^k5su9`U%bD3)o2-wP7eKsK` zsm_|@?lyRm1AsR8Tl#8g$QOsWfR?S=vM_^M@65A?h_c}0A(kA1R+O-i{AB+VW8vkE zj+R>PxO-{-eL~+op`)qkKI2o|tw@vwM^Hp520F;PH6)}|X4AUyF63X3jD5G&kc_}C zxt7P)L0}Nwk-Ji$DaZVTLhl@FVLLe0NaVlw2=&GCKj$*owC4AHCr1ggZYJ`-=;RZ{ zZbNm2E$-Pxz@idse8WqL%q3g$p%B_&x`oMtLaWZmF09{qCWaUB??R8LVC=*Ws}Z&* z_524g=~o8e#>W^YV(~DXoFz4=d7_c6ig_7-+sA$T2Q1Cm-z#DS{yk@(`Ap!a-p6^! z)Df<)4M-N`oI@jnNm!=c-H_kia}&sKK*4!Few<~ugNlWR7G+v3hltvXD#I0=fMv+! z2u2&oN=;4K8{_~)BAg}@D=d!B?w#2z!RH&uGBb+YcYSi6QJ_PHvtPN7#q6e00 z4ks!Wwhb2erHgM9lCp;VWzbKuosr}L&A)TTuqLPf6W^^vMC_;UFm9*;J^7t{eYZqY zK+j!_M@i+rU!`@~9#2XJ9q@BJW6Nd}{z=weJMoS4{;JSPuo`;eir(yo-n=Kga7^Y9 zgdU^u=+ka=_~p}_L=AmP;5*E)C!DM@^da3v=IB7GCBC==e^X5UShkIyB|U-IEU@d{ zYjXHJ^))q8de_9vSQvxL z+X`2Sm9_UdR*Wl2UeZY$dU3>sjQw-1lupi{8F@v+WX5M+YTaB;Yu!!G$>!s68jnu{ zKkG&L7ME0H&J+OGJ|ClT!|K9YcxJX(zWTKn+9`qvakYX)#Er4Y&zg9NJAC|ikr$`M zX_z$211NVXurkFDo1LCU_4&>PfvAk;+(n9%r5@gU++lBk8}>zXVd7IrWq~ z*eB=j(|b;_JW_YOu}fr1KeP+SkTsubuF)InKtF`F=#E;OYCZ!kXN}Zly;9wK(<}p7 zi;m%D=ldf3pWp{bFR&>XUA}RD8fVM)*`NNiu+mhljU{b zlpKh^x1%?AfNV??>jZwC4_I5= zp7*vZ?rm4@+p^H+i0HTI%QvV~MQC53FyAC(I(+P`tU^F~$ofBdbVNP|{4%l@XH%cG zWyATeaZ)O!7@)Nb9KNrLpj#=Y5B>%(s9W>-w(^^b=;jZ{J5qu?QOA7uezLChW6DBK z_vj?atardpV&GbyeWIi;RO;2F0b{1D@$=w^>&Z)8Fonc?WcY8?rJwNw+U1+yT?9zI z`q*ps-yy?C3El!^SAsh}yc6|iaH@SrqHgWZ-z3eOFACa#H#=>>A|yA8 zhTxG)*L-#8j(Di<^;iO&Lu$0s_E^JS&9w9JHD4E&32mUh$KrR-7(epB6Jg*?OL2u= zu~@C@j7r;Yp-4oJRyl!@&y{P-S8BgSOmga%HSB!>?#ZSDejtBD@9q) zKUtAqeIFO4sJkF%bvNi9*KD+YMV>Kw&t!pw=?}-iA@Gs08CDXmzx_r1O1wT3a9Eu} zeX-nXua0W{-}FOzyFPEv^?-rAO0->48`W~YDfNrUc2cyZ=2Xw#js zZDw2HgbV7`A&OjWP1|S!>!@Yeb(2i=to7}#eTD!lx8_~L8!NcVLmTi9&exWRWveYE z5~-bmVqn!XdilOB2IuTyHV;vwpudOL%PVE%1%HnGkAj#k_dvf9H`XeUHsi<5+J%^bz1WXzWDS^aoT!CCKv28+PXz)x+vw9m{$TqN-u50$5Erl zjK&o@j)8WZHB23LG6z~vBcLrk=+-#u0mUYmi4RZR!%pXpji_QVqX=eDhNDB7@k5H@ z9=z53o4AsH*et$j2Xs|FE&{L~;)1q~&#}M~)U2{Jd8IOjS(5u3@$kTh|Dt{*pnX(5 z`4f8osF?I_AQSmu|3!^&>=VF4yM!)HD=e&7vDG8l)kE1&z~tTs7BSL*b!ZE@F3P2# zdW#^|OKIp(cD!J>$jjaa zyIL-t3y$K!**D%w5?l38D#}W`UZzZ-I%qFp)hW&HzIpcGxqzf4714`0?DTONDYOat zh`_(&^w*+$6ka^i_j=e9`IPA};ypZ{=TyD8X0s7r-=1{7Jl*D_nDpAMYL8ExHsTsu z@~gZ_*?P7h66JPN2vB*E0pI6~1gwGAuTs;6*B>r@CW@z0c-Gl*)y_p<}D;19-d>$h98cb(WcCMa5|HqtlKZ zvJVi|&*r>C|5C)5@b$I9z*#gi(x04ronHe91$^Q`m zHCAqqafy|@L4KVioSas&4q%~s?ai(6syRNv{WrhX|MYV>r(w-#s*^%7d|=TFjNT`P zU6Nu$r*RUcP#xS2iweZwXdoh{z`eAEuor0%+TKzOUTH#wa)0k&lVU)yrqQpnB=#Q0&Cix0cqm6QUta6zquF$JG#>QPf7e)!KgPmf1SFcEECZ^eEP#NWe zzdP%Y9*Pz30rht?$RyP^%O0dcb&3_>`8P3I0_ug*52q>3god5EtgMEIIZlA%9Avy8 ziJiww`%=dK874^Ca}E)-V>1rj_?o55iV*$RWgvunes9XV>GzRJ1m&T9R-@zrjdSD< zjgz_y+WolctCF~s0!7L}QkG~TYDEwoY;ed_<;$Gc6U4q^J0nObUo;_1=|%!5^dmZy zs3@bz)g$rsxfIx>&M1yBMVT$cX;BWniY_tjRltd%za3}dOq{fee)w97p(jig(Y^Peog{95tQ=1Nn96_8tjRBwU|C7m2?S!UyZhGuHou6J4I&`m#^o!w9sB`GPrDKBee8#@z zoQTW6rGYK!L2|i!N5ORM;gizS1N?4YR`ypu8p%-Hq80r&vE4)PSBB$>shns9sZi&F z?Y5LH`Y*O&Xj@KCIqhHnEMX>jOJiA7P>IFzO?8>)+EkXZN$!_wHUllJpapG^+#OVvQNVJ3iS3V^wfQIZKA6@60Y+ zKJ-yhF>wxcrlL3wg9S>3Hc>NXFl0-cqg}#PI=zI3Bbe%^r`wIamfk66m7pN5pdk0Z zum0y(2Ag{=^rBsaqFn-_HFBrfS1S)w6JO7-tH*tVelDk4mvdRSP7fIC?75~tg|tZu zO<8)c2(@ti;8#OF*8Z_V)-=YCg{Oyb`hn$rM9Pj_jgeP{(XGr0XF`~ibm+VH|8BQ| zGA{uwn^^{SUd?zs!x!#oX>+ zn))~8#{jU&DP#w1vitW%lvDms`=~7#KX{DIy~C>1xqci>x;V23ZF?eoESoBQIQDbr zgxg2Q^RJy~80}7|gXc;rNTWVJno_#}u^s^%7ux6CqB?@m0hfYqJbpx+Y{p(%du@jVW|S}4dJa>|8= zivK}EgP~Uh;a3DIlm9whR&Fd_2aSG*;5sDO?bbL9cM04<4@d#o+0<@s3cZgPi37hL zoNheUD}3~v|45LPLv-WImQ@KM!#Ds_9w=SU89x?M(M|udtqPnVV?)k&Z^c}xhAgXM zx_Uobk$h|2U;bWk?Nc*))9-6E1sblC%l4{wbIPWUm^9E2JVY4fJ;y=h0a)oan9$XF z>~|#FUTUGHO!bHVd0+5RNePi}!%;XQ==d}a;`KPxBM?)QlF2iHlA%tMWXTCwy|_wH zlY^5ukC({yK4|Y5%7jKdxKe$BEsY5Qq3qa4Omk{+SwZ+ysJD%1z z#GbL~NuN>!{EW+gIrH4rCw58H)X-o5G_ly^oewA?HS%r3Ew zK`S2kolM510OV}&2%Kd3r*oVFJs3jHtdVD4Z{1wbF1GMfU&xdf!~01lh$Etp{kIVv zeLy7J&N~2C(5OiVC-GgAJDkF?NMEs%yiGd6LMt96;S<~s7P#hi zHA3PoC@}fXLIYcyWXrAof$u-M7vJ+;M8U5MQ;Xp{EMu)*Ngd(k;_erZL4vv#3l!VOL`0_Tp3>@8sqk?8u@&QPn0qB9F5QEf1! z?$fDH#*1zV&|f4@3iKRC<$l5%L4!*gyqj=WMypQ$t7V=mUNh-`pl|VPpGRJ={BLE5 zpv`fSUhQ(FvVT=k?=paOa#*4?m+Mfinvbptl`+0=bRh|66f8;;~jf@XeI}iD{a% z6VGH!{q4HlwW&S%SJ7$wY`NYVRJVWNs{?KQ@;vKOVLQAX`5s(Itz}6o95SZsNrAYEPy!{!qbbJTyh-v>OWQ82x{5&CAaCa$=%MXcpfTzJ#=$Q1= z&GYoh;~}$xngZmdW03)J3e%ut>Hn}ztlf5`HOS1s?X=JB6r?mMEReOZezjqq5b=nv z$9Jh6KpZdU6hO>H54440o&l*siBa)>TbMLmirskV-a?)^uU=3;IHzC?WqiD|V+=xX z?b0~{(OPU4Y*ATQ9SvJO5is*^K>YCu`kh1X>1|f+k95Qz%kI6WR@h#A1+_ow{99IE zn}SVA$_EJ|eanUf5LE_4So+4YZvZI$WbAG$%$IP=?x&%E0NI1GCtNoNiyy=F5P z2_m9S>vj!3{!q#^gmkDt)X7C&*3>p8;%xXT`+rC*G(GXRpjE9{Z{7<3Ft3vb=d0^3 zuK&<2MaQ}O%@HAtJ&0L@jw)~;!JvPlp-o6=jVv8V|I)oKM~J5`A_?*t=T)Vd+`;ty zFRQ?#S6=qIL&Xlz`;be(T;gI_ik-h181g>}F=U4staFYFeZZ_6nAFI9hAyi+6cO)6 z8wD4%;(=*cd8H_=P@tgj-X5cZ%*s?;;NS;ZfX@m&$lmRt z#NzVK{&b^-rEPAskrVXjuW!<@-C!{?^rPLY)7Z{<>=@L2^ldRCh1P^eK^t6Qs4MFw zWKWtis&QL1WIspo^KnXuzF3SMhJ@>t7G7tyKkny#uQyNz)uE>MKX&n%qMb*wevX$A z?c8m)oC~Y%KC&~bA#|oKGPLh(Wf?c|lOcEFJ1y7IB(ELAw1v_PM$2#|?U%1`GpLr0 zx^ftfFRFkg{7>2E>c7*9I44MExVdTwMu;45(B{z;tbFHT8wja^WO0VfaU^9;bX8Vy zBubP{gTs#K(yVaxfSYcn;+I4Yu}N=Wgawx*r!^ySJED`Z!Fbu^;p$j!=G*aToUiuY zpy!Xm8mIO>R|_0|yCKjgc@Je7-PtRLC#H(V(TxD9cIe?CB^3DgaC|v|jzGtY|9Ib+ z9~v6SCqx7HO~HJ@k9?2^h_P1lYP-Gfq-NJnqp}5(qHLBng%Q-3YyQ(03pv744896J zYK&p--Z%BkyD%>#Y;ItCn&P0yVwtrq55!_n!!3KIjT_!5(kk-0aB0 z`bh)KRNY`@)o5T>1ow!}O_@r>XpdR_#Dc>z3y>MRSK|Hs!?0LAe<;U+=A;}fMCIb|8NZs_m+@<)vJ0{uWD+Uokf8N3sd*l&+ZhNJ(pw@4oCL^Y7kk+*Xr3GfKtx7IG z_QI;rG~t$;Uvq~ina%0_^jTdQ#p9!6A)0F<-Wf9aJ&6JZ+Gx<|_e=KT zfwJ>e?W7^EG}V6$SlFC#>%471v4l6k>{?V^6(FUBx(VG~i;zDwOs%Sl|NR0T+&Q)t zB!BSF!3g}db6lK@5y&Ha=K*VynvNR#ZNgIn5z<~<7&Il>)EQyYhij9Sq>F3+`Tj@o zwm!QmvpNJHJB8>^*izOAc)&E{b-wMEP0N=^{V0LJ{;*0bt}&aQEtZUa-u2-q6vTK` zejB4o=tsx>4<=WwJnIEE?|JCeoyPblM9Ew+UJOUf16)nVVIzO@{~${Z z&+*?^>DFGfcg^k_9`V#hKRscX?)|cxF^<*mX0f_nSm(_CUO< zl7gep`1u2H`&R7QNX(gIlOQhLF3?S#^4kWtYwjP1_UV`*_L8(KYT9C`mR4Z@SoU%`0yeTZ2Ar7Kd&u99qc^0}_kI(j(HD>H4}H^GyyE zTE4oy=4mK%!DIiW*g6jtR6iP`Q(Hm74DV16ij)_4E`DM^4kAC-ZPS-!K6EVkow0s6za-OCjKz4d}=^n;#2jfbP>tyM>W@h%>(T9Rk)n+uq zIG_Iq@DRc)80lZQLEkg9y=H?-l%j#y1NXAlOJ{-jGr4`c~90gDSvau4 ziRsb}rN!#6REJ-l{xmWtki-4{YEl{Z>s22V>Ow97mqM%oSoM(g#N(tNyu}X3AMW@B znNom{pYyJZrm9JAKgAIb#QkR^tj+TFgTqiK^_1^X@qnCymRNm^H@NOo&39&~(=(N# zY!X`6QMAr%5=}5;2&3CzM*ibWcjS;riNvLsncrT0Jg}soREN!|!Q88=TT5({K`i_M zGWVKMFcyxXmC%IedeMplw5U`(&Sst=lLTrsr4pLqZPp?ee@C%0f45D4)e22d?Mkg} zDTfI!2O-YkR|NRH{-(9Hp1H@A`)LpAnR z=KWkGZ%vLKLhgBW;!ev)G|SkOP*wV*bGmHAYD40?{J?BMiUBfA+t?i{rBTy&tjuAR zv1itvSqr-Yrn-akI)n4NgEiCK9Oae`)7(|%w2#wtgy<}nFm>P?TH0<(5@k?gOgvgG zaa^!8f9U;+?@mnnmC0>%c&z3ca`9q*0|CTXj}knt>^Rs0wn5ukt*mJ}6 zv{nq~mM=bW(dZS2>PMKmi`EC|B&$Vs_==a0-{@B^LmmDE=-|~y8frY~@r+9z0E6~w zECrdb0!a~HT9Kpc!=1=T1>U`Kj%$J1wWxV3DBR_~(IznCgCnk0^bI|;M#1KTOLl8b zW*&KAQ%?N*X+B}(5Hl|uD%;k(ai-NMMxr;|@^wgeis2fhR z4whzu=BnFgaZ$I#9p~n(NqV;o!wotkh(xJ}k;y~nj2MMzFCE>PG@qXoU)sbB|KiME zdy`kPQjYDxN^9N*YJk`WZFFA+r62Y5{F9g4+Q|#HAQy%QKsEM1Z=F;4(Tlfpdmfwh z9P#g~9sJ?qm%SE5L^^@nRQ-GcEm7$@Thec9IfnTtRSE+^8<*xpBaC%{0i;kn+53uI zmt-|D?7%$#<3GgsENj~wk*vA~*Z!Lqar~e!t}(ggkoEoRcvmE-qyM1fd$F75HN3-% zW>FRWFEEO16^T+XW}!m1A=oWaL8Oi5;h946W`6~I{ncTe%|As}o#yE~ zqkr~O^)jYaf5TVOqp zhYOO^9@74y>*f;n#`xYMOvHQ%7Us<#;N!hMX!YRdz24hKN;$Knhm&=DIM6+N_t4Q+ zOBTZVw<;sIb;wp&0VI)EC^>W!rtOwe6uPfMy}IToTJcECL5jMSkJ>69q~@ zUUd8-2|P(2s3J2yA@notrC)s=yEOCe9lpq@WfPy#j&sHZUpt*YdShr3+$z7FqmLlc z)EB;XZiYrwsGiwMao4#gsK}wXZm!k$0;yVs&3tbQ$&g=Di;+M93AJ}d`M4ySiO`UL z6Oc|TI=TG(Hq3o5`IM-co3A{To-ZS%(fkNZ7;%CyX-3-an`)@k@)+k=wY~G&`l{un zG;!bGnpDr1#w@3>=AN$#bB|fudi>~w8C+6VZ^7J70_`6-b%C`HYyjP}z>ce~ zSFqV~Sow8VE6meGepG@?Q~XQ4V_IoRN7s=btH<~Y@ZBv7X}it(#hv;{`906*<`?~6 zob^V5>HPue{ekJz0qK8EM=K7#=vQ}*IdqNfc8%STKLlHkR!q$Ie;}s3ZaazSDtMFP zx3PnTyTz_OvEtinc5?hys|DCNN=N_~g$4cWz4dzxK(AW~{U^8-hH*WMFW2x%zofa$ z+bk*fQI-kk-VmM(k;;ELa{+rjpu59)(g8ewsi}_H`Q&8&R>N%cDnC)!o00#(>l(JS z51K~*ad4aygDT7<{V*Iw%Vw`fhAx9`?&C5T-ywP61_o4q*G$^7)#hR~uwCe<&A}P7 zT4x(fDjqXcxZ4bSAAMj*)8Ka-n4{C_bUnIZn|IfU_@6oX=!3G3mqSLFy-72>c1G56 z(tL&i`Uq=XJ?_?!a(uB*<)Gd#kr!YKME-?!lBxIwJLmz>s;+kKC|pK+R+eD5Aim$@ zCalWuyq+~<$WiqmsN%?FuwCQ0*#$Eqzm7}CAfI<&AvMg+* z=GZEznX;F))Fws$dxJvVBMZD+mGkva&z8s05s9?at`)2^9dt}TV}c;Ew;yVZ6Tr18 z>nTg6_n`x^A@#JY`*K9WJi>n)sjy^3DY~s}&m1;}LQy>}Alzs)eUJ1%ua`x18fbvh zl~3W73rN6zv(Hk1pm_rPZ&70Rt27<86y=-3RDy$jh)QmT9k=sg1-?rEwhm?z>-4;>0TC89re{Id zH&8Hr!)HkOJABJDnN6`V4;PoW^4HVDyo4-1VJ^mx8$)QnQu_m%I@>#0A@w4@;;8QC zQs=6V#j#D-dg?h^AkK!7nLck~V>0!s7vX(FnS~jSgqvfN zPgAaF!Kl7I&%KB%)$|ZcY>_MRY{2pC?NC zi8)y5kD+H|xNBMvit3vP)fg0%uaD;hOzIVG8Y z?t7c@XBd~V44Dx&h|R@_lYcmGKtlUQ#jIVauh6VMh?$lkhV@-%hQ*k_7f-m%*Y}`F z_%dRjW*^CFqpsjnVjek65uS4dhmi894k_n+r`cGd{oDRO9a<}oun(i5`^r=0KAj)W zxL{$ofa+lWaC8Ved^p;Ayc`0W#NScZlRzFA<7J>5toSf6r6@}Qzf!Lg@j>y_AJaH% z3^sh9y9nDUzca0?o=7jcVYZi8Blxu8#i2iBYc6W|LrH!F?JW>BJ)Xr$zu|BHofh+_%+`<) z;32W(jn|+9L$WK={CL$K9m)R|CacAo6yN=VjC}dOQG(A9U@M{y_WZ; zsnCOJNR6S%6*@?b4^1^%Tm=tm=Q^-*;t(AVg@Bbe%}>B zWWp<1*}kEO)`jLmVW8r052oqAFNfB`ZlIW?!Ng%8I zz_Z2}7Wol~@nqG_1t8|Y>;<~CDBLnb5f!#K38h zxgtk?=J>6$p)>5AXT-()YoN(l{Q74_<|_vondIHM=rHG^FR%d7^n&Bg^?W6$F5v2NTmjE;q_0JL@&;y>DJY(d~&`d(3Y~W z8*_t)hY0+^+QUF4E?f*vcYa(OT_)47vlLO)`2vWiU#mU7%#1I3Txr^RXz`he7u9a^ zTu|CJW1hrGMALK!(36NbO9BoieJ%NqoxC!^Ykeouw8U=eUpP^*Iw9 z*b1`Uu`#*yGmN_(G-iV>VR`f0EMvPAGz+0NhWDUyPEm|-0z|wI)d1YUCS(re8W-b9{FJt~G6Q(vTr)X%PlkuEz#EkpkwuV=iIrFIFdN4rh)Z0Y;Uus zMZ#MR9;PP)Fpo@XNeLFfrIxjbam3Hq-ix3_x#DAe&F5K7RdN;j^Rs5|)k)g(9BonL zsJBKh1?-p~VS_u-HQL$mt`H0yWGRdnLfp}gg?@B2*^XH;j)l@aKUxO3suG^`z)rWA zi9@FV1b)<<7}VTarG3x9P0*0}u@RmPT4b-;Cc<^JX+ju z=hSsV@wE?qlDA*h!cYEVE!Q~1yS{DdZX&I}3JW$@{qH$%wPHpTOc)*9kJ=MZ=)%Y7 zV!-RfJl;G9DmpQO&`fx&jx{pG>K4AYkrmH_oN31XLdr95L+OXmXW z`PG((;MiejSggy@nDVeZExe}uYTvhWdfYSWLo|GvQ(0!~VY$QWD9osQtbx;N^)zCm zrs`jCpt{EaN#U5BNYM&M{PHI?cldEOz{v4`LEVJ_>Tywa(;P?Ee3-p;=-;T$1TmLlqYG3~v<{t9Kvm%VmCr0~70N{YQbLn15NB!)!uzxiq|DfJA=weT zeiCR1!p(!J#CCCkG`w5-(@wN0PW{g{BhzhDk`IUR4o+}io@jE`pdl=2&!u zSnUVI-!u4$BEo9OM4o==Ez!~RA;ah&IkDB)V{ZrKv*+dZTL0elko>XoqO*u1{R10ByeGEuoufHJy5 z(Kuv$E*> zfp0QAp>!5~f*z&IO|T+!vYwrN##&Z+4PC|VcV46aTI(U1dTHIkkIKzkqdp^}5P;&@ z_-#cxy+22pPnpM9(XwMEj%2&HaUiS|(P3~=wtAaDm;tQRMxO%}Q6UjKD*my*ot?@r zezvjYulENY(ZxzV+d%(Cl@h^pEi!|YSlsR$*W!f%6K{P9#u&aO;y3!R$^6zW7f(s9 znW%Ju&9Av21=FxpzV$!EZTM8Ht_Ij0&})%wSD4bWm(00}HIRn?b6R^PotilBxU5LE z;@RS$qBS!x;NdFat z?e+Wa)Ly7(^jUg>E#RnfZCSRgRO~r)05#r4Qb6lAi+mA2T}BIRut%(qwQ5%w>E7O| zsLv5Sgqz7xk8bErphu8?3N(ir1^)yla%HpQ6o$Nu1tVSb&`1Cljcm{+r;vIi|MjMC zfNu^=4C?Lzi~98bR91Dr4y%KN)H*{qy3fCoi0M>IyZCfPc37whK}c?{>MN~_8%WCJ zvoN`b9!9d9>Li}Up+|i3YYA{m`t#-Imj6r!AeN)8o_eZyiTQF%e)oL6vz1VEb?gmM z{dc&S+0NF{WLetFY2)*dSoJF4%ta^fUevv$k%^vf76v69(YB~p7yXw3$*}ogphJfD z<)p0Tn6MHc1(hWjg5b_9;X37D)a378&e2@=~1P`?*4USw0` zun@Y{c)^}4l&IQYbxTMnm``h~86YaWK^tO7hIrFZQG5qRglp?YBZjrFGt^o4i-*$zf;8SRaqF}+_ z8T4-ni&1x2$k-P3X&IM6p()?fNTfbOP1R?yGdnU(X0d^$^Y{Aybf^(UL%(^S*&W$r zPuDgopw*F-Qu}@4NR%x1wtaC3>GQYY+1frQeQP_JQcV<7Z59CAcs`^X-)5JB_M3G^ zw=@5MyG4t>ft-K0x5cJiV&Dais@Ch09$b7C=U`Dx9e6=48zevxN=P?UcvM^LB;6R& z;Qk#~UeIjLijkZDR(=O%%R{qXm8*4q6uurpnU)u8!IebXyYTNH$4=d)H}Ssqjsbm5 zHrZoW8L(_O7eAf}CzhAr#Jhf7I@iO(eY~ZSUi}SVuHyvbY$K*osLyKCBm6s5Z2g?~ z!!CV)`!bhJ)SNA;(|exc_UA5Va;MjuCeNHN&HimO=i{?~+l+^TQQ8OPmAA?(AC!xO zx!3~}vePmyud-5z+@yDw|;M?_S!{o;6_(1Had%N(Y} za-y?I=#h)xxH=S_xHM3@;eDeW^!L&UG}pyAuTNE;*!B*a*gFgNSq*|s*ykL{h=s2^ zWk0s>4CSsPN6*m|!VS5E|LxMn%@v`1n^2wf#Y+27`%|SC<^{=EyJz7+@XXRG&9*sF zudOLEs5HYPaOjHGd6cQ1d4vMxcK`Z2gpLpbkGRyF~X6rOExje{2g!d zPms7fl(`Jvc&B58S?5nHPOxaP9@z4@HRU>;Q?S2f6K~s5#kDbOZC|i|e*H$(nBXDX z#(5}qWlC@XW%iHga*w>~7_a9Tua7h74{L?RSqR*8P4#_W&f=_?4<2cx`NS4xK55z-%@qfW| zVjE&lfDh+*iu}(&C> z{;35I{c12biF-w<`%(NqoS`>_viDIoh%}@ZoJ?YtmBbUbgl5hIyFc_+q3T|2BE!eU z_tRhcRy1W+6!*3%MlBMq*Zww(1YaL33X1eFnXP0Z6F;j?Ju3(sW(r06mo8#$CH4^$ zlY;$;d?)QL9zV;LtewQsVarw!$~N(`!qDpo4|L`9U$sUM|KZII?xpZUY+;jGXCaZdU6+P3dER(6=E|bs&sSCeoq)4*#FtbzL6XKk#$=?Wl$z>P3!V zz4m^?-4lZ1ja%u$ z#7VE=-&T&Ezlrj(i_D*Cho(y|vIp0j@(9cukn2U*g*=J20Jw$F!`;d*#>;Yt4!wmN zaH1$XU(`%f*~Jviw}wBJO4L=2ot0nyynVYzT7Lgev^?-^L$>@$KBJvMUY(z{(F~2m zh+3v}Y!5>|9KL=dDIXCHmVC1ikpkkvG?_Oobc;cA9(;O(yE+{&nqJGjj5 z{%t^K?QgUAU+4dR1PFus`#@e^u@92#P;w1VF*6$T3YX;opxd zewoFbEEhGI%&aw5@qA z;SA&*B|hrtr#FGUNj{DI*cKX&m~rM?fPoXo(_0=Yg>=dy^b(zuIprD!Kt6Qf6?-NX zG|4phS-nMJu8fk7((vYvlF-H9Okb5=`8*|{4_y8p%4dCeGal&W3iWOCnnTK&_m;4I70eDfKI z;u4W{A|H$T>cI=#ogOc!oU+ z7cxnl>;5plD=hy^O_%^IxT?(~*=Hi0%FE*ZJ&C!m&m{5LGy9BV6eZkR+JDEdiCMvk zM%#(T<(AALq+I(U=fp1i^h+&?-|lOR1oEDCL6*iW?cA_u2_tBf0QR_3yE#T9oWX%_ z2q}XC>2@BcQs14Yifr78Z2X*KFu*%@omyHW1wLk7k91J|_W7^(Y&#n16qP)pRVh2> zDLbowudby^aXRS~vm@s9#w-~WaBGURsx{w6N6zcan?>++Y5`A4g4YZJ<+;X zxL!HBgo^PvQX*_|21m23lE-* z5JW?ev0id!R|~km9*APg6^I=OD3tyAU0kWNg2Hb5v=$bqjXBri&-2;meD~9i8^_8| z$fhL>Mgn|EvcJA{V@XpgWtf%zR=lQwc4MXhjyQN{A*K2QHijXZ1a5=@n<;by|xu!5n z@4J3YRvE%uAPPNj{dfM3q(mU<6?d-q+GBSX_S%l4t+~%wg;eV&jS$(8u=j8d+bF}I zG#>&_G#)?bdn1%uc;?!VaQ%*KM|zbPaMms?Xn>>9^#I>pyZgCjvUi2f?e`~N>J-ch zyNo~$Y12QGA};g`5Ci9Tb*z6xtcukrgz@oBiWXhrm?Mr$84+y?+w@1~{-s@kXC&4c z@i=oiN9h>cp**ejXH8dwc1x|6M6xyfv9CMg8cT_SoZ(XG*PnB9l=>R+jgeRHb5PrW z>jI{_{4aUCJgH30tmd{^;vGe>ndsQYoVxk9>$3Gy9EA)o)zi(x0MC^$*tLEE!TJftY$KX?fDM6y-i2@EROYg#^f%G>O%l?Zn1N2xz%e3A+>46U$?y&6+@@(ahR0-)>Mwbi;%jf~v|F1(Ysi=;$DLhE8c zOqmQA-*VYoK1LXREg0Rb6nys-9-ZiC)z81DqCLq3&*}`A4ppFdGkd?dHpcWPS8J|j8sgrou@g9bpHC!b! zde?QjG3x)hRT|T78s1O@H!TkH#j&SeE?4yBGHoUIixtxGP;vHa{ju?N!dqk=76rBiI{IE!+9sr92b}L$*^9YhZu@pv5LJXNFYZcz z8i@=2!G5Xi-`2oVFyaks=yI6fop5`dQu)yD7)V%cZ4^j^VNN0w|8*71+6xUM`y>NMFLqNPvW6|r7Utv-z7E9R4J2vO+w2_9rLG8;_sK zxdlU~Fb^K6;XmU%O9A73i8X2YEDKfyXgc@6ulcKm(aD})NV{dywv?_4NJ(0j*z!OX5dC})0EzOhH+?^Am|BW7Oa;b1huwvk$SoxK4#o#hGCvjs+WtC7V*L| zySjTKVm^gZn{zMLT-%Ko@wkF!C(svCOU9Iy0f=m`gzlMJ#+C-Mh|2${kET$sosPBb zZ8EI?WXk30Wa88(Xm#fziE_EumJ4KMqE(fB&VAk&UU7G=+4qqvQFXE$Gw+tk(=N(tN{h}-wa3;J-S zM26b6;(@qA_Wyxs{2Pczlo8twxbCLpmZ#I)U<2}C+Z5M`U>sB`WoF0+&uD;Vm*(h+ zmaRSTG+p-?bkBW(5h$Z67H5sq>I{3pPRVmiu!gA8sk zt&7^Bc}FvmqY?5ks8^{)e!MPfJ<(W+@RLl$MFT#@UumdV7xfnLG&0tjctUp6{KJ5{ zd4?)^t5%Dv9=YtY)3j@r>C1NnoyBGAA1A#i6-3^XBRV%KL92tV(95eHwSu4ClmtD! z&TEo>l5&!YeJuQODG|!3oaNgh5Of9fgca{|3QO?lsmXfcB?LU8*mCokWW?mQ~w;Zn{{hO>wj=QLnE z8}zWqZUZ4x2p}x?G!eLL1$BxX3!X?Sedb=aNzR9cpY4OzL}sIhvMh=|Z;8=PY9TX> zGWF9J;PKHyew`Ha>f~bE|GFEG#&Mm%rL7E2I3(xPCfF~YMt&9Tf%hhI@Fnfig>o1F zK-;}i%F?Iz%gG?QYJ>V;4Q=Zz7BLyw{WmNlvn`?pvUhQI*j?GeElmal*}UQo7&)>l z@}67p_$P4`9hn0)-L&g619$Pw&w~;e8)dUne+hq2!&iWB05sAL+~nitA9xG2leA*? z|NNd4KbPMPa~Vmp(HP|$j}GZ#rx)`22E0|0Po#6E4$i03XGxblyZhyI{p~u@G_#;e zI7#B4^wqYvZrgA8#mK-UrsRn&YZC0lOo!jOam*4`n?Wp~V!fOS;A%FZI40N``D_do zHvc%}0mv3D-(WdYGy@8B4X@4{JkEdmB8U$w>FtI!I~`rUbzbu0YdiRlPM%W3ApV&p z?g;2-P*`~HR`vmFp0v9nP`DoC{RSDCDt!$0GoHjs@v3#Klt z=YCtw?LSfN#SB{w+r}ODiP2jVc4PbRLxk&4YOMSM%9+fn;d|U>=d>xdG7;WFy zBN(lH_q09NhlpdqeLTjK(@bl|evC@kOKdQ58-CduvP(f=q+EcR$L;L z+JB&MAVYYr#80~rusTTY57WQT;sZi^IqY*(8nqqK&fREDiVz2@XG4lm6|3i*0(qxK zSmjSw{n7&9YFyf@vwNH(Ju?)xJ&olnNpsp~rLf_9O1bMA zY@argRcMXEols2Y-@*H`S;^#c7uwS~eIGgo6a-kjJV=+CWm9$!Z2TSZYW5(-yiFJb z_6O#2MzxoMsBT+dZzy$`M6tgZFEVs$C37(l&n2Wvr%ooXAb0g5go`{24aL3xBd3N< zJzKium{DzE7L`@Tju{sy&G4UTtO7(;O|a92mf&)xOquF*O~Mefm zi@A+B0e)as9+}f!pOVxmGX2wUDGz~~3-!0+ZLs?5$IC6{7I4(AJ`7I7iVsqkp;uWg zg`hy*<&DIdN@^B)fj;vkq5L5FoEE*=*pi3vUZvU45(UYiSn#%`%+WjOKblFt;rhgy zqYv*1)vTz+rHxO!P%HGnyQ|*!YZA(Qd2$W1R|)c{pgbeA|Gr-8z))j&i-YTP+N~}9 zCNJC6A`R*T8mRecM`@#fBzjf%)@<%nWw`Kr?4c``fcVMT6r4uAT2M0(o$h{N6c2xC zCS+^)^4Pl_gvRpd4_CqI_0{nt1##fq%uAEZx7-rWhu zWEAkxLJf?)!y@IuwcyxWd3sE^Am+X?K}E@KxhW;q;3D&i;U@*i-80Lua`04RPeSLv zJ2GQSZK{l5aj(5vmt%cpgN_3s$*dE>bfP*=s9lpTe#gAT$Ws3rUk;h9KmH)M!4iU_ zKxdxw`r(7F%sD1&QN(OxACDC>Ri*#CtF!gmjH~NK^>IYTlm#G?qQy)^#Kp`Jno=wCWoJywa0m31=HlNhk>(RcX zf+0TX#s1rhA~%dU%@I3#@p7@kql|APHw*QM9XgwDMejbi`i=mcLz6qxOxWJ^Q@!-@ zyA_THmvPv^E>IWH(@<$g}~Q{@&w z5FGLOHeLvoIrX#eSnz7ik6367=M$&lMC!|+XDAQxE+~GC`3igCul8tNHh9APn%L@_k^?J8^YiDaF1q=%t3q~jKW7tHRofG@>4hW3h^b_dh zt=6e{3LE-I=Dyxtgm;QO{S{Y`oQv|<#$*}VT+M&A#Az#t5{9RacCYThFel=re| z`Q_-?BN0+yuY=*a$};6kGQ1VY%B!C%_{;NtP80ZxeIRRps^E6{pEt98ClvbD_G}p_ zdw?3~;U41W4TGldvJc{2&!DbS#J_Rr~3$jlQMO(WS3#HQrxAdQVVsxYq8EQ0C%V#E3p6_N|M^y;t{JGD%+bS9EfQ#_B zOKyc!-|=fc*erNL8xIh$ehu30Z$Vn@;ZjwQC0;N$(MyF(|BB`uI#Z7rP6A_rI^&b$ z@{~X!&w>VVE1qVc9`c2#p{S~$QUuqo=ByXht40`9?v{_!JYN|RNwv627 zkF*uk>2#DCwOA*3kJ7k2jG84rYizsY(Q~Px>_@D_N_nad(pE{m-n*Q z?cCmU4ty9os~Yy=zZ5I_ot)PdC$lp8z**rLI@*{LHwDQi^qPUq(vVkFw5| zr5U-F0Pr-;n3CSrAe5Ozm?3DpeemgTeizt4Q#H!MVKnWg3faBRbXZ3C2r!#cl&CG1 z!F|Jo;Is_f^r?T8yj%Q)z42O3-zc4wGx~dq!^6Oh7J)T-Dr)o)OSc&^3N!?eoIqyS zh)A<67!MRo7lBHr1d@lh31RvO$cv?h>&&rZPVZCIO%)XitH9pc04viyqnSIgS1>+) zpxyH6!v41Zb%2q_@xPC@>rrf9_SOhqx}OSGYva}0cHH|8+I}Mzme`mE?+4Kz(pYxa zS4%rU96(+W1ixBd21|TXZhS-TCKJ4~de7gt%S*hW%{PPvR;0Z zrr(^26njr+QG%!SP~NJ%H1Dn~#})TZwct(-0xQjtDt;d?RXF5NmAo|oB7N9CH}<_T zZnFN*d-TV4x!&;UnT(7Hf{Sa>e4aE;4)Fbkp<<@}sf%%~9LsAu1ke7ie)I>xd3PZB zgP6o+}j?O>&7mxA+3 zEmC;+AjKE|umjKg1${Fvki!1XJ&%_A=^5X)}f<&A_L z*`P(C;&GOYe6G)h7<{`H>0NANPyFC_j}SI}@ruJ4tsJFA@C*I2AzAY~WC#+ijXd&b zek|dr3~uvFZ*cJN*S=b7Kz^{6J#wDiC*U1=vVlOTN0W?-!^i2Nnh-V%5XJul^1*a3 z13|E+D3~EY6u$v%#?0I5r7&+>;~X4m=m!~#Qdc>W6yJ~xB~7%N zpUGJ2J-n}_#j8mzO1YoHA#b243J3cuUBN|gy&*Xj6}{Jyzeuad%vqQG^>?-!Cx;&~ z*+)3`@p2C+6PTBP`T*2$YO6Q$wykhJg7J96m`m~c@1SVqWqJ%}f$3v`ktG(uH9cR= z`tZR~jb$9R#Yxm_1oxd-vS-Wf6`X$SUY< zbO3Iq$J7?5R~UUhb$vQc24-11n;|a4(QxNy7NuaE_$V-&YkkHmUdjr$=90ZS7jyi{ zzaH2eXk2ae_BOT2g^^UDA~K@azLROCXd;$L{ z=-BFMf>)#yR8z@IRF&L%u@16Ylo|c9v!e|O#ZE@5hulE}f+Xu~93+fY@$M=S_-;ZK z^l-r~xIEdVx)t9}1Vz3Du zc@J)%@sINH2iAI~@19qPk2+V?0Kxqhm?&6zs0LbD736*_RbSOgm4dVZ&p>fL9Xuwam;lROkZzUiImwsZVCqnzcfkjg_(Ftbzg)1A9_m{)ISH-1{{6iFvdQd*g! z$f(LHvaYS);q(c0sm>e9JT2NU{zas+F19@=taE-L!cbFZEjXi?N;@p{F6X#Q1HaUY zrnjCf(^{|*7%UY&ENLoSq{}JzJhIn zpJ-`W5jt5CZPYZ`-U?8f9-I3#ZX-s~e3c%CSEhbbXOJwX{QaCPHj6ap*+16v z6+_jP%{@sc21P+4A3Zs1jN-|UogLH4Q2|Vih@CC9-#!Xd%hR0ule*L+I+q_BWq@NCsuv- zF5m%Spo>WNv~HK1=0bfsXOWMNL#O=q90ImIw#aCRBhB45H94c~aojSJvH{VnV2Lav zPYs&myNVD+Zo2g<`Sxi+*ps;={u3xG*>iB7kkI+7nf8ZxUZmK*7WgF~9z{#b2~LS6 z(RM6zbMHFF=kLF5+Ri^ZgbB7qx(wKEU^?F;EO$6A-OnG%F03drEM71zCX03o`*n#( zFzO~%TXc1O6s_`pbGzOZ6e0bGE6rMgWxg+NEJ&sNLVB1dMgIqo$*<(15WZVllZ^NL zzv-NRNZ$N<1bo_H}|QG!yn*OD;!|Y)to#*wfLL zfZDRx8$N2F|u=GA5>8GG?L2$I{LqhVlIDoDvL}Swbc*QFk zMoam5TkGl9HfDEa&r$=#(rxP|!M)iM;Ucro;)-rH&wopg`@hiRm8Dkz3XPz&4euT_ z3x53LHHQ(uyo#*WLHCQ3Bbh(=V?l|Dh+O1^RQRa35b3K7g+yw&3O@R~fEKq3)#@zz5WPuHO zoR~gAqeQ()!FJIL91QDa$m`P=1LZMCuO++Mf17TKq_jXm6jh>E-V2IK?R4*@+nxyRdK4=Xu@B9TWL2ljQg zbBfO&&~T#Ow0wI(Uz9nW=_ZaCr4AUJ(jCl2SsK=niId~I%KrlGFTw&XV9tTI=W};) zQNUcql><>hVYgjru+e^4(RG*6z3F4PF(TtD7s0SqD_sR9-$kx_c73b}C(*kVE?158 zsWK&Mn{S1M9+F^SbWHqi_Q{eR-bon5EgnSLx;7u41OFew-a0I*FYFo?2}Mwll$P!; z$q^Nil5V8CJ0u0^ZiZATX>jNe>7Eghj*%S6A*5s8L;Rli`~LX8=eoA%I_x1l=j^lh zz1O|gx}U9@#7&s_C_zmaC#q`R7A>Za32U_MiMtzs_4f$ju0_jQPJBm*?uBXqRX>Mk zpk~HUz>annHFpl@zC;eAF4j>FfJmwB+o9QJ_q?m{WN1q8xt|;dV&zM)3A~%_L!*AR zf)~IESHG(^up(E;a`>){ApLgs$*-<^@J@3>)1c!UUdhq0jmes-?%!uW+Jj~?jvF;V zYG6z#kc~TBM^JS|DkOP)@NBWX8HA;NnzJW4xf&^y4{3ZfkOsu8Y2Rx-QqdTRWA2JT z@_(-@UT_3=!uUSjUtY5$>m&N}3(9xRxio@F z7#LL{JkqjjHV1{b$gAyCk*4FowAxZ>KfI``uI5YZ!g&`gyD~H}xn_SXYIn>|US3V0 ze7Fn^d9|7WsG$(krJ}}KE@J20+*$4pqXHEn$zw{4c!m0L^fGvp>ZVRA@32#|k#$*;VA%NB4DBi_LWJi5iopXDlUH zQJAz?O`g&x7JeD=%M!p@%ecr{b-)%KLY0Gd*GT~&!ua7_+2f4N6>x0MV@f3@^_cX1 zK>i%yNcc%&et5c4b&|X|-w-DH#~kPvdbD4RRq$(d6i8ZHijw;T#J9qWdghk)wf;#y zv3FPBvY3&Ht55Y=FI6IjPZhMnjHpxNqG{btsJL3*2pD{HluMxKiTb!t7qv?_7(yy# z{qlX7urzQzz|N^ujt%K^BKQtdo7>u3bR@OMYt@mhC#heEB_T48HHwu}Nv20FBu!<4 zaY>Ca^Lni)?{r1DXplDfJ<~bd=2)A9IJa>i;pW~j2X%2Bo#-{s%>g*M{JML}k%ep& z*ynXdr*>0$wVT;yiHTcG&#!6&S9>b5?#XP|CI7>kp<^yk*s<6j9(CEmF2y5lw+6<5 zb&Xe((~9N}=c%mSWps(jhQSKe*S)|(aTQvW(Vcej`J>5eNsy@bPnT%L^#rWpvTBx< zyg#r_2P%IILR0iCdlVpVbDu%1<)Y2p%gy5X{4JcBh41J6b44ByPwV0`3Q>dtBndw0(3uyX(IYOU zNpJON8X4N}f(gEAnHNcVARF-OulO(K7w>jY#KyBTUHwsosmUkRxqwp%k565avPQ7k z12xrZ@p-q@UrMb|gM!FnGg^8DTFJ73gzh~7X;wd%6yMRCSr4hT8TEFim%?IiduYBA z6)=VJfw+C=_WS3z#yVCqcA9HO*`p5-oa!cJU2;Z+-@9+)M-={$X8zJp-<+Rs`YhXZy1dp|9@~9g@ca_92@7V9LeQ%9zg|2x z3_mfG?KrS{a3}dJ>3_C0qL^V>yeCWC3(>=fM*F#=3V1mUn7^}g85BYUhE*k< z%Cn?zad&sRHuRR>{)BtTz1KCELWkZLJsf1o4s%*3RS3yyLuC?$O4DvqQ;n zEJk07>0_cMhw9jAKFn+2fvOBCGyZSevo0Gpg$DIJ)!O*hFDg^|{-5p_(B8>i#+UDl z850RYVl?I54C*x`-gA!7h^#lI>3+E;8R^KoId(PMv5RAkW+gtzaAHjr)8Qm~ijjiN z1C%$YRZjkcp{TN5qss{pfv;t{LPCX$iH%X8x2&HI+KF#9?A1(3H27%}M{QOTwL=_7{cfaPB4o?xr`qXu=K2VFASuwnDX+~i<9G&1mPX@yg!-k>0 z6{k{PLz@ryB*^|OdgNx<+ssycBTR4X+cu%@QTQtBvlF*-0+#;i7N=p9ZVk=?UZ9Dk zgS?7CNa%sg6+N&2M1pF|*Svb9Uy&wPAkMcP~K&l(Fhh_$`)MTvc11Z3S0xso{`A*@|M zuh)rrM$(;hM}O3RFS(6V6a}eLg^1l*e8eH-Z(K3|U$fy{@%>J+e}!PhBsjl&dYWv! zYZI2AWV9aQA08vgy^O*)4%q}Gu(`$qiX^ir7O{3!HMu*e=dspRXHSe#3*SUOnU`>JbPMlPnU{i&CMy?na-^-R z>%zkOp050rjSshe(1g2DK#J&To`2hY9zNtz6-xatEBOpap17JGx-ADQ*q)hXliXtT zdJ|}Sa^)L8NX^vvI$CU@%fQf;v~=-AA%~}Y?9U3;C6>-JE!4Ji*4i$TFkj0zVxEg0 z`!Qc8pX@71WWE8QCS?bKg7lH_E67bHUs4BC40x@sxOe7i^JcHN{VfsJGT{W3Cz)yf zEI>B@^zBk}iDQnU$YV?hK(kO6GWV`=e5sGk&oTt5v6K6L&{vdSv#2%q_*unCUM@H- zWoRVUDrErI+&p73btoafg<7%R7bAY8U9IzmV6yMm-~+YfrdB)2oybyxZK~(USW-lC zo97@R=n$#Sjbbmu&qp)g5jwhP4&ZEs)Qt%;3d)RbUic88&XatkH4iiTV_P&+3d!p; z5stCOmw;anz@j_{yffx5;KNskIUwx5>AgS=gDzHcFNGzH_%d5sEmGMbACsQ34dxI1 zaut%`Nc-*K#9=A^>JVwYsq;uvjM7pD+`4ikJi44w(Pra=GrukB)z9H8k9oFr(I&wU zKYU&0=hziW`4hd&Q|{A+P+?pm5e6t$Y$n|+h`^dPO;0|X_G;I#Sl3Y{Y3#SpOu zK`L>^>KE*aY<7a1S#KEeZ~pusYeTcuS`t*WCXgs&II1%@w?8L$ZSP!R>jYc@gPFl# z%P_oLR3;?f^9XgQ6O`%N=y?Qh_`5&U;C@DMc)We-2&=bY8u+_e&--zN>;>=q5azK# zkhnGEkl2X3eSb~l2b&Vgrsxx1Cwk}Z4<~URT)fTLdmg>$%?oI9xa(ASxSi;f$#T8u zD~^27L1qIT++L-#QZ4@ufyLZPF+w^q?~0RF`RS@qdP->U!H@Pup9gM)DSVxFfCK@; zmPk#cthT2i?_H#NZw1(P~e z9!En3PT1$t(y}8{=5`vl3Z^KQimBB{!$e0jrd5c$STQ~CldkYzEt_`{-M?8CgYr>Xdn=Gp8T=j_MP4Q zAh|Ns$9A%%K6KcJ$aOv`IVnxS)#jx=>#D?+l+*_ZQ@aB$>z*5!l+`{6Z0oTsubQlG zpgoEf%>0Z->V@$LAmLM`D!ULe0*O8{4doYB&qq1en<(-g+)g1XBcF3GWD2l%;0etaZAD zu64B@O=Y!edbS$QLzqb`eE>J=-?Xln;rMi8d2PwF@w<+;Tbs7!O&;)Ut?$CznJ1Yc zXKXpS#O3g;-IivQ=mAnU3N^TL>C%W&a{XKnYnwmI8ie4IB9Pfz8c>*}U1KhIW#ys# zbY9(gS!=l|Thhtw>kNVvcmWdliEiD2YeNe@fQ#7ELkK0C_JE0IVHOQ64wrlUjN>Bli zL;xIqc~G850iGz&{j0+ffT3LXI-!uTz}1UD^bjHjcI@~)cFCzcTTMMZQbZR!OJhJKQlOoPgA0G6<;Z zeb^hZu$MT|IWR&Wu*9o-b+X=$^;lw(1+8RMV5V%veJWV-W(S;U`^?r~164}MxX=AL z?<3iIdNjWz(^51Il&ol9S{TpZ2#^Ib_{Z==HwfBpUHbxd_d$0+o-N)MJd@Q#MY?U} zZ8;m(L$K(#4$x1g2rBJq1R^-$*PM6923cy+D#epoWZ(O)JadV4aOO1Ogw9bjD8}eZ zyG}jC!4Y;ZD%kg%8{QKA%Zx=P3L5aPlZ$^%e;?T_U8C#o>v(PeOgm%2w#HMI1#ca#j@_vN3o3u8Wkcc6E9tG0Y?@v5N8)UvXp$tK@x z6P@G*hDixIBqwx%p#x;O9A8Ui54Y`{H?pav5yXDge}lh_mRiN|f}!>fBcSPdF*M4_ zXsnZOO>KmYZ1{4^c|saZq0}yyzIz^Kf{vR{f(ta1AsN#-WyVV5{@&jX56!kFm~HEs zZI763CzAxZl*X-;#v1^;&YZFZrSXI8wqn$NU*t}2DDE3MmI^8srU0`wP8UXPMXZ6J z#Y1%Nz>saymu+O|6OeaI@NBmML{?V=udN+bCh4aaK|WKY|4YaA`NNGz$umMRPMe~p zg2M?Qny#_xk5j;J5?NpU&QhZb888QSHzgwfiKz|o#rgLR2$1`j$uqnoUWs#fOArb{O_ZQ-*QCEMzsJ6z2J!oP*Z4aQ zS^Y#7Z1(5+#IkQ68(DAHKP-{LJZFW0=y+4nXwxsOtVK{>)>hj0Z0k(}(czOp*J-QR ztg-*aod{KhKQj9r4P+zxp@J2OWPp@0g9x>#84C zXRo>lkeW6tk~GdZY=?&poJ*#9~#1i)*=rO=oVL&x&_ zOq+Xz_p)#7as!5^a(bq6uUaE0rq@hqiFa!B4R2e3tZ)9gb=H=3*2Q(>Rx(w{7~JE} zEvxL~py`{CcyB=_GA0b3%0Z19nv44llYLv9sVICWR=hBeZ#JiD@+~z}D1Km$12(ut zt!%;%T#$2@M{wHqK4aKJ|7ciK6b^7%^F18PlRptulAU+RNI3A zpA_ay0@Zf{-E|wChi12N)KDTPC#qN9Xa+B66W*Vmz(=alSeuLm(Y}9w z--2&n=oo|kO(EY)EAR{PJ?z3R#soAwz^X{H{bpZO&&$w#nU&Z?QWc|8D^qegXVcuJ zDc7l>_6p@7+Y|q_yM5l{tF7|2Rl@{Vvc&j_@P*Z;_-us~mYdITC^YUT0ZNUaJ^udY zM>()JeJsI3j@;fBPd0HPu)oDN3NH+l1JBXNF5bZ5lTt~0@Ad<9g0ZRjHh3GyB`Y%C zZLToKm=n^d&7l3ugq+TZlos=8;`v_2X2I@$%)Na1E0rWPe{B(b^2;IJh$rf)H-K($ zhJNlcN>!HvG|d#ZB-+c>vP)i(T#ul}w=Ok9kM=>o%6wQLqx<&|V_@b$45L6!I7^^Z z#fS8}XF~-Fe;5IwH!A}pPrP*p)-q2Z>n(Hf5U-X)22^ThaAeE%(w%>k1Io2Dlrh&v za3Czd;|am=ge6{Bh+H}t9%i1!)oP}fR5J0WS*NOPYuYv*jG6W9agUalGclsQv-12kJGUL*p}$SbWt0WjHf`!lc8uu5<&AF&)1-U<{B6p%9WU1^5xGMs zCm=8Z(mNg~%cB6HtAhuyxwV*_vTp{h#)-1vYxsPc~-Wn}w<+p%W zhjc2Cdue`_f9ChnmU{V8C&}Zr57dx8$7eWj9H#4R?HyLX;9`X>sfGWUgInM*10pr#G?D*~6(Ypst(3 z)(j}u_u$1~1ESD7WgULlnZ#K)kDYU3YGD|!)qk>9p+R_bgvyxsMSWRr9#9tAD=_r< zqR8qVI15>I4>hB`_WjWT1G-IHx z?Py|8%E`;%khf1Pvpl)fhZHdwl4XR)JTPVgo-R&2Gxg2;XP8O-=}NGoQ2>3>b0(4t z4as|JhY>q*Z0J&`q*xi*imLQ>ynM_tCwBQ(Kh`U|Qilq#WOPLdU(s%~jsS;7tt*>G z;EeyO&-IFm!&}|#wd(>Hdcu#|JVeA1J+)h2KPZSQIjpw`e#W9{2+UgA;&RaY8cERl&bQn|ERws~ zZmEM^{U(npXgyv}0~;M{syYu~qr-tA_ekd5(I0XX%lwopHwb&fJ7m9;Jw!jqZ#e-1 z?C;!9Q`jz))FL|%F&VtrMgdo`qS1Kzxh*3E1za=mShH~lQM{oR@TC0UBfJRkj z?k@%`?=OJ75nCNm@?boaMa!}G9IEnET7>&j=FvOPww=XmEe^lxmJdxj8cJ#NXijBk zPA7cE^&h9tqU9_2IkXHN+4<~!)}9oXBqQZk3Hpn@KNHJK-fU&DB<%^+&%8d~8+aj} z*O}--o@7mZ{vaop|LG0RBfOzK5qg$doc+cs+-WPLd4Ei^f9O4;vVp%Exmnphd+wqs zxgwjE7IexI0(taLmRe_Tt+N%J-*NyNm2`-;=Bzqz5)!fYES+`=aoCm)1ZG)DiwW zs!qn$^QgO)>UXx%UBj%p9#Bw=V1zYp^P3=7D0S zm(Z;X4Q7s;7aSk~R3f@rdiRgDP5o=A)#551rvc*E_gfp@Q-ZxBaf1dTj~dQPve*nj zj8#WwdxrZboApWT(oyj=^RoAd^`1|~yG7#sB6VNJkp!^^>oE1$ECLq+F;F8Ir9I9Q z-NVd>z&yS}pKi}FAQmWEg^eA+5fleOQiGvJ19b4DyU3}^?9YGy*&1mO(ne8&FTLR2>jP+dio ziIS#%PMH;O%q^>8W)cV0R8!}(A6^~KUH)VthGmRYZxU$W^uQfPA<>`7nRIrfU2;c8 z8J)CgonoWoI4oB_fa|2)b}*rXclc@>9UTUoKbL1uGsBMMy~FKoI5z)PuHWBJSor6f z<})1brLS9%|NEn*pwOUA{8$J<8J8k0b@rHsO;F(*eY@1LTcJ2y#oJH6QE$6gThlzE zea_#)y+Fir?H*sv*9fS47$s7k_>T-z!!v_1YS8zPv5N!L1PT=fxm)7*I-n&_t zjw{_ZqITNjB95Hbe_D_;mRp2*Cm@*#A*kY!q43#8Rm!c{$lXmX(iI_CT18Z-ql<=> zxbf&_jyeMU&bN6zzA1jG1`pw0aDVT&N*B9C&+X!KnCFi1_kv}^U=tcUm`$|>jorwm z^01U?;~#sa+T^4YX9Z7(>s-Z|hNZHtz_!oBN?6+&7v9buFYndUbjDs8zuDeD6{S_x z7pL)YQr^i`f4=ldTIe9o;GX`cG`810eXP5rbmbptcA`H;T&hR*8F~Uv?_nCe>%HAH z3y2{Ws-s)3ctGhL)Z@Q1SHz0pEA8Ugh2h+dd|>QG$_RY0)rtZLQ=Wj?5FF(L0vUFY zeokX(q+edut3@#e@U+6^dyZdFD#?ZQz9jqVe00J{{e_QN@X8Y3>%NpeSdxwUL5}LJ zS$SKqOhYqjma2j(Od{aZ{msqV-=0ET8!9l?qnsUFj_t6n2<f_Z$(mtGoSZ4&^eqn|*CYztQ=fRv`!Ar&&hZN6De)auO8oNb= z0Z@sJWWv5jdAM0)ehaEROm>KH_q;M@zY04pLUlhkpXFYN6^%TrUQ44nwLA`3=Eh_q zA&4@3blK-LvTlJz6L&q8s|dfmvS=;f4I3N2(SN}mCn320j}QlxF|=(UP(3Ngb0|BP zkom|g`_U3Ya(h#wyq~=-rARtzK`ug;fl?qQ2E9Lk74?z6q<9Fu3=nCbFw5P)w2CBB z+p~$LxSjA1H>PWBMbF&Vauhr54&|i>od391#;GcR2?81AQ+`GZ(!VuPB@s~p=ZY;E11D*}|UQI1O*{{_%q(A6eLzM6Rt}OtWPG^DIOa;{UTNlE0@v zC%-E=+gn^D*6*!D$Z_Jm%$E_SFrZGUsOJ&Vg5bN`);;eRpueB zvnxf*X)_{KN$4~pQaou+J|l2d2C077|ygk>`5qTa8&xYCOJn-M;KOGrnjQ8 z)A&W2)!8F*MFYCQrmO#dd%Ld*0sU!QoQS%*+V#sa6XZWA1lne5xjJ_u>f-iigT&oO zq;KRxV7sDQ#x*LA#GGULtYs$C-!T@seK{f78|Us=Z|(>cqd$s-X>2fS+OJd1tfsc- za6V|dsQ>VHsA2Y^V`cklqX1obf!&l^h#%(MxYV&?q03o0n3Z`OJBG3~8TRZT`9d|Q zCTvzR2)F+yqj(NL`Az`;@#=5{fci*SPD~H)LBrf6Gf3Jb(>cu=6MK15h@vu8i?*^( zv8U7?j0Irm%VP}f&KXSZSV%9}ZBVe}G2Z)GwCovE=@*}Wx{a_i!x5a=A$2(%3MG?i z!=I^p%WPv10^5fvjrjdU@4(-%WC;j0{rA-i~rMOJ|IRK|pgr?QNLjd3iXG^t-d9;B@Gai3? zrewwaSYlA9yfDf5q?7J_MqyvZTRG|xh#h}fA>mC3R){*XFl_sQV&{eqL5IDk824oL zTs?|Drm*b9S2QYjPo)IA%YW$29Pm8`6r&rd4934cTXX4ozZ>Vg9fq2@jl!`F{OXGz z>NRuMC~e(h4^r~70z?J^aAg`9zVujri-g&wJ{yo%Tu`^0H*mb;n%m$ka(9?g&qk~-G zfzS(e-X{twY(jceWH%X}tyyBN^(ifzUvJ{}+B9tll;gJB6uiY&QEs~dHkV3TDCYeD z7gVikuF8W$67FMM&1&;^V(?>3--HR?T8G^{>lU9`GFy3JCusss=m_qTl?URwEm^T7 ze07brcp}4}mG?O~-*d6;d$_46ZI;IOzZ~Uh8Bg5lX6gc98-bN{z57!9^Sg9)&B`bF zY15gIW_G)e&LOsGy(3QLw$u+Ns5@#i!UNnZaywRXwb#i*8MdsAr)A(WaU+2VbYP5uGB{PSXB;){) z^#6e@9kZcePq?a@kIsE@m*}QNNHw_K9XSH#w-d+6L*@^1SPy6QHrK*Ex3n)W!;d0y z5QEusBsg#%cMMB`wmq47+H)R#A4mOT%!U@;M|l@~A@L1Oq>HT;X9eEiI16hi^P6WP zi1&q43904;{t#RVmv%Wg9=~D&*?YOb5cdAwpYH50+Y;)oW1V60hhDe>coEWs|7aMA zGspCP2CyuE6luTA2dQ#l@JY*dTO5$wf}UHZcPoFwl4L!OC!<&;`-njGo_EiB?8LGp zH6cN~PbxRjwEwQBj0=!*EuNRADV)A-$sX#l8p6_fv^#4?wEyN$ABk0+w?3Y@APe(3 zL){x(jZ`qpOib+2&IPO1`SKgQVB04K*8k;9)|F*;wftn#LE+o%;c{lK_S!C%AE@Z7 z`=B=~DC{$G`kouG^?Sx;X>e4u;`3n=vTefc4H) zDZ@6Fg#J+!H8RJ1`?$z-yASgA0Y$;b)GyCY&4y*;`>96UOasawR?UfY-N4%>)|pn@Ckv1hogIFUDkK;m&yBt1W>ysv#g9#D?&abiI8n zo`x-sz5{+51E|utAuS$s6N#tQzXOMUjHIJ!u*Q=;15BD&BZ7Kx)r&v83HiEFA}8hc z$`othO6Oy-G!9cL5AYKt+WL%MU?a%U^GZhLV63W-#8iRhon~iod8mm(4aSVk8=&UO z1*%IiPY)MNRO)ZkCci`Uhv#_;Pjsh6c2%}`G}Y%;QnvQcQw9L@vk>c_vcj+ zUS~LTNZ$W1;x?t!H|KE;pL!{{tmr!Tbg7#B9!uVluWftX<=9ZRMUSeD7#yfyH6G)? zPwFua_G(eFi{^IPVDFZw<&%uL!Vy%f1WI+zpc?ifumRc|&+J+V%< zwe)oG&}{ZK0@;@&9zCJ*8He>t&&Jo+ua^^dMFm2Rc?`lrxCErhhHM0H%gY?4X`QW% zJ@7n_^Dee+#k9odd!EUwDITP-tYTW`_8x4-Y+44GXYuz$%EXTl-AgWz(SCWW9jIoD z(;+KRj_LP)@O)W(7h{;2c!$b&Fzpz~nEUPqI9$TCP?lGCbLanyG_S;j6mO0!BO$9u zowGT68oLCl`0a@h0K|7i0|7h{yRjNAHsh83e-elrx8oZ?old?L4|b`mrfJc7y!?Bq zJ%=xmg3Bi`LeKE=aJdh!Do^&cX4i{@#K7cSNA^ZVE-mKk_SRhF=MnS6ub zg*7RbJw)Q4-9cu-SsvptP<_h=g~tBLIgR!GL}Wif1JEPH_E=Y7ENXU5N<$&c&u>VIzwZ)&a3GsY;a{`-}LO>wxc}5eZ@j$vj^~YABX-dDHSPs=kY}j-l z57ffLC0J<#^I1Cv_nRUmZucY>7j?E{dGFtE(txWg*5({9UwuK0(QHO$5%?$Gd-U=L zUaAUv!0^4dMxXfNEP+C#=Yot2sa6@FCtr;HDQ*ToX(|uXP$lTQC)oI9_&T)1KTxT+S7zWolYZXmf$uQJEi`xsZ`8vM-v@rBZ1hpO!Z=1`X z5Q55G%n~Y5t_b9F8p-Bt!H2sse@z9VosaHM(N7deR}9S-*9XWEy80_1V^A;XD%tGP zB|Z`qOJ}GKJ)n>sQt5C5gzD^ez&N>S!s63jT_z?|?$cHKTx6oOG#?l&J zl*OubCc{I79RV+B5i<*ctur_m95wzOwRL*oczEG>d4W8FeiPtSHbe!5wP8}CYKfnK}Up{%Z#XbbT&VXKvKWZvLkR>eIwjD6P{K) zWTab&zw4mZ0eh>~@)hBI;IRMYn&3gkJ}a&{Qyoe3m7HL{HT&V6y)lLJVQqWMjXNwO z+JS(mUo$Bgk!1b->yHDkOQ8BXAenOfKI0AgahdGF^!L~O{v9*yWY*r7>g0X^_SBcG zHh|zBRR|6CGji*Qx|Tr9G~MAwC*F<6I!9FO(O-bXFduyf&Bjs7*=Yi`J7vCulAqAE z{|gsIN}+&~!B^WQ1HZ0z_js$Lf&ggiF(xq-hdRvaEU5f>3h=OY)?y=y`Ey+sY&;m z)uMeF5z+$;bcXFu7(35L8P{8IobLfu)UVtQoQJx9Pt23*(XP_@pG2TOqCgc!k$&Zd zY8#mDsZ?!P6w4ED%c+%YC+S!)Atz^ zreRFhJY(ZUWcS+`4hj^d0^cw$4RAaBiv1)IpPTm<=P`GOn*!@I=E+#*HJt21{m35R zhgLj1V~czmXdb?xfPP&*i>O+c=yOe*v0+APTj-qQ2B>MDUAdwh_o2=0L!@{+H&c^w?j!*_(zIu57 zV)e3jUXw0d&59U5dBAb|qo46f)IY0qV~ z+w(5t-`*PTPX``ftNa9Q+uFuA;KJJj?}LOj?tRT?Dh!b7_SsOZaSX+Wo5i?tuX8Sa zxcIRPa`Tj95Y?!;q>hkm^;ZaeH4*ws5VYJJ*E+z0dC&XNSo&QiYEbWPO0YPf+5`N; zvuIcn0t2l>H@xRV_R(*~cxElZL)o)OCLMi~*tH8Q6;q1*N)Kh~o2(W)Ejm4^`fw(Z zuRJf(rV*i~zvn2=pU8wHC(G?|{5H{HNpuO@^}dQ`B;$%1GU!HXv`HdwZcFW(L*s<9 zEFjZ;o;!z{y2u^AI?UZx{{(Se!l`6u=TLxCnM}e@K+-}U@wVeL;*?_LW#Q~Z7z-YO zHDrvee(XtoH(C9x*Vn$L_WdgvOAVOcp_JDFsQi94>6rY^hHy?aYIJ? zP@(VUpC3|^PRH{x69ZIOKzfmiYwtU#f?$;S1WZ^!PTiu=KEuU+o||w7z6Yv1ghmj1 z#dXx+^z|K);ELz#La6 zz8R`mGZ|}a(8;7*R1}2P$pp+h6haFoVj0^HGp(|zZyw3adse~k(#^k1_x?mh7mG3* zfxODpgKA8l{L$R=c|?GKdW*^6JG{VStosUN@)GFpGvcBPP^loOD5Y-R2e_HZFQHbD z(>ble&`D-el=0CA-+~g2_LB}{;`^4If+Br7QJnZZwo+YX(%5QviYj;cbo}lEfBcF( zw$vA^6>B&D!!b}ksEZEo7ZnSdPMPFKN}MQ}P;g>g|0%wl$d7&^#-~wZVc|I+u0jGo zaP6M>Zfuz7S*??u_}Q=t=G6YHsHSfWgsG;n+SSWiHb)H`8OJ(9IA5$r#S2Y3zKURr zx;^I5-25$GKT4ZabC3}|<7(yy?=#O4m8p9haG|WmC;UCC>`8i6mNd0yxwDap=EAGD zGyNIPZ?*a{na+XHOru%8`=<+cROYugP1fkmLSd+Gt02A2tl}YMl|t5S5m)(+K(tXRbeX-6l(tSP*SQS9YB7c?Kxf2I^IsbAg}F3} zh@F`!w%Ou7&1^PtlL&iSqsR9BiT&;UeUis2i`puBM1)M5o5~_K|&H8fm zZ2Rwf3DG8lu)Ga-q9%hz5GgHRik1EgV8ND|*jNBQ`~n@kXuMs(mYY)}O1(=SY=+$r zBtGhQR&+eBNJ{#=DsB*stw%vL$BmZIr%aOB%Co+ zUK~GH<2aSYicYv)zHQkvwucjjW9aq%5i7;eiiuR=73&}KI{q7!zt~f4Yk|giXDjUj zMB%e;RO?Bb;f=TfxM2;)pbXT~`gMsx*b(B{zX$#)UEON4kBH?<-_9#;RJ;xtZR<8J ze3?507=Qf22Cx2N+wtBpyqWwiFb+9#(9$L(oP;J?C$l-z#Pp`KIVZ&QHlZYKkg;vM z*4e3P;5a{J<5_o_UEYI3%}H%ucoM>!kHxX@>&Z*$68R{HerjE;^aMvaw!pzSsTF5U zv0eeLGXY$F^B0qRKWs+tjM^wo+8~lWLa$!HVXtkn69ktD>W6LU_zn;PW>Pspm)?>6 zSzacpx5XpfoSfh#0FSwr<2F9iQxmMC&Q@NWx5<=dHr*KM*X9%@E0ty@;ulT$$dg_; z8E(HZ62T=`Ak91s-={iXAqZ&f3g~658v)bTY7|guro4V3hiM|KB@sQSYOTYjNtb&fy6e4?TVIO+<)!Wjv%+NgB zZ$1Gaj4vIET92zcAYM))V>=xBoCEI5`0B-8rY&8rgrhKJd_7T)P-hvsu0>i^RUK8y z2gIB@(u5hEYT)uEARkApm`va_NF*%}(Gb|Zx%}K8BcmkqN&#bBIn3yg?Mj6@PdYaO*yi-2c98s^vzg=hj`MDL&Z7BUJ*EO^`4nH^dEfQ@a5IBcPJVkj;VB-M zW>7CsIC1(l$MkDk$3V^g8p~jO;)C%0_L7!Ko4CixDqz}7zHn zO2HkI9GiY?A??B`rKeU=*5?gV`ibero0~PHE0S2EDD_AxWk_vM!Yw9-0hEF+o)}3VA`&(wtO|4#?Zh2hw0t(BS z?73|DHlOa@jlX4f+qSK1zh2`bzG&?ZAVwcUvItIC6#Sl!CwZ>wu6;O39mt9X0Qm_y z`MW97Y5?cVere+OO}s(Tdum0wVN7ZJZF5o2a06?cB!`|cy3EZzQ! z1C0L5ZRWPK!Q9KeqPFw3-kl=P6{KW0s(Eih7@?Hiwj}v5;s`lh23V1cSc;Z?P5Nk| zlg`k#;_IDgyPQeMpsNzFlsSGXD0>hfRM#3i+x8o}Sme|ApCz_tVZ_E4KDHQRL zu2{pTvK8-r%#O}y_RtS@)Zo@&iJ{mM(+mKIH_|})*QO+mA4NAM?=+S~vw>D?meVTk zaBvUZ!)gcSzgoXreu zgYYMndDg94rW!#`Pw-jn$7ag>Ev)Oi-?4>mkHIv8?43!ylotI`^j}&#YwZhb;m4zh zNXZvp6!m<38(_dqqbjpYT-8>Wxx z!F8lh4EwOPy5O2FlJ`P&*=xi_m!n=4d`DPcI2CURd7v?0_}Eo@X8*rFT6_!8{GVO6KtK4Wx<77k%K(Bek%P~iDX30 z970vddNaE}ji8FAA9L9ciC{%64*DjwnLVNiRTTus7}~N`N{FM+hxuf1qZq{-51|u0 z*(gZAsVr%3+pP9qP#{?f_KX=&%)xF?J6n<3_P4jzDePv2&^2d18A?_r(3eid?oWhw z39GGui_LbgWK#|)*(}(p)+D&W?A^k7w+qT$itRjq*uOwwo0M$RGa}6>{Xbeuh5>){ zZ9O;lDb3zZ)iU}`kJYWXiJa&_b(^P$@)O@#7(L*%N9AXUS%t@jQ17c0uW`|alE zqbk0|v@s3Zw@p>S?b^;Qe9ndsHyrC`9P7>;g*JsL(%^PAa6A0~h;iH04m^4Un|-VQ z$C*O)i9+?1LiOoYYd^3TQB&?X(adEP%48MFW&Qi~-7a`>J9__b^u9<&e8gka`Pk(; z{}aoyHu~2}*oL+Sn>2SM!Crs=Ci4^sh1`SvM(Ck=7w zu1EX=eI#uwM|~}~fYLE?t*GgEG&M}KJtuZ6N?e)00tPr6QuiJ+0YF;mom-R%Z=u_9 z3$-P(*nEZ>aE8#WU}K?YgS$LUYn`B6KOV&6FFZap{op&^?|dMRjn3xU0hA`!m*8fl zO0y0P{@T_lv2im|e_aAxhwbanDibGzjD%7Aqo1}h0Xe(fDoEOmd-BS|PO5$WVnVw3 z%9TE(Ic4-%a=c<@;4zCK&%q?0Z33d&`}-Y{Hrq>>VE^9$x!%B}2&K2L%UVh#ySkE6 zU`++gk$7cAIF!sX0eg3L2S(sI8ZADt3zrvP0tON|`rG&i?_fv7V*d8~be~p7TEgP@-=>sjG@HhrLd- zN6=8scju%3hq0@Uis}ouf=EayUDDm%-QAtiDJjw&(%mT_-5@1hLxYHPNlTZMz|6bE zZ>{&wTkEZL9q&D3Fmum6=lk~e?Y(cuxlAN*<|3>JYR`v@cx^Xj~a}1?lZ|>CL4F$SF7EV!S#$Qr#TJ|w-TuYF# zLrCBag_g8rs5O?ZcP&ZCOc<^^qrtx3k-hSt4Zi_>oQ3GDW1^BZ@c#wx0voeCR&+T5 zSz_gAeLez?cf)MgW#1;75za6a#FFMXY>$Nf=^Y`Yen&3ue*D>lrcstsVny<4*W3nu z8D`f;(dcSJjS=$f$T>}}D5@UB@+$nz+U6wx#l+xMBG=3DxQeY&r`r{G4EioVuKGzhCWCuc1SCXrYAF?_oS_O*B_8pypb;VDBfok zk{q_WP4wz6oesl!Z+r|$tWNOP{{;IJ!47T8bOj=L5gPCb<`268Owo8}$OB&6L*V!d z=RbV0q7#^*ezS#VNBq4H^1G02u){WF4_ti&v3Yped$b z53tiFlk#D|Bl^7`AWj^OG#jW6;SOry-WU#$W=bRf!b)YDUgR#X<0MH#MUg>h$(*_) z@Md@SNrpnx33MdaWtYVVf5JZbyICtsWQg*w4~TbSk#>CUmvq04%8t3i60OUVo2n~~ zem{pd=In`vey^qzveDy34RE3LcwzVS&f~?F?YDZkV(k>Yff^SJ#Ykk?aC4y-we+ub zD^1`}w6?^7E~$UR-?| z!zZ%&6({zIL0$|oSMYwFo9p|m07eQl)ir%hoKz0J#{)lA0znK;K}0LWN#|+vIi^wv z`A05BM4EnZJ#|=L|CaD+x|LS=Bl2>MY}n*q+ae9Y?-3Bu7({! zKv;c=!s#cJzx|+2z~6EGBIW?FF9oz>-k%K>XR z)o-CpUKt@S7W|yg|4CSxwtY!IyX>Z~vv_=PYH*v~p0RzGeRcD0MASlp9&w|9ZAM}l zYYt`F=LFQs!(=ca}_P~dl zF7G3toPc-S8Y{aS>b||H-8Flt1BU#BUTPltSdu zegrVa1Ib))CHPO18^JMa2)x0xt^{YWTOKBl&48~X5-JxrIy z07Yb}j9)9`ohL6J-yc>u<*3X=Z0XZDw?rMbno?+=@9vNGr<|_f^%5HwIQ=h!ZDOTM0A~N{$V-A zyHJnR)1$87O0rWo5gY*p?d-F0>PZ1`P2PDG&dx^_ng^lz?jrNQA(-GeW^$HSHCz74 z`fsJ!w%?WXaefDsYzxxKJGhz0pb!Z#R(YPPE7%%5(baQQrmW6coiz1VTzpVO(Sz&Hne?6N=!Msxe}#Cg0-%*wWC%omPqI9KvP4 z4dl`Eu`STjz|p1W1YzOgM7ccUZIVt6M4Fc@9&1)bYwN{bwqXI|W!HQVglyzkZ&njBpS=I{%hu zZ)CN;5DygF2`{lB42VtJ-%$J?k= z?gCwD_Y=M^bes+Xw#}Si3qE0{WQ1@aTlQmnj7TREcD5Xfo}ydIfsYO`^f{Yur_9`q z(#&0Hay(oHR$CSsAWhfYa8U!pW9oU8A8lX7WmIao;co;T z(Z%8pRJV=Ww~e=JsovLdLEc_&11oo`PX^xAul#0Rfs0@KK(ImRSSejqOX^3;Xnv2x zNU>eN4&(Y}Q`)dxblkLR*dt#_L%K$n)D-OuRf*B$hMv)cmeQo#iB(RC(|Y1sH4L)F zBQRUoAe%t=IXYFBVBOCd%A?WhI#<7o4lLwlSQ?AO!sZbgn%n*AD+(I6ZywE7pt&*C z%uEK$xB9QFnFhlcq%%<}&~3#uDIpZ0RBT;Owjtb z0G}Dv3*4Ivochf@vYWwoz`!QdS?21(-6y{k=oZH_j2n(xPXAnVSvbX|2_wl>=A`Q` z>j=Ahvlg!uOlG%O(Lgh)YjZX?rN^QxE;v!h!#rG(Cc}bdY>Ax&Tv%)U^7ufgW@erK zV`D^PQAC5h%Q(d`&c)KPf}PEkXEh4`g%&QECRI+E+#t6F=N&(vZ_YcRiO^iCfr-S8 zouLyp3K%l>SK>LyLK8m0)DO3sQmKxMGdN3TL*|4%rRX#Qp=$JB)Dc(qPAzSGh4B1p zEkbhMkg0{0D(Qsqc%Em=Z@ZxOU{#m9QQ>dH2|nMeg!b^(l5Ptcvk+0ral5EgcW=*= zp?Z36)x#m`b@VTa-k?4VlTO|F`(vF70vYxLg0t&))JOa=Jpm2EjX45cVew*7NI5-I zY!HLg29~-TA;UryEiDE7T!=66a9_x0s&d1XS-RE^2vF-u<%V)z7gGq9&*FosP)%3X zEP8{!BRhOP#4e;q?9it3ym(9_oglK?bslga(o1E&dVL{SJLfWr9OG5u;jP8flC+)m z;WboliPO(!C&H$T4$)NM9MF&^?c&+en#U0ipon3gWk*qN9ie_{;$i=^zH;#dqeD?y zVCKdtIeOYSe~1L{VRB?{b87tN0Vk@01Es3qegu;y**qy^QZx4jvD?J3H+N+%z9?K%xQ`J;NcRe za(TbD1cp6$Ixhe3lT@zXqqKuw8}BT%a` z!X`l%+h!ukR2qi z&3OFQpc`YAUDygJ(Tz{G9%1?*`kWXt$&Fe;%;%`@q1kJaIp0U8)bsB}Eg_Frc?qB@T zA4m6(-1NL(gJqJ7;9sCdq5x^N0582?`Q@y$QikOj(@>Sz&&Z&u(}oQ9J8!Pvgvq;Y z@+9lo1;N;#i`**{R(JRYp4OY~J-E7fq0Pnb7Kdr1F(4i1B45RA%Sooa94u$8h7P_R z8|j1~~m^9Dj0ole7dJGR%7Q*r4EV|m9_hsYDL z_a{#4HBKhi+$`Q%IGl<|L{y=%=%1s}KgXg!2u?c0xVQ|@A)}z-*N$;xE_};w4KMk; z2t)NH3s8d*N9B@r3@n;2Vwe~qw11jE)ue%EE8NFKF3q?^Go!g^a`8|n%`N=}T2N$? z$*chdKuQ#mjz(sjCJFQ&^p8G$@f~$vcNA;&N$fRj2}IPUltl>Hehzw8ZDdnA9#w1Z zyc$=6>S3549Z+wuHkmpf&w!P0)VMmV{H}yVeT8^qV`pV5yr?SziXZon0r}^6L?(9* z%&RGDS5#_@n8xUH?I76BmQ>G-T{m$arUpbpZf22|D(^e_l-%ob`hjh0x^v|3`)@gM zlROmAT>$}vC(NzK=zJ*hZ`HS9NYzHE!rxJ>b-R3$afd&?&UE_p*p60NHFnk!Jw+5` zV87?*l)32|v9p9fAv1nnXmcJFhLsQP6f{wPSjqQ`N$I-SR<0#;o(|vrd=AKNu`~a9 zR}*IIv9SQg+dQ%ou|YhsLvM*WF}SgPEDu7O0`BYd4KO{`Sdg} z%@i8#iS8)vPCI*nD%TcnveM_TObto$3O457_UHe|bfy8qkYn)O@x-g;%#r&S5Wn~H z6S{M**+yj1WrXS!Yri}=K$}&@seh|M9ql&TMd`6i1_^g?TR;ko_#;@TT zzkOxpYD=Q&JBVVUfpbl_IQL>^PD6dJii7s!lFwvC`?7y~zn5AV!Ywal)BNn(eS;NU zo1bKp37EY&anfEyNXM0n4T_`rmwwShmKex{YYhJ`F`xl zA`5J=a%I=YUvmtjGt7@aGSQ5I*>4@GQRQ?`H?k0#Zeod~UZn!9(B;FboYknkg?Bad z<*_=gAvS??873ZYrg1)AmO(gBmi2FI5NsE+H54o{o@>_sHxqNwoa2L8Y>xa-okPh+ z;wuECn%$%`sx_>j)id02@~L2>#7uNqkI-H~@!flmV(Z4t6a3z+=FR?}=i;Vv%O^jG z3wG%Gewo|G&+G3UpRPD;hrkSTO|8u}Nx$reaLb0umI*=1TcGtyW&4x1omEj%+zq5@ zGbBvliFjyyG4C3jMXq>d?QH#w0dij3)^(_p_if0=;_0~({}BOE(w9>p z*Tos&Vk9tX1^sM$IgE42FXi zKZ=*>AJw-&vBw9#;y!XeBfIzd>eks?h}ENNKKdSCValVswO$F}gF8Wrx9|UIxn?w` z=erTL3-zqa1IjFD0sd<7hH371KH1TUT<)*r55HpKz&?1EoVZY%0ey7MaIf%{CAmI; z8(%Y=7$_Z#XG`RHwAEQ^!odg*&U}s0LiR{qpKe~kzQ1&Atdt^LN9&`rnjS8g-mm$z zb6oCB$~M~*758R>EdHJ$*H|iF&f6g1pe0GCk3=mjUgI{2wI~C9!0NsWEEtb;sDHWJnn?1_k4-|7O)6c?kQ_gGd58`5loTr*Ue<7Mu>_KIwtiFTqAP*qVT6>O#053HH== zYUL@@KaL?C?}jkw@{1fn!syN)Z7qvht+$T{aB}l_%>Q@tzuvlqY9=70V*UJ;l_)Dh zLRgao242A&8qjnU4|!7vsN7RSzb=2X{#27j_d(b4<7m6by_>Cu0Mi8@a-}&mpT36r zo7?^na+Q|ciILu&czb03oU+g`Uif=ipx?C~o`pv7b-> zqS3(8BuIb6)xok;y~s6V+jUWn_!d$Qcyo4N2?89lv1w@X*&s)aLHG2e-DN7 z@sTO6;5u<6BY2s;W;vEe3o=XVxrs9KuzYTBC?D3r_bO^gMQuwj8JDU+xFSU2oVxj} zu|e(d<3xd}IYoc~{l?*;H;`_iHoJ)0Mqr{mLhCsh8wfYIS>ft9btnsW7~kAl z*7gY`J;si9kK4*qkqdAYSpO=yfJ%Z z(=PmFc;!Z*^H|oLCL$`k5U1*Wx|lJXro*0Q^Tm#DW=cYn7RrHuq%Q)u>Cz?QM#_iV z-|s9c^KTy2z0Sw$EKuq8X&4-#w|o(l6qABCTtWy4nUZuQsnx=4|0w~93V`h%%l_9a zuJn8Q=m_FnQ8HxwLC_-(^*s_$)mwE+;(?V;MYFU*BAS!uWC+iy6_p<*NCD|aFuRN8ON;DDGF55zE675Vk>Q?DkKFPC#?vg7zoM6H_S1wchvZG!$0dv+tw&OHUI6EU*WL&W#f?P^#0$nRW|#1_VR|C zamPH1KoiZl3?uqWOP8sj9CsCci|`nGbXEUJ$A2fl z2r&MbPOYPXN+Ps)_-G|H+GOu;vQ#$SW~c<&%CcXDO4OZGBxLK6k6d74#^{pEsf8KW zit3w$Sk*$$YCXpr0y8S~nF&`z6&M*?vpD;I1=G!6*8-R1xC-Tfk#qHFe!G%|+!zqU z_1iQ_pmD`=6c?Pt)F`dJs}hB;s2K_SVjNKqU2~%7Ox!0*!+?sfH?x&j`)YurQ9Auw zl)RdLF=u1NzM1LBcSSrsM}1SdM_o64uDGRE<+qNnEUG_SP7JkYf}cxM-l&5Whi^bflFCRqTm+HbDoh9$oPf4Z zd9^7y%ihm97e2Qu^!&FMMEvy)Bj1mUwD6icl()OA)~)amG%3!jL+e-FXY)PEKQ8x_x&)VceYR_K%zKuLlbib}>kAfTBORBi(QYt6YuLTd*&fqw0c9Z{%Mq`m7D!zKWo+idgR3ib# z-382_&-R!GO+FaVXD==^hVq07;caW4(3nIXkNf=N> z=)Q@6KQ10!u~nikPKULH(~b#MPOOPBwP@1O4q(q-5AG;$`<+W@iGTL5Qg6ypv;4 zBfV@)yKljI1{j$3PjhlgnVWEm)p|)Wm?JWokPu`+4!TB#76au;< zpK=}@#?#lEIC#~}c-6%Ar$d%-?jZrD8}(Wn^{I%t+3$tsU$H`w7Usd2E2xE)pU&@x zOeof%0?N@f&o}nm7sLV-eb!+;;RCSjs@={g7raor(UWm?hcHMlR|>?rQPu3KQ@xSW zU;MYLr$yy%RNcA|oZ!$)$;vKlsLSu_br6kImX7w%0a9$&vL_$YR3_@qaX`!QcZu{xy1$pjm zGZEFp z8Hp@eQz2_vqC4i|nn+ZSw3RvqxS37wQ*FR_ua#eF>|zLxrrNbm%(mQnGDiP*V2PY{ zi=!6qpDr||0{9a3gdFE18;&EJ_Qx?ke&nZUt*JTDZ9nRG{B?hlmvH<>K(L_;dSmdg zI_VtotWkc39ZvO|Qe&H=(M}cn)MWew^3yd3TPEa9u+7&WSXyzBEd~PkcqnXJper6C<(@B!YV@g!qXReoPfMZ1M1Sa;Tiw0e`hoV=&z6UL zm&;B|w1N2=Fr~%ABf2jwB!jVa64mEwwcrj8D|tpz{O8b3wW{N+{$xtuX>8n&juU*$ zf0w5!VTI_ZOsFJea~UgAt=3zmi8wfor5#k2jIEJqf=LViLY+QgO@x#cghI;}fF?oB zZr&ZCQ9}HpWId(iob^*l9nNFc-PnkCMNqOdXylTMx3b59Tm80^mTae#Bt6C%1L9{) zREKrSMbEs^Tq_w-L_(8}Sd~#~IPx;FoG_Y$7FY^)%92M5X;jT}Z{+{xza0NGn#3t$0y;P&Rm(fNNclIV8RJMFCL zI-}9{KNXsvN5ryXnaNWWRm$8@al+Lqc^{*<=-qT@5&#K>AQx_(t`$(OdikP*rz2#U zb3}3tAvWf`xD&#=XVc?{<=NFnhjvDX2S$fWDx!Y)9BO7nLs!&m1Jt+0?QhB*7Waoa zB|ps`*{`0ffjJMVa?s`qaD%twH-FB1-T%(`gR4%RER!^hVNw;I0uvElB*U@g(L$;F zeESH=2HrSwA7H?cN`44QC>nCD_2&8&N4<*NNY~Tat&nlH{3V!38=qGqTZL3-^V2((o&Jo3e`F7A zQu6d;t3Tn=WscL6>>0Mm0;ko2@B(?cOJ;w|Axd1>6|0QSk*D zH%-Z%mb!@){{3;fyVI*$e$Iy^Uc2hnW=`x!ySedS6H=!Zf(#d7`e8s^Y>uTA4LLQFp?YVBs? zc*q&-YOKDU&yp_MXD^n-EHQ2D*GtL z`a*uW?C(h+f2wx&drpW4MmoLwnT(ty1R-AD{q1bfR32>>zBmJT>1Rwlp<-v493%R4 zHdy%|7$f6ZvvWU4jImw;V+V9LDJ`16=*1UZCp+?s0C_l9R4LS-;_*>`%LtX_+bii{ z(a*DnHOCdw4_PTKxF{)ef9fa=`KBx#8|ur;MxLtL+DAzjfjnqvTwG89GzFij!DOnB z6@XJllH;CX-0KK6%2jBYui@tmYCC$M-s_Z8=8h1PGlm3!g%hZn9_6qm@uY_a)A8rX zWeQ09xTLxPp8H;?hFC?ik);Dyn^S=`5>KvxwA+qZ--rnBfwlLDCm#0^U2)7MJFtKB zYAOmmjH&GSTu)IyWH*bnAw$&yu?%9PbHg}gRd4mCXS?IigJFKg$^AqN_J2pQI@oWg zo=+cD^yaDq1?5Gde4;AMeuRhG)5GwpcdBl>)x6xToudk>lZTF|&W++$Ar7shha?sq4!djsGklV(fq8B_2108WmJ;fu~G zTK??=RmU?@BZ`1Vsi{DU%$h(El8snJ1l4V1;F)9vC!APJvNzShvGp;79vctaZ3 z*e|TIt?^*Qf@bu4OQBSgSL$%zM&~R;+U&)CYS=2*_H?KhUE;DgE-!fb^q^x}xou`{ zG_-DP<)%kz14TbSVUza}k;Do)^5Op?dIhM-vWsaX{$dsfBjgsr>m>#l%a1(aKAEk5 zIWD(*ChvYt?Or8?cZUc?W*#=xxU2+*Y}A9M;1QF-8wlw$W2>R2ONZl%UHCX>Vml)ujh+C&e1nA zM{vh87Qi$9&MJ`l0R$o_n%*ZV8As;VR(TM?68d5s~9~W=wy148Xn8cN3(35t0=<9@B-->|%wev0;P* ziP~VvqWU90>pyz?Vyv$*z@W6(1E?rn9(qI8XE|`6j~-P0!gO7x>&Ussi8-+;UoM{K z;PyQ-S1FaeSfMg;{wTXy=0U12wW{U)t-p_%Ba5wD)OLIjI9Z;&YO$!MW%NpI&fHjF zo9VXt__xe0ZwdIL$fuGdhDVSZf-X5>=eV#<_+0PT$% zr0}^9FWf*^yfFsL4KvkWAS6QIk3ct5ThGf*BXCCC52|%x)jxxrXqF0Rwdb?qlo7-7 zYC{<7gFtD?4-LEt@LlgXp0`t_-K-RY2_s>p#M_O=oj$Y|cpi zzwJ@C#3HojcESlpc;FhnAwv{VT87;mh%x7-L>#<3-}jB{9l?Z)KP`;U5R*+UDc?~O z(Shk#M>!~$Zuuw_RrPZMY3OmGz^eLlfyBrohB!SU-g6l^uxjl67%2zPJ6u4d{ooLn za;t}t$j-PUb>DS#t-6y8rA@3BE7k?lr> zweb|r)o%2u%MbfHQ|QC}9Z|hAPBEd4G086Dnx8Ph3`+?p#|Oi(F8lUX{CLx;Y3Sa! z*mmLp*AqmOM|S)7y(-6mKl+W6RPOG3Ue075#X*eq6c$Db??Lvl%R}KLf|vjCiHUuC zDslr@S@MNQhUk0+55_@TS_6Td4A39Q)wer;I@y^ zogX^{V4eb;%HF#jMuem#KgtrS5ksZm?PZ9pw^a5OdfjZvQtusn_%D)3urPg&wowJy z$g4bY77_)L@edbkO~JbnMZ{Q%V!!2|n*%f(1it%*`;@>l=x$5BYqR?*;3?nG820|K zA)|#$PV()!3$uex9N}jjw-3|TZCR+xn8`nn znk94RlzoNin*?mfK5G;(-+iSCoHDE8&UxP5KlBewmZ?x~V209OU`VtX6L=S1hEH|M znxwN}r3)wrdy{%TSMweEO}sj#0u5lpO!o!IOKD``G|TCJKTRQYOre{;7N^L1P!0AN zIL0ZhxQxrqaIMQ};jb@v=Zbi2%3?IyNjYkTZjvdi-8>5Y$_HsZ8xMVw6_n#-V02!l zC&p8rmqnda5LM1H&?wfw04nC+=Ju5Y;|zqjD^Di7KyCX;i-6Fkq{CJ!+S@o8b3@P~ zZLNnxn#0j)-X3(b8-4sjw=T|b^{7rU_9x^Tk?dH9$!A3eEEobn3)qplDZ9gcHpAwE z{Hf`ip9)3bCcFUFB_%mSDgsg%9{}4v^m!=sIb)>2IFqHcabcYs`i$b_CtTkwBM}Ge zR?oaVT&cB^mnYGi34a*8`R@3X9 z${u$*S?}-TdJG`F=MHI5D~svYM(J^M+Ib*IZ52QM7oNfg2XPtf6=bn(i-$L;;j-QI zkPyEZrZs=5i(NA9=AQc}Q15!zN^J=Fd^ zD|En(1iLG9FQes0`jV0R$=hn?A|~*?l;@|g24W*-n9_g56INE{$c{BBFZ9jmdthB2 zimD_%`t#YA7ptB#q~{+nw{M_tK26t<;Y}ZIFUPS>R!uK(@y6L{c=H|q3Q{T&a_SYw zo&#T>4;)KaGOM$!wd1Xze_6oTeNLFI)s9dX3oUxZ5IgMS)Cm^q{zCV0MT`%^fHeD9 zXlR)2LTx|x{l0TB70oN(D;*NmscTp^Q@%}*C2b8El=BstV>YVs}ZhZ`29 ziEm}m3LjtQzH$f~i4$wzz<1*^{#Dws0vwW((KWH6H!QKLJ!aBs^2y;Jd19X*^Bdca z-wPY2j)%XL8EhOFs+;iE4H(1Rtiw{h1Q8n8jikJ!#BqZZn*9T+Y;8nf6R6~3JF{6=5g{L_~4#B`<~Y%*gs`tO*XzIt)eLS_*WQ0Tr zq1PU!w1aR;#hp>|!j*K?iZDLXrhf@7O_&FUPjthNOU~0E7TU3p7LjgVYtaZ z6kG@$aszUGq&g4=!gIrmLMnL3wmPOK<1X^tyw+cjAQG8QALItN0505Xkn{ah&mlKD z#TJkflCUg+sWL$ws*@F>jynVWSJn{?v)8A8Y|-3Ml-T?IliFTNeSAW|n)cK|nyW5{ z!ZZJ*d4dv_M5YO5n=SG1-!{!4Pty5(lhvfNXvjTT_6XH5`hF~GfD||fQ#odlqbo4A zeF?*(<%_4N^l>n`mZnxEO|=_&tZX1HVKCHUI>+v$4Y*Rlk&gwgOrxGw?|UhBTkdjM5QPo!}!J_}-Q z7p^}?`U*3(0ogeDystCj1l8PIxl#NT^cq+m(>es4h{QQk`gzz64r<$c*2o;Q?-4t~iR5dDP9B40us5R7UpTEnts z$tqwP8ov4?m^ow^$pk35b&|;31sG@K%H*W3#y#Vc$C3+s%iKJ<*f~396zXFrDM z#Ak3O5>wVaP<9@V4G(G_C1_eWLIZcS$AU;~N#z^xIujeltK}?_T6m8JJMVAs9=mVP za%{2sTfd4U`ESKQg~e4M9eE6h%Fw#t76O z^1DasxB}IhU7=QG7x`mcbF}}zFXrFU=!o7h2v!6w+`aeWNYkWieCToCR9kH z-v6SB(gP?(a4`(Lth2y*H&+?f`|>-cz^cFz2^d+8g;FFODzb>i{*R?Jf@0T4F|qv3 z!#_fdkBvWzpYr!d30+=sSzeMR(1?Wwqv?hXDAH1WF7;VIb*Y$_hAwmlC`Bx-v2s1a z;!}3aIXmW8PESeC693%q}EQ+;`-LlGJY))3TwJ zn;72>TS>Thxu1k^C`SeQmE_ctFhLtr&NJo4!Q`radEUxRGmEAb4a1L@3mng(7wvbD zv0I=GD%oKlBkG|5=<&BMdEs~4M}C-9P;iP{e$xk~c@|fl!}qWgi=Iy7M?xbDl;s{9 z5<5qJ$s-ckS75N#1ooQTG*w(@dp>h*hqx7ulNQli(2G>`SUx#qif}8-(q3&Fdw6j* zJE$bWw;s>C#bHjWoBrQKfrtW)7qp*ov{Kx#NBF`wd<19CuYHm+u42kH^o$NhN_p!i zwRvYseW2wmbx`+3{?>0F(N8YlE3KHk>o>0~+w=f&*_NMLrIjSInB20e|($x<<27Z7{HwCOicaof3~^qib-#DNMJz8mjG zBi@FEtzE-QI0f5U`@=4h1$jEJf^j;~*vwqYgVD@+CDGw{g;sjme8++j=KgKfj@cF< z)Wyu09(ree+Of8*{QZUOjE-l~T8(_K(-8aSR$O;iEAR|Fg0v~Gyjw3l%Wo9ui8Q|` z_}v)3DQw}`Q7Lcy78to7cRY>@^fad0Txbrg93OlFo;43=4fA?*6Iq+;WJ#|Nf1)-3 z+wZYlKs{=yB0}Fww)Y$7N03uBY4Jk~+XuUa4dm*Aj1j|t(m?KH4RQ#F9z*u9uy71A zo4H7l#``*A#r{lSSp)_JA1xIVXAz=*GkIy}`ti8DGL~J++!aY+kSR@M__Y!Qx7(s_ zVIl))7!7HwKpz6PyfcZO{7C+3ALw5RSM%u1W5saeS+SWMdY@Q~QYJE_L z*j7M;<4e;F@R)9UCO%*u9!+xNUx-o!olk>lCy74&gRy;ykeI}YFh)Z^PdM(dUiT3@Xt4$tq?$6IrHJA6-X%`rNRNZhELMo zoqog1Zl2$pAjz0ulSb{V)xdvL7x^mp>QbwXo_3pAJvmfyb1~>sZ!=wU4A`cJ(9v;| zdB%X!7q5pZ^oy@F8Ll}y8dOTpr7tlXIkgU&5m!G$8%Vs1xklP_m^Gg|8sF~Skh(RM zMsizG0%kR{`H*(?+bP8|TBbN}Ylq6wt82{hZ)ZN^usAM5tWin!dugI+G5^ z$cZRsmd3v=t}9osqed)x!&N><8X~3k#`|;aGiF<@k+u8_(#mFBa&$~!AlPtqoU#p(K4JGM9MFHj=?p7bFhEP#0(UZledI|JWY z^t2o6(S6!&pZ(cxg);T=a+f)#^g@&Fvef1>B7Dy_hl<}o+HO7ig@b71v03po%v%lB zbdqAAp&Y_RAqbn6-+$#{cmdgd+9S(Zl~y2wIRMBWK-Ss{v{7H%ANf@q4!0M7Gfa%y zLPWn=!upWS_Ik|J_06bl#Fm`(0P_oM=UoOK;TYm(2io&I0F)Sf8;lkTl@U{NjuJ!s z3{%&M?kxB1XKN(SL`pVjSKoL3+Z&qX5We}HOI_OhdXr49x`HuM&NZ)3)DS4Q8(>lV zNMTn{hJrhWqqxw>h(yg#)cz{v3)L_w|i9ZW;%i24#NV)NWVRCn}Py9mjjw?-g7W?yPz> z5^}pKYlgSW9|A4PJLHTpd;FhcF;kWUyY*{-hn)Uxa{I6XvEBR3BLDUJH6Y%U9oXGs zIyzVZL+TLx(iBSW4ZVe+YY-|&v?}fR%DF&%oO!lwSYK^pb_-?6Pj_1CHM0*RK4L4Z&bX>TMBUr_UMvx*i-yxO!GQ%sYlBcOAtoK zXwL?uXZFpMLEa|piy;TsKscF>2FaHsZ7V2IfIn)?f%nB(qYJ=BNp0Avp+5b2%Ow*CZ7mRW-Ml7`@?HF20t6s%h|4PAs4<&G>0VQ7=2tA7Hu*p}Ig1h26*+$V{U z2hW(1cL25A^VIJHxLWJU@(i#+YrXE|fHaju0F{Im$Rd8!nwNdH*MTEf)w=OOg6l^bbIcWd_wd~mjDhkuO@-E97NMdsbC-YUq|%z5_|Xt zwdMvoZ;|nZ(J3v>O_}+(aF|SIod$Yy6dRzaPm7^G#4LTL%$#7hZ0oVYockNHJfCrU z3m7Av06sl0P)7)$VuS)K@62z(c0}!Fle`6u?HfDST1Qf z8~Uyu48IJ2$H>fHGkH5CUxvsJi%IJ;_@I3iP%NGh_si^;$Mmb5rxi2=GKDG-qW^myFO44=|QLE}q zI|J;l5Eur+c$vJ`pK)95c-M}%Zsr~1D!Lo1R{M?)6X7(srwg{bmv)J;Rn-ZcXkr9g z3Hm%c9nqsB3j+f;0TwUW&5r}j454pGdVg@$5rOVvNtk#=U8c!!)tLR9u<3W$sl(|#8QD1umxBBp;VhZ`RKK$VQ}ii{y1WV>TqV|^69u#fXh11^pU%=i5q{0 zsQy3McpisF`3b3jb71&sy)r7-BvjLTmw4+OoX@?*>ihO6SEBhn=imPa>5<6)$MIoj za}d>c{cI`j!+!FwecNi>246Td&X5Sk98uLDYBQw&G*x=y#MQnP$ub5N;66Q;<j!NmuB_ltZ=AlKiz=EhD6qBWxv+fmrNh7-8vt zoG^NdxN~xcvJNjUbV6ajq$RvTB;$PvzzI^!XScD}Ma|8eDcGi*fqnjPF6@JoaZ89_ zlXKaH2i+^6{jdTv( zxV})WO#tUg^8s7Y!Zr)3vz}BlDiI(uFLS5g_Y7?o!yLOmch(+TR*I8-wUuEWgJ34oMKsINlb*A-V?UfHj!QFVRQ_E9mYuc|7@eH9e?0_?&L-P8O$A z6oDK;K_m|tIeBXH|NXgWTOcOUh-C3>Q)~Rxf^*yaKHkH)6Rn21-)zEm46eUz^E!i9 zCUOGqT=l%WO@I3(Z7~p%%nA~XmIGtDz?k9o%g5YNcR+Y0%q`umQPI`Nt98f3s@cJ& zmcyl%!^GZ9O!?;iry~tD+ufM_nfCjS?R39D)VRP4 z*C3-4*~nauE6EEFu7b+z8;Og~5-sUFI@PxI7RwZ8e5Dph4rVgqTju2f#+fc#own?$@H#{yT%H?`xzXhHI6+p1`ebWxbV z7x2)zU2E^Fs-?4IWk2yiJ@O*UMg6V!AYY04VC4Q7?X^Aye~+S;z-Tjs%yv7mJ~?>O z@5_?l$ju;ee2Z|NV6qN~35X(FrJ?VIr?P0fB)gxBZ%sHm2d(P-n$E125>=d?hA^v*4&A3G#il0d)AKV=)=0V>E{(-Co~J$mGggu0xmWhYmOUO z87Ac^n-wQ^fZ)}GFts;VOsSKu+F}0R5$yY2n<1}TKfexJEzEJ;myNVp_rt*-j@LoU z9C#qV^cta_U=9dHZ4%{o$onz%5H>f+{P(uk?imn@EjkJ{jD`Q<>MEeB=%Td&l7e)n zba!`ybT`rs(hZ7qN=Sz^NOyO)G?#9W?uPpY;eT(fx7ILT&c!=3=bp3ox9i(}Dyt$_ zt+;;X3EpYW_J3}; zOo_90L)F>ae(H|rWV^hYEGsx^3j@ni52gY+Kc?ZQS$eS%Zik{VXWYnb4ch zZmu~T-dJ1&t5wa5HE#BV@Vb$SdYS5=1J zq`pcV6=;a96GXwE3_D1c{d92P2PJ3xNCS|1m_i5#>qASIdnvj1LI*tGWHJ7C?VKHW zYxB0<-&83)8%ikQF^-3EjV*aHV&05b60BsA%7(usSaUyROBuh*V)Ewz#!P^*5((C= zPuc%`9d}q(o6Qg4S2gy(={Ac1{+HRCc=qkrTASuhn3|{b?GQq9JNR@J?Ki=IbLh>X zAQq4mZ!(ogQYSv)$F)NIzhwoFCZp;k&MM3)Lphj`;#edy6GyzB($~<$3W(9`sfh zz$$^{k37d+b{qJG)sLKu-I!~vfTOw07=#Ovg0uZaQCHsgLl$M%@NC6FN1U<4hhvwN z&X+)G&4{(_jp4k^u8vyD()W7R7!_%Xt%2Wlha(INDR=eF;89L$wc!}^a?Q#ZM)PVD zOv2y$)RKN18hs4;pJ{&5kbnP63D`-+pjwC|LYdah6*oKWYLkBnz&=>f;8()-E?^(5 zH2%S3>1vGGpG1OawBV=* zg1XzG*R~8V(uJqbkV)3iA}jzTVyNQoG#_@DVj!nzz>Cd3CCaOL?#@yJk%OFkF^+05 zoh2zmD54ab;y;!35~jI%x8bn9wDSW2oVuOmy?s-6Kcc)P2ZX*NAGt>nfkE+yk+bzv z?oUsJbKY+dfqPy)|2QpclOIVe9*xZ2BX5o-7Fck!k(){LhadQU1Ew784B?Xu=EIE4 zF{@v$0%!pQCu;-9YbYGD`MSG2x8a`YV_VF7%c5Aj`J@pJzgq{TnJfTnH; zdaZT4xY5t~HlxDEc{c9LyMIGGgv4(~gi}q?mt&FDJV&x!nB+M?6ia7@#Eh{6*?^;D zXT=SuSMnqD%~hXFq`^4UcwXy}c@UAdgTXnT3E=fLfZsQ=@Yx>Le-$#B^K?#mi$NDCEC z`OVH@s=Uk5s!RMzF{p>$0=pLaYc6H9UiJpkE6T3U>+a4QQ7$tifjxG&zk~`pqxJKj zGPxya7&h2wDEJqO*`jdj%D&hoP}cfNI*P-5keTlR5-X~M=f1rASM+*s&;vuz9(l>t zFX5c${&oGm*bd(b+DMys1y`r|Hr;l1x@Pd&zvqUyGJ}1^uJMl=8z>gA?P1eex9FeW zO2w0@WR;of^dkLuH9mjea&NPZk+?qKAtnutm;L>myrVzG@swtNu7&Y~Ke9fR43WtU zP&dqJo}~1l$q*j!r9XZ5HD1k!Ly@xl7i?hTL+`{!pUwr9$XZ5uOm_4wC)GjrAowfC5h4w2 z4pV#>kj6A}7rg=@<6r?*k@;Wx_~CU2o*VOT-!4be+5u4}W}1n98Rx`zcqRh}?#vUC zFr9@pmq0QbQ|cTl=D!NO2R%(`i7IHn*`qLIts{JA(^>x@jxV#RNC@MO=iD(O+U73r zVx@3hXH)wH#RCUc(`q6EzFZ846|4&5`iLQznLmD7GpNqFL(CP}TgbfQH~lQ1J9bYG zlNi1881t>o^Is^mApy+!#(-@$98M7f&yaKydTzNVusJ-i_22Q|3q%hbf=4#Kduz|x zdG*=9oN`B{9KXvGeU#Su`Cw_AyTA3J)5a}^d~&AFqxnp?l&Gj&cL0D_j6oaP_vb$#DcPDKv4tywr8sAWnlIUQkh|tPd@lx-P#1>-IqV_tw}dxY&1~g;{e)`QOuJ*37|_9D>^VWQzOk4M z4Dyj&^xQB2S@TmR>h$BQp8na19Uj>sg3jp_y$v1CL_IK=g?u_O3og&`k<@AbqmEPecfODae7m3B;StT6`(ba#F_eDkUC6tv2g?O$P zF$L3pWuy7a0@EfnCaKYIHxe9PZ?F%)-@y(y;ew&ap~}@n#-MKN3X|t6LBS^X1@0rGA%PbK-c9DeUZ-n5cM|?;?0j- zi7mvz^A}E+bOuELIW<;#xm+z%(~5=uY>o^s9|vtGa$-od`B>dGk?}~sV>})ypQ(yX z9RFb+G8ntJKoNDTUqR`(1PM@F{(~r%)DAX-hKKLSL%*0GNCWq zK?K(kVZ$HiW%(zjn(0c+$G|&+Co+}FJN`y+<;~OSj$jMG-K&p*H}oyBI@c$|+SiLJ z^umTElH<|S_yBhdv$xuLCG$)m5LOW6Fr+$@@CzQFhlmoZ^^ECYewm=wd%9(5FRVGGxaz zGiw=0<9y1tFL^a(5oBq+Uc)M@)z}yVW#V<=A$winzJ0z^lXC2!u3VbdT)vq9UaM{A zf{T&SNbjIjm$Te~G}uW-H*3mhrbJ?!Te1Z{I;2@Zs|kdNM$vvU>A&16ovxP5Uk(z^tyombV6^=wz!n~rrXj7 z_sG*1EM)bgryD$W4 zUImCT_a|7!juAfkZl6D}F>CE?heGQgFjo_0+^8t!6B|a0Z~lqLzgy;&%X7LAkkmFt z^eiO3f$?!Des9vCIg~C%cM(Y0mGYP5HTDEc9xWlmkmE~!t~<__w48R__)yntvd4SO zuXD%uQ-07oY6{N1C50cxoPH|ui6n0IzA}A^!{ogls=#O6eq~Me`dOo4uS#vq`t= zj|tJg|80-BbfEDy!B=*G`FU^@nH#*e35Hl|+JfRVc_6Om5A$>Wl}?Y}+Rc4mXaH|+ zxISSfgD4gf-(p4HA6svIuj4y$)Ao{tnaWtIX3`rcTzbs zY1aq~?^_`Q=BA71nLQ$(l*qh0qG8i`us@0zpqf+NSj@U`NFow*-S}uf0ET|&!;H(cs+ZB0{4z+c(EvSqlB=uM!F>j` zr%M*`y=_|7=lNRU#LldXG*mJ0Fy*5g_$ZR3Y%4{bm^3%NN}E@QhsGht|FEte(4tZG zKpSNq2PgHd7aqTdA45~hX4?QW;^+M?j{UlddFZ}-_+GJ13$7)N+qrJnIQw$Tc*{0y zn3HVO5qnY8K{Px4`h00(pv6=Ch<*1Ojamx3%#c63z_X%xfLC^~1vgv#X&6kckHfT; zAMVe~O8dg^&bx}0!B3^hUoK}%v3$^f5^ltFOIji+S%5jZHWb&L2sDI#|5U??K-n zzFu90?hLDKtHcfl%)==7HM0A7ssDHE=%5XLSYu4FH+aODj+kQD5m5n#+4`8l$drtu z1-NlaKsrB5*d!3)p8~Q`J9>)h!ZgN!bA*Pzq3U%48kOFa>0A~3<@oC(4EVWV#EB2UCYWivhDwKRg3GSdq`9a$e$;+f!Xi#w>~cW zkn^pBL5t3;XuG)LUVJe(CN5c7YK?n=XjfI@!cQ%GvX3s_fNXWkufPXJd zR!FzF21(u1r+X9at-44X2^RTwfhfd4shy_jsdWP7TZmBTSdz2*IsF?}e(+P%%|hvCPsc=g*QboMnx%gZ^|Jwi@*!zeW`9OevM}YtDK)+L3+ukh)cN+KrF{{Xj!DS3( zhyKW}Nru-Ed&T-q?uQ2Tl)9-^AAcDmd4DVbTajEeA*rIJAPIH9<`r7eW0k3b7TkNl z3Z;*Iu5ejEl5u1O zHnHNb)y$w|Gw7FqYYlvnAr3P(C*y}F<2DYqVme74?CDQO{VAWgt`xisukIYJ?ws}E z&+m?#Ojpq{VB$b-8ut{<^SZglF^e*McgtI8o4w(BZp0;R3F4Ym6o9{ZJ5E5}pp!63 z2!dP|h96x<(4({`_yxZeYued<9C*YU`?y`tmUn&SSp|#RGafme+Wj#q>}_Nmk$e{$ zl~4Z8LDPssqlU8RS_0Pbwm|iUQt!!iECu}>%DEF8Kko(moq>D2KfCE!-|lhW?zsfs zD@9E@c#mAgF@jfeWtyEi(c$YU`g-B|dh}1DNMoxo=*5WtN>MCz?6-bYVQcyK6JdQG z!KDI-eKu)Wa_TNLG2p?*fOK_nsQDf1wYBre7SK#Qt3;iYZp0q_D$p2OB8J(EVdxz7 zC($n>_{M)j2%{hVw2ze4!oU7#DGG{=46Xo}5`0GzMBe@oIr9i0q!DHS&cZqXunzc& zZ04Or4D%t5=p{DbK|U^UKu+SB#-kE<^=9mNFc(GnsgfZ z`~R5RG@*^vtyP0usgs1@*Nf}CNM(T5dLrvDzR$wfyA*Dh+$i2c(ysNDK*~CR?*Xh2 z0Q%m^qoN&E`xYnD$iMcc|DaP_H9v9vzUGH%VAj^3FGCH_b9rTU{ny#Ed zp(;8!yMv0SKWG|!b5>jBWi0G1CWN_HqjqjuNaW}B)#bE7fagcu1d&8~n^+Jz8!>a) zce+fbeiEQliirTSkZBUxHPlvz!waEGWi3Tif;`A1pT;e1`@2;>&9c$wic1!6u`qur z00uU%rG5!t5!MQjhE4My(o&?e!agy)|M;O5y2xWNbB70P#Y6xv{n3pgW$HDvp*affgH%R?XmS zMRmEqNB&DMq2`$@o$^njAJF9(^t%eYEKdCFW#C~Gg0M{njyu+1NW*w$&dao8d@)1G zpIEJ(ZFjC;-H*Ce3}0P&T3o_V|D6_NwK#1bCGmr8@i^MsQEC4Bpf$V?2U#uU5ASJ zoj^wEg4BS%KyJO`D+-j4LC;e1ZeZWd`EcpZbP-R<=M^7cuN0w?RA}TueHEIzdwtk} z^42jez@tAPO0+=3 z`knr@w~J>hcgynoWhEg(86|;h{p%NFwK{E{UGzk=Q>rSWJT(Rn%0=2ACGsw5ejRLj zWLZJd>qb(_M7|@gkV%o6x16lA;KNPS0spmsv9RT@rjf!yAu94~Bzpyt&(}ml$!Q{~ zJPr?Y&g1ak^3jA|)35OL3-%XDvh3lY4>fWb{(^2Jx9A{`6<&BfUGGLwwGeKQzxIcs zmq;O^L;*o-_M^bK+ww{6FU;Tn1`!aXOwh*uU?_a5l*{Xu(k1>e?jg*znL2t*BwsE9 zPufk!Dm!Bro^Kp-OIxbIf0)DxwmZeE*3AW}TDdUl-MDUZ!kOBS-n@Ryan%=XE{nb} zHR<#0d@wAZQOsN|qaY;5AJ*uozu^eY^ZIS>dN@$43Lz4Jd6-AH$fVJQ0+@;jai^ zJtS3peWJ3&=f{dgOE0me(Ww?ZDr$OIE>I{NXZ0U!0ww*qWfQ8c{!GoxM61pisH8`h zb(+j9@Aollgyzjg_2P_dIB%F91$$lN$VoB({v!=xCjVI^j>BO-860D-)g0K zZiZUz-*Y&q(g#Ia8Dh2*TItgz#5eix=<3+F(08t8XjD(gR`$Ve4^;2NJ@2~>w4+7e z+DCufmhLkp{B&xx1h=_~x>91 z!`rH8+d4-|i*C*Qs@fq|WE4KC72bXcc?}yN`g_^McnS*2>FEn*zjZ7x9Jx>t6Q3>@ zON;WaOgZ9M3#4JaAv%}*<6~jQY&`>U;%TFUvQH0k8qB{4C{6~!riaRjeZ`e-+eS6^ zU~ZqT#i_9oqq%42OJrAg`!pADjWf24hU6Kzijt{Syh|PF9eI+wS2 zvWT*+*jE?c_E&u}PdA|tF-^Id^ts=m=GN{iHN3;wUyLJ}^(fGEI2B>hrLSt5hfZqT znJe!Vt>Ppbv+KSq6G7}yl4wjzx zwV}PjkIreBfk_7i=HXSZ^?pxzroy0rmenYh4e|uj8<%Pg#N&?KX>h40t;wMzetMt+ z%bQ9Gh#tg3|4@)etekFO`{~O4Tn|O?g{0K^Zf_<}65+Kfb@s1ktKi zntdEHCU=DHDZpDU+;~-5gJO6KL9cmmXLI37#Z}=5;TT?<$)jc)>vH(>rexOmwds~t zy=S0ER1p!@D@@1S@sg}*aed8Gd^A+|$Y&LB##*CL>YH;Q;BTh_ChVqkuPGg!EZx_S zbBU-lgV<7<5>XGDnfWuR8O9OXgjj5EdKmioGVt>yjh^H6LKs73fLR9Tv5j=cX$XkG z7gTu~l^Lh|YA^&H`+0d=+QEtuVuq`S01cAt%Hq>%7aye?c@?;pE95{2z@gRO=tbQy zUyI!6^--!ZbD0|=CE_=&6KN;)!X5p?H512I;3S7qIy85 zO5t}At&rWzZ!ZK&@OFEL%!XSN2XXzz49D#6*Z<~~}+tdgrj6P`Ci1v&&u z`W4Wt3k=}b%>ai9+R?axl&rgZNZL`cec~)-;qPL5U;;?bCQOzB>R=nZ}m%LUg z8_O}Wa-<9ir!&mTr2k63{%fR&82i>>F>RjwcaDe*CG$Ha@e*dw5a+YF6sXXvEu{}U z(LAUw@LhSoC{oE!D1&I~vwnKQZbA5klJWU}S7bfBgSNWbLwV3h--!@dc5iNM)t@}r zZzD~`t6LaFAej)lrh`=+LD04_g`)er-?r)P{EPW%JINhW0wR>r(_K`oxHjRt^}FN5 z&v_y%Z3*zyW<&Zh37yWNoU_xfTH&2T5dSHb8RwX=A;d_r5mbrq&x0o&VlWrK6W+IqCf0Ayae!HQzS#BO^vRa&0CEwLOXOu z$|Nqo8HJ?B7oq;i{y z(?Tb1fLX*}7{{)k?VzW7aCorHoL%o~fnk`fIMi3WD|d5Ebc_^K)pBU}{7ICukx0cWINiFXS#GW z+BC>~bUUPzR==E9pJ#e_WqNozq>~O(5Z`KO5n&`SzN1LvGWjwfs>Op*{4*bIRxxgF zhU#_#b7hP3SKU@a?Fz}8IZ?5U_kTNt;fo{-G-UQaYr5WlV}wHx|4Jdb_jwnU?_-E& zjH0^X^&2mFCQEdgTg}H6w_2~bs_|&%lJuCUFlcG*+JVsH;kX9)mW(6r~q<~ z)do4ER#NM`ea*a)H;YcP(~qwDE{9#o5bc3ZY91G;#9~4OyKb;BLyHJJ^>C)7-W{u| zmfOvwdSHE<-B{15nmzBAO?%rRU^9`}Q%dN6%c2-3-LKu6>jOX{AT#(nA~2FK`=$?f zL>|#YG0z-9F$YK0+J?M~dPrkX>U}Wm`@T49j`*7CV)_aox3WlD&N3Nu?lTEO2D{H6 zL^v7MCokju=YRvdB;$%EtU|8Ei!&k{JR6g)LDk+N@>1YZR74`D zv$vm4-(n%cY%ATjWqNYDnn(Nzum zmU`#WhrgIgG?tj%!UoQV*QNIUJQgCdh9wxmx_0N!7IT|Jqhb*G@YfHJAQG-go3RYl z^%faZ0fr|nwB+%Tr#B46J1k@9u+fivORlHd-n-Pq;(;-yah|dNYG5%Sl~^9=k-gf^ z*+XuIP;q597yhfzGFSv-T%j*?bJWZQ-Nm=S- zioLo1%261Y6V>t2P5mJ?kky@pmn6WfbvQc8O%>eq=(_}CUR2zPaR&o?gh2TY2i^K? z?s$r+v^~-A1X1C~RAy*)-IUOzE=!Z((0c&FKCNH3pL>hKvGwhX`)wB=0bbnxDqaxb zE+oszo9PYi!!_=4y(Z6IQBU!n%F~EBTW$+EZj08Vd>!Y>67F3h?p?cig~+Nb{42bR zA9xpk@Gc0qY7^-}Y}Y|zptXxnbH#J&b2~C?9!o22(dLJM;=tWglD|}F*ujiQqiivK zxrdAPVMY!UaAM%6QgjtDaJ$>k^c_0$FQaop11FmaG5USRv)M>|)b|s@YtCDF^)mCU zHm2|DLw)^ZKEakoWin_*;?|x$3lcJZs;Oz~J!YOR5Vyt1A(X`xzCo0_c{if=)W4$} zv1k`c_2O;e^|$OU1ZOo{H2yEccM=o{2P+#;@4T_2dIGyXgu2*V()7>b{jHx&!Mdq_ z06RK%-(N3a*;3D89mUs}v&w#GcIt7+wVt4ZWpe4c%Rz0W8^c1JfoXOAXVhd0r#Sem zXI#t5ly>o=@}8hO*!4P994nmF=lkn*wAdoMWHj&BFdx8$Hd@(o*r@2DZ^h9_A0)OK z%{y?$9Mqc(ew-&6q*DDGT{NDl`WLG4@%5#JjW2DMzj@I`AC2^jEs8!{c+eNA z)f#cWZHZe+uYt&WeAup4a~Me$Giu<`m?7W0HPT75njxRR=y!Ij&`Aeg?wuOxq!;bQ zT+GKX1`r{I3tutg?wZsTyJVS)toPj|hBCE9T`}X&qqqN<9lh_Wh0fY|7y>Lt(+zD6 z((iYWVs7d}AF)-4u|vgJit0K<1*bQTMAUsVt9!h7Gu!{u0hca?3FsASa^nNJI>mZD zxq3ZhdOg4Y9aR6l07iiEe{a2Wf-P-}x&@^VJ)m9baCu<}A1-<@4hWNA>wrib##tH+ z+95C?gLhylJ;zbIp;|vV`ac6~uZxW&5w*B3&Q0r)X5Y@MyM69ycKo#|fiIQbCY>d7 zt_@Pxq5OZX46h?*lUI2=e)mdM7#YE|kXq+g8X5hK-zU~Yu0TaaCkjbQgh)rD{`mqb zxy0g+RmGtgu2jXV;c0)Ixh+}1**a}|)a;0q;LR=FWYdabPm-fWcvSb{giB?Qg@^12 zmdq+f5F+3&f3X}}4s14ekNjnG!wqk`kGyAwy;oK+%jy$Yj-Yt0K$&#vLOk6rNa~Yk z`8Yy5Jr*5U*LdWyeO-Hd(fn9+#9jNiYWqOK58tA8I)G|;i)wv;3#aF^ntlUU{_7qB zvd!mY$`mj@WKQnrD{LO3bwmtbCF`c zUFnLestMY@SM9?hz4Qsi)!U&CadJIJ_qW|*KzGVewhr3vxV6Z(4gTBK9Y*PptHE+o zcXZd}NAV}sgLF53f{O@JI;+4C@LXNagkxm(t#=jB~3(3KXn+fr|#fMUXzX}(xyor_pPB_}wz|fV4vf%>p${t{G^yvuE1g+&hgytij*U@9rzd()eh(7o|3B z)4YGE@K&?y&_ml>LdIL-8i~LE>{YKP)-8_M2?SAG)XLWkJB(>7TN;7aD4Ue1kmjuO zvigmg6cIQ~2XzxKc)Uhworlv^G#|=n!-{LP9=kLq|mlX8cS`cSB{{TIiu@?{j zmGdNY8D`8XM))vG@NkuuRS&LA zAB|;0vHh}DO@fD1(IC#ztNM4RZj05nD8oHZdeZ0X%K4F)y-_;QvA=-ZvG}@}%9@zf z@Ov_B7bR4ZHL>hhZ3?Iv8B})vw-*9cd^E0$MMzbO;N4PZ<#d1~$LZjQreYMMxeYr7 zI-CmG*m*96ajw-=Ixo9ur_3F$RWG9!@4oa4Vf&Q))?1=DomIZz8zQY}jVVMdm%P^3 zQgZH#QYq&RW7EOeOP=GFLB84~1nU1cD0n7WN`!se1L7kEajnw6{%h$gJswK}B#t@k zpV;^#>l#fo0B9(gFlI>`A(Mfn*J}}W^LaK=nEFfHLBfuq8{`iv1AGfQWX7V2Xrf1O z%JF*Z@t1mUXHG0RCWd%0AlL1*S3^A1r9hi!xFXXJ*OI=T_ za`;G6DK19rOLJnBqzix0!GHt(L(3W-_IvOTMo}!?I9DbadPLEgx>7A`{H}LTom1V=r^u z8EoKA?OC1oDR>17dJwordbq>KT9#$OVsywu$sUVhK9WKUOI~+49h_12zI7-D)yXd} za+eiJ=8`4ecwHS-9;JEeoegg$Hj_b5(v9w0qZQ#Rr-KsBC|b8oFVo<%HxiqRech&S zhuWX)DKYriJGS+VE%C9!hNgU8H}%1tTHD7d`>mvH&%&UOSW8 zT7u7|x%a(jGwAG)?m}9BD26VD7`pl1Ric9SYCp8UMma_h71S)%%ljOmILY^3J*&!y z^Vxm4@y0vMRM#1Lw^ToBOgA&!5yWR20X49|XWtX2B}9)N0ph#kj<`s7PE$yt9PI=s z$>J!Fq%DIFG6@}Wn+WLlGNUL7$R}=paVqfvUxHC+oLcCFRsZHacjIYSHRvZPsMLa& zNz>y&%5tl&+f^fyR3q{t1llT3L;a)D>4t}k)@cQGypbAT7hPvCpUi#*Eax zhv7h(2d)y|Df=T}N%4A?WBS0sCNPQino4`X-laYZL^THEIXw$Qq@^4zQa1E&`V7f) z>V653O1T*uUmU~l8p1aP*b*!Z{aXs|zSQ7rCB2SHj57@D%8v^xn95Ahr2SSfW#2j3 zM`D$mFh`s)2fU`y*1yuZ9>VNnnQ2(@;I=hv=pV1O*6LF%?VC1J<;~R;&yn zMm6N%;o#KJvo#G@b@rN#jwb1f(<6r1m?y(ul`B8|2lY24CA--(oQq|c`n6R+Mq2^y zb*k56fK?QJ>+mdVoim3Ld4dPA)fam)srzrH5k~IdDXq|p`}p2+C*BPe{5vRtF&p%X z(Khs6t8>BrSTC}_p|_ybf~GSUU5+ZD(P#$5yt1}bQbYW*v*wzIp@d%gL`Fn%g?U-n ztE_xlpJRgKAz)Kto%P*rxoUwbt=s5R=2_6cmIq>7ZOmGg7|*wf3Lb*kR@PQBJ!ao^ z^Kw4p6_=rjZ`Fou4ckUbWvkq@kHIWUw>59#V)UOdI~JSeO3RoAq#TiT_zJ=p89v*F=+hwi1Lg`V(;2 z3#_7q>*57w&C2j}<>C`hbbXFsJ^7IMS?o%Iw@ZdcMA7kVQrK#Z$X=dlN*Lbj0Upt! zb?LsX-)ni45yrjxaP?M$zW}allZ_nlN*e$0vQ_vyZjgme=8KkI0+1 z%V&)!jd8n2a-u+O4{9OBt?W?EWN=i;4C~K;PB_oabmY<@aZ)2TBq_H)RF%D27AA`+ zW8hA6p+Y^;VyMeLwu>mia)@P@vZAw0r_<%kLOkzl2oKQ5rm(j2$fPQu2~cCW5_4 zJQQ6efBhMOoIj?w=6^iSn}vDj(aJmwRFnOfhUuZaZ$hm$p+BCu2KZ*5qZ+fBSC@B? zx@=yzYzp5DYp^LXwV^^?hH$yX!h&n&+A9bc6i`JJewY+;`saMlG>HItnHSzXKf&_4 zUgJ!CgxN=4W$olh)7FuQiA;f$uZs6&+!6Gwa!8|1t3Q93(+`OXu30H5zQU&rS^qS= z*TsDIG65dV_v5O%UdoPBi?U5J@}8t$?PZ(FEM-3o8&T^q4fDDvL|?L{GF@n+(pxRe zER(&shKdQbG;wO1vhY8Js7UFZ;}*u=mL98@Hg1Mh-SF0fysX4@eWF{fIp5sM29(xU|MuvMN+f?NlzL~Jx8M%|qpFBN*L zjmE~st=F=M4+ZI`C=jhIq^l&QWA$+ukg78%B)UW-^?eml^+(AV6<*9zs}8a>M6 z@b0{Gl&c!N`m_9HVaaiRBC7&#QZD38cj=)nZOL%_vXXLmd9)gWp{=2p)9C)`c*MqF zn=sc(7TTE)1S=N=>n{6bKKW$+vO*SJK9VR5F^q-df_zq1j~C*IQ{eBmCq+Cr;Pkol z6(2`FG?WF&$qxyG8HvoFI`w8pO-I*S^6GqzV#tWWB>32p*}mFUmJ3(l+@00U(D3DN ztkPRKw5vI+qeBdcFnn`P2h6nH^V#@h_wkkpTT^peKa3iuOXJTC(K-2R# z7Zs0TjyE%Hss6bU0Wo~zldyZ<6VhI9ItxuYuk0+u}{>T zx~?e(kf|1sNZ8*p9751U3h5h~UZi0bbEZvvLq6fCUQFtg0!VkGGiH$gLh z^*S@ul9|tTqUJpWK1DƫM_nF?=-yM^|Y5EoMPL6hwUocI^zwcp3zINt)2=PC5l zySt)$xOqaiHdE8si(}W^&)c&KH@$&z`xs_6OEkvKwSg~Dxw+seQFMXiizAKr$Nc>8 z$IhZ%=u*25yHBho?~6F-1uv_<59oEbn{MLYPHp_TKQnUpu*oy7m9vV@NH^Lq?Y)}F z5oMUNmLBG>85U|+Jh=S3->|?KNzY0_FAM|*#PvxxP}@4~yc>#k(k;=Rkx8*oEb7S! zY`|NC40;1?()(i7OvOlV2%f~Q8!f$+_hOHGG6}=g9kmPtG^cvVTXPJvt8U8ovT#L$ zOvB2K3O_8%TOo}R_cA*@^TeNh+5qm}V?M}efq#fk-hD;&@hM9G||YpETse(Vv`OYpWk1^h_*%e|I zT>0CJ@!T;@0m2GK>&=J`?QhhhR zO4?ee3V}blq%U0Q(f_F^Xq~VBQx7%;wLxof5N~nNLkqF922x{5P+(C|ueB)8c*qWZ z7JX+0F@6IvAK5K;ZSmWCeHnETFIe=b^-ab4kP?5KW~;1wGgZ%Kp1SH|E+-9=i8u+s zqRY+a7=#x>g{qCXyDcbr#+9X6xku%wy>i~;ddMG}~&PH7nh~(6_ z3Xl()I`Xtbhy1)JX&w+o7X@-;G2`o z`m-N-;??MTC6m@u#Qy#cf`+*^gS+-1oK(w0-#A$#%}#O*NOQ{)rLV%27K6VR<1I^` zq4ZU?5ABJ;8T6+Wod_>pqRth@TY^lV*1yX!j}Ik27!QrRK0%MYGT@JYeHJeGMZm%r z{J2NHGh|pzMW8Is$fRcdJr77Syw?n?Wb&~v&C%_H9o%w{#ddn7ptCCde}?5~pL{v% z*E(DZdc$fhR`hyw-N@>(Si*@oQox(IoQ{ei8?;8wX7uAffGZ51a)wb}`fgBJQ+=9; zNmVipM!zkE^ARzm(-8?5NoUWKh6&01iNo+|XY@HW0q-`FgOVv6vG6#~&jVn$eGmVX*Y)06JB`T@k?3Pfb z&})LyFis02Rb9>)tfwr}{glik6c)p)LDC)XR-Xg-xkdTwcqRPY5t93-Ldml2jCsp% zKh3>f?k;M9K1dfb`?OMtH&ei8`e}Ci7InXpbf5W(_rv}dZf0lKdVw$(r-Kj~X$B&{ zz5W>qB@BAE*>=9SW+dNXP?9ns;30`NEFHg;pSEb7V6BvqBs^Ksla_>r=?i#zqok*% z_^!!BK=+@4j1JWY3^J-UuAot(ffcT}qAi1RHP3cO{NlA81qul2<-V{st+x-S;f`4}!Vvzv*D@KixPb=c&n~ z!l13U49UGbMbBT;!P}5-NGYcqRL&zK%;N}kYtZ4(vjN9<@KrhFDKS$qhl34zd$`2Z z7~6fg{YBP@10R!hd{#h|gX|-IsdzquRlXdd3RVgI0#I}2*s$N(J4b&?L&#IWA~&;1 zJ_&KNJaY-erLY%AqsjEX`UmDNZ)7^7{4Olq(hiSqU$$;v)K8LLpMK2Dm$hJRS~sk^ zmdm*eECeqYFhsdZEBuJ#Ttht+f3i`Ba8I5wj{6KmuT#*8$l|O=S0I{Gn`fAB@o~VWm`GwP$$}E=B9!-?3ys`qUq8semc; zU0UrVnHy226j%%=!#Kb{7quz^yQ_dIDIIFW@#4^p9QZ;UXNt!Im}5? zf=WR}SW#`B{oBkp;++~Q-C9^(HMG(~Ai3mC=||B&GA9ix$6POZ%++v!S4-&-bdGtl zQ+>gA!vX+p>TB%RqRLmHDe`Bm6{Sufm6Z3pTX(a@{eaNy%>W(!Sp--&cGJ zzzutY!5Z^Afp(kn8BrZU;U1eqTVp(2B|mzM1L*;+p^uHbKs>;EqLuvNPUl}pARWs) zBD;0%04fbKs8QiP18Lj1mnTCVTubiqod7Sxdq3d*8;Me~Unwa%dNNER$Zb8(c{ra+ z1bw`x?0B1u*1(Umu=U9pc>~qT^&Aeh@e4g=u;_(e#iM{C;8x*tpI)Y<%DAP^1ZUpT z{{|D^T9QwuDd^nE2Jc08{0K^1S{ksjd3^GK>6$~fxyso-dcIus z1bSqvP)@UDl16_tDS~u^WWaKgypBPuTs~stLML1d-CL&-x1eT{rmMcz9xSgKUFr~W zQNAO)J;HuSPz8|!lf=%rBYTY|aPv~;k@7lhem|3lbUK(*0?(c%<$Ev}(O zid!gBoZ!W^#oda#6qn*IMN4sq;suHnDems>E_p%z^UgcZ&RI6ggph1@XXg9vcki7N zWn5bF)fQch-_Lz%X6LTUz18KA;4q!w&)udn=eNH?@aD%ttv`#^rQ*%U;LRVXe!+SB zs}OJgN9*O1f#7>VmPFSO*%QEUErSwq(23CGkzq8d87N;`1lKSYC|zx3uV}FYm-aue z5&dk*YAm&H;f#}~7!a0Vb^2h|-~_Ye0(%qT+lm<*V78MoCJ-9CcUIv@DnH);7eMmE zNtz##ydsH!!4%cm-isl=`=4FrtS;Rig zI90eqZddcmz?MM8eBBj^L}1_6Fcxn-!zK2D?t6^V17kd1V^dtvGAROHUpA^@E?#p7 zF7+rXCnQi(tyZp$ZumjeC-kNQ@rA~>FCYjr+3#9h?RO!z(4TE%Jj`9ylge;o9NLmh zWs|@4c!=-H9@dg9w%AW)BmS*CJ$X*Z@^HHLGG)oNLctWsw1ULK_lcN+75@Nl)R?va zAB7~j_O4-T!BwxDgNoIufM55%C0coQyT|`=9*HQ8xQ(%$PPnjLoLAF^g}8N$ch=a^ zNdN^WIc(bef&+=yNpGO2#rOra_1;oK18N_3sgOr5gbK>dl{jXumv3&go(GOg_~UAe z#cjf>*jE{dn{01_1V*Z?1ZXFd?j*olrGsp?w0uZI~ z40PZP^1i~;^|OTf!Tpg&&cqUf&MEb)fB`KAvho#B^KT_(e^Ipb zJa5}dj)^;eocM|(49OJlr8rM)X7g_V1-+-qR5n{FnPzz2D6(8f9bbpD2^x&<5$@3*pLF!3^et@4ty0Fu#QBT_NI$o<))*>KOd80#K|R zhdEH}a0ED+18*#m;D7bl1X?k-iQ=G!rihtT_-4I3{7+$H@2H_(8iP1PD1eOl* za_h(JZ*bU(6GcV?1DywFpi`J2POKUHh;;UwfWD8v()hary`!DfR$KP)2$9^Mia#YS zH_%&|1|9}BF<$J|rll4cs${{7UA&7~-g6yA2g@p#M{nG(vY$38cOC{YaJ{VBbO-N` zvl#~n0b2oym%Y;goOBoz+pV|R4wBEkgEJtWE}G`=F!(>~JkM;VNK7>HV1XNGA|Yr7+y=3%cz z5U<5atO0?Adcz^>LmXXC)1#o4j3BfJ$>e)ZK*AZ>c%;|wH!*cA=A84;UIw!FlppMz z?m0V70=elT(?kxp(y3iDzV{S&l8e_a7z2#MdpX+Xxf*7TQW)Gi2um|jZe|>#w!UUo zY)k&RiXT*?>F|zKURbts50Y>T>b@r>J3+_r3@T{qIK4n0Izu12PvGAkYSw|B2$Y<%zU&Qh!Mppyv}mBD~}{#%+o$FibaW3?TVqJLQQ8I(sQ3NfdxiP9rmFpu3)6MA!}f`#~Y0T$)KD z#QihTuKwGk%Pc;@KD$Oe;!Mls^Yi)XmEHadjvzo!M~jKl6@bBQtp2e5F!_11I-mJ# zyfCA6M|%z*><0Il8948LO4t`u9-LAh%%>{6ccFE_8F+=CC&^mwiY(2_7s4y;OPI=z zAu;d3LC1UM5D13LOoUsQ{Sap3b+MaeWT|; z>qYmh{Ez`*#5j6ZGRse#_x^f6O)2lR6-#?^lT zs|ko}(;wjc=QD&G@}8Q2)0uz^xkc!isKp`&kdjw5#ON;w;afL@pNrHUh@*AfHKiyB z*_e36V7*)@cb5YZRxlR2OZdOZz8n=bDHHWP7PXiuycZ2GeKk>!$jYd|!S)IFqHEqp zJ8BQ{mYQv!oB$r_HVzjH>Mi{AHO1Fu^0WsYynt2bDZBkQiE0_TeR80|ei zg4hChchO0!@;7hYjc4JfMls^JH&){+x{0UCF3+@hr;q%cpUXbK8=F+{OnR^lTSf%i_wO`2!6w}2 zP12FHj#lX_ozOBXvN{Um&8ztfggh;?E`&eAouL5oqsC5#4!%48|TdF)`~q*u9^PXHN&cgm7|Cypb_(Kr8QF4Rk9`8;V>0S5He z0FrLR=dS;uc4J1VV$aS|W6&+3UzkD>`+oVG_^+n87_?6Ze&$$k8;O-IDTba{^bY;u zI%5Uh{eKP}Te|wK8_bq9Fj!2abR#9sT6o3@3U26m#)+m4BQ*q|2ZZ6vsa3K})eVGq z-ZdiTuXFLL3bR>-Kw!}FUa4h+f*;BAZGH7}FQ*wyf29;_UX&cu&1OQg7auo306&6n zVRX&$xrBykVkgcsgE=&ynQGdDw#@WN zxJe(*1g&q#rNFDDV9FcvpRJc+sUAit+TiV~U{oS5ypttUru1pNuo#jJsX(W>>QMMDK4<| z-3}=%c-V7bElwUdye`dL>SA=NWsrYI)n(x8Z0XL!;j%RAm2KM*h-3_j2C?apV=K`{ z#q1y;$i|e#3tOiLvQSrLXr)Oc^=XeA4TdvEm%yhHY*)$NCqxWA1+*|WxH050gL1}^V7&^THx)kkBq8H(3)cHJ zm)G8;2|1CjkMA^xV=+da=%!@TBkg*?5*^6gA=s66M}JevE@p^YI@(*|iB;xVovAS% z%r<=IwkzNhVA-$clFm-pE{Z@cmi#Y?osd6PTHv|@!f+uUAEkR@alHRj>K(l-7>;`R z<#$O=r+j&#C7z=;;bd)VyPHPm%p1rm12h&zb0sBI6ZjD9>$4RTw}pk&#DslaZO>Ej ziQB=`#^@OJj~&|CQU?8`P5tj`)1|o^mgdD_fHAXn{)w?`=wGj;nTvdsh|lqitZxl} z>N;cO_5rG+8G*PHDIns=F7&vs-MxMx9mWjEBYX;c@LQSL6NcDVgsQSHqsldkiO48= zA(33;El-lmi9X+gF-dGp~S>14Mi|#$w2bwQ!Ff?SPQ4kHUv{BxzF=9UUy^#Ggf5{{e&4x_*y~N# z$9_VF$|g`gO53J84HY#_;>qub4VJcUxJV~*O1RF2eHW-M^ZoW}rAl|ZayRm4_3p3q z$c6Cx_Gr?aBp8N*T-fd7J*h&R2inHq4doI4N{CgLH{eFU6B>g^*Sj-lROChn^xWfA=JhUWfDB+MT-hviIpQxU_$%MlJ*MpLfIH zFqK2FJ6%Es5Jo5!+DP?k{|j{w?a&@oyK!x*y5*?sSl-UjKtt%WC#TMxs2g z`y}YNZ-YH2Jd)83_mmRfeyT-~LDd5Pglwp3z23~@tKfE-Pw|X2$kI_^y=mFGc8q9n z#$5AufE82~L>u*VJ#sF9hrn{(Mimjmy-SevyL^$A0E7L;UuaO)MKX z1*em44WAM+G^Uh{39CA3vbmXv9dRcg%uM697C(aXZ@7oOmG8O7y>T9Q%J-@NwUST# zNnnf$(l<_#p&`9g&-nu5h>gPAmueYpIxQ0U8(>griJYxf`z`%9vWOzd*+k{nJ^vU6 zeEX3}%-96`*t)bD#-wS@?9ZBP(Gxh6QEhl`QS?<7g6-`OBheyS=@nv!K&4(T+pKqI z0WOg^Njz&I+2RMajr{QPud*AhmfGGN8ft7_(p25l)qa>S1P7yL=j|4@Em!_GZb!Y#G?-iqvm3&S;a zzu%@R{f28+W0bL>S=Qu{NSIT#;znn9NI5-!08U#eQw)(kUlawaoa?E8Rn8uFkH13N zK7t`7H&UW1Yr+XBsL2JfP>pOsBtdpVqy*#&+MFb9$wv6XAlVaav$}U?6=49$HQE@q zE*;#bwijGbIK=7NcxFG8!zlY&)oowMKBq+9&Y+7;dk*7!5-Tw-Kgfbn1i<(o4Pz8IpO>W_#J zU?w9 zq!t$K?)nT5_{);-VK3N9f7qEZ(Ov&=nx6J6_ZU%a4Z*8S4E8McC6o>3_Y6{}Qt1#< zfO#2?7p<`mhIIZ_uGHc&iY`Cju$shYa^Dv8w@PyMyfKb!7f^z|U3LQk%PE~awDy19 z+-5(Kh!Wh*i#y%jE8NZdRWXOETSfOU9XpF#M`wE&-_29kJ?VjzL3}30?o5Ys7CscU zT2jILXXWYLvE>p7Absr{MzT;8=D-nF-P(}oY0 zeBM0ZOyAvt@Zo^nAbBP{JKq>Rm+c$Bq|-P(vHrTYcv1oR>jD|W!+lx@pD8}K+nM`H zTC_9Vb{(wQIKd>|X!fhvYOF;IB}QwfSunIZm8DfyhF>k z3>R6rF$#WVaXs;oB6q4;Y_6n&q;($TKA-uNI$HM{I2$zTZiYK zYdXXPcgSIASDPm7L!6JlVb0>O{HiW{$n&UgbVhX`WNeZSi-^sJcQI0?CUS@ymbmT9 z`StcV+OEpl)A)>#q)9s&x9w9X44<{%+ZU=`Sv}jZgGA;;O>K{CFvPi76~(C{g@|PI!(W%Ouc+p#X3v?^ zO8<-pTxy0;)nJQR&?X5;Nn_Q;nA7$_j4mZhM29s)dNM%4sRq&IhkGm`LZ4N>yJ`Dn zc`ToM7qs~3vl;#w$U1ESlX^nGPBaSE48^yVe^2x>Q8#0vno!6gkNFyH1^^V|-XEcq zsngd((`8|V68DBWD)~55_GN$hU|wPEpzt(^WMZEG14;54m=uwh|GTc>nUDwPdbtku z00?c$^TJ_TWCaB_Q}Xa8FKfsqz4h`KHzhYxGTM@vI}5xz)83TgRDNk$p5hV82?n`3 z6K;|u8(UO?Fgiz?D=bpTe6aYe)!DFToq3`NTXQ32IzGCcy<;Jw5S*XOau2FMRhAQn@TA?&MCrrrb8z&bWJiAQh6`Ex z2`S(j;=uWd(~D_|P|WGRu(HL#W>|55(aQ;u-NslGyUOvZ3`k8_;XdE`$TFH_;n!P} z^JYLN9f#YI?wTQS73xAP|G>~8kdnfqXOah`=1@}slbqSM;=g!0Y% zgXQ;Ch7kYWrrMr7(51QYI*Ce|NT8co@eAF8whT+Z` zg;EWe$C5C<#1^efbA;%V0b_F5g%njL+fXm2Y6@pL-yH98VziEDE?`-e53|CZa4 zv_IMU*2~llzb^AXMUX92rcvUag>%0YCl^@;k zZU0O7WD+UHCn^kC(q8G}^w-vuVX*D;z|}JzOO1%ae~yO19^Q$?np58n#kL$Br#j!+ zjKmW`ZafXqv|i9DP3Z$d_q%O*4rE_ogK<@y!dqV}EP9b-wdLRpMIbMc+#g^6_--AS z15Eiby3si@0(jnuoGeJC22#-7KQeq~A}!*g=#BE9A|FxP!O?q^@Qjkwb1pmUIyTd$ zeM?$iG+egoB0r=D@CAHr{VE&&iD)!YTmBkvvdTm;W<%yNL{h8|TWvXz!N11S5$;d< z$Gu)Hr>C{=Qmj~PXfn))Jdak=b$I9vM+Y7T*DNkFEJR(F+37tzJWFY!=?#U%GO`TO z?6KeZVkkolk=}bJ-5}Co!!q>Ii1ZS#(HsSIK+uuv)xyxHn}SLHl?rQHpz!qJsSI`k z(Hr7WRGHODSh_3&P~5%(?wYx)NG=G8fV2ZEJ@Db>3?=kKPFD|U|6Mlcz7MK>Q#~bn zaS=&fQ8~T1vDS0+`Tk=_NsLG`)J&1}L^v#f@h$4V(eY$e(Ip5C|92Y$yQ0om=qsOt z-@ndZ$}4kxORb_Iq!o^LiR$Hc(x15h2zlW2Y2oy_AMShwaPGz}8M-RQHs~ir3xWIp zeqU;G#DbsBjrlp;>-U2cCYXo!p8cirkXm!W(w1GuHC&?F9goOtrGDn3JRnEygxt-; z>E7FVmIMq`IfeUSJlc_La1sEJmWhgAMY&9DlI5-vED!L&3)U{ zjSV9saar}6dC)_s>`%m;kbbhW_Nc>n4}0G|hEMBq@e<$W#Bjwn6|#Ne9N%Rk1@Rzq zse?7?lPrOrVx#j5k}2`2e$%3E@u^ke&Z~h_8bQ- z9ve@PMW;IsT_fQ$z!uQUt>H`Of0r$kym^g-uFh#}kc;Anv=yHX0>*(pq$)8;L9$fV z*UE0xPxK9mkKeowhr`#|^qgASd)=7bia z7+r#gkd3A$MUgY%#G;5V1+F+>fUOVU-B&%v1!CB5<&z1(3=(Vt4U^dG2$ee4$r=3w zyb_xzb5`BwMXd@r5{e@Uib`kL&{4Q0NMy1w1_s4p;fGbeNXa}W0ofExEr+B>M5af+>OL15lr9+KSf6; zNp~JHe6anHnvUAaer|lhKm8t7d&+||S8lLOuhszbdw^}WH!>wbH>7CYz4)~oF~5In zxBvo~iUOlXXZc;z0$ttd(Pw??Bu1J93i|Jy6}41-8&^{w`3(>;xJCSi=xRtmd!q9N zYL_p3Exc=&Xh=|*{dA>OVVOo>nNGx2#&Qu<1T9Jff;uP(H6ThOfMoKUes27xCCE>6=Jr6>k&~%B@Vj0YdYT zL|FSbP|Kc#a`Tb=nR}#l>asHMkl>2#*v2+}ewh$lOD;S?VJGO*WBYUN-)14F&uTk5E_@M2EOX8hRTMJQym8xQhAuoWs>I;chjE9BLvfK+>D78tY9=Q zSCifS^pfrLl1t~>K7Ot9bgPrW+FAbD5&qeOL(5p_+HL+*UT$7|rh3aENEiz^cM_0w z^<)#A4@s(01WhluD@bmc#q4)b=e2eEDnqaaOLCG%$k`JTUGLxPR( zGyIZ|dSw}Kt9;YVZR#O)Et;L~8|76Zr8ragB{)+FKXBR{58$GA z;UMMr|Gkal?0iwGN=?9^4&lOE_8`q}ZX^ zAXZ{+_&ockhE7N2%U8vlOpZ}kbBIS_;D=QEPjzwYGJAMiHoq%ZI5Gn|JF)OVrmtw| z(!JV028VYB0HSWBBtayfmb+ob>krXFkRD~>lNk-&z;pEMKy}aGhuKvf7J|c^y$bKw zW2_nYW&%ca6))Q+9+{TL*vuGx1fsM$Yuha~yQ^g*)(v^{BbURcgU5?pCPQO!0yxt@ z`axD0+nI#CUNOgYtNsQj^VXTGLh4RlMW9(&94Sv+BbY41J4X-O3`X_Umh{D+1w=1k z%^$tBB&k2ip8C;uobLsf09RbpR;VDxAjm6H4AZ6&6Jo~A=Li;!r5&EUv~E!?oevH# zS#P|Dt8H{wz+0D@I^YHa86o{dXH&-Ek69IEJv+q}XcDK)Lj~c#uGiqJVOaFLd0_&t z)5%#|qiTeOc9nE#vB)^%;+44jtH^eN+I{t4 zkUg|88(0Y+lG|vQd{R!3p9QIlg)k~B!TC~zijL@1f?g8$TTW?_kii(mZ2W~fow{y) zVOmPz!qTgV*4D+!J^bEE*r`n<8w7Y_=fr(0v3u;ZlI@-GL;Bqh3_n{=vr9YrY*&h0y&^&nMoB4;E|Drm*Fq@J0 z_0^NV&S(Wre+Dm4nFSM7GRH&n!(h}7XlyWF3bA-|(uEmNB9Huv;`MHsEt@Is3_6ql@{CQo$!9&6HP}h*9OI5Cv>{erqdKg|yUS$K+e`cUb>fxU(oNN_AX6!@@nNyP&-vkw`d+5^{p->o8&k#5 z6e|1-+0U0hc)~DnxpdKO5WB|gz)8}mLr#5Mx&$>4qT^qI+2?SB-!gJ{ zufeebGy_?}EhGGxAgb#usPi-M!Cv6BEvObuf$uQik;9s0>oOQgZHv#Z*}cLAbT;W; z<~5ud=7Z1?^yh?=!w$2Zs?k@3@h)F7K|N|DCP$tt?Gk|>RvOBTX0hr@A?nx`KPKo% zW2KhoIro$1at-X2o4%WMui>|KU1=TPrZ|DDM_3ye7M74j&L&u|+4I*tBbvMITE%+l zBG?8NJlCLayo0B%&4hUb7XT#U8;EGribnXPtGvcuqF6~hZNb^VA=4~Q;b{m|BoWWL z^C!7$G@|E`;A-K*nXMsIOf(B)df;1L@lJCtQU@L#<2z9-G*>W04FV$v%~9}!6I}?1 zS(N|6-R6uMMhNIwaolD^VVhQ)As*3@cPiImu)yNpUeDU z@v*4vbmtmBjmd!!ud*?n)^Xz~39*Q%>C(`Kob7-dlSt~qY2bou2e1I4SQJLezv0dC zZ$H;!92uY(YX6Cq1lis^?f;JlZc%Ml+vkZ<8n*Xc*AO$7)73SC4ZBh^<70kzWSIML z@N4M$ZLrusldJp93G%6{1Y3J2j0|AoPp%IMA#wg9u*(Qp)3w_AJ9`3iKGv~j|LVg0 z=9mf+;;fpO&G*0hjvEYJJcpo~-8)#+Q&@Qbd}tv!YCE<;c@D#QHn*zM(1l`)Ebh0g zFe2{^iG?8Ua&_Sg#i`lcMeR^ddY|E5gf3a~t(ACW=U+Lm7=k=qis;MlCi_Ay{ke|~ zNHGxe=)c{K9CWYn-Km?TeA>vSm|W|AP+IAJ7=ci2i2h4$2bRLa&eAAv3sgtzDAM1m3Q)oG zdSMf@n_;t0a~M}b^0AO4B!(XniUDFNouFq$-l9n-N$L4Nk1Y55fAr{Xr0?(*b03W7 zJU^$A6Ay(14wbeVlnU&ZWccpe?jN}C&UmI%|7$F0<`flnY7cHuSFDCey~`Y4hU|}w ztbY2q7?o7@eg>roCo3lUSP9TLS!iM!Z8Uf?z@EOabo05%p|%q?h9?mKmv<>TLu0zu z0anyl4g%NM8v%2K8KPlSEj_uU^{?%)>@zYD7K>E|D*qI>O?S1z*t1aOXnBU5lmFXS zR$R@q3yJopj-nzGy9?&+TRTKL+~chg8r>ZtM9fJbJ3Q)%QR8(LA1Jsf(EPP|HWnk# z6p}PBpFP3$Fp20>vxTuSBKAef!d9Wq#W(MPI`Nf7(hJvn z9A4-)#!EN?Bvm^yIQWkxnjuVs@}X0G?8A!u37X1%;7_j)DlOl|TA#N64&E#(jNAO! z;r@93nyu;2vAaS%C0v`zMlI2Zd?tEQG&`E5o#MBRQC|40uBQ~7Jm0rtMX7UkcouEgIsAcLUa$q*=h`_WJNbz4{wcac#kx#J~oLIEvYgkwqk z)jdhdQ3T0}h2kiy$@E#2Ox+%nkE6nd@|iiF$|YknhmMU?xt2h#T8d~@i+u1~zIie5 zeLkery?A(Ym<@5~avpA7JUf&Edrd;vxH{+bGpwH4XRkeP#l0WYBrs%B?z?#8dr*WJ zOY`c}GJ8~|L(Sv0!FJPhz|}9EU+>N)&=j*XaRp#Z!ez(+j2#|C<2dl?)$7lH1S(GiO8T`FUa1f7U zFj~y6-C&$pyuzx;-3tKB*0jc8a#OP{t8dNmx{RjgL{;TYxDtIU0l8ql41fm{f%=jVp7=$`EC0l4|$QP}b z?+P4_g^NnldyO%c%ToZzj{WTs$)G+u=&|EVe={?}h0H=jocLay7-Du%3Im=4FN(fJ zz;r8x^n`S14C`kuW7UmnS_itQe(CtpVTZdzb*qw3X}y31(h~K2g}7?zE~PG*Zu@)) zkxj8eG&B=VRPnJ9`z0r@eVDtU#{be3MmWyD=|aF7^Tw9k;!*3ZDaGFesUbv6pj@(_f88dv&s33rd_#6 z9&ZC8Z@vW9OCrkCq0E9mF)cUXWA%lp55N=?TeETez{&&g?_~Z5wX#%(OJ|Kmamth|%y2MELVrggk_S??#~oUk@d{fJ*uSQ)G$E*~u3U+Uc{1vFk6juSZK%2m&(`D<+u zqdPrrSXYsMSqNY}MOaJ!oct;6&>Uhb1chsb;qVp#?(88g~+f`i&HXHBR_<9iU&f93F4AWa4E*3L}Czwi$!r8 zU6S?M_-)FboxL0RFw~(^@Z6O_)^wyL`=aLqeJqQ6ZBoaGh090X<4=-PWIaD~ip$%( z1%k8u{37fnTO^;hTw0wk-d(kcfA#RlSF0>eB>Av7xp6+f7R_gS;Vi;G&z?e7tC%kyusq|;(J)-YLVT=O$lOe zw3?a_plHKva@m5`8T7MVzGgFiiSENsm~>GDK`dE}A`?fSz6!CY~Hu;WPrWs_LgW%Tw}&Bo8J`cr!(|g1sPTMU((x{wDSpVo7t=!0PqomV6{(&Bv%> zosn7^obhJe?Z2L*s{~|!m)ve4~t7e*e%&So4bS4TAA zKzKH$PR|=rGVD|o7yp3Z_A@#fm%TS_+W`I4;DVO&q7Y_<(zJd+S>jKoFBuRH4U!U@ z4IfRPXTE07@V-yh0_Vwi5i=wW>70)KS}SlIkl#(ooS+pfvGCHIysKuuHiJB&EgWp_ zm2$3XWaz6HxJABh_ci91DAUFz#`n*SG`|Yr z;k-Yd1TzdT_w_VGIQv~L05-$*j#ge45uQ6rR`(~b@5SxE4~8a0Y-qX=y50sQ-`8)i z#0HS6Z$~~ryfvPfK@6;P7BhM_qwZdLNxd?3RRg9+LeS_d)rjhb&Xh5oHW8p(Oo&jL zQc5m)h1pymtGeSquY!_TNv}$rmUg{v5137-{#nnGURIk^XPMvO&8gFSNyqlx;oI>1 zDL1hS6ZC5<%3RB>L94BojGlsJiKahq$4oZPaO!{Rm+JMOU>GE1gMZ$X{RF?cQ5$dl z`Ji%E_S0MCUTyesH|~vhkBE@FX~Qp#I7dE3_5=N#kZmjfE~z_R{*OLv(kn4Yap9A^ zc<7Gs*$=x#fB8Spr`AFh8!EWMBJWzcdSNKxR=N5BA>>Yfmv`!mO|PTpAB|1Fq~~An zmGi9J%3LideCtKLnY(y;Siq-S0T5CO>c z>O8{J7GH*sp*pizVPB@ui}BKj{(9?3r6|219!`Me72^YcKS`VGgh#52jp2+8L@#9g zmglRQh$1_pPu!{13zz$X%XQ^S{`WW&jL_Yk+mKA}^=+)db|+&<^6Q#~cN2Jn_REfc z)Y}aeeLfeb>KD(V8E~q@y8s0s_6d(O|0Nb4>}k&B_2s3=W`27UBhiov2@kAg0*!>6oJBrTW9&MeB6=T_PL?(02&>!TIh+(?P<=t*K}V z;N02z9T6bFeE8Wa-HSz`VjURW_yswK{p)liOv&Q88X~*0?w{>qXJ3L^1lwiSduk#NM z$H9<1u0Q}s_uW*U)SokP{ohGikQhbccPG_;a<*isbqwpka}R-OCO_*O4w^o1-83aX z{ESMS*enyi>@u)00ot3pe}7WRA}2LHi_yN7Dlx$(PA*xyIv;3cHsK%}R5f4VCukigsu_6X)Z_Kt!F7Tn6XRnni=Xxt#&UeQyw z2)Pbu!VRJzAFN7k{YjJg5U}l<0q5BUM+32N*>L3(!@eLwHSZB1xl7Kn-$6c)KToqw!jhh5oILMFF@kVyTyMZr1mtwr9GIp zV0~yQ{W{+(;l@cGS%;J6y+d60r4yo$li9C z#;tJ1O!_B8v;RiUg>0p3gOceyoCW=5AjTV$ZL0+X>KoyJT@ z=$|<_CY>K^1E3%rOcpCN^rm;0i%JQK8$h_%J4mlj&TAKVb(;macTVzU{K`11R#`G+Q7; zw1~nxDefc|RZSRB^u!)=2V(ztKUHW9hs6X#RkHRNs;Yi``88z3eYEZtPu#sUrNaVE zH5C30)G*lE5JF}K!>pq2)1mIuXqLAn(TrM3L0CYhzRLOaVZ;C!3H;axvOOJhl3n@Cy&_9LvL7+I@p}!6?(V zM_&?PGqI8{q8k7`18l95(sYzDOrRLKAd(~yO;KE@%>$4e7B>{B6E zuJ_jfs=h)jdbkV!y`a6m$J3!~Z{5-w-|}InVn)}wmN3xEo8S8wF(29vSWL{!@4)}E zEDk}9JEgymU!N4~Hr(|&Fdf)Sx;#@qCerODo9S`($G`_1l3jkXafoUO(3GCzw?UG8}vOwrN)%}^)75hydwz)g& zP*jPB-Mm>vCFVWi-B&Fh5IepJnhF(#`0s>pANyV4BO@AGR-<~Vy|p2P4@DBCS6vEY zfv~^A8V;U&Q4QY7W0ziJb-n<5qCZ3q3J3v(v1$#e$$e6SmJavG;OI0_6me-V<&{uF z01sZT9tNLBWpPBfD6*v+EWkNI*h7c<7nbjyk=SrBkQ$8 zXXGjJC-!PQnpuY|42Nmaq3wi9oRBq=STrD5Q>}pMbjka zS|A}+FhQPKpHv67%m$Uh_on-yLfnT5~jb$)<$eGq6eUR#&Z({ScDq;MP+ zXGMtAfGhUvfUcqGIm58&Tc5{Hka^vAJd5&oAL%dJ*_muBwAQF;+3T(&?lez?Zncm! zSUQSPp+~Fb9$p66MjhPtV->2+m)HL(B|+f|6=zG+^W%YKaJnTXt1Ccy%+XEu-i)|X zBIC?pnzqP3hp3Zh^y2risH$FY^YNPItBhKx(RS;<+` za5h01^w7dxLpO?#4;k+ToYO^uBeEw{Cn2VujW4lnJ0~sqpuyq2au%YA!NHMqrUM>pn);cjviZi*gu9hK;ejBf=wO8Mb*fA;T zVn|%kBS}pnv&ycU(xw%=)(H>i6hA9~3aS{&RcL0>fYa>9mJ7TNpgv6a5D-vlYKbA# zkiVnQ?DdPTNEJ`_Q1aq~>bL3hx^R`1SF1DfUqeATTYcBTsDh`zeH0^iNALe0F_ZLy z()Kc~&A27K53vK4b?4FDD!Yb7>2{lF`OV=uvN84I)Tz`5u(U znOVi=yPB6?R&Ao56eU8$sWr9W z&~5l!SFbyHxDFsEai|^8?Isz3Jt^KkYKth)A)BnCyArtuPgafNsZcrP7r&N!MrupqkDDuC9Gi7dmF|E5qYV19`(YvSP z;zzV>UZEYf7*`merA!m!VJKi<&Rab|?HOt4t{0NCjJ{o}X=Y(+A=&pI* zH9`U+rmTu9&X*Ka$yW5c{^}sOvAL)BipRNu_3C8u6llxq`mV>*mxU%qNb`A}NnzfvO^@Vfc1h@x1LXDgR{#9POvg&S7}U zp(|AycwTiY;~lzdQFMpbu@v=GYeb9EQo@*M9&gui?EZz@e1*txj~eJH?-nZPSGDfm zc07b!>P>+erocvMOk3Z8rE2XDLjm`#`zz%MBrI3r@DG+BeTZs-ilw}eg^_+{oCMcU zLk&W)Y`e>$5%2_i4;8BU`)_Q!qbsIq=&~&wpb@wPxE>$!o|`Z6uF-l96%KrexW%^d zR!gQPkyy|4QM+Y`&@Kx9+{c39A}Vr3H~kw(98=i&$aU39!sQYSrJ{6+wfywocxFSE z+I@Z<&h6iGl|i+NB?SP}ue|E|)+9k0UFFs_x+~}$Zpa&|F|LjwbeuH{<4@APgbvL7 zp(^;P?{!tCKv)dN$G;3(G1|D@OPXmuMUQl7NH?_kxXM&WY;(-wZr#Lj(kyV<*xJ6; z?P!#~Y`%P@QlZ5sAU1)k`?;=ZLw z&7ITf5~(m7@}Dd8%|$4W6`3gu=QadG;vW!>=0K!#--RXtr!pxa{vOIRn8$KLI$)5D zzfM(o9#dvEQ>zxaqK7vbT^6GKy5hb@#7#bVz;~3#xXKVMcp9_Sb)WjW&7+$;Dafd& z{jIjl$yZqD>-g!vZ;3y*-keui%Y3QAGBi*z^oNIBN>yPlbz(GQ6~i3lO5xCDdND3Y z3nbnefWfnV9;=c5vuy(XGEKvRn~eO1?hu_WaTNJUZt+@Pi8G589*dO< zixm!wRimq!*2&1-8r3rtqE`qjAO>E|2S=X?9zgubz~65&v%#*TV9-sb^S%5q_~X62 zMqxs=l1jT3IN_8r?UU0zyW9!as=X$Mp_>hGhXm-(Z28j&B{j4n67j0RMP|iFZnTjD zXnXl*KJ;zx>jD$&iI8UJ2|3@-r-c#X&Ace9O&<@nYDP%kJuX;9bE6vV$1kK3@Dr>c(Djz=z8ThzeZR^|1TkU z%gMaYi(^el9HtB%4hEIZu16IIVp@_;%J*p8=)?r6Y)+wi7`qt6qu26UtcDx3R9Stu zu65+=eYyNyTQZH)6UT{(sPQ)lqFVQ66b=x8hdZ zA-EQI_tHXfcb7t;xVt;WtvD13?o!;{-HJ;#lzw~mpFL-oOy-4T-n_Z?yZ6qF?$FF~ zE4l+BKi`;Uf0{fzy(RG6;8`KZRo!{R=9=RamhB|A!*6QtlT@RoN@00_*;6RFB$!hr zHV)+zKAh=moXSZpMlBv<(kH$%c9heb>(jKa7yG$p$+-t`AL>^LqLA}=SlyA)L{;03WEphwi6Pnh-HHv1bZz)f& z366HjCPW)$qgvSBo*t>jF{dS!IF*lH;CR31o1SNQL?OnOtbZOG6#HN z3cY24lw`AkTXd^d0PpR+v1u;&*Ds%EFjVIwzR!j;1wL@=(|VM%9{J>mqa54Dq>O}D z1qJibXdQqz1rSFlj6VhWfjZW|cL&A`o=@+`JG{67Ni=W32A6 z|JzAU!Ak1}Wnfi*6y?%Y3m))*6g*5W6x87u;vu3P+<3b*mpD1zZg1WEZC-@FB;-Q} zgs2uMiFjvz`{%mHR`r}E#pEymtf$qdshWHPZ*5`fqPJl4PfcTm#vi?-@H4`iAjDUE zs-=MIN=hahcRQd?=DvypM*)j=(xwG6@y3&Z55oFiTV7`C*76;@3oxguUVhHCU!Z$j zi^aDWtb~u5S?!1R;w(~uHyjfECnPs59pVo}$_^}bwI#|3lNMC3u>n=NLwTD5c)KlB zN3iUSn^v;!akFCSJv41!3UJr2P_cSy+xrtMW7!*hNspOgpw|l|rpf`)Ot#YW~wLgpt#=Fjbu3`8R2%xfSbDHHaBGx_b>yJuCg8~5{@j?5!O zvam#(mb;1yYf>M4&Q!A&QL-tna0qmySt|Kqd%Oco4y|l!*t9QeQM`V^cI6f220}(G zO530$l^es%)ID8s6I#5PfS4-yJn1luPQ}y>t+H-;+$IMlI`ApCtBPwr%Ou7;1cM^o z+t>n)YX~V}0!XZ6j3SEx_y(O#t(^FH1|q7#sG@THJ=wHH_#r22sT?#3;9s&8mE*;s zh&OA~btI!w9ZJl~vY!2X;@b2DeQ{6l!tJ{_zusztme_Uq+erZ-5)wa^76(GNEPrjg zhQKq#<^5SfDCVjf)4R3Dbdvb()ny-(BHQ0Zi@RgPDOq=yoVgvY<1^vZHJM*bEQj+i z;dOPMhd=$&*U@RE?W`B%@gZgdm`P>x*9bo(`tJ?b4J4Xay3zr-6KK1QWM%y@+2uvp z9o+86go}{?j6QMu^_omsS#CAE3Uc8Cf5>;U_SixP6qmEWk*^HbY>2 zc#wwbmYF1E0w(cgvcKM@E?{fqQIGk#as+gB0J38=p9k zsymS5G2dm_>?Yhp%UF`?*uC>0sMdBJ zY(h}q#jzeyWcAf-Sb0;Bk&!kIjvx*l-y!sfHP+YOvj6M-p1 zV;fw%rW^jY4tJJU_wRh}!fs{dDsP8^vKdT8wWr?m`-pBZ&<3Q&ZqL5eNtAzl^qM?h zQ%Z?SkW>A{CK}^!4pD&kF_Chj3-8T$8Soj=&n869#J4EX*@;1qxePu8#_q))pKi)l z8ldbfLCT(4D^u%PYPHsj0by2Uo=<&5rcnjxvZfaO!~CtJ0HXJ3&m!^bA>855A*U>9 z$>&XM34NcBMRYcg8DMHfU zU}EYYF?fj6NwSwD;TBC=KaS*mabL$NIPV=kQV1@|zfChkpQk8(Ts{qm{eEE-H%GTY($V9O zLP&FjOV|qLr2d~aE1Xv5H1Sg`fJajI{y?tl7xDBA9-0K4RxTgplqSY%Cym6)kMJxt zf%9eZs@%vWK%$zIxtIzqsypkTr_mtL-|{rt4EkICYy96!B;R)6pqt*CIJ$xmO)+-V zhJWmnteQGrH%JG|>)a3_yGvl@*f#UwS96%aYg2t)t%#0|SL27o@0=K%QXoVWvS)bg zW({?Ne(J6|!|dz)+a-rmZG?H%3XP1%c8(@BrxuE_+K|rL-=EV+g6%9$dr1Z+>!m2V z5Z^a)HO7Q!c)g^A@q;Xr7dN6TQO)n64JF=jvivw+zlyd-$^!HS;%bN^)75N|O=8^? z&x&3T9FjfQ1@4JGMoo+Ucwq*ZLT;cW>WgZ zDcaCi-@1>*Z&@4f%+}tQg>LF9r*NqhVAaqu!RxcgSKZOrzXRV>{NP@}h~A%DDITPO zWM-+}rD&uI-?x&uvBIjs`ce{~qQldReBoFFH?q|NQxbu5<10$JnN6)BBBC_oZlT{W zl|^FxICp6NKq?z}e_z>Gp+X{64Nh5=8f?%gNa=(q?kp>QWneW)3VqcIVZkBgtt{F8 z7ii}^{o42`q377~58iJQt6Mr$uvUv^J#Y;!Xqcp0#I@@Kt6TPc7>I30H3y1fYqNiT zD`slAGD7`)ayMQjsRG( zcHldt%#H1_%$-FxLu}EwP~*{xhoSQ1$f#_X;2V+(;3J^9)|tCr?@S09z~{YTzAV_+ z$R%U%3i1`I|2$ln8+=z%wQP5)aP|u{>1GSU+~!@db@4(PhP8XtQMAKOX0n-C}jEy8KRZ z`LZyMRxJA@9wK8BtNq@hhz~ZOZMgQaJOK)9KXwi0>YGga?3xbKp6-1{?~WN@4v~gK z99nv6JW&BCG?2*#lC(-D22-^zED=za4AxCox%vU5L|s2{VG7;wa>moBPsSTtml_&6 z7h||h-4G9dRp$?S`Tpb5u%E5*otjA;7S7t6)xVTNbO`HzmC5RTp6Ss{axR`W{>)Sw z_HqxWXL>Y?nD&QD@T)+RqSNIn?u-vN(=4287Msk@&lW&E6tv}$maZrqHp z9(xb#myiz=V9eu%sV^!By%*t8XU^biKB_$-m3_~a94mq+3BnNtCF6^PbjK8+p}$q` z6#1a~hBqw7=O4X~HSQeS3m;G5^VpZ>Le8!!{1VC|A(^baTzLj+SRee+@4lMK?>3}J z!B~qPs5L_BH1g|HB{o4gk70$Qe1pN>Ll(DBWQg`U1jJ9&Svq36(M;4TcFprPp5wm- zeFv>7z$7>qCJ}5fos=ytLUPKOrM(3^UzKV)$JE4(*VtYtd z-}9|glnfyVe4|Z@nivHhsnzo9-D6|G?N^ez8(kvMY<}Pag+AM_LXouyFyr^ac`R3N<)-77x!V7NCtEf5#{gOwG-a^yt%$dzCu% z)2*lTe6@j5z(=I+;{l9KlsUcbW9IiZW14c0&Bf=ZbIs*dG{k|jBgjdq{<0Cxj*F49 z?^Tzg1``p&-tV|A1K`cSic^)^*s6PR?tBp@vgVV3Daa&d=n)MO5s=rOYM>J&a14e( zyJ|hyCp&<6Syi^Ib;y-Ur|DHU2Mi}8xeEO6L0Af~(rPu2tYTt-#E(?1Dv|Mxa%6t_ z60|-NDSp8&xUvzi!-Wz^!*}6)%B%6VjgpOU(=DPBjM{aAhDoDGrBv2q&4|Y3bDm-F z)uVw#oWvs6s)>gH{$__nBn7!C{8LSx3x`&&@7xWEDIbqRdKi(z3_pcf7IfpMXX&$u z15IFR)b8^KK3$l4V#e6$IAsKdp}~{H0_9tFE7fB!0_yw65Pc82La-)CRY3}`&nu6~`^`1{3@o8v=uq+uBPBvI zi$fgJkX(rC&xa#c5r`j&L?#HVNCI$K9MWirhEevfYI`rSWh+;IKeN%Fk|w?lrTz^~ zQNl1$AJWXK3TPnB_^Nn)&8&1E30}k205Ai#W17hE!oafML0dGjK9FIS!>EeG==^Wp zR7NJNBbs=KUp=ns!4r2(OPEd1L=GcjQ^QCfV+{om;0Ep!<7jJ9UM;;% zeO(jYFntj;1O`v?4}D3;g{{e9+rDADf6M>h7~()};lXje;ZFzlS&WT2xO*pFKQhej znpW+ap6{C0?V7go3t4)4&m3OXEL_&yUy3r^U?XDRyF%cJd)Fw`=;zp8*Ws|0Bz*ij z&g*HL_VET#rreZ@?o<9`K6O^k0iTG`vv6*)AF z;bNE`;@AD={ksL<;*eIc1>AVjgz@+{?1t$veiYRor*1-9DN+gk5{vQM?yH&lq$yUw ztQDi=F-=$r@05FFiJwwIPS|!49c6xO09B<(fO<}{*#wsPo&gUXZ2pAf)CJdNz}+r= zS_#1d)Tr@>RrgFL_u>KfVsatc+cn2YG#^X+(|Ltqx~y793z})C<$P&mSF7vB+qSvE zl{q1~)M@iNSe2753Zu_S@_B+vfJ$?jiJJIGUNWjTg0G zPjX|m0{St34Uw75C`z8;_<7(+{P_217%2vyY<|aVZZ;Npbp@rl9JV1rwt(P4cuH;s zRV+!2!!-`a*VP`iHhgx3yapdF#y_Y-_A%Bz(QOSjo*Tu#0IfqixBCr7K{jQ8eIoZO z8JRkX@AvoKG7J|uKj2#GkP+Zj?Nq=>LmELtT5(>Fax*%CTE74-CPKAyN>Y_#DUG%Cbx^jYv~BZG5=SsJV}BH{ zKpr^Hh(aB^i5)du=DR${{H`!}ZoPcu#AMv$j04=VNTu0gzr|IFW#ZB)Wq6i<$JhQC z;g;pShj~$YXEpjpH2SWpc`K})v4*66hm=Q_Rz{|kM=lyWFD)F3qE3(k=^aoF>rmAs@S|US$U^F``GyDGVk-{rpE|s^G=Z7{Xmm=eV}(C5 zheVkYJ}F=`gp?B+e(_oZZEa_1Dv1Wg^|3sAR5_)a7i>Qf`NUqZ#+%z5K=b-jYrRq_ zr^$p$qsZZQLd>moOn!U-V?M=(rgwswelOm4OtpeA@Z%j0!kBoMO5UU$0rJ{Ppcy@)iU_)OW%{w%7c&2pNn+07#)6coyuXBk^2BDK3GkA zdo4mmxG1u#r46?nAEaJ*WMUH;h^Y-XVYkR<#=vKIlREB9F!wh-D{SA}rL}HaK=<3i z;e&{8&PiHImo&R%QT_c?*j8CdDkaJ6D$3kc{Ox5KG+Y$rW#}sHZ3C#alos78Ot*Rq z;uHRKaufJiye)xenr8MnINcpuRUNur4sjD9x8mX1;BoGDbjRIj3hz@dz>2|CHi$kA z-ZcuQ1}~Uj=9f1KpzVY`l83cuMeJTs>eqa&osYDMchxFN(xFM^ShBbvdarz~T#Zml zCi;NC3_(;nPd}&ZzT9!Wa6ktXe_4g0Z%s`U;1PfZb`=20x>UOYn&q#fEIBve;5x8O zw9QNeqvo(7%!Q$(c0jTF>pwpw^TpnwQYM4g0~$?Eq~PI6%*a`R)6S(-*p$_Y}R?t1y_I9=~4U_c}#x@{MOIHC*&mUHX7x;b}|UcC#~xyo4+H z!-*|^AT6GqKD+K{l+=baehp?KUadp7>+RdpafH0Kq-DI&Xt);zHf`A>81wr;&B&v% ziOec+s6|L9Y^0WJh7`}glD`m9Ax)bt=Hu4z9bYhh&?GKQ!Yh*oock-WpZHXN|c>=O;0!cQ5`mUZy zTtKKmP~kG@(g8H)0vbDf5;}g)@&*lo=zDWAF6NYxq&rIFyd*db%%$3I8Hgua$Gs%XN@|lqNGEFs zGx~c%T_SW{kA;nYf@2l>or;51o-LK=MnF52&h;&p9A*U0u}dKh5%GUB@E!sp z7I76p+Lw}4ts}XGV}Hv?ZqV4@@?WFy?C&&P@FfQ|bP`S@ZC28rJ}kQKSM2bsg6YP4h*rz2(0g^rQJP^QycJ#=)Cb>O=tQU(or57{(1w`YBEpBwnf9A z4@)dsn^8qfCHTc>ExstD0VtyfijC|}(Ng-Nus4D0YCRkRzZiM@zixpc({mroXIo7W z*QJjm$o0|(cnjnL-IRiw?|{u9UfHuyC^H6svTW*EARsapfQ__GC7c6Q`b z3L2?M6fyjal1-GEfUcAzQLmUM&P*F;e3=&DMfPNdn_%p)}EM(7bTNi@*O0;=toIaTE<_U5=|13}* zmS6x8v4+uZ417RmwkEaTm~R-St-=bwr@rZ2e`+vhhpXPpryt<{x3h+H?iRo0(O z#_NA8e-OLIVyku5`znWRHTO#qEJKcE+>)4~pL(qP$I8jON@RC=mRra%C#NiE$_iU5 zbJUh8V+8kAF!+P|zppKWZQ2CXGx7v@!9gtYXaN~59CL&-rq<2S!B>?YaKTr(^mKJ$ zxl$Vl)!l4N5U?KgIq$sNtLZ5r{~3zc*BEZW?|&sA%Owu-963hQOmZ@V=IV zPDE!DBS$*rgN&Acy+qXSnKL-+h|u3Njbdi`f5rUjfEy)c9RumsTN>+)-AG3fX_`s< z(V+EoEA0=e?Ckx)AtV9EIPFo696^F~Ov*2}=pMwi8JmF1NTNKT8M9Qu?7r30^`edGn!pPvDJnr&maO7zE$ z(_d$13-_001O&qvM}7^w(<)2Cm*KPQvZT?`5LHu@Mn0tK22Q=-+2Oz%t0KAmgv&jC z?prMzm;6v_qL!JiJV>bcI8k}6c|}kS;~=~au%trCibcVc=p4xlr1rK6x2KE4Vgh41 zqqur*$t?2rQ+66qxP1QIt z3{ye`BW+|@T^nUZc%>(ox>3SOY=6Q0Rav-Fq`U7ccPk+eh44>+91%AkCO_SgHG=gr zp!M>G8Sd?^*8*UcBMNcDPV)z!qOO*XMqa`RD{Ejsw);+5T(ax}9Id23V8u4KKU(Sz zR;mXXvhWxOq9wol4S2lWHjpw+-2+$zPzsBT?f>vf{f73m$Y7DLzNkU#^OtYOMtex@ zO|L}AXd-lJzLm`*zBRzj90{aiAL)VM=3kKq^Gv77om0d>pW|oN=ZiMC>*XhE7|@^R zyCa+Ci|D|B6!bSK($KI&;`)dD-My9gt)E zgH5Q)i0)U`@H>V7E>(bQaS7y3?^rQD`&0&;m+rigCg)v(yti@OG$!%WU|Wy3F^00D z+aG#*Rc@jAzZdktpK);or7#ysWMOc5lrwx#^H%lj#z|!I@K#+MLh-iU=BgVB;wOCbF}FsJ`vaV(Vo)l6Wq(yk z`Jt2|!vCNUcHCVeJGst(sH)}s4{|yrYyodR#T~193|GyY6n)$k?S_72Jp*gt9imoD zF?S;Ms4vCemCW|no$1e!>^%;D_ zon{Cd+8QW$0k8VA-lDsc4k$@Ocw0AbN$=0&3_rom=aI8u4ZzeX|4O8b$WwiC!7+jw z@cneX_tGRZ5rtprk}mX~a}5G9*Urxt*JRp;+qq2Qg!LA`2JN?s1R;M7A)y>7yvfZV z0Riw95CU7&e3OI4%lt!^ z6=D32*{PwK^vYE9;L7tSb>{u1{8N(0B9ERbJ*x}ZViZ%myg4$ zo)r`}$?Od*r@hO>{&kBUKDY8D!Qj-LE6~tFlzU5svL@&0SXQOfU3fFD@$lff(d63V z@i4yz_}wuWQ~RA)8PnjqY}%D=6hW>BwHHhNNNL3U8`!;d36L_IKgL_}RFx&qI&^EB zL8qwul?-n9S2gV2`6t88>dHS^jx8c@ith-W&Q^*vy90Mo-PB~3$|5+!tVUSQWR5Q- zzDsa8a}Q&YU%RVr_s1QJy6D7LmVt)dExJWFpM{^0C3qG?g*nG=6 zW>Iyj$+}kvurTc=;rP=!4Ik2a{MW%<&IS7X#5Lvg*jXbkAkt2HTyIf6hZ5ubQKCf4 z<}og)4*o&#Q^R3TUk|=Ud-~H=8#t=^dJ+|`XydLZ~r$wCxGuN zg0gbwh(6=KH`ZiQlb6E>o3c=Y_bP&sO;K;(Y~j(Go`}`8Yf}hrOuCmPx~CrXOywwM?kA)kck3*<|7Tl2{?$(e=)FG{4VIi#V;Md6?) z`KyN&=uF+%3^TuCwYHBAU8WkFFM(tp3jsenieIAGUhm!KHJ#ut3QQwg6lKhaQbnwusPAO|mUu z=?iu-J-w;mwi@H&pzqxa+QtIo-N+GrS4SFVm429f}Nhwi@s)R{;5-&zB z7d>BIDrS+ay!Pcls(Nj|p_eYwQ=|PzA?xmC%_&BuZqG6QvXB`X=4u_3qb;aZbPRSz z8z0g08V+dSGfC%O!bF=;*f zK0r_J^bq0{^(i*vyF=aK<64c7;_3Mpr)|r+RE3nU!Gmns{Ji^$1V%vf*3oZ%{Ut=aq}4H%9xSBX~b0!5elw7WEk;|T;!cbnZvO@KLQ-{@PCCt zCr_VP2f#s~l({A0`42AtMh!L15{A?7|5Ju1wiom|y*=|({Q{Rf0Y3`NBkxZF?=R5a z*aW<=jZ9S;w>h&=NqerTq}QiiUlEcqohw%hSh%TZ;+y#D_`_|ET#tZS5bHh2EG7MH zOROvt9g=rz*Hpt3+5D>nEMRpce#L?p=CJX&JxeAjcC9?!564eWHKXi|XmNW>eEYUg zjtmMf?~Pkn0R(V@uVoDE?0!L=JUSWXnpgxc2ThzfsoRj2-Y=)kV|`V^`X-o%>N;#y zh(eiKK8dxlm-JcX7xkpD7HMY${p3GKSb?qE=w(D;cPG`LGitm*-#l#zcnfqXV;nTF zi-1E}MoYsiw0ieecUtTpk=?JdK9+;MQ`^Bbf)v+7oz)}W+Ry{0Sc5Y%Y9`!ZM;%^( z%-|xuYHjx*0_1=8X;_6yxy70(S#8bDr@UX^Ezk~Vnl1?oQ}eCD(R*$E@FphiM*C)QFbi3JPIWnhblZ@*i;+3TbX% zG$t+{c>!mp2$S$ z4~1(apZlJ%N~1%7wuYMqJZN#L!MBnHcr@*NW$OQ?mF!^aOcAu_WRX7Fj-86(_Xdp_ zPbA#Ad?PHV?;UCsGck^y68W0#xwtp;CL*#-e$TrRJyN?(nbR;bOd=`;HyUy?d;Z_E zvLr!0xa-_78e2#F6gb=z7235nG{W}%>64NTY9#*hn>J)7LPvPw#v3a70^Qj`#v2beeDT$-;+av`&8&}co|j<{Lnlo*X&7hBpP%u}o%yfYcfrR8&!om?6<;yZJM`>^e#)1#$dV(w z2Gq4thJ6BV7oE1I7puQ4-&wlxX7QD@JH08$O>DwztFWS@m>U~#c@E>X!>?ScHPu1! z*cvf?*eP;W4^Sr)WDnZbJ8>~y+#ak4*H?p_&DA57Rt@xv%$oJ!x>B=#G2z(TcqZUG z;5bjchiHEVX`d?fPwrj37pPw9<_CX?(&>46rf3}NG3(sK7B|1>2mLh@z)zZ^cdSTD z%Bz@JAn3*09jP0FdiL3jDjz9qMz7~Lk0`q^nADlPh0T^OlSt;C<*raMpS{IQlLAK( zI6mvB)&41xVx4&44WA#*ViQ7^1O0v|2dMR(R>gb;iQP|?$~CTHLZ{#3m2|$>@?p|A zu47}2umk9uHJf|f#H!-w2yjUh=H{rjq7t44W{oEI4?-qq0Y zE+yN%Q142(E7o45`)md~uOKFv&YGMY!4kttfPw8x!K_n=6ljUgI93HsIyz6C=Ju$_-~ZF{o@v25oh|4W&^j>lQ&NeT4<4WFqdU?d(f!42l~oS! z4`!EY=x4P?Ty0nf)AyQLn51B-vAd=*k>6KDB7BR-LjWrr8wasxlauT@j@edT7Ox&0 zX1gn$2On2L^y#IUG>!4oFcTa^+Ep*{N!s&vIXQfO1xK-2BmeA}pYc3+16T%ZA{1mD zx#qEgXmtRtf720?v9jc&-=OK=kb63-&~@Z^26NmZ5!Nf$Ab?ik{@rd_$n^dS#QXrN zWt1zqjz!%H#wXVdkw(wK_}KHAAC`~KhhwXROi|YOsb{XGni;XrTJs1#56RecUnHM~4b|g+r=Cu$G6%P-PQKrhN#mm1dedb(zL+JSPTfZ|p%-Qra z0(YW-d79AQB4A!B^tb%iNc->7;vmmF)wIB9#1YrBq`nBCz49LzVEZTK@ox zlK+0mG(mFXUEo;1#RZ-}3dRk}7X+TFx-VWso%2YSI0-z(16Ugi*N{xq4Me}O2#_cE zMonH}DA!Ng2Z z8JU--kDN89PCYBvPI^|>=Qzhr%v^PBz(Y@K&rDv9d6G<*Vk)Ze*9Y&+V$Ij8ixGo!hqfwH3}8=?mL;dz0c{^fhaq@rWm( zHTy6>{C%wFxL6A>^;-69HUi>)tc^TzVR7F4{r3l+J(~YC?5s7Pnd6zh=B9upb<%Cx zV+QVAjTA^M7H0`+a_fTFc!lKHISVgEe<^Xlh26<+m z!0d_GG?iMR*6RF`JU|Ge*mN3lB2o#7)JMU(Nbx9qLy0(>EesZH))-+)!sp=1M-`n4 z;P(8BjyMn=9>r}9qxC;IJXiyM7p#cS=amMXvX?Q9Y?nWy^LfoL?}wbvC%Vu z)KQXE^NdG10lmR`%|{ig_M5-8Xjg0*Gg`ujL@DEfXtw<1BL5$sT8vZMp$~AhZon4* z3pkfR!a}?laX6&Dr+(QfV28tEe;lawltXefGJa-kO7e%iW;@elu&omc(x zVMC9(9?Otyq0S!7y8Kq4;2VlN#&C^B?C8PCTKKw#%I{VLkjG~%3xV{_{^oTwLXgKzU&T3(gV&2Wp5Li2P&aoQd=OQ$bu zr>6_&2)*o|3UjxSyazlwdjVpAw+C&#M*ly2pz()q~AU9OogK2 zd_;6p#oeR%N(5hpi0F=-iW<{Vu#cUJl&IPHl5z>z*$YSW8(r((J@{$#=$C&CZ9TWt z3sAq!w4S3>N6fv7R5P z_}<3Y24$^Fjsg_IV`+IaX*n~cc{6u3gIME`N|rLW(zx^x$ty^8CS@O9B!o_@^6H67 zvp~Ib?P}TSS%l=Gz|$VLB4NlrCbXYF=`J^3U{oL1IC-yRUk8L>LLZpH0R&^?QH$gN zZ=etYOm+TQUw0pgIy}5461Ll%Hf%Glh6Gl{8dO9qJ+0r3_1=Vht)g$^Ocf2W-eV6) z{(MfU|EtiPvkkVbH{oBH@Q#<*)G-gq{JaWl9mgk(`rmz1vvyvHuB&5FZGk>vUy+lN zn@=h8J=sQ(ug@aKv0?M8E7zCxs`>*+BgaB3ywSUXVWg3&YoiU^`W1;E5XjE6;Z6>_ zSTPK*rtmPAW??C>ug0-9W^S&^`Dy$LxFyJ|WCX#xIKJpe@0yR#b(U~O2v5<@<)oGr zg5qP-j$tl}Gu)&k>f}$sa@usv(2|cxZfwxdlA8E6*g!lGC91y;UZW3(zoUn^$Q{Go1?olS_DM5+gC+`iJhJDhch3^gxoy_y|F~&<#`|m zst`EHQ-UVs8-pBRf9TX$qUcr5__RChBFa3m#NW4MPf@35-8SV-DPaV=#NX@FTy6TP zn0mYs%h3EU3V}Q7cpMNb;D}8&GaqB%R6Evu?jLb*gs_Neuv}*NxSVJ4bwT!5l;Ax8 z?No!2@-i#=+*})i3mFcFbNJS7`1U8mH*h!!9o%g`?U(gQ7DE)7d}GLw)pzWKtCM&w z!(PD*vnVwUW*6Lrp0-CGIRl>^J5oXzealjlP%7g3z)@Z8# zhi9%;Ct4q6{w;~tR+)cGqO}qmC_(8c(fSN)sQ7Lb1AC0~xm~Hr{YjKavr;k7ysY}C zRaB;@vItaN%$t~fY!}6~RIUl?Y<|X@+~lStiWV34kv|C2x-VwYghSJ?Aws zZuZgrm0T4OmL$!G)551UMU7 zN(OHB5j)%!{gs()H3`7+bDM*#dqR69^)-`&O|jw1V`(q%h`V7b5}#d`GUGb zVgFEd_P6c#@BA3<(=0%fWYWO6Kuz7ThH(h_&%kdwsa;u#bUe}4r_6+h?-?WNnMW%6 z=2dO;E3Zt}80Rb4pL|#l>!2NPo+#m4WFY=8=3M=7g+%?3>G3?h`(vidqxz&3vayqq zL+OLqBkLvyc^oS?bYjsLK|Fw&`^D#F|?y3N`_-9jEjc|a8*ZC-6Ti#kl73la5K?GUP zrP}zWShq=F#oT4mNzg^;Dks{ZYvc-d0W;k;ICE_>>u-5&WPWLJ@8Ign{K8|_=zgAZ zdMrfOCkE$%t?fo$3Z~BNMZ++G(jQ`e>|~*4jlqr6Z@8pd>dRs`3>t&sCKA=5R)4&> zgNNwSfSW0Nuu!Rc9k*qxNa#@G%2G`gZ@-6qy8f02wTv1_sb=z8dTM@8s9h zUo9K{tEmxVoIg8i*8R6QD51DpFXlsiDLE6b_o-k+ejs3|?BSgaWWu``d>n2wg(O$K}00ztHCiT>CIW%*igT8&P(y-BkD2QC9MI({danQAij9`En2c?*r1BfcAkjGQrh$~ShO1#2geri zMTVIn{Iyf-+VXyKUrD#i2!LING@Bna3k2Z<*;cUf!>sMZv`Z&Kt zUo_tWIY14iFVofpT9UqfpQyFembB}{d_Ccol`!46-gEAd2e9@o6w16BFeXe-0ud9 z1UKH#p!aff!0g}!tilfsr8D7sOERGH?Kr4seq%?4|N1y}O}Y3;i84ZbX@M(h4CBfs zzRZ_$85@1^6Cra8d~)q@qSo8O7t3OVx-lob<_i5?HC(*?*Wemg+xU}{U>&lsjZlD% zd;R^#jwHu;d$Vt)`;~&5vn_l(Uu{9!zzVM{0kz%mE103f(jQK?5_>m{Q51A{UmC0N z&I{u4XuwgRnMhrjW^4ahi74RR)gLrPgo+W_op_du-M5EKs6C z$!2~hp#TfO8xxOND+hoWI5l?46)q09S$LGE2uXgxl=N`X&#Wu-U)JgaNWxFfNyJ(z zIOzO&{PJD^XK?-kI+O=mX7Du5T*2Y4H60RcPb8AC`y8gE5kNKi19m*g_#?+fd*&?g@4XEGG@~YrHAw3_#uFo#o+;XrU?gILjkJ>Bk6Pj#< zRV;a_+Th`l%XB^;D-;YDzXV$bSGdGO-2Z0h`T`-^xA^0gs287CUH7tbrXJ}xV~L*x z3@z!$d2c+%rm$uGf42fn*(mF#8h-=gevWyp!nb(G>3_c6l%|ms zcyxIZMT(7{1*L>`ote?#L34VX__-qS$^Eq(i+8huN^u1`FiG8K;Lr9i6}?1(5E$t4 zorbD%1g%h=ja5Dv`=IXvhlX1By|=kLOejqw0h#O6K;`W9_w@JQzbV7$>u6&bEm zR}s8r8`;Jz5?J{cE|vCd8*qrY30sln18Q}%5ROLUP`%c3066mO+{2rddrMO+QO17t{mL*6+)|Pfs9IR0je#B7mO3g(V z*RWdyzM{GEAj$YqgfTTwcqLYIuh5dr@IuzvvByU<=LE9P9Ildnr+U(j?w_UVNT&m4 z6f2(}XKz^ z?HqW9?b{`r=WkUdBJIrBdp7k6z5oN>iZ>wkm+I(w({ud=;JD3C1I4t4gw$_39^>7K zQBj|r^PU#E>f!ph>-=#`FP8q3EafnQ^2o7UfxdB5t1XE0#7A)N>KZ=A193U!AwI&N zu=UaR4bGfLV}7>02HR=*6Gw`LT_Y4#`BWwUnWL?fL{WQp)Ry#Zip8rht?OHFAbrwa!(Ca#lvg3SPs80H|R}~}~Vf8(Dh@89Efw!AL)S+KO&)hDv$F^sEX&|=g@>uty zdR9k6(M83s#57lxP6?bLIx(y>v}{09r>Epaa{1Zr8w8bc#|i| zVo&}N!Ui30tslpk-Yc_DTi8KBB)Ic`13M=*MB(F@<&`6)ogyzeU%5%^wGgFXpXWm| zK9fnRr|D{p7i*45v=sa20TmR*NRjI37A!XE4|w+`ey`e7GXfj zhDZW}nL@i=H+Dyr1He1DB#V5C$Q#VVGYkDrfbrc>WB8Tn2>EW}#hm{3)m3%NbMr^k z6CykVy9D=z^ghv?f1G6Rfi46p$ysybhnhpb_NzUi!1l;#wqT&hgfS854M zbqf20jQEuthC6{E>(0hTRaDxOE7m@jQlZ&<{t4CUu~a_>n6kGz=9+kp=s;4n4*YyM zOo$)11>U$@JP>?x`U80v(Ke+F(xYqHerKR6c}P6PXC=9Jn_00dvJMCO1y+-m!(U>g z^btb$4IWiFpaWkdxxCyLORb8$sn4R_TpY~Q-3%n(K|9L>-0>K=3e@wNw$MCaFCEuT8c)y;l<{_c-T*8&qqW5u%N9ck%V5dNg#nzF~4nSzO_w#uxnb_a;3}_bL}c(FhlXt+TZ>dzf_Ou&MI;_!MJ@ zwH3ZLc&GGE+eUUD=PkaE{*pY>Y--|@US|l8-^EZ~x}A5e6Y=UeS39FzWJ%!ZMc&69 zdwgtn+dpU~t$d4sUVk0=>^I(MU}m#QwdKpm^dO_T`wt<lqex2B2GBll0o>ZC zV%Qq7E7YmIAHldfcpJUCE$T0ZRs+TB(my&w-MKR@ zF0$s|5AQ!RgRaVVLe`227l@rCLFM1;^DRda+xr(?XQPqiPcoB)SRb?h{#DQcc&A|g z-L%*w1}g(u|w-tl!FHZ81LM-e{Z7wfNiO6ovEW-I1vN@$e0Z zly);gxC2&gav2)$WypWwenwdplnE!c=ni;d^5cQ}>4Fpp-Lv83G6dret~Yt2zi1ej z6t~6zMW;W)KfjDJ{9eZUC*1?LSL4An{%w7^UZq>7-$7Wj;F7ZwlIZfb*nxcYME1~O z*Fxhx+tofy$79=^tm%TS$u0Wg=ryNf&ykOTUGBkRA*RoaV0hsfMD1d|`dYM`5H1F0 zQs;4D+g$MX_Jz?$x`z@;BW40g zn_oGz?~u;m|9@w@utnprhRiFcE7;PcUqj}e68~$5Fgo)W{*?MX9Scq-#5m;QQ4A5v z-mVB9@pDGuQdaHXTsBv(YDfs#&`20dMctXX#UDr96^^Ura?{ePQZPv>8=Qz>#e}@N zjoWO$MPH(z{^-4PMiNPTt7>WKaSZ>eC8j@+0JZX z(uW!{Jj1vAFX^oRt-WD6$JW;z^gsX58Y}AOqpg$`>VPN4hrk+I5 zENC%?F$K}u+&1guXU?NI8 zS)~5(0GBjHKdy=@ydT*G30n4Xo1%;+icX!B@AqnrE=u#%X75|HKAc}doirT}3*9d# zXP2j5XjrkJR^yVvSlV z>78x>I%*%)s`S9)^s9l0>4tRWI7Ieq_R972gg|BM8hm;;crDDulJUE^?mAt{GQG2# z!RR~&n}|GOt$_jGod1<1hLKlShqNRchjuw3dHebA8|@3ZSMl|mdWP!I8qL!hDE`*) zuqrwzmGFjF4ICXr516hllg&0Xz^=sJf=(KiD^H=EXT_DEx$^t9P}tWy7D8yAJAo*k ze6R^EW%wu4r3~RI&b2N6X4HFj#`87U!d+@9bYu&_zQD_m6Oa`Yuu(QX13ALB3t?AX z-(S*bOdPPK)x6@fXn7{GEC63qjQYH#_S296yxHfrj!Pn1#oD}Cqt=mG>$2c|Is@zOcsX6W35h1*|ti!K$s5t510U9vOB<$G|8+U861ZzNh;I ze7?#wlDDU#Q5c{x*_jifOAezWWHUhg@Bfs$>~RY{!Sr0$$OQ)Y#|MGJ<@ucxj%wF7 zi2ube0=EvqXI<(w`TT7WWx^H;pkIJ-AkG~L=>^TT#(`{E=SfzycOPUl_1h2Tloeq7 zKoOik^ItNwqakt4%PmUT%LQW~C8Zl(n%J3bT?1l9{G$qabUT0WwpIIP~Ur=?gYCTsZ=HrUKuaqY$ zQ;hLJX=GeN+B2F-YK9)^w%DWhwQ-8ZBAXqzzcSf3ulm3UF;Rij~Mcwl!)(;zyZ9m zh`eyWm(eo~t3r{*kXdY=R}%3k;lNB(LxqyYEyG4G%#UTA_9ULsF79_$!Ye}7Zz2>)_syio3@AW1dLh_xu zAjQ=8QxVX>C4T=kR zM9Ylj;JYECA67+|9&h37mObsx*sER4jFXU`!OTDx1abSNFc866Nx?Wyta;q#;^;<$ ze#!cI;@MCN-T3P*`oXANbjHHt@ubw>X*pFkU#S@V=_*f*^jxw268F=geP++*x+bUI z%%UCtu;->S{DAQR7no&DI%RSeW?Hb)8H+Sj2L>yFU3D*m?qLl8)$&uO`e%tg&=i%tZY(U)$M>=unp3iSQDWJBaAWk@sJgr^u3d1HdQ$Ze??N z+RS)I(5Rv5pM#1~g^sx>rGlx?+4P=8KV1F4=Pw{o2gtJ;Kp5OH7v` z-EYZr!LDD5W5&$%$>i+HCcSU9ZPqb$WH2;j9Cc*sAV@h4#c!i*)}8(}Vd%*0yaDoG zqNhfUu-`;q*Stb~{CVxf6w{rMJ}1;15(7ON{DPYAn!U?Be3GDta%qPi4{7 zR3D(bJ>?+JiWkd&Ilu}VSEIuh=_wOc#Kr*rX5kNv-ukaS1FVp>{bTJB2v;csFn7w_ z+uqj{?8jHd5URrps*B}`ds1Wb}2S|r;qEN?_tMUcjXdk`>BASP6d}=un<+75V zOPCFgY~z-RWK0Ur8`i&(;kFGVljG8aC+69zBTU zEIkYpb!LrJY9J4%4O$Pax6y~O4Ei(_4%F%b*)jHZFt)F+w2}NxmJdvp7e)m{3lR|k z?-rJAQ%Uaw;=@Gr!zUdTx9oDGYjkzprk2)GcF6^uvC|8LU6PS!bzG_@oxQ=#!yaLD z>)CFTwXx`?lL4$13PL|EZH_eP)isE|Gy?{V#6FZFA$pdZVRJGn& z$UoaB2kVRxQ_{K1G@+EIasA+_R_IKU@||o@bKSv4Dcbtm0*cE&wzG(BPUk5xqSO)+ ze%SU72@!KvnvNM)8ExY3rLGHsLYV(PX}DI^s(~ot zPI{c8rM98XOEQ}egN=V~kroAWXB3PCY>qH*+(HDTie+1frVMvGjqTOUWQRsm6Ew{; zig^pttoF3!qWvfMr1Txkx6Xxdk5veB>vo!R-%q2i#nbsm$f(lk{F$6tKzo+2_ztME zLP$)+)@DffRn|n9nD`h$h7cIu>D33|LQw}lWJ+d~(5WHJ3zyJe<_1z2{z&Ni#PVARk*Wq7Yb3mJuY#!1v|ENKhN2Ub6A_4AZ*;o!sig-A^=HPyX(`$6s?37KRHs zd~GhQ{>_)wsfQGcuJS$}053=H=wjL9ja)Ih>6AsDXdeYVbv`D46Rz6)XXvTCgeB-! z-u;+t$?AMs*yNVt9mXOZPZI3p@A^$Y?8QFy^pRaJ*qk1se`!8$oM!$pWo2ojKr~!r z)pli6hX=bQnEwL*+;~Fnq|+ImJ_T!!5y90Z($Cs>pvF@?6+ICT4p?VH>L~=6wWPeg zWyK?9MItf9BSV2O4^AehQ@V3>WBjkdV-`J7eO8uxk&K-?^Xqf}PZf*%<_(k69Hph3 zQOpXz#l`O~Eb8-6q3uk)2sDE9Wr8d;0e|m`L1%-<3_QJLO{7O$SEi4MEjt62{~EBKO^P3f>Le;$J^T5AF6kG%j3NRWCeDeY*0Uk=ttBT$j8o;b zcmB6kFFSu>W8uq?Z@EWAEz^uQ;^w)p2|SIyZkZz!Xf@}s))|a0(`gezmtKG5-3scP zYVe0EV+MOidG<@w0&COlsgx9rK|-;U=eySbn=g_88Pi%!yJelhYkW3nSCDlO!SX!p zmU13`c9E#R5DJzRwHC>(Lr)dV_>ypap?&>f#HQZOvcbkdWY(pO^qDnr1Lt3xP%ns_2*{|Y=jLFPMai&~Qlul9x1a5MXqtC5%d$FoieKPa+3 z`(qui?VRZC*mAihVdewfl0V0r3@Cp1jV}`VG!_n-5qT*E!ODWpRX3hDc%*_8bf_)3 zF@=Mw{tOVyo8Pn5iyd_AXg*xQl<(9k0j0`S98Q zZ~gCbeN?y{Ur0V}bw1T9UJe#ncehf5t@xso$l~LdQd(~7f0*sPA>275&5sSy*QStS zih8p!7PSG?!co-IQdm!1u`<)4zW+CXT+7F9*E_e9K27f*AwiAcD@B5wyTEUct{L7* zpX&6wkh2-dFaG9=d{1NccN%>JiTbY90>v*Cbl|sMnQrtQA~<7)k%LXfO{35b*tFh3 z&fFjtKn3UnaGk78wmUr=Lu;!h$%>6c5+}{wDL+haapAZQd;{gh>P(~%auOG6!rA7l zw#z3SmrW222=OHhXFgqspqbdQ$a_iOxNlyKKUS2Nv022Ksu6)(+xY#`XvJnwu;WZN z1uy6o8zXGPw9VU=50=CP%Mz{YIvXjw102?NA;ysTFhbYmu!II3we-&;b*4oj>br!$ zSX*>mFJ}}!jNbd1P}_AFnn?t+W;WN>Uiy84D^$;s8i_R zF4g+v{kR8IR`NgAgFCXd*Zpz6UNU#+Q#VXnsDpq&>L-Awx`jP zp)LC7r>l~0SN&;K{e9iwVHO%e>~EZNUAx;=yIWJcTbKCx5rEMB{1j9QhC1A6+F=w6 zK>#maZiyc@?|Vaf%!=e(w^m4_cN?Y2*WxofyWn!1i?IFH*`B23Z8(UeJqlN-iHU?9 z;z=cC^_vzm#Hr)GdB1mvsYYqXSpYkZ;Z{*vF+(IXRv%=fx7l~)2B;B+YhKsMPvjcC z!Ev44r8D-MUAxiYslfeNSH-P!CWYUQHQFYh1(|_psnmG?Uv@eN#=wU(79U{}bxj}f zaNSOJX~QpL|E^2T^-&>=5l1KcDd?$nXthMP648H2^E&bSiH?!>UTl2q0J8`+Tw<3; zyvqlU&Apbv#wljD(x+Ov+L@>yBfUikiKmd*t1eBSN>n=~ym6N46SdyGR?XOU&3MRv z#{5KE{c7S|3?BmD!`YL+2_<7AZl~vX-^=l`)tDf>{Nh=ZNsti0xr+#6x6>yWB_e-o z3hI4wq&j89iI&lH?%p2!kuxQ`ie4dg-WxXAKpEN6yR^K?QF7R~7w7)diPD0ZT7Kj- z9G}H7_E0EOv#!*SpNXNGkH<0N*Kz z7&}`eIc+#SpdS!pk61yFVKV^)9io{}=*_>LH=)HKr~!UN7R8|4@}qN-Vuk2!AKN^f z=Z7fUIJ(Y_cuC=JGUHhh=>e^ANl*CoO4`BKc&H8Xu857cBSA3BBMq|QQ<}N3t}dg- z(JAovBiy~K{!G+{g#laLR`4_YDC8a>pB+E{k2Tt`aP~6?lzdX;E9(c6aqq zFwbY-IA$!e)fP45Rq2KqX}98`C?jZF_brEk&*raqA6+AaKt!DngVJ1;KbboQOGJpqX`|JeJ0Dr zQAu;BQrEJvwq{MgWQpg^Au8x=qXkGsZ+f@?oK`{ zY~nRfsz@DylQb#pAV6;tclTYg*W45}!G>a@uJ(~Fz$ad7oCZoV^rjP01aT79UK}LO zybGbqWyNHSrR(Z+q+ZR=qEp|X$_cr8vM;?)uXXv_9y^T&{+xIr zviUX!17ZOo?UVukPX?1hbc3p2leiJ6&B*qu7%A5f|DOU_6wlP$i5H_N!jzSvGlR=`aiauJP&Y;m~7x=Lx>@Bnp_QSgfaqLHt>K{e?#YO?CIl&()?@jihKE!Jd zO4moQop`kyM;LKSiRbFbcz&t6)>O{5mUv-Ns3P2r!36-|KjQSX7%$)g{1_D7$R2p4oe)UAK@ z8hFbZhqwX?A4vZvt^q|l8z+8572Mc!{sJ!RT)c$x^Y@J_ps84>Qm~tMV81jyDy3a# zFt1+?U8nyoRDnhTaup%KDcm3y!+sNO(S@w=o7+#aT~>BHDd(r>Y5o%-;xO$Wexv|) z6B?8^emBuSy;Y`H$Wy_?Y2eUIQCLY{SV{TtdWNW$OjN<66FxZ`HaQzU>3B4Iksm*& zka@k7k_*g#^P@(bl6=PpJC*abCdS!^?vA&3m~4yl2g=w%3} z8ISfUPKn?yg(@UW!s}a26Qj34KM{cByJ17Li;JnScFdNUZF28A!wpYvtg(;C zFFt;5_YvB7pEzW)FKx)-9z)mJiB0|NSGsAt52UFR`*GQ`9$pE}Z@fY!J?Q|Hk$K~* z^maLRQx_XW`+cg@k(DJh###!}Q`J;&l!yPM1Uc|?@2g|9pSSb$ITk`65K^b8`Mnu-GsUIT?&Z@}`PUe5I;^YO*< zo!i@yFH|dCIj?MfF$q&>5f{y-!7SdvQLBgkjk1&)14-EkGs$E$JEgH_i>=39etr==E5IUyi-V z@iXek?v{Kte_MQUW&$dt3Z954N*;EOo3s92X1Fgc?1Rl;GF^?dCqGuMg5ldjIZZrL z?j$suSz1YegoA$=pF$mGS7Tq?;hoxhFHu98HLRn1FEEKjnc~||$~jr%gdoSY0n9ox^QTD**)_WGBM^BaIA6rKu*EpN_YdZHqc1sPGh`UG7E7X}$6}i(a zwMq%e=ZRa>mVB4?Yunv`tb4*TPBWp|{~lK(~;T~b~Be!68g4zO)>)Y}c%SuIb@-o^`CA3)qW?$|L_Pzfx* z!bv+~MMz*BzIH}@S>yE$De5N=u$sT*kc3F|v45<()26U^;;_A3WiKTz-fKFV*D;14 z{vcF7K*N7d#2tt{A3sKQ6lnggz=>WG!Ov9NkTq0F_>Y%)O4$c076VN-B<Btic6m zcjz(XS-I=aEwW}S`tzL=u`>H#(_{mLzmfgkqCg=%4S~F{`bPy~<)}PPHtZ)##p;y5 zA+0kxhcDzAuS{%;)^Y16`i=^;fOstlK!-}l5&4e4;cuFvy5s0wvDLNjJ~Pd{R?%qMyLF4)k`p=Tij{t1GD>PKCNtXSWB%(tzUN zfgx%6=Mtvz%q|umCUe|GOZUWO6QsQt!IXc6kiTQ7x{+1sutS)q?T!v%%!JVC(PMzl zx8$h1{o(2a1BdvIxJ3J$=Tfb)HV0H~<=dsaget`Mc>+G&XVNHN{=TZ(Dq{ZoW@P%&H2FUpacBvoukY8+%G=>wg(s!9&sa6Ck!-|uG*_fT2J&uza)&{u#)J^Z%# z#;f2Z$Vd%`=!?Gr{mT?Ka{eGc>H_w!vj81P+FgMckD8OFPSV}+q~J}pSzB0SK;zb7 zG%k#{AUicc3C3p~Vfg$a)%}XjW$0PpU6~?6Yr7|a#!ah`)2Ir$zlHZ)X`5mEGsy}> zX-xGoJLK_0EuZr&fS;nN%YDzBJn}kBCFehu=oe(Vs4O5hNt@6dNM+ho8^hDoUOX_O z8Etgrj8*B#^7g$|qeMNVk}9QVS=wHkmgaVd_FXqZcW|sJlo8T&Hw5(P%ft^L&so`G zJ=PD+yF;Ttj`WrA%pm{Owz6(4Gm@$D|2vq-(!78C%po|X#PkJZV^Rap6IzN1M~976 zw?|t2UN4uY{PGB%!}3b(JY-c^{@hU$wtxXd7`vzpnnB)-B4qE zJt^pL<*3b+_d9T7)HqO!c*|R=+|F9;)cgm_{4aDk7O*LWUiC+PvJ^BcFzU!HpR~@= z-1G6U7F=8Nr7JgTzmeQ;oMoV#H_Xwp%+Y$sb~t7<*9HC)l_c%{uZ5ZIaL#CM66{L% zz+N`9t=3!+b+hCG)#%9T92A5_Q$?dRW(BJ6eaDgBK0%T?5!Z5FtAxGw z;SYI2PTsf0)okQ~XT|)EnrQS~be;xwD{Z}aQF-97RJ)b%3|2BOU~G7VWZBE+NVa`k zL{@o9XO9jPD8&~IczEomo0rg!SGp&$-xVr@0+c~x>b%3si*`$H(Dp)C4qd-ZU(_#B z$lu>u4G&_`?(+tPzO~x-#!eJ4MP*s1l+={cO(2&8EH@}0gQs~%Z!60YpOP0^S8Z?n zI%_B`W6y6m4 z5cEi`*xp={*jqGL^we4{_%Ek3m?2J}uGnzmdG$6TPAEs`LsHUBn|5=ZNx{Or?+@kD zizmIrRcdq}O$d*JmFFa1uzBRDr+paSEAcX48m8CFzv>vU(k0@}0Z;uBHI;PlHDs9{ zcu`;<D{x_v^2X`7KM$G4@yLON;j)f4^R{MwjSoD0JBk@&2d!hGKNDWdXl< zs?sJABgtVKNAv00kIgPff8a?p{x$>iu!?q2X(N}8i*56%-s2l*(Xk9V@w^J1Dn?ps zTS^rTx3c!Ns;dK#5ZjTKuRZjWy>(yGm!-Gl9lwrxaOay?)8HOXM+W2#?&@Df1~~HO zo3tb;R@FuZT<%ML`d4J!8ol4&2`_sPsd`XobR!vA-F2^(d~!5d*ZE5^^s{7Qu+2a{ zuIb)w)PF+q@yAipa^0m^8 zINq{l0q8T&Xc^VxYG z{H#?d2Zbh$v~oWX0RE_y{cwYx9@%d__M^ash^h0okV(HM!Z*N ztNLVVvySThA2qBeDfXj+zgvk=R9Vnp`$obd?tj^1_VFVysAx~dK`S=dUZF5X<}fIR zWn6@-$r&i~G#m?~%EDxw-Fs(FYP zHMD$`>O-{dl@FkfUHem4u-cM~>3wwtrRtdc)TJg5vo6}X6kD)+ug+9Fms&Q%D}~qh6IeG!c5dfx8>B8C&M9tvIO0bk49g_^(E90qvI5(~ z^XETmO8i8>Pv<+n80eMX^1JUoeAVq1Hiz@6McQGTO5mQH_sh{y%a^yKbkqUN*pn7P zA?v>gmT~Qx)=;OL)xqzlr;8#W6}lb^ecy;dYo2s3x2YCMxwaQqP_y9*C{SLBfA2^*ZbUcM+_m5aFrG$b2Cv5^~FVidbE~LOtm0iI{ zfp8Zo;!2UQG9)p(sX^g9!U{e`tn(6sxE#71 zT9q8=STlnsIReiUyKUwSlf$W-k0*1)SCiJVHiCwsk~)W_W+le4*`gG%ae5mk3uNd1 zQw)vt^GO@Lw0HW=*|=03&}Wk2mY%-Zu1KCs5{40E06gXQqGd_{MK=eREk4NdNJWCh z&tI&ioRPX&MfRl3E0)s;T=AdsUjkle{Fe)FL-}j-^<;k>xox-|r~y9ds;O5ZGs*|N z0>;W^oD+p$K8FeOy}aokuWDU?q;T`nmfV{yM$vb7HHN2}M#{?R%0Oy<{|QtH?9|r3 zuV~|oG7*#=7sczn$@XSPkzI(p!ztd9Z@j-xHe-Lxy~~&n`O(pJAMZ*ch}x^E62(|KeEjP+9o< z0pH%{k9~nWjaG?=4!Tz%utnzXb!bl3GeU4^SqQC{{4#^6 zgn`Jv+#=>j@s;uu=r5a3rK)<-x`XddNu$y(N2Az<*6*1Z{muiZRhTJAD2Rj~Bs(4m zykB+(aq(6AAd0+Aze z^x5N=z-e1^IKri|6zn|tAHk#!wGoGwWfmmJg3hf%B7t9{KR8|#gLxJ^`WC=-nZ}=I zs?>7iXTNq*Yef8$xqU&b?O|kddgj_5QkJwrjEgGbGvUk;ZSfgxd{&NJD(;O5>I%&Z z+$RWa$vmBY_g!9=yHHj}L7$zlpG!dSg<%q5?!_ugR9RNkJHEZjle`gz&;%(9R!7nc zQ@*{k_Dlhy(3{57ynirSXVyPbKOHArZknr~YrT?%&|fIWn@)M7J?ZC}1{ZH&Oq^5% zo-X~bOcp|xE<6I(JvVM%{9x>VoV(tim-iZkH!39glgSB_C`Y^9j4x1Df@-{I?BR>B zt^aUDi1?Gm=V0MXhl|<-+1O27VNV00-2?p%$#IIZ2h-;3vYVGq2XMZ{n9Yc8=-OzZ zU1#pUhT$4gRa}b_+rh&1%Y&7tYAk*^EumXdZT=ugn2og9d`piY~IZjXS$Tkd)v1xd-4=g`2FrPW0 z(2>Wx=HhgBwe?%$oAoO&?C1(~b=xw3zkCO^_JDCVz!H~XLtvQIzvkQfT9>fK)<1zx4me(&9ut9YdH$y zG`dc4)-&48t3G=KXVEH~=|`XhMk}@8=UrpF0TZv-mtJcg6dsPgXG<1f{hP&kz+l_Z zUT0D{@?l@oZiq)`i;!NDv$Ea@eLcfxRvPKf&CbFj9yAw**N_GP=uF1vl_(Vz~;kVvjk2&YryxJuBqrz+tB|It+ zEf3&vRv~OeV{d6|r3*}?SVmIA5q2VT;uSZqSl1t{03M!mboL>Uffz4GGa=sD%j{hocUxlfhwa7xR)^w}{7&%xJ_Oq4hA*)d!2?=Bi_4B_8PMhy)aNiO{(68sa*twa%VDe) zF{I|g6Gt1LUBS)jGZQ?ti<5}+{AU~QUBVyQ=tb%A<@PONM6KZ6VbXpD$P1Pu-+N#8 zlDI_WORB^E5!8`!OHM=kj*peR@aMO?rnqBmod=Gqp+QxE8RPO|@k!uU0wIN*SNeKY zSe=@!`hMk_(+r81zAy?M^5LCWK|&uv zDI^&S!crV!ZMUA*p>dlm`RSNT|Gihql-xq&ROT06<1DCNxZrn}GeUYiUM#M>5y^?G zU*CE^`=QwFEC5KX-irF8AxVpmjF8+pxX9Bt#OJig_mTJ*Q*K|9FdmDSs4OHnb9}=1 zZa#OB$fvQw#XEbQ^o2uUps#!TM+Hl?kb_6Xi75?H>UdwbF*op@EJsX5qUjA${oS&S zN5R#K^@Y4(vRywT$Y@-u`}@RA%Qkh6%T1DDqT6KRA!8$KTfv3?z=8^Y@;i+3t<4Hb zjOc$r+U7N1SXoD&?0er|S-Z5dHd3t^nF4Jav1Puy8H$c<{D&yewP9>qb3q?9_z}G2 zXYn;*t;*j9ckot-Vv0U~tI3ag$qx8qm|;a6ca5{>p*wdj2jOQw+}AB8(S=T{m=?q! zTn7>{OlrT{rTImYXq}y+c>=2sw^MxdMziE6xT~}bjY3WsCAEPfWoezi854v% z=Rcv8BFmh>eX<&<4Sf8#L@pCrc60sw+xek(A;pXJI|{SKrAVus8k%eM!9RW+Lxkaw zsWptRdoew%b_-`A$8GGt*uJ|7)HeR>*gEs3^F^gd^D>ib*opGCgb4L-IC_Nqrw9`C ztSt-OKR9Q9&$YA=LkxTls~(T(x60YIzHXuJ(ZxZ$wFOgCbc|Nuw9b01N(nKUq?Z$BJptXcei0%ux~MNn7@~wO{=Sl-3!kT)+kbe#G9Voufi-aE(Rq*^ z7VEOdVc_czk!V(y41DuY`AT~IY4FR}^2r3UBhIjQv8hgK_9Log9Wi6vhK$C2s=eHF z`rJ(V>2x@83FY6ueUo%#)n6@Yi+DR3^eJZ-+%nXqUSIkvj*U$&rp!Y!=9r|u6=JkF z-ZYb3y*sR4U&*noR>^DbVH~(P%epxG^~fR~Y*EguaW{;&#+vf+!pP|Rfb=(O+;%7T7e zo&%t@ZyL&QT3u0TmR#OucUG-2h0;!5F5QX5^(x%4@O`;M$Yw48y;S!9D8%klDS{G&5KovX!u6rJdSf6l8^8U+hC z0ZUnSW+_9?@pDcO^C^B#n5Zsw27cXj zQMd_25wr7X2@wBHi$p@@(e$}k*3<4U^SGIN0MTbd)beSqT$&c`gtY-3DR=tEyQ-bY z-LtygClRzQZQhPO#>qbAD3?u@4RYN?sB!vz3Z17(i|P-(oY-IR;arSns%-5trym(E ziz06_QmwXAjj+qKC_bpRi$lo0c~@+ws<$at=`zOSw@Z>rvrqixIRmHq%{y4%B{Xw( zX`GELrO^8#DwlB;G94~`a`#+e@Iuj#+b2StzwH&p6kvw@+cbds460e2`_xZvZ8CeD(ghTQUGDFZNTqv(U0$&H)O~u9kAGXn&-xPgxeOI+;o2!4YD1QJvfw(tu|^JMS7cXe`qpD@NAAu-3Sz4G!ozkIpLep{Tbp`}-JCE8=ZVP2DCEcH6Z0(x9JmlXk$2@H}%|0=o8cRf{|V5WBd#guf!N#&>_j725sn34o8L1U!&@BIIxIH6qvb zD3n*7tk^M$|Mu>>;r8V>+BHw zJ(E*SG_L~UPj??dE*yTh7XylO`3%Rq+%M14V)+HaaV`e^ziS^_-*vvD+!W9E$K^Vv zIdM=9D6;AteZwPw9{S_9P#Sl%&0K=ZH@+gsz=1LtX|-_T%^0{puUMb(>U85KLDLwu^B<60DWx z;=gwfIYm3`-*u09=trf=e^2FLsVUr7ft7W}-E5;ZVYQBJf&vMDVwAm)dcX!n+$8bmXix zC2)`Q5TrApsn(IQg!c8UJ=abnB;RB78I6t}zaX}PWdr#j+sm!$*BJW*n2!6d>;lrs z)LJyNjc<}#g_F|Y3=j^wISOe*5D4`)Mc3uhMQ`zBxK%&!yrq5i(-hf!WW;cjs;5@? zq2C4%-Uy&<(sKnh&|6ra-d~+!_%SiL88svLF)jb@_?@|>wVpbPxBUhmJ@tmNfbV4& z)#@m}+?xO)#H8+AsF10DKP?|%V$63Du{IiQ$~V&ra^3^h>xT||!mCrf5qHh&v0YFv zbx7%Kf1ZeD>G3>d5U2Nq^W`ZRPKuaL8iE;e$9xJSBZj25>t6ASQX%rd>F418z=TKvVf$c-ao~0TMg^r+jussfnn(zyeg<14ECn;8_tXaHa2|}TEvh^9C?MP zy=GX>R|3f*Al)3Vx_PgfAymQ1`@qF=TG zVFC(L6t;> z4CKO~@FPn~NuteY99evuRN^q5EThd%`~z0JNF&=54(|-=hC&*4IV~l26hqSle?{=JrM{64fY~$12&){!QCpnjrIuNb$6gxC+ zv^Ao-`-=Xm;0a)>3Iz1TNjW zZ`NNMS~ihu$?Z&RnXxOLQE)!H(kM`ZUR=S_LnlV9*M@YK57^^pc;o8WsY1SXgcA{0 zP3^tnuu#ontzqkr(v#MWM5yr1d0jPSfl34btJ0jVWlWlyJYh&6F~_-L$mK77jXuN! z#%~7~*ciCN3LE+`kzHStb}IrLhNXtoqV*qsR~YMiQ!V13tiu#fHCp0KTI6L9W!}uq zpicWZlMr?tS*u1jw}Lh^XZmibPv9WOrwK$ow|!0*oy&N*?*dV`U*Qg8;|_DvC*k3K z2}O>|enBo8U65{la0UL9@C^fRpUymsL5PPvj35{^ zox(~x$|3eYzP zE9nlJ3s@(H1}{eft2~`^sf29x0D0)y-Rmakk4|@TAXEN?r5{`v_LumZNf4X`L!rNJ zF?xt`61H%wLWmelO}BdCza4uUZe0orm2e!@bV?`RjqGZC6(>rSxMtAfU;snuosYK2Mj|c3dD-U(ydyp z9sH>i-VsIanU0EIkEgTh=&og zyC=vv6cKpGDOp`)O0;=JIp8vBkOtJKQ|Xq0%*L8!*`F~j2qh?0_}WFEBwR+zDQX`Q z^cB2zy;gb^(Ui7bv0a%pYeD7-1q*lnt>_2Rj(e%(Y?)}ePbpA<=qgwPBlqEgBlc6R zNa^sa|BOF*ez~-Io8`uP+BSMQ_`xiq=#+*tk={o3ci!|H30N6o#Hs{Ep{F#8j`(sZ zvHVm2Ko~feujw~mj$b%=nCO9XQT$Re2xCf)InbojJ#!GSN{CIuHE3Mzm$g3SDztI% zB!}%j$4tT{-3d;iae_M|A$=)ME%gq_8??!vv|jSj<}*hJvlnm+9}i?$$I2!?Ka|cU z&y81L{00}Z2x_w^zQ9ntNRqTI{i+v`&f}bALkm;!qsG>DGjXL8*F|62taP>RNEA^1 zbMa^;ktqIpB*%AZn5nE%vc>2@+;rrd6W9q9EH4VF|5F!hsk6=_e@KP8YV9tcgdp`TptZ9o3a@~LM8 z1<<^fvLA{(!-a_A{hNtbo#c!32qnXWyrE`JZ{M&g z$rP+)fB)UP2uabS!?QZXH9MpON^ymq*s693 zhS;M+?*fSWz#FTIj`nL2(jb0J#{kOoXm0r$EjF{-cmY#tRro`O*xBOPd4g+vBq(k8k zw0OSs%$LTuXx<7I+@HMh&_M>F`y+suz`+cBRVOjgSZ3&sn|DP-u8y#Q$LE(UBQ!BC z#vkcmF&Ez_1UnO{tP*(azCKQ7!+n_{7K2J6%e2(Vk?Hgy`9$y$=Tr=AM*x)Tl3(cvSjON({IGeEZM|3ID#_QzbS3wG4oBA=21X zW!lam_`7(@XZG!rgO<4AArVy$=9SaAqsrh^BW_gIj0!gtPPXKk=U?u0xedLj_MbQy zlp|N?>`D7Ul+zpVpjaR4Y*Qj|Z0z(#L>ePQA-Q}p`oxAbh?*A{#y8-b&&`vR0gj#8r z`5J|k9PU*iQTxxXKA8ZX_GT_>ZRSCYP9CpTNn z^4aflRoVdUmEWwVkVKVYj3 z*14tDxO;~kkvF)3++G|38`)Q}wI@UZJGuAp_T4|o2}{;*%YKzn>2H#lA7YsGvf z1Oy!5;v3KCIb$RZ&O=)LyLBpMzDBo`^)4Y>IfS!wcco`_WjwZYBDs8H>sKz8_^w?5 z);Fy9mx%LoQNA>VZ232+Hj91DAaCRwTNY@GxXKpLh@4nS_R0F2wS^&?W~5Q>J41eGzQh@+Vi1wu;X#)f zQNXOes0^<>k|CuE~Jau%P3)-VU7&RI%_|YgWs^pk~TEK9EfHgINH1%mYrhqYK zZ(OSX=hz#ChZ9k)(2hO$`|RRw%<#;QWPQY0*ME|^s02K$*5x+P`q`;*?L+gr<$W7ld>*gp7_X^O@T(uh{0tZ zv?%T6E%9}+Vo|%->!vs}lBFD@g;!;5>bWUcfo1J$lF8-TCLhZ0r7=#q^=5C`2Zn3a zJ~G{Y+o7NPQxiv4D$CTWf3PU%aY)+i5p9^&_ie;%&ayfh^F>16w`J40qv~j&PU~&# zye~VBMPR{KWM?T>h>OLW+2z^T<+;Z;8#^-h*#7JMpDBMm?*3Z*-<>SH0-dPQRT0wj zU6f3+_-2OKG=dKUz!izxtVJ%~iAHEuz_7xA=|S(0_gKGcaAqyCbU%*h;AM&}#kw!h z&RQ^+4++)2eSGBh@$iYrbxy&*-i){4@kHFY76LrHUQzYPh(pLbUsA=17CfD(|IBpP zsPrnW!&$IxoG2owldO6hznizQcElw{c%5Y`)9f?$k$svOy8PNG*AVNZXu3~a^|#CE z+%1w~y;oASZG$q^q-3m`%;~mJOocFaoRx-2<0Upen$y8J&RlWDO---xM1c@KTeH9K zmZ9Z)QpQ1MEb-Rd#I7Se#evl7O~3?>HZI~^930&F^@ z_Sz?l&Ag6Byu@-~U^jA^TrARPYjBOqBb_HQuHl@BAW>w_}| zlN9Wkgia*J8|vy%81M_BbaD+aJuQ?|Q zb?WG&s_1b#*S`M4>S!(nvD<7gx6g#16({^bZ1gjuG_i@(`;2LhsmNQ$ijGR%fsNvI z@Yld(j~E5gRYyUd3}W_isxEz%Jf~sfb0lmVZ!|j#k}b_p6&RNT=In7a}}_B_pZ4`f@x} z&KsKTGMn5OdjS7hThT9xlfpEq$b$1!o<(-=nGt76ZEE`HmC)D3uwcCDy#^RLj%}8#3;jo!z*v8q^wcgq| zDbXsHX?B8}!kb`pv}*f68$Ku8hWwX$pXj^0_Duzf(~5bzxm0l5Pz?XUUJ`Bd?#xsk z@*!_f=c|OrpFyCZ$nMhb%7jx{5k!i~b9dwNU(&wwDR@p%_4>9?vgpCboW^bwgfkZ< zdqkq1zSTC*^lZcVx7&1|*`Ek#o}jGo?)$miiyfeXX}MVz!?$Szo@)&J=a_mwm`Mo< zP{2Vn^C$t3Mp-&%d}>8_@(0p5a64X44wfqAim1$z zn_H4O0=nyBK#`~q%!ySxfE;KSNThe3Or5!YHwOJXwxKATY8EqDTl2qD%qpq-Ebr@G z4rW~51LDIrZiF0`ZJDia*6+pB5C8VpkzKVbxAol^cX~qk^76T9x=OzzedZ8{XUVWC zORBp{c~POYVcSOO@to>7MIt4ONkBt~Ww*5b?3cMOGdHoA$^Dks`l}qQ=p z>QRa9vSP9yi)C2#N5Fu+_9l?=E={S8()n}o)XLbZZ(X_}O3F{j;g z`Mdx} z-E+%qa;eY5oZ0Z7kM3pTKLYCZp@DWvY??JB;^yx~x7CO$#0KnjfRMih(l?~RQtHHs zxbwk@Ay1kY)G6*qxN4_Z9dUj5tq`;+{7rL($&iB`eveKURS?{QJxcW07GZI;nvIB6I4MR15YoJD*aRpwKExUbe5L#^~J)+o!pW?}~&i zo*?`1d#Rs+Q4kz3UFfxHG)L6Q-O6G4KhMv|{c|tc#yYdHjLQ2b51fd)`i8U$g zYH8Oo*bJ00%v|JqcS}n-O$t_@nYLn5EQBZ}AHZj3pPyoI0YMTl*cC-Oy)b)`{F3Sn zsS`B}4+frVFSSx}zVr*xiNGglV@oM)QGA`1ep6|zGiN^($EBpixrBo{Rj+C4reA~#y$TouyGJ6*(k-&`lCYwoMjX|s6%g$ zC;Qv_EN94aO!TqkX9RLw}hBM)#1_9T0W(f(;U z!fbI^ExkHBW2n1T1#fJ6>)h?VXaseh&!n14a9sgC!|urbp8eMn=|r3rNU4=z&ZAR+ zHx*wsec|KU)bhz5*V({mv{PiXXK8+Q3u-Gso{_ zt7bhS*BdRy+pc{ZjF(Ug)hnheQ@??n*xhPXOH#~5T=+#-)0c#&9v%Xy92Y7C_77Sm zNqkZ#VuqAD<<+yR%BKS|nHyXKKgb$*JmkUp8Xl{2m=2eg@AMD7Tq8B{N&k!DfOz4- zsS>BJpHp^NrfSW_=sztfOf{}u83YhL>7_MeogULl9HeSaYTb$dJl)2BlH53kmHQ zkXU~r6D;|DCT_~#FWDK>ov8jB2V@9SJ_~FFlD3d--#gt$Km#-HOQ3;2?n|!8miv3- z#+Lhs@x}B?24%;)d2&7=6AzK86!3_t%UEhYXd* z9@~&%_|Drd*N-MmNYpR!Gbsdl-*^HR+MgxrTa~T(Fwaux(8g1WUY3zKU8^p9+S#$)Qu_(> zxSvZ&%Bh)6DwQPNtqzp}w%F_9^x+Rxb0gCw+CN_YswLiL%iW5RJ>%Z-zW>!`97q$G zS0DR$gq!`?@?1W>CF6a2IrYxtO&fIF^r}1tVK?j;7%#C>L|15NO^{1 z9rZYbS2W4K`sWg?5Z|ygzc0+wqob}YwwV57_?-?-%k#R8mC8YT<$sX1`chyjjDyi>p9_`(@Q`*)DxH=!(RgD!SNOSJZkZq2#F5=ux^!>xHlyXbm$&h1(I zHV6q#y5^GIVVPmQ+95apfEm|HWt{oW!8j~nuNC57w!ECFJ4P#e)wy-u=STwA7#}lwU8sS6USej--$DJX zNfCSQhbv$7x{-2wdG3*G*5+#ke+Mj;6HOjP57{G6K^6dQQSD!D4GLiO)&Ii9VPTxJ zVLFAMbO>^y7`OwCHmjHJ@;8EOB>kg z>G#Xy9bYn`SoK?}0}#5O_nLoS6R@^(WGW$inUUp43fC4en@1K3OSXQSC*gWcMHppO z;pLJ&Y>{leOF~(wSRe~uv7V7E(XeS3irhxNZN)KX>+f&SSLx||e)((MJA|mM;R~~> zSo2tKr9fuT(U}RF$E%8)YCf@*FU8n}>N1$(Sn{lb!XI12_GsJee6(+X153hbk6jaQgDHgN5ktE_b#bH!; zWpG6Lw3Okj+D6m0TO4{?iZLv6&eTV#Q{R3L%kTT4)S1+*$BUdgnBM@%Cy(!PV(BF| zDKAz@FkqfMHvWhWH>-jf^fy01vtm%ByT&sv9R zMdTmu&F#2!nU9v1Spiso2A}m)Z*d9tG6ZNWm}yy}A~?|#IcTN99_Ud)ix0`RaX92YzmvUr_=54LAF~EzZUfS|t=$24 z?db0K=-%Ps<>=uO7<-s#w5xJ+{N(E=H~uU$&ax=-(|p!S?@6Q%i3wiO3N2334|zH)Iy{F%IfYde4(KJY0_`rFx3V+~uW#o4kr1&nq@eIY;WjmXFkW=e zQh3-t0RC&kLi+!@L?SLrDd5x!V@ml zZy4?sc5d{Y1MLrgP0jZ|)7C#m`K&DL3>)INQdzx)X#701Wb=e(eOE@OK2ycAk#9>5 zCZcZfUpijKS(&wNl-w|vVX)SUb!Xd35Fym|w%f%b$fX2XzjAIMoDiCcgdwH0>w2&? zAK8AqlbSA60m?7fZB@CuH_9j>zas*Lb3w7NwDYTuD0#4I;}^><}DgUdNJeUM6kpXZb6mH+U_ zP3z^R0%CWCH7=K0)lwJ!MqD(kq%LyitsbB+$j5ctDo#uj57d@Sl0XF)u&aSiK?e7_1jKuFq)YC;k9MYS|^E-$}I;_k?6jiN7Vy%7K%MiV0-8N zE^o&VaU1D)kBy5c>oqC3m-j^6mLec~A`TQtq&Iw$&SqB@2Fmi~4r#V$N3`6dK#0j% z*g@O2X2fcxwzMb)83<|VZJm!V<-IlB3`cMl=wyw0$8#G$kr*MYMz9A`5MQF;lcRv( z6suwudKx@;{zo$?3h^GmFTnD_`!mX3ivsGKsy-x*nBy!yYPF9h{6$tIV|a1?e! z^0(}y_gkI6`eO_haWJLV?4EUg+i_fit{SH1jO)XTfPpm!WI!uCUEj9)!3 zcIo%|sQD}B@BI2D{Q5&V6=x6nK^ZvXM_jt_T?%)FdB#TUHfN>YxxIPXLaR7>`?XPF zrd*^SOnr>4uKy-h$K)p9YW9t_)fM}*Z)V=7u95s0LZj-Pa1 zA>u4OYZ7Z1EAam`80P&3NB|2NGDw_KhlOMieBxO#8JE;vL?2zRRkSsZfa3*dfZK{+ zI1El3I1~e;@8d^=Ym3csXmCAs4@CDaMR+BGgd!4PID(Ijk@9^KCp1i|Wjw}#s zFu{j0@+HQhJLI=vPx?X~o1J_A-6GR!MY{aQY^YzdD`VEIgTkmpBP~knj{i3acSr@B z7Jb$>>ge%6`L71c*&GO{dH!@XlF0Tv@l#5e$V)w)(@~G;PCAysl>7oMG6FdZ!XVrg z$S7)br_1=)_^8g_egd&yuTZl%ZYi@waz8k3UOK^PuOWwn7lsL1md$Ly;XeX@HeW$m zZv62tgoy7R+kYKoU$XFav@USO+Hu!AE(Q-3lG;tQ7{z%SE)&N0FrLFvnDa4;`Sb&@ zW>^;>#d)Nx4w70~6Z|ZZsXv#gw2-)kngZY4yG-3=ebtYpd`bko6lHqyGhkQf8&{ew zHvQ6M`|Y1LzklyNw*RHWTTvN5))SYu;<`L+uq{WNfQ6f~&|)3@Vt(c1c}JUMGXG4L z)8VZEb>F?y4Lkt?I%f3o4PDB15JHpI>4_Yja~-uJt0c;oNK9OTQH>WTi1k5s)K*_r z9|ZD<&kNPB)wp8CVx?Ie)XFKLhYPlNF(bc%G@EMmW5ZQ)yA;NfXp6DqhW;qQf+C#9 zo^T!!oQnMS6h|WM-DB;E8!I9CR{TEiK*i+MKmT%&@;Np5)J8zY@xef(&F)BX_sa<{ z>s9aV2Pe)0P*B-_m|8?U zkZ8FrR>+^I)sM*kj_Zd%(Qg1J!fESW}}ZqHTKp^ghhcDkqwc0+J@ zJLY&B<`1v`UuP@digy?;wfzR0^bYJsX>8Gu%zkZ^abckV?<{3fmRX3iC*~4<8E-H? z*nJ|0SZ9iSeA@)lLbdX`?+0ncfz}isLv0dPONPIgwQdQC%e>zu48?|=!SD1~ZM?=u z++qblMW3H^Yw*SNi><-J8@2yM2xLrXu~7;>&mj0jNFO@ovW)IYz$K_nKC*)D z!Lio&=QD_*#=PPO;&An;$nP_ox{2X1(+uK-qc)He4y}`35AGoKA;;OuVI;q#hkOsV zVe0QMh_nN=(TDIYIPt!v{Yx7?bbD9Dqb-Rax$GN5uapD!8C_~eTZ7U)b$&P%I(V&t zg1Zls=qQcm6$s9PBDqzXKeN5cVhfARNlSS~XdN|@a=Bw$@*mr*gj`sVyX^V}HP?EL zFOvO_ifyzdt%}00Zvyipv6ktcFOFkB4gxDZO&B{+-a)tarA0#FHcX1n3V{&;At&Bz z)ykU0Eg0;|L5P)iAEP)h_wZ&U?7-hEuv@(3)%L1A$w@n#^*U4EH)W9uFdbZ2cY&~z{XgeQsVlgg_u^;wCzaKszLeiQ!A%_Hm~im{VyFXw2GU{67%5<>h@(?o$JpXT(kFDlzptl{ndJ# zyXu>})Gl9k;)eno`X>Zk%5iyT>0Qbnhn|3>zhEDs=fD2Gtu*|)z2`T1cI&u~nyvkX zP*ZlJ)EF}TRo&3>Z-Ev6y|$m;LAo{<8D=Tm`}*V86i4nxOtAHP>I7L=K$a0ESZX+| z^mUn#NV1#UC&MXHJpO{L#W-U*@nBUKKY}j;r#8}-#GWi9f(wk$PqN9o<=C_*4LxIdbcxrEi-!eADiue9bg0)e{68Y*xS5f3p-bySCvAXC6^j`E9(Aw%IAB6GY=QD z>i$0eF3ulk{#`7c7oNYR%3GmbY$Pga;VB`$@5eT+Y)+9tp5iFE#8Jw?tC)gLa@IAe z0rYL&tKJA(-lLrXAb32cG`q1);MTQG=lvio2kaZIx4U%JZ-}E;!iypN+A7k#Y4Qwa ztN@qXEk&Jz09BnMRvIFS`#T5mC6k3T%dx_VNj1sO z=wk$<_tGb9hX_W4aqm`ijixSK=pH$qMy_r7ikJZ$rUv?nJVMfZv1irQ>(1qt!9L`RtAu5q&ah|*YW4Qc_;!ReRpTHL@)*WF2!^6FveNh4moKGEq0>XoM!>h#tq5)5gv;pU)r*M&&K$J%~<*~^AY0_oCcCP2Dm zw8%6k7&;;tav(rDs~B8sY0D}xS(3OQ_m04p_Jg_P?@djjrmxhVL8V85q}X`KY~3gu z)_KSj0j%KyY7Zp)UXGEb^jX}RhL{)R&hs&m;9nNqXe+gJ8;w?&gQHx>y_X6(p_qm+P^qcFUFR-jB z?^Vn(Y))KV2h9PQf{Cq*1y+30kjmdolnxEQ!o+juxaMNI_CziA`f%}%q0k$sRE~j0 z_Y*PGbRd2y?myO@JoPT!f_jYy25$mHWK#7b0-pdvEs#>=;Kgss)M_t4uf1VQO2{0? zhBtxJ?=KJkClAYHKCVzom+Q8%iC4W)Z?)b0RTsZ!Uw}#VtE$09`1h~6ygRN#t2RX_ zZ>!=X)MI9ktW~9vK1+|a{03`_6ow{De?WquG*!tV4fNoq&!FRm8FypO_;P{%ZT{k9y!(wu5OHSFBw$aEFCv82oL7qbAxwOqpjo>b?|hfZQ=?{u)oc`ni3GA z$O+Tu_4oXl3!N|%hFUVped7|bsV|_)Fjts5dTb5~Sk(He5;P>e9FPKOUDa2zGiR>% zsiZ(eDBpEE?)}`t{mes6pOG6d&3(iAJr}e+<30;o`7PQgfMAvu=8Z$fG1EDTTnqg{ zM(wGd>3&h_XxZ7z&R!@EW>Pa&EH1t##+Ov@H4rWeLt&73F*+r4N+=AnBIWrD!rs4M z|Lw?FE9mfd8n3SsGxny???m+qSz35n<){x)J2e0u8`?PCL>2Rgjd8(i=|x~!bgugz zKtxpT({bJwmpUycGiCN-YvHx?N&%Z`#0E6vC0V5CjcTsj&e`VB4S1={F@@*ZGTFVk zHjTE({f?4t)^ClAx!SXe5&2vQ{rAZ>GHEUXb(|JJs}`Y2T8DhJ`GD4~-opEDOBy?6 zZr^X+86VwS{J-U=A1;BhhlzHT&SP~~LQ|e!*vFyxX~Fn^rMsQl)`J_qp9%#MYHR-W zS@85#0w3zO{c^o?P=-1v-#aiv9V+*lTL(RTN5F>`;KMEOVUbngY8{f}BK%9wR$uMo z_V~aOay^FcB!|)MG_iTi)`_aMrXS-8S?s2Rtg_NOzOw}F|HRI*Qh2RM?$GgbF)-_jI>;Qoh zwaXxSy(^|EvNmAwKI$A1OIAfZ#0{NCS5at|d3IAdPBaKpTn(V%+ny#p%eE%8@Z5af zZSWr~Z=ig64@tiS*j=L$TR4Fq>B^JESuvy#1lSDJ3cGY?n(;)+_tzeqNjU>`67T3& zxFcFLj%>}M5EdXS$%Nbp8D?{fCGIdyimtVuK`F9iT6OD`*Qj$!wpqj1v!JnnEu6k` zRk9u$xMN!C$#CLxST$$%-bC@ve1jZkgIMR!60Zgc`bO}d%p&H${XJ7#XH+gKL$X53 z1B|xhU&qwdl6o1{PIo}lChw;9yptZlz^s-6NvdO?(f2e|d5RSKC!_Ag3sf3#Hq`1- z?p&aL(Twf)Nu7+R1@2t3r%`*3vt%p~QxoX{f2(%ci*Qghgd6z6WA2^#&ST8;MeZWhiOlVb#Qy#?z0Z!`8KuGFB(!0lm#*5 z)|jA$^p4Xt!WR;|^7IR2+7eG3u)S-3@K)zsIpnRNz%M)R`X+JBtD$jz?uME@&(htT zU#6V(ljHn7s-Dx^Ub5oHBK|Rczyb(giEghf83G56O)-*YTF@{+*US?O%cbM?|I7vl z_7I_fCUU3W6x`m{eTkBp#FJC$CZxu(s3L16jU%by-Np;rK?%gvaSelkp|2>%SlJI9U zo6_$=o>oS2)FgpZD}EJc5Vw0+!gqn^ z*H5RK@RF|SJtF)uS9Nby?Y<+k-7~X8HHxGSnQlAQyww1N3>oa_D&H4>F37Nk)jT+O z=@bxEft=)%F-sq;|4S!yuo#<+eR|j{qI@Qv8TQLEq;N<~r)49Jzqop$IQxe^w(#m!q@fdh;jyafZ?wP%KNT|Vf`2U;&-1`leR2`gUb^C$h zcpu!zP4wA_5UOl=nVJeSD&RFtI|LQUzkRn0`juosn3c9hvf}o%-hK+{{}fszLL{vw zIvzOm{`|Vy`?!8{R4DP|C#vsFJjV;Mmj_tKpb_6SjJanI+?$8YU4oRT)n|NEq-p&y zNO5W{)j6ZO<~HFGET}-#-dHvjP|=9E2tPgXztf!3;Vqe0eMi>LHL5SBBWA^yh_0%g z+snV4^JjYqXA^hPhGqOQ5?UTRyv>m8W$)1=0W0p@TK=(xoSlPS*N5RVU|1=;>*kw- ziGQ2#3_^2RywWXF>Yk9T1WH{qPF>j`BCG%I>*`2_s#r`{zgJ+9PB*&e>o#&7WR9kV{(j-UNt!OGcO?MUhDo=e+E=$Zqc10sqW3SWoNbc2lCas>n*Z_1*IosV-sNrI@7-Ym3vy4^z)qQBdmV!^50{%)Ek0$##&5H#5v1xbYcbnM z5BgkimRJHwEa_3?MF6ZKUrdmGY`Ygv@$K*eRVU8k%qHaHQ4NITM*cL-pbIrxMkM_b zynh`anogVN^GS{z$p3&b_R)>p=Cy6(a0Yfmk!9)nr(!lz?+h^mhPa7$h?#FeW-c^9 zRPdwGRWNVw+d^Spg*2EIsf%s9WAOOX79gwPi&};_=GJbrudyRiCx~Hj5|i zywbm>fue(t5x+7bOw8hyza}Tc!C19Xb&88XWJG4?4R>c)qX2{eFeoZNMTsG5MN{%m zeSx*}8LFsplXcpUjQ3g%cP`{3ep$H)c%M>>}OI!6r}xT4lLm7y)F!h7Hq8958yow z?^lN{bJT1#Ib4vNkQ{|mo2|iKHBG&T^`Kv|&rgDqc}a|3+SAE`xpqA8HatE)j&^`= z;3Vn9AB0B3pEqerN8-vT7~jUf1%}+>9M&+ZH6`ru6C;JCY}fcjyeP^S5CpGTS1tCG zewH-r1{VA&3Cin`$+Mh4mz>FFMHEK|Oxfzo?8#q9lPBuc{l&D`C^8kxM|N!1yDoAw zmkVx9nj6RMs@YAO1>Bvo5N7D1t-UMdxz&P~qCi~44s3|2tai8MBwT|7XH$8!t1@mc&+%6Z~U2 znWe#9T2(iGP%wOSt>=PrL4M?lg)m60cz)NKR&}>PMuz9~)eC(kvXxwlKIb-*Wy;CLkwWBoG_8L*_GXG@D}@w+`ZjKvG`EA~ zj*jDLciKOxd?^;p{6oyo+l`!tKQBa$Tm%Qi7v&p6yv+kxcj$CiMPl-tx9A#OG8IMM zA0?Y(_2c~Mw+TUfjv_cYO*0^uIliGaPFaHTNDa=R8PKy-4J_>r>x_)r)9?KQHIV7~ z1HE5UsJYV5;8NOXl&izWS@cfmE49|u(I9;;7Ud2Q;Iu($VXruGalB>=Egs?bueCIDaH9J+8f$WF!6$o*m0BA7Evkm?`_s) zi);KQ^Lm5fy9XFegH``j_IFwkXr_pUV5JiVA^IcE_U+=?0r%vED>P*cD6|4S9_F<* zz)|LB9q`6A>z(-=A}(7qpRsA8P?OiwKMpd8aMW&SWPs0+)w=tDmF(=8FhAJYl{T?k zqj99s$05ED!(SBn7GDm*ibJw+NUcfz>8!c}4>8wH<5auEx8^#Y``!5ad2#2(pWeN> z?2mia{yIJ@5tBPI*If08d-SSsUU%!P7nQHE+ zcB~S7BP^o|Vrpd4dX9D`Xop+2`Px`DUeivOD3)Au)U&1L-VwcoB24ivzs|V{t#8}_ zR$l5=-VLkYDSXdvOH%083T2 z>}j(zS{;CIUiZ;gX(0FA5^n1mEf3&8({8qEuZ{Zs^GijTp*l0WY8!f>Z^Tu6)K!?* z%!^Oz=Pc1LwS%X1-%HFR$ng|#T(76TP|5H1!p;;!ZqvaudYK7FjT{$yjQ&rq_T4GX6CDkP@^^IW_EI3npS%b5%LCm(6Yr|S z5HDO$;DWLDP!ns{-8aNsc)O}YBofq%hHt#Ym;{?Po=k*E_Nt!kqFd;zFnWgy2v-&e zU|_s3!4NIBGbNiLdxEXpPuI*K7e+LCbd@05eB0Ttd&8$6CS#lS6xzL}KSItGmSnbx zT*Wc`1gVpbM&~Mf=NKnKC)2am9lIw?ynK09wq0sIa=y=-t6H9|TAr)wnyoU^>x!!h zM|6BZzgLt3*8&+CtJV%Tj+>14Q2TxnLlc)AfBquIS8D=uETcH8vmI$C{AFnwiPk!5 z5IIM5)NX@T@r!GBm>43zhcgv_t{3Kz{aJ{joCKY9Nk2dEzPQX3;g|V#XoO zaV7I82=FN8a(qK!P=N`UNKqNNs9$Y#%IGy&UzH=+fkpWAzyw-vnM5159Y!v(WFOJ> z((|AqkN+X;zuGP9mKkDZJfB92eUoEFBG6=FBF>*;?O9?INvY(J5ULGROo`yV>FAf` z^p9{u?KwZg9p0pJkT2DufbtZ63ne0}|7a6-NL1|6D0GN$b6>(cm=W`yUoa!U-x-n;V`&m7W~ z{bH?jh^TOgsC4MkYGAE!C@go-Bgw2p9np^1F6-L3t$d$(%LYwrUvOxqFxE{w1Y1q& z4-~#1yasD<)OYTXTtRWx;Fa$CpAUu)H|tyt&qGl4wnE2^BxAhxez=Ezxe1zc2Wl!# zG0=uyaKN4%&ti1`J6})^bQ#T;tE`rrxvJ+aj=KIz-qg=`mR+@zlw99Sr`=yQ*JN2i z07Js4*THD}o~&tS$LJ{VF?^VeB1P#{BPHa#*pZ?!enXL3LsLuBV8+p_avYjPXeM(= z`Bn$%?R?uyJi2e}z45=zV%lwEz(dnjH(aKvf;^g(R9u&wW~wjfBPCn2C1d}GueT11 z^7-P14fqlwjnYVil$10`cXvy73riy?Dc!k9celh!H;8mD-CaxV?z^bJ_qm>bp6fc- zFlUB8?tAZ<6Q6VDOt1*rT<7@c@qWHolqB-AwWh~V@S`qQfVI_YZPO5$@wD0;yEi9c z=zu5HI*NKhMY`P)qfU8IDpE&WeTiziqH1VC^%O>Hhy-r>ps$qV-H0ii1rR=t42f3B zhP7B(UZ;Q4R2=OEW^*H|-h2o=EGqn(%k+WrjkQQ)kg@+4sUJ zS9GT?WI5>+5*%6lyCUJrr)6L&(2Jzo75dEZk$%u4KJDO2v{RKpBAicqzmXtYP1E$JOHx<`u1kzA2`mMyv3NDj_;ceWL5gieJk^QdtieA!uuSv zfLrTV*W&d5-6Qegl5#bmxyI97Qx8E-F;B$RSP@267TrMmdNm9)w8au%Dt(~LbzrCk z@okhai8ddi`g)cU#6xgNITU3XwJ~)sTX%PW*-YC;J=}lJqzn*J90zQk^pjvdtld8A zNa9YrEANAJ=?N54MdR{R7<6dV1uK7+U5Dy?mJ_qhzdW@?K9y$fgw)s7;K|kd{l+&n zM~?rnH^KE;q#C<}{_mGNv2y_BvgE#6jrL*T89gsOb9V}W2sPXZIiv(AFD8K}Jru!s zNoSe^iN+az$_{rxy<6bIgAn&UFg-w7(C3p7^SyxJA7Z{=6#7Ff_jyR~#MEg#LoEUj zq7n!#0G$T((L9Wj`&;$Mo_PP4e2&C+#V3?U;%oEaSs?DIOqQSr6?roWJ(qA4Jy!W= z+<<=r0>Qj8P0R1uZ#=#s=T$oN{1i6Fq5&zq}yRSwYHE=%97Z=4i{0x zxC~mvQkuAJ(3Nkzo06ZU#1M;`;zHrRp8^69l;-oAD*>5H^!Cc!3>1~q_&40y>7 z?MDa|WfO@w`_>$(rV$>^c2{`xmq*OdZbXO2(mpMmWgAwCS;7c;zVu>}Q+-k1KK_{+|3GMz}djLHKPvn@C7elMr zCro^_NF}rn`rXoqpX%L@zT^*kghEhg^?zZbOI9!$yv=N~$?Riz%Ex#nAFjldQ=^dO zdG_Ub)#Jm|lf!BOfy1$dV!%uYSeL}h%0U4@_XjIb#zroTXpeSZ4+rvYTR?=2-JgvH zfnJCm6zmNBsKM`!4R5ogc)y4Y9n&)rs#7ofMB|iU;bB`VwXl=6Y@0?#TWAHGcSxRR zcU9R-GrS{7GhD_~ne`qA-w35Z?Mp6r+V3+~jued_{?OsS&dGHlAYif;w70x+=__zq z$ovYtFB~+zzNnTu#HYpbs%!zjOfOusrwpBU)Kv3Ar$MJ&uTZBUQAe`vf6)y3H$`(} z^EYHIGfk=^=R3<6f9QN?^x_YlTglxJ*+k%bH9a5-?Eb#kxrC6+-1S%O>h<#7Dlpw; zy>_W+B9$$>spj${(An^v1wmU_y@Q9xzqIQzCpM}pF{dxiiE{Y4)^Z>1WEvG^8VP8Iov7F9D0R~dK?Miai3FagZrZz8I;v_ujIoBT*NkP_JrJunK-dktev zSDlgD@+FBCG)1YDbXMwrvP=SpU3qV@1iL<-tWZB^K-6rB5cR~VxpDaSejAI$RxEPs zCMX^=R5i%6-U4=KF}x%7z=l-Z83Yq|6MQy0rl){HM2sj-16nbmC?j`Sz9#U?=5FD! zvi!R3-EB5|w=h8~ySn7!ceMN4gN-4>{gW)Idl6x$S6wt~AK{%7nc?0Wr)8IRmy?cz zFddy{oiaDWgA-7dlWvp#N}Y86)p76>ii>+Br~6g{C~T3hGXjVH@gmlh<~?jdW(|g`!W$fY3?Wl>!=4nlh+_xG-~7ivJih@> zF<{UxgxR3G=)|yRytj!+9{Wjk1N`S0R`G6^k6)jp>uO*A2K=(bG%q3U?u{UYoJ_=P zk1G{+dGt-C8U$DW_(&!e@(o#Ba#%;nw0B)E&z1gFF2dxkS`g~bVc>|GMJl71CH`O1 zUFYJ#+qdQoM7T7caTu6nROY0e$6~*Sydb&G;iBxUcq3{;fe^?2!h24eh$MOSLiZCl zM?p|r1Y>t|@|wZ0bEO60tSj#yBAgWq{~GSb(%t;(u^g4&Z}3t;^n6|fTZ?ggIuH96 zGrOevLPAv!c%e!gJWU)5E4N9q3zX>ETvsLugc!kl8Vr0Hz8gf^1)^3;;wCTkHoqz_ zGpJ~FVR6Mq=pYX}$;54R65OV#7`-q3cV){r(iNRmqS^U~S`>XnNRg82q zrX>fE>cR!SEHI^zqo-i(7B(4lzc&ph8?u}WH7#F^M}2~E|C3rc3b6x1{31ZQ?A1EG zVf9}uEb5<$KcfmkVrgt&u2Jw=mpKwcTTdy(uAz^{4JS-BUDWT9apnEDZ@gKFv}t5A zK~ZdI(i;5>y-CR%{Kb)M#)xWb1xZK)qUw=z(cE#?!GE1&ecoaw-J?V5QqJpgroFx^ zySXJRW{1(4)$w#dnVUJ!w2+ISo~>+r0uEq@LLJSU%d>FN2Gaeq#}@`o|`JM)KmbAr+!DmMy(&z#?DJH#4O zCCON1_`!=`%AKE3Y>AXlOhVZHC_~#X%El8;8oElhQ@;AHoJH*1-hvN zzoy1qk~S4yQUIrc%p(1on8fONJkJl71$;Z*e`}4p>2Z(O+M*jfPt)8u`*up!SEi%k zk{W;Neyvw}P|Apa{rx#VIkHDcNJST9NNZKqRD;orcTK+M?Q<+Z-Ea(;~NR{r%8$`+L^^Tw~X%lL)X+ zKy82+W7TM7z_qh)y6(EX5uu&oef@D-;rv@Yt)9b=$EG}fk}jjaYjFd;#Ty2dnNX$U zl>ta$IkYR4j;PZ3)rtTlTv?m-P`4j>*h)tAN&tmPv^7Dp9HMLUb_NKOi62>ed6f_y z@#exe9*mg#-dT2|kbCv148Lzo2<5Rer_3 zqMH$&169v#uKSdp(en2X_!_X6o{O#+RV9L?Oq=SK<4dW)7FA#iyNFviuw`w0$!2_s zPsq&*QGfC_P2ea^0GfvP<^FQFnU*S}w)S;Y^}-pYd~``%@dIhYdH2Cvx?ry9Vu)Ja z$`0|BBRAq!(y3MiUn13>LVP7WTMQ^uJu%ALZaGZ@G35e{aSd(rd2MHLsD@N?hpU<4 zzIb*Z3n6b?4ByfGDz@;zDvZqOjCmh#c>4lzV~40x;k>VVox<^{Li7n|d_y+}U&px0 zF>vrGc~Di1UrL?EF4V#m@d<&01t4xJAwYqU@HVTN(HA!TnCfRSL;U2yZs(j4B9)GU za5M~_f+*wX zlB35sP}ueTDH0iq;5_@SgLuI**CNU2^PtOz74%xxM{| zGk!x%WSn_%Nu!ZMDLcF4R@Y=s-_gi~JCDV!zM~mPN|BQe+N*M(j8#V6OD!dsaE_Ty z0CCD=s^q>ARe!}+uE$AX)Wz11k)Rxe3cEU*>+!&o91Wki6{_j1KtXXZ6~ z2fA{b=*y9>Vc{>i6KP7#9cMFJ43k?X>T^R91>IhJ{Lm(3;fU~=vpi&pa*gdmn0(aMsrRVtYiegw;I-Uy3~621#~R<$s7V51os2uYb642yTZFc|l80N`OfAivS|> zE;QQc-F(L08w;9XJdP+f5#bb2SDA}k>O=iZG#@6G*#)uGx2IKzVkgav4D68+ zh1jzT?EPyd98nXdKZSi8|3Od_0$&FsQ}bS;eaU={=^n{Gjx)&j+n{&9Ad~e<-vTl!ig22s87LXRrKFIE&2ss=&G8#t6KR5 zj66>W*v2q$nQ&PF0>{@g{X8>h)th@0ak<3afB^YMXH%Z@>wFG18| z?pA$-S_=lJ;gC=fS4FP8uH?MHpEE=C_d>?Y{&mM7T?n{*(W&v~56%7S%pCC?z%tz7 zqn7a7L|t;9Th4wBp9aCUS%&12QW3XNU<=~xXoaAgga3BAklScB-x~FH<&as^kdU=Q zA2=AgGPK|5X8>sof4wt=@*rZtAU~**%qOnPES|$C|2sM7l2Lq*R(#JbMC{R=Xj+%4 z7zc(rThXY$92Rfpbgkf3E6muUOeB@&n4V+7daSY{NCRbQXR-=sB@+L<_i`;8uS?`b z*G?(h*8t+KBF3iyk~fQ6r~$3GYfc7NoE62W2oT0ea)5*>YFngpU#l>DFrdret@cIs zx+V@sR;*1L9UbC6r3^Z{$x_msD%gD_n#+k`^_>H}F#(tKBDC~CMdnAt50EdHoHEtae(U`Hz;Th5s!?l>fvBh(FZV1l--ZuQowIdQ4dFrN4Ptlk+%}k-^)IhGfPb zq5Z+cE|;_wEbJPRW8J^TG6@d;1z#W*r3(_dw2$eBl_(l+p%`(|oSp#{L_Gzt0&dqE zMfNvr*l(#B{>7;#O-kX3g%|j`=SF34(ofPBJaEQb@|DqmwB!r?I`WQmxNB@D;2ds& z@=I&phiVwkG^)!5cNT$@$uPP`K^0fdE;TQJDIGmoXv)ZH{PniEzvowM#(n^W9~NaS z4VhbSBJ!$n{gVMr&B~5errASiEkqDWN}~Hs`b~~w_4K(SS24#vKcgw7fuzSW$i(4# z7&vCytGYhkyyT)J=y76w5OImViZBJ?&@?eYJ7s0{cvSWLSjf&>(7z%w|55RtK2V;A zCQo6Cp!bZMlw)Uob_Hlz^Jsk01?Ig4Cfp(f%3*eAA$4of_b`lcZxI6L*dWt-qXqqpnyR^CwdGhG8Hr04_-w{W z0*Oue=Q(%S_i7Xu;Lq7=6vgF)>x`|72kAO)3G?Bh!*Z|%{{eu}3d(w+3)0{?J1-v@ zyE81T^G|V|IpN5@VtSM-kOumXWjbp>F$rJMavaFRJsAXelM4_hFZPZ+w+Y~)b(J@L z-lIy*bM^vM)Gl@WSjx0r;yBT{&L?W=G8#OoN)7n)lPlOWOlok<04*fzQyp6b;o1|4 zw;#N0x4Nmp2xz<~utZ^5c5*r)y`PX)a#yjk&F;TX>`&Vmhao-skvA5uAG&- z|9hdRxM?ZvkbR$3|tFX=90P|M$=cXO?lT z$cYN$GF`!>h_G1=Ou%8ad#k0r>g;48pdZB*5e4kMJGor_i65hRGi3F@+W?qQ`94b0 z)O1KsXcVSeKWonOCxLKbO0i4T&+5423!jf`vJ5W?{vqaJ1ED{}GMs-2n)gXDA9OK9 zb7pcvdyq|>nY46DzR&g`?uP5r?jV;&*fX`+TdxVi%nQXdf=w5KAz zONSNh29&~z_5&hdq5A>Fu+ZJd=8;8=Jx-jELkXBpF})`0wuDu8n0pkRWjDekAa5pKKdbM#d8yjjKxCdRip69=>t zOenMn{@1Lf78_bw5%V|g$X1PJ7yHF;qaMYJ4?@bmK54`X_%)2^werCv{f&lGnC{P| z-+8QkH-C@w(vPBy&(;$?T*aS#fbG9qkXdYA`*!WKxCdGITiy-tFG?c<*@NoC^O934 z55~00S?h|%4ItoM_VpAap7W-{&tssHVDAMFXLDO;kL%O?Um=}rA~kd`JxGE8&Z`ZK zyQ`n&HRn2?((v=f26^K*(7n8FJzQP=59_ZnI*%GVx^Bny&uvT*A{*?zLns>mz*bJlK)WEQ#U z3SR8NCtu)hBdkHm&$}rrM7_QH>4B%Iez8EABMAH#D`PNF1Td&8ezrUA_X7BUdow z2B1Y?8)sZR1h5CUe|h>fkPZE&PZ9Z5^OJAbw=M$DQs>G)sK&mU=Ivd_l3;OuT1k1n z@%Q6Q3Mo5z&>o)jR&MrMHo9&1Vz>T6T+QIoc4lfRzIHoDzZUE^^I+%yYGRz0ztk~| zd`%#7{V6^^43kvZOYmE^q3B?&0uuvbp=KIV2Fog{k}9*u^j`h^yHMqr6{?DB1iRHj z4seG#zaQbgP_LI|R<;cfmW~J(O5XWyZp%z@w@xa0qX?Nk4Ll};r+W<2CAcajon$IU z4jH~#V&v;Bnv8+VLhy@jKXrIJW_ub@uTa4o3Q1Y8Zu zHVwypY}6iE#Mm@q7SL}}1MfbtyR!537SmUn&$!5Q{;zlyz6N-}CQEaR*j2D*Vo>jr z%$`*+cnbAX;m8OJ>1h0xMg$c>3no0b{)r!eiyn8=BKt7%>IL~w;mv$2rzbY^8KJK*Tzg;JW0ts}`7H&obJ8TV}~^_z?GwI?8OjFfCm)v?yaPs}0s` zm9onHz8>VWsG60mAsDm7?})^bvmDNqHLk-;&FbN*ro!;HamB`c4TIL%w$S|S3CdxR z$7jC_KPjKf}prAXyQ(HS;Upww@kzHG>Y&fs3b#0(^t-!Ph zP;>eFD#ke=>htVr0i-OvIL_z$yAS3XHxZqqFYxTXtiS)&=^BZAkM$NpmY)?&nvYf( z7Sw~OriQUY8KIaPa-D{@`gd_r`z1lMnl4=CM3XqVYq_MHtY} zV-Ndl%n@K2hv{o!&c9E{B;&p)vtwpt>w}@RbXS}0<%8i<)Q0b-QAJq2Lz+OzvhY?7 zmFY>F4qc70iNv$|9fdEltmwa~aEm^3G1!WRLRqPC|85Vbp{D$H6h=HP-1kVo<4NZ! zo8uf7(AK27qE^qs9_1osS+#ILC^MgQ{4Jp1FDavPgU_Z z(*PV(36-e1{|&5}Sx@jWq$x^>8()|vf2(#JR_gTR&Sx)8doM8mp>;O)3FYK(YQ*Co z0@YQ5axE7Q0X7idzh9sbe$0?dU;h366Hh;Svdr?cdSg!dN3^lUmQ|R( z(NF=BPPQ#1wh;$nr+${jM-FczW=zG5pmKjtTh;eh#1!7^%W1&Cxw~rQ-U z{54KQo(a{ltN7n*PEUN-2^2_Y@)-uwlxwDBb>!bItRt=x{I_GhoX$JKU`*KTDo(>; zHw1AmV-^z6M|LtJr%5+h7(UVA%ay-UQBz@%l<%`uVqv(HV@T8)MQFonz27{JNX&CY zw-!1TH2KM#TF-fOpS64z+jBX^RbWyeHa#z;ts0k@#!a!SwME0#lvgVRe$z9-mBCQn z{;Qj2RhH7Q)0TU0Fw4%2dxdAChdy+J(Rv%;A?u$&8XfIRjP;lwH}K?L=F@z)L2VZ3 zX|6sk2{Z0L8Ji_r+DSpfmCuDAm)6y_t0_+hmddapvCwkC#B3|q02k+0?wc*vsE(zA ziAh6ZzjpcV$2AE4#C6U#dx=BV9*lXk-)cBdm2E!ovC{)QzNA3 zLb_hJBJhPadc`hdqtt5J)4+W@T2<-HRc4P6S^p3sC)ZyL+Qgq&Vt>n^@OqC>l4LxM zjx0}1G|aZ2L7FY)JBxCc4eU7aAxoT2R39JN3vIy^H#%2aOdkmPr*}4JlI)BzLJNev zFANEeu)oSa)V<*fk`YbCtV7CC{e;>@)9|J~4LhA$0aLD!YUI~z)QX-Cr(>SPN`48E zQznHao3Sd{v6u>%pAs9S5kV4TF^@~=x3{9J|KAmK!gFZ8NX~K`gVr>Yoi@Yj_w4RB z{r4i_r#&pd6x~FSUWq z0(G0B?U3eH(X;RP7S!}--|gQVD`v-|T&--Zu*wNCNQxVOYF;2_S`5dxHf~7y7|jR- zr5N!E+OeN=O6zf74TW=t2#M4c*)?cmjuT!#j4-|=z2P4tjD8r&`M&Lns4~50HVI;| zWtvx7OnWBn(4Td5X{@F~A}j9jxUbPaY9Tcw*%yh6?o!{0AnzZc13sz#%(qc8(VN9f>n4?n;T6uRb{#^t z-qB_2NCAk%H~bVXz_Ft;c0m%o6m>p>C*xYnE;(q(luC|_H>e)LG4VD{vk`cjZ~qN^ zRY?FGLw-~t8IDvR?BfLV9kcP~3<9o)Ju~KEQ8F-93HSv!fA!jiHYpAsg@D#|8#6ZX zM6D{y`79D3#^!ml6mrSSF0pq{i5bz)>z70GW4{*ea+03$1LyyWtZ$R06dZAv$vs0U zrWQsOnq93ZTH6JPYG;7gSwTs%B>;NT4kRWw6%GQX(2j{wkNm1VFWpbyD5F`=&F#6K zZ@qN6PguS)ZxWtoQT8}USUxxZaBg5F2^=BV#5Ke|I}U@X_boA)7UvL_A_b|9tuQPc zpt)vi8y{cn?+I6Rtn5hA$&q?zYp2||-66)6AzoKk!faNL7VKy?R1i^$ycRT`86J?5 zheE}tz6`-v>SI~q*&aN|6TtAZ-ed|JbfaLZh_r@Jj`~f*Qb~!ee8~pAMh~zC4=&!F zrkyo>3(6!i_HhN~a-OjZf5NlBkNIFPZBizdpTfiBQ47PeCO()y^ z>ycV1Ct6V@asp>a_Spv)`L|75Cf)mHXw4Z7uHxD3OpW)ViTOvC?&x$gO*oA=hTzeC z66{WUU9P?RmjdXGv*7LdtXw%z=e|N_9N*Pjn?8#Zj=8~O<M1NUN-ncCOnJm(apRbl)46Em$&trbNIcPZhDqW09Y%Rzk%Z;XBM+JsSIeJ>-F$I9 z4L%CESRzl!oHtUYC;mvrF)n!z_ z;*6hoM|S>IfnxBljpW8hZmez`mr^2T}D(F?nE6vbQ~HRFO%y{ z&A~~LB7wWog%Ki6jn*i|wI~+xpBNRIAhN?Zo{vcCRN?tmTd(wG&%DP%%*QSODQ{7g zqUYvM&!Y1@-Jj*b0)CdA&PMA5-r^g3rYpEw191m#sD6jWi&Gce1le@xyMF$sBTz^S zcWPI*zjMSN*?9ct4gKlG)GZ_vpf*Fd)_%`|i|;f)rT_jaS+UJR(@A$)U+XM6pYUTz zll?kNhPV7%nGaMeYNz{ODorbrm5Er=4$g&)thoG6I)%IfaIc@N$aqLNmJhRkhn4|Z zMg#(OyjobjB#a`Q&0mOPRBz*CY~nET#|NX?4pOfVeWlh-C44k}LiGq|buO#E!MOK~ zwV`FZ#+q=tyCz9^@}*N5O!3mG6tvS{T18obcaKKu&)uuz?}_qG?p-p)ePD)mBsY>- zT&{ptq&sTg`gilUedvD3;qL&2cUaQ_VKBq1lhT0K(AIshCYZ>VtI`LMGB8K#V(Y|N5i#=kSKm5Iuaz&C>>-R5kVNZmfZGMKt#xsvrfVe zBoS#oG^R|iA5CcDDONApBa=b!C~-b5-wv|2ox_IDVe;N^3qQEzO27ofcndmkzds^##t2+*{ov(lwfzMzMe z&3&1!>0iIS_Y8%ee1*2av*(hM81v=F?demikl*vh*wcH`bV|lVI%JCdxE$~ZYBB!! zoFY-7^SvxMMO`gj6@b6jtcqjd*FEnWVAMlS9_lGFoQ%L0ns!RwL)PYa0*iyDI$aYt zf3m<%NpC9noS9xp-T9sa%(A6vYH3lTn?sng{@QLl04%FWRNFmrBX!8>z7TurXx#Cd zW^1T6VkG5wjoTe-=eU_r<436W5&77%OIXS{{u*wUzBWOOS!iF4_{JQii~THbqaEoY zZ8WW5a+E=a6CzoTr`0Ssiblb;VPK zh2$df23hZFkz&wFY>*F{B)%a=!HYl@q}YjbgC^hHcyY8U4;{DjC)3}D4BQS5^^8TP zmn%&*BoC1^F3*^|tKE*IT0~gOYS9-LoQF6xaqDLNS$a7qcJ8@5Z41|Yfy-A_LG-2T zX#Sf5qvbwXx=kbH`j)TGkQlRczhY>fN@xm-B3oD@15|YMt8y5REOH?Wg$N)a+PYSi1wDJTZ;juCN+E|Ao#xiO|?C z$b>@Wkz_z3up=##Jb|Cg2U4`KavMD<>|Fir_9uj`WUS%7Rp>XXeT+L5UFlZC4Dob5 zK^f!u7=hqnnTbT4)@$CvPQMPN`SD*K3@1GjtZ^i*UAYWL&mejuj4I6#=W5J7q+c^ESp+X{3 zY-UqB=U&uX7k%mDB=O^U)*WElV%ls-v5W}Hi+~|0E5c&D$j=7d$UqEh)ON*FuYQR4 z3H6lujouq~t@zL{UI}8AgJx(PD`c0{5}F(6T z@%(yefo7~gGrIA$n)V{49yf(E(#RuO7Tpvk3q!%iM|j4b;*M^3F=5MnBxC#|-`3OI zzT{gBtt!|5%Cz~uY|)s?^L-)6MWwhPDkn@-h+;|M)LG|S@vC!aZ`bhu#G~~o*!RrW za&q@RGB?A@dRk3z2Q^SsH^DPH_f2b$+oucsBSxUx*MDe{6r0V(o3%KKMOUcr;-vlD zm4;+h-iTwIi#DpiC9>7=zC+^3L|V%nzo4BBJ*-C}eTnrUJ+8qB18oCV5W)F_Ev|RQ=x1x@1fcuA zbC5rg=e0fg7ufulC%h*J2RQWBO6^lEk~E8d3WWFOF9fod4d{Q3u-YIGE{DI64?MBU z&)odsXw|4QIoAGgQ5Kyd`tpqx)s+B-Vx6LZD45;D2}7cP25ipHQwk~6e3KNJm+I8V z>>^5A$;Bsl$y3tc0|hIO(d{*T#5PG)P!M%8NmZE8ZueGSnF@C9aFjMTKhb|PFP6F> zpYkF2ElA@`^-iK(LX_!|)A$Fc#_ikwoHI3EJZgo5HDm5o48`r@O0>`g*egFLD0nmU z#JK$0>9nEs0MuIb()f0R=e`Wg1@<)DqRr0wk>}HZ3=*c1=SpUtkkQSpu?!C}4-fg% z_Qlf@Gs<(#Fi*rXPyBjpaT-LX8l8^Gyr?b-a0Y~k^M}qy` zx*XlV8!h#%D+QPDqc3T~L3Rf@ESy{TBXhyxWFD%lGn6c=!5eSP7ff(oBip?C#h5|P zYAc0#K*ISC=dim2+l&eXN5#%&%?eiIK~#*ijV=NP8FRJuE<{zs+qT08i{V+bz6g2o ziwAP(j&F@mtm5j^;pcBEQE6Y8_EQ2kBG=wBeH`hd?bqUlA|%YMq3h(5kB?S=9#;0D znvN67+*Ffe48Mc)anicZyw8UbU5=tYS+}ThDqL6sEa{eRDI|o9y^ZAM$Qtlh95~=EPc~!(9Yd$h!_dPy^`X=8>PfCB>uj$)3>gI2%!e^S%GHO9@ENEvk zSOyb2IFyXylXM&#&F{;WwCVm!%3v}4w8wOTBYqTv8Tt{LqZ456)6*ai^=Xtgsyq$K z_y`3asfIlp!|J@FUd&Tbu_NlaTQr;7SzI=G8hVmExQncNd z`Yr6o1(h3Doi}~i27ZR{N<2!ZEZ*3W{P`P?kHQjFnJ6ykc$Y(3p|E(j`!Oy0$C$?b zy4`eMZ5_SWx%moyqAaObt$z0541Md?prc={J`jU=Z4iNTZ4JhE%+T^?ePyg|#T9;S zMB!za(b?LM?{k2K@7zxHtd)hds8;US{r6alr6%j3WRbVbB?n;qhGwpk4Wq5ZA*Qa7PGa%e#FbAm`8s_z(NmY$FAG)-b4}-$ zvns3PRokU|Yg+{>dnb!KmHP*djHpv~&QjEeDupxm4!t zE#OE?GhbhG!ckMQRWq)h-fd{gP1WF%b-DE4t5`;z<#X?ddX_v_$8A3EJdFnz^v&wK zlJ`i8&Savj6=1SP9Q?)zoghYdv5$B$g-Z8P@l)`#=1vBqnzEvnZ<*Vy-s!EoHjeSl zS=!2OtqiQINs~)|VID3(>mkP3(~K7pA$a{USgF(W$!;0nz6_f$)L6boM$3>#4@t;< zS2lj~V|459(oux#;u4QGRNJAeWkqNdQB5<-TxsNczf}`LE{R9PN{|V&f;13*XoQBi zaT#35hkCp9=B6etjMcIcuaSakV}fpe_$)n7;+n(F7tmLv3rF64yT!!8Z}Q)SS41l> zYEIHBYia-W_lVZ?RaUk1Gn)GSpjLz<5z#7UTvyMTQ`TnY4ftfSqx-HYo4H;4v(qOP zaqeK~;S=Gu+bq!p`BKJ}_gLR8BN${f)Mapdt+}`2ZPEX^h%cM%0-$+L;+t!+KKeNG zP+DES?-HwnDN9Mz4Lf$>A_H2J<8>qE`k8un`jJy$({d-jztMC4 zmN~}oU;22F^p@BYyy368Z&Vp+dY|D)sA6y#h{g>4^|z!>@Zhj{ev$iBVsA+iXh{tG zeYQvc>j3eX&EUPb=MLQ8D_#VETrt-+o7T9;^x4CO-huamWCs$P))?|p=@?(oF`^}$ zk{Tp6;h?{z!>JEm3?VSt_6dU;rzwMai@^JnPFH(PH<$8$cLl;w+-#+YXkEWM7GbDX zwh}TW@m*KZgK2yK*XvKvCIfW8Y^g(U`dTlkn7Jz@^Fn!sw*V@EhD|kW#Jy>cBibr% zjQ)+QRn5kyGE3aVy^Ujjfe1+q*4EPwo4z3r3;Z8yFxsl< z5!K!}3mS;N&lNcScHGQXyV0@xmpN=^`|*dN`a6SQm<5i>RQZ1VKq`CMi!(v1q|7kp z^5Td5lm5W2b35Xa=;CDyCd%(6qx;A>+0-02{kzE95QB(9L})i9<%?W4 z`|Fo})J-r}pN}hRWUiWHN#KNvB9uWG8v2n~bz2CxH`2C65l*>{RXRJuhn}(NVZ8sz zYC9_NxqzMLAKXrXJ%3B4;|3Wp0Z^R3#(bhYk2v-eHT(7ZT(X1Ezzqz|s1vEafI;SP zp04*};?MHllRKcpUwO`>WcCi-Od{Fa!`UzqF6$$7-57Om2HnLq1+!&&%c(x04yp=! zHbi+xQ3}twqsWD;KtuOMBoKY9X*f0%(WoFA3b$AnjAHRw1p(91dNW;4^G1Y8G2Ujm zP-0h@Rb#o(Qcm;-i~@G`NB_NRiI(w7pWd-PwGWV=gfhZJA|W@GQ<+fXdyv?{%R<&GzjSZUr=^nq?^Ue5O^H{X*qs~PyJ zRG){xkYk)K^;NML{wclY4^xVsR_4|#{4p|-cH%R#8;0dHTvfl)XRI!(HLl4CoBrNP z<msMQ~+m**ry0U2Rck>8>iebj$(Ks*+=yNeNkQN)d{-Tb> zN@t6cJ*e?*k6W{Qj zB5(2wysVYwv7uifr((IQIUui^n zmr4lbpN2C;{4A86>J}ZGDyF}Tx~O-8bp8nTusgbMu{^>_fb3= zM6_!$-(&UIhyqptLQKY-Fw{p$(g#Gj9Rnt%B(Ucf>Itw)^AV|EnPbFIDb;uwlzDR$ z?hmHEr8g@DM!F#PF7&2lx0UJg2R3nid94JcscSg`8^Moi#O3GX;_RL0AW3*QnFtrc zWxx+|$_FHiyFV5(zvziDm)`8S$44*p9IK;t1^Y1+pDisegNet}jDsoiQrcgWI@6P` zHaPQN=sW*p;e7(Z;w|8PqK)ySj+yu8AC$4!qT|4|-VdYWK67KNN!(-q><5u@QR*cTW6X3$Bo@-I#wdx4H0kc8$0UNgb<}6uDTI6)K)@o_r_@ z?Yj8`qf|;Zw5Z>j5FG@VSzDXX@hU}RV1CRxG6MA67!rTl0LK4R&>X=&^Fn&P^yk`= zWb4Osfi1IR9@0S!hR{@DO6?6DkTVFBE7f+oJM-**k%vsJ-8nR7?*p&O4WQEKbNDl4 zNm0xaqhD+4_|8A88Ft?MRc&@|r*bEa5mgQpybds(OB+=9j)>Wv(%p7ihKMMo;gqk7 zAQpysc+-ThE>Xfa%v^4(^vqgmS58U;0tde0kv>2;B|_*62JiuT z*B$50SM=Mso>D9j-}hWH-Zbq#xFavpEPV~|&Bu2r7hT7##J}Y4AnM!U{(T3gvAcRPQc36!A|OIKdI|$ zHZm(#@MUi^j42C!%vkzw9 ztFxVMIj@=F1igG6CRQ=qSr~If^t0D4pyrhMqdS+3_Tbi8-S6}XEP*x(^Z`86*Dpqi zXR;hrnlw9?4~!P+|3u8!G+GYDyt8%p8SADvLtW-$87kOR^^{eKp>@(WhPhl3$%zH1 za(P^wj5mgN|1vY2mge__-}qTIHPPOqC}Z7r9-Lyu>7G+B&WlK>$#KZ%zk;j82b_-J zLZ7GM2GIE>_$ksiO-54*e)Ehja57Z%J1EUIcD`T(ir>#n>kIb(ZmKNoa2M<+{~`zG zN9a0Zp?(?VS1p|>3u#k}uK%4?S)8>EW`B<@PqTk-TS9sv0^BjlP@@av8h4WihT=y)n&g2!JuKnhCK$h{FPGAKyQ>;Rv7?-jdt+HB*psb=-{EzYve>9C5 z{8=3(uE38bkMSd~VCwligK4g+K{A#R3t#ce3Sl9ij%7dZo6T&e>x)EsKs9MtA@RdI zOUx;=H5qw*K^mz~&{3P_&#$TmdX z=vvJLOiK|2j-BZFyQiF5)!+(XcfJE9r&(~h(?Y?AqqC-px)%p1d=h!+CXQpQ)ZGJZ zm?X#vHaXddRo)h@{<#IeVJZrd6S3J?gQQsNvg@BQK`i*_Xu`Og-I=*fhx4Hb`TqEa20oll)<> zz+3!hgnFZ{3AR6OE&}|XKstLIlPf(`Yc3JOlg3M)auVH&kulp8*FEIrQzW>dS&~>U zc;LrWLeUbYOVO$Vt(F2_u`Y1%yVxRTQm<-WBzm-gC0l$-?=9qs- z)wqFRQGKvhDnveJMaLzKz+ZhP`I7GG2Cj|s-=EF~c^lPl(1MJ6rxx>vK89=JfCbrc zNe+2hVcWN$a=sMz=GI__%(IKu5WhxWV-6L&xPakl%DJ7ziY?jv-|Yeu}P{`FQIY9zrG2(3kVW9NM3a!p}&W)B~=3jJ^dM(!cO z;@+E%fNhIT38UoPH$|D3Ux_?aIe%Zb*028iXeHKocqA!L68^L7n(Y^%Jsh<)~=ufD=6 z;}!$AT<5E8)$*p}z7;yjIS#l{M{%_@>^wZ5**pWw{RS2^dfzeYsXVj2~o;`0QTv9jC6^ zo)6m&3KoWu+i)WXf4m$hLj%dWc3wGes_(2&vGR)@5s99K`v4F-qqsYdoh zuN5;y$W=YJ9Wred`xxMoRABjko3H^F16GjC->^H9+{?oXRU=-@v%$*%*H$ApM`nGZ z$q$u?T#wN-{KW4JLqo}&g|NR-m@3IJmfrrzTo%{97WuxhYU^undS#Q`bkaoASgA0i1Zq%g7hX*rDH&P5fG$HF9D*6^bXPq2-2IhP(qd7J4lVvJJM^&H=xh6 z-tS%STC*lM=l)4DnS0OKXYW03%er%mU?pw`yqFByqPUeVKP1Twd_o zCn0a2bn%?(2qneS$K~a|%{NJ0H%YWAQ}THo{&zcR>&CTTr3kVQ?9{=mzA9N$tk2Hz zR5se+Gg#*{xITO5O&n;HtXbD*19R5(%shC#^mUuu4O>Q@D$T6^k`J-61bPGoef>NQ zE0T3$8HpIdO{~F>h)&ooAx{FmEItIdjGmzxAob!)mMUKd`v0_P3+R-Khcj}WThpe zi!2op*;zJWY4axCSuYX(In~cyyT<>plF2}6SsKA}z;DMiRA_%v<;LQB`6HQRK=TX3 zz|28nvbdAtz{RoK9xsL|Cvg0rSMsTH=D^J2)x?N}-C6In92CF>y(@I-C9Ks=i*-Ce zhl}PCTXMOEE9-W8+yyy>O&T{B1Z|H%T->hmkM#yFONd@FCiVu^POk^N<4Dr3LTFdT z73%2~>5*=XkJj>)+S!)cap+VbbgP)hi}G9+;)BcY7m}P9#7<`#(a)vr(AR_O{M+Hb z0~W#{k-zff|7b9}-F}j zqCGFScgEG`b}AdaXALl%XKrJS1(yau0}Td2C$FM3Fxh8rLsy~09aI)(`-DKVZP6Mj z$4AVNx`|-Vu?yC)-OjQymGdWJ;kNjdMQ&QgovE2aubES(k-F*r)P&&V6RXR0Y+#ZMwEI=L&Bt)su#PbD?p;d#JF3 zgD5e31TrQ$`A*yj*$?CwIhE^d`dBRqX#sptbXc;E8<(W8Wi@x2nq-aj~CW|L_7^1xE<8H$!cV z_N-H(nSw&S>R`HxydhSh4I$Gt6$*ktaT@B5)`I3KII}3Isp6&z>f$j^XiX@ zAOsoeOBP-7Yt`0%gD$r>>RkzlwLTfisbaGnZ4KXCTTxl&54a!xE*{=Ra+cVp`=P!T z#D?oMxpBe+tXxzt$GRBn*IR>bGiN`zs<3M}G+Bb@gRMux3xfWwIpKjclpgiw(hamC zk!qC0`rU^Q@4&W&Bnn=$zc1m=Q>-T|Ch(~XL9r=KNHHfx>d#lcFZm8xuYB+F9bLR* z|BpFsv|`yX{R`j3WvDU#QuDAR1E!7+SvQi#WSo(YH3naW@?j6q_1o_9sj)cA^=79D zx6EjaSu%cFD#g8^1NfD~;DIR!Xe*y1=BCK+zn|^PECRVKR(QU5F3eRoR7~+%WHV*w z#aVEEsMcWpa^33@w?5X*;zljZOx3#K7r=!K>aiYN^GKIBU~CYQ@#~5D`!UvPE08_} zw3$6EwFp#}GR=}4uO(d4BUlq&8wn300gez)FW}aeGL;Wy5$fWA+F{g&N00 zY0*Fj5->)8{-JL9xV+Xg>dffJu7^?Lc2HDt_CP;*c+4@uhOEt?1_7C6_lQz5$~+hZ#MVI7F*@ zU?3=92D%W+>vrTsBIqz(x*A0DbxKNqfhyGd5!n<>L zv9)U@oAoWOzKdZ?nR;Vxkq#OYu&vDegsIIWIsKKf`RdN6?zzRU(3r+-m8u#5TJG&T zJm&ozY8Yzra=awUH+Tv5if@7|ork$3#}@!ZonA`9f-{V*pOQ{+{oU@8i7rJR?<79& z!WV9O@j>oH^Te$mzwAK^K*J;E&t>AmJ$XAtocvPmr<&TnFFb2bAGRMRWD0%hr}^sf z1LC+=^_+Hfzt^~5RDv>byPHIxg$px=(|=}a9(i*ea~BR(3d?+9)OEQKN z+hN}(#@Z|RvLgc%bs+H?O*n+xzpEhC?V5f^uYkTOLs-xc z9)HJ1kD#=)khHX}f&FbEw{ggYD6neGuavY67+r_{vH86dXBnbr4{_`yvGG7vjU;=< zPMedc<7bcAFlsBvgi%Lo>MxI$J}Va0 zh&?TsmEPjmlG6bd%W#C@7e2pINmMg;SpN&Sxpp~Ro0#@&5l$iUi!!*B)Poww5V|QmCnAY z_4PGTp9F(n|3KBy47NLHyj1TbWpTJ;PyNONEu9ZG&C9+gnEIp9i4R+eKWx;hn{F%? zh-tqfiXv_djeq}l<9=yG?~xftFlP8VGU;~2hC+Z9`BJk{fl%a&-%W&ft4?Msr7C%^ z%38-Hi|Kc!`-1PG=oQ^W#|m-9;1{5d5?mvZ%N!L}&*Tu=#(hQ6L(;q2gx>>+3VoVH z2pke4%wi>s5>+};g&UH2Hi^A%>>2izh} z&SDLAM=qvnR2O&1Z1K>{yJ;&EtX~Up)@X8y=m~Bdsp6u*{BMRtV8oQ%CFyRLuj}{Y z8PBR#QyV#h$vF7vF0OetJ*kb;7Bj=~9+$=8o!>1&bxbn{Bb%#|b&z*LY%lzU>@-^L zJN;~Lr(Ax{Ke^CuJj^(eA{Sr|wQ5bQ|@%B5PcJ`YS-)us`dw9%1FDWi%XOCMRU zrG-`?lIUlo<(r6*`Sj04%sJ`Qgl~WPO7?cJEI1Hc|0a15j8`AAcGf2cTGJnbvv-s@ z4~e8L9sU!vTV#{H8m5=|YrA2N1dDQ%pg-(VY|=4H5hq zB^*1coth32{MzZV6%N_&7!;=6)BD>6PD(342Y(5u{qw18K`sfA3Qm?jVM;W#SBY zU`Xu)Ywcc=$w{ren?gB^1eh;%IZ|^Y+H)iFJC=nzmYvW?XK(@!)s8)Q_yIipP>gC1 zPT;LNQ(5P|>7M2F-7Hu@PO`pzs~G0HM-uTm0N(kdK+2KQw#1RLC?=Pn%eI0p_*-mS z+NhCT=6!4(ZL3`*SUhs1-$iIkf5dX77VcW?I90Q5x$-0@bpse>15;vK`b!l~V@W+Ku{^FBr>*@Z@9IGJ&HApK=L&;wGqYecz>xVRk1+ZAPE~LiS^W?A z!BEJRVW`}{iOzB+p3w^sJg9fbT@90Be42L9{xt)5UvvGwm^S8u!$)B2<}BG(Hf1H% zsSnN+(+{*xrPQDu;?Te(-iw6G>6VCa_yLua<{r7`KDn1_r_pFiqw%zis-66$@3$qc z6cdsc`{ckZkZ1K7`8A+QOFjslXl>eWZ1Ks?(%_)(;-H#XeoOJN(3u@;o}4#oJ-R^E zYq0q3w?`OuMZhN`5F)4QZHjB0k5QI_L4JK5h|mp8G{r;a4tTHmqhc@-24@)#hwuu$Uh`PzQa}WKI3Co{{^2 z?xVyzs(-ZAz-p|R6FbX-5QhM6Rz$MQ%doz8G${+IR_dV)BML5@cx6kFq&d5|jJPH& zpZWhVR<)&)86tKDQMO-ns`U;n@+NF%G9(hSGeS&oEV|C1Pvg&p6jy0njJH?VbzlJM z>Okh&M!xMPJO9Us38apC56Bl%Zv;puo~9hD^8}oPVxEMJj0hT)k+<4QG0Tpe#JGqm zZF26iY`EW3;k&dUfkm4TocXIwTn{ zgl@L+SayvUl9!s-n_G_;=$0F{B)On==HJfR^m#t89=8rR;MqRR9gZr`e23cix7uK; z)Uwkz-Fh%RMIE~ZozsS5lU8a4`_?&bjR_R1gQlnM)wewQm)Ds_+-ppb9xiuRB2MHp z8;SHL0(dH{X9}!my6Oi^tVtQP_L4)#z8O1y89NVTVy*!rkXrOn$z&55l(J=qw}(YY z0>?6VhqKvDY38HQ1JqM&Rw0R6HdS(f-F@r~e}@IxHCR25-XH1wJvMUMXXRh|80R;~ zRL35J;hH{$lZu0&Qva8l)h~`Jl9L^P;HUq~)0M@)Wa8v4;vwCx{ZZvlG!C&Io*Sa| zF7P=XRr}N&H-O#k8zSat4$sj+&7j&!*$N-rYn2=^Uv3%awCzb(f3}=J5BxvS6%AW{ z89!r9suK`bpw87Alu*|=Z%vCnW9BLo$q*gUX@_jHHV*jlL6v&DEDQ{ z*y-`ivNLk8h4OrQJADFAD8575WfRP^%aLeDMk4xhZr-i_&hIrB?yK~mY^Qp~yQ8>O z1D*3<4ezyR7jgg~0UGF)49vE+trNPc_%%3;!-Px*KlRKerQ+4N4qvlgf+eM`2Q@`%^ zN4i_E@Ak{@_G>Ss((U#Sy0cg*BTc934<}NV==jrF8oAi&C$zz69m+O`Ivx3%fn3gG ziZSQ3s2zWi`VaS6g=9eAW-K(~&qJ+h2Rc<3&(j^#)W^<4y#!JUoAkyhiqiF@yGCBL zJ0Z&W1==nXZlVpglHHi<>3e777L*=q;G?$7>E@g_DUM@rKv#l4&`9nr*40b4{Lwdn zk9Q0w0~bL-<^ywZ2DdR8%b)u|ANT6#%6p;*fsbgBd)|zwi~mu+?GyCym-1;EF;e>C z?5R=;&?1+cQzXuF>Z_$J`!5yU_3WF;EataO`u*>7RsOdwjItnTp^Xg@MW3h>E)q;5 z?QUHFmubEL^4uf<`iAD_g|}e4vh@gf?z70=6xJPcnNVAT&P|9kR5w}jtMu^x6eGf) zeE({75_YydQ^7-NKBel?b;U9elPsm+iM~fw6ixGO!#g$#PCF7!4nX$au`in$)Imkj zX{bZ-?ti&Dn`{+o$m_eQLuPd%9L!)-De$eI#kB0M(zgsi3fXyTjJV;ZUU6Rf?t|(- zZQE2#YE+J=nmml0E9JC**=Q3}($t^lN^|_QevxciL_^t&Nk?v;MHO=eD7|tunKH)t>*$6D33|~6+o6ydpN%Snb->Bkj5c`x!tD#Q z7fz>^M2;YHZ_K_9(b0lKs3nMtYeLWI<8#Zr#c_QE?jF9|@2VnmgqPDT+Y^wj% zmG-hH1}bX@OR*}dInK4`Q%M`{&$2o3Uj2`lF2R!=XMF$>NIaW;TH_r7o^&vDZI2h?+iO6>u9|iahXae`3hfx)) z)8OptHEq2M&deQ%{ZmJ5OL5(c?MtYR>yFIjR1NKXpQ`#>WG`X!c=V6f8h^m9If_?Y zD?W5!jA=n?csT`f)Tck1{RPdrk^+d3fs9??sA~wKKN*mc*F*4L*x|kIN0KpCIij*R zsKod0QwA@V*}scmlk@unVn>*mBbO%mSw zMSsbRu^_kN3r5G2plY8_gi?N+kl1iwJSoBMT?+gU9D-%*qgkySs`v+P#AByqC`q8s zEN?p=`J-^x%nGQeV_M+;*YY+t+&6l4p5M4)cIPPdxI}Kx`6$c5B;@~GJYhU>6nAgX zlj4(cU5D~=h8MSOmp zx)0{b*Wb3~#o+a;X3teehEka~S`533+H%Yjelu`|$giE# z97~ab?iuh9lLS6M6A4-)S`2DkupnYBb$f zxkvHrNj2jWTA6nx>dhSLfLz+KrE4aCR;pR#M7l9E zDh!cqBezRE4wnK<0+g4bo)zj|6R0n2LBu76k6W`=tV5Hc>vJXczK))@}_%8 z8PAF=wXRG^(*RTqfgjH7ebqM*(B@0tH?W=DcYS zOnh7J!7JN*P&zv(eMrCWs~+fXxUhEVuyhXW0*cg0p9Ql0)Z?IkLMJv8l>D_!>2nGzXaj?*}~8`dI=RJ`4*c=1HOXdGc=91DY!5;3;N3X4?1 z2~qt**Uz`&ck1_JY5+yqQxuhxnrVZg)yMepTUrLsQndaU zKYBf(do@ul67Ahq;L|vM>0ZJvqCBrOvn_Asg#PHhD6OHVB3iIQft>ID5kF2n6&s=E2bo z{u?`fbJ!5g8iSxwwj3sw_LUWm$mke3ahKoAuk5wTP+3`rl3gIhB?aW2{ z_I^^)2RK66Z}~ESnQ@_kq+S1KX~6wXzd~EDrd8cNa?NysSrnYLF<^=kN&r zrgC?|`}l=T<)!aWd?LqxeRv~jf-T`|twcTenN{8x`_=ms5cXqk{g;LRBpS=!)YBP* z=+fl?uP5_G3~h$iIlt)-VHNj|U)Aw}aL7_BZhGxtDQhOh@gf3Zo z#dCd8QIRf-bCPELlDi}Zb|S40kggpfB2dQ``fE>(9SK(B%0yHnx){~iBMATj2fA}W zI_%_z){%)lg|Y8r z!>k|jcAX=nq;D$a_lOY?KbHqRx9aN1fj*|k`$K;t;Ssi91GquS+egeAO-s;@^QvS2 z-EY-1E#K8F$^sfJr}wEu=&7(TO1`c#2g6}wgud#}Tuj4w%^qvime#&orJOBd3SL8z z6nIT#mZGPymQ{1#Y{|PWR#LqA>^ZAf$0-mTTE}m2KvJTpFu_cMHI0p+PQpQejFiURTj1t zW;^qsiu+OEjNZ(wCrjaxD{2?PT1!^U)Yr8cfeb$|o6@|Ac_nNcmNi0F(!qCsoFzs@ zPfEmgcU%8ePfV7Io`V}F&X?;@mRPmkf^2Vj(sBwM3tF{7KG*Ql;y1#X%r39|y`Bhu zjO7i0u&(ewLn2p0BAL{BkJz!d&f{z@+`~)cf(#O#vy%A0E5O!8^r^Zgc6?8;WW(9ka|^ z!n_R(OL9xkOrZ+xM}whTbSL4AJP0|&O#qkK1XE1&PJaN@Ejd4L^p3!J5L2q>@+okq zn(7j=G1cGS?AV({SxdGEIz=`GaQ@fwVBW$Y|+tMaFd$@ZMWcE zx8VP19o+=H8C03YOr-C#ly1}`1NP(1Zn1V3%rla{=Sut_^7hv1?7|D-E-W=btgNqJ z%l2EX0{V?>A(mzI8M&K0r`;mg!k}LUgLh&&*^DFe%zRBX11wQZ%^_rE{?-eT7%Y-V1)k$$N9$PsW`v1GO3@BPnZv_33=waK7W3o{10nTn3r3oj_B?p^%hQKD zHR~^FyE?AE9F?9$I9yw?Hr{H2>I{0Y$W$P*v6CSe4o}fN;ChKE``bh1^>j=-V)1CM zi|_YNGrtoqTD8jtr+COyRcg>L6JU17zt@&r<_}EX{8y)w2*~W!o7CwpgrFw5h8Ai5 zLRdLLUw*o9uwfSht1`VdPL0Yw1z3}>oBWmvXUC%D8QRuNDbWjitoy!ThnfkoU=7Lc zSJVOAJj(nhh?d*70_$w=o#^Bxa#xup2 ztA6ex!;gV!mn$2FK(Pgpst=pw44NrY=#Mxe6!uW?a_8j-_vz#=`3EZ+uqNXidB#N! z>oSQzT7^G|fikeuw*K-=;_^&Qe+^`L2J94$egHVWo8n`)WcH*uUFGk`B94+{roo-$ zi;0zN!%Z(k1T45+ z9CyB=Txt44yS#(5#KwlU)SLX+Z;Utvr_nY7Ex)m*M>9sSG+R5T{>h^*^_%gK`8gj5~}L zmo+=;=>9Ap7F1vY0fYi#C+%F;CB!Zqk#`k(2;gu&7B$2U(8fgX&RBMrqhu9_w6qgt zPorYp-Q+9U^rZcr&si)!G4Pav*B9ojxax<=$a8ev?HKqk7yInjWDQNoz#LW&zASFe zws3uA;u{K^+I+4yBq9hVR~xXav#RM%ZBJ84SLHqLHl`u{EW-ucqMnatAw zp<(UZq3*hUs6`XVK0((2xGHv*7?6B@zr=}n%RJ4aHO!2cs6nNvP9;T@M|R+}5?0g@NpVe~o}&(^ zFOZ$J@2vx=f~=W%F3`SvLXS^*W|dl1l|x)&c`VV<=bPd2xDR4^SLXaBzv_>>!ADZ> zV;U)0g~Kyn-pA#4kQ}<^)A?Wr&&?(Ujlo39UAN91R;c(@9Fjvfzkk$n0u_naaL&Gw zB4O2a`>9{n;y)M7tLXaE&o@D5gCNC}3^fPUbs$sYMs7TVy0(2Z>aF{gT1gM%6$LXw$C%(Xh+sue=jb#BQ5A5&J2WCM&K+ z$~5(Hz3quZU(dfwtRZ@1$CA2e*rE9|TAff~7g#6wTuNn@=7k0S*oeXW8X&bZ=o;A- zORbe?eW0PbvI9;&B*9T=+5W2??$HkjmEdR4JnwFwuExDaRJ9IM^^y6i4MpurGyllolL{Om6LgUYw z2u-vQ!+GS^uKJXE`tDS!isKm`LNj?V<4EAlW_EjqY8-5S^i70)JUmS>Zu>jzrOtrc zHUT9_{JV3&Qqtl~l&Pxl`*y1QZpNTU7`LqYpD(|P1 zh0KowZw7;UO!nN;VEDnL8vh9v(|&yuf& z71WrOc~V5xX1~SiqbRqlClZXBQoo4%J5`x^Qtu3kH|P$*mIPr@nv4#QM36g+l9_L< z$z@BnWQ(EQp*Y|>{P%JIRBLKv;95jdZK24Xo+e(Bw%NK}uvTL~S)`8$^HnMCo%F_D zHt0^$sUMkCoGe9RX0qEeFpdj2Aq%ck#$!fy7w^@@!&e(;PMYVd>*FJ?b+Xlil@8!bhZ#P0D2cCH1((c~e(HJZb zuCliaI-%XZ8WyLw;!Np$%hKbc$LmZQVo0a2U0S8N?uJGyDc#M&Dc0;mY#}FrSo1v5ldrI%7vBZ z9^1BOviR*kZl`e+Y9sd|m6}3z?DzR zJ+$IaJo-!5!a~TJ<(LL)h?L!^u*CB{`ak;;74fX>3FG4@K{-wpdM;@>{WH4AVej)K zB9RiQephFy(ePgDYThm3*2FJP!GAx>QZE>gwp6h&U>~wh>0Q|Uw{u`Llm|RZIxVq`-`X(w zse^NWD$fc*s#8FJjnwkYSEubkA-C=n5tsf{;gxaTm;2UQF?|z1C$!{>SL&9$Mnp9W z%TFf`E)?Uvh^v%6*O`|>W^Q>7%k9Zje4s@xhP-QM4OaegBujA$Y;t-eeP?*Vb7LwO z0R-a5-Me+hXhF)~H2x>$4JYOB3yPgf+#JTs!U74(`GNNN0ogr^y7QL5MLhm=Sw$!WQzV*d8LZvyerifnd^E>Ah;wL8M@$u>*pDyT<`b(CVk zIHwrG@6U8fc4^E!JoD)gM#fA8rwm1pWtftbxa3Wk%qx`Z8kFgJ1!*1W>Q{|o`VHAY zqlM#D?nSeQ7(xSTej|!k7Ng}p10~d@)7?AwX6KUnNQ^dP0~zHmb#)XyBK6qzHsels z1d18zr;9I*56>4Amt#5{V8i#iS6fj?@yR?@*X|gqGqV8kNjg>6)vIBS=v8z*CbcJK zsr$zuu2^4~;!68IrMO7w-o~2kNq^41z!q_?Kr=7k&{r4Q1pq%N3W6CX;n+SgvCppCbyHXF?S zPtad|V7Vxo`D5f6y4a^N1jT|4v@ul%{ZK3Ej=t@{T^@UPJ5Obu%&Rk=;_R)zPa>UB z_D1~L+1pyL#Nw+V#okr)tC2aoQFh>^%pq4ktm`a*fsAHuEP!wqc(CnnhST>Gjk#A- z1(#g|8oTKOZVD^B$mzA)AdYG$M3s|;CuIPAQXhx>`AMo<6~|oA~$OQYd<*%2RkaJOt>eeNSWo=h2`64u21Lg z@dr1AW!PtSPP3j}4WC>`&-mBR_$Jkj z=W5KVLm9V-;PW4{oS~jUVq&PDBOR}X;d3QN6@Fs(`-$J}o|4!GX4&p+g7W}44^3WS zlCy4{Iw0DA#2@N2=sjQBIxyYeKYM6VRhyE0v_N9R5YPf5RN0Rqvw4ogJT;;oTeRtD zHx;4iK8+-6++g9TdqbUYWdW*<^N(+yaYaF2M@a(|bb+zPkShv$KFsIha%a>Wun0D9aMf=kv#JOUx+50F9EnmNl*7R@ zXLwbW=h9>ENL@z*j-^`qvp>p-JobDOZL6O~dF&y@J(+|w8jc3aP6pK8Cy)0i-ghZM z2TD=D>YlC}TRv!+{>+u2>1A&B4V!e@28=gs_sJpn4XO0j5At4pS^d8knJd4HxOrpp z&p^u7M9cOW`Ox3nK?fs$Z^cDcJvv}9Hi9X~t5q2PirTD!DO*Loo-W(`;244xTmI`I zf}Z0-WFdiG&_BbE&(~C2$pJU^edxrS$D((`cgb?DXzHj*$g#Wuyl^AN#k-7Cb^M?! zNn9s}#rn)lIjykgDp;(FaF%pX+!04#kQD5w?)&1priGOR%3e@-pY#sYAtk0~5%!JH zUu<3wMdEHfX?6r!QjR2m-J;*pAh?iO03ufw*0IN5on&XATveE@r!~S+aQDczGR(q< z5~O^#TvAhdNo=2lV_GLPB2eB)_&dd35IHToixcl&+hLLlh&Glom0t3YXc{ue5WI>f z4>$i%?LvCPt*{6Q- zP8%B?+uiocLbYw=8X<>He zn@^L@?I6+)=B^5o#-+C$3$8}*0H^CSL6ZuMt7n`7~q`f==yfOu(>km2bDUn*Ge5stW9D8 z+)9n^o&A|8H%j-=F9`3)$0+W=6+v7^e`BIxl4#sJZ^B!CEB>IZkh|%H^$9?e`i^bY zt|S^)Rn}j7^}oao37Nl9&NKVV%QtsN#FG-yAN7Qq>yzae4ap;wh8_Ep^?b4>B62=0 zrnrqb%~jl)+F-%E_omN8;`_nbU2MLXQ4Eq0HKPKXqxzH7aV6Zr4?eo%e8y*enRN3r zw#>P7r_o3rw#>0#2HN^HI!Ut;5QlqY8BE~&^DKU(@=Je&a5C_#MNIa10xIgCGLiR~ zX`ji2Z6Zi}!CuONuG5>?_AM^{S3o+zW|3cT51>>ZDp$efLG+yF;^VVoUdBSPraAy3FUAytg_)7Ky@3^_Kx1E;w{*?0&y>?n` zvGR}8C)#PB`s?@^l++5jq6SW*9ekiM*l>o)?-0@TUGstbiScj4uj3VxvCqxX33vZE zQY1+6+%$BLQP9(SVoSE!lJA%W^&nL0!eaD>*k-asj5fCU*Kek~Qo3T{Ak3QOr2Y_B zktmhgRUezR$%&FNjQ7zM|6-76pdY`FuxOJr3wBXF!^@`fwajbHIy1@uN@(B?`g=A1 z;{?t%27?wPZb_5km(_>?JLmDuUVPbhHQ`c&si3W46`Ocx6J!PHbXMw5&b3xoOBRHp zNU6c_-zirUxum_p*QdZI=(i4W6x!>&~ z=Wv373wz~^FT=_}x5KvpUZGxh-2R&FMCc-RthO{GHReR9*)KKX&+V_>H39j+ z=nDgAO6NRPKxb|#k=N0C!_BplfI3r1_t#Fb z^%nbu3bL^sZfAS*obcUN2k*)s0UKyliid=-yX@C}u~)0GHJUcsyZFOVRc_1s9{{yM5r3((;S>5ES{1C6*lt=bHAKUEDlc6VlKQ-{(gRtvHZ@rQX zd)+8|)gHK7ejx|IQVcl+{!PH?zl-vI&jCh;8*>YbcWwzQ{0k{At!Z+e<_>Uxuh0MI zpyqYGn-QmLp$FQB7)2djje8Axfi^X+v`>c8~u_6kBps zKrD~i^u^lr>6h^xX$KMsR@HyRO1M&3K~ynSN6$3X#A>5;dl7L@V9Hygb*J~p6thGk zj(m7@f0(HvwWp3Bm+Nb?+v>2}zKn|#;6m20n^=bEPCbc3aK<5+6?>B7|Je?7Wj6G< z)-7X&3lzK-YEXGQHVzyWRvWce1%*@j1&FSE+n#(|%Q1w@7{5-XvX(8h$|_!u@2H(T zeshMd?N-V5OpVz}f0l?F=WLA>N#&c_8mG1XR7KZq{aUAv2WBry+IBAO%f50=?rb$G zy)1ZnPO)XH>OCPJFUIIquiU5PU<0+Gz4nSl?F{q<~gHABJqHx5r|*TN$uyO++A!IsQn zocYpMOx`fg7e-Lk!%t)J$s;RY=Gw_mKGh#$o~EI_j+lPgpOu^5aQUf(jZN!(uj%He zmmRDZ=QwQ6H|}zu1Kni*uPL`8({q~{fk#lV{=GZ6xHVo*t+*hNInxH12m!zc<J1x~0 zS!ut2Bhw|=lXwRJ9$?z6?bY48x}UU0^R@9WF=;|{P+Lsx^zbQDqbIx${bP07*WUl-dU7Tc;oL%#%;Do#}C5J6~fQo>pe4~wc!#udFcvKkIaPzrcw5YYBM846e>HBgVv zd}L;7YtrZpPuo}L<@tUvNt`*@FI{{Ha9%kFebdmA*8f(l32Eyo&=M^Hv*_SSi1of{ zZe_)gqTizh@e%|JU#L?r$HuUK@sC|bw(XSB*gdBBONKf$ozgv|^K{D8F*yca7!+GU zUy>L8MwT4a@ajeInj{P;^q2SD#)3^ETX7p^>>Hp1-2fOWERD60yQLCmV${<*i}! zjlIp@X6~rvm-D!J6iF}Y0iIO2#a_=gAC07^m%+<6DPJnajhMlFTWux!$wYSX3g0IW zyRp?*welB);{=4S5^S!`adJJOf_-!2UNM{#~@l z)}`c4)8t&tx5D<&n2bE5XNMu#{NpgUXG^%PL!G6IJZH4=lSsO>udkvNw&b zFU>ktBEC0Gab+O>SL^Ib#Lg2DGxEntQ|JEAtUc@n6VQLW*(ei!uF75+_4rCbpyZWt z$4wJ|JOIwi)q@EHCBQY!imp*hGo!V7UV14mL4Qk__*GyJ1yb+7>S*AHR6K0dz*rB# z+)_?<^+%U+Ni3d)SD1&}OGYMdU`me{j;Igx4p0w1+J+nZ9AY|%&0e1DN(Kg(e*oIg zwGf^x|8h}?LJA+Y1wg0!g08br0DFE;J66j3yIdSodfvI1pMgDE;Xz*hHWO1bA;&s> z8emZ`6Ydb&g^h5#*4wKWYGvGebXXuJbIgD)Pk;Zh)5W9q80d$V`VV%(!a zy$@xGd0c~70B!msRsRNzkVv@*|4#$JE~!t|WJfZoBzJ#9t!2vc-84&2ZVnhxT7vI< z8?QX8d69-c@gC0oepx|$p1v>Dteq|93}7X2@YLw7hIyOCza%YNJ|>&-G##{G*GQu02 zR!1h`!6e~PA@#M+hOiYwCpRN45xno`fbzSVnOtImC^ z2f!W>HAL4|5o+%2Z|3}uAnA7##qXgh&~Krmk)fk><0op?Ub%eYt&a#R z+og(jiL8}^xz&nxuP2nQ+`D{m9!=`O#FX+qrgrz(*@*Zl!}JH0Tn&AcY5!Zm$5(XV7kC zzs>n&%xV=6p5EEZe)~5&*l|0MOZ{(ob)69Z%Z~y3gMUR==PLTmgQKFfnz>OkHyO`b zjQB+HZG$?;gxRhd_>C9AU$c#KAx}s19tP*pbR81mdL-qZ?%eU;!y-)x{`$gbF<;!6 zHRYLCz%vyy-yq5lYLR$vNGO7$A!V#e5}yE8;Zh_!9{Ae})?n!_uny=iS@c-sd-HPY z00M?dHZ7k$++m{M6L(a$g^qeK6FSS2;lr0mBzVascw^FblW@_!APL^Kf$z*O6wvp2 zs3BJL|GIZv)M%|=L$PhO!%26YkM|9z3sm~QkF9DCu(Ag=Gs_~3@7;CeyN{5#HPZVT z@F*HvjIDPk=hGta3$nj@1PoA;qy2jqF3$$c`m#5%-!9$XCwBUh_pI-SLG)+Sr}vd& zr&znoQi_;g-E(+`@Ai_cKLmD7H&0{P*PkT3q$-me{NDd@oq_e?^vwk41Tb|3O=jx$ z4Q*rBPevdnOV=qdbeGdA`=?L5>lE;3yAoKBsT_~Ppf>vfR|y3vfIaV?Buu&?dge8MQh zxmhXj{|u8yq`0$@$Xi1d87;Zn)+i0f%P`W#Ce8?D3JYe@j35p1^7!zOg6APB^0MJe zDz(H3!lDNrS@QIF4htV2`P6K~q>eI#qbJyz-ZZxJ+}yuKWF+TqA?Idc;%*TDPMOtC zWtwUQtxw-WS3Cc$)65dk-^ma?oRePVe!04sVSY3g_Z%u*Cy-?{Vn%#0R1hv?x|3S& zp=oG0^YtPW>3a;;qc1hP0#vT5okMMlt>qVuoYHgOCbpDjwv=ki+sodT;ko&_sf@9S z?O!T!1*6}E)Loc5sx28UsKTiGYx?K*j`Zi@W#1QA)@4`^d=0d=duSF>)D^E4difu% z6qH!M>Kb4XCt}Oe8}|)Fn|DS1D{(-$SHE0%4sW5JM)^epE3@{o=(ykZVV5(6SC;$e zO{$4noG*eqEVzS#&-((s-%qBq1G2x9cd%K~4I*jVc^EGKRd|qe{)*+Q;T>40ar^vs zS@Gwaxjr7eO48{M7^S%tWHbf{<7H#t6~ys&lBeJNXHuQR4^EVrK-DVL46Z|$gRDbw z!Lk(Z;*f&G8_7PSuumdahr+Lvm!F%oxL$@m7oz}I#b!+a${9YcBR#uBVI92xQx;e( zk7ZO95{Mo(v9DTx;!nRNxZZe&C4v9bD)Gzzz)fUXgOb5d6PYZFKuP<`L!@T%q@Y3; zu?e|9Su`u`^z4=O%8*PKY8r&Qn|(nY9lK|J;oME@N`W;m;&CK=YKD#nb|Et&cRj_o zOw91B?}oh!maAx|`DI=r@bvA&P=nz7>r>%QGK#kkOThK~W@U*I%4hyjnS%wEML``; zrh^qsXQk~+GF$BNQ^VTj57G;sIYKJ5ac@6+OK$uAR}=i7Ddl)18zy>eX; zTN_E&_OlX)oP>$gAMbs(P<||Y!Z_E--*Qv&0f2!n@6qz!EMn=Oe3P3=EM5;=UWfTT zq16S1|IERMcBo1Kx?54t5egEK-+9XEV2SZ>do*~1x}C@espKPISYJfPI-Zl<5#$Kc z83@u*lP&#OApDZyn#};|xsGYlU{vhuDw~F{C=fFIOmxXo!YtN|&w4XWTwz>!Z-Y@` z(ym~xE}%cw3HQ$$V-(k2K*-!>*~#kmtauw%Ft+GbJB#M-8iw_gZ}F9J?%5#4@^tc9 z1tv#sy*)r_-Bx4j&57a5Zw7t}L@aG?^pA$VYliJiEHkQciaNBjH?8lGS4Q{k8W1q} z^qO)I$C?luajR8|T>M>Pd`I**L@oJ*qY)xn(1Q@yU73E(R9G`1caRs=L#8r*HwVik_@%Po;xnqHAOwIUro(jo=ebS5>-z+HcT- ztBMdi`6c!B9N!5R=z78B1a$2tjQM?SUO53bfxOriegHKy3z{8qtbMhYJg&m9ugwG& z6S=UVs5_+}BYOwd8k~(-1b2}taTNTDSkt)u*Vs7!)+#3D5dJV>32piHbT9E~Y=Mv9-OoJP>cZWjYPd+yNf0H6J-gdQu0;Hncu7(%`QBZO z*-0CNp%>xD|>;n8-Xzc|&ET z>~~(DI&;GLCl-0`JE|^0Ma)*bduqTmbBeoei=O zIlWO1NgK0o8ncBr8U%^L->hyb^hqpJzOdu!Rd-|%agR&J-Dw{mi;{DTGtl4br!88l zIs<&m(k2X|#e`V5rz9(c^<&EC5+#HVO%w3VS4~}swgn_0u17|To1+(UjeAiFlypxg zc+#r~E3J+9owqR(RVx`3yopDu8~qHGNyyY(112bg$8px0mB+Esj)f>u^L?Cv;39+j zp!9LfOT$k7OLd<2Pv=K-te-HB+**8te9f3IpUORRi{Hv_HO+%Ub?%8e%`49eHTsAh zJ%-AGtyj*;e;(BO>|06g%k`a~Yo0@wZ`;_{^Zv8YLjwc1+SnJRGVeI_`CWcX@H{^4 zoWTIC-M&77i`oC3-P8|4{Cxd1x8)=n&whs`98nH`ldJ4?RyD>62<#r3Ax$u4JBMbT zX#i`><)mF2Sefz+`F7A&2mDF%0Icelhd;^yaWFTu9YkVtv#ij4_Wf;%Q_QX(DR&P8 zX_csT>)!B91C6d6pPBor^!2v=x6`e_Qg#Q;SU6UijkU_PGS_c>^**m_f%PPB&ZLW; zi&mPBohROy{s{eC$BV~WR0@fr%LmIJlV`2cez(1G{jScYEe-n`!)g~Wf1OIk1(PEu z(ZnkUpMYU(#qA4%qNyQ6Def6h(uu8Tf5*8-Ut?gP7vL{6SpcY?ax@Kx&8Q+@bd+>= zmMB{2bPB>tLb+Kp6U`YEJh{PhIH#Q!Tl0gqGZf>g=ey^24P7lPVhV&|d^pbZ_q+h`qfh z_h%SPckUM3-sGne@y31d0EKXSEuvZKXBG%giY>XRy}FhDTmPJE+phDI={EYS0Lsk& zysH?ie)@1;p6QbPH z#<%l)r}8C{vKd3z!#hFXzpxsX`;I}fEK7U^Ebrcs5cey7(IFMG@w7HXtu6>pVjdyd=jUW+%LQBU%}J;BjZ{O#$gq4lV_Lf6Gvwv%tq zgknDM3P65+;KuwlN~HUof1$b@aIIXVu&noGu^>~%kJR$NHO>4{U-eG(8Aug`n%s0&ld8{X z=b_r1>q>qt7*TdMGJxBc(pZVQztJwv9F-mlvm=Q=$LZpT)wF+Qt#`y)`=5urt5zCj zOjZ47H{n1tRLYX6N~wn$D`#0~OZZS<4JXgE;&6g2a9Q6-^X%<5iy4Q)#ak0uY>Bn9 zJDiq?%EO7~U~cdim2r>TFwiSN=+cY|Qn3eJ2pDF-Z?B7S($>X9kr79hascs_7mJi;u9ZF@*8RqPj7m1Y}<>)rm zmO_55!e=~eIOYwrQ009&0^j*6GHoM9PFOmc9Ml~j0a@pWaext{e+(-HbT6y6pt?ZT zDJUw!H1q*YaGFzkFO&HY&$E+Wdg%zyvwrDfjgDs9$bi=kKbyTcQ7fF)MqexE_3yf+ z8L(dWtO!X{Ibh~=y2c3fVYr6WL4Ca6Dk>a{if${m{l3Eu$@zkLSAXxxE>#4}94Q&X zbGc^I?>i6FF?Pg_U3Hw&?=G@{4ea`#b_SE@gbh-Ci$YNAaBp*cby zgr6&qZR=*UK-sWQFUsr~@1h<4A4f8G*9h_OYFp*X6TyG;_#_b${QKzJf7R3OJZzwm z$+WoT8H=M6fip~Ok(4f-WpPU}{^0w5i)EqC6P|}qM77(P?yD%v!HH_ja`@pkKz)oL zgtLV2q!Uah5KQyX)yNT$s{3Wu%VrWxXAn$_(DD9x=iL0GXwNjV4leyOi>oSN;2b8d zZ#WAe{(I`45mOQWG;m!o{GJB>7njAmk+}8{o)6)@0t|QUL|9TAE0rq$+Hb@Z<%i{F${o-ZU*e<5%uGJl{Q4_Z}Qkr3kV#v&gTuF=wneMgIQ9(!}-m714xEN-G}) zT!+mkBXaf%Xy`n>eD8@})jj#$1&0SH4RxbBjg%}z`;CS=jkdMDw-Gx^2&n_f?lqGY zwwqO_d+&BI8tz==iy~b_5fS%y&AzE^%KvPi5$E**mHmR3fOO z6rXZNaC?8jPX?V71lse)T-HUvFIHZAYYOd!k^Y2X)j`{}m3~n1{g7BTfk?G*)n)g3m`TeL)oP+6&IQ@GEr;u`<$GyO~IWoX_dst=I7Ky(3> z82kh1b4=VSkbXtI47>nxs;dI;^6c3R3?Z|>CFZWv8!KoW6n8{^UsM{_cnX!!E3u>M5fny#gPWA zlHGy~BYBGrbknxN)5VlPH2Me50d)(W##LT_{`G^D0CJbuN}1;{wy1@3x+@z1RtK2P z09>1Z+yyXBbiU}kWiQ%~4uPkiV}i+gP_C)a<` z4OUP;)m4u!#VI_mOMP6w_|s83v-D6RfTk&?sOce_W?YPfXcc+=c6C?ix?uCF;8cmu zn$oLJou1V1lH`H_5fk8$14Sjk%4-a)>zHo96$**Qmmc-y z)YRwivv$GJuSDM04sXh3BO>CD@vTfAFfRlzz(MBW^`cW~9Q?451K1Zp{mOY6s(r2J zuD>)lT zUye^?9|fP;=eO8A9ANwi#6p=7|fZy(IjI#H#|218$tBzJ@91r zV4By}vX5!xEJ7!<&wd=i)TSpF4o=VFUoLtppPWQh0o-k-^8glA77#D~AwrF( zon?CH7Sl&|ljk(F7b-X!!^AjnxtctOzur5|vPaR7sbs)(oHsAyRPK@@s=#TgI98BkPAYNrW`l7#*k95iKK%}dP_4O%bV)!i@8-r376z%(uw?H=ib>rV%Va;; z7VWCCk2ISU2{d5{G!Y0KthHlN#}uD>=B!NWE>G&NOvZ_1d3ge9C@Fai{Fa5F3j0Up z@|9I{yGo16lV_I*q{|5x@kh zTwW!LxnrjwPID@9rGyKH)Y*4>A$KG82#J22&5oj?g|quxoTD+QRrK7aNE1 z6gQhbgm84raMeW=TGvqsx?AIzfva> z$NbDA%0PFCJaYzzEuP`zk9|>fLVqa+-XX;=*Xp~dKWAVi=nVc+9e>*|myqU*T^P<_ z^BeVrd2b($I#EWmd0;}MYYQWW@20U@Na{1ZorU=D$Wh9zfMf0XNwkpz@Z|8J>J93t z^R)(tABe%{;YMHWqS=%{)f{SM+;KxmJDAa2oPzwHTj1y5LG@eKNJIXcg-$fQCab`J?4)B+nq#r9b`%Z zT~`s)j-XOSfb(a$g^PUD)i64+*N^LbA*u~ci~7ECeTwgc3Ts2lA+B#9ueG2R2sBju zwiY^aZ(ygZ&>iR2C4q~@W?g5&PTC{-V)H7tNO?xLZ=+i4k4Kbf zXD|-+_ml{*abIwnZi2Y(tb4x>70hZCY+ukj4yMAu3}}s!PEMoUlj32wj)?zI-efUiG17(%zm!KT zVmOylZQm}*yWEs~_}8DB)4?|Qf{=!+i-lm*LZn)s6Kxe zK$7YQ#UApTljp|PC8H9sp$=Mp`rJHtO6ANrE#O!6zBmO%d=02F!fIfp+C=7KmYUjDV zwatpyE0>_dU}(0-N2iD=6fK$TSGHj#R|Zr~l1qcb7ZfQ**^llRdGmx#PI}-fg+++` zj+V8?E8l!D?yM~kHAEANtm;h7R{D&qm^71h?4x`_ohUZa1(0KhUAtvl&_Cg4C)6b$ z$E@Yrjc*%@eKmbn*ln1?SFZi^S8b{fZ(>l zFWk+PD&LhQBNekgOo|lkijuvr!B~g^%VvTR{^IB8qI=WZ262 ze?0mfFP?mFYAm@uAYvV*&5!u__ytGa$6|ty*CwGGPWTdg^$0_vh0&7tLN&y_{k$M( z$klk#7^W;&Dt_4eHD_a;VuT(a_13CU*~)ve_bVkYvWS3?w5aoAuwrPGeCR)IA5t)+ zX>gVtUjGiuu*~+N(^0i@AKSgNJpQ+Ee@T07K&NAIFADJ z)~|Bc0|ITpk9?M64b?Vw0T(MeB`3a!r@J-%y>x3&mpz;*n>5JN16^9$qOUvsy`Le} zj=xfnzOtxAzbTkI2U0~Fx%Auw6R7@L>~;=Cqz0Y>Q`pC(f{jniqAWog%uCiI#5Yz6 zJUT!i$b$$o;|C9S=rB=nw|cn#48(1yV#kzClax&-lylV+K_n_cT-Do@&X|{JZkz~DT6Z7u*VWB> z1F^(|?53e;4kS@Z$Hj;BnIlw8}rmA#q~bsiVONCEdyEjZHu3Qg_wSs6t1aeP^{L8 z4JjAHxv8=nbm^@|<*(8kr%Bf#7<4J95ZLkz79bnwCmV?2pJGm7$YO+oR4tu&Qa5om z8H**l1US9y$n zB$PEBD8*+i&Sb7Res{UPsJe8Mge^Wu{q9=Ig=6O3MIj?g=r5z)@vxnQ-Ot@NasPw< zPmvN(1j3Ru#eDM_wJ46RmrwOo_#o}67GglwXaW*_B`w6v~ejdU?!(3is zJ4b%@Twfh=Z8QBgiJom!BTaGp4Lfs<~zl8%-##O^e!asQP2!KuR% zpHfOjAtQN?w(98frXWuxQxTK!L`}29+_G#=oiMn+Z!>|yPw*I@HB(mZ)*LUS`neUk z>bwsm>d_Ea} z4|#>d<)hInlex%{84ByQeVVsEhwUYC0Cn=KTa!r0?tB1%*sR>Cl#pP-X2K~9718n-nz|hZ1se5jNN#YeW%6Xe4MM+WyG-YIi@O#_6Zs~ z+e%i4)ZLTjDY?TytC|_@$^V4V7JE+Kg0RhTD?^{nbw!>vjq3s z!au07)tT3=A%0(#3_b9TtbFC}Pfw|gDP@QIG)&ob5NPYLiO&mA=fA~=n;BTMY zd^+^iAc?X$b8mRUBaAbW?hN&wONf%8QfwS}@q{PGYh#Pl2l)t3Un%(;U;c{EW$e5z zH!#-%oGp<3N8gjdGw#Y9DjNIW3v9Z^+p;fiF^(iJUkh17Md5#h;3U5uhn8U$1sg5C z3WRHMq@-Wew90)L)pH7n8KjDvx7|zqB46%|xd)A65t4moCi={Lp8ZxuE0R}&Nk7#g z^D;m&*}|vXAv<-NH!1y7C$>p^M{9K*Qivz=g`He*-V&eyj@hj~YuHc^nyP-1MLsb8fnLBQ~cc%ONc@12g<0?L&j*DI#zbdY!g-TfIW0g%k4V zFjyt4vPsPn+1A9M$jQuY*3QOK6JW+2m;}$%J_MvAv&jMLy(Az}WjjI=TE`kAYARk^a zLK!SQRJy}8JPxQ^6EQ-^*O1NSAK#!|>+G`S6ovP;Tlor|BhmaDs+qgH2c4m=Rsn2Y zIt^hiFyZRwQ2Gm1J#h;W0SR3x~f;3HE%yKk2+FlnP!xE7g_dq#mC;$KM09r$#5Dmex6{A z+jL*O+G?%exQqPr%SP2h{gV$@ZWU5p^@3q`@Dw{1R~kQCHk-@uko>uPYsw3af97FLU}!;`EYi0CRP8UJ*gUbiVw5B^f!a8I=E-CDwCZ)Va#5J~O(1_b##^^A5Ud&r!=ch2h2WIDjAnuNThy?j@+grYlD zN8I`WH&ktX@H#hbE`ubDTrN8U$?)@NRBUz?{%sTf&BJEa-zIBrx(M>^EGuHV)3Sy| z)@Z@?!uiH)Gm@rYm0bDJOYMZqvC1EMRk=-_z&mv-ah z>NK%GjfV1Dk15)Xz`aph|3z#)N&0U!oZlEKp0Ekq9E+1MY=BDad8}N-xQKej zo3vKZ`J-h2i0$(nA71J|gtnzY40jq%PF26yCnvX6v07XM7oyi8%DD-@N&Q?Ey;WRh)Sv32BJ>p!~Z7}f5L#Aw1XOm1sCHr->a+!L9w9gF)1iO~tgS1L`Q zJH&Pu^j@w3_%QB69Vne)Mi=U*rIfmbu4km~^vgG$$-R5xi&m zsmC7vY23TVZHQ5&!F%|O6hEWGR;7d`c^Ug#4)sFZyv|uYVL_a*-As4ljPoGQlo`mDgLteYVQgwmp1CX(t>R^-;I$vSM~cs zYjOKTKk}z!0qq8om03vu#U`lNbF=IMy6Tgch^-;8?yLNBLdad=p5l5yq=H2%ZuThg z>j^oFN|30_KqtYL!NH!^2P9r{)dC8aTwCBJbrPU-2=Wb5o!~Q)P_UfBx2>x}mP4cK z(t7v;Kddf^#K4S+prmAf8W9xK6`v2%)Rwva86DRpkPaqiOKY>QP%WJ`puEEoR{)KK zazJg$E`WG0%Mr?(sc2}A&+w`aqYuHWl}VH3N%0UeRSGS2?eK6jZCQfMqI+792s02Q zz9#L~0Up;bVRvzqD_YtM60q#zL+w*hVwm&e>gTv>r0M-5w86UHZ#PGe*pho1#O$Y( z=;w2$yiP)bUV-7$4+>!X=b6hj1w7?%$a)+T5nPD~B}jzM#ntJ%!*E#%75wlD=HEob zsu3>?UX+-mNeqIT^o8vqT8nS1CVU;VDUtV5Q9#t>DVFv3p2j#z=lixj^y{O9%3|?v zVXj)=!zYF%O6uS%MH^~auLV?Z81ERSdSfrp>RApI{2{p^zg|2#jDlG@FGctM5<_kf zhPw@gzl12OX7t19gD{83Mgl0CKY&b__3nfFRIfI5`*3gB4bX~(It^F z%B1~dM87bg_=R{p{<6N!WK`ei5$zaC#6En>OD6v!L>3J;(hqw=YcbG?-v67xC|%P{<3q>A1e!@?GHk={^mG zg&{!FvuK8gwt*pRxGBvg^}3)LaH-JE)iJ{=7Fl@8w_loEG4Uj`hd0W@A>CEvs{ZHv z3eWwM?wtuL^g0e;akDRw(yjhMv3B9hR_A6kKIx`(m+G{a;&}L~6sbzuROL1p?Vv}2 z_sl@HAp{YJ3cl{#3tXV0SfoW@bC~N#+J=+Q6=!n;HF~s*csT;BYnfK^%=5ELfjr$5n|p1b(Yw1iQB7UOOnaYu=p8Vxg8WE zZbW^p?DP!4#xG_9{qTp-yktt60>+u#Q|Xx@Ca>?VFSz`r(ML;_LdlGh@h3+SCeBkO zJIEE#T*{qB|HYo5k=L3AR5$;0PUK%?3R!z;mP79A(Lwjvx->|b{_e_rR?NpEwS{3U zmLjWk1xxO*PV-Z5yT~vzdgtDMCi@mSwCOA@3ot5U;cXE8bwy{>Dr*5 zw2@o9|I^1Zs+CU@lacsECfzMRX7%A_E>}N`s|k$H4370T$3@pjl4q*Rr?leHTf4#G zeF0XW!jmJ*yq0VGytaHh-Cf})?Qz|$^6mRy>ks%LT~lOwju|>jw*|+iN}EngyXRT2 zdh{rCW)vx%?pJ33$;u7pGoT+f@-JFI2PpN@O|<(boRHW7_|J9|YMxfBzIl-SYX5@f zEQTxes`jbZgWF>J7r8bXJEd=ZZYVR||Ifv$%lXU;Q~!`95IDJkv}zm`%yQS>xp-S| zdCgB%=uvr@HPm=T$24D$%&ZZS0}c=f9(rfxu({xvXJ-ae)yDbO2l%Wwc9gkqX3yU;ZtGPs@_Usv ziE$d5mfrRPyj5!-QzUk8%r0g1umtJ}z{=N#YEqBhJdUW3E_O*;y8`UG;B3Eslk?9+ z&x1^&y-zfc|0-X;2trf$hGygJ!c|Df#H4fl&3n|sOp-2)k}h!nMPf;5?NO{HEYD>u zfrIy=M>qdyZq&#g-mfEtLEttJ!*C~W`fzGFGf|-YO!Sjt1%Z?5Dj6v*tu7ZoAH%?~ z`Tc`MJJRiJO zHQMoGgIQimbf-=KkCRX`FDW*k(iOQ~&@5ja|8zi3Iz7LQ9EC?K5t8_&PP#Trw$+Vz z=EpmJg~cHk{sgMO&d>$!r$~&)vmdWt=09rGc^^d%h0VNX3MDeh27&yeJfiH6Uqmb? zB{rn~{XDiVu1<9&mz>frFS3sAaN#6cr%ZmKOz}_qf1hkq_;5+l>|RJhrDu-%gMQd+ zy{z-I!tE`MW7TEF(|SDbCDXtz@VNrWH9Fi5OoSG1LFoE^8BRJYlAj_1yF2x`$qfMt_{`hy^-`T0Ib)2au;jI&(8J@oJ zG+emQNI9g$k;KEVkV~n-@sY=@piBe7dnc0)@miebJFGq8KNL+^HU!TuOkoAOtcG;q zZL?$Sp#sb|X+6c~EN+y-*dL7O_K<%bHEqa}<@Z=4VpPr~dsnkfbd57yn~e7xl!Vme z_O3gQCm|_Ae`h7(Lb;q+349b=#O{v7%tHBd~`K)N% z^FLzzzTEgHo1%-H+wZ=EfWFq?#TNTe7A-PvTby30Lm+mQzF$n-*lBp5cwyN!i#lUUzgUM^`>s*ubboa_NAbMjt6KC+!Il~FDBjKG?Z)%Z6K5sngnVap7fMhJ0u^Q@gn4>;AcKy(;z={cS4=V9sM^ zr{)}U3d!Sgh69}CT|#UE3=O;=HW|x55G9H9zw&y`0R{!u97`xMZ8{;pThtd<=jv4H zChA)|!nnUb8aZADD7}A5%gaC|sZN8p?VkLUHfWRCb-rD)=dagbfxSb_W;I7}Fe0`d zv9a+cp(kv0@7t=x=?0(hMna9nSgewi{S%~m!*1@LLz*9^L?mfFxwu+1>UB5Lj{Pp8 zE0&AT+FuO@IclO{yL_=(uVT6}K!M?QSDt2@RuC9czFKJpH-6h4atO}&z?ng?ULwvy z*gN5_lK}7SolvLo>I>l>ksqV#6>!t}N2!aou@Oa>Q6ehfEKhohQOq8Gxc5KwAnw;l zg``l2_(kjic<5y^zcw39V(%k~Gr{>=*?WT$IylUP|Ms=CAw7;0iQb>#ZVPp5GubRZUN8 z6hHCN5B+x@kX0fnhY0^bRkX@WkSFnk`lHk7D=beBdYAK9qi&|vMlDDtlAFgGdluKBSfB3 zlTxo-s?@Fsy}dFG@RO%s+*kgOlILrK0}Ra-d%4^TRHtv-P<#`8b#@LgU2*xHi>Mb$vkYe4LXtXW0H%ua3;N#15?GAb|iv zMWpAWU%%G~LcZYGpR3--ZVVEz1Ca~^-^zQXq;iz$?h(p}7q$|_9~g;y8a-ka9`(qO zX|wy@2y(j2u^f3p`$Szkw8)+Pyp{h+z``J*iUnTW4dFldUvk+H-|=S%6`|7}QPlb^qr0Uo>26;tzw@c$GTXB^tFh0J-2RhJA^@<73j#D}Zg|F#Q4-%; ziEc;7sTKx<5EGjWb30C^MRi!d+xfp_jDn&;7y4RB=@eWIq98JU*tXK?;OQu?w%gL( z=Paf*rC5{*_1)U9+lN^P-~^iHKf4HTJS_C?NkDJ;P?CDR>OAwl`f+u^*TQTZG3E|e zo%R~V?Rz7jV_?Z8raZ@&dHidNZ|3Cle~%o>8$yYWfAN2?^;2vK8NQ`n%~8igBQEn7 zA3;GFI;64^KGp!eY=o@@@1t(LC~{GKh?Vw8I-&~%y1jcrV$?#q(7E%yw3b} zT&k-2bPx4ttjRJBey++t@gpC*A1rcq8?Y70`z{?qCfp=d#AxRE277J>A@_Hi%C2$o zAdH_d+VXOaj_glreU|WChOn_`(YHIAVxM^T2i~_)EDzA69_RVw)B2R>P}6XI(DYbA zW%mRneql|QWl!wsDBdhO;R$N_3jBjzG|lg0B=I(-thb~Xj`MiYd9+u>wt&bdfI=G( zc?pQDW89SikviaO_r?PL%GaDX*|V)SPR*+xPmoyQ3W23BJIUM^-zeiAx_61ZywT0- zZDZ^TUzGtfiF)y0Sj1BoDc^i5x0LfQCkG{x!?xyee``GA<};qf8GgN4dOafnJ)@R% zS^4r*qHub3!dOS5GV8ytPE3M3B-QM4_c(3U5%zK&Nkg%hioY4tGfo}{wk9E}QF8p< zn6Tg7mRm7OTQNOzZ%6aIR^4;4#ej;LicywW|t%&HxiVK>d||_7ty1YX(OFGnJN#&B>>^LgW(t z{RGRy_PLy{0UT*+P2XD$-^wQZ1z;yx-R}7d8jtZ6M+xRlh4VLWJrcsXnH?1-X6W7H zEov!6689m9C`@sLxS%W0m^XZ@=*hxO0K574uN{8n$gIyfIC85+6FGCHE)wUWp;a8s zB2uX`+nM^UGd27;=g^@e)mHV8-oY+!YBYC>s5odm5DK2c7diAE&wz87+Ao^LF>E??aFYulXw?S}yD?|4p&}ycB$gA<|s?)fO>( zf0JU=v&%ItXtENA^lJw^bflXP?*EfX0HuMlzJjM_pBopYvMZbC~2F?piVQJcwG zD%$4uUg4;8e%3emc6UD?BCq)2ys zj%ptjS{ph_N{J=BeqEQWtd=s8+hIFx3kpEUJNevtY0Nbe~Ud8cw5M=q7x+l|6IE zlodWdR0IK!^@Oc*(U&;_ils@Ypa0_3K^O*W`R?`wAh)_lu5~&V?e7UpTYds|w1H`` zAu+Y!TD^LJ`2RcKS;me4-VRjhFu(e2k8)E{K~sm1f$!%%R|ZHW|eU*)ry&_;IH^!g6Z2q`sIprk8}NC zhF%xRer6YT?9^DNyn|B4oA%6i2pum|k3>_~q)+rls#f88HY8;iFwvGNr1N?@Ytxf8 z%CZY*<*-&el7+fr@h9%D&cwx$^o%rXorRn6@x0y3)2yFp#Zx9~Srn|wmZ z%PLT~wp&LVnXdHy;Q81&LdyTy;AQ9l32QS;Dvwi5_cixlV|OU@`g&WtDs2fOJw~V4 zfB^%?z|Y08<(Zai>eYuu20jA@q!|*d9J|OO;)iT4A?;~J?|x*NgFMq`i?w|;%~@vG zl~C?}um6|?$*s60bfLy~qtrX)u_?P^-D3z$3Y-&@fhflaaKQ0@KGB5rXEl8iGMypk z+KovA3%Y)HwRNT#B?r}M{`Z5#1#dg&*1GH4BuH#1;V$=J!aAd#$T6F1q`I(zy0V?@ z!h7Q@*mL(mK}`|#u*4JKVil^1K~DpmV7@y@j94B*>4BadkbVn0ACe%9p$WQ^$icXG z%3`x79+bW8K^$}5EVp&jmHlJd`eQn5Azm&kJoc?%A_gevx+qILi@oD9=9kW}+%xu% zZzOXsSq2vhm0c&}XK!XtOKh^8h$0~XRW0u2x277~>i zqvH`eNB!&LiI3~5+SGB1R$e=3xi=(!h{YKQ;@FQ$JZtTkpMNNY{}BXMmIE2e7yEH_ zI3+cR1(Ngsm*)XrO&@?9Tpy1AC)ENVhCN@mMMF&{d3I`IUr&1Cwp3b9SyTR~+w*8c@p{9X{G*U+zGYo)3}oy?K)Jlm{^gR*k}&rQ4Xb>P1wRT z3&cwU;swf(pk{+>e6Q{O3Fl#WBM8tI9gvXu4Cx}=C(y=g5_#vjngK(_tw?Re(HAhi z(XaA6x2z3Wikjvov$&O|_}~z?*@A)|Mmnj1Nn3?xTyZUfSP}jKkbWtZc>RGuW@rmm zJLU&v;Jz~*=6=lFxux~2yaPjgb}kZGL+5t*M4^xUG;ru*NlRp9px04$`AHke7eVIB zZiMTtus=D(sr3+?%iN-=MRZ#w3Ioy^*D9JZ5LzU5^gSW;ipf`qo-r1iOy(81=U&qf z3Fhl1A-y8nL16lS9q;n}R=$69v_WgncQ?4taXOKO6;=MQko#7a$l4&q`5U|dzOdE| zImFL==k?@2;^V>W^EZm>goKJpFNyE?5hLAQCgW1r;S>6CDgKrZp_yfXiFHRa`wl6F zYv8dy8tUrR+zQy+l%=Bcls5^ilxSfpfXr`8MK6VT%8Ma}E95A~9h8JvD|+du0xB5E zk|%3&T@k3++w+yqZzhFm)jZxL39T5Z9DH6ES|OsYYRfQL`1$wNKo-mQ&l|XO0$)V4 zs$)2GZK|lzjn;_I8c`U61q6?{zD4@ zZ%n>*-IDA!U*LcH<6h|0>V|ZRME;P-1=Pw*bwL&HBBP;sy<>VhoHfH^G2e6p9wu=p zhVj@BFg_(HsT=B4cm4Y9JAT?u{^;*IrP#(N3)tkI*Vv7|BGTFiz1(_CE_AxrcSW7E zVkY4vC(i5%nA*NmtHzaiOMFTw8=;vDt}=az9+JhvP6bnu1n%Rh{IRl~Y5m)if9o7o0g^W(g^^)VF}nUFz1l|#f$59{+P;P(Xb=jSZH1aDZ5lFkjt6Ba*h z-h6y8^VI6X@QsW%@oOECynmQ@ih~pz>GMpzeV2q@7B*#ZYiCu)->*S%*#W2v!j6(B zz|IH$@szt{sbz2X!r=@D$>%h0Ek;txzi58J;^xd;uN9m)tQhzWZLVDt+1SDqPZYK6 zRUBIv1NXcdngKH}v^4~Xz;KzuFgNgWdZ>qfYTCvp>v!j=^-!l`Gn0wmdFXpH_;5-6 zbf0l0POQY%r82nKli z!O-Kf`cdvvd<%ySQqQLhtk3;9`sp+n{tsVY0aVo!hbz+E0#ee_(%lG12ntF!(w)*M z9n#%MNq5Huq#NnHbi<_^?mH;|S2OR;oVo1TWd`oqv%A0ezVEkp>D7;I!4@p$UwRzG zavYTR_o6*Ul0{+|#iIyhIY#=oK2)9Y)OpBaDYbjtJ!Qj_uZE+;nwmK;o5&S|^NY#2 z)EA%|hEzqjtdsd<ilM{S_fo zQ2=R-^v;BWXNGxdk947s881(0Lw4&H2PG=-RYpwKw}Ov^7iZ_>8_rG)5;QZ7O_CGy zdnZHQD7@Ev71O=j%gLwuu>o~F$5eit2KLd?7RiWa7WsJITAsZWhFE#ine$^E7tbD+Yw_y#;@LWG|6CW|&ouF6oJHRP zQcfUvNe>5{xQ|i;nq1x-jmO^>`LZ3HFSWU#BYM)nc`n%W6$t@)0}Z^>72+=kCK2Oi zBNIAC;^-vYz-zI9V?pf;XCZ$r#QtWVmCnOnRk*LKE+?#muECO^U*US4)*~86hC)G% z$Ymu4aCA3fR?0qo2jBkUv+?s=Ybdg6@BZENL;u7GVxCghaI!SVEKf1lx5Sc!Yi%Cr z;@i;S{m&J*+3)KmJvaoPvn@;!Qp_@6QKa(9&<=G;TzE3(WaT|_kqp2*kLn3Ca|e;0 z;3r(fOvJal+fEz9^2^&LoI27DEBDpfg8?fj_QDZB1Kr#-QvUwqT{*JyrQeUV6x`+L zdPW|)NgT_4IL(G@iiHK_G(AHA$Y>^ApL)%x*mo!7=fr$_7tuSi%#S&X3>bnSkA2M3 z3eRB(Ht{rgyx)%Kd6PHh7RP13tRcs6psm5VB1!L&JFM@_A0p%8?)hA|$O60#h8J$kd9NriWh!8WP;z9p=82 z34=HJM<~L<;(Y7&C1wE?u%iJ+0;@f1O4+y_2F*+>QtcMpyTlecONav_%ni#-dY<;? zXIb1@R^<8H1puZq(ZF@5P!xZ0#_clFPc1chbPMWAku{JmEO;m3^%n?n8 zJ?rHiRAS%k3 z_W=#eYAx!)KUQd_z_t}IakY5u3KUb#@AW0Hf23#xquUa`DgKu&;h6+aMAY9uC{nt} zNN%D1hD`&<>kxH46OKiK0MQDD?AI^`<9N>&>S4$D{y7U4j8wW_v-6geowQ}dDgYoNgCKjUF8Z88?${Vijt zw~4zg@0Nq&a?hT_Xcyn;35lB%lmH?!!11U~kXitEE}%f=Rs&!SciQ~2>n@Q*Xtm^qanSeyg#%~JpQJP zpR_tsvI>}`#8luP-2W{uqxsyD!W%F zSthobw|FG%ukId7&#w_P=Qr+kTcAvb&S1mh!At$TiX2EFcjlEy|&&n@_&hc)X$b= zmv?t{c_ZEy$9D%VZVxJRRL;slLL$(Ty;HE8p!aQBIzXTXBF_;=P-7O})7$glMUXF8 zNutz{X_IRj^VVSB1y^B{r!{ZS$-kwC;HulEcF=}5I>uZt6XYt>LhB`w`+<-LK6};= zY>5k+#R1J4drADY;&x%CH%yYUluy>^{j-R@Pt)83-#DUj`S0|iEz)TIWuH}-+TAn{eKt}a8uHtUPSY+}`7vEU6$ z&W&B}z4_P~vEV%b!6?n6yN~d92EJbMSRef$zMJN;E`NFG76t{^xAV9^K-Zu=hsQtM z?+|;?$=XD%U1#r)!E0m(6m}6>ajOC_x%FaDo40t4rlmPVFG+2eOg~O;xBbE9?Cw)O0`~p2kk_f zHm2U=m;<)V7HIK-2nW+IaE@Px4XsH)oIkOP-VpCNze@UJ!kdqZ^L;cPzTP#g=VfA;KTd&0viSZ-^bsEz1?=~4fGTcJ`}YkC zPckx{0N19DaQW9ztFTM1r2bp#`98Y29K?wN#EA*m-38dfGoM1C%y*ck%9y4Fh}8{< zoI5ZI?$3xy93}~D7CAsJrLv{O_^{6CCZ)9aEhc%#MeA29^#sox0f@-Dd$^>Kd_?_L z?{U=_6}Tz|$oSC1L_|$<2hYD*Q5GqGH$K$qiAWd5sxr3>VB#x$aUV1JmVb=UG9K5; z<3cslzB{Ln0q1Y~Kn{$~smNe`Bq>EW5#CTEjB@?GXb?n$C3Os+Nf6LWX8Q5om%VG-jRB~HqC0dG~?g&0R2TV6VN?`JyC zQ`A3F$Cx_ZQ^Gp#^(Zx2OnWsG#@M!f2Lf)R66GSm)Js_Z?kbO78nfXn@4TgJXC ziW(1QkULS@%4ywGPIHL5r?9NaElxijciH4i?-W$M1kav?^4WBxCJlI!Ih4|~4w0M- zoDQZsy1ocFo;Pj-+nmx)(XXXXp-6TMS@dePe_qU*5pvsN$EN(kM9IcIK&Eu+>ELV1 zQ}Xc4@NzqiQQp)%RHiL)7FMGbVv7Yp*nD|+qSQq7YM2Sf!oeeYMSv~Gi=yobrGqtb*>VN@+VZZMo5s)- z>8dvhkDZ}X8xzVr=-xKaGAmR_LsP}jDM2gFt??_ny&lv>0%8dr08n&uA=(pY54@B? z+EnyeYvXvt5=+zP+Eo8Spt>n0gxFt)*gs{%ayPOG>*4UX(t&{V;8z$Bkz$HOa1Osh zl21aI0KXUYo}5+!SU%_aUxd5c(+ zLB`QH?{43(0Q>NkE;%uo10GuMUoZynND;;X8Pk0XQbcGGVRVre+mhas|U?vpVe55C-pl`b*4DwsDGDLjSYGYaBo!W{{ zTQ_F4YoL@Mj^NC}5nt|J=PHpN2m9!=N0+D5oWIh zOa`)y#8W%VPaEkq-aqpeX zFmA01==IChW6dhwQ>_e%HxUf#pPZGzK7)-m1Q;ut2{5{hfqK!ODhu~B(<7Pfv?259 z{r(^MB(H9VOjg__c#E& zeIXdX!Jzh*fIMkQ7B}b_XU_0cx$&G>(O^xNZt;bpW?&uvlscf+R+K~_Ee7NeCibhO zMR*%iI^j{sc;Ah^)SX|ZAPAls#aoRuMJISYiZ?)D>D6Am@$bNo+sDMNeaCdJPl@0! z%JXo+K#^ygDfvAxPafgjMPROQIxmBrb{Wn|EbiZA{-uy2EgtioPeU9~rW57WU7Ip* zp3!&dDiMiF5jb&9czJ$*av)0$z&AiT=&o87r@KFH$C2^roe%erRC|7?xvr&lQs>bo z8*?QaaTOYKSyG1h$!s|p<|^gTau$tI7q$QM9P*I#rL0<2&G%8Ub`w<&=uQWP1=YGz*izU~|T1W1sEemB&UHxFwW+ zwEibO!wl;hb?KLks@C>|%i<$rRN*M5J!P%a1E)9?!l@1*^>G<4BX9z-GN5t1Rr&^3 zG7UxLCgvs<$m~CZX%B7MWcT)xMd%7mvhDKj7E*-x%vI}(SztV2P&_>pZ0H_CgCUKH$)fL*SAhTRd7Q1K$v-#BA=Yj-$?aS@ z747XM-n5<9(JIA^oEo2h)`1H13s)ESrXa8=1Az`Qzf{A%Katngykx@9Km4gF$zLrm zxap$^eUvS`%G@nIQcNfQ#-0XBS%*nHH zBbnbz!k0o*Xq2zY=gl|Q2={5Fvguks_w9bK)y*U6k@Du?c-YV5Gw+ud0(t8DGF6Eg zBjfgvuwYq}3T5L8hvcqd&d}>?L7~fGTO||V-e2{cyq9UCXHWU6eHtnfS~lIC-?n*G zI+D7BjqWlPM>xdNYm*WQj*lcCiEzBCMLx-<|Cae5aad4}dcLKW%C3wR*V4szdUuh$4FN-Dtk(IWf=ot`4wkbW%JGm6j`9!RFj8^y z_}8O~uVrWNq+=zEI6cMaj|$i1mPca)iy^a8tA}`s=fCKW8#6EYvo4cI1!iL;ju^Jn z^59OtFU|WcX^KOP6vc?(S^#kau4Z#xlbR(l5Kn9{%2@VYj~p9yinp=SnXSZ35)Juq zQjl`Bv3ThzOLTK6@U7NH@E#d_fZRt`<_((k{vkV3Tp^>r{5B>;^1^F?yJ3;pVN>+$ zaGX^3BHn5gr8|fwc>g{gID9z*pEPyS`E*dlgZFgJ!oe8wiG}^CUhf_Fe@Ej~t#^6= zH@m4iU*4CEr|OKS9$ya=mH+Nv`i!tcTv2U!~7d%6)_?o<)3FAwf29iy@5Os=z^-0oN~O zUkeU=&w60V6TIyBc^yj_9Z3KDqMO>sZIux1FM=dsxQ{E2?u$r5reQ;Y(t%5lcR%!bk(lzi z0tQZLuVM))Zg)Xf-hj;%}|!Q;NwzLSWt!#Z^vzZb$bb%W)x6?Hx> z1l}t*53eLQ6LcEdc72iOSK#QF>1>##rAqG5ayt#ZrHaCZ`)oL1X_m&tc_&TV%_L!I7XNl^RODir z&9H+3{QK%mXkp(>P8Qfdr!{Yi?o9eXTMLAjl{2jA1+fa=UMLTiYOf{F{>z))~0NHNm|Z{=_5|3fZe%9sHL(;yFp` zT)(u@{q57j$z~(Iy53{O%f_{o2;Ne#UhZ3W1(JA)JoNg&#*-(thLg(kl=2Vq){h;( zn$}jB(NuYH!Ex@h{L*YmolLs)5Jc69$$N!Ja;=HuH;6{BUrM=7i!_T{k!O?~-|iyT z8%v0w>bC$#@o4T-1cK;!h{k*kBY3Sk+V4pbVc%AVQF=|uSe|u94Q~*^1PoI%feO%u z=2l6n*89`?Gg)GhuK&cY=o7=f#(u^Ts|7%<8lK3^HEfxd70zF%Wow!12)Wl&kJ`8>|XHpjbln7 zxU$+)^*G^MS{pO>{%a}AUw_xqAL>fRP{qCFl?qqk58pvvIpduAB~>v}{Ejb<`C_oi zdtmr0PzBXdX>(6VTE{B<(5y8*dm}+|U^Y(3){1pe4bR;#uvwwcr(SA+H8{SCaU73y zk&wt8?%#R{y(wUB27xCo!UQzQY>E$|t22Rn)gJPk$Z3gk&6dBqxBDJOy7X1%@b&@W zw&qf_-(M3o2zq{nJv@bFh8_f@I0}lOGnxHZS{Zlwf3yI;H`VP3^RER*KWM9a91njb z)Eap2<=x&Tj_v_+W9z2-iL#?ptzB*jK{zsldKm@??jc0BacQ_vZ36_(FGykr2wy^o zV(~bZ8Jdt(WCj6pZ&{}x;MB^XtMQDK?5*|Iu&wMq5XT6L91j_LM)JqhTb8jInPj|; z!S{}97gnAEln*LaBXIbI6)Jv}^@WK1J6bMDQx=_8$u#LOy!B7A5*O0nN6nlGcjZ~V ze$(7z*8w}IM0qE#98gHZt(`YhjSeq*=aE8&75I1Czz*aM6r;i@q&OV8<|>u^*7;>L zm9s+TCjEmaJXgM^^~rb_oWGE+2ncsn7?(*s7@UVY&CYWW~>LY>=fmeOff z)NO`7_%^8Sv=Msi?cb>f+ylK&&YXm-d-}K6*rf;TutcnmIdy$#e&~7&jsqN#ay|kn zgQCkRlCn*MqKA(TiTeYWf!(FUcDv@c8=pA&)hsqbW7nLpV~tiKv{9A0qXU4cZ`CS? z_6=JY(B#bE`TcJ<750U_$0K54PJ3ku3Y9eYXyhbQ8uwKP%yC>nwMr$;0>{{d*x7T| z#x+1y8OFu+dvWVZ)fMe?n|ww#7onk`t$_qqIb4rkfYz^SA3#=N!J!)Aw{qg#8`Q9l zN8-m{^wcEnhe6aatq5^W!)|7cABhYdR8p>Tnqk}6*;<~ZtMy&(;cUhEghl3`GrGJ4 zVRn0j=H8rKa-w$fu{k@PJ(D5RG6;gtO8EiOwJBuhHGIt4QMx^&X_iV}rJ2_>!qod` zhj}ks@T-!N8&jup?^ngWLu_Kfu}9>;=muY=h%-b4E?ij3j!Bs$T)j*ZWwO%_AASPY zoW9>b%J}1mQP%YOpBkgYBUup(%66+LG!ysM#`DA*klF4+F)Jl?EhYV+9lSpp#+tm0 z%CfwyqKn&lR6`Dj{OJf@!Cl;mLgDHsjYoS8?o$?V4b}ep$8p@)DEwi)cRhw9(;HzI1oh%iSETZ3V29!-vDthPe5#Y>1 zZ1oe={!=_wgIQx7du~kVuzF^v`pN(c`G zpHv_7Xt`dtA0%N@RhQO2);gRDTM9QZPI=_d`F+1o_z)?H*(ilc7$h?}hApIrBvF_h z_*t66P1G#JD`$5*i0o@GyzCD$KTr@^ClXR8*J9E>{B(ZHvfCVL>4j6t9n7aGT=78J#8X{T6C{f7>$E013p+Ka8 zUHls_I8YyF>Uci{(H0mt$m?{{HS`=_?IB~e6|cO~%8-H5gpv~v*(MLDnaI2lk+0Y= z99{*yC6p;5S=eJHvN(0=s8c7@jE-OUBc6v*%XMt|{7JpvkxXw->zm z)jMVIC%=7#OD&B1ynwG?8-eM|-v*b$4cHt_oW{;(gZt5mL^Pw;$r@^dr2~mcfW6w6 z2dEUXVys2ovv`NrN_D>Q4gxv0Q(JXVGwb7YD^mqgCi><1z5f30#_ye52X$CJ0v3+E zIKb=idMQi?+T4=ZGSQ#PXScBaEqcNiW7$*iT*AfI%YZoPIF*$H#&}{yVPf z%0_5Wwzkxp7TF<=K(4H}Vpl)=c-cq)Sa5oNqIFwre3f53mO46fvV=daYZ#sW=ACkP zm&X9jS~?w@)EgG^OTl|K_BH$QC_v*QZ?F$PY@kO7;4BbbMuRSdxv$B%?;o$)JE1eV z)9xq^pVAdk;;Hi}2d>{Y_;ut$LR&_!cJn~*XoIq&5?oc@~3L(8G@$iY?b zwQpXt#T#exjP7F!w6CvW$@+Z)0S-1=JtOR4hYx*JHv=qLhYxUO^!xnQHDapcv@!Lt zIp(90Hn-o1Ti>~49Lg@@pt5a^=hZ!hw5MZ$@T;2gwDPb&-#QCQxA(#Ep~!O$e(*uH z;!EiBBUFfD`8^#{*C(a@2ok*XO5vqLx7eYlpctf@D&8+#p!@8&8STnT99Nr^lpYC?6g%pQ9gei5Xm5Nzj){f=cf-RzY)lf>znYB|)@0IeP4>1N1jWa}e3)l|;xNp!$ z6J_j7h7A_{Bj{f&NujrlW<8(F*35=pgrdKED#2~S&pM~ndwIytrEr;GYPeqH1C%>{`g4pLIA7LKbOYaYKeRv>H&kUk+VV^0?(0#^t9$ZS|4p3 ztpcM$^5~;a^B^>8<&mA0|prW4wP`3Dd)Z$&@Jh%E&q(DOGiC5XP1O& zet;HwG+Zx=B+EqplfIKfwF%?J;27S9V}Qk1lc%sF_$>k&@(r354rV+;Q0FF>+Vr3R z>|M^EwgMnfnKTi*Or~JBU%m2tiRhn&lG1HufE4`pjI*|W{cW9QNczK81w>ahJUt?yR2FtxB?XyWC7KpwpX zy;{Afax52N>Hh>wc`CSc!W}Q)UN&!yR@xX_75j#Xb~7vc-(rz1(UC3TVnR4DAsxS) zPL3!9J>&&FsL6zl$%Op^F*jB|FeX;whBU!x<4f+7eJ_2{qhw>b6M1E(uq{hj#M}k1 z?T}$~f$j3?(DMq$CD#?SrBmghwPl5Nk=#$Ado#-Fxt$;kSLD=Xu3e!qqT473r*)Hy zdHpBQYexcfmZf`h6SPmmstNl2vK^Dpd`kFp!K5JH+pX7JjN-fkZtc1B>fy-BL7&XI zU{Dt)M6Nbpo0sX@Ip%#8J~dxx`@=uE_*lZu;#@breIJ)rJVVXH1)Rj1EaW z0TfHH2a|Aw&62+ZkO-&E!Kd(*sc|jj!^bZ3OUMmYF#>Ji<-3B{r*KN#ol-yvc9{*9 z*U76K2Lx*vb}X;#7dyAROGU>i-h6yW;CN@_8M zsdlPVoMh-xxm7FOMJ>gBu+?Lfd{Eu414)^KnQ&zL(#zD-Yj9j;JckCUoOaj4_^XM` zo`$R&;W0wSma?`!V92G*Ou=EEVyyBa8{kiwOwe+ej}z4lgaN9+HTgu7jGsK)0|tL- zn@k*XFuY0ZWF*8m85Ijr{Yu^Ei-A*i^eR>|`nAF_3S8*>VCpAeMCFaiCrRYH2a20H zbVRM0z-Q4mbI)J2F>7-_w2twsJ&Q$9SiqyaaLHY);0#_L`4>^XI z>Oh?wr8zITPzu#vRp9yeC}%5mjbd(Lr3a(aU<~HbOR7{Tbx4XT;}sG{uaZ3Zs0jI+ zy!om87MwQ|v?-(1@{D%$T?9g1yq`1tf#g($Gw!-Vzv#L)?g{O@?YcI+tE$*i5K2Q% zFY!0>p@H*CbwAV_SG*dYB0l#AS-uJYsNM2YKs3+ct#`;MUU7^3om) z4@YK|uyR^EZFEC=s;-Yg1%mPH)bZlV0iQoIZPZa$#DeVsRh-6`n9HJnHC;`bFCl!& zl}smU3sBWSP?1ad(rUPJ{>uzM=lf2!;Rl7$5X29h4}Yj1KAvvB@R1yo#jWmmB|DT& zytPVH@>drYelB^-5%NP_`P340BP1ZclI&yXk(}W$h)np?Gh`6&O)AMOp|X)-PH%T2 z6|n>*vBcj`!w}0byjemABSRS@LsKI|Nu%GJsHOUxW*NM@Ku~?UiFa(lKl=}!0d}|s zZMX)G^oAS36Amq;M4(U@|C56$t?dhyA+h_&>*dkw<=E@x)J)$E-l%Z*V8U zFz0Tn?)s(T5qS3`QPHsT_1j?kyIu?7OTPj*tLsu%J{BBAlFWhAE8hd%9ZR@)#|shy zJ7w#Fgf&X9wr@5dpnQZE_jj8G#K$oBv~$}H+rxP)!VMOlDsG4cZiwc2kv8exo86Bz zvYkr7h?XB?d$XCycB5WnD_{m!DkcAvM9N9U`SKs8?ANSNKTgwYUi;g)2gVr$qL6(( zXaK|mx;9xc45%6l-}=|2cAAqFP|$J&EBhh3el+ScA;83ZXB3==l_D9>`*su$Hz-Sd znC0Id%eq?`e?jhXf7Q7tw|e*%`0l*^%X>ktuATbs2q+p*`Fv6tcnf@ab833Dx8FJ} z?>u`72s_1XivaHoMmo!QKgUv29{yyT>Ldh9cS~sMz6XGFY zd=99I@|*)o?>y&FL0A{Q#@PLzD$8{R&q28;cigJWJOynw8sEUV&q0d#S3;kbFB_hN zL+ z$UHYIgh?Ld8J&Ik!AYaA#uW#;_Ma{G(RFd;Xbs*ZcSW6OfHU@PFjIleH{Jk&g!D&jv z*c+@!8iN@7qVlmGiFNFiEbkYf>Wm@J6J&TQu~@*SR7jxo5PDN3AVs2I)_TknY-CW@ zDiNxzq+iDA&+FG>pMswp-l^jm_*BG1^*ygTzONG5|F>kt^&Ke>Ux59gdzoEdQ-d5j z4dYqFf$n%ijHD_~s9NelNdzF-0Jd+$8Nppp8}C;U3;Z5iXujEMcg+%SgLZu9$Hmj0 zY!j7qb6J7(0Mtl#SRe+}vIkjXW>9EyF*=afsv4=d;O0aWQrKb9acp zJ(TDwFP^g^*$Al?^&67=l_iKljglqE^g~8D#HGYg#u>mZmcwld2%-Z!@L!FEMyT0) zk#V70d3p!EIKHFQ%{GpqZ>0-y#nM~N)W^SFnR>*xQXWT zTf~T1AUJZD$WqH#Hixald6_xS3ezj`@>LO9BH6< zB2qoD+*I6=wB{1soojynXg3j+%%~2r&)FV2ImKwOB{&?WWXT^3ZgRg*z_ndDkCk%@eY7DT5mPiwb3*h;I(Uo4(}MS{l>=JwQLQpjq3ZAT|87|I8$@sP-U;SiyXIWG4xXMy zUb}AJ2^x8kjo%6Wxf9&Hb_GTqy~w`b^EJhCHf9K7JlCvLWj zNX>_>8{k+rnIC?TN;e(@!6$~IE; z6jozU;NGcVEHbsR_}QHn(JYSrM;+6#;t&)Z89_n(_L7k7Pmrb6TcuY&5op3Y^XT91 zONb$}hUV2y`e`TJDt*mXc~o|-X#j#{d?&J#An{32)`U!E@^WMkoVk;VC5o6#=4A0^ zI4irhyq&nw_=xi-fQ0ABK*Vs};4#sk(V0Vinkw$-wQFgg7qWgfW`Km?%pq5obBWIj z4!Bl@C)C~n^ur&Lj_Y+#j0W%9kc;O#1m3rVgV?juTZ|FITUR+mmkFlH;b3oNMlaQQ z!{SRjFePjRA>-+L!UxWir8}Ak7#_pp511ec*kLQElc(GFpG0Q4OZO>^=jBb@oIMdj z;+!Iee9~rK`3d1>Bx@cg{iYTpX>h4{Dw;^_DCh2FZQ|i_m4e(AEm_$QYW9AqsZpc zcgiX4a%D|0W~mIDKfOBAsg|2moYH%{0;BeRUS`SRQ#h9t0clFkim#g#FZabLe%#uQ zKX2G#TRfGy6x?(tvmcRw%qDdSQPu|CPF%$D<>s-etrn>sSLA9jN1XrCUMseL9WRV0 zM@}SHr5D~$sg`WeSL2KkWQJ1jffNr2(lW$jc%x6RSJ>fdRdoqrPLio4EwfZsk96}+?yK~@FursislV>-Szy!`uxJ#{KCfk zLcWcIB6w5SJEh4ZrO7MhRuRqqwUqqpj>}2B^qEtp=9~TP-u4fECbLY65+rOs=VJ5- z!QZgM1yHx*Xwzb!tK^0j1k*79l_o#Fq75~`kzhBXdP=^BI(9P5iAo0l@DNYr@z#_4 z<@;r3Jg6$?IOUTdcm6@fW?ga8X5Dnmu%|83!(oQfg;2x= zPcE3@J&j^_9EJ3)NNU?>X03{9x zJ0cOpX@K*UjR8Rdi*OI{6lV!#(e&(ifmroO_tUB+Vk;A%&A9Ti=PtHRMlYIr`)2j% z+SgghET>a};*gK{v&&Gxr#(u-rmMTB6hf%sfk+rGB-_;V1~Z#0TYlKYiENi2(OFqy34Xuvip3Y)vgDFGf zDT%~$C1X$Is#aQKPa0#-d+@~)vsq)z^q+%%@b{3uq}i}t$;Ad}-50u-;+RQ0HI(Mk zUxyYjz|CspeDE?7h;XS<=RbOHjEy|0D&wVJfmRk(M?o57?E|QU8G_%j1)oo>)MJ3m zO6L1P`s1W8L<~&nKZvOoglZm~bveD& zBewQ-@tNy18u?egZ|D>q#NXy^w3;>8s9D$4@8yN!mzp-*XH$0ABYJuJdaqg z{@D1pComAmLwtBT6hI7&17pL7WgQ=>H9{oiqV(ulG(tk-SHI^f4J<$W%#|s}3yv2@ z)0iHzIf9jk)f}y|ih)*+z{ZPntKXIumQL{nDkj0q8hz^eb+L+QSz?y0t~svt+e%xo zrWP-rdCKeeXxt~MYSfa6PYJpuL2}Hnx}evL5b&gzueVBPSZNAa`#_(krxbk5q%(8u z0HWA$^;@Vh6ng)>I`6GO~H-xJYUIvq)TUSjV-&XxRJ%BOZ#tS#W!FA4d1P?ZPy^Ny~bs`{d;!oHfK)2-KQ zrNbFR-%6*nE`z?x;o`YC?YlTd1U*fQRm0-PuAnbNqQC6t>s(ugG6$>%8z)>883H|9 z_b*mZrdHA5F??g+Nk==^Oquydh`46Lh{W^-R{;TLYy5x(sASS6GCPy8;K#m}$38zzHsVOj9 zQvC<9*~wPK4W7|PD+Q5J{?Cm+5k3=Ude?AmD3{7D`Rsy=xwcz=by}(W{&vTC8#LaTUZ(>^&XdgJGc!zDxKOwQpe$5Pc!LZ5phfN*Ds5I)Tto7`C0Q}Ba<^% z+9GC}YXPWnJ!M=czu;cYEpBhtA2emmVG7J^8QT_?naNCGV2^xA&=2pL*wy+rXou4l zlorZ!4QhufJlGuB)ZPUxry)JSg4!{IoJ}6W7F`>iTsfg41|x3eCd@b0Aze~u5GDi{ zuuToiCfaAa2-o1k_aBy7S7lMZs#@eFa+G&uEOH&BwktV>Jk7*L!=_$Aw&Hsf=9-^O zZxy8hUCkispH7$FUmiY0y4lco1*WJEdY|mSvNpc1>f6_APWn>E^w_zckTgNPFjz@c zU3wmQ<3;b#%zO_NPu?`6vKo}ge(8`l+pqa2e49QMJ6f^kU{ANUc6qwB%Oj%4O;W4x z!7F2aIIKVW`26~g@ze&XNuv;P*}X0Rw3-1~#E?5LDyoHl0W~MW^?*#h(YZTq(KJyy zv|R$-dJC(=L|7<`@=zM&U|oi2rhH0kfsjAIOKO>X;^9B^WV=qs#{T5Xlw89!RDAM9 zPP|O_Lx6_=2xW4CimJs@g|UX2F{Ckiv^&j6f*hYMdvDX_2VW|Cr@Hv7n|>{RfaZaU zDXCbua(p9Xp^g?KztfLm_eb}odH{9X#HY^O!KKM$hj%_2wPCxB&(qJFlyNd6LK4TE zPMdy$Dov;yxT|*|V}a#2%(%k19>tR6a+t%(#Bs}pI|Uk4I%gFuS8C=-**T?~QZ!d; zz=A%j;0EPkme-`!){aj(&&)|_&YM~gTb5`Hk_@B*_wO|s5u*5(?BdD~J?SXj1|>UT zG;vi3Iv%x+UohB)su}=EFVcKORkds2AQ8AS1L;88}CfOh^K^B6ZRd!@c}TgKN+XfJze7>2wSn&_MMLzP!v5SlC8_GB9&anurq-Pg^EJ24 z4@)*w(9oYy2PKsz`1uphFg4?P?~WFK7f2MV)}i~xd)eD56SMbowRN9O-`8&$sAewZ zqkXp3cD8i>DrhHI=_U{%zP*Bw0OsI_7L#qq&+oYKc&gW<%lTG z)1e0vF!HOE!x-HBHe(FOvU_obgCBdguFYn`W*YVg^oe=<(sTC`{k}B|+)u`RR8}gB zb{HwD+;Ih|q^2=6Pw?Wz^e5Ew%=JcH}I8C67 zS*IK~zi=J)UtVe7K`qE1)NjjOB18kS+Lh1?!U(`STSkQJr zB+y}4Dnzl?JK9)~>(cy`B6ef%rTD|LO}CQwyO0`o(2{Ss-Kqfh)D6|l)z^n?^uV5G zEFL$q9bEXSd)=ISlc*Qi)Yb)6i!|3>jjBFP`c^{tCasxLo6`hLKUsL%tkoFpc#824 z18UAyQm^A)CJ8ebNKFrw9R!p_B?p?9P}6e0>t4+TNx)YHU6eO8YH;+R7&l?qxoG?2 z@40+(T6tP1kWIcz?|W^mFBe$e!%+4cLW&2$mTl3j5)F<*b8!n&7u|)G!_eF2+tuzx z0v0u}_Fy4IIp(v8;M;GDMX6{3c9&2~9FJ1LfH+7rr?Fs%+EKAWWShPSTFgUnJ*F?ue>XHFA;@R=Bzt57w7c7W_f81M4lFSEM3U%5uY9%<)I zUhbj743r*eZDrTyTZ!XQ?{+_ANM{R2ykLKKFlvI$tUi%Bl1&veQ81Ei<4JZuYC`vD z1v~`g-loG05vp(YvP;La0mAh(;Y|8Q!Blc2>fMiBe3fBQo=20BG*0tDcLi9pr}@1N zUQ$~&A7(G+m%FrM4{qlwJ#_;uLrufy;AdNLo9iWKTa}Mi|4_`oe>{oM@sY?4q(%0M zgT~88UQH>qJzwUc6F1=@Ls*2>E=jWG7C<&A*~8J7P|K?N_clPHf8?+2_|IHEhYEx( zRorg=9|sSwSN9<$`$daan0M$#jez0tT9kV)#pUut4Gt1f1EN!nvDl&5`^v^-)D}Uw z?3Y zqu6#fdDj1A+t_-ZpqtVO?B^K3NwHa@=+g<|1%C*0u_})-C;cFg@*!;gou`WAT;GsQ zkO3f3coMF-0BDQqTo=qdwDfPR===uj%X$2U!LfYZ@>)>S#o$O&UKMM6gDP);A}=P- zT`wMcyuc!SYD`mFUR7M4PT?{l1Zj`(>h0riH3V~v#=tb6xrFVo8}L6q40$@-{8E}u zM{Cma57>|24Q$vrom@u<=6&ANyY(LYX8-no4eDMnZSJFYkKYZldtLavC+N z+9NCj$!EWl&%PJ=_}A{GIp@%uK_a}kKYPYOgdQ7c*k&>PEIA!YO!!R1cr;>cPsIMy za?kcTIhFGb8>v^AhOyD)q*fe^h!pTly#_a3RO3b}T>|qoE3~benUnPiJ))&Da>nS) zj@~hNM$2a8bkKbmAXHU#5P0c<13cIp>J;5mS>1!+kO5Z}tzjiQzLAgt;HK~I=l|6u z2WnZl{^bon=$*BSogjj*NY0{uUDo5YKsLyDQ#}K(I)Hb%$#V5W`zWPpna8DlQi~r_ z(zP_CeMJ2CK22=TZT~w+2V{S!zhj{FAje892)%%9au~U&F3CM1)}A)$;$xjZh!bes z9tmUx|7y#CS>f zOmpE&?HnbHSX~DK?8TmlyUW?fAtrCH6Qa)%j=IWZ#u^fi1tM^c$GG zLL&(Otlf*Zo4-P6#cHw7y9DLh7M@)oPhnh1*SBdYbU|wG0+nz=4nLg(w>dC z1LKlpm$IVbCAtCLh~);-jIhsvVqN2yxq?xyuFFB4Ud?WqS_$gsy`PhfrZuIeHL1bR zA5gE$mO*59({0{DkF99vxVg~uuFkhxEbP*Sq}i%Hcgdi6g7olekvMz>yCFX=Ub#0B zRd5`sG>Kd4--D~*VoZ=}hj9kinA*`ykT+f9^;VhM*VVu8@T{e|Z;so%2!_DfLfIF7 z`qr7GhbM2sSGz;b40&pOCi2{0}@wc$a%O72<)lKGIwF zjg% zGv&vjP??%=1wxm`c4_jze}z>L)I)jDd?74XP4Qr^6&!a=o4L~7fUk4@YJR1l@vSAS z_Wx+@Euf-myZ+%DDM3IH=^8*pL}D0V=ne%5>F)0C5Rg(*0Rd?dke2SD1f-Gf&Y`>K ze+Ipu`oHh@ed}A#th4s~_P)+JSI6F09Ifc>8AVTUS7kl4mG0K2aA`KvGtle2Zi-!- zC^z$JpjRBpd#{_~)h5a#;j5XRrlExWiJG>Ea@Mp_ClM+dI^7doqMhD?IiaPMckVUp zy0)R8rtn#-9`*qsw-IKCH8tNe;z~4}RW+}NUK*k_g}*bN)e@Jg z8)0QqwC&LkSIflZGkVHYt(l}tDPR6mk4y0iuKxvpd;AN~)Tl}_(|5#HcU`*qnEYuY z+t5ah!@R+l|FO z1bp|1ype2M^DG*ubM%QisF7P;xiP>3YcGY6`w(Qubb7 z=x2bhzUBMUT~<=?qpE0N4?6^jEcDzp196>u6G$eOJD*5#flHfXa3ihtjRWb(DJI&G zBA!x@NE~EA>_q&9NV#(RT}V@|?(YE-5Ku<#ypCL9U!)j9RU)TYm3gm3`Q|KCn_}?u z_fGDO5azqIJ)>`X);P3<^3afQ))(w!ocE2pkdLvG==u9uH}A4j3e)sXu6eGwuuhQ` zbMI!)d31O)aRDJkE|YG_$tXTg&jTKJdUCxIR}4}BOo=K~ExyltWNC6zL3^p0;G^?k zS4T~0Lam})y{A#tSdXc!*l+;oS{>Mp+dtBbtajYDDA>>vOw#Q*T%wdLZ>0t@GVCLb z(qA?@W5!9l4Ax`6wRBuJ0-rr{m{&&petz9-H?XPZf^PXPOrc)Br<&5ELa&66+NjuU z>10l0cw15o__oOEB@U?;=vyL-NdwNGheEI$lPv+ z)+!P-nq=Ye%K9cKgTm!mzn%vvhR5?}(pNk>VACWEjR%SaDYK2QSUE?a%MtNkx}B+l z5}^b}sT7CH2@LK0+^fyt`{5q;J%L84BuG&Qe-v0~O6cMf!f#qg;#CsK$0zMsSm2Ex z2}g#nJZYY&biX-#NAx1KgbgZjuN+XxKhF(S+D3WqZh2=B1ZNC|JolkmSs!#2nE>T7JD>V?Sza?2aXlgrB5Gk?)<^h?T?9Uso@zg}B0}DZ+_P0dE+yQmAkz;xG#rDUUCz^YmH6};W z()C_yc&X{W$nSthn9ENAU9VdEs8)asy!J!ss@GkMKf`GJbK`OQAU#{TK-|;LURx#ZMimcKQ7hv%m6DohDhu zP*@!WJfYy~j=>k~^a%5n!Oc8H%V9aQ9mfKr(gT6F5xONdw_`P*rD(bDu$!F{%mq$L zAxMRFXavdNChxw2ThMyr+;>bkt;`|0`$Z|u!t=Hn@M?8hkD6C|C7<2IUQTA&;)i$K z(lU!QvY}tDveGfdLccgG4kQse#716zv%+sfF1BSu#V~@*E_ zA1#9MVE4`>%~VRM0BC9{dK=%^D;Ws`OMMOy3NvV%&-H3(Cqon8Trs`A{>+uav-B<| z&d8WPydas5i9}Y-RLlrlsb^$?p>Z7DB|gGds%7^wG3s=;FUIGcDsC8F9YWdK zS!l0U$g}@_@~mM{)jIJcNVNPSXh`e%9?^(OA6>nKMCgt=hTY(9ivuy?Y^L59C&}vO zLm7Nd;@XoG`jwPSCu==3JbinFxQB-z{qktH8p8ZinN`Y;B+eXJml@wnS`i!b0CA>Dn zEXCprmH@cQ3kAB$a zGT$+sM6_)0xXuadw4t9P^_SC;5AIrOknQ3*m%2Y{`ulL2XIPi7Uyh5>8wfFBNt9=S zn6UW%Rg{9Xa9##$bgFrWR`%<_{2JE%o;3o7=l;{S#5-T4_^l$^u{@9P=i zjkLwj@T{$_n3eN5^(Bw|_5S3dDd{_Uf<*UDYwny5))spf zdVOit^P|%nTnMUcy=T*WZ={fHN1Dq$V>9mvy?(&gJww1fqgKU;;pKc#9(%7!N2H{BApofa@}1NMpkL9z zJ3WiX=C(Twi*pVU)^!L2yB=3I!C?|#VcAncBJ3G=9W$z8c+XyKAHUuh{vg%B0-P7B zJ601l=CT6_eHx3FZX2+MK$;!1@?7~-!qh&$@*Sqh7T?Kwv2b3-h|;T3vJj3)P{dMf zJBkHGv}D6&A<@^@@?NZSOVN_IMk)+)s;of)yF;HR-W48amXI^c!=n)Zztpp7QTrTH z%oSM7C4Y;LMozv3h8zlYRGeBIi_U*&AM?zS9i)6Kw59VEmN#|*e8#qcf^&usthd6P z=UqMH>{mx4IPmfAPF~1alb(`21NFW?V8j4qR@j@9qTcCakFI|A+`jEZLZ^Xef5qlZ zJ*XnL6|*0G>8dB#WCkxa+G=E!I-*>Xy=D@_6yt3T87Z|n-nfra^ip#@gY<|2jrjF_ z98EPVU^kQ91V=7>(i!^p7tWu0Mmxk@9Q_(x@8S{m!P6a{+M_zQUbs6Nvr*Xu^@Lx3 zp=Ez2SntxY2{VOZO#AZl^6gwiO!YX33pJvo2q};8O>(9?2@KR=IIH5G;uXH>i(8+5 z)3+_WMl_(oISsU6NQ;kH{d4OZxZO6#xCh;kixp$fz-#(@qN?;&w2vqqAA)H_zh_H4 zoqhO#M%3fFNa`tIHpb6D^F0+HZTW&TTvN5?u;|)(z5*|NxPj-hb3fGGklu7}5l1(< z`5t&Sf^_&hm=NgSBtorDwhrJ07Y6&m=5s$rFpN6FLSA zi?YpsC{Hfy3{@KH68;&9xfvy#Ec1>|%ql%-Ogx619MuNI-EAD`hhrYs2HWP^U&phOabn)@Tdw*&T-Um>*+x{C7GZ|D1T{Ci7p+_ zLQDi!)GOKi7-gA-$NcPKwi21ZsC2LM4y-vU>aHN|W?hOA3%t!$@ojke5y|&DJ$Lsa zM)#t3<5ibf{VF3IbwfPOry+$gtY@Di)-ldZg zQrr8V*R~A^szPLEskj`x#`yuk!byq8Z*F;0Uc+V^0oyE#~cQxg_@_yEo<2bK`b*3zbgreRD-oGf>^pi%5<206bXB6}+ zwz_MLi&@)=BsmJh3;jc_{DBtpQj@g8+H=I^yT$mIIKWDdH1tL!mip2txl$*V@)>vS zK$KkRl(LKRCyEmo;lvOVpBnDq=*2m~&D+)>Z9L;DGUA^6+w;)J2Yq-&ek;CBlf{*u zpo;7}=uW3OLHM6;e1FssJtc9l$ps7f)xg8Ve zmf1QITPZpX@K)Iv91{*Z4f>*6lg;p)XhV1sTc?Z71$~GY-hqQOJ1B7=)6H!Cd?ZhH z^b_g>MF3gPn?8HYR{mZ6gz7+p1H52LCGF;4KR3~3i2DktVo9yjl{8DtILFH(GKxM& z=B!|wzpGYVf1HKwu>B>bi{r_%YGsv5K$XOOX2s=?K|VkCEd(BBL0Sw&em9A^bHI z#uxI$$9DI^I`Qknqw@{T?vZf!BWE6y$FT^asL1L)y3J$iOdFg4-iM-0u%#gC7TS+uE`Rg;l|cY?J@)+W-g;zJq0DAX zBUj~^`RT-?Fa}+UwrJpIo#v2b#IWMsj3)ZsxnoVbKUS@|pXuHw_PTIo7_A|0Xz25+ zj-DpF9wo0aGl|J0u?DI(V3!h9U9d5Y@7%X2iQW`r+I#<6Tk8iMWL{jevDdE0nm^93 z>)T_3aYcXTm8STIC0~=r72hxiA^GE`c(RfoMqo@1eHr@7YM;o-*l)69qx7@&=4C@A zNyqBFWU6JU`5NDo;_@d-lD5@*iB!u{kT4>DLU19b08Zv~--wFh&?0CGOioz#I&$Kv z0aq6fIeOV^ZX_Qyk!!%U$%BMEzV1& z1#ckkhta1N5g$fD7I7a`87&BrBo4^}vZof?(dA6(PfeG68zfA1XMTV&KabC@zJ$33 zX(0Bjt`nMrNeen~M%e<7lbhd>79<0_bq7u*TOcrn55Q!R;?|mUMq8SC;HThV1}a*;Ria;)&Gnd)=OsP`VdyyGdXd+kZ?z@@onUEXN+ z<=BX86fy9oFdr(F9Kpp+ZnHIEzLbE=usXnbP6S;xg*zqe4+aXn_K>U?ne zVjqnTIb+5`O+SskQC4HRH#^&12sNEub8R&G+WRAd)SAewbJD$M|H3Vek-5O@J=`~B zNQ;G1J?ha|D|$Qw)HZp#+QV^a^=AZdG`MZ*Ez|xp;`2Y4evOdr1`98{$yxGBw_hi6 zle1V;`SHz&tnCH^K&lHyF3%82?OFTbbNFi$=aDof_SZL}8{!#gkEF#ja2|DGVz0ar zJ->zGG{xFU>WM$&615Y<;z+dlbRZ zWcixI$jD|n?ziF6m&zlR{(~)Oy|BE>->v)vV+Sg&4c#v;kPZDWRazVLUwJ5Vr&E8&t)afwf1Y&kZ=~ zbyzH@5Deu6` zGA#C4aUk2-QYnCo-cl);Yenp{<3P4I5}H^l-Mow7qPY8I; zsfX04kHV=vVJ$v_ZPhHQ$1!5*UCm(85_Y`fhHJt?P`>Z4<`0~-Maq$GI=v1*rq>4? z(BZsWY_0HB0ig~3-!lcfnxy%vgOdfL3IP*mdY^EL;)ZbFR!JL&o1=38Hd`0ej4F<> zQ5PL{^M@Jde~h+4RlgPr-Aj9XrN5QKg?x7`>L_q$-vLTPtJdq%S2|vMs{H-gzawIG z;Do+$4!0ZgcrhybvzAc<`WT*VJQG_${=r45)K+>F_f|*`7o^X>$?N0e;*+EM%(d7! zbIg=K5imk_;x;|=OInTg1$}@r=mkx{Bia`zNJ4{T=>tMVwrqI5jZkuj$|D(u-r97t zu?#b{fin1T**#C!*Ztme=E-!2WfG#&QnIIbm`BzM{TRpA!u`C*1xo$AM@WKX0hvO7 zdxjYu=mkRnTGwCno2CW(zKynxy1B`G-Rw^u&(EH3>5w{MV(&cmtrg_gsnk*OF-d?W zq&?t$%cV;a0Ya&a3@s_T|0v^`B}Mz|B{tEBR&FZ_3`+_OD~coC49yV2yPSAS z1r8*+4kQH*d#Bhw7~Zy1;L_lj5hG*H@Pbsjd=ib7PBO{S$e0SYQrE}=1LFufE8(^y ztW(;rlXKvqwTBYZR&5O!)A?-;($o1(NP=Xo+62I%ujV2x51`IY!*_yvQCm%$N<0k5 z(Sl|56K3=mm<F1ecawD_}(cF7rdyAed)!Jd3bp17-{nuX$}(O zT<{vT@QzZ8?*TgYPD)c+blc!iE`y10sV1c=(}{=4eGKoE6A`ZDwEM69&qGT54@>+Z zKwW(?C#9k77t=>vCT9Rfp{yjLwin}CuNxc<+)IJ#r1Fg6X>j%VQ>(@4t zn3Y?+7{LrSQY7>5#-*SZ^7=3 zX%@XN`d;-Fuak&bme%fMtic@nwpO-JcZprt3G-kh{W!FOdzH#C%eVanC0NlcynI{h z-iz+)tNqENk;dzQWZ(F9U=(N18R#QuN_Rze8Cx8GIf7kh*|qVhUe2YcC!@;xK9Any za}QZr-*Y0~hE!XdvieX9N)8n@&an*_yTZA{BCA$Fh3;Fv_^oG-os7%->$(fC7fr|0$ZkdbVEsg8odOlylm-|Bm;La$_Y@( z*wXQlJT=JxD#p>R69MX#anI0L!C&97WAYw+!;XGN@Qpp@87h(x04yMD1D!*&o>^$4 z+@qDt+F`FkjM#N*sh7@IrKm$*(G34b`<(kU&Ms-tyL z?{=1n7JKS(v1g@Km9cR=a74z@keZ~Mu@RRvo4&Ckb;B}Ni5D@)x~A_=dm`| zGI|>$WE6=4tQE`p6m&za%HCemy`)mB_h0O9Gkz>KGL}PX-NddCG1Q?9e@1hCUQRX< zR02*mG1S8he;#vvK_rB54#3~07Lv-ZQ70KBU6LnM$W?}U?a1A&n4?QGi#nIrKR2up zet8I!a!AJ9%t1X?6834ZSsqAva}k!C=6`W6d`+RCXGdA@jG%(mcKA^FE^iZPlGAP*z_|??)V|-p&0}lM5~hxBOS+Ww1_R@rHh^?;4g&IIKvWi3Lz9-!##@Wx?pqtwi7XT>)t-Xo=ZD%}BU%=h#vo_mid%C`R1Xt|*y z+q<9l)lXU6@GrfJM?{!$?86xr%%g+)aNB&U6uh!Sp-0&j!;`a3}pSnA81d z2lsxb_2mwJ!JPls+~#0z%hflau)BBC9`Ni6eLli6>bvZp%aRXGu7dV5i1&H9aaOUe z)}KmAWXZcPpU-Xk_e(aOJo_YkPAqa`fopAG^0awdyNql*QR0}Tcb7{6@oYWtT64+m z4N3&bKqv|>i9#4k9EpNIl7s;)AiH%qC&W6sub8F5LvMGELB13Dm zGk#1B^T;qxF^6WRn5(H-om3=QPJGCPlfC(wq^k6Lun0B3I7{~@B}@3`pGcOFfh6Dl zlT9Q$^S1DIWr2IWt#;{llis9pB4k&?OJovR?P7F7XIFcQz)kA|azwD$I+k zvfIrmORMmuo>SZi8D3xO*rV5KGfiXK72oS5kTPt&`+7sSriXUKLLj#sOn0=@{PLJ+ zq)(0Cr)S|<_mub5=YX|q{3+@@v;K|~ol9fC%g8~< z(7S&&cD+~ZwO4#Bn8Wvz@}{D8Gne}c?r=6ncQ)oZ)GlJ zFP8ccNw&Hrd{1)tQ6GTc+zi^6-<^nB+R;E6|Ety|Q;VV2B^^mJr~azN&HPMad}7q` zI=_%_NKNKzyjzdDMP(ZzoRmr6$)b)~r}}n0IHO24)FUK(H;BW6GBUrifyt$-2B zc}qn{3pjCTh^zkIelU_A{hM)Gpmb1(FCOOM3E4r!V{f` zmgOkaQ>>4wNJy)KqUiJPUa`XGjar)|DsQOWMEt_aR}L9()-zk(w?>haKG3-3B5*!E zCQe;MdyMhaJ--MNpQ_H?Fas{>VlYIA39=X z9)@<){nHNx5p<=tr+5FxY95w~L_c9t2K#TnR`p!M>{}Ea!j>@^o+GUBoFf>XyUEaq zCi`9LY}4p+8`J>nI`|E08j7G+ilRFPBfdVT&2YQ3d1`yxtGj&yDSn@NPp`|>)9mS5 z30621v%u7gcN?-bPu~>ji6Or9Uy#K@R5+fHM<|)4a zcyBhsiD^B-OwbB2zGHTzPw}<50w3PMn&T5XCRFcpu~Boe0fXdRp0FgRbT|&(RADPd zygn)=r(Nc1%HZ*8XOYiP{!4R-C#Bx+RP4>#e(=$;085*6NDh0!a}b{$&Jq)Ioy!>k@y1)|&RixvklmP`t-#F$2 z?aD@@$V)xL!ivj`A(DNYuN_gOmkYID&!OIdfYRWM#yDr+qD8$ZSfH_(L|>%wZn8Y$ zS$i_iY5@3?Q4f81O|lUSiPJ)Y5N)V!4g^gD@k@?r(&sMkQgJuIRye|{Smkm~V~mAl zki|qnO=lTqFUqXs3Of?I+}(lP+-SeKokyaHkk=vYsI0Zs`_DfeYAcQpDC z7dB|D>3fL|`>wr5KBDdWrK;y#b!>$!$+y!E(3;=Qk(|vOUlz%fcknsIc3)cdMTaB_ zl_mkpG>f^eg)D|}COKv+Hij6Ni=htIGmZk}h|LMa-J9=8oTej(IQcxZU)O_M+@ef_ z^*%?FdC{RWT(mo6%DX+ROi+349~J6ZDS;J{pt2vYc&{_BU`{~(hzGfy=9FPnqwYOn zU4|nO1+f)45{z{!2Fj$Gz@_h|W%f!}l}m{;%q(wiFbn zQxDx~!ePf5&b9c=6GcU%6rFAGW;~aQHGU$;6~vEM^|u?~Xqd9xoZh@ynS_5>c1#S7ynZ0#Ga0T{Ixd%D$zFsqX zuncPp>sZ}wG!+8ngjAh5&xCubs{hmjE|&EPS%JE5X3(Rp?9}fcVCf%VCAU{{+||$L z7t|tat|wx#_grCyz0bx99D6ObAwr7AZ2_E0hwT=RWxW@YR0=d!l2nQ`ek2V}Y2Mw3 zkeylI;M3e;$duafH4~3svz%Y?tjq$hPxO^O+9?bk8Yh2cg8Z!6mkgB^U^1!JdLUQCSS{)KE zqm#~YQ-UmTNwn|d6rlvVymLckWUGD{NX}MGNiuy01OBM^c5@pRqg6-S*Jl&vsAa!aq**#$?=W?d{DRn?+pr9Wi zNArUB3BJk0*H0dpJa~bomDjEY=LU|pTsf!kws)EkAwZd*cFPP$-AmE6(`Rh$A8bca`=I|WZ z1UlAJ{||Iu-&&`C8TFGmX9^MM?eJMC+m#0<8v@^tp)|llW{=a|u7~UJ8sNiqC=KKx zvk~cTOSf>iZl7EiO<&-{e)}t0`s0H5*3kLZ0NR({bSNBc zcG%z5LaO>i5eL#YIh(UdssL-Zo-YlOjPav#C8Paem7YcwCy?ydLC_Ju&surajX+>t z2~BT$hUe8fe4zp#-vu9Y8*Tb0Xaf7Y@Rj=MvQufYQ_Ws6BUg8_E;hcc?q^-7e6WS> zFz3?lL%b;HqCyf{E$=4m*-5h4=-lpeyV-a0<&8c>!SBMk*FJxP$hqyRjfDEC{3)5} zwD_)f$5A6{`&5pRoGA$V(%#V$5uoIr$KtpLi7)bwOL|y8a3C0X%7AcInl*h8T0|&l zT!Klum4oBjsh@*`*E!E^Y>!4taSPLNJSpM=ik)5v4|Ildp12;&^|rTJhZ}K8CPX;& zwKrMg^Z|U25tnH~ga;D7>TADx%!&RmTK-$&KnBT(LfsB>#xTLizx?|qZ_^%?HM~^?TT>mZLl(chYw}&R?&x* z+A-QcFd|abzPS8R5p1l)IWUq0?Ms{?`{1I3SN-$5>7Nap(BYnG5hdHqK&!XMd;<%3 z>-K5u_NbJ$>8)pZUD|kZ?mX zO4sKo!mTOj?mb0$Ke1xdiBGCBYDpU!kLvcUN1UuMj?>@aZ`TmIjC|Cz!Wb#F*juYQ zxY2>(_EPV#-!A#>)sOYGdg)wDt_U-onj=Y!zOWMAEVNMEWi~Pt-7MylZU8nDzVMlc z9u!+jO$*nY_xmHf57L_bFc7?nA>>cp#!AoU7!K`GS4;ga(0#T4_e2hY*t@BI>#hk{o*2UP7R=nusbIG5+m1;lyd@hJ0}ihSsSJ3L0`Vg zKWBWsx$Vo7lSoCnBq3cDT;XZiqp?{V>H%zKCl2-iwiu1sQ_u46wmRJ=@=G7_yjNLW z;(0ho0wCdkXBiYF1mFXc7tH<9fr2m&pJFFIHhn7_Z#yTg#a6Y>W;J`Q5sUo2*=*=N zZ*?-!q_)|5QVXaBuEzcdMqod zgs+(FcLTX;`Z-r()id6LJ;H*LyoQ-r-I5mKLi+$hxe!9RX6*b)ug|{f3*t;$BeVC{ zsB<+In4H^KQog^Boa`4UrL0?zz6qy0EW-W%UXvoR>!lZgjsx7u_| zr{(8HIdkr%=G)!T5(d488AD7`;D{pZc0Zc7xwdX$68VE+~w7sVc0$pKo8socE zD@|R?B2kV_UntZ`cP-_X-b(R&XYWf-9;D08-79+5z!YXT$y?UIgys8=cS+}7JyQi< z%1;rqgKrR0-jClPJ3127*cJXe&;}1_`Hrygr2L-Si^8f%TC{g0trx#8TivMwC^ZkQ zir6iS*a2!)bf5t_ah|f|9e$&6+*Clu*4WqCR%h9Glo?>{T&d}t#j9IPe`6`_Z;gyJyL_}M}LG9Tziqf zl(R+n0t1)GoF?lMgOKP27O5N4JbA8*u~p9%^bBz5BsH!yy}3(vh4@Kr(@BYqC_-#q z8-LPF!|m68OPLi8v1RE`9ZLomGydd$djC^WNOwDM29H37=0S$Ke8Ow_1dZG4-@!U? z0!CS?y|qoI?W*ukbk8TdRE;-3I1lHkVqo(8-q-J~;!8|7)XRYB)D$EPvkLCi<9_Xr z;lSk{Z~`rZ{80_EGfk_5jY`bKNTr~vPo z8@BASWyJiPhcX?5EY1BdWHnxUyZjsm%0u`g)k;_hIbd47vh2Zme*tGFaOK|8{}D(P zHWPX~c7#9pqHBC!%PB~L^BULgop3=xBe+rg&OUSuQ&LKZ^HcEZVoH+g=j2V4g zF_hWx!D0De4Mo}aeGa>KR(nPBge&hL2}MsiEhm2E+*2&u6w}$XlfIVy2BSHKe!U4E zE|`lOJ_A&zVKiSqQLBX?G~EH5-O(3A*qHYrU6mD&)7ep;0Lu<1;`bkbMJi`-ns>BA zW@-XvVyx|qFzcKKceL9|FyX7Wi*fZbc4+p)M?R-U&=nslqj}W!38f%%;5|d<2r9jn zFIy#rh^}cNCMTMM989N-+66U&wCEZ22)lyV7oBOzFzNYh+udV|lV zpG?B`1_hNw|3kccB{&OfYP?>-bC`mL@AuLxLzDBMu7me+ zE5uCQtjf0z>KeY3aVtA%4NH|9%9t4CsHmDvZ(I$9QIRw9m>5T>sGd!4e38)EP&h>5 zofqm-es*V z`7XXd#rH~;{iIt$wB(G98uQFzL2se=$|p5R>oxYwoYJkl%k-~;z#lBBHIaGs$)k&#qFnQ~rm;pGT7eWuR zFwr&`0-TYPtvH}g?gz$bXoE9%!`$e&1H~WAMEqslhI^Of5G^%$^W)p({UNiZ{aTN- z+KI@kiUN?@>SC9+g9$&D4Rm>0omAe8&acqQ*0!i8D6XcOomg#^cllABY1r+B^}mCS zaZZ{2c*fa2^0_bjsshGE7>W5gJu02rUwb$^wfT&T&=ak4knl?nr&P2V{Ho54o3_tK zO8EQVJiS%JAj+ z_R6W$fN=#`Yw`l(3Wv`NN46(N(aHa*V6x)KuQ+if;BQ*KevhxED41QdfidFGQ zVMY&^6dI}d3GY8jSwDA`lY@Lm4bnu#!SuRp@gy?r$k%(7LaX zWkY#t@G9%|b&LLYvnC;6^bfBuu0k7-#swyqcz5A{Po(JI8~^1ef%=7GG29i~ZGvl5?mxuVXQT_w$)Z zX&0jg`UjP#8iXHI?*GgaDcxj5LV(P^#Jj7QZU$a@B|Y5hus&gAw$!Vb?5RqVvl2b@ zaJf9$Q4^FCw^xhmfzMLaq*&_5O6?8JE~ z7A)Rg*SeFR&r;_qDN;ql?kjGl0c-#OwF0zrJ^M;tN7W_5*a zYBHYqitnR^8T;0&%#@eq5G+^8LOLd!?8mKr#*?Jr&I0Gla?|r1??4Jk$>KGb)X(Vo z@PDL0+r*3Hh_^`6_KyU)g4X_Y@xAD@92cOe+)~pNi=09UKrX-ZR#COEcKMNCI?L-g zjX_N~-lArbBC=X7Z|$+w#h-$>bIur>CVI{oo%ZVdXKWe{lDtB)fGjr6u~Xh1_+m}p zmkz67$wMg;dc)(6qKPG!Re0Cc+nzA5@U6Nr(0L$7r5Kr3bi1pxQ6LAGv{4Ahi5Qtz zbh|GS0>Tg*8-pHlkrrO+vVHp~ZfQ2P!%OQ}r;bcY#W~P1aPAOUR%5E79?fwalHZQL zAj)b?LBa^d-LidF1cD6#)r3I69ixI)fm9P!XF|(ZtEl#nH&b33yh)(auQ8 z#950~L0l5JQNrC>O3B&4*#yLWd#|7%HmjJOtuyen6NvL~(Vu`JUxy4BKR@U;44~UU zIDuGYER3B%TG+@SDq`z^fH$}RzJsxWxBYn({EtWfJSk@2Y+!9?_V+9PgjCkV*}xcZ z0rC8Y*U*1|{-5E-W|dcv1%U+x|9FIq#_uq)DnhZ5k175$6v(&!aeQTBYvybY0z=q2 z1O@-3KfjQ>y@8RHi8IL1#LU80fMK@|#sIP~7GO~0lx35(7c()pc;V@2qU0&3Y~*QW z#AD1LB#6x~WB_EF3A4L_J+rBWwX=z%6UfBLNPt#M@s%Vk@&fAZj3Y8*5u9 zUUvb8+edf-j1;pnfNpPbwh~}amsJ2c+u2!LSvZ5(S$J5$%wWiKkg21AjftC`qZJ6u z!o>i*($UzIS5aK@&kF%gfWh3^*`Ak`)y>U~#SOw@=V-(*_qk6nAtdim;r8LK*e=7`M=x*`TyZ)=co*1r{Mn<9}rLv zL28Z`K(XOx{m+N^S&_;8FERbE#$8tS|2g(HHpqf$U@t4nD{g1xVgs}ZFU9{qX8V6J zmyC`65lnj*N9)^?ZEVD9Vr_y9krR+nU?7~vM!cqWjy48Bxiql1x3(}cKo(b4pinUg z@&k^}7S7ftg17ZX#M=2cu(m+f172$bTQdO$cV=S~Qv(-kX9hu5dq)dbAX{0TZR}Z{ z?F~3Npgd4R4n1yT9yUD=PBue5Lql#hJ!5WeP7`A;c4JNmH;cW~@658c5c~~pePR8l z&;LVK-im-)4CE^7KiUXEY|ww{_uqTbKO07%l@(xcLpFN=`uA>&{hy8N-_`i(|5oZ5 zfnEk#bAT*D)}5!~yvT~h#>K`7W@qOCa{%r@t^41cZXdOCd@3uV{7OXhIY`;u1SD(V zY_0}0kWSA*FKvxjK&n79jBKx?wQz+e^*7Ph}R852ia6YGDx?6)H?NEUdph`l2S=%&CtybyL?Fegxt zl|jfz@PQod?3{VsZC#kbTs%B1>|89|zF<~GiB}RLN)meN++2DptL3|0#n&fgug@_b+~MfPudGKV=;Ma-XxKfrYh+ zhFh#QDi5lC7Pax9?;Vtr|AY6n6VI$(tJQXHhk&jaOP=j7oQ6^BB>Y!blw wLpB}>F?MkX2Ut`>k_+hP|KIP>K@M4*oDCeEZxa*(=3!@J!=|T~ke9^%Kk@`~3jhEB literal 0 HcmV?d00001 diff --git a/doc/images/FactorGraph.pdf b/doc/images/FactorGraph.pdf new file mode 100644 index 0000000000000000000000000000000000000000..13b0c494bbd7404c517426fd30d439d58ec44832 GIT binary patch literal 5768 zcmbVQ2|SeB`!Cmar-f1~T3$qm*;g@P#vp6Ml_fOIyk^ESV-~v-C0of-RH$gVt<)_^ z5|zrDT_H-lkV?6^O8<9+EVs}9_xsI!nD>3od7kr}=bZ2NJkQazr_%IMa12cIe($~< z7!E)J{H@+FLqmi$$YYB+03MRi5j3u^7!(2snlD2PQb8u41(L}ykyr>a{9wVE9nMv} z&4jsquAbST7sGY+=VM7(jmHF$QUU9XmHnJji7sXOnRp9wNmFs?nVuu8?<4O&>?K8T>oZHVOW@nLpIVjvq`kj-z$y&Po$F1m z*$;%Oy3bYIS-ebzB}aA2uJh1$DQId7unUkT5$=jV92iL z^o4en9m)763xi)@( z?5%Ti5$PRv-zZKdXx~$-LVaIrzJZk-^T?`-&iyBjlIWRbTL4;JVf=vA%bAj+^)~?)KS4(-Vys`ZiK? z4jOBOANE3Tk&nY*&FC;SO_V3UAt+7y_xN|tQ=%4`R` zR;TH>&kYZ%!9gRb0c@K7UA?oE`$!+zd!*9q@ut}h7tSkMEV8@ja_Cg0p>$kx<;_j0 z$G^NRPFqrS_pE>Z#W>H085o5{t#>KX12BN?x}e%ddQPDrC9O3)|M9?=ZxysT4^I$_ zdb^le*;~84+RdNb3X*CVxOGkHii_0Yf(vAAHF&`St)q;`3MaeXI7B)2YwF_NHxAm> zE%9bOU8uQ6KD6Qu)4ZqyEKW1*9+p|6T)yK*Y~2eTGXVz%&hcS~%{uj08ZF)hzH%P* zG6!(mRjhl;>Kk@WSWs^gK(l~9pgg*kap}3F{Hi68*6OKfAjwA zFnOf=K%lqgiejb866Ji+blBsQXV%83Y zerZ9^KSLw`e1DkrzRu-wq0(Cy>vdg~Uw=dFyR`u1vBr=LJxS0n!Mx;`gh#^0MA)Ci z;27c$BJ3G#5McwdxC~Q%FyMxSn(-(!Kp>&rVF)^34ABIDgn9`nF0t$Fjx%fn+1!_9Y#%{B;!J=G(KboC1EEz3?d!` z1$u`pi+~Byn4glNeh?UB4RRD1^;85Pthg)@;0F6)&mDj)1V~Iutc|InCRE2XDGV{g zm(LzI@naT0`xB=2|LHXhVP|gxpvdHL!;^wXC%`0n^q*!%XEnyTbQBr}MGh)rCUm?LrnFhtVmpTvi;FKpszTr&ELCJ-fy#)D1;E{_cv z;F<75+=+LGfURQ5mXRz66qJc@ON>pQgM%%VLZ?XPK$tNF$@D%Z;kgt!0#zZ(n+ z1e5RQ$8evt8GhpS=L-MazoUD>mf;7^+~lSZ|3LJkkH#SZ3@s~MEXCI+M)?OCPw z`a*ku*q7}$*KgP(YpS#2qg>Rx)R>1KIybhd5(P;=kz2x>6Nq&__Z{$= zDw@krE_szZ+|1HiT(sE63jY1Xi@{K%6olHJTaz!U%iQihohkq4uo}GPT=K!p2boFX zAFeGj^ySd)TV6D+2oYTD-K13U@=9ik)Z3g)y1ZJZ&qqBqjWX+da_dtV>ZyLZE9;D7 zofSBPa*TgkjtSxs9x|CyncH?==1_(&tL!&^y*9+C;O))w zd%3X>4>FYr?}~(`2yjwDv=G=Sp9H z9D1y>=m=YDdtvA0#!}W6452jyU%6bt>DVlvaGp`grJ(^#;35=!G`F_6#^-S38yedBoX+WYeybvxM0b-s2R|5Br477%o8DhuFvpWp zZ!P4WITG#;H@T$k6yMyC3gf%;-qm7T6AW~l)dG*>zc$0OBN{dBw3^12KLInHQ77<%1aQ!{#N)9u;Q|RK!)5gKCtQAo76M^9T8I)e z<7naYK!lhh1fl;yd_*WHH41|1W!OuLWq8nr-g%H`Q3=1AReJzd^jxD zyU28lS%g>Oy_9$q(tZtSG4%9KW&tU~BP*lv(e4O(rf1(RVQj>~?`+)+I%`OM*?GEp zjo$L#=|D=H3dkOclAhh~+`-}p#j72}@yH^0Tok!vmQEtTo0Ar5{Z?wOUy@Ab=(+JpSP?fwf? zApgbgbk#SdntoEY{R?DsDCS^&_<>F0vcIXTVFB@F^51@|Q(9|16Vua=R!LU(Z)f1l z1mq{EaR3enrQt~2OjJX{$*3NEorG$r@m~)?B6>QkryPQ#Cpp3k!AAs7!SnQtby6nv zpW~T;nSA1D+Pg{cJhF;C;Mk+pdkg-0x!#>9IC+)y>NU`RPteM?`i=q0@B3?-2$RJ+5`uOq>JnL(^=_F|6ZS?x+=Z}q*w#(H{+XE$6C zMji}{?Txx-1H6kUJHCpQv-1A_k_6A!mOc*UX@7~>2@y~AZp?QG#%M;LGp8c>dT8X6hNZ@?n+X9LL^fPou{Pz44PC3U z%%(E$${xApWxUN>+4x}AP>+n$ z{GoNn{=8Ga?XJl~q+HFC$fm1h<}!Jub`57-4qz127gC4p~2U?oy0@o3b#oTz-J^0>}+;y_4QkJp31eiAvZVcys z*^>n&Ied}$M_~sL;W&a0 z1ZwCSPR!-=s8H3dO*KFxq4ENcL?JO40-ERwb+F;He%Usv%ol320=fR8&DuVjbpRZk zga;^m|B%s?7CV!S9kO7q@Lg=O!KsaziL1>Kt=;DSC z-HAXI9v!-q;d$`^$tHxZUo5GBn<2@BfXC5rW~LMZ5kobh5wRp1fri1F5h$hq)U4yLJTW=Dhl9}uOk*8l(j literal 0 HcmV?d00001 diff --git a/doc/images/FactorGraph2.pdf b/doc/images/FactorGraph2.pdf new file mode 100644 index 0000000000000000000000000000000000000000..df8d47e5ce96b3cb66d81f8135bfa980ac52d358 GIT binary patch literal 5608 zcmbVQ3p|u*7oTyRW|d1zZ8TnOLS*hYp%|A6rBPy0CSGP3Gt7)@x)5cIluK&MCYPef zWos)G+FFX_5{hC~E0HLwVTJFVNfO`wzWsgUH|BlM`<(Nf=RD8v&T6+@8TSsE6_LGnS4XBH}cWS{Hl~8)iQT} zp6w%-ONSjq-6^8=CB4ky&Spn}C~?n`z@KV5d6kHjC2=p6-wZ5S;@-EVF7)_XmpHJ$ zrt_Bj&~f*sl^dd3eD_xt4qHF$v)`p+|Ht0VP3?F4S|<&ITPS|IT6;gX zupg)yj#LH3FMDGfd~12Mr7+oJ=YZxVdV*&-C*RN^GO#5U~A7qnj(=zP?bu%(}+o$MlvYR&eQWX2K15HL2&`QdX!>YAqI$gjPu( zQnN3#dpNmSXN{=Uq$VFb6SL2cB(HrS%tfwF<#}A=UtMvTu5PU>t~g)S%5Gn1eeKnC z|CkgLT$1s%t9q)!=mR#C(;M95?wG1>9NL87XK!_nwwTCJN1Lb~GvTEMl&!ed_PR%N zDaCf9%+6lhhM>UAI+LKp_sr^hGCv&4MK~B6{7Q48z(aiGJZqP08#q(<5LD{3qS&g5 z7xjBvL5(!(A%nhW2S?<_Qr9PK7bY`Znid_Zx|d8)DBv0R6#vHaPx?wpw5`pT+bYwuK_)q^`MKK%k`zIQkF zRgRCR=3={{7hbg|#OrR#vfq~6Z<(T&Xv5w&>9tjlti7_iVC5q{=L}(V`UNwBA$}v} zukDqpCss~9CODn8D(wMXVwQTA9X<5)I++lgZnnOMv!$uM(?TFp_*H>Ym}O+M?p&I6FbCv*l8yF^l^sU1LwoXzLSjoJQstp%1gO$)D9SJcXng-oNmifSpXxdN7RG%3X zvIaQ{NIm5PXgiiSA818ub!Ja(nnB4SvLBO}=k zC@3@GmKdA6hOHKM8=M>@Yaq{Cf@FW_|F8t=tR-M)mOvy?f$8u6;h-eubN$<~V=LXl z1@g~fe3B7Y^|ZA=0(jut8@IcO6UEX^k#8-gSEyL z=lGP23aWpH1#d-+K;K0026NFPTA@kD_ z%K7VKgjq6LCwF&J@e29h`|{Eex#K#<_4!FB(;uWCi+p$eds8-(?%4KM%kuD`;(;BD z@AX_sPnPM=N~a@q(*1{xbbh>JU#++w68u&93!V+^sH*dvuZ!8`K@uxB4<0|8UXe zHy#~w`@B4g>_6qcm@uEx2-b_-6PG4W@UVIE^OpRo-r=#Q%f3J3yJ}x)*X4&*-kx}J zdpN09OWFA>%s-N2R#`GOf=}H0{hyhchqMHv=7UdljIPA?mgR-??L2Wi_DpMg+fVUX ztoY{UjyKNvYq}=ts1~t()LkFnt*=WP>FGZ)bobhKyJ$`JJl2IXksihtCHl_st<5P& zt_NqZfzU28S>37=l1=*5d}EIlLDOs@BWG-zN{D83?6LicCm-IF(9yT)4?8Cj%psz$ zfSF5HGkC!OL@05QNQC)tfrPW+BE9_zmw!SFnLHOQ6p5KHXyI}|w1CM2q5q-WZ@@7( z*UZXU{~jDf5@{AV;D$0S6L6TE3=9s3%S)JAa6grwVW+X3Ck`*b* z6^@=#6O&ZMXl3zg6__j>ZnMdi#tjUY0vgb#830%+l?+$}fIOBLg9A7)1WYi1A%Je! zfD_k?1q#BA0Sh)8pi3x#4?r~p$O{3zCG*m_0fE7izQ_UUhj<(q3?_@iV_~qxuT%g|SlSL2PY5kSlbJ;|YbLL-7dV zLE(YDsiJi4=@1l+<`iAafQyr#%8Fl%si>b9CU8-9_L%tHB80DEwy0k8doJQrvZ9}8 zpB@VIRrn=AtejXZx+oH>#bw4LiaoUf3PKi0k6~-B9ibcqd?@&lN za)#1^+!Q6Hj?+pDVXza(H?{LYCdrlmCMnHNxL;951c*ea`vV5{#@`IB)uWIG4*`-x#O$r}6h&Go6>+=R^xUT4%+Z!zuE)${&MEii9NhrW&S`Vo zII=&>d6(i(x9lqsWQ0W=4dbDcJs*!#e=4P4pnrX8qr8#AF zd~2ggeEliXaQw6LX+HJV-r;VVt|Mf|N`K~$^(UDhru@!XJnFjDtaJgF$Fe!9lI(Jd z8q>d3{^Gc;aJcci0%~u!#`%lZ<=2XXf9T&ivf%m2ZnxWaJ{=wIz1QcmTjNldsolzo z{pzS&2vqUGx@Us+arLr@lvaezt7X?50=L$A8+L;WtfezpWj-3| zR@iN9PJWLa)9dqwtr|lWtN7+b@*4lpvt1GT=boBR&xG#~3Eua9e|bI%weWEusYU(F zDGihn*^0}|zaML2opG<->;6DZgIy`7yX=$7D(7=x<${p~br<}Pt%E5AX7(`l%T&M1 z3r{G&G;~(;M1t}Tja_C4gO^=4e|XTcUGJnf?`v5jN4E0&QQz~SLC_jq)pa66-q1F} zZ;MdZ6_eH;n%u0AaQ%4i^WWW>@A`VmJN)XmU$whc(5CSIfcB+(cYof0dSUqlXZPeI zKQ`*^+vuBR_4M|1odx-uXhaL`VozkXsioZDi+77M9BQ6cw7$*Zvxp^w%bgR5dM!op zsWEzL&98?|-W0+QisQmM6v+{ZRpLHfW_rl zL4Bsal?e`m#bHPo91f46;;=tK1E7@fkI$saT%Nvn2rH29uJ7+|01%C-B;ade!eKB( zfX?uirXlNa5K2Wpf>5X?g)DDl3D}^%4Z{oSt896UKqk%@GGs8*?S=6`AEHGd;rcD8G%BEvh%kxES>}vBXeX}D%8wJ@f{hgcZ)5(yM|eoyCh!FeovsjF+f H#RmBwlCX^} literal 0 HcmV?d00001 diff --git a/doc/images/FactorGraph3.pdf b/doc/images/FactorGraph3.pdf new file mode 100644 index 0000000000000000000000000000000000000000..affa329b3922e0384aa2c1c6a0973fddca6e8a98 GIT binary patch literal 6281 zcmbVQ2|SeR_cun;*pjHO?QJ1NW?w}1wTo<}NE&9C5i`t;oh*eILPC^ftV!xxB1?5s zawV19rXshpm9@eU@_R=M(f$8_|Nr=md7tx~bDr~@_xqgXQM5EL+JRI%Va5FN^jYR=)AjKMPMD<{i835eKgUBKqkX`5`vX&N%$zqU+o-qG&od;TI z2k|09_D&qKE73mpRsVg@e`Z;vMnG*J6=41kLR*3yLmilA9X(bCzPQa z+r8_t#7Kwf3i}H)&$Q@OZ)QRgv**_AJ}T|ku=TT%%sV}U6OG*iTc@nPY#Yw6vcPtx zSM7{Q(cOB&O3?N<+k3CnF5RAbvghN-<+$F3S73{iN=(k_0Oj*=R zW=!N|^82e?`zThQ{F2jV6fSCA(yyappOZ#_J9@Pk2|P zta~PKNm+7BLS^sgeYOv&>6-cdqBY(*ZOsFvlRd4WGO-qh$w%wHBuSrAD2FN4)}QjN zfQfDtzi66NKWp*(m=QE`jsBsJ6ScRtHwxXo*EpPUXpls?Oo){`#y?WzJYd2x)KHB; zhf)3eQR|#3_Qe@1)yOYhw)?Vqw)GNIjH8~s>-Almh>^2_%@TFCPafc3<;TA&k7FZN zue}$!KEwXPFej~i1R2|zcUbsjUBLdH zq;OVkjogYYW01dYRfLmZiE+=N`T4t)HP&eu?!Lt=gO;u+safqP-{{Idbayzsr?$y< zupa|3%0f&eg4c^zHs`f_wB-%T?+Z{3V=-!WiJMF*rQFylWD@xnmN;kud?;&fln2*6 zIyzxJkr%MGPT`eDn>ZKLbV%rFr8P3V(i+w1RhE9d)-a(wXn#*xPE~TtP{88}GoU8u zaqkuWv=?QvSgAltKfs;(W4veWSgiG9TmrO5?Zs`G*P3#pFT|h&KzcKz#Yfow=5N2- zxzuj|BYGzPO?z%^WthwP3<(#XKkjeR@3%#_@Wrm(^Y`8jyIrLZjb&LJ( z2Yn@4k-x`C1$WZ!tLEVEj_{u;;InR!>M7<&r0rDle$|R=X^eI1@=*4EVf##xJty0=f!++e@=8ng$*x=0!3_1v^ z6l4mKbqu1;`k8e^iZ$aqfRBk zV1JFB^|rR3Iglg9durD6hR_=4Z2R3Sxf?GCaqdNOr!6%; zjcMJUvJWv)h$3ZoMF(|hdg%;k)hmc|Ia-C{t+%E|MsB5szPt6#T<5RZt5T1ylEc-c z3M4+Y?(AZ#?!qL;?tMfEJja6Q#a`*4%5D-sM^!2HapLc2$_i#(dJ2g?rdGY<L z>U5EWY*R?GM%w7J`0bw=sRM$N=?2c(BID(nYsMe4T3(&iOfs$R|1jQDA|fpipm#v7 zHA#0PGG0Avvx4s10cL)P<4G3$X3}_Z{f)Jcg!A>{9gwq|Z2BwAPK{STory}2ciJsk z{YRnIv6BV@G%w*g7g}3ej}tu_A_0Lo6DTN!8GV~#jt1r4O$|h~mq=$s9!+fDfydmS zqVxkHb$$W2WwhSL1iw+62yXDG=@adO&ITsza`LU}ka-9h4EWPSeV?{ZRee*|CyyzM z8S$yEbYC)!^etk8PrNA4i|xE$BnCr(eWPI(GJtJ>7a49zbR)yf$s{UKkM0jRAi!xH z5(VJZQI0UUHJt_K0{{VXF~~F)faWC&kW6OMeHboeCYVMn8FUvLGRpxDCK>>4>ItgT z1K_q~e-Gry~E$<-Q(f`MKH=i$~!1PsY@EBHu&5thjCc)rQ#5t(G3 zd*D_!dM0)URP@b3(Rqg%keMzFsuzpS0Fd*>&+lt~3iK$I!DQ)EhztOOfSVD&KO^CG zR1%BAbO6u5fvI%r^Gr_$WODVi>gN&PXl@o{GHz`%1fxZNL){458^lc3c%t23@n=W^y`o9~CRbMa` zi9&q07C_;7tIYqwzWsh5Fa7;L&12Mmp>3H4ES`5JzrQp9`E>*T_U?GI-~2Iu(7(&U zc{uwqSc(J#s;es*JnP`$c7TCyaG`s85*-&oV&Pmayypdc&LhHt=t*7+2JPr+eGHsbJkp zMgz$CB6!gzzXwh*zJ0BX7Z=9hqKl7<{`X26t&Z2y`cX2wkPZ`_50gkF=7cB;!&hb- zYJ&cfNc_C9rDL{kWO_E+{9>o(y-rQlf$MXUpJ_^yor!aGm-wLQ&3R}2PBV|{lC4|= zjbb9ADheYw1qC$`E;M&5SB7&|1l`%x$erfADls{4^||bG>GsyeMgN=u2LgXvU0i+I z{+zvSY6gGRb9L?NoXRa%Om5<}6|X2KgolTl>L-VXCx;7@q=Mda=Hjk%M1towILM=C zh8;##{I%ZJ<=yKVnWISz4G#>LW_)rOt+Slq{y98S+u4oO{+y%Now4Cp!&)az zheAr@qlRxpLc2E|ML(Hy9mb7RWlo&sKBPZ=dt*u=(0r)(OnVpJRK9U+Z2o) zL)V{=X5zawO6L5IK0?QL%9aidmCAKye%jvC8d_jMX| z8U*|4ms>4D0>9LaB5Ojr(hEb~hOa-kX;(X1G~3YC(i{BX?41b>>dxuymxMbQ2UUAN z1rXL*ynbDS$c|16hw$Y&73}AQv!4?qa!HC<637-%yfoPT05JltAs#BD#_&rwNUT&EATS=Cb+{ zwst-EG;o!zc(l~yP z1q@F)!2Hf0&)95nc09+S`o&n48eUs_j~i>$!XdK2-mU7Y_(w6e#zL*dd3WCSX6~%8Y}P1Q6=8YF(QW_b2Z|@8jz>LQ1D9-x zk&UoOUW4&Ib8nN1RAocn)z5JkLv>U`3jfkJ_|tK0^j)06EC1Nv6s#FSQtqC2bGH7` zsX)>E0+|fEX?S-l`a}Dbvf>yA?FQ9j<#rZC(S3azo(}%z>8`EauIQt{9w9{^{Zi~E za;D~k`3k{Lse4LgwNA?Livkg&7cSa;QRutoFJna^i?k)IIo922Y%&?GH`||u3%Ft% z{iG1uC^gU^DNR#ddtJb)H@D=OnvgN~#x!Fq-a=Rl3(?U3(=`iD!%6t?!3z3BNy+gaGDbZ zZXvcElGsojr50A<#CSBOG__+Wg5R$VetkAbEM&dD%5V}T=J*TOZIwnAlp9>9FpI+v zRhnCdx#7Eq|js>+lzKS*ca z!me)*x=>d49wXlPPuS2&Mv+hU5%IMRO{YHfnvAlw)*m(!ubgVUW|^Up$+k5)hH|wM zyL)hMeMyVo(@#Bv%-ijnlAD`G@+L!eYef%JAlqh&%U@2=Tb(@3(wu~^c9HmHb+4S4 zw(J&*KJp>IN~B8EzbHf!A!;)!Jo7Z^M4?ii(=Bntp(l4cXssI#1ly2QkK-DU0MC!=baI$nX*wE zb<}TWxf;EBx7TZUP4#1$^e)+(A#&$y9bn5e3pOd{tLGpF z(30Hc5p8L<=M|E_O3TYDqJ@x#1+ZAK@<(8o$25?*IHt`H7sWJi@|Ss;fchWv@_cat zcZK`^6v393$cqZQ|2~4@FxW*A3=+s6ISb(v;OB!tAS=I?gSAcVDY7n2XsBj45|x} z2AC6B6tX9g1r9s_8@daX%nDEgbUi!(YhJCv1i+4o%;iUHfKzlhg&i!! z$_&jaIL|4oam;n5ngu9(%18R12xm^O5i%0=4`cg>o@Qq$vq%uqJAGy{w&bSCR-!v_%5u=s7@$pi0USyVdB0PMz< z4R)dsU{iucp%7>c7KyY689*TY>)gCBouN$frFt7x)#)l-Jz}WFK9|}bP z{r)ozgC&5C{m(QM5&?$PpJ`|`*t#sCA=R2KzzzZEZcvk{;hSuO+4b7Df@IVM&%a|Gf4w`7Z zIu3=$A@y|eIIN+rt`SNfgTkQ^7(5bzLZb|{{&x;X-Zc!9MP#t%fdO``1el_t;T|K{ Fe*knat&9Kw literal 0 HcmV?d00001 diff --git a/doc/images/FactorGraph4.pdf b/doc/images/FactorGraph4.pdf new file mode 100644 index 0000000000000000000000000000000000000000..cba5ad2a3e5b4d00344da4a968241e42ccc368e2 GIT binary patch literal 4294 zcmb_g30M=?7EXvloKgiU7Pn-iP;n!BLKM*u#08=l6h*WeU`PTXgUPT6q6kQV5my9v zWD^w;tqYVsH(a5hLbWPreTr49SX&nc8Yu5h2q@5gukZU__!#D%d+)jbJ@@?Q{=w15 z!*deHnFl#uZQhgz31Bvi28Keet}JgvtHe~W5Lo0aPqhX^bTG?PqreakBnS;g+}t2N zrb86rP|ThOi)H92k>xA@bM9ALt(N4SE!8I88VKEbWhNdvHQX)snt4QhUPoIY-~N!l z-M|<3&8gqO+4c{ceD;*BIXU=WksS})U6CiArHdV^peBG$QdmD;z3Kl_|80HmT>ZU`<8nrGvO-^`<~Kc zytYc3{gdXVUbW6yA(n<7H}gAmq2(SMO0&8jkP^mFzP&J1b$J!qdEok4G5d#UHKqEf zcDspFrd|I$E;{eg;nR}uXDR10YlPTOr!7mKPFLH+c(-7jb7xwgrQG~>M8oSM<}dKi zxd&}RUyMDp1hZ4Ufm8g(HBOoQ7#O~P)GZ!ktP|rx${*KVeNldYpJ3L$A2Tnucbcnf zZmik-Ta~18gzEc8^_t&n{1mwc`TMLuNkg()Eqt0uP4W!>99~p={xsixYCy3It!!(U z>csH%9`s*#K1!d-ENIfj{Rk_Zrw>27YICJsfmN0yFWT|Rsk*b5%qRbmLoeM_IDO}$ z!Eqa0V#7W=vs#~U^TbKBv|oq3TAAvvsaR>P78o2WEq+r}oo{if8*=Q6Vf4Dt#Dp_V zO9D?A2AN;5w%p2VUc4bb(mOEz%IdI_tJ`CfTX`M)yP^y zHS-r};_}bxlVg`Qr+JSa`EFHgQ(@K4Z?kf&%}~a}Cg$!YRpuWTYkrc1>K87YcjT7z zm~Q#>RT}d|+0~%zYtkIqTaElc;j?`6o0+GMIatL_kc_<~y*A>Eo1>K8^mCP?aNA&d zN^QPf*?>C}|7e;#{=}cR#y?WOHP5;*(S5|loB5|}E1=4!yz=t&1AfbL7+DjLOu}Au z*RRgOdSaSO(%pcJ8T{K%sPjF1os)M}d|9b!7{ALQalS5P0%M9K#zlK$X!6Nx25ph1 zWbN&TO*z`H>~DIB))#&Cq;XUF?=K%uTeBeb`ewIcmn)6iLUrrnpZd{SM=TZ9Axt}mLHu6rbSnoFSAzRv-Y>6cwDpps{p*0{Y zGT7CdmmEl%GTLr;(oMfJnWIW-X0RL`T=B1Vwd7?x1Xho!V!!eavi3d>7tCN^_K4<& zWvE$+v+eCf%DZpx&c1MQ<;YN!=+6@jpP6iS38LxR-` zcQghLV1sTUhYO3u++`3;j$)vY!E7)}hiEaFM^-stM)YW;E(pGA_gBTEX}z_T7EOR5|KCKFC_NLPsk z-T+Y8h*S@=ywt&ZH~=E|A%~X1z(XYI@}sGoo~fppQU#{apvrC+J*%6R67?Sc0X4*$ z=OcqTZf>T5#!Z;&zFY*6^W+~88+X;+%V9$tGL~|d+y!#!Gmz{s4RlxN5i%yM`4X>L zzOo5YnOwvo4IYR-NT-g#P#w%6HzYUi#n=Ubdq$_nq$-6D=8IY03e&rQ!&;;c##H(M zSRfR4|B}a`1vimes|4LziB_-fY5PV7Vq_AK0S4Rbjy;LDFFvouvia_EfKN7?!|sbv z{PzGkY?luRIb3!RM6Q@z2K+$AXV<&&DG-sl*8}n&f;L9UgxZ+dy`yM^JXaBp^oz7R zNPLj@lelbHz~RF}A%7Wpfh+YeA7V-LL1f|sBgj=n#4JRuRGFIO36XtZBE*^vGE5yL z(JD27E)dHXL&E)FkqBbR)OtM#z42gRo(t&)oEu<_6ARTMEKH?Cz%v>hX9NfY1j2&> zir$&^5ox<5#>WZ+toHFSO1mYAKqz!`>(L(631+uCsFVR_6e^WEkW4f3#i4a1wRMzP z>u4Gt-I~=laUgCF(k2`1N-qTvydq)d_ld8E@) zC=?o($DvR@qYS0k7y(i&C{a|1y10{?@RBmP(@eaQg8!Rne*e6bTK%3#YNoYj5OZwR z=BbhEeAcW>TJMI(<8*_!`Mc*wi>_AOzH+k)e?ccc9dp|-)Lu=;%;Plt$rcUO|Jj0Ys!+JyFxc8I* zXbX)fBp%z|ySNZGSV=?X2l2A5D3}!)Sx4~w^kRLU21R27C%v6Zd`d81K7W1B>z=_Z zkMZvK@gMPP^al171I<7aE}WvyjX88UC$H#W^nOhS<7nBBj?Zf;Oy zS(HKzpD>^Sq8!UXMcXVb8+KcMN}*&!ud2y<(ECOqiT+PG*1uYGvkcHwz!kwl@n5k_ z+?!=&vxj9I&fl?2+?QoM-bXCcuwr^~%XrazsCAr=wEX|TEp{(%y{20I+08ABt`gaY zT?wuEZF5ZQI@B6uLx`*i?hwMci(TFU|0i~l#koJf%rr3+ij3kwoUR@*e&4fyson0r#%N=8z8LOLEpPuPy{`ffvF5+gO*VAGzO znvj-^#|@X4sVa^X^+`+8PA|^PsCH#rGFit%7~p4;}e9_!|~#s`5QKG-bbeI zloYVcjwgiT$&Os=!DqzvXEfq5QE9uSFz;C%z8TNQ_pd=yqII~Q9+wq!Ah&q$iE}(;*jk3JcHwp{PX9t~u+^>Gj%RG!n30*mEO}pBP=eF<9Zj6CiJcW?&g9R-_n_v1zM1CiTShwD~`EjtrkR$E%PWg{ayq%`;{PJeTWuq_}lC#HR!oW=}= zXX?XndT?BEN$!^1tTN`{$lSJRxrPH-Sv!mzISl>K&5?pFmX;Js?z+%;^grr34GgmC=zpj7} z&auxpAWHh$xSam$^4PqOuwXg`xX^Xr{{%40R~?Ihn8H9*qd>2cH$2eG+7J{rN#ofb zaDc1WQ_Obv5X=yI3M66|jzq}ey8u1TV@o}R5`k3g_TNV=Bc-q&Q|K_`LGoOH_;+-i IG0zkF50`^M!T> +stream +xœÍ˜ÏŠ$7 ÆïõuLQlKþw „œgg ° a&°ä×ì²,¹«Yº‡Þ!»,ßÈ®Ÿ¿’,Õ~ÝøÝµ¿ãçç·íçOyÿòÏöu 1aÙ“‹JÙߦâK"ð~Ýb‰R¸¢Èª×íÏí÷ýï ¶?û¿›ßÿâ¿mµ$@ç÷€!Cʼ¿(1G¶ú>]QdÕëiŸ×íysW÷?¯}>=óíÊ3Ÿob}>íë^ßâúö½K‚ šBNP‹ÑNÁ9(aøõ…߸並Ÿßö_^8J^þØŽ ñ{%H…Ê‚‡êËþò¶ýð“ƒøãË_Û¯/ÛÓæ)UˆÕRMÅ` ÍpMEÁn…òÄ VÒ唨d„š-ÑT ÑÐ ÑTÞATPŕȸB*`˜TQ&Ñ”I•û™B (9/L^‰R­d ÑT ÑÐ ÑTÞA”`Y]òÆ%t)Z—TQ&Ñ”I•û™Ðä´º”ˆ²‡l]RÅ ÍMåDä äÕ¥`]*ùââQÅ0 Í0MåL%B¢• '…ìøš0Dª(‘hJ¤ÊýDx“D+‘q‰RŽà¬Kª¦¡¦©¼ƒ‰¯Úˆ+M¢èÚg]RE‰D3-j*÷E^ââ‘qi6ž­_ ¿jU–V7£bH +-Q·2¾–‚çšæahç­×Ÿ‘V h‘†² ͨ‰d¢îõ ù"o ø4 9ì½T¡D±P%P6êæÅAF~iĹÞÖu˜Dü+@k“( ÑŒšD&êæ7硤Py-lN§i`2 +Ìn™†²0ͨÉd¢îv‰áÐÓÅ40ÇM¾Š X—D±D%D6ê^—"çwNé4 L¦Dž›eÊÂ4£&“‰º×¥˜</¦ÿëGÆŸïüT}‚ÏPú×THàÂYн®}¾µÏ+™ÖÉB±3—V¬tN[ÃOßùÓò`#gÀ<Õ +ÜêD±Ÿäxħ`>?Èy‚@c°Äæ‹ÞJèjïËöDzîÄãF\œàQe® ”Í^”ù·).{©c²—*ºŸ¯r¥˜(O¥r³†[ÏFÓ(Y§Q<íö<"Ríô%ƒFˆ¦Q²N£xÚ‰€d¢ØS¦ëE”h%ë4ªÕžÛ?=ðe>Òµï]_röÈ­&¡=>÷ýöù§Ç×M£sqž×qTÌ\Y¢D9ßvçÏÍÐ^|EðÔ•±“£åø +ðg%ynBÔFšù’øW€¡+ÃD£„öU³¬â~ÍO%º€¥Ï·ä=a殤61NAÅ(X9«b0«°òÍQÑlŒ•Úÿ|è³±bO<åÃz™êŒ2ÎiV /¸AŒaNüÂZzq¿O%/}ÿ˜kq¤Ô¯´G^TP<çð޶i‰píðÓ¢+Až¯å²¥N¢µƒœ ÇP+µ#Í|FÏø1kÊ£wÇ@7«bºený•Ì"ç8é¼)ÉPË(R‡à|WrO¹#›Â©šÓ|1V‘›NWÉk—±æ~‹ëÓµpÖ›œA+GÎi•à +]t˜¥e,~jm©ç’I—ïåCkë‘=þ‘½ôƒŠ‹2uß´º(3Vµ Æ\3Dm»\ÇQ¹t»l”(Rq”s·A+nî4Kƒ2vc´žæKš½išhî9ÚUɹ'UH±¬ÅM1Å=›•(Ú¬Æ"MrÙv–> +/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 0000000000000000000000000000000000000000..a9adf2cedcd5b3179008a89a5a7680aad9107b55 GIT binary patch literal 4295 zcmb_gd010d79T5JNISR`wX|4YSq!u$@4f7aBs7qq2oXp!$|BI0&puSTI%v4 zA})2IiWI8`1Qe|zIt+-S<5m~23f2YDuhbRy1+6mLxi2h=ZD;12&-YL6J?Eb7o^#Ld zdtc7B?2|vG@w#$-RBw+in_!2QGD$PM_sUJNU+vzYHky+cMBY`k*t42v|~m z-6Lf$I?X@+*Fk~VPXgmwzG@q|PrB{G-N$!{uFmlDp--!`+YnFWo8+(wv4@{+D~Qke z=)lv@qXLHw{xV|arVncxYC<2uAB3AjyBdD_=^gp=mqg zyz}lY;3P>?I`99Z&HD41XPaBkr!IW_;Ar6^ShusGN# zSC5ie8$wMPNrv@{HNYT4q)toTe3_-@OMdCS}LaxdpCzsGP5 zo%zYCdBstAYTj;ir7l{-9j&pXg&Bgxs|#I2A`he+MjluD9{aEqlg)w6J9iX5v_i`a{Y_w|oyr$^-JoQwc zV>=A_LsX5)aZ$Caf{0~{*?GlL*W0mw6b|iTW-RWBllSvqX{;wddrOQ=Ji)EK7tD zT+I{3>C4>j&pQ_eXlE@O_x@o|Ldgmk;i!x$omZc{d-BQMIqkbW=J>W~Lkg6tpi!Oe zLjyk@oy_wZ^4??D`|*mzBd=wCTSodN#?Ajhxzl;c&wI}XbLVbj?S?moYcOs4F<;4!??ry8+JTklTC^TllZ*11TPq?jmRKCY*Pb=`0Ykc>i?SX&%hnbbPHNGS zaW!=X0k7p!aew_+>L{NKNyGIxb57yf2dBIl9`(aFZocxJ^=2l&(lNH`{&x?U4{yC0 z8Zc<6mu#nP)0z?A9z^0vTVR6z?3H zaAZPc`L3f?XI2FNw4!NqM{TTXTk$pKlBkpZl?<<%TdRz5)vJ_*xiw>SfU5cGnC;Z}BjPmG6=#}UXCvS4nk$@gw1&DlZgrXXQR#^Ji&yVDfA3~h zT64{N9Wl+-A6>AV`mUzb@!^vSm!^exWXa&fz@c{H!aGPrW8G70hn%; z*5A^#r_2(pnF3v9ERpyWJvyS<@cOh7+b%~R^7QUX8XvX)!}a-P)#-;5qP~4tzUZC0 z*4XUIRRJH@pC9epxyi>X(D%;T!JmE3IC+*iZBs?AhdAM&c1!A80^}04@r|3K{EDIS!l|p(_H~ARX!IGpI!Kg z%<__o&e$YxVOQbA*E>q)oR)7pG-F3X*Bf){5{A!tvN(6r$Ow6!*}A46dNajE4eq#e&3xr2*Oj_N!XW`g}eLR8RrLS-NIm)6meyLo<>BnfH%~9hXq^#*hgaYhLr5gZQoK%pI? zQOr&1agVmpjcPy{@DFl3Xouh^!eEDz7_|FpMlu96IB1o$wjNQmPqare9HTIkHLX`g zkMk;=!VG`|fhhai7WP;0JPHOJ6RUzynXJbW9aInWs)Y<%O#OlzbdQL&|_}DVVVZ6&;pQ~u%tmK9hVx`ICK=9FZxn|Cw)P`6m_2*tRRd= z9Apio30xZ=HWLa=0{={N=H@HE0AW!~P=z=Q~c zlsTENLR7YJd@33Xq&87gChgkqrdaF!FZv5f9X#17$hz0@yU9Ub9E zA8<;XW}6u#0dks67Q4hLWx7QqU`>-@CgeUsO_ws`Rk09dwVI|A6vSbR*(eL;j)9CM zX2vtDdOI;(?{GI>Uf z!xiwwEL<-TvrrV*vk>sH3`P#0E7a-uC+|EJVOU zIUq8?3kNeMm^okO$wK;=R#FSnDf_c{Ai9Z6CJ8XWhQKcig~0T6zYyswja{Ys&(WLB zbYWsPl}e(p>K$g#y&@I=W7=O~mJIqnH*F5mz^L?U5ZM3I%=|^b(_$G-IGH zF`LZPU_q&mssP2V{px=SSgjv$0Oef2L8!?B8V#;6}Nu-06 z!j#ztQ#OuHhYJj-D3!wz@>6*N3`-SbLUAg>6C3qBosKI)jBJ~|J6R?|*1d3BfuCFc zgH*an;1z?c!hJnL#(-YY_v#cqZ;SvAq|6Mu?SWN)=zXEN_CDjFKdbs+fQR(U0V$&2 zPLM)EKP&{mFoGgtR0R0o)%_XEEovo$RB~;!JZuc4or*&$jG8(bG)VgxDAJ;5Lz8gQ zPWLMz8|AVQHebMlrUa>hdQ>+hm<`3)a1xjYV57;jQ@B|IDKIjFumJ2~^Vmr5E(#|t zxT#NBH&X(sfMU6ggdj15iX~i*1m%NwtcBNPiNN^KUltYr5seE5iI>mu ze?KuIAY zUIc;)m0Uhw#6blLv51d^$-}}TB7|W8;lxVWe?O5-4`y}>BPn+>xFQjU5g4e9iD3L2 DRox8* literal 0 HcmV?d00001 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 +xUŽKÂ0 D÷=ÅœÀõ¯i²GªXvÅ‚E*½¿Dš$äÇ~3öŠ+˜DáQˆY1Zü©¥*¦A±4îè¸à .uàÝûVGý´ î[‰- U¬R ã")AœÜÙpÍèÏYpzÕWþ> +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 +xìÝYtUå¾÷ùuê­sv½uÎ[£FQ£.ê¦îê¦ê¢.ê¢î¾++}! !„BZEPƒô­ +¶ˆ6`‹""Ò =H¡‡Ð÷}ë¬gM¶¶{o·²"|sd¬¬f®9?k.VæoýŸÿEþS@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@P@ ðŒ„gàqè=á±ørxÂÏ^ðp|Ó?X‘7+ € +( € +( € +( € +4=…ð9¼âh <ÏÂcàyx!¾õ%ÿ:FÃP/MoŸÜ"P@P@P@P@¿¨‡ÙI>Mòn’W’ŒN2(vBÎB¡Wá x Þ…÷áC˜Sã%\ׄìhL„7a2üŪýEP@P@P@P i4$Y–ì>Îá^ÎaT6C³›ÉK)&¦x'Å|’d| 3`&|³~\¯áÊpÓ§q4î6¾6j¯¯[¡€ +( € +( € +( € +ÜØšC}_ðQoòR£ +™Ç y¼–ÃÛÙ|ŧ)¦'Ó±Ï\øÂð±:X K`)„R¢ÅÔ%Y `NÍ‹ïvóR+ € +( € +( € +( € +Ü[3ùl)di_ñq1ïóJ1£‹Ñœ +y-äByLÉåól¾ÎdnŠEI–&Y‘d ¬ƒïa=lˆ—u¬ÊbY.õ9,Îæ»æe³$‹•)ÂM- º·¯´Ï®€ +( € +( € +( €¶ÀÙæloÁ²R¾iɧe¼ÛŠWËSÊðž/æÕ"Þ*äÃ>ÏãëæfS—ɲ«B°“bcŠM)¶f°=ƒìLÒÁÖ,6æ²®€•ÍYÖœEÍYX”¾°¶›óØ™e× û€sïP@P@P@Pà \,aw)«Ë˜[δÖ|PÁÄÖ¼PÎÐ2ƶäåRÞ,æƒ">+L››G]+²X¢žÿ¤hH±#ÅÎLve³;›=Yìɦ!/]_´±ˆu%¬jɲVÔµ¢¾«ÊÙÐ’í%ì/ä¼¥A÷è÷iP@P@P@PàÁ¸Ò†Æ26T°° _UòQ[ÞªdB%#+ÕšñåL,criz°Øô"f²°€ey¬Íac6۲ؕÉî,öfs ‹Æls9Ç|öÒЂ--Y_ÎÚ +VV²´Šºv,¯fm;6·aW9GZXô`tîµ +( € +( € +( € +Ü-ÙQÉŠ*¾­âóv¼WÍkUŒmËðJžoë¼]Δ2¦•2«˜ïŠXZÈê6ä±5—]9ìÿ1ÿiÌãP>‡ +8ÔŒCÍÙªŒÊhhÍæJ¾oǪ,ëH] K»°²+ë;³µ{«8^jto^wŸUP@P@P@4 å¨bC5 «™Ñž:ðV5ªQÅè*&´eR%ïWði93ÂÀ±RêŠYÑœõÍØšÏ®Pù“ÃÑ,Žæp,—cymÆá"·àp1ÊØSÁ޶liφN¬íŠ®,íN]V<ÌÚžlêACvät™YЃvܹ¿ +( € +( € +( € +(p·nôàx% íYÑ9ù¢#ïwäõŽŒëÀ°ö<_ͫռSÅÔJ¾¨àÛr”Q_š"6…a_ì õ?¹Ïáx' 8UÀÉBŽ·àX GÊ8XÁ¾¶ìjÏö6ueÝC¬|„úžÔ=Jýc¬~œ ±­'ûÂ6tâªYÐÝ~ñ}>P@P@P@x°®Tr°šMaÄVG¾éħ5¼[ÃËÕ‰‘ß‘7:ð~5ŸVñuæµfq+KY_ÌÖ"vr €£yœÊåT>§›qº9§Š9QÊñV­àPû;°»††nl~ˆõ²ú1–=Îâ>,y’•ýø¾[ú°ó1÷äl‹‚¬cϽU@P@P@P@»*ð$ç*ÙÓ‘5˜_ÃW™Ú…7»0¾3ÃjÓ‰—:òf>¬æó*¾©dAëôœ_kJÙTLCû +9J€ò8–Î5ã\sΔrªœm8Ö–Ãí9PÞîìx„-½Øðkû²¢/KúQ÷+ú³ö6 ¡úpòQ.W›ÝÕ×ß'S@P@P@P@GàFwN¶£¡Ëj˜Ý…i]y¿¯we\†uæù^íÄÛ™ZÍ¡t% +X^κ–l-aW +9ZÀ™<Îå§S ó͹Ђs-9ÓšSm9Þž#54vcßÃììÅÖ'ØØµX9€¥ÏP÷ ˲¦–µ4 d_Ž÷ãB7ƒ çèsOP@P@P@Pà® +\ëÀÑöléÄ’ÎÌêÂg]y·+¯tetFtæÅ^ïÄäŽ|\ÍWUÌ©¤.L_Îú2¶•²§Ez^°Ðè| +¸PÈÅ".s¾Œ3œªâDŽt¡±ûz²ëq¶õecÖÕ²rõÏQ÷õƒY=˜ CØö{j92sO²©»Jà“) € +( € +( € +( €†À•6é»6Ö°°3_wá㮼ݕ—º0² £:3¾†7:ñ^> ³‰U1¯’Ŭ*gC˜¾”}ÅiÎé.åq¹€Ë…\.âr a²³•œªæD'Žt£ñaöõb×lëÇÆgX7ˆ•ƒ©JÝ0ꇱj8†³u(»sè9NäêÃAÆÁç^* € +( € +( €÷Z`|ŸÀÛ0F³Ðzâ™é½~m|þßGàb%û;²®†ùùª S»ñfWÆwaxgFwæ¥&uâý|VÍ×U̯dI«ËÙXÆŽRös´ˆ3͸œÏ•f\)âJ1WJ¹Øšsm9Ý9ÒÆ0)Xov=ɶ§Ù8uƒY54Õ`é(Vbýh¶Œ`×PáÔs\yÌ·Ûïób»VP@P@Pà¸Ü‚ÓÙìÏaK«³X’bn’ð¼õc +4ž€‡ #´ƒªøg¸–¶FC÷ÁÁ“HD÷|¹×ŒÛ°¿ÓŸƒ é]˜ÒI]y1n46ÌVÃ[ø°ŸWóMßUR_ÁšÖljÅΖ(æXgã (”]iÁ•®”Öy®§:q¢+GJA{gg_¶õO·Z7„U¡hu£X:š•cù~[ưc$†qr—Ÿ$êct¯ Ÿ_P@P@¸áZ WZs¾Eº’aO!››±:¥YÌO13®z^…±0ž‚^ÐzÀÃq]Уð<DOÂ30FÇ÷¿xÜ…{ pÏ“¨xÖ&ó‰é‰Ä”DbR"ñb"14‘›H¼’H¼_9-‘˜•H,H$ê‰pç͉ĮD¢1‘8‘HœO$®þKâÚ¿%ÒAP)—[q±-gÛsª3Ç»säa{ý9Ú:ூ 1qô<[Ʊc4Frr—žæƒ {p,ú” +( € +( € +( À}$0€½¸Þ™+m9׊£¥ì-f[sÖ°,…Y|›â‹$&y#ÉóI†%äñ$&é !óéçBý!” Õ x.‹B +ôL‚÷áSøÊJ¡ûè¨yvåbû:²¶†y¹YôFW^èÂÐÎ„Š Wjx»S:ðE5³ªXPɲ +Ö•³¥ŒÝ¥4¶àx!çCw xhØ€ÿ¨ A—˹‚ œêÊñ‡8Ü“ÆÞìíÃŽ§¸­þcEP‚ÆñýO‚ üÐ׊ áèsP@P@P@ßAày¢Z~x‚k=¸Ü‘ó•kÍþ2¶—²¾Ë Y”Ïì¾Êbj&of2>ňµ)úfðD’¾IžŽ+Bòj„†Âð¸wÐ(½á½8úæÃbXiô;¼’®ò÷¹Mc5ë;ñ] _ufJ&uá…Î ­a\‚nÎßž/Úñm[¶aykÖµbk)»‹9Xĉåÿý{mè*‚.TÆA]â èQ<Ξ¾ìxš­Ù0ˆµC¹=Z5Žõ?A7+‚Bô´AÐïñj»NP@P@P྘LôÑtuÁõž\íÌÅ0QÚ°#îv»ª˜ÅEÌmÆ×y|šÃ»Ù¼’Ř,†dÑ?Å“)žJñL’A¡@F@ÆAH~ÆÇU@¯Àkq +ôNÜYh:̉S U°vÀã ûúøº?vîr5‡ªØÔ‘…˜QÃÔÞ¬IÏ?¬c;òJGÞîÈÔj¾¨âÛJV°¼œueé hO1‡Š8ÙŒ y\ɧÿŸjŒN\ APçÛp¶š“9ÖƒC=ÿ5ôgK‚žû1É¢QÔ!½À–±ìMãˆôаËý‰ÝÇ—{¡€ +( € +( € +Ü™DSˆ^#Mô,QontãR §:r¨šÝmÙÞ–³´”ùÅÌ,äóÞÏãõ\^ÈaxÏfÓ/‹™<›bp#’é–A/ƤCø:… 0ìÍxr±ÐS(”}O7&[ë2ؔŎldq"‹³9žÒÞ•Ý'¹#k¡Ÿs%[Ú³¸3;òq§twèñÞ‘1x¹ow`ÊmAвV¬mÉ–vq°é èrÞŸƒ Pt©çÚp&A5íΡGØß›ÝO’‚žMAk†²b8KGR7šecX3Ž Ï³u,»Fqh§‡rÕqawôRú P@P@Pà˜Gô)Ñ;Dˆ†=EôW»q¶+GkØ×míø¾2=ÂeAß”0­ˆ›ñV>/ç16—!9 Èæ™,e2$ Ë`l2]" 7þ2üù>„©ð1|ùc9Ðê$ë3Ù’KC{šs¸§Š¹Xµ–ÆAèñØôwûd)YŲv̪æÓö¼Ó—:0¢cÚór{ÞªfJ;¾¨äÛ +–³¬Œµ¥l)fW…Ïç\.óx:® +“ñ](KA§Úq¼Gºqðaö=Æ®>lšÍY?˜5ÃX>œ%q´|,kDZñy¶aÏ(Ž çì®?é5n¡ +( € +( € +(жÕ͈Ë^'K4(=.ìZO.ôàD7;³³#›ªY]É’ +æ–ñU)·àÝB&ðb>#ò¨Íå™e34‹‘)ƦŸLW…èí¸ø'ä?Sâðçø¾ˆS ™¡;P‹³X‘˺fl.¢¡„=e4¶æh%§Û¥G¥]ïàém8HÜ„¿8ßš=­YUÉœ¶LkÇ{Õ¼ZÍèjFV3¾ŠIU|PÉç|SžÎN—•²¶˜-Eì,ä@Gó9“Ëù<žúSíÓ£[p¾%g*8YÅñŽîJãÃìí•‚¶=Ŧ¬{ŽUCX6”ºbåÖcó8ưo$džs¾–½}§üÕ‹ä +( € +( € +( €?8@TO4—hQÜè‡Q\¯åj?.÷äL˜½¨{:³µ#ëªYÚÞV0«œi¥L)æíB^iƸ†æ30Á9 ËfTãB +”âÕdz Xæ õ?!ÿ Á¦ÅùÏ ˜žâ«Lfd1/‡Å¹,o–>MÞJ,*Ø]•nÃ{¤'ºr¶{¦[EV;üä…ó×& p0ôN¯`~¾¬äƒ*&V1®Šámy¡’×+™\Á'å|]ÆüR–³¦ˆMÍÙÑŒýùÉåtvzüc¿?Õ>5:q®gZrªuº×±î‡Øû(;ž`ëSlx†µƒX9˜ú!Ô ¥~8«F²~4[F±s$Ã95„KýÒ­Ý›‰› € +( € +( € +(дÖÇå@_}D4‰èEn çr-ûr¾gzö¢ÝØÑ…XUÍâ*æ¶aF9Ÿ¶äƒbÞ,â¥BFð\XòžË˜^Èâ¥L^K1)™NB!PHÂñ7# 0M|¨š³ÃÏLfæ2§€EÍYQĺ6—ÓPÉîöìïÌáïÉéÞœ’+Os#L‡4Ðóܦ},=x[wº8=Þ’rf´fj&UòB†V0®‚W[óN9•1½”9ÅÔ±²9šÑϾ\çp2+õý·Ú§F$Îrº„“­8^ÉÑj†Á˜ÝÙÝ“†ÞlîËú¬©eÅ –D@ßÄU@áïÿ›ÐÂ$uÔ…S€<–7gu<Äfs;¶wbWwö… êqŽöã䳜Âù‘\˵âyíCZ5ÑsÞûÿðü£ìáµ"¶RWÌ—¥|PÆëeŒ-cx)/”òz “‹ù´ˆ¯ ™WÀ’|Vç±)‡†,öeq$ʼnOükí“#'šq¬ˆ£% ²Ú°¯»:²½+›b}/ÖôaE_–>MÝ– dM˜D¬–mϰ{‡úsú)®t÷ñG9^~ývÞJ„î‹b¡ðÿøQOˆ€–d²8>–Æo0L¸.›Åás!΂Ò_ÄŸá«„_ç#P@¸ß~>á¹=úù{Þo.î +ü*ÝÑêT´ }•L {‹h‹ YVÂêÖ|_ŦpòÛ]°¯7ûrt'žãÌÎãÒx®¾Ê!šLºxÉ +4“ù¬-`Ns>iÁÛÅL(fx1c[ðJo1µ/ ˜—.~[‘Ã÷YlÍdWŠ)¦xü¿Ôöš8–Ç‘f3Ë—²¿»+i¨fK º±öaVö¢þqêú°´/+ŸfÝ6÷§¡ûŸäxŸtG÷¨³ïˆ&s4ü®r{(ôÌ…B…OüBž%,Êfa. ÒÅr‹‹XRÄÒ, ?›S׌º¼t"´(™‚£ÂW ! +£ŒW]W®€ +( @S¸•óüÍüë[Í‚þ&”W*ð  LFÛSѲT4;•6…è ¢ç‰õåRNõæP˜´è‘tMÂên,îÌœŽÌÓd·åƒ +ÞjÅ«¡æ¡#š3¤‘7Ëry5‡IY¼›É‡©t9ÐÉôˆ°›µ@! +_ï.Èà»læç3¯¹ÅÌ+aQ ËZ¥§^Z×]Øö0;co_öçh-'†qz çÆsñ5®¼Éõ0»}H>'šîÁƒ~7©ýß“Åò<¾*àÃ0•^!cã!“/6KO«÷^Ÿå13‡ùÙé!0«RlH±-ƒ]ìMÎæŸš8”Ãá<6ã@ ö´dG9Û*ÙÔžïkXÝ層'u½Xöxº:hÓl}‚=½9Ü‹3ݹVí{¡I wqcnÏ…îâÓÞÙS…<'| +„Z P R º|–„oZ°¢„•¥ñÒ’Uñ~]Qœ®­ÏM íƒBO¹ðQò¥YÐÑû(P@?¸À­çg²¿¾éÖ£~“½kûMÖãJPà^ +%Ú—mÊŒê2£oRÑgÉè}¢×â<Ïr­žàxoä‡P¼ô%Ñœx¹—ˆ>·!°-É¢>Ëáð^ÈcDcâ oå2%‡/²ÒÝѤÒ#bÖ$ÙÛ`'„ÕÞƒa¤Ø¾öç±·]¡u›[³¾-kÛ§Ge. oÀîÔ?̪žé‘b[z²ã!vçT —Û˜ýÅ«ðàþr{(ÔÄþT›ÏœPÞR ú–ç§{§¯*aMk[±®ß—³>Ô…†¥"½¬ ׳¶ˆ5¬ÌN÷ +qPøN!Ì>9Þ°4èÁ=ÐÝsPàøë´ç&ǯ½þ ‚î͇(ÐäŽ%£YÑÚ¬haV43}’ŒB¥ÍKéqa7r)ôgîÃÑP–ó(Ûa]–ueA ³:ðE;>ªLwÄ PÆ—¤Ç……A£ +x>Ÿ—òx-—7sx7‹3ù$Å´P”Lw‡¾Ù:´] õaP@Vú»à…ÍYPÂüV,hÃÒv¬ +ÓÓwec‰Ö›ýØû ÏqdÇÇrjg'rám.ÀµO¸¦¹ŸA4Ÿhiü³ÉáºA®@væ‡A‘™éº¸0}Þ,Æeñjïdòq*‹ÎaQü.X ëasõªMìJ²;Åîlvæ±½[Z°¡%k[³²-õí¨ëÀÒVvM¿7u£¡ û;q¼šK-M܃íìy“É…^‡0Yd¨ç AP}’åY¬ C)Ã4‘¡/\+6”³±5›+Ò3l©dKÛô²¹2„n,cc1š³¾ëòX™•S¾VYÐ;Â¥ àÍ +( € +Üw¿6ðù{÷¿ƒ ;@ó! +49#Ѷœhev´ 3š‘MMFo…VÌC¸ò,gûsüI>–ž½zóìéÁ’®Ì¯af¦U1¥’·Ëy­ŒJYÄðfér ñy¼šÇ¡"›²ø(ÅçñiïÌpæƒÂˆ€0Ìò°¤Xú¥ñ]KæU¤g"[Ò•Ó'¹{±µ;ú³·–Æ0/öhŽ¿È©W9ó&çßãÒG\Æ0Óý·D ‰ê‰Öz.Ðä.7(Ô-|¯'“dH’qI^Mò.|Dºwzèv +äB´,NÖÁCµ‰-°=,lÍfs +YÛ‚•-©oE]k–´aEUº:hc5 íØß–£­¸\èÁï±ö‹nÏ…~ñƒ~“;†c>,áã¬L±6—õ…l,MG=[Ú°5ÌÙ††°´eG;vT§†Ë l$[²µ˜-ÍÙÜŒõy¬ÊLˆ„oÂL”“àE³ ßär% +( €¿ìüÚëï` ‚î͇(д.LE›s¢åYÑüT4=}˜LÏÃ5–ëC¹PËÉî˾ÇièÉÆÐ¨¶u]™[ÃŒ|VÅ•¼UÎ+eŒ q‹þ³èõ\ÞÊá½,¦fñiŠ/Rér o“ÿ9(,œ„3ß•°:|)œÃÒ0ÑR Z³°K:±¢;ëaco¶öcÇ3ìL㎌åøKœzƒ3ïr~ +—>åêtnÌŠ –­ ZG´ÈÓá¦u|¹5A 43 E `< £âËoÂûq=Ch{†L†8(œ‡2¹Nµ‰ð¾Xka]8úå¦çš¯]s[°¤„¡:¨Uº@¢¡Œý¥é¶Ò"+pç·‡Báòïù/äŸÇå@!ù ÿó‡NéóÒÁÎÖÒtÔ³£’mÙÕ–=Uì K5{Û³/ü¬bOv·fW+v†{¶`{![ó٘Úð=Bœ} +¯Áh³ ßóåsÝ +( €MMà×>ïþw°_Aw€æChZWˆögEë³£úÌhn*š–ŒÞKFaB®Ñ\ƹП¹?}Ùõ8[zñýC,ïή̮az>©â½J&•óRcŠÚüÇî@q9ÐÛ9¼ʲâr ßd0'ùck x8ÌŠp.NuÃ9oP@}1uå,®bY'V… èQ6öaëÓì¨eïPGq䎿©·8û>ç?æÒ\ÉõÐ(”-Ë6m÷¤¸i_nÍ-ÐÉ$œ¨ÖB_ôc® MNÂüGŸÇAP(ª¬M„Þ)aìd¨š ¹PˆLëR,ÈJ7—®ËaY« ø¾€mìÎçH†ü-`/ü·çB¿Åún­c–‹Ã93ˆcý9ð$;{³ùQÖïþw°ƒAw€æChZ—“ÑîT´&Õ¥¢Yѧq§èñ\˹œ|ŽÃØÿ$;z³éQV?ÄÒîÌïÂÌNL«fJ[Þ®àµV¼Pšn4¢çãÉÂ^' ›œÅ”T<.,ƒ¯C›èÐ (ƒy!Êdahf~Éfy6«²YËŠæ,mI]–´gyV?Ì÷áû±ívfïÇqdÇ'rê]ÎNåüç\šÁÕo¹ñQ¶†h+QHö…IÐü§@“x:Â#qP(c‰P8ÕU™µ‰‰ñDHaìXH‡Þþ±Ž"œçÞœq¯Éï™xŸ +Üž ýÊ] ùÌKñ@ÈPºÂÌI¶fÒËîöµà@)‡Z¥sž£•«Jw>?Þ>þ.ß\Úr¼’ã+ãh1‡›s(Ÿ9ìÉdG<é^Xg\š…·Ì3fA¿òÕñî +( €P¿ìüÚëï`÷ÃSÜÁ£|ˆ +4!k!?‰ƒ E©hf2ú˜Ð)ú‡áÜ0N<ÇÁgØÓ—í½ÙØ“Uq§èyùº#ŸµãÃÐ ¨5¯–ñ|IÜ ¨/„r Þó"eñA˜/)ÌŸâË B›èÍù1Z”Åâl–äP" Ðó3åE,-cQ%K;¤§§_óß?Φ§Øö,;‡°wÏsä%Ž¿ÁÉÉœ AÐ4.}ÍÕÙqæ ݶ%£=ɨ1M6!^7E_ Píã (T +ýßµ‰§` ‡’…Ñ.¡^è¬Ã»(pn…~ÁŸ‚!ç Áf(u›÷¿Ú’d{»rÙÛŒÆ"—p´ŒcåœhÃɶœjÇéjN‡Ÿm9]É©[K¸µŒ“-8^ȱ|ŽfÓ˜bo’mñ:CQP(7 +5u/Àc¾eîâ±àS) € +Ü+¿ø„íùë›þúšf³ ‚þ=«@SØ™ŒVgD‹’Ñ×Éh*Ñ\‘Kc8‚ A‚¶õfý#¬ìÎâ.Ìí”îýiè݆7Ëy¹eºSô°æŒó…åòzofñn柃 0_Ø¢Dby"±æ¿K”þ—Úy™|—ŸÛÉ’\êC”Ÿn´¬˜%åÔU±4î½æQÖ÷as¶b×pöަñ޼œ‚NMæìG\˜Æå™\›Ã¡AÐÒd´6#ÚšJqkLEÇRMÖíPà×Ü<ŸND~ÃòkÔ¼oS¸=ú[Û3˜ôLy¡ª-´‰þ¶e°+“}¹4p¤ˆcÅœhÉÉVœ®àL%g«8WÅù¶œ¯ä\ÎU¤—³aiÍ™2δàt§r9‘ͱ ÂÎÐq(ž} Ì öy\MgQÐßz¼NPà~ø™lç'7ÝüõgÒ›Ÿ¹éoªýÚûÿÍ•x¥ +ÜcÝÉhU2}C:zk/rq4g†q<AýÙzõ<Ɔ‡XÙºÎÌéÈWÕéNÑïWÄ¢KãNÑ…éNÑr˜˜H¼›HLM$¦%3‰¹‰D˜/,LÜbPbN&ÿV;?—y,̧®€%¡5P!Ë›³¬„Å­©«¦¾3+bmxº¾l~†íƒÙ5’}ã88#¯qü-N½Ïٹ𗿠APò‡ï2¢¥¡¢)3ÚœíÎŽ³£©èª÷ø˜òéï@À èÐ|H“¸=ºyLGÑðx޼0;^˜äklÏ`O9ÉçD!'‹8]Ì™–œ+ç|.Tr± —ÂRÁÅÖñRÎÅr.”q¾”ó-8WÀÙÎdr*ÉØ[â©BÊ4#î¾&æ+·(¨Én +( Ào,p3Þù{+½yëí?ÿÞ=o^ÿ«²_uçŸ^oU@{&°he‚ˆfM!z«/ra4§†qt!êÃöGÙЃ•]©«aN¦‡ ¨’÷*x£Œ ‰ÄèDbX"16‘x)‘x#Å;|ä£$Ÿ%ÓÝnC¹~èmR<(:EÏË¢úOµ òYØŒEÍY\Ä’éùÂêãA‹ÛSß…•°öq6<Å–giÊî1ì{‘ƒ/sdÇßåôÎ}ÊÅé\™ÅõÐ)zAF´,­ËŒ¶fG»s¢C¹Ñ©Ì蚣ÃîÙÑäß±ÀÍ“f+‚îÐ6EpX'£‰)‰ÄîDâfÔdo&‡r8žÏ©fœiÎÙ"Η¤£žK­¹\Á•Ö\)—V\)‹—R.—p© ¹˜Ï…lÎepŽÂþ,Å…F7§ £ÃB¯­>AMñhp›P@~K›!ÏϬñ—§@7WòËã_~ÏŸÙ;ÞæeÉô”g›²£†Üh_At¸0:“]±"èo¾Ì^Ù¤ ‚šôËãÆý£ã èX÷ó <ûàÊ¿$®ÿ÷‰ÿšˆþ”ˆþÇÄ•ÂtÔs½˜ë%éð'D@7ÂRÊðk¸²ˆk…\Ïçz.ײ¹šÁ%þ"Ú+a^þìêŶlmœ;¦û9Ï®bz>.grK_ÄÈfŒÈKA/gz½A¡>?L|khX«¿ +‚æ·à»úü¯µ ËYTÁâv,‹ƒ µ¡Q¶ô§a»‡³olÜ)úuN„ è}ÎÄåi\£ØBTGºÍõúÌh[h”5DÇ £³9wჸ—A÷Rßçþ†ÀÛðE<}|¨ÛÙ »Â018Wõ„Úž«Ét¼Bžõ„Ìç‡ODÿ‘ˆþ[âÙÿ¨½Êâ (”] ·fq#ɵۂ Ð#( »Y‚ /áƒÑzýÎ/««W@¸~>êùù[ïcwM?ªÀObŸ['Ÿ7÷'¤+!šÀõQ\ÆéA@ã“ìAPw6Ô°¢‹Ú1»’é|ÜŠÉ¥L,f|sF0<±9LÈâõo'ù>ŠKôÃßäá[à’ÚÄœ ¬assAó⊠tTÊ‚2žþßj¶aI;–×°ªëz±ñI¶ á9öŒàÀ8Oàøëœz‹sïqé#®}Î_Í Ç­%Ú”Š²¢=¡St^t² :›ùG}uÜîXàÖ{ÑŠ ø(¸ow} ¼ŸÆ,‹;‡Ña7‹‚NÂ9¸ 7à‡Œ³ PüÓœgÿkíÀ‘‰] Ýšs­ ¥Ç…¥¸”â\òϳ†Ý +‚VÄAáÛ‡0U}‚6ºo(wLPànüLÚó37Ý-ó9Pà +ü$ùùùûO‹{½Ìù4˜39öO°§'Û»²±#+«©«bNÓËù¸ŒÉ%L,b|a:–ǘlÆgòzFú›ß›m‚Ÿýá+àÐ&¨¸61;ÉìLæä0'Ÿ¹…Ì+b^ óZ2¿ßU0𯭯fEgÖ<ÄúÇØÔ—­Ï°cp:jÇ‘—81‘³osñ=®NåÆgD_ßlDô=ÑæŒ¨!íËŠŽäD§ó¢#Îÿó/³·6Eƒ ¦øª¸M¿‘@_˜÷Ž ß ÔÅc¸BO( + +£ºŽ†bp!dAÉtçŸëaØWV:ðð¯µéá`-è?<R Ëq›è+y\ÉIOv6‹“™Kq(ɾ$a² "¦Ð#(|ûð^<4Ì è7zõ\ +( Àƒ+ð÷Ÿ¿wýƒ+åž+po~ûÜ:·üå[7‹Ž†s¥–³8Þ—ƒ±çaº²©=«ªX\ÉÜÖ|UÆ'¥¼×‚‰…Œ/`T.ó›bB2ýµï[09îF‡Ýœ8,Aß&ù6“Ù9ÌÎgN!sZ0·”yeÌkͼ6,ª¢öÿ¨ ³’­}˜õ½ÙÜíÙ9„}#9ø¨½2Ÿf\nNß¡‰K͹ԌK\Êã|grÒÓÍâPRìN±%ƒ5I–$™脊 áðA¿ÑËçjP@d¿™ùüÍ+d%÷]»-ð“äç7yú׉Fqcúqâ öbïC4tfS;ÖT²¤‚y­˜Qʧżל7 +˜Çè,†§›LçûLŠÿà¿}tX‚f%™•É·q4»Ù-˜Sœ2æ´fn%ua\XjÿÏÚu°áq¶$q®9ç Ó—Ïpª€ãyÉå`û³Ù“EC&S¬L²(|ÊÄó„ϠЕ¨›AÐ]{}"P@ûZà¯cŸ¿¾æ¾pç¸×?‰}n:þæÛ5†h—ûp¦GaowjÒAÐÚ +ê˙ߒ™Å|VÄLÊã¥F§–L÷dx^‰qQP(ο9wXÖ¢613É7)¾ÉfV.³ +ø¶9ßómKf—§+‚W±²=k»PûÕÖþ?µÛû²óö>G㎌ãÄμÎÅ7¹2™«smzzîø‹Â”aqEÐ6¢}DG‰Î8YØo~(¸Â»$pëÝlEÐ]÷iî®Àã0.´Š‚æC=¬‹§ Äö'9˜âp&=µÇr8‘Ë©¼tà–Óô”8՜Ӆœ*äD!G›q¨€yìÍeW YlÊbMŠú$ß%Ó-馯CµÐÑ èî¾Ä>› +( À},ð“äç'¿ÞÇ;î®)poÂÉáíËÝ܈Z¢G¸ðÇâ@vv`S[Ö•S_–žêë›"¦òaoÆ3…… hH2=Apø;ÿVQP(οU‚ If¤˜‘Í×¹|ÏÌBfñM ³Â +[³´’ÕíXWÃÆlíEíÿ[»§?qxÇÇpz<ç_åÒ¤tEP‚®OOÏÿC˜;þfEÐö8²5ÐÝ<<|®ßZÀ è·u}MK }\ôj7/ßÛ­êÇõÎÖp¨»«ÙZÁº2–•° ˆY…L+`J 1 †aqˆðøKñ1oÞÖ)¨¨6ñe’/SLÏbz.ÓóùªE|]’. +ZØŠe¬­bCG6wc{Ov=NíÿW{ðYŽåähξÀ……Š 04ì£ôаè›xhX¨ +CÃBEÐDßÛcÅgÿg ‚þYAßäzÇŸaÜV˜S2”î,€å¡.(I«Díö;²Ò>{B©OûBÚ/û ©©M46ç@û‹ØÛœÝ…ì(`[[òXŸËêê³X˜bN’™ñšCŸºq +>’š<‰¨€ +( ÀIàVþsëÂiëÝVšŽÀO’Ÿ¦³a·mɵJNUr ‚íå¬/ee‹B‡Ÿ¾Ècj6oeýÿì½w˜T×{çyŸý޵ǞqXÿÖžŸg=öxÆcïÚÞݙǻÞï­êêêÜ4MhrÎB  B!@”…2( !!²P@B$‘£È9gº›ÎáÝï=W]*»›êê[Uo«T]uëÞs>çœ{Ïùž7`f3lWzÊÄ礃؋F b° jAÜœMw,F^Èž,NÃ’t,ÍÄgÙX–‡Ï)¨kÛcsvvÁž^Ø?‡‡âÄHœ ç_+OãÆ³(yeo b6ª?Dí§f7cŒ µÆ5l'cAÎé„?ªÍôeP!(M‹Ü4Ýzlу˜™%ÀÕm¾2-gk»BØÂþ0eâp6Žäâ(Ÿ<ÉÇÑ|tw,þËׇóq0?æ`o6vfaK&6„±&„o‚øÂÆbóÄáùy•‡TjZãèÑJ@ (% EÀ“€Tj,=H xn‘}" ?ßó©-ÀÕBœl‹ýùØ–ƒuÙX‘‰ea|Âû¼n»a‚&˜™«å-(èXžØ¼æ§aA:e`q–æ¸Þa« +°ŽúRì쌽=q€nhá䜃KO€J¦¡üTÍDí[¨¬aK!_C¾oÈæ{€Z@%p_‘ûƺ/+= q 6aœi5Ê=ï‘ø­uAl +aK:¶g`W&öd»RÏþ\÷÷Ç|ìËGÇò^ìÍÇž\ìÌÅÖllÊÆºL¬ãë–±Èv‘¹As Ç€'UJÜ^¢%WJ@ (  +Ä—QK§Z•€7ÍüÛªeyð‹_ËpÃ2ìÎÂÆ0¾MÇç!,‚¡i‡ï AŒÉð„± ºÅGÌv,Îù9Eÿ(€¹i®Ѽ ÌÏÂ" +Ayø¶ ַŶvØS„ýÝݨÔ'ãÌ0\…+ãP<¿º!¯A(̓|Ya,‚6ª!Ѓ7¬žÁ"S‚|ÑZˆ–!À¸=ÀÉFúvA6–1¶O«CX›ŽõalÊÄæll£Á|väa{>ò‹ÿòw[¶æb“ÙX“U™n&Êe!, b®·ÍÈÐxó¢ej gUJ@ (% ÅV… íJà6É¢üÜV19ÂqÛÓÜIûr³Ë™<… çŒ-7aùËøD3϶!vô¿:ççôx߯jAA|’†Oé –¯³°&›ò°«ûÛãpgï‰Óýq~.?‚ëcPú*ŸBõ4W’™ÙEc}£*ÐíM¤ï$$èg© +A Ù„ZèFðžLï>xÏÆ'&|Ü!|ŽUa¬ÎÄwY®Ýé +>üÍdž|„‹ÿòwñM^“‹•9nöÉ/èeÆ‚> ¸žÈôJ¦m*·$hÔèâèJ@ (% ”@“ ¨Ôddú%øöÝŸÌÏ²ØÆ\“,ž¢½é7w{G³|Îó™GŒÑ¿8sÊS/zÛÆìÞ§… FNÇŠ0Ö1ÚgöåàpŽwÄ©n8×—âÚÃ(‰²ÇQA!h*jŸ3ZÐ;Fb˜ ýQID@… $jL­Ê½x]}ÀÀÑ +Géæí> º^ËéáÆ—™Xžé†¡£Ô³*«óÝßÿϱ¾¥q>V0UAž›t’é–dc¡ U÷AoÙî©hhÄîAÜ«ú™PJ@ (%ðÀTz`„z%¨¶KMDhçä œû°›ß‘Q¦AtûïŽE¥ˆiå)½̦˜|Iw€4lLÇ®0fàhN¶ÃÙN¸ØW™­l0ʇ¡j4jÆ£îiÔO‡¼l´ D¦åVw% BÐ]ÑèID ºŸs¿€rݸSî5ïrƒ „yéXÆ¢LDŽ ˜\’²O>þ/Çâ‹Ïr±” +s± Ÿ2me&>cVoR#šgãã&‰˜iU”€PJ@ ø‘€ +A~l-“ˆ/Æÿ¡ÈÃÑ D‹ ~À 9ˆÒÐß9Vt61ÉÜÁÁMïò5ð=@AéÇ€›8ødδÁ…¸ÚÅ=QÞÕCPûêÆ@ž€<ûÓÜ>z)ߊêÕ”@KˆîÕêÖR”õ¼­G€=<º“{á6Ÿüå‹—l¼À;ix?†ñQ&æfã“|š‹ùæ÷¿8ÿü8eãƒl¼›‰·Ãx=„—ÒVòÄhut7k½Zê••€PJ@ ¤ +‚R¥¥µžJ èÆ^ª@Ý€ÞÀ“À÷¯‹oŽ3ù|i5ĽZ1²ÐBà+“;x+… àHNfà\®´AI;TtBMwÔõ†ô½Ã¬þöE#J§‡(ÿˆîÒ*ù·´dÍ"ݽo9 xSŽvAü¥’óœí +;¯…ðfoebŸl¼gþýµcñÏ·³ðf&^ÏÀ+a¼ÂŒ ¦Ø®2Ÿ,´8e2²[ί*% ”€P-A@… – ªçTÉA è üGXM𯑦iÐt/@(0øXlv‡ÓÀåJÓPºÿdž+‹{,.’ Ö"uDwf‚R§ÝS¡¦Ñ}ûnõex†wfX9/ÑÀ4Óƒx!/…]ÁÇýÍÀ8ÖK™x!Ï…1=„©i˜Ät +GFb>‚»\ßWJ@ (% bN@… ˜#Õ*$#Т«ÚÆ,1’Œ§V') D÷ä2IIO+åOìÕÑûÞ…üØØó0¹C=Ó‡¿SmL ¸jÏ”¦¤ã7krSC˜–æÊD/0Óvs0YMLï}rýT (% ”€ˆ-‚bËSϦ’@K¯j¿ÐH>¶Z£¤!Ý[zÈ$ 4­ˆŸ Dw鯗“.ÃÌ&@y‡¡~èçŘrî¯Wƒø#Ç⿯ñFÀÍö.ðq1nüÉõH% ”€PJ VTŠI=HVqXÕ6oÅ‘¬Àµ^‰H ºÇaÈ$""-sˆîÏÍ+ör`.0xÏ>|ñ_‹ïÌKŒgqóάßRJ@ (% œ€ +AÎPÏ ’›@|Vµ¾îHîVÐÚùœ@tŽÏñ9-^‚`OŽî̱­…ØòÔ³)% ”€h6‚šN¿¨R@<çí-·úH…–Ò:¶.èÞÏQÓºµÖ«'ènÜUÓ¡ÑTõœJ@ (% šA@… f@Ó¯(Ô!çy;—!-½I¶ÓšÆ“@t¿ó¨‰g5õZÉJ >÷^ÉÚ´^J@ (%pTJ¸&Ó+xh•y{ôš:ž•Õk)渥Ƕʨi^Éõ[J€néÀ-ÇD‡F˱Õ3+% ”€h‚š„KV©F µæíq[˜¤Zƒj}[‚À-ݵµFMKTMÏ™ôné½-Z_-ŠWO®”€PJ ñTj<+=R ¤ Vœ·Çsy’‚-«UŽ![új+ŽšVJO•ôØooéºq¨²ŽŽ8@ÖK(% ”€¸/‚î‹HP©L u'íñ_¤¤r[kÝ›Mà–ŽÚº£¦ÙµÐ/¦[:mÜꮣ#n¨õBJ@ (% îA@… {ÀÑ”@ŠðÃŒ½µV+)ÞôZý&¸¥—úaà4©üzpª¸¥ÇƳú::âI[¯¥”€PJànTº}_ (ŸÌعfiÅe‹v%p_·ôOŸ œû[HA­~;ÕÑ‘‚½N«¬”€P>$ B¥UŠ´øøx˜ L&c€¡@ UФmu¾š±ß²Önu8Z%!pKçôÕÀ‰R_([:j«ÑÑÑ*Øõ¢J@ (% n! BÐ-@’þÏò®(oƒë¹¸˜‰Ói8Änm¬´±ÔÆ\ï/S À(à! 7ÐÈr  ÐŒU(Ù»‹ßfì~XÅ${›kýb@Ào'UÒS$>ŸÜ?ut$~WÒ(% ”@2P!(Zñ¾u‹ºá¨ë‡ºÎ¨l²|\ÏÂÅ0N¦á@ÛXgãk‹m̱ñ&ð"0x zŒDˆ/øç `0˜ ¼÷+ TºoC$Ú>œ±ûd-“h-©å+œ¸Ö_/æ3¼múêΩÄgD‹£”€P©H@… ¤mõ÷ 3!Ó!!£ C ½P_„êB”¶Á¥<œÊÆáLìcSßñE (U‡Úê<ÃñOW ÐƘQê 5J ‡h>4 øX|¬¶ûUJŠŽåÏ麯V4IÑÎZ‰ðçÀ‰q%õt BÀ‡7L Òw´˜J@ (%ÌTJ¶Ö]ù2ò.äUÈ4ÈÈ£ BP'T¢˜BPNgâ`;Ò±!„UA, `¾÷7€ç€IÀãÀÃF¢/X!ÐÖÈAžE… z= L^i‚–+€ ÀNà@'B¸BqºÆJà.æÛéºß6¸¸µè-@À·§ꪧô/ßÞ'u€ø·ÓhÉ”€PJ e¨”‡UJ˜—su?/v¦¥µ ±&c'Ö•Öóùˆ€ÏoŒ:@âÑW|Þ â@¯¡”€P÷" Bнè$Äg—ÓädšÊ[ÖA¾†,‚̼y222µƒQÙ7»áFG\iƒsÙ8š‰½Ø’ŽïÓ°ÂXQÌyÏ;‹ /w|g =PdT îÀ;ˆŽcO'2ZÑŽhð%°Ø 7 Ù¡‚r\Ñ©¬UPÛÒ2 òä)•ƒ o%Ê\]g» ЙR¬ˆ‰2vR¬YR¢º¼úÿ–¨$N}Ñÿ]!N ô2J@ (%p*ÝJ¢¼U–›!¹’!Ù”íï!Ë! !!èyÈÓÇ!ÃQ;}PÒ×:âRÎfã… 0¶„ð}ߨø  {×lãê5˜ŒêF©Z”Ä>©Úb \ï½ãé‰wŸKÐŽoLz=% ”€¨䣯ðEQ©&u=¤¢HJÛÈõ ¹hËqsÇÿùö6!h"êi„C!¨/ª» ´#.·ÃéÉÃÞllËÀúV1eÀHÑï›ÜñÏ›(ÐŒ=ÜÄ…¦;Xt€ >Æ_Œ^c‘Üñ? A66Ún¤è#6N¤ãLŽ+]é„=QÚCQ5 +5O v2êg@¨SÍ6iî™ì~d#dä0ä¬ÊA¾èg =K× ¯/úP +"¡‡O +·[âU=qïu:FZ¡·%nwiXzI% ”@ëP!¨õÛÀG%xAd‚Ô?$Õ=D‹ t¹9ÙÙdê*ó ïB^ýÉ"¨~´+ÕôEYÜè„Ë…8U€ÃyØ-ø>+ =… ¦ {Ý$›Œ5BP€¢£1w<#H1ѤSúUÆ—¶ñ cMÜól`g‡8Äù,\h‹K]p¥7n ÂÍá¨ê ¨‚:FŠ~Ýø¯}j”+êW,ünÈÈ9È ÛGÈSµ(‰>K× oªö\¿Ô;ÑG_8j9îB€·¸„¾Ëé¹KöðÛ ÝiZ˜ž^ (%à7žýolKÈ3Çö„z¶#ð®ÈsR?NêIMw)ï %yr5]Îý„æ4 +!ô´ú2 òŠñÀz‚j‡¢bŠ{áJWœï€“mp(»³Œ +#Í‹Êï AÀ~Æ#Ìó £ñ‡Ç€§ +A3w£…  v¤áPÎ0eXWòÝ$e7z d +•?†Ê'Q3Õ‚ê™2Œ­ΈAÖ¿65QѺ@!((eáè'n$˜¥ë½­Q-­µ $A-FÏÉqsÓ1ƒ®ÐŒS$GïiFÅõ+J@ („"­ÿÜò:VõP!(V$[ø<‹DÞ™.ò˜Ô –Ú®®Tœ'—Ó]_*zTí4av¾,†|dr½y2u£P9%ƒqµ/.ôÀéN8ÖiD!(ŒïÓ°Âv-‚(½ ¼Ì0"¥ +>´ÿa²0 +AtóÑFˆí…(ñHO;¢yz% ”€/ DÄŸèÒyoF¿ó ¯Uzzqüî‘·Dž‘úÇ¥ö!©é&…Rœ#—Óä4ÜÜñÛ!ß›ô[‹ŒÀò&„îW“!ãQ;FºÒçzáDWîˆ °3çB-|hç3Ñ8ÑÌ‚¨y‰ã hðÀBOŒ&DW²÷h”†%éø&ëÂØžý8™‰KY(ÎEiÜìáæŽg*Ç¢ê)ÔLGí+¨g¤h +V”­(^1eËÏZ°.W(¥Ie–Ô¶•úNq$¬—ú¤™¢ë„÷íªÄ‹@ÒŒ xÓëÜŸ@’ÝÍtŒÜ¿É[îˆ$ëL-JϬ”€ðjA*ù¬mïXœ"óDÞúiR;Nj†J5… 6R’)W? AÛŒ]Írccó‰Àó<äiÔGÕh” G±±:ß'»àpì+ÀŽ\lÊÀÚ ¾±±ø˜Ñ~LÌ&…`8è‡Lް"cä AÔ…˜GŒÙÄÆS€M–±96æ±,+x6ÆÊž\7+Ùù6¸Þ7‹PÖÓÍ_1UãPý4jžCík¨c#º°Ñ‘ÍKF‹¦C3¶\Iq–”HU©ë#2èŽDôÍ–& Sô–&¬çOn:‚’»}ã_»ä[¸ë‰/úÅ“¯Ký¢zú‡PJ 9 ¨”œíz×Z}%2Wä5‘)R7Vª‡Jew©È—’°\±åd¿q­Z ¡›Õ{‡¡˜g ~jÆ£b4J‡ãú\î‡ó=pª3·Ç¾6Ø‘Âø.ˆ¯m,æï/Ï€GÁ@O)º‹I"ïâ›üè `*ðð6ð°0€/˜},ŒõYØF!(GÛâL{\.Bi”÷FÅT>Šª'P=5Ï£öuÔ¿gR†}ƸF¶lÈŽ  Ê©4W*É’ + +Aݤz°Ô=zW*úA‹Ðùy‹¡Õ§ +D©ÒÒ-_O®×“rÉ®c¤åûÎý®”ë~•ÖÏ•€P M@… „n¾¦þs‘EfŠL%µƒ¤Š1‚ÚHiº\¶å$„Ñu¶@¾3—~™ËknʰºI¨²1(~W‡àB?œé‰‚Ú¹ZÍŽ,üŽ5A,·±Øè9om‡ +už‘À #Ñ"ˆ‰Ã¼AŒ=eL†h8ôŠÑލ - +àË4|ÆÆLìÈÁù8V€³‚:£¸;Êûº¹ã™2¬jª§¢æÔ¾:FŠfÊ0æ8[ui²-]~ ˉ ¹˜)¥YR•/µ¤¾¿… §šNL¿ñ@t~þ@øôËJ@D‘ö‚˜Hâ•ºŽ‘˜ô=I÷°E£ßWJ@ ´&» >w{¿e婚ñ-ýJ ¬¡ôÈ+"“DFJ]?©î$¹R’KFÚg„ æÞú¨+ôºš‰z†â™„* +A£P<—ã|?œê£qBPvfbSèV!ˆÞ^ôù¢çý¿(1S#ES¢i ˆƒè5æÏz¹ãOÙ +A´ÊÀºllÍÃÞ68RˆÓp¡ ®õÄÍ~(÷„ 'Qý j^B훨ûÀ¤ ûœ)ïi”!ÙO!(S.dKq®‰ÝA¤Ÿ+|¹ò׋q®—Ò5¬ö%ð t‘û õû”“}‚¦ÃÄÝ<éû™/(k!”€PM#à >·h5÷Vn9ø¾×kêñ÷=¡kkD>y_ä%‘‰"ˆô–ÚR•õ“ÄL[‚6C¾…PW™™í掯›ŽêI¨›£pãa\ˆó}pºŽá`[ìÍÅÎðOBÐW Aô󊂈B)š~a ÄHÑ‘ÜñLææŽ7鯖ÚXž†ÕXo„ Ý8Ô'Šp®.÷FñW¢‡sÇWyBÐ[¨›ƒzz±Q¹Z ÙdË.º†¥ËÉ ¹ÄzåJUHG‘"cD¦Š¼kªz¾{ÐÉù½èègJ ü?ˆ<›ÏŽ@´5š?oò¨œ©°:÷ÿ0‰GKûá©ÐÛüÀYË ”€h +Oö¹ýß{œ£IÚN“¾ÇEõ£#ð­‚Þy^äI‘á"½¤¾Pª2¥8$‚rÜA?!ˆžVŸ@ÞAý+nr®ªI(‡ÒQ¸þ0.À…^8ÝÇ;àPöec=¹BX… EÀ‡]â… ®#šBå /@¥! +A^îøçLʰ÷ùÀç6¾IÃwew‚d¡ñe£!ýÚv§ÉÁ 9‘#ÚÈõB©è(u]M¤è±"ÓÜ@ÙúG:9#l½Trðí ¢W/M:éáK?ßÞ& +\m„ Þðy“g^ÈqÆ449Fkå'¾&~‚¯²¨/Òz% ”@ã Ü¢5æ‹—wdc®«Ç´Z-™m„ 'Dé.’/•™r=,ç´‚˜ŠëÔQz•“P6%â… ZyBP{jƒ}TlŒôm_F A/“Í*€k +At +»E•;þ à`ð%°2ˆïÃø! ;s±¿ Ž¶Ã©N8×—ts˜±rŒkØË¨}õšgŒn½ÖDºÞ”C™r"_ε—«äf7©é-òÈ8‘é"o™¼i-@WOy':9¿}O 4€ 8iÆ9ÝycÌÏ"¨@!ˆ¿íŒòÏÛ>oòôžjö¸;Є:ë¡J ‰|8LšXƒä:\µ äjO­P)K ‘ +O#KYŒ>¨ø÷"‹Ef‰WʳåZXÎ¥ÉQ[öлŠÁv LÂe„ ÚWPý,*žBÙã(‰kCqiÎõ©.8F!(?fºBІ(}ac!0Çä‚§ô´‘z¸è0_iÄcFŠö6‹7b|Ó|‹ßý +îyÖ…±9;yò¶8ÒÁÍS¶.õǵ‡Pú*Æ j¢[ªšWPK›¥ ‹ _C¾‡l3‰ÏŽ¦Ë™¹ØV®w’²RÝ_jGˆL0GäS´EªA'ç©ÒÒZÏ#à·Aô 0«!/ä“&Ô-‚hêù»–óo,ç·,çß[“Pb€8ZqG ’²Å é‰S€ß†Iª·ë¯Zv% ”@RhŒÈÓ˜c’FBWb¡‚fˆcnòTû?‚›VÒϨµl‰KÀWÃ$q1ƸäªÅ¨žN (%Ð:î«óÜ÷€Ö)·^õæ‹Ð$¦Aª/r“j•dÉåt9M*[vB6@V@–@æº2KõLTÎ@Ù$”ŽÃ‘®ÄX=g»ãT޵ÅÁìÉÀ–0Ö…\—®e¶ç‡Ñ~^7BÐSÀc&£Cw¢e½lY´úµåüµåü7Ëá^‘Íb®¾¾ `c:¶eaOžŒúXGœê†³Fº: %£Pþ¸kÄÈE´Vb YN·´‚ÖÃ-ÿ!ÈYÈÅ ¹F«£Tu—ÚR7Zê™()ÃÞ¡ÆpIúÓâtfÞâˆõ)@À?ãh%°Ô¤wœ xB-‚èö§Fò\Ãr¾ð„ ¿27y +A/o³OÞä©ö§@£i[€FJ+TÞ·—¼M Ðb°½‰'Æb…ÆVœoú¶Z0% ”€ {K=÷þTúƒ]Ã$çYc4P„)Ãr¤$S.…\+šý¶l·]»Š*´±ùuÆ"È‚žFéø!ˆAÝq²#Žà@vgbskCø&ˆÏ˜¼¼Ì&c€¡&_üdËb˜ ßw\!ȳ ü³åü‹åØ–ó0Xb„ µlJÇö,ìÍá!è\\¢E'C5… gQûªk³ô“DñŠ… Ãsp¥­ùRF!¨‡Ô ‘ÚǤž¹ã_1IÓ©EP|z£NËãÃY¯’Üü3ŽV!è€BЫÆ"è?[Î_Z-<¹²‹A\âñO®ì(ýWËyÆAô&ûØXQíOîöÒÚµÿŒ”Ö"àÓë-ˆ»~ž¡w»ð„ †ón|“sB@ORŸÖB‹¥”€Hy÷P{îñQÊcó€ú7Mò,¦Ð2BPu¶”„åbHŽe_@¶ÚnÈåå&êÎÔ½íº_Uz®aãLŒ Á¸d,‚N!( »2ðCkBXÄÛ?­ž5BÐhà!c D‹ +AðK!ȳâfq†åä[N{ËáÁ‚ÂØž½mp°ŽvÆÉž8×—†àê#(ƒ²'Ü,f53PG!ȳZ +Yi„ ]#ókiRš#í¥†Aƒ¥žBБW„ ~j’¤-‹NË“¶iµbq$à“q´ X,ƒ«ö¿k„ Þä=!h0ÐÓA4by*Bü“+; ýåü“å¼Pí§ô™±Z§k½8öŸÔ¹”OFJêodM)¿jY„Ç›¸aŒ CÊg¼cDtc +AOy™· † häÉõ0% ”€ˆ' +>ü¹ýŠw|óöÃôÖ&ð†ÔÑ"hŒHê$™R’.Br,Möe‹‚˜käÔ¾…ê—Qù,ÊŸrc•ŒÀõÁ¸Üç»áTkƒC‚ÂØr… ¯‚XÀG¶;᧶Ç>7wÞ°¬—,«PôK!ˆ ®x€·Y̯xA]-§×ÿäPYÚá Aíq´+NöÆÙA¸8 WEñã(sP55Ï¡î5Èl“æžÉîàšÑã訂ŠRž%Õ…R×Mê‡H=…¯©"3E>¡E +Añè†:-e½F²ðÉ8ÚÐ"ˆv›¼WseÇÅÚ?XÎßZÎ( "qŸBPG;šoreG‹ ´šñ+Œį¯¾×U^²wÚV©ŸOFJ«ÔÝ·åí‚n¡ 9Õ²ž0÷„h‹ +AÞí‚ç9'äœòÞÂÛucßVJ ¦”€Hq·Ë>·¿“âˆü[ýºiR3Nꈴ“ÚðOB-‚~´e+ä;È—ù¨µo¢ú%TNCùDÜ‹âG\!èjo\ì‚3íq"‡3±›©ÞÓ±:„/ƒXÀ‡¶ûÐgØš϶,.¼‡>… ßq,ú x®a|èsùàíþP5ŠA´ú>€>¿áôÿmgà¿sF„ F…âqnaª§¢öyÔ¿yò)ä ÈjÈfÈ^È1‚”B*²¤¦Pj{IíÃR7^ꟕú7D>Y¢®añéœ:-g½JrðÉ8Úh4OònòŒóö7&"´w“¿Å5̳¢ôXŸÞMÞ ·^—xÉÝe[©v>)­T{?^–€!h +sZÖ#Æi´{CŒ ˆnì Aœ>k&¼]PbD2?ÖJˤ”€P·… R!(a:£åÔŒ•ª!RS$µéR’KA9ø…´à'!¨êET<ƒ²‰(õ„ A¸ÊLîq®Næ¹BkÔ -bŽíÚô¾À,`–5Þ˜4fÀ‚~×A}L6y¢×˜cúÜ,žÝðÐçŽ3… *KžkØà?t†þ±3ìϳFº6 +%žô ê^€PzßÕ¬\!hMƒt¼AªÌ”êvRÓGj‘º'¥î9©g|¤¹"ËDV'Lc%lAuNž°M§÷Ÿ % +A¼?siÆ•—iðÿÞ„ý÷VvùéâA‹ Ï׃ =Þù¹@±ˆ®a/«®ì¨#-6èúÎ_],yJã“Á’<@ &Ü×£ðëÝ.x˜j ~FX–7'lg‚ESâäFãž•¸'y„ü"u$Þs úU% ”€hAÑâOô뼤ž:&(UvS«WgHIš\¤dË~ÜnTõʧáæDÅõá¸:W(ál!NæàH{Òñ]Âø*€…¶›žQÅùˈãLŽø@7“5ìß9GPâ;›„bL+6˜i"NÌ3ý•Àú6§»®a{Ú`é†}0â/GÿÚó_×"ˆ¹ãŸA}D¢M˜ZŒ&™,󯛌óóÏo¹YÀ–tìdŒ f%cn2#11‚h4öœñÿäÔL…<yà dä†3ŠAt ‹AÙRY$Õý¤f„kT?£Aú*Ú·õ«¨òÖo-ARðÉPŠAŸ4ÄšÐ5ì×–Ã-þh‹ úˆñOnñÿ'Ë¡D_ªFÔŽ(-5B‹NŠŽéÇJød°øM|ËD±7¢{„ÏxAÆVðeË¢” ä7XÑ5ŒVâ™[Ĥõ„ Î ©oT-(¾m§WSJ@ 4‰€'©Ô$h­0ƒçÜì%¥Rb»Au¨ŸPEùò-„±—ç¹q˜k_w… º†ý$ Õ¸Øç)åãdޱ‡<6Ö ˆ*]ÃÞžž†G°®Àÿì¸éã#A|ŸŸòÉã?_køÐ`[:vgãÇîˆãÝpšá©i‰4 7F¹1«+LøïŽóÿ:Nš#s !ŒnÍÐF[àjY¬È%Ʋ¥,W*:KÕ©~Tj‹ OE–·>ü(NÈS ‘µŠñ àŸ¡ÄE÷è©çpeG#Oú–C#Oo‹?Ú5Œ1‚Õêiô"ä-8ÙŽÓÖqŠù² ®wÛIÈe[n2kX®Tv’êþR;Bê'ˆLyG„Bþă€NÈcH™2)ÅRN§_¦§Ë¿ôÇÉ3ûª\œN{ûª4àÓe Ë §j-þJ+ÌÒŒBP¤+re÷(ð§–óû–íöG–óg–óW–ó¤q a„Y AÞ4q#i%îmR7f 1ZM¶,>¹èIÚ ð,‚x»ð iäéÆ+Uº7hýT (%à*ù£šXŠâ¹’!gƒnÖuæ^gö• +AAÞFýK¨™ŽÊI({%£‚.Ñ"ÈA'Â8dc§QVÙXfƒq~Þ3f½3€§L ‡¾@ç_ +Aý¥e¢h×0.u¿ð,‚‚Øš]yø±‡;áDœí‡Kƒ]!¨t*G-… g /»R•Ì…,|§§ã pœ¡Žœ²å +… TäKu'©í'õˆzF% ”@Œ ¨c q;ݵ°œÉÈ.Ȇ(!è-È ¨yUQþ8JGâÆP\íWêˆÓù8ž/.ôFÛ5ß]f‚ûqçUó(§¯÷€ÙÁhôÛ©Aâ6ýIþM/7¤Šh’mMôW.î(N²+R¢FD¥ˆ @îP;JÞZÌÄ&àÏñ’ØL›^úˆEÐGÀ¿˜ÔÿÍrÆ›L²Ü +¤ÔÎÜ.~ÛL9-ä\‘[‡Ü@ŒAó̬R… ¦³×o(% Z€ +A­=¶—Üp-‚(y®aošÌ\“Pó*Æ t®Á•~¸È =E® +t, Ó°ÇÆQBžžEГf‡w>âó—B·@àZ• º Ð΋\:¿|幆¥a[vçà@ŽÑ­³kƒt£/Ê¡r8j‹²Š‚èÔF‹¦ÃskA)É–²vRÕݤ²w —ô'žt*Þ4Ú= íP—‹ê0Ê„ Ï"ˆÓiO¢EЛ 1‚¸¸¦­Ç•UN§Û‹ Ø{ûªüÈ[}S5âêûc³¯ºÊØï6AçmܰQ™†ºL]›7­¡Zåhߎ¦gŒqÕvÅî ù ³¼iœÆ¼û|«pÓ‹¦&ߎ—Tkλ2-'`9œãña4ÅlÿÑ5¬¯Ù,l‚øä¢nL‹ O¢kØLdàÓ‹ Tã¦õUJ@ $"‚±Õn-3å”oŒEÐ\7F]ÃdjÇ¡êQ” Cñ \íãJ@ü=Q€#Ù8.-7ÝIrŒEÄg}³XàZ• o­ÊuÄËf­Ê=£ÅÆf-Ï–†í™Ø›‹Cmp¢=Îu•n(îƒÒÁ(a\ÜÛ\Ã׈VDº’.ŹRÖ^*»KÍ@cä•Z¡[¼…þÖ©xÀ„tG}GÔ´Ae&Ê®EЩ×°õ&HÂc`Ïé4…SN§¹¯ê­¾)Ñ#Œ–4 +ò„ J¯4°§ Ëéô«¿ŒD×°pãzµqÝFU’ié¢rPš+þ‡ú4 hW•dEˆ=“êPüYé•€ÿÇK·‘™þ4Ýò¶0¸Í÷† ýtCt;Zu5-ZòÉõûŽÅY"§…|rÑ"hšqj~ר².3®aIŒK«¦”€H*%MSÊbȇFz 225#Q6Å\±ZÖå.8×'Ûà°‚èl²Ñ¤øüÌ<¸gýÒ"èŽBßäŸF |âSâWæ6„1ùÞÆævfâÇ\)À©ö¸P„+=p½JBÙHTEíDÔ=‹zÆb°èý… Ï"ˆ‘ŽÎ2Xt𔆥*Oj;Šôº¥]"•[Þ×?cH@§â…ù(d0¤'êŠPU€ò,”q?Çò,‚S®Ism hi°Òñ~bß|ˆSááR”j—¥¿k²BÐn¡³q çÖ·V¥É·õ3»Á{…'YÀ–vgà@޵Á™v¸Ø W{ ¸n2FÐÔŒE½gtKŒ ˆt:(—ÂRœ%•¹÷ÆëM]î}Œ~Ú<:o·' ‚† ¾—+Õä£2ãg!ˆ1‚¶sDD¹†E[1êæ… æoŠ6·ãtš£Ò‚6!è-‚¸DY:ªrPWˆúnþGT jT£éAJ@ ø™€>}âÖ:wÓ¢ @{o>¹ rrC’AÏ"¨ !£Ûýž±â´ptƒEmYi4OM +£9êk% ”€¿ ¨äïöiVéžs]ÃhäYúVôAI7\-¹BW¥9=éØ€ç½²Ôè9\xÒȇÖ4øá‚”澂ڛð¡Œ=0·~è½Â'>… nýÌ4F |â{kÕuAlIÇ®LW:Z€Ó´ꌫ=]!¨|ªAýh… ‹ž y2² ²ÊXífÖ° œJ“Ëé®EPã~3“iÜ™ô¨Ÿ èTügw{522ʵ¢TK!(axYÃNÙn°èˆ´¨! /÷U½é4… Æ‡ƒ«­1°gƒZ¢ipŽämaû½ŸA(닚BTfãJNå`vdaS:¾ `91ZàZuЉgë­U)üõ¼Ã1že+Œ´%Œ½™8”ƒ“ù8_ˆ«QÒå½Q=uÃPG×°§P?½!}¼gô-Ăޯ` +ñ€³Vk)ß\X'á÷o +F¸ºMªl‹›9¸ž‹A¸A BÐ +#y*+×?ß&qp1Ò… opQ¢½PdpÑÜîsÎý`/pÌÆ +A¸ÁAù¨mk„ Æ¢ØKWµgb0‚î_}=B (%ÐbôC´1ŸÑ5,ZâÌðWŽE‹ –YO¥”€Pq& BPœ·øå¼Çÿm—¹Þ72q1GÓ±7„-¬ â+Û‚"Q¹õÃx¶Üúù_‹O|.Té½BnýÜ.ÑhÞ+ô,û:ˆïBØÌÜñY8”‹Sù¸XˆPÑ5=QÏ0&ß½Õf@^‡¼ùòyƒkØmE}À7b>ÿyÀò$Ê×u~ÿ–bvOù³EPe!næâZ&.„p"ˆQ®aKL@õwL°h +Ao9#£,‚†Ó<þ™Ìh{5¦½ô% ”€o ¨äÛ¦ilÁb¤E.ýdÏþe<Û1QBçö°Øì‚k 9‰Ÿ_øgå+JÑíî«‚ù«0´jcpfº†Ñ"¨+êÚÿRöÛ€µp#±Óïò€æv‚þÑr( ‚hkw‹k˜'ÍŒ‚h了ٮE… «é(Év¯H!¨6"i°hu-PÍ$ ¡{€óáÔEÛëí¥)% üO@… ÿ·Ñ]KèM îúq3?H'{Ëðk&öÖýZê4z 8SxaÒvšºuC-caµAi6®‹ “¶+m5BÐWÀà}àuà9`’ ÀõŸ,Ç˽ÂìÑBПXN´¹-‚¼¬aŒĬa{L¦ng,tfrÏCi( ¹‘|~4®aŒíæY†‚~e„ ß²œßl‚žfD‹þð‚Eóœ'ËÀ Ze£²-jŠ t £4JU æ·¡~S (_Ð'QÂÍC´É|5‚´0J@ (&P!¨I¸|q°ª@-Ü 7{p:—kúnÔg ,ì†q¦tÔAÌóõ@‡®a‘ALÉ÷8ÀAt ëÚ;ž‘Ø»ýŒ@ÄOy £ Ñ‚ˆßâw#B³†Î§¹rSI.* P×B×°Áª5£Ýô+J@ ø”@Ê>‰wÖ‘²MæÓ!¤ÅRJ@ 4…€ +AM¡•üÇê3=ºwn]‹Æ¼Övo ¥Û©+D Mt‚¸–†³A7¤ó>ÛMøNKž/Læ¯[bÑ"ˆBŦ c¤h +A…(Q ¢Ä8B´bpiO¢s¥­p­ŒhtÉFq•é¨Ë†!èöé;J@ (D&:£Èƒ/÷'uÚ+qÛHK®”€¸‚îF&5ß×gúÛÝ›°Ýñ£äxSÛýAÚ±,Å´ØŽØØm»y¾äÙ‚Þ3®^Œü3 ú!ˆ‘¢óM¼hŠB|Çs ‹AsL|!:—ÑÅl;pnbz +A¥AÔ„P—£†@Ò\ú]% üK éFýÇ¿mÐÄ’%}“5‘‡®”€H*%LSÅ¥ ú@¿æä›¿y•ÕF¿G£7þ£sÀa`7°X,3™¿˜ÿ‹ÁŸ)9ÃA{BPgc ”Û ÑFȳ¢k-‚"®a´Zk"í÷bÙ(·Uj|ƒè‘J@ $d}%ëü=,Y›,ñ–X (%ÐD*5X2®OóF¶n’Íè´ÝÙîÁ“¯MµFJ@ (% ‘@œç$ªÿĤ“ĹÕbRf=‰PJÀ·î&øÜíýfTD… f@K¾¯èã;ùÚTk¤”€PJ  ÄaNøBbB ­“rêI”€P Aàn‚ÏÝÞoF¥Tj´$ûŠ>»“¬Aµ:J@ (% —€NK±í´Õ±Õ´ÌJ@ ø–ÀÝŸ»½ßŒŠ¨Ô hIö}v'Yƒju”€PJ@ (%g:ŸŒ3p½œPILàn‚ÏÝÞo +‚š-ɾ¢î$kP­ŽPJ@ (% âL@ç“q®—SJ ‰ ÜMð¹ÛûÍ@¡BP3 %ÙWôÁd ªÕQJ@ (% ”@œ è|2ÎÀõrJ@ $7Û5ŸÛßy*=½$ø®>µ“ µ +J@ (% ”€h]:¥l]þzu% ’ŒÀ-²÷ç=Ô›{|tG2M=þŽ'Ñ7—€>µ·í´äJ@ (% ”€ðUú§-´$J@ $ˆøyqïJ5IÛiÒÁ÷¾®~êO‹·—i€<< ôº«=Ðè Fã©æàw€¹ÀR`àϪi©”€PJ@ (% |B@… Ÿ4„C (¤!‘€©Û4ò0òiü‘I3¹+r6Œ“i8 ì6+eÀ<à]`&0˜%õ~ ‹rPg# +õ†cIÀ à5à}`ð°ØbãÇ Nq9„KmUJî~¤µSJ@ (% ”@Ó¨Ô4^z´PJ 4Ráiäa-P@=eÌTvGuÊ P–‰Ò.ǽÀÀjà #æPÒyxΈ<”z†ƒ¿E» ^ƨ‹±¢¥í…žj‚(} +|nγØ âtgÛâ +¯Xé +¨¢PÌšRO¤”€PJ@ (% BP‚6œ[ ($#Б§1Ç$–ä©ÎcA¨+Be!Jòp%çÒ\!ˆ¢ ¥›ï€/…Àà-àE`ŠqþiŒþÖ  @Ó îFŒ6îcÏ " +A´&ò„ ÊJ—Žq&„+(ÍFY”÷Då`T= +™ªŠPòt.­‰PJÀ·øØâ¶ÅàIãËü*0Ûl[ðyGûUß[ ¦R€jA©ÐÊZG% üOà¾:Ï}ðS®„oB^‚<q £Q;ƒQÒ×»âj!.æátޱ/€­fJ¼`˜ Â=L0jµ ÿÖCÀÀ-ˆ¦AƒQfj= x˜||f\Ì6°-{³p$g +p¥¥PÙ•P55ãQ7òämÈG:O¹^©VJ@ ´4Žf†¬ŒhÇ]Œ¡æYF-È{`1®ÝÇÆšZÐN•ƒZº1ôüJà.Tº }[ (%o÷–zîýi¼Ëª×»7Å!³!¯B¦£v²+¿TDÕ`TôÄÍN¸Þ—òp6G2°'›Cø. ËXb»aŸ9I¦¶Ã 3§Íô£åÏ?Á¢çÒœQ3@P#=j”"êE .ͯð‹KL¼èïmlNÇ®lìÏÇñv8[„+ÝPÚ Õ}Q;µ¡vj_@uª9õ•ƒîÝœú©PJ@ 4ŠÅš1Ÿ\ü}Ü<ÅèÈÌ×´ b>Úfïóm|eã;ÛÕ‚N©Ô(ºzˆ%‚bISÏ¥”€x0÷P{îñу]S¿SßCV@–A>…¼‡ú7PGÉe +jÇ£fª¡¢7J»âz\nƒSù8˜‹ÙØ”‰Õø*‹ÒðQïØ? Aãÿ‹ShΫ švAžÄi)ô„1¶ÉÑ”h±åœWðCÛs°·‡ÛãTg\èk}qsª†Ð;ìIȳ™n e>äKÈwí*Å´'èÉ”€P©D€:ùÌšhbÜM1Γþ>e$ >°ÆO3´×l|À ¾b}v§áT@ŸA©Ô]´®>  BA‹ ”€ø™ÀÝŸ»½ÿó7õUë8Ù Ùùòdêç îmÔ½„º©¨{5¢âaÜ€½pµ ÎuÀ‰¶8˜‡ÝÙø!ß…±<‹Ó07€Ù6HÁ8y¦wØ¿Àâv*Á1;­ŒD1þRâ”›“íVÈÆ ø2ˆÕi®´3{)4uÀ±n8Õçãê0”>Š*,š`Öh­ô.dž)íjÈæ€ì Êñ´Ö¥¨WWJ@ („#ÀL—ÌbIkf:xÁØ©r‡‚Ï&¾æï €Æ«T„x ‚¦Øx!€×ƒ˜Â’V¤cSûÒq1¨ZPµ¼8± ¨”Øí§¥WJ éÜQó¹ã›IWõĬÐÅ49CAÙp… 5¯ Qÿ!êßBý‹¨§EГ¨‹²(Œë}p©;NwÆ‘Ø×Ûó±1«3]!hI>üœAž;§ÜZýWX´®çN+}Á¨ÑAŒ‚x¯ÝÝUÏÛîŒúý >MÃç!¬JÇÆ0vr^‹Cíp¬ NõƹA¸<×Ç tªž6BÐËYOŒýÒ*[6Ù²Û–#ir6S®…³%´ÔJ@ (%oLp@wfî_¼¼ibÖÑ[ùmàÿ¶œ´œ¿·œ¿µœ¿´OâæÅDÓx9ˆ·C˜Âgéø6Œ-a ©ï¶Óë¥8&A–•⬴úJ@ (ø¸]ö¹ýø”D¯r×särºœN—Ãi²;èÚÕÐÍj¹‰½ÃPÌ ÈL‹ i¨~ +ãpóQÅ•8×Ç{à@gìîˆ-í°® VæâË,,ãã <Óiî«rÂÌýSÀ¢å,ˆî`ÃÄøâq“l<Àkü… –…°2ë3°=?fã`;é‚“½qv.ǵ1(™€òɨž¡ôމe´²Ò– ¶+dÈ™°\É‘²¶÷©¸~¬”€P©M`¾IXIÇd>¶˜¼’ÿÎ1ëøNšåü«åüËùgËùËùËù–ó<@Û!Z=ÀsA¼Â{!ÌOÇò06„ñcU Jí¥µ3F A”€TŠsÃè唀Hm·(?·ü™ÚlüQûÊ>RÑVJ³åJ†œI—#!Ù”-YkË×? Au¯¢ú9TLÁÍ'Qü®=‚Kƒq¶/NtÇáÎØÛÛ +±¡ Vçby&–¦c^o!ˆfö!Xžƒè æ1'Ä2ˆê+‹ +A󏵯Р|Ÿ…­Ù®EÐá¶8Ú'zãô`œKcqÍAéTT<‡Æ¢N5²Ä–¶¬ÈŽ k×t&MÎȵÎRÑÝ µJ@ (%à;Ë/L¶ÊEÀ‡Fÿù„! þÙÖr²-çãQˆ5¦¶ü+ËùsË¡¿Ø³‚‚˜Ä+!¼C£ 0>»þÑ4d=¥BïÚY ”Ìî/©”Ìí¯uSJÀ¿¢ÅŸè×þ-q +•l€Ôv•ÊöRš/W3ä\Hަɾ€lµeÉõÄÕXêf£úuT¼ˆ²i(ˆbê0#pñ!œéã=q°+öa[;llƒïrðM¦kÏ3?àî¨Òºžq¸sšËsc˜M:ˆ1jtÄ(("1ðæÌ f‡ðqK2ñuÖfcs.öäãHŽáTOœˆ Ãq™J”ƒÏ ôET¾ŽZº†}dËb*W,v@¶å`PN…ä½ÃÚËþR>Ldp +µªVU (% G`ð­IU¹Ìè? ¥&)|7Ë)²œ%ßY`>¢@ÄçÚlà?ZΟZ7/¦]-èÅ Þ aãã…±*Œ­éêÖ8ôz”ˆ»jAj;Èz&% ”@3DôŸÈ‹fœD¿k£¥vˆTõ•›Ýäz{¹œ+çÂr<(ûm7÷Öz“8l)ê?Aíû¨~/ý,]‰ CqzŽõÁîØÕ[:`}[¬ÎÃ7Yø<  Q=C.0Ò&½Ã²`ybL%ï9ˆ1j4ÃDÓ(ˆ¿´b°…g½}Õt|”E™ø*krñÃP·Á¡¶8ѧ{à\\|WFãú”LAÙó¨| 5³QG‹ E¶,·å{[¶dšË…l¹‘/7»Hù`©|\ê'Ä žO (% ˜À` °X |Ý } ô·œ^–CK!ªCŸ”ƒ-h.ð>ÀØAtû•åL·19€Aã×rÍY%ocûÕ"(;…=! ÜYRC „lL-´PÉFÀ“€TòM»N‘ÚñR5JʆJIo¹V$ åt® ËA[v@60äê—¡v>ªç òm”¿‚›ÓQ2 ×Çãò(\xg!¨vwÁÖŽØÐk„ EFb˜Í—QP¬gL²Ff1/j´g44ZJÃ;‚Â? At4Û”8Pˆíqº;ÎöÇ…a¸4WŸÄ©(}寣j6j]!ˆÑ­mùŽ~mônË#Ùr–fNm¥¼½T pkZ;Iê_ô -ˆPJ@ ´2Ø lÖ» ¯zŠ} ²œ~–Ciˆïxrµ ÚÑ(ˆîcŒ#ô¿YΟ1Xghdã%†Œb.3¤aóÈkâ°VnX½¼¿Ü®…p) p¾çòPœã˜êw‚TòW/ÐÒ(%Ò¨©äðšÔÎêIRõ˜”?$¥½ÜX:ÛÉ™DÅ;(›‰Ò(yúg!è´‚öÀž.ØÖÛâ»<¬ÈÂ!,¶ÁS +A¯m`1Í +#M6©äiäE +¢QS†Ñ"ˆ©Äž¢EP¯P +¹BÐÂL|™os±!ÛÛb;ï€3]q®Ÿk‰ti´+]ŸŠâp“>kï¢úcÔ-6iÎÖeSXvæÈ6r²P.u’ÎRÕKª•êÉRûŠ?øk)”€PJ • œ°q8 ?± Ø ¬5b+UÌki9Ô‚øš¢'}eÄ`AŒý&Rmt|~ÁÆÛ6>¶ñ¹uì´c¼ÈmeRzy%Ð,åi8Çį°·#¶uÂæNø¡6ò·?˜$#Û +°/WÒb0^~!©;X³ÚK¿¤”€hQ*µ(ÞÆ|®Ô¿!uÏ»2Õ£¥j Üì)7:É¥B9›#'Òå@Ð ³³>P¿*Pû…]½•¡bÊ_ÅÍ(¥Eиb,‚N±~8ÐÓA”‹™? A´Ÿg*ÞXÏ3®&0Õ¤s€["Ñ5Œ¡¤=!èítÌÉÀ‚l|ž‹•ùXWà†¡Þ×G;âLœïãÆ&ºü(®>“Qò¼+•¿‹ªQ»õÌw¿:(´¿œh':Ê Aê)µC¥Æ‘šW¤nNã(éQJ@ (%ÌN¦ádÓ±+„ml´]1ï÷Ë¡Ä×…V-ˆþbŒD£ ÆŽ¦ôŸMú0Á£±+-]éý&\‡èÏl¬±±1XØ&3z­[²(âx.¶wÀ·°¢+¾î†/ºcY,í%=±¸ñ·–vÁ×Eø®=~ÈÇþô5?iAj”ì½Kë§”@‚P!¨µî‘O¤~–Ô¾,5“¥f´T‘›}äFg¹ÒVÎeËÉtÙ’í!YŸV·*XûE°zA êÃ@Å;6… 2 +A´¢4ÚuÑ:5Gûc/ìEØPø“EЗ!7¢-‚(ÍdâXœ-3dt´w‚hä¥ã N¤)½œ†·Âø 󳱌š’‚¶F„ Î8߇àòH\O£ä9ÜœéŠTUsQ³È®ûÒv…  aÙ‘-ûóåx¡œ/’kݤ¼·Ô ”ú±R?Cêß•úe­Ý +z}% ”€heçÂ8‰Ã™Ø“‰íalNÃ÷A¬ ¸JÎHËöK!ˆ>b ä A ô·–ók“GžÜÝàNÇkF â³oª@­Ü°zùV&p6Œ +\ èË.XÜ ó{â“Þø°>è‡÷úav_ÌêƒY½1«Þí9]ñq'Ìo/ +°:ûÜ*]!HU Vn|½¼PJà®Tº+š8}ð•Ô/”º¤v¦ÔRzL*†Ii¹ÞM.·—ó´ÊýaÙ–^¿>T·*TóEZõ‚`åGÁŠY²™6-‚J&»BÐUZ ÿ…´­ ±6+³ðUÈÝ9å¶é,37.4Bç6¥Á;l¼ äy‡yBÐ4#yAó³\!ȳ¢´·=ŽáLg\è…‹ƒqy®ŽÃõ§Q<ÂÊgÙ•ÑrÉ®û–ÿŸ½÷Šcó;Ç>ÛW>ßí=Ÿ]Þ»=ß–]¾-{½¾sÙ®³Ë·û†a‚„ 2(çØÊ Êá)çœ3’@”%„$D93ó»_÷OOé!@ð£¦TÃÐÓáÓ­îú.TtÓî ¦'þT<„Ê©6šZˆ&-"Ú@tèrñ–Å! „@Ÿ$PfÁk78Yqgy~òó5ÝLà– ÎzãH vÁÆP¬ +ÇÒH$Gc~ ÄbQ,’â‹”¤D#9 +I‘X8ó"° ‹ƒ±Âk¼±Õ‡MßY§ý¦LP7o™ÌN! þ(A”à÷ÿ)Q6Ñ9¢CD[ˆVm>5O§ú±TGïè4€^¢'t×Í~ÃÕvÕ¥õ¼ó¯"hƒ¡•K{±h®ô¶="¨PA·¸ôŸ72=pÑ‚3Nê“S~lÊ£â@è8;lÀe‚8;Œžò€™µÏtmð<«‰ ­wˆ u&luÁ^+Žºã¬Cù ÀQŒwÃPƒŠQ¨œ¬¯š¥¯IÒ×­Ð7¬74n34ï7¶7ÚÎsu#ݰRÁ`zH/ÂèM UŒ¤:î6…h>Ñ¢½Dç‰n?Kù¦ÝJ€ï¦Ù óÙ ˆÑäûŸH âÛÏ|áNÌá ¾7Ïà~O\…‹Q8ã5´xÀ$wâݺoúïÌj¬(qÇËAx䉮gâ†ë®¸â‚‹&¤³ b©SbtJ¸ÖGžŸnðQÇ8þ?Â"ˆ+±–ä+‡ñ…Œ¯k´^,Pÿ=Zd˾Jຠ§<±Ï[‚±ŠÅN8°ça烥±X‡•qX5ñX˯8¬‰Åª¤EaÅp, GJ(c?–za•;¶›p¼‹ÿ¡:¥ƒ‰ úên’ „€½E@DPo‘'*$º® A›‰–QÛjšAõã©:*"¨4^ùУÁ”ïiÏq·eXÛι¶siÞçÜ´Í©q½*‚ÔöñZ×0®ôv4Šð4…á(CetA{´»AÐñ?*åA2?<å+Ü;ŒEž;Êq‚˜CqÞµ&lé$‚®x!Çù"(åÑxÏ"h’¾z–¾v‘¾žEÐ:CÓVCË>cÛ1£íœ‰2)×Jùƒ©0žSEP9§¿W­Í#ZM´Gb7{o_È’…€P ðY‚uqGd» .Ï·Õ|N`)4Jë*ȈÕÐh€Ãçká…|»í +:§ÇU#n™ðÀŒV¼„÷¾¨‚m((4IŒf_"PÏíŠÜñj{â¾;òÜëŠL³*‚ÎÔ2ÑgøØÓ)a:%X§øè7bÒ),‚Öi5Žqå6|ÐòáÊ5¾Æ}iaò7!Я Ü7¨Í^wûb} –‡`A’8ó+FÍ[«jŸ qØ­ñØž€‰ØÁÿÆc[,¶DcS¤Z5h]V†`Y ’|±`–X±Þˆ}_þoõ»t0Aýú(“Bàç& "¨÷öߢ¢ D‡Õˆ {*µ&Qã,ªDU#©<ŠJ†ÐËzèKwÛ¯j»âÑzÖ­å¨kó^—¦mÎëÒ j ¹¨š¦‹þ¤∠t ÎjA ÝjmÌÌO"ˆoåxðìA|Ó7NE$‚ö¸~ˆRE7òýÚ#‚†ª"Hrˆ öˆ ¦mÆ–}N­ÇL¶sfÊ0S®Ýñ¡Áô,œ^ÇRÙ(ª™¨Z/U­RËe;Aô¶÷v‡,Y \YZ0ßeÒ-±Øá Á…Z– ŸølÐq~à[ì1šJÔÊËó_ù4§”-zì5à˜íŒ< rh‡'J|Q‚ºáh‰Í’{ó{˜ueË«8;l^xâ‘; +¬¸iÁ53.™pÖ Z “Z] Ã@NñÖ)Vâ¤Y •Z²3?ÔàǬ(ù*ÆGfW'ÓþJà¤;½°ÖÉAX0T-þ“‰µ,yXõÄa{vÅc%àp"Ž$â(ÿC±8}‘ØÝaØŠÁX€åÞHòÄB R Øö¹ÿ\:¨Šê@!o„€}€ˆ ^Ú#ï´ˆ \¢‹DGTd[EÍ‹©a.ÕL¥ÊÑTM%Cée ‹ {þ`[Ž&‚ιµsmÞïҴݹqƒ*‚ÔÔ°yššø%äH c +?9å»6~âÏ"ˆìrD‹ N™© ¡Yñ¿~#‚Ì`tDK »ì…ë>¸ã‡‡xÉ©aCQ…Š‘DPÍ"N 36¬36m55ï3µ3ÛιP†…rÝ)߇ +‡ÐÓ*ާÒ1T=™g’SÃ8"È!‚˜§ËÉ=Gà%ðÈØqÄÅ1`¯Vb—ãùüÀ!¬ƒøþšO|Np$:άƒøv›ŸCVè±AF2â´3®XkÅ]<õ¼@Í04Æ e4ìS@‹@ir“Þs»øçZRƒÊÜPÌ•‚ÜPhÅ ®›‘aƒš{ÈÇ'»JÎãËßrô_ΖkiÎ|ˆr,Ð-‘cØ~®­–µÝKà”»¬jyŸ$$cy(Ö„«q>Û£±;ûYøÄãXN%à\"Î'âB.&à|ÎÆát NFáøp ÇáPì Á­pô*o,qÇ\³ZU€ÿë}¼ÂŸ²@<ˆ AÉïB@>C@DP/íŠ×Dµ˜tMq×°µÔ´”êçQÍ4ªCe1ªzDýíw|l9^mž­çÝZŽk"h‡sÓF§Æ•†úŨ‡jn? oÇ (OcP‚¡ŸN cÄÏú;‹ OÖ‹fÄ^ˆïï85L­Ô.‚Îx‚EP¶òüQˆ\,:¤]MÔW+úš…ÆºeN kM[œ›÷š[ºØÎY쮚ò¦BŽrˆ ±TÅe±g‘‹E‹ê¥cP;° Ô;¡Â ¯ðBû@.p8Ýäȵá[l‡âÒ+Žbb|fè(,ÏÉb€Á&™­ò:=¶:a¯3ŽYpkür^'F‘/ÊýQŒ†(4FËØç€–ƒ6þî>b`ïÙúÕz”¸à• ž˜qߌ›ÎÈtú ‚j¢r—f~ÖhÇ_Å8l"ÀQja@ÜïoQ;f-o„ÀÀ °Ç„uîXäd¤c}(¶†c÷pŠÂ1öÜÒ#8§uYâíÚ]6‡rŽXG=1Gô #4ˆ‡q †£*ï=¶±—r“+2ÜqÓ ¼ñÂïPŒ–P´Æ£m윖Ú$"h€vß²¹å@‰OxhDžÙF¤ëÕˆ A;´h~¢±R;29\Õ8>-ðë¸3ý–eÉ´B Ÿ8ÊeÒ]âdo¤ù«¹];B±?G‡ãL.Dãr,2âq-9‰¸™€Û È‹W_w⇛±¸œHdG + ™¡¸ŒÓ8âƒ}ƒ°ÍŠÕ&Ì6¶g_~&¨3RAiÈ{! „@ß! "¨—öE Ñc¢[DWˆŽ‘}'µn ¦T¿ˆªgÒûñTOoÃéÅP* ²ßñ·åø¶]Üvγõ¸{Ë~׿榦ÆU†"hf»‰§qªÊÅÍ dû¶‹ ­×Ã7‰ ~îÿ±rG©"Èy~"‚Þ:RÃXMÐW³Z E­Ñ"‚öpDÅvÖÕ~ÅJ¹DϹFP•qjØ5"¨mQ'Ä5‚$5¬—ŽGYì€!`†æ!ª™©ôEé [ñÌwÍÈuVpÎqœ«ýhÙa´g¾œ#– +ü7òŸ´Ý¡Sþ\§ü©NqT bÄÅX8jˆEÐf#v;ã°§­¸äŽë^(ðÆ?¼Äû`4Ek ÚÆÁ6ödÐjÐnqAæ°û® }<îhy‹éZ¸‹ ÎãPBc-éP@\ºÜWÐw–/õKÛ XlÁ"w¤zc“¿Ú8þ`(N„á|2"‘ë¬zâq;ù ¸—€Âx<ŒÇ£8íÅcq?w£PÀƒÉ0ÜŠÜ`dâ¢/N Â7ì2csÿ–nz,Ô/3Ù(! úA½´¹FK<¢ ¢dßE­©1•ê’¨Zù ‚JÂèEˆ&‚l×UÔzvPë1MmwQEÐÊvÔ¤‰ ‘DÐ -"HAqÐq,=?Håpz~Ðß‘ôñïtÊ¿Ö)ÿB§ð šo븺—þø ‚ Z×0޲¨Wÿ"¨#5lJBQê¨Ä©a3õ"¨i³¹y·Këa‹íŒÕ~Ùr<)Ÿ#‚X…Ñë*MÕ“¨QiO ã®aÔKG¢,v@–X4D¢&Aj%gîÐôÄ÷,¸åŒ,'¤k•Xh·Û›µ¸ nÌä¬SþF§ü¿:å?蔫Sþ•Nù3òOu +Ÿ%8Œ„¸dû¢MFì4á  NY‘îŽl/ÜñÆC?¢”ÕS(Z†£u4Ú¦Á¾P+´]DЀ:ø¾scYeP;mѲ›Ù=²ŠŒÿóPåký™À*#æº`¹;Ö{a—?q<ÏP¤õpä Çí(ä³ç‰Å6?ñxñx§¾ŠcÕ׫¼ŒÁ³(<Àã0<Š{Á¸€ë¾àv!çÝÁe¨÷þmûXŽ å«ÀWQŠú*"™@!Ð+Dõ +v"‡º­‰ ãdßM-¤EUŽ£ò8z7Œ^¡‡jjXŽÏtÔ½eŸµy›KÓScš±¡s ±x9OøâÞ9"ˆEgÚEßÙuAK€ÿ¨èöëtŽÔ°®SþD§üò÷tÊÿ¤SÔAE»*‚ÔbѾí5‚"ˆ»†q±hUiAKM «›~17ï²´rµ²Ò%wʤv ãAÄíã¹kXã ²q±hG×°3Z5Ž’’! ~i ih¨êiˆEõp”‡âm0^r@o ÂM7d¹àŠηg‡m×nºé‹Na{Ì™8ÓÄøtÁ±@|3Ι J³[Þ`À˜ÕžÅÝ‘å…<Aþx„ÒUµ†Ã–— Z{*h+èÀ×o"~ ™¥B ø…OÈF¤˜±Ö Û¼pÈg‚p9Ù(ŽüḅGÑx1x‹7qx‡²XTð+F}•Å $ÅüŽâax‚çÁx€_5á—ë¿]þûºNjÁv~ž˜ÐÄ ÅõÏ£M¶JŸœ€ˆ ^Ú,‚ž±âÔ0AZDš¶jf*‚bé](Ñ#{¾¯-‡kyµª5‚ÜZö¹ª"h½scª±!usÛ‹EýP#è"ÈÇÕš:Aœîḧã+¸Cq :?Öç‡ûA|÷¿ê”ÿ]§üKòotÊÿ£Å¨AƒÛEP^„hAŸA;5tÒJéäM‚èYsDЪž@MÓÈ>—h%Ñ.¢ÓD×µt¹^Ú!²X!п ,‚mZ§¢iêQƒò¼ U-Í_<„|7ÜpÁ5#.µ‡^ð8?X§øè¾³àó?ÿípAÄç¢c~(ÌuZø|²^í&ì7ã„+.¸ãªnùà?^á]ˆƒÔâ&òAsµzÑ[DõïcN¶Nž&ÀÁ™ÓH3a‹û¼pÊWq=·†ânFàép¼ŠÄë(”D¡,ïcP‹ÚXÔÇ¢&UñxϯX”ÆhñÞ¡(ç‘^0^ûã™/ +ÿD—ÿ?ër-¸èŒ#Fð’3497ó«)"諈d! „@ÏÔó̵%vÔº¬‰ ®´žš–SýµX4w +¡wCéU=öµxÛrµ®açÜÕbÑû,ÍÛœ›Ö;5¦’QË"hʹ}üG]Ã5‚A,‚ôˆ×D#"ˆoè©aÄ7tô‹NçAã;u…þ5"ȇÝÁé!œ$â®S|uÊ¡SøF²´“ªo¬çˆ UÎM›Ì-;-mµˆ t7ºÎí㽨Пž¥×‘Tž@5ã¨y +Ñ,¢4¢D§ˆ²µÚ½´Cd±B Hƒ=móÑ:-ãÑ0 +Õ (Æ›p¼ Á“<ðA¾'nq«n'\i/Æ©S†ê”ÒÄØñ]ÇqbG rvØ?ÔRJ¹^´£qØ6'ì3ã˜ç<á…\ÜãÛ‡@5ô¨*ÍÃ`‹…}h6h èÐÁ¯ßAôãÝ"›&„€è^léç°Á »-8æ‰t\÷Çí@Ü ÁãP¼Çë”ÇûᨊD]¹Ÿc ãÑ0 ‰¨ê¨e#‹ÊhÔCýÔá}Jtº—^xä‰+®›qÎ ûõêƒÅ‘"‚ºwÊÜ„€=E@DPO‘þh9,‚¸k‹¾¤‹æ®amë¨y5̧کT5šÊ£é]½ò£Ç>"¨íWdnZoR#‚’õusÚEP§Ô°;¡¸„,Nè„ VœvÆX½ÎQ¶sjßͱâ:,‚8Ñ{NÇAÄ¿þ&5LAj×°Áj êŽöñ1[‰ÿï•ÄÿQù'Ê覌û3¥~‰©qµsó/æ–].m‡,öS®tÉJ9îTàI|ée0•„ÓûXªE­‰fk©aŽˆ ¢â0ɯB@üQë@«`_ +ÛØXMDýXT@YÞDâe(ž¢Ð_A\˜e“–XºZ«ÍÁ„Ž  ¤Sþ¾Ná¢6ã|3Žp:ª»zòÉõÆ]_<ñÇë`T„ a˜V/z͜όæ ÔüwºJ”zá•;žZ‘oF–§ à b~˜ø›5øÔ/ô)*ò™B — ˆê¥P¦‰ î“•®µßFmk©y 5Ì¥Ú)T9ŠÊ£TôÚ›žzÙï²åzÚ2<ÚÎvDý*‚ê碦="¨£F*‚‚‘Å!Á\ÙÏ §ÌcPE§x¬Óžés ~‚ÿ_ÛžÄAËuº¯ˆ N]Ã8müõ05—¼lÞ;ÚÇ/0Žÿ—ÊÄ¿P&ÿ•2õ?*Óÿ‹2óoºÌ"Èîz²Ô¢¢@*JU‘Ô˜@¶qDs~[#¨—ö†,VôcÛ@ka_{’j`š§ n<ªF¡<o£P†§Á(ôUËÝrEŽ“ÚDþ pàˆ P² êPŸEŸ=X#;D7”wˆ ¬Sþ2 Há?éñ‹Qm(ÃÃθá²'r¼p×OYqã°4r™ ­q˜}&ˆ‡­ÿúíC?Þ-²iB@n'0V‹÷ÞÃeÿ͸â†\OܬæÿqHO°z®Š&Î ƒ=¶h´Æ£•›ŒFó8õÕ2üfZÐ Šý=ýï赸 Z/”»ãOÍÈ3!CÃZµDqAݾ#e†B@O@DÐgü¹%<$ÊÕDÐ"Ak:‰ ‘šBoÓ3wû}7ûM7ÛUkÛy×Öã––ý.ÍÛXq §ÆdCýUULD‰#5¬½X´ä§ÖvfÄ-Ft\ñƒoåÉ,‚øVŽEWyåú\ô•C€XMâ®ñ:£k;¢¬ãLóº†qûxNPër!Á·šª˜¤¯T Õ ?´oÚìܺÛl;ìB§-г¢xÌR|g+Cæ(Ãçª"¨&‚šc‰Fq ÕD»µ®a%?B@t+nѾ´öU°-mš§£~ªÇ¢b„V4χà‘îÂ+nšµ^ôQnɤSÂu +Ÿ7v[ÛE'p]hÖÈl~øA°£¼ˆ Œ6þ*‚¸@WùàTŽÿÒIñ­ÜT`¢V hNÇ^ˆïìX­í$‚ÔÔ°öˆ š +ûÄ"¨J1Ô°ZêÔ°ÚÔü‹C™éŒ™2ÌtËB÷Ýéé`*öWæ*cç)Sç+JŠ¢¬W”½D{ˆÎI¥èNdž¼ÝDà0hh3ìk`_û<´(h˜Šš ¨…’xGâùP<æ2AƒQà†ÛÎÈÒµzÑqZ0Ae‚6hù.Ãô§:åÑ)|êàÆaìùóFìpÆˇÆaÙ\ƒšFûà?ªÑ4T²M×juÓ&Êl„€BÀA€ƒºY×â²ÿ&Ü0ãžÏÝQâ…*o4ø¢ÕUïpéþ‘ê ¹Óu'¢m2Ú¦j]'ÃÎ%ýÇ‚þ™ŽAÄCs(ZüÐìzT˜PlD!pد=ðþš $‡¨B ¯Ô«{Ä‘¦‰ nžÕ–LM³¨~"U'RE„&‚¼¨È…šíyf[¶s[º‰EPëA§–ÆæA )zN ëAEŽöñ‘¸3LM »æ¯–ôá$ñ .ºÃZ¯OŽâ‹ GË0AüL.À™|+7˜p\1$H§f}ViA/8"(%±(÷“Ôöñµ ¸X´SãSËfSÛn“ýˆ‰Î™èª‰òœé•ž¢7¾TLõè-Šì㉭Q”sŠR¤ãQBû«WwŠ,\ô#,‚öjÚׂ–¸^´‚Æi¨™ˆŠ1(IÄ«h<ã ÜçzѸiÆu½*‚Ž.Ïeá;G9ŠE³FæóÃÿö[”ªÇz#¶9cŸÇ­jã°lä{á‰7Þø¢ÊuahŠÓDЬ¯?>îGû@6E!ÐCxüÆN× ¸cÂ#[Qá‰z/´yƒÚÃb JžÑ°³šÛTا©EäÔpMõ®£¡£ñê4BSF‘°C[Z£Ù‚:#*ôxÜNjm%G‹ê¡=,‹B@tA݆ò{fäˆ:L´UmžÕ–D³¨–#‚FRY•p±h5"è‘É~ÇdË6ÙÒMmšjÞa䈠Æ"HÏ"¨rÞþÄíãYåÁUAÞ8ëñÝ¡N"ˆܳúEÇ1?,‚¸ÐkGïxBŒÑDÐLͱšéÄíã9Äèº7îøâ!§† Á+î@²1ú÷“õU³ôµ ËŒÍkŒ­[Œ¶=F:j¤óFÊr¢;&zh¡TâC•AÔJ-ñd›ìADô›Ÿ#Ôñæ7–_„€è"# }šâ<¬å°/@ëL4jAïGã]Š£ð|k"莇ÚA>ËðAívA:å“ya®SØ!ó‰‚# ùťƖq#¶˜°×ŒãÜ_˜;˸¡ÀO½ðÖ[A!h‹ ÔÅ'“ ! ¾ ~ÞÇ&?¸oÀsÞ¹ ÖŠV‹ @-ˆÏÜöÅÉ_|6ž;[ V@ +ì¬èÐÿ¥#.ã6Mý“ê‚8†“]Ç ‡Ó{ýÐâ'Ô¯{À%-j”‡‘_]Q~Ö÷Õid! „€è1"‚z õgtžèÑ/DËÉ>—š§SݪI¥1ôfùÓ3A”o´_7¶]6¶ž6¶26ï44m2h"ÈP?WAUãP: +Å xƒÂäkÅ¢A,‚ƹê™À)¿hµ^Yq‰AüLŸoß:bÄ£þ—ïïø¯Ë`ôk Uåx#ßüñ<¯"UTÊõF¦ê«fëk“ô +ôÍk m[ v‡º`¤l#噩ÐJ/<5¨F5'RÛT²/äˆ ¢“ŸóëÇFÈñæ×?È;! ¾@€#‚¸E;׋^{*l‹Ð:KAµP9 +eñjã°šzà«v¿ÙÞAþ”ðÏ' ŽòÕ)î:ŤSþZ§ügòïuÊ_è”ÿS«Í‘„“µ`Âyœ/¦‰ ÍdÆ%3r-Zb‚'J«"¨iˆo@äG! ~ 8-ê›EW{{È®FJš\ÐÆ"ÈÄ'ápÍêp8ž  )šb4Ê¿Sè/uü†ø×\O­J$WŒV õ(kÆéÖªì«$"諈d! „@OÔ“´?³¬ýD›ˆ–’}6µN¦†1TOåÃémùÑSO*4SÞž£·]Ö·Ñ·Ö7ïBÓ&4®BÃb8RÃX•Äëx<ÆÃ„â¦V,šSÃ"è  »õjhÎìpTŠþëöAœ6C»•ãAœ6ê·"ˆ#‚Øí±àˆ>ŽŠ×ÃñNÂû)úêÙúºEúÆåú–µÛfí1Ðq¥èºC¹Ó /UUûSC5¤Öid[D´á3X¾ôñG^ˆ•! >A€E¿vhõ¢Ó`Km6š§¡~ªøƒü0µ³°£qØmnfúÐ8ŒSÃvqbÀ[§¸é'òßtÊÒ)¥Sþµfç Î'eÄÑAKôXÍAFìç¶ÂÜPÆ„›.x`ÅKw¼÷@ã`ع6…ü! „À#®ñsj˜&‚J€:=ZÌhó„Ý4T ìáê@ÊŸ)ÊŸ+Ê¿R”¿P”¿T”¯(ÿ·¢Ñqú0ÍS¥ê‚8:ˆã‚&k¾ˆsĸ¦P„Ôæ‡&OÔ™QaÀ àpZ[~u›D}‘L „€èI"‚z’ög–µY“!š²M ¦TMaTDE>ôÔƒ¸Ðƒ=¶Ëh;ÖChÙ…æMhZ‰†Mq¢ÇX”Àë8<‹†šŠÜ`55,Ý“=uG]±ß; ªrä…q‰AŽAÐëx¬Ï7t,‚Fvˆ ½äH ctÄýWÄAñ,Å,‚âP1Z_5I_«èê›—éÛÖèi³žöê鄞.é)›kYè¡•^zR©ÕúQS(µ&’m +Qòg˜|óÇ¢†¾™|a€àbÑ,‚´ˆ {²*‚Ú¦¨ ‚kF¢"ï4ô8÷ýç…\7\3ã²Aí @³@F¸¾½k<Ÿ7¸k|G!Wc{Ìɤ"hÛŒ8hÀ9=®9©*ž˜Qâ‚: l^bÈ'›)„@¯°h­@øìÍ"¨jÐN½Sþ®2í(3þ‘¢üEùSEù?õ!HüaíÃþgh!”:õÃÍîĵ£9((J­Ä}ǸîtÊÍ(6à®Ö_€¯<’üòf‹ú2ù«B ‡ ˆêaàŸYÜz²/!Û,jO-±TIeTJÏé¡7¸Ó-3eëí—`;…6A;Ѽ¿A•ñj¯—‘x†ü¡ªÊôÇL¤;lU«vl7bc{8QË ãlŽßç…ÐDÛ¡EDG± :éaƒÃÝ…|P„gÃÔÔ°’”AõdÔ+hâ +$Ka_ ÚÚ: U]7ѳ*‚ŠXyS­?µ†-ŽhêghtÏÇ¢†º‡£Ì¥àÔ0®´ö$Øg£u2šÆ 6ïcPŽ×!xˆ>¸37ÜpÕÔ'¼|+ÁÕ>êæ¨*6³½É C³š«WNYíÔZÏŸ7 Ë ÷Œ(2ªeEûBÙ! „@ß'À#ÎÞåLÞ­SÆê”‰Wi´ eÚ¸@P¨–ŸëÈ ãÖ`ðÃa?,‚Xþ,R_ÊYúÆá‚æ‚.hŠfF‡¶H4†¡6•>(uÃ+ó‡Þa|æçѯòôUD2B Çˆê1Ô_[Ð"²+Ô6–Z£¨)„ªƒ¨$€^øQ¡å ¦7Êt¦tMüªã®aSQ=Uq(Ä«p< Ž`Ü +À5_¤{a’‡*‚ö˜±ÕI½§ãÆñ‹ýoÃOöya‰Zï0‡ZaÄ:­}ü^ ŽZUtÅSA\,úA0ž†áUÞ&¢l,ª¦ n–*‚Ú–€Vµ‹ S t.m¦GµLUEP}ª¢P> oƒP䇇\ž5¯;2\qÞ' DÐ-Œ%O +°P«-ÿ‘âB>°Uæô|†áúÒ\žâ²–/Àå#~<²žB@ŸŽÀ'G5™Ãÿ"‹æA¼7£ÎMA­Aj<EkÅŸ9‡s¾>AÉPÒu8úÁq˜» Îãɸ¦ô8´ŽT;?ÖG¡jʃÔâo/­j™ ®GÄå¸ÎÀWŠú*"™@!ÐcDõê.,h ÙGQ[5Qý`zïI¯Ýé©•îY覙2MÜË~¶hÝ– hJEc2êç n +jF«"¨"Åax:÷‚pË×|ÚEë´Žƒ|´ä(:G8?Á™ +LÒ¢€8ŃÃ:‰ ŽÔ0Ž:ꦖb”㥋~€¢¼@YœZu¶v"§£Ç ) ŽÚ +:ÀAFºèLYÊ·Ð ½µR•5y…tFOLòÑ ª')˽E`±:¼·ÏT›·ŒBCj#ð>¥~xí…n(´à¶×LjD*‚ôj AŸ´@|º`i«%“ò9„óÅøÜò À½Æ8š(³ w½…A–+„€øé|4\qüúÉ­ˆÑœ<§÷æÏPæŒ*O4x£%ma°³â~aÜŒ›‚µ‹ n(©Æ‹¦@ÉÐñ¿ì‚øWÎSsÄfƒfÀ6 -J:õ£P‡÷\€«DàÅ ùóɉ¿ãCžùw|K¾ò ØÃ¨%€ê½¨Ê•JÌôÜ™˜è–]åVì:¦·ïGÛ6´®Có +4-BÃ,ÔMFÍ(TÆ¢bJ†à9w‚ÀM\õÅôÁº“8dÅnp7Ÿµõf/ÖÜ2ÌÑ5žŸñÓüŽê@l"ˆŸì|H sÆìqU#‚Îq´€§ê‚îúàIŠƒQ: •QjŽ —iåàa0ðÍæ­KÑ2Òe#Ý0Ò#9Q™™jÜ©¹¯X ßïDÇȪ󿿟F>?7jËà¶D4G£aª‚Q懷ƒP䊧&Ü5"Ç€ËzUæÔj­Õ*NtÎãÓÅh ˆÔ^£ÚÛÇsý±Í]¸ø¹éÉÚ ! ~<ÎãÇûoZ&Ç~r€G&¼vA…'jüÐ0ÍÃÑÆ5Ÿã'Ã>¶Y°Ïm>lI°-†m ”l¿Q]&‚ø¯mGª q†:Ú¬‡Ê‘(‹UŸòÓÀ§Þ¸ï‚Ú#^hWVR\PW(É4B@&ðI Ôö¦g%û«Û4S¥?•¢×®ôÜD÷MtÉ2œè¬‘Žp7.½}+ÚÖ¢e™*‚¸2Oí$TDeŒ*‚ÊðŠ{»s‡w/\„YºÓn8äŠüâ .åÊ÷·øq4 s„Óîìøù~œö”Ÿoôø¯ Ùi©a[ÍØgÁqW\°âª;nR]Ð3ACTT©†´ráAÎ7Ÿ âÔ0NBÙÎM«õtZOW tËHY9Ó;k·!ê©ýÁÁXO­¦,G|#p؇¢5 >¨öÄ;7YðÈFuH8© ì·h½`’ÎåŠÐ|¢`íÃg‰á@(w–¢µOø¯ß¸x™\! T¿fð'ð‡Ÿñí2€ÜØË‚wž¨DM(¢Ðœ Ølã`Ÿ Û Uò´ÎGÛB´%¡m1Ú–A¹©c¤¶˜\¤~Þ2ÍóÐ0u³Q=ï'©bKQƒçaxè‡+nèÕTâÔ®]DýÁ+_B`àpˆ ·½"‚~Û?4çjg*õ¤"7zìJ÷œè¦2 tÖ Š ]zÚ¤·­QË2sMž†™¨›ˆšj¹÷C?<Üîûll¬˜ëª;ï‚cÎØË¥~ŒªZ +p¥èjDs–úàX Ž(fÄ€X-2€k­7a›û-8¡‰ ,wäyà!7ÒéÞ¢b¨š]Òû-̘SÖ:D^Agô”©§<=šèÓÒg¾ÜyÌÖgVJVD|'n+ÜhB¥ïôx©Õ”à‡ÈéZ®ùÀ}yl¿HkÃg >?„ÜP^{}ç"åkB@J óÂñþG×â3ÏùÀc³íÀû0TG£> cÐ4ÍSÔ8ŸÖ9hY€æ$´$£u Z—CÉÓ±â÷Í)hJFCê¢vªæãýl”MCÉx¼— x‰û¸í¡öˆ<¬U“ëʶˆê +%™F!ÀD èÃ൉žé®n‚2AgAG@»@Aiêóš~LÃÁºãQ=ï£PŠ’¼„®xàŠ›®˜ãª;Ëå}ÌØcÂf'¬f¤‡AÑñ|~`ÄøIaü”Ÿ-—ûˆêAz$ꤊ ífpÁ) .[ëŠ{V<·ªKᣳ:¡h†m4ˆSø´à2=­×ÓNmUσ²@-0 bÙøŸ‘?MÞp^ØÏ¸ò²ÎB@^'ð{çßôØOpDË+4á¹§ZÏç]Ê£Q95cÕºŽuSÕÚóдì|– išYÝÑ5­@ÃrÔ/CÝÔ,Fu2*“P±¥óP¢àõdÃÓ‘xü!ÈõÂ%³šMÜÅMÔEP2™B@Dt”Ã}ØA§A‡@;@ÔNÐ\ÇÏÆOs&£a,jP…wÃð:E^xfU×›t\÷õ‚Ž9a“*‚V±D¯¶ ›Ù^#ºsRgypÆ׋žÄAz$fÄ&#v;ሠçL¸jVkÉ>4«}"JÜQ9XuA,‚š95l¬šl®¶åÎDì©vƒŽ.vu` {Y! „€?)ßkŸÞÝn¹½—8ÎÓ€'nxé‡âP¼AéTpŸÉ¨šŽêÙ¨áhŸdUø°ö©gù³õ©P +t5+QŠÊx¿ KQ¶ï’ðf>Šgãåt<™ˆÂ1(ˆÁ­¡ÈöÁyW¤ë¿a¼'.¨w Yº? ‡êüo÷®9Ϲ{g(sûQXÔZqqùõšoaë­Æ£e$bQŽò!(ñÃ+O<·¨}Ò ã,p¹ýZ;Ñ5€³V hš4àt6?ñZÒ[ ®þÊ¿r¤Ðl=RôXiÀ/FU"e¡dB¶ ù&@uA-ñj¾9±âÒ‚© M =ß0$øQÄd¾B@! „€èV¿w>}s(͉½Ç[ì‚\ñØφâe4ŠG dʦ |&Êç bÞ/Aå2T-GÕ +T¥¢* Ê]ÝûU(_…²•(Mûx»¯“ñj^ÌÁ“™(œ‚»cq;9Ãé‹ ®v9"ˆw…ˆ n=efB@ôOýÏGï»kƒEuÉšÏ~­!WcæR<óaŸÛXµDs„Úâ} ýûÌ…ƒoÅbg]–µ‘À^-a|Ô¼0.Ä1?ŽX  Ä +ˆ«pj b4GA« ØlÀ^ƒÚKú’¹ú"ˆ •»£Þ­~°…ª.ˆûÑL÷åÞñò#„€B@ŸŸÀïµÏO´M; 9–û® +Cð8 +ÏG ˆ‹üLÁ[%œê•„wKPºe+PžŠò4Uþ(÷t¥«Q²o×àõj§áÕ2¥àÙB<ž‹ + +¦áö8äÆãZ˜*‚®;«O»ŽEDP×YÉ”B@ Xò§3LJ?ù#ïEýz½ùÝdµE—}ŠZœ§-­œŸåz/ÔXñ΂ç.¸oFŠYwÅç jQGÝ×4­q<âÒ@\ÈÑ&Ì‘Æh¨ÖˆCs+±¹ZÏèÕZ_ßOi„®‘ïŒÇ[Qå†67ˆEw#í›ÏÃzsɲ…€B@Ÿ†ÀïÏÏ>´ÙåöaÜðD~îG¢0ÇãùT)x5¯¡x1^/Û4¼å×J¼]åîͯūux¹/VâÙr—Œ8£™ö9ü`ˆó¸4WŠfÄmÂ8(B³@Á€?0 ˆ¸pOÀ“qv9»#6Hü8邿”îèÕÔÅ.äÏGÌÅ}D~B@! z•ÀïÏ€­œã n®x#k(rcq{ò'àî <˜ÂùjœÏ£%x¼OVáéŸûœ·ŠÿôMÛö­ÓÓÌeâ¾F ‡®¼ßxö5J²>B@! „€èOn7\‘„ŒáȬqÈ™Žsp“³½’q{)nsØÏ*ÜYƒ¼5Pîën¯Â­•¸‘†ÜTd/GÖ2d&ãÊdMÅqȇ!xfý ÄT{h8ÚŸöŸl‹Œ€Cø|äj~ÄGÓaJþÓ7MüåYÉ_û>ž»òŠ êûGƒ¬¡B@!0`Üò<‚¬hdŽBÆ$\UÔ Ÿì$d/Æõ¥Èá°ŸTähî§!;Y+pu92–!#Yó£àöd܃G‘x9è;-ƒwÏHÌþ• B ŸphŸßÿûåÍìºÞéú”_^¢üµïèék®¸ ¾LÈ +! „€†@!pÏ·‡âF rÆ k +2g!c2 # ‹‘¹™¬}V@É×]YŒå¸¶YIȇÛ3Q0ÆáI<ŠüÑf4`ŽÙP! z‰ÀG¨‹kÑEÃÓÅɺ¸P™¬/èiÔ—YȺ ! „€B`àx<òÀƒ!(ˆR Gßä‚?33Ùs‘½@ÊJFö(·u9Ë»·âöpqéÉx<ÏcQâ Û·w +ûˆ´ J?"¿ +! º‘@W$OW¦éÆU’Yõ"¹æö"|Y´B@! ú7V¼ Äãáx0wÇ# +òfªå£ïÌEÞÜY%[W°wçᾂÓðx"žAq4ª}@ßÚFäSÛ,ƒÒOQ‘Ï„€ÝF૞ç«t۪Ȍz›€\s{{Èò…€B@!ÐWTxâõP¼ŒÇÓÑx4§âá4<â×t(çu§áé<Ÿ„—ãðv$ª‚Ñâò‡ÒÁ>Úl—~D~B@t//«ž/ÿµ{×DæÖ‹äjÛ‹ðeÑB@! „€è›šÌ(óûP”Dâm<Þ&¢dJFA9¬+‰ÊXT Ù¹;ƒƒ Mûæñ k%„@"ðÛó…?õ'²-rµ•c@! „€B +ª]ñ£‡Ž?zþ]ÙL™F!Ðï |Nø|îó~d m \mÚ—íB@! „ÀwøÑCÇ=ÿïÞpù¢B Ÿø¤óùä‡ýlÃes˜€\må0B@! „€è":öÀ"º¸±2™B ø½öùý'ý›ÀÀÜ:¹ÎÌý.[-„€B@ï& ÈïF'_B@ô5™Ÿ~íkk+ëÓ-ä:Þ-e&B@! „€8d9pöµl©@gùÓùý@Øö¹rïßûÝ ð€  Læ)À*`3°G#œuB†7¬¸ïŽ—î(„ÚÁhõE[ì㺿Hÿf.['„€B ßd¿ßŲB@ 4þ§ãÍ@#0 ¶W®ãýlw+ÀT`¬æ|XûðkTûûD ­M0X +¬Õc«{M8bÆ ®XqÝùƒQèçCð& Q¨GË(Ð$Ћ (<Wñf&J¢b9ª×¢a3ZwêiŸ‘N›èš™îšé¥ùg$)ë,„€B@|7F~7:ù¢B /Ô—÷N·¬›\Á»cÏ̤5 ¨ôÇ;_Æs<´"Ï×\qÞÇ,ØgÆgìtÂ.#v鱨®å‹q˜ÐFüê…X +qu .½ˆÃ„ XbÂJ 6ºa»'ö{ã˜ÎâÊ\ŲŠÃ«±x3¥sQ‘‚ª•¨Û¨oÜnhÙg²1ÓY+eY龕^Y©Ê½gPÈR„€B@^' ÃÈ^ß²B@A@DРÚwæ)—ï¾³/¾¼&¶D4@}ª#Q1 %CPˆ'¾x0·!Ëéî8eÅ!WtÁ!g2ᇀýÜ Øì¶j=ÂØ­Ó„8}Œóš°ÐŒ¥V¬öÀ/^Øé‹ƒþ8Œ !È ÃHÄàq<ŠF¡x +ÞÎAiо"M_µÞP»ÍظǹåÅ~ÒJéž”ãM÷ý©(€*©uè—7Gþ*„€?%Ò,à§Üo?n¥e$ùãØÊœ…€½H@DP/ÂïEËå» ÿÑEÌA›‚æih˜„ºÑ¨LÄ»XGâEÁÝ ä Ãç|q܇¼pÄG\qÔŒcN8®‘ftØ«Urè Ú ••^aD²ó\‘䎞Xç-~؈#!8ŠKÈŠÂí8ÜOijÑ(žÀÙaúw åK•«ª7›êvšXZŽ»ÙÎzÒºD…¡T4œÞGQkÔÝpù¾B@ôf/Txâ^¢dÊ£ð>Õ#P;Mã@A³@É Õ ½b‡zo?õ%Ë`²ìY! „@7ÔÍ@ûØìäÚÝÇvÈoWgh…:̶-@ë,4LGõd”ÇÛQ(JÀÓ<ŽÛáÈÅ•`œ ÀqvAƒqÜ'¸æ³ N™pÚ€ÓÀ ­Žôáßé ®#´Ê„¥f,²b¾;– ÂJolôÇŽ`ìŠãa871ȉGþ<—ãðfоd¶±,Ùé}š©jƒsí6KÃ^kÓÏÖÓ^ö‹¾tmå…Ó£z@U#¨eÙ7þv“ä7! „€èëòÜë¥>bÈVCC¯FáZ<®Âí1¸7ÆãåD¼ãV’SÑ8Ä1B‹´n’[Dõõ=ûƒÖO“?¬ÌV!ЋDõ"üX´\»{òw.bhˆ›s¥¢m1š¢v.*gâÝTOÄó1x8÷bq+ +Ù¸гCp"'üpr0Nyâ´κༀ³À)M9¢ƒÉb;ôج5ŽOsÁ+¸#É Ë}±6›ƒ±;‡Ãq* +é±ÈJÀ푸?ÏÆéßL0”Ì4–.4•¯p®\o®Þj­ÛãÑxØ«ù¤OÛʦÜáT@OÆÑÛ T3‰Ú&­ùNò5! „€èA'8jÁ!OìñÅž ì ÅîHìÅ8<ÇÆéOMПŸh¼2Ù˜=Å)ošéátÓË™¦w3MU³LMsœh‘‘Öh¯¾WYÕ'È`²OìY ! „@·Ô­8ûÖÌäÂÝ·öGÇÚœñë¨ÖŸ} Z6¢a-ê–£& åóðvЦáÉDŽÅݸk1¸‰3a89§qÆg½pÞ-¸d ]k.8é ÒcŸ^­&½Í ›LXcÁ ++’=10–øbe 6ÁŽPˆÀñ(œEfnŒBÁýãñúWï¦šÊæ™*–:W®¶Tÿâ^»Ó«þ€wÓqÿ–sÁ¶+Céz݉§‡céåz§PÝ,¢9Dû:6NÞ! „@_#°ÝˆMf¬uÇj/¬ôÃÊ`¬ EÚp¬ŽÅÚDlƒMã±m‚~×$Ã¾ÉÆCSNN3¥Ï0gÍ´ÜR\ï*Ö'ŠkÉ,Kíl‹}– -7Óg:):¨¯íä¸>2žüpeÖB@^" "¨—À÷ÄbåÂÝ”¿uy ,]4Ð }Ûa}ó>4oCÓ:Ô§¡r)J“ðz>^ÌÂãix0 ãpc¤±)g#p&ç¸È³.Æ%\vE†32 È.µÐ “\5È€ƒFì1a‡ [ÌXoÁJ7,ñÄo$ùcE Ö…`Ë0ìŽ#Ñ8‡Ë‰È…¼±úÂñ†“Œo§Ëf›*’+S]«×yÔmܰǯép`Ëé¶ô0ûµºC÷GѳIôv&UΣÆ$¢4¢ ßJB¦B@M€;K.6b޳Ü1× }±0 C±0óc0? G#y<–LÔ¯˜d\5Ù´aŠyËTËöé®fXOÌt?§xd*·ÏBÅó•âY¡x6+¶dwÛ3í6þè•—ù÷2¤ì;ûBÖD!Ð-Du ƾ9¹j÷­ýRzh¢|3e›)ÝÙ~Æd;fh;ˆÖhúµëð~Þ-Gq +ž/ÀãYx0 ùqc,®Ž@zÎDá\8·àb .ùâ2—wpÇUd‘d— zœ6⸇MØoÂnglsÁ&W¬qÇr/$yc?–cU6…açpŒÆ‰x\«£qsœþÞDý“ɆâiÆRÅ©|¡ùýRkõ*ÏÚMÞõ;ü7Ÿm=fËN9ÑT0’O W3¨l>Õ¥PÛ2¢]D·ûpY! „ÀÀ&0U)N˜ï‚ÅnHõÂj_¬ Äš¬ Çêh¬ŒGêH,‡Åõ‹&çOvZ0Å9ešKêt×53Ü6ÏôØ¡xP¼N*ƒ/*ÞYŠ÷Åû±â]¢øÔ+Þ KÝmkÌ´×H7¤pЀ8ÈdH9 v³l¤‰€ˆ ~¼·åªÝ‡vn¹½r¥§nT`¥\‹ýª³ý’“íŒÞv-ûP¿U[QºoV£hž%áÑ<ÜŸ‰;S;WÇ }ÎÆâ\$.„!}.s…Oo\õ@¶×MȲõÈÐã’A­¤º “ê‚ö™±Ã‚ÍnXï4/,öÅ|$#u(Ö‡c[$öÅàh<ÎŽÀ•1ÈüIú‡Sõ/§ÞÍ0•ϳ¼Oq¯JóªYï[·Í¿aopӑЖ3ám—"íY1t{=OϧQÉ\ªJ¡¦Dë‰.ö!à²*B@M`*°Ðˆ436X±Å;¼±;»‡`wvEbg¶ÀVN +›€u“ô+'—O1-žj^8Íuþt·”ž+fz­U¼7)ÞÛ߃ŠïiÅÿ²âŸ«ø*þ¯¿êYƒ›’Ü)Õ…ö6æ²õ2¤({Z¶SC@DPÝÕrÉîC{¶Úʽè7=ó¤nö;û gûU£=­§Ñp ÕP¾ ï6ãõZ¼LÅ“%(\ˆ»s79“‘9é£p.£q)WBˆk>ÈöDŽ7œqKš â4±KFÕqC1î/¿ß‚]VluÇO¬Œ¥œ€EÁXª>Þ‰Ý18”€S#‘>Yp{2îOÓ?›a|3Ã\6Ûµ"ɽr¹WõZŸÚÍþõ»‚…6ŸŒh½eËŒ¥ tw=™FÅs©<…êRÉÆ%£å÷!ì²*B@I`0H3b‹3öquhwã.þ8ŒÓ¡85'cp<GFáà8왈“ŒÛ'›¶L1¯ŸjY9Ýmé Ïä™^óïdÅ'Uñ]§ømSü÷)Ç”ÀóJP¶|O ,R|Ëç{Õ§¸ÛÓ8.H\Pÿ?ÎdTÙÿ÷±l¡Œ€ˆ þºÃå’ÝWölC0UÓ»Pz9„Ò=?ºíM×=ì™–¶KNçœj;Ut*ßåT²Å©xÓ‹•NO– “ wçëóf!g®NBúX5ëR,.sÃ÷a¸Œl?äxá†;n¹ ψ<à†^‹ 2â"·•7㘭ØíŽmžØä…5ÞXá‹ä@ÌÆ’P¬ +ÇÆHìàf1 81 +çÇ"“ÓЦàît<ža|5Ã\ª¸–/t¿Ì«jµOÍ&ÿúÁB›G´ž‹¶]‰£œDÊG¦QÑ\*M¦êTj戠D™}»¬‡B`@ˆR€-ztÂn.é†t/dú"ËÙÁÈ +ÅU¾Žp‚\…³ãpj¢þø$ã¡É¦=S\vNµnæ¾aºçª™^Ëï…ŠïÅ?E HS7*A;•àCʳJÈ5%¸@ñ:×»lgcе•ëíé b::ýö5 ¡Ïm´ ,?GF>B@üŒDýŒ{­+ë,×ë®PúáÓ´FS]4UÄÑë8zE…áTB7({°-ӽ岥ᜥæ„åýAKÙn—·[\^m0¿Xmzœêô`‰ñî"}Þ<ä(¸:éqq .%âJ 2#p-׃냛ž¸íŠ;&äC ºnD¦ éÎjgù¶bŸ;vzb³Öy#Í‹Y Ar(R#°> +Ûâ°/Gµ{+9úHŸ?Mÿh†±h¦¹t¦¥|ûû%^U+}j6ú×mnØÚt,¢ål´ír=ÅåØT×ýÓÝvÏðÜ<Ók½âªø¤(~ó•€%0M Þ „ìP†V†žS‚¯*ŠßËYÞ•s=ëR]mkM´ý'tA¢}>u}î3X~ŽŒ|.„€ø ˆú÷ZWÖY®×]¡ôc§±§ÆqT5ÞM¤âÑôŒ»®GQAÝ +¦ë~­Ùƒ3=j/ºWv+?j-Ýçúv»Kñ/æ러r*\a¼»Ø·9squ&Ò§ }<.BF<®F!k®#×7½gE¾3îê‘Ç b\8Ú WL¸`Æi ŽYqÀ»<±e0Ösãx, ÄÂ, +Åò¬Æ–8ìIT³ÎŒÅå úìI†¼©ÆÂéN/f:—Ì´”Ís¯XìU•æS³> n[pÃÞЦ#-g¢Û.%سFÒíñô`:=ŸGoS¨r5®%ú…è””Œþ±•Ì]!ð£uÀ®gÄÿÏÞ›Eµ½ÿ~ý¯JRIn¥’¹ys+u«n¥R·R•Tr_ܺysïwwÓ4MÓ4 2Ïó…[X~ +-v/#À0;‚vº…>«}l²þ,l_ú¡µtá "t$Š~¡oýi§'mu¡û7ê­WëÍ«Mg_˜LOæ*Çï)F2 2äý鲞 úizm'%MǸºDT­u +zˆroT¹¡Æu¶h°Dã4+Ñb€×b´rhk‚*¥x.C¡Ox`Œ;¦È0Ãe5ÎZ⤒m‘h'œsÅUOÜöAŽ?žr|ˆ¤:LÒ)툖öÅɆˆ|<^9yÔtú”zöâÞùë6‹wìW:¯=ußà½5Uþ´1”¶ÇÐÞx:”L§RéÒ9ª¹Bi¥ _š#+`Fào×H‚R¼&úåP`\…qKL[aÜÃÎuÁ¸+Æ<0èƒwè æzB%aÒ–Y}¤¼:JQ£(‰S>!ª{Äô1Ë ê Äò±:JlɾTbw‘ØÞ ûëbbYGÔoˆÙ(1Y"ŠT)Íâþ¦•ßøòo\û®«Ž­-wIY‡Fà‡&À„ ]i~6Yo¿Y7OÒ•ct.‘NÄÓaBßGÒÁ…ƶxjšœ×í—ë­«-柛ϘM=6È6½m<˜¡ì¿¢è¹ ï8£ßšª×tœ«;‚ŠCàcð<eB$_T¹£Æ uvh°B“9^£UŽ×zh^m9IñB†"Cä!G…»¦¸i†+BÖ`Kœ²ÂQ[¶Çq'œqEºnys÷ý¸¼II°¤2Tú2Bÿu”ìm¬lÈÇ*'“L§SÕ³ç÷Î_Ý·˜¹ùóZžÇF±¦"€6„ÐöHÚKèà:y‚.ž¡›—)Í¥´vûá³0Œ#ðƒÈàðXŠR9^ÉÑe„ACLË1eŠ)+LÛaÑsN˜sÅ‚æ<±à‰_Œb,˜ “ô‡I»"ôÛ#e-ÑòÆXê8E)Q>%ª‡Ä4K—5,]&Èúg-Èæ"±¹I¬rÈÞ¢n f=q&1Fëq2zn[£FÿNöa?_áO€-/¿TV$#À0ÛC€ AÛÃý+×Êfê¯ øo‹¿F×.Ò…4:{ŒN$Ó¡Ãô]펠Á´Åw³Écí¥ÓJ½íR•õÝvñ¦ÃÊ=—µ\÷BoÍ ?ZLÛÂio :D§’éR*Õ‰ÃRZõ·tØ Œ#À0_ÀU„ÿöh4B¿ÆŒ0eŒYsÌÚ`Æ‹ÎXsƺÖ<°ì‹Å¬úbÍK˜ á&ÂÅÃ’‘Ò¾(iOŒ¬#Ö ™Èk‰âQ“ÇdO61¿I,/ëÂé´ «Tbu™ìÍ$–ˆOÌ_Å™¾1š‹•i¿íî°ß)?_(+ê`ˈfFàû#À„ ïÏfÑb6S¤¯yËúº|.ž£³§èD +N¢ïâiw,m×´m4û¬6º/×;.VÛÍ=ß7Sh5ýØrâžùÈ=7Uýהݗ ;δž–6¥Hê¢ò0ž¼ˆBz¢ÒÕ^¨uEƒ÷¡Ù­¦xm„ÞˆÑ.D +’ ^ŠJx9 +x¢ÄÜ6Ãu5.Z"Í't[Ã’qÊ…»èÎex‰ïúHùK +‚ô^„JkÃe¯"åo¢ ßÅ TŽ1LQÏœµš»l»xcÿÊ]çµGnÏ<5¼/­ ¤-áÚ òC„N'Ðå㔦Qú€ÒʯI–•Í0Œ#ð™bd¢D©M%Ùk‚ &͵{Áæì°à¬uþY÷olPˆöØ  €&+!Ü|¸x:B2¡7)ŒÖ!-İŽ(ˉªˆ˜æ³{D}ë'-hïQb™D,O‹+D}—¨ó‰Yu¬é›h£"[>$¡W¾ZÈèßÉ>Ìáç7£à½aËËošUÃ0ŒÀ×'À„ ¯Ïxj`3õ6@ÿ¥JͺžMW¯kã'Ïž§gèP +}—L»ãi{ìfkÄú« •&綾…û¹ûf ­µBÐ}õÈÝ=n™ô]Wv_Vtœ7hMÓo:)©?ÆU&âùA¼ˆFyªQ#¤zqGƒ#mñj/ZÍðÚx#Á­¼”¢Z†r)§‚î˜!CK–8c[±G’#R]¸óîÜ5/ñ_ÉCɳ éóýš0ƒæyg”¢?Z9DT£GLÇSÔSg,g/ÛÌgØ/Ýu\}躑ï¡)ñ¦U´9ŒvEÑB§âéJ¥©”Þ£´üì#À0ŒÀW%ð¸­ÀSSÔš¡ËØ´Æ”=fœ°àŽ%¬ù +Gh04aX‚&tëçh·&Y —,„ëÍFèMEKGâ¤BâÈî8ykœ¢(+ˆª˜˜>ÑjA7‰Å%¢>EÔID}”¨Ïj#™=Œ3-U5E+z‰lê DsøË A¿S~¾*GVøÇ`ËËãÄîbFà; À„ ïÀHŸØD6M"°/}»æ)Ý̦ë7èò5:{•Ž_¢CghÿIÚ¬é8´Ñ½Ö²Òä³Tï*Aó/lµBPîÞñêá,³™‚dÜ®è¸ o=£ß”ªW\\•„‡P‹ŠT£ÆuhpF“=^Y£U×*t¢SŠ®­Ýaz¨ÑGÙÏBPŽ îšá†é–8k…“º¬a‰ŽHqáιsW½¸Û¾’½§ú|°¬:TÞ®h4êVÆ©FUã'Ì´BÐ%ëù Û¥;«9Îyî´Ø‹VûÒWÁ´+‚ÄÒ©Ctù¥')ͦ´äKeå1Œ#Àü9džxl† +K¼Þ‹¾}qÀ”3¦<0ëƒÁá'¡ Â!(?Q 1ÐPá8 ;â8ÃÑ(ŽFp›âµHñR´d&V2+ˆ“õÄÉ_ǽŒ3®Œ3)!f‚”­S~.³“Ä,‘ì9AL/ A„âTÏb”UÑŠöXÙPœd)þs… ßÉ>ÌáçÏ ¾ýgÙ"sûmÀZÀ0ŒÀ— À„ /Aqg•ÁæèmµG)ÕÓ͇tý6]ʤ3·èøu:x‰öŸ¦]Ç6;o´Å¬½ +]iô[ªw_¬Ù¯‚l´BPŽÅp¶ù‡Û¦}7TÝW:.¶ž“5–ÖŸW'£ì0Ê*¢PŠÔ{¡Áh¶A‹Ú¶v‡ék=‚^sh’ V' _+ñP…,!^´9®Xâœ5Rm‘l'œpÁYw8ÓGòÀOš + 2¨ +‘7†)Ú#½QÊ8cd:&$³Z¸¾où¶ýÚ§<7Zä©‚ZiO(Š¢3qt5žÒÓ”Þ¥4[ù³ÊF€øQð2䛡ØMûÐáˆwnñ¤/¦‚0†Å(¬Æ`#4V'þÜu@A€&é^om‰BÚÛ6b±+žÕ›ŒÕŒ5è3l×iAÄDØ#ö˜˜Þ%&׈É9¢:NT‰Du&N•«|£(¢LGI{cÅSB-ùó;åç#Ÿb·m7¶ÈÜn °úF€ø2˜ôe8î¤Rؽ­Ö¨£šçT“G×rèâ:MGoÑ+´ï í:¾Ù‘°Þ·Ú¾Òä¿Tï±Pã8_n7[´oæ‰ÕÄCË‘{æîì黩꾦츬h=oД¦_RR}Œ+ODÙATD£2 5¨õA½^:¢I·;¬eÚ”h7@§ïE¢}"b."JÑ‘ÿ""ÿID²MqKý!è° ¹ê„ OI¦·ä¯4ß_¿4PV,o 5lWôF*?Ä)‡Uc'L§ÒÌf/Z.^³YÉ´_»ï¸ùÄ• Bm  ½Át$œÎEÓ8ªÙ‚žl+V9#À0? +{P¼5ûÑì†7ÞèÀH&Ã1ƒ9‚¥ƒXdž þÇ–òsôè ГºCx!œÙR„„{tŠÐúné xî€d2N:§Õ‚^#aXQåC¢¼M”éDyš(“ˆòx¬ÑÅÅhùÓ(ýªH½ön,Z·õìøì#¼e?ß'¶Èü>íÆZÍ0ŒÀï 0!è÷D¾ÿ÷lŽÞ>QÚL5TS@Wóéüc:õ€ŽÞ¦Wiß9MwÊfgâúk²Ú±Ü¸TïµPã<_a?Wb;“o=ñxïÈõ@–Y¦Iw†qÇ£Ö ò¦3²úT½êcâ-!¨<•á¨Ò +AÚ0ANxi‡&+¼2G« +¯åèЃ3õˆD¯E¢—"Q•HÄ‹DUøDäÿ‘'"ÿFDþgùDä¿Öýþ×"ò¿ŠÈÿ."ÿ—ˆüGùÏ:íÈXD,DÄNDnüe¦Ì8K¥º¯6{dcùÄÁú™›íú}M® -öÐ AþZ!h,˜.„ÒØŸ… íÃÏjfFà‡!P£@å>T8£Æ ¯Ð†þ( Çbâ ¦c| ‚ò#):å'ôhèгºÂ[áÒñŸ¡Nsˆ[—,’Ìê´ Y/‘·y=‘¿ †Ïˆá}bxƒ^ †)qòÃ1òÓÑò둲‡R>Bü*C¡X ×9ýNùùaì²ë;Ê™»ÞĬƒŒ#ðƒ`BÐ.34› ·Õ Bæô×”ÖÐͺòŒÎçê„ ;tàšN:¹Ñ™´Ö~pµ%j¥)d©Þw±Æm¡bÿ\©ÝÌ3›‰\«‘‹lóþÛ¦=7TW”m ›Ï4œ”Ö•T$ ìÀOAÕ: -!Hˆݼ¯ÌÐjŒ6C¸u-ôP¥KöÌÏD¢G"Q–H”!·Bê>µG¼Ž9#Í•»ìÎÝô”ÜóÖ{â+-ö—UÉ^†È_‡¾P¼U%žPMžÙ3{I½pÍj%Ó¶ØÛtácÜù#^|š/5€Ï +àóøâX¾4çïüníÿo·ÕR¬ò‹@> h—¢SŽ#¼7Ű%&ì0ãŒE¬úA§ûDüõrýXÈYo¿:ƽhrA¹/jCÐ…ŽèKÀðŒ'cê8fNbþ4–Ó°qúWÊÏ9Ðó @/^Ô½Îl)B‚F$(BG9š(Þ<,Y×[8(9 ˆ"ÿñ‚d­q²Ú8'Ë#²l"»NdgceGcdÇ¢ô/EH³Â%Eº/ ÞýwÂ2Dw|u¬‚í!ÀÖ™ÛÃÕÊ0ŒÀ—&À„ /Mt›Ëcô¶ …Ò7”ÖÒRº\@çŸÐ©:z—\§}4ݧ6:­¿>¼Ö»Ò¶\ï¿Xí¹Pá4ÏÛÍì›È³yh9˜­~w{OO†IgºqÛyEsš¼!E¿&Y¯"ûI +Euj½µ[àFGP³-&hUÀ5AÔ.F+‡—­ô\—Aþ±1î [ÃÌpÕ—E¢4‘è¸H” ^»âg!H¢‚ô+e Áò¶PÞpÅ»8åÐaåøqÕôiÓ¹ ꥫV«·l7³íi®-q¥5´Õ‹öùÐ1_ºä§Ý¶)¤?÷ñüÿB#b#>#»óO œÎé@&¥‡ž(P` Þ •–¨³A³½6¦JŸ †Ü1é…?¬b`#›g ¹š ZÀýiáì$#°t8¡ÙåᨉCÓatEïI ¦bô&Ò0}ó±r ‚à#‚òsYw¤ƒ^Õ‚æ)¼Nn)B[rÐIŽãh’x#A²rH²p@o†H'b¤b¥]qÒæ8iuœ´$Nš'DaB9©›MΈD·D¢§¡¨óC¯V„ÀÔìgW`KÍ]m^Ö9F€øQ0!h—YšÍÎÛjÐJ»)­£/èr1˧“èÈ=:p‹ö_ÖôœÙxsb½ýÈZ땦È冠ÅZï…J—ùv³…6“yV£‚tO+õf˜t¥·Ÿ7j9-oL‘Õ%K«‹ËuÁ¢…A[äk=PïŒ{4 +aB-ðÊ-J¸$Š^K´ž‚T-Ås*«Ä=d +Bç-qÊGmo£Ž8-]‰nˆDÙ"Q®HTä§_ «’·†Ê»#ýÄh0Q9¦‚Λ/_±\¿iC³léZêDk]i›;íó¤c^tÅŸnª9³­ðYå?:ÀðÂápBŒSRœ“á¢×Mp[ûVȵEž» Úžh÷Á[ a4“0›ŒÅSX=ÍeŽÞ–Ð<=Z.¥Íú´“‰B?úÛQýï´Â[4…¡â„„M'Ñ~=çñá+ظ®“}®Asš hn€Þ~g€ +—ÍSP„¶ä Á;HØ5&„:M"·y[= ^ŒÏF‹G¢Å}"Q‡HÔ(UŠD…"ÑýhÉõ(É™½¤pIJw=„{ˆ*/ô¸c5’ A;j°|ùư¥æ—gÊJdFà›`BÐ7Gþu+d³ó×åû7¥ *P¥õt½œ.•Ò¹:ù„Ž> ƒ·é»«šÞóÝ©ëÉ«mñ+Í1Ë/C–j}«\ÊlçJöN=³Ë5z°çý]Uï-e×5Eû%yËYýÆT½º£’ªqá¶²† [Ãj|ð“´/mÐh‰æ=xe ç$Q«žVjë„  + uB +·L‚R­ptßÏB3.¹r7<ÄÙ^’\©àØÿ“K¿Hô&RÑKŒ•£Ç§ÒTóö¬\Qofì¥Y64Ï–òûims¡}nt“®úSÍ¿aÃ.3_‡€p‚hþsHà A‚¥8,G’'LqZsV¸l‹ë¸ë‚‡xêÞO«¬6† = ½‘Šâ«p³‰’å£ÒµÓ²õtùF¦\“£ F´FI{tZòu:ÁJe>À7t‡¢™ *Õih¼ˆ¶Ë\÷ñ»kºŽ±˜ÊÄÜ],ea=š[ºCxqš; Âq4ô–N!ÁGhK ü‚„­d'¡ù_D›ÿ£hã¿­þW¢E‘hR$ˆBw4ZbPƒÒhîq$—Á]  áÒƒãƒr7t92èÓLù=ÞÍ–šß£ÕX›F`gÔ˜¿d¶nØúýe»ð×õ~ÙºXi_››š¿6á¿+_P„­a t½Š.½ sEt*ŽåС,ú>CÓwi£;m½óØZ[üjsÌÊËåZŸ¥*—Å2Ûy^=]d6žo:üHõážQßmÃî yÇeYë9ý¦TiýQ½êIù/B°5L,ú×A‚Ôl —$Q‹T»5¬‘Cµ^B¹ +ÜÛ‚ÌpÞ‚”lƒx;uÀi­„î\¶§$×[¯ÈWZî/x´ËQ„¶^,œW­¦›Ñëjzo/Í·¡Ïmi}íDûé¤']ó§” A7:Øõ/MÀˆd HÎç9œ“à¼çô&Cª!R”8jŠD5­p̧pÞWÜqÓ Y~x„‚”…£.­Q\w´Þ@ŒþD¬|(–•«'UëL63L5Ùf4_MË-ië^:lB×”_º+¬Ê+hÈàZ3$z}·¹Á»ÉÂÄÌäp‹÷$kÙØ¼‹Í,h²¡¹zTø-Y?+B‚$hAÿIDÿƒˆþŸ"úïEô߉4DZy‡°ƒÕ0̆c$}hDC$Ê"ެ0¤‡"5„KÂy_d{ Ì û˜ôi¦üïf«ÍïÑj¬ÍŒ#°3 üµÂókè¯ïüŒÞ1!è3 íØGØÔ¼Ý¦„ NJ›èz ].£óÅt:ŸŽ?¢ÃÙôÃMMÿåÍž4m˜ ¶Ãk¯bV_†¬Ôý$-ð3¥&ÏŒGr•÷úï(tBAë9YSªþ–TAÄQ\ujt1‚„`Ñ[BàôÒfhRÁ9YÔ,Ã+1š8ÔHðBú“t_‰L\„ 5R÷ê„ [$ïÇi'\vÁMw䉷¤ÈGZî'«µÉ»Ãäïcä#ñòÉ£†s©ŠßèBO­h™ }iG;öÓA':ãI7|·›<«ÿ" ÄÇuâè:p ¸Ë!‹Ã1îHp[7å¸n„+ƸdгºalíqÄ 'Üæ‰‹¾¸€»!xާb>R¯&JÚ-댕÷P RNÅ›,%˜m$©5§,ée+z׆æï£ev´ÉžöZÓ™ý?qÖÕ¯CàW>˜¿ù/öcÎßù‘®S{d‹C®\²›ä¤›ô¬›ì²·^†?n";Äÿ ñ'>‡ˆ÷âEˆ;!®„8bGˆ5!„˜¢$¤ZDÅ"í61a˜JHˆ&M +6“±!dŸÅz8æÃ0†÷ax#¸!…¢*…!¸ŒëAH D¢Ÿöo*ËÏ…Ð[{™ôu†Ë+•-8w˜AXsFà»$ð‹Îó§­ÿãÕ/«1!èO±§'Ù¼¼Ý†¶†uPÚB7êèJ](¥3Ïè„&Hˆ¡é¿´ÙszãÍÑõׇÖZ¢VƒWê¼—«—ÊmuBj²Ðh4O1˜cøî®AÏMYçý¶óÒæSz Ç%5‰âŠ\y4¶„ ­­aµ.¨s@½-ö¢Á®'E/Ðd€&=4A+•IQ$ÄÈ5„VRáêd‰dk´Õæ;í¨‚\¹{îâ'ž’boi…~ƒŸ¬5XÖ.{+;(›="[J1X?­ ŒéMSúÀü÷ŸX·;«ÿG!pØ:n! ûÀC (<•"_†|9+ð@‰,]˜ôk–¸dƒ³öHuÄ1W$xà¨NùãB®…áN$r¢¸üII¬´2Nöò ¼íQO¼ÉÀa³ñDËù#6«GméI;zÙžÞu ùN´Ì™6»Ð^{:åB5¡? +zÖÏ&ð12ÎÖ=]äïo\ÆØAô¥ íê3QvW¯æž´ñ¾~Û}y×#ýwy’ÁŒ=OçéÍçê/?’­?Ò["^áØÌÍ} ú4Gç ”R%Ò:mmrŠ Éå…HAÉÐÄc3X ÇD8ÂЂ– Ô¢$üqÓç|ì‰S.¸³¥ÖhÛÄ ßÛkW¾g Î]iVÖ)F€øf~yþBÛùã¥_žú"íJû"å°Bv6/o· !}|3Ýl «Utñ9}J'…Äa·éàUÍ» ›oS7º’ÖÛ®µD®6®Ô{-W9/•Ù.–ZÌ–¨&K FŸÉë¿»'}›©×u]Ò~‰k9ƒÆÔAÕA”Ei¿‡­ñC­jÝPç„:{ÔÛ Þ fpKÑ +A/uBP£ qx¡‡Brå¸g„[*\1Å9sœ´D’ê’ȧ9 Ý ·\¸û®â“®IÖ‹°YúTƒžè¡‡Úmb¤A¤ ½8Zp +"é„ zM$–"0ŽÁ0¼ Áë4úâ…ò|pÇ —ÜqÌ'iÞu&íÜ‘ó[Æœ_&+Š`~dT{¶h|êùÏ`È„ Ï€¶3a“òΰ‹ 5ÒÍFºZIKèl¼OGoÒÁËš÷g7{OntYo? ‚‚´AU.Kev‹%–sÅ&SÅò±BÉPžø}×{Ý7Ðq­gД‚ú#¨>€ò(T£Æu¨sAý–;Ôh0…Û Q½u¨“¢ŽC^‚gúx$G–7ŒqÙgÌpÂB,å.wXš=Ò…Õ»÷ÀEœï&)õ”TyKšü$íAÒÞ0éP´tò€Þb¢d󨔞’ÑtCzGù“TgF»Mé¨,Åæ7Ø÷]øo®±7ŒÀg¨jÇsàÞf€” L_ý¥-´mZ%x%E£ †¨U¢R…²=(U£Ðy6ȱÃ]Gd¸à²;Îz㤒ƒŠ8ƒ+·ˆä>‘åÃb¢¬ ¦ DÝoÙyĦï˜ý`ŠÓøi—¹s®+—Ü5×Â&åa!Xô+ª©¢kBâ°":—K§²éXºHß§iúNltÿ™Tj9_d2]$/Œäc ýwГÎKh;ƒæh8‚š¨ˆDy0ª…HÑn¨×¹ÕíC­j-P³Î)¢j#TÉQ©J1Êb ò¤x`€Û +\Sâ‚ N™á˜ –ˆ·Âqa³Œ-®Úã¶rœ¹§®ï.®ñ’´øHzü%‚%ã’ù8n-žÓ“Ð4}zÅÞ6¦¹*úBI[è;]Tý s¦ ý vùotÈÐ.C³ª”(5oŒrcÔžo +´B¸Ú­‡~N{¼ÕC· oäèP M‰f­›\µÊ­PºÏìñØ ÷\qËW}pÞ©ÁHCB$NDsgã¸t¢w‹ÈîE1.!¦UDÝH¬ÚÙv'îwÔy8Åuê´ûüÏ•+^›7}hŽ/-ñ§õþ´Ë›Ž¹ÓÕ€¿é»Ì|Q«‰˜:Û躯×òPðR–çšV?3yY¬jå;K{JTïŠMKTc¥Æ3¥ÊÅbãåÅJ±ÁZ±t£˜´ à´å$ø=iÑ»º$bB¤ !}Ø/Añ q X Á\ Æý0胷xíªý2¢Hø›rÀ[¤Øà¸%2÷ X΄ /jé][vîlû°Ö1ŒÀ÷Aà ;Ÿzþ3zË„ Ï€¶3a3òޱK+¥åtƒ§+…tá1¹K'®Ó‘ tà”¦ÿØfOâFçõ¶Èµæ Õï•—å +»¥ç–‹{fŸ*'ŸŒ>’ ÞÇ»Û轆®‹h?–chL@]ª"Pˆ*oÑìQg‹ZkÔX¢JÊ=pL•+ñÂP›,ì¹

StLRn6Ay%@0ipbPF@#Zw|DEE^?k4~@-WA8NU%<5;i+uyRcdgQU#j?B`a763 zA^TVF?@#ULdFvw^EB!xRzAS*^;eH^Azr!c*`7(O1;Z!H-^21{DKb_UgY4Pu_e!DMb zUu4b|u99Zt!{y6Hz9;xBi7c)NRtlyHe2-5aZrb-4aeLjlmHvcRbE3gp()j@Yo?7T? zZ{&gUG9O)Z%|9lv`h@Yd;I3`fFvhTGd2>0styI9_lgg)`C(wmFifIaViJZ63H*t4a z+26+PlxLEr3379U3jBhurG~@*lUou+3hQ}`ceNbM=hZjXZ%+hgG?-p>dRA@pKELQ@ z)Y#PvnTQ1D1@@jtyv8rT>&{O%I}36+X}xsmJ#qi`n!aE6wGSci=*i@nbNj9<@bK$f z9vNIL;?o63-={azO|g@}?bkV^DlAip$$MZ%y5_PXj4=c7+y*Fot zE9NubqU;hPI;1(@(jFVs2N7nfW?1D~O-Te475tp&BAKuUWukAi< zuBIT!@445`a%||2)7)v6gwl3ppU~6toy(E+@xg+h!)19z%yvzm#9i=f(X-XfNYcrf z`h$8}LA-?DXOx%gj|?uhzkc3_{eAwwh12){e>kQ3Kf@`n;Crh7ul+wm==zqSve$+j zZr`ciPO@R+IQbMBFLA})&QLmwX6m?{@R_ipizJndBq9hAuwiC?yFd2_;1x9JhL|GR zGej@*Pc9lLd8zJxy}O%MZ)EN76c-Y+3YLFwX{>Siw4AbtH>;x*u)=#uWTsLMZ*^w2 zbjVV#cNi8H#FI4-Jhzu?vN@kNS1!;Ly!gHbD*qe2MF~c|i;_o{lu<~~j>bpp{pfN1 zjDi}5|9$dUXG-JSv`=n6yTVQ{r`kV+H`42=TnFjT>qV{xR{2s&8oTfJ^{Im??CefH z>ymzmQh(SOOU2pipKy_Hs$GzMlIQt0WyWk155JkbG4H8He#8}Sr1)9wR79R|gXb%u zB8hGrPMS^X4B7Ze*n{iLsH)n;d*$s8uT34r$HZS=?D{)|A7xpP*^q82a>KbVBD>80 z4Tix7X)QbC>i8CRw9+P-1_coM{-DMwK~*5t!rveX^DD=WDYcwRHRCSdutt`Xd=Sy z(NC;&iDi6qh;IJhWU$1P3kko|w_3?OFZvJWCf#MZ-o2wNNEo~)p*SbtI7_2pa!ZUb z(smjX880Vx$sN7uZ&Snkr^0_K*)yJg9;W+~A}TP=AN_lI`n^@wCggH2r@ETOe=`{) z+SICRg8*8RsX641IXxSjZo7_1LgjLBYR3at#yQ0sZRKaoT~AN@?3xLmXo3eOL^glVM2Zscb> z4?}`lc&p8r+IjnzS?HR?n#dVy2+B@m_jS#;+vz7R=Ze9|PGUZRM4f}fn&ntJjIL&^ zD(@At*e253mI|<=_6uivZ|Ma-CUU@-Xj)_^&V3J%HGY~R*+XL!d$Rr>GnlJW(FYSq zOEX~}Ng4}LW@08=$OPmmnuX4xop2&Cu?#)KU$(2)o2af`tfeBlEj!82OH(J@n1GGYxz#(#k2Mt_j*g3FDpqsj;+ zxA-36-aLS_XgZEV?vhA9r`W-#zGInbDIhkl;$u?qi;z5~$#mGeUiEny4HE?)-9K|8 zbD&^T^kiNLye0W_<7<7vMmh<~`(%|~^eZt;g3J|3tx(b=BdL-|WL3tK7R6oYi29?j z56v)hxuDGfk07zzp$ym!Cv{a*a2`fAoJ=Ip(X(MB7s_c?|Gdt#1g{js}1 z7NdFZ^$Z98XL--h=)1vV;rp&_J=xeqv_k5@i%U%;6luUzDWWCsH@k|j^wM~o20PJ_oY=$i$ zAzhSd_S?~DE=}Hq5ab}X4ctb$oVWC_sBUH7o!~!(I-h;C{$l?_ELnRG; zv*U^aA8fuy*y*ep+5L$tLq+Xwl5?w({;Sdp92KJ%#!Z!ToXIONfl<#{T09^hcl>>_ zk2$xS8cqxwF-TRV%R8^C>UFMJ;aKmC&jsicLTr8Gcy={azSn~Ftflqwx(VLuo)`Y` zr3!s^07~LUSAWT9Oc~W2a#hq&_Df3iK4m_B-0d|YLU++Y+ObK_wb%KT-_VAvo6=#X zOkv=7Kd-db%#TrBzdAlKV11m3cKgQNWTjwmr{ekjK!~+Ln&@-IT%5|@t3=r?hA-m> z@4}bQQt1X3&r{w3v|AP44XEx>oe7Tg>2vJjI*4npQZPuTF-pi zRY8@0+(i}9bUPd7D#V=N$3){4*^c9flBbeV^@zsBFO-c9{puce&r>crzbrl+{dT(a zMBj_4Yfe;9k85M}J;;^-jNkPa?LIC06ZA800Bk zkdgXAYI1lT|36VP?*D_DeR8*lsDqk{hL$EqPKd0k&W28Zj!4-#*dVfsiP^c4>99f0 z=jLW-0RRAG9DIPk-t{014synyU$Y~!%7dI7EFfpHL(XI)`|}DpL&e0=&e_4p#1SG( z0wBjBvgE&IO3r`tKr*ubI}>Ew;`qe&Mob)5kMk|8p6uJ8EnODxNnLSO*c7iyQIH zckzF}eC*?nDQQ7c`l=`sL??l1Y4p`%M89gAu! zYUm5+O*lSds>Hf-s8%ey_S3gQh9Y1M*U27f^BMw+^V;&Gy7Y5B!ii28GZKMXxe5t1 zir*#)1wAlxY2JQ(Z&J(NVbJXv_NmB7Kx}pCe=6|gE?}|7F&%aFl ze`^DOT#Cr5VPOo>&)K;-0f?+0Of1aIoyY*Z9EhyqcGh+ds`elw6NsaD{~b3ACr2d{ z2XQ+adplbbTPHHU|GTe_mbIMJwmWa{oewG;T{@g6bPA-RlnYo6icSuS4)R$J@=rP$ z8NK1j5y%74#W1z8F(j4H1Fk9%8$*eCK1Wbc{6K(#7y5vf7czD0eOPWL-$>NxY1dSX zP2q*_Xk1=yS_u%bVo~3*d(L^qlzdSYg@VOW`sd{zANh`{OQvb}}Yeqyfj+Zgl7aEc7?=M_JenDq|_P3ZDSmtDcu#>&$cu+=b?r!9r*VK5V zulzVteM)#Ftnzj_OBDY@VEnq!OG4&93d>*E#%sh!Dsa%Dx`<6+isfmnqqrfh1l_KS zr$Vc4QtQJ14m>h{FBixQ;&>V;eU|(mI(n`JJQtN#a$h--@Wgr+k^The6OVWuUdFI2 zJx!4t?EoCUSG+NS7Xs&J8n3r?Uvzt`)<^7Tiosl1Cp^TRJgAlgRaH89|7qe9)?B){ zH-SL{GBeG%u`~m!* z)LJk|pB0EO$0JT%E>TtfC-*Js_;KD_(;Hi07~r0R*-x=9W!MWM@TN0y5#5=$#N6eE zw=bd4vqY}TD$6e|o{ebB;_n}?F3K=Gs>aiXJkn0 zp)%HL66R;ezJ4|TP(wK|A?IRJCy*hebu?T=&Z=inUlZy~U2ZvCtNybgzZ1J`WPU3C znEHrytGy6-yN7*i@t+s(!D{{yJjlWGsk$1)KZf&)%iF^4t$cSgLb}ni7gz3iAkt|}+n!phdJLKnegY{#|pP5<9U}6DLUA?wG zyw!!N%G5@HrwOD1kk;13z4}bzbkgu2y<>^c50iObc{rS*vtr}YrCnp(N-ff6^h_q( zuCENcU2h_hqbP}^EcG;8Q~Ub?G|yHIcZwe1=#~A|Vr)}MI0TXJXQcS}JZWj~JG(qvC&d=t@N0!|v%D>;3-tiLrxTGd=ev#wsThCtN9~odE*<)Bde!FWqqs zwXttsS>&J$CLTB%lWL14J@l)maQD1Oa1oo8zC%_Nz;W!1aaix(?71N<|T$yCL$l1aQPUDx%kZYm-?^p#S>-_}6%d7Tlf0 zvyb1#Gh1EFY2doPS=qjvl+wypi&VhR*%{2sf36QFj8Ye-#$FXafL+dDCZ3AXndm)0 zWHGT1&9V({@f{7)W!Z2*0HM~_C1sZGNYF+*6`X@^t_^=1|`*7HwEXhk+$FQ z#m4JpReH^k`ca^^GWb60z7$Ed?c7vj&=urnCgr+QNI>Jf@r>%FKK@&6tjhQ!Y}x3% z=3unS4X$H-DCc-{=46toF8ziKyM|25T)LwTVA&5d3-BXrkd0o`&P8arv3Q;@);U0n zn~NCgSJdZyI`t^SXYbj3LEuLN)wyFQEPp(1XG%xwj%pXmHWKqlN zG~*3zVEZ^dx+cxb{T@tgP!zRYs-O&WFop9O$@V5GP=aKdKNuN z?<*5AX5A}^i}}I%jM5}Ba6nH|Gc$w6YsIFw+Pr~kc{t`U&IOwM=}AWSUx;)DtBt7O zg24{(DLGUJMmSDYF~~Uve?#16G#HX~Z4?b{$4<%Cc#tA_Mn(;POrh48B0Fa#tOu@s zPz@Viw!i)qu}60wSZ}J}3{Q{*PC~JllMO~{=(Y>ZZ7Il;%ziSV#O>`Y&HGEtu>G+9 zLcCI+Qj1TScAKI}E0L*czNgtR#P#s`~+3${r^;b&dv&ZqpeaKX#s(g{% zSm>hu0aT(-(E-;mn=Lw)at^gQZh;6qp8@a-{A*SIx$I!{D?y#X8Y3<^DF+9|riaA8A$PYo6`L<%NApS=qYdD9ctPP2v#E~bEOs?hOpumW#zq7cDUCbj@a4x~ zYW&!(bE+7ceH8M`ecWBKXYxdZU%g~*ET|D;h*$6B{BPG)??zq<41hHDXLlj;g1mkYTX*WAc=#a(mV z%;$VxOHi3c&TVvX8bR(>vkit;^lcFU z&HgZSnC(|Qm}gI$Jq#=cf0j>!*g(AvvOQ%~!HMk7Be(R5xASbF4dN|A@Y>wb*COwL zQM`=)V(3@(z^T)7%Ql6-_o+^tRJp77)3Hv@J=fW~$72I*QOekG3)Pe-E^Vc$1CnDl zgTLLq()-%x+v5jPnSza{MFtY+vt`cZ;(>Xh@KU1iK7+syUj~QNM60^3z=&50OIqgq zV_~YfYSmCK-B6pkj}LdPA}%Km+##iNKjVV3QkDCD60DSeoFot_$21bSkda8Y3mYtWpeXcSN}W64Rz9VhBX2z zO)$gI{vBofeln1Ckoc?k9VS0~(ED6AoTG6!hngu>2x@raDDvXa5bK~Ga?B+TL|da8 zgDE2F0NFoQl5m%4TPXdk@^T!hbr$NH-*O6EfQy}6_s)s&SK`=--CEw-xqcq80Z!Gb zm)i^{zjwg}SI1()?vw2~tUwS<3B&0d_U?i`4GfT*=y)PedTupiSuq~fKU*FSXcb&* z$R{hU!kcblq{$hLGFj)$)FuTshbazm_yq>JUa35g{XOaezdQE`%tBGtCp=cTB>cXtM>^v#t0OapGX-w}-IH-^@M?YJ0 z=s{yq64Nt2GH; z0)e_Z%8XJiz2SJoo#b;hdeWw~Wic9@Gecp@i<0r}G@^GVoLmuc^n*osIdU3ML0Ego z&3Ck0BB~o_yO?)GouR6^X?X%l?;`3n<3?Lety%K(0)4skSkdS@MW! zOB71_5|A)@FPQzHdOTBriK}DZNo~f!r!{aMO>`o&*>`lDgzDcYG*IMM?isBnuE~?w z8Veg`xQ#a(Wpv3$Fj#FzH5BaFnM~N>UHtSb0#bqd_c^-=2A}9BMXnTc0_7#*y%1&H zs%=XVmfJ14)Q%EDPyV_F%EMAEl7$s@wz5o%LOJ@KV=;Y;!Di^-9Zt5G9su&F=_i~` zF~r1;U&bC}nt0GSJFrOCBIK_KZ+nUc?kAB`vp34*OpV!DLk3!y?2?7$SMX$*80Pen zZ2LUFV$!xcG{WI}7U^J1stY`A1zrB8A+u+@QmFd;g|M@HD}aGUoxL)A-Nro+vhHD; zZV&CYm)_u$N-|DeQKw zFl`iyN#UO9YF^-FkERmof8QvS)0btZPgC#{BUk$1*9&vbOPR|i?^Obw4qMkZDQCLF zQS1wuKr8pRzUN7qQ5rtEIXWF%Cm}i=-e1Y|iDy)Fq?8Ncnz~#n@@5ip({XL(6N*`h zcQCCtwIrlbyAUG`R%fg9*U-6C0FWlJcO(J^eqz_u0tnNmV<$UxQFrY*7_(rnpPLqn zrKl!w99jbtD){t=r!7%~ds3I@mlJ|ltWQQCpvu3Q43H%YN-uv-MgtwQ@t~SLvfUtW ze@CA{-Z&`e6nMECGN8Z++U|M0C1&zJ<75Jz_`;!e3#tFt1ZIr|LeVN@q%Py9afkQb z=CiR_6Nw=2jQBb|IkeJ-keIrSdgxqh4$L!swF^!mLajN6i zbW&$5Rtq^5R)T!YlNS?=6zwnQCy=)`9Ce9D(E7p#-J@ZaN&_Zgr7pvT5pL}P7J*Da_U2=cHU3!i?wm;IW<%!b zP?Qq)Zr7vunkkXf;qG&ds!t29BM2lY-Cav1tI9NNXhAc|p^5P&sP%3JMB+u5692L- z{w)88O8UWRkYT(&ragDLhxoWPZscufnSAdUeY3e$mx!@RRspF1pgWyMh6WaC;s5&|M&*yKUGST?z4mJGfc+?tARj{gjf*i zqoJqqFF{gN6{k7r@@YKk=}>3f|Ai(|gW)U}iAYXrQFXfZ6PG{|2`*329!mah*gMSY zZ52|5>m8-k`n@!HeaHej?4?6|uW!wOL)A`?CdK5<1YV9_42@Ww4ai^bv`u7gDfo zMj{V5Ap3<+n+@-I=l|Y76`XXaAjQpIbF)JglyX^=(KTQHcUlx!HIdkR?vX2MvZ!s1gmn1ZF5nRnmj>+4@mqK+M5+CXdOFjs zB_&k23EGFent3>%NO*KT>rDTo$DmJ*{x}c)yso&#?R2H>twcCES5H5L9y#T`6)71n!O)qsN+$)Nsj8W`w1mw zF%|lGpzLhz1=7-g_P>0}z?;NC@6A+N!Bok8AWGgX_AIVq0LkN9>C{wWucp)q{|pK) zr06I|`i)!H7|IP>KBjPsfe2Q*Qy?D`2H>w$bM5sAO)Wb@BCzI%b9Y$3OEXl}@q&tu z;(zjHJcMp)3nrSnAWLg{q1+s#&c%uC9Um!HI4-*n2JyagpuaLZ>6=zczNA|u0qLP7 zJDUJe>L3$i0pU_P*M5{JrNNZ1LqS3BfCY$d!Z|4yZp?Vzi4k7dYzFc3+#_<-B-j{cXvo15 z+Kkp=-G;>nvg>LyMo~)+kSoXB;;C+Uy%mU7DGKkh69SA&+iz`V^InN%8ZM>4en11HulJ2f5nI@;BF)K)rmwanMYC5PQV2-IEV zyYP9P3-XX21;Fj;vdr>+BufFuq(|-v!$JBXY+A-8y9huf@Az%4a%6G(KCZYtR$WG( z#JU>p48|Xvu-4yd83M<1pmqrR?4ZsgH>_Uoe?H zIzD|w6;96X@VM+N-|va99IFDE!WF5p7sfY@x>rQv%HV1BpPBAE-#qiz$MM@>gEq=-K@bVwwdQ938b)tuvrh5sV!6%Ub>&mUhq}4 z_zA`z;=v#Fm5u*rso#ntSXRD*d@FI=$JBL136cds`Gy8t9O{*XvY1dT~%ktOc3mlSwjO-e3 zjD|Rmh~+lnqa(NPWHUViI8PnEAf^a!A2`{Lg(LYTqgRk=OV@v&Sub+-YT*Wwad9F@ zB4K{U6GST57`5wt1Ph6qdlClA1@qBmW`%IHC^Uqfb!xt~0_oxL;XJ@^7wx83q3Jp5 zRDTV`&f_mpYZcAUi+nEJZ~Q^QXuk{H6e6~MaeB|Xl|u@dXpr9{zg~tY>=R!8=$V-P z;qr=U*BB4u@sRpA74TZZ)H$Q4;B zkXYrkF8*N4R8EUXl=u8KpN_}*vpCb~L~rF-CCCF#_}fN@3{BFd3cgV|{=(DHi6|H_ zwFqb@9r3H(aLC14HD;r|H?qog;~NXNXF*qR?gQB25i5y$vpa7yRT^s1ss}-|E1nzB z;mlEq$*B^7GnUQ0uEHEM>c{im=Jso|1+jtcIJ4i> zFjZ#Bte64bl@SqEC9=Fi?~`=S5KxJZw6t74aD^UpWL%Pt)S?tBcc{YjU4}QMaulRR zQigQb>1zXfG_m_3819MrGwTx$bknX_*T92qg^{3K*r=aa%-&hf>jPGXoX(R5a;~5dO;6h?JMvL;#K7dE<+9pWuNPiYELT7;7$ z`T(4vM$dpVDgn>Bd*xX{Id9j_!;x}=&b@AFwf4o}u$P z^EKo_(fs+k38z^I>!COzNIz=mLog+PDsvrgg@|T!6eRtfQ>VJggntV`c`{E1wQ1A- z+J{AYAx?k6;VVjrj$=vW;Coc8TGpK97B1sjdP+S3+*$k;n$sS>fZWvwI(zSbwQTkO z-LeDz%greX(K+REcNoO_9+BxRb+=7=z5w ziA}!@o4WIq)oNvphVL-heAFXMt~YbXRTmk%UB`c{ImUNEH9dtV7y=tZ579at=uIeW zKke$K_x!SJIVV=e!)**UXH@>+cY_i1aq6j9Gy&HQp1+q8?59L$1Rtiv_X|}GGp!*k z>|Ejl=t%QJ$jVDiG)3m_N+!5!_%w~sEeCNa8|isO5BYvf_FVM4QY&WfSk%Wx(;u;; zC(t(yYohca+J%nU1xZ9@GOofRE5a}MEUUT;4(;)q*hGw*=IkLEj*v%_0Y}5e(t`W? znr3*q`021gO=Fy7v>*zB7kE8(t6KKJ^#L{@^&8t9Nq zv;u!gVR8;kWu+e@$k`Z07R%T}hZ(fIY7knYoGEr5GxwJ@iGl_`!>EFZV4AX?VK5?=}e1!hFKq8`8h`4uc`b=4VG_k=l zcAR*E^=z?+wH(Yl>fU0~s(Mwu6N!2mw0+@$V`qA9y93dV*$n3LB@EpuYIeG06JJsm z+|#^L26~$phvRh*#9Q>nLqszDyp#Ol~lp1lP*`ZS^${5blG{B4_HAoO@m=bA8wgNux2WPM7#yNGAJsZBw*Ot@*FFS^HTtviWj7V3gCHL;9a2+2v}b&flcy@8 ze$R;+))FR>%E}~%vt+1bs6d1LsxBas0_)B+R$S>zoyV<2KAKTi9yn0(t*oe%lM$i> zxV3g#e+fPgnCFi7-sI!+qpSiyF)MUT&d0Qz!KQRUSnNf}DMx-`UOqkNLMHa{L^MHN z0p_>8Qf#c-yVQ&QQ_*g+J=7_$4+)qM_-u8Tlb$|vi*9EV&`;g6dTTxTSrI1+Ks3B7 zK~5XNr#F_CoXNQBMac5Wp#~+TSEXlQ_FQFRz=0(Z+?jaE%%{;kPc&idz%Yz4_f}`) z8=Tk(7v)JO3C#{;6J5zLF}`i=UmAJ09g{uh%DpFJhx_5N$m@!bo&IZCZI*%aZjO(> zotmhhCrx#Xxe2^~sOfuoa*wDoRtFGQaWL2kJ&GLupzlU{ekveI?^_v20j?;7tR()H z!L1+?A*_E-!cdcfohQzXKF*DDKmgw>cB_CYhk9n&R=nlQo{fqi9R|PTjpEw@iN<+e+>&&};K{zyq*Wc@P8 zCnw9#Q;J1-H7-UsvkbmW=FAJ)sX&~`3Q1MMN^rh#z!Qv2YoiK|pU}?DCZH^9%?Gtg z7%EV(3&q{>#ieF`2z>EO5;Yw@aI8!uy8yQMP+nBz^H)Etpc_GkbeXlPe9 zuf`Ro4W8%dJ-{5=Y2iGkQj2v39q!ZX{(GMkoVYhv5?WyqpJbo{at#o6mS5SRjW+g| z#VyQ@D8LMHd^sOkM6#9;~=#Fd|#&d$vo!+?gLma0gbsRoQ#`@Q`B(8l^lN0v@Fs%2NTkyaMn<7 zM&SR-T!(0z+ev>7*|(d~Svma`KylSj9pKcG+>QxmaIklZ;_YjR-dv_6v!-rud@_^G zKz<|B@%M1s@{{3P#p-j5#@SjUKF>ji&(I+Tn{yf9fZT7ocbTJ{&B6jJJ0`T~w8? zw_${@>7g%)p)W)INxe=#9XnDFsrS!lB}939RYs!DteR^>t%7tXcRg5s*S4hhP`^;X zFTgN@^aWk#2+z5^s7-;d{jxjae{$C(ntlfFFP`Eb1*?5enxTEz{Mg10MqeYnZMQ|> z9%{;X7fDRT@#@vY^+NdIOSd)=X_^cT={I%QN@FqZ1#|is)8s}zXut$*JmtUuO+eORiBsvy=Sy2BI?r0=J@XusUqh3)ysESdM9QJ=qu z1Fru*4AQk4ycUEkluJ3_-26Q!BzU4+a^px0Ar;gCTw&G&u$oh#-vMt`R(D^rV1v6C&m;xCy-F76k=uIN*!f5_ zt^*gc%Z8oWF~zdcuLH++Lwpn^UgJVvbT;N+OFA${{5Jm7vLH2?f+>d^7X5RlDCv+< z+O#mR{Bv2?iQxmLJs|Z26Rc%r8h>SMnqy$U2p`zo?lxXSy9ly)l`=IGGo@ZQpX zWh94B@4i;nB^ulZ5)q4TCLEyxm0Wp#R_DKsSYU69-^cb^3Lh?%V>0z}l)_;XjHv<0 zec!movZIA$hr?yB`c}8rb=Kk+`ZJMx%R!Eg@Yul1jqqG2^iL!H9N90cmbi_ej{?cR zt4rYyJ!;NBHlpUP18ySMy7^EQ*X|B8Jt7=W!TXez-VbN^DEEZZ1LKV{;E69jp3WtIUn-e#5FDC1Pml6Hd`>}!Riy>@k z-thh;Jn*e{XmqY}e~5=IWb4d@OHSV9DCSE5gouzLK2hD@-#;owc*1myq4l+JrE%&v7Px;RaBWun#~IKKMc+NOsSZx zHnQi3whOW|XWtFv=F7phd)9yF6MShYr%xDuM)i7X+sZqh>KEMLI;pg4XC@C_{U4W8kpUZq6ZSPD7pl z4F9aEVSoKI^PY$xhDz=zIAf0yQmye(5#NO;A|Z`P7ECwXNd+RPMM0-1f;2g=$1{CF zt}(JbUXN?ts6PZFfbr}WI;YF^Ie>9Ho6+75_RIUnCH|(TZ5?dhi0EL)!sNQQd@Csd zF*Um&g4Wt^LS?0zy2DGeUTTB1h3&un!-67NKYwEBtHaMQ6ytbqIMrbToWNs9g)C?C zF~I;=Y3_Lv<^f|9W(wqv+H6gU?j~bam|?zezBX;3C_(68 zupP0Znt~PU+G8_h{K^HonjO#2wE-(n^|<-Y?HjlD?uvy+XkE$v6wWH?AmGR`)wNYv z%?pzqZ}}N13#&V_=|y7Z@M9*5czi<%2TtWkp@uqu`(rXy8m7-4q}XZwEEXHsH9fj( z`G-M}82fdl-9L>pk{VOr>iM-XpCxSV^146#4wC{Ky}^9|Zy=!F7@mrAIhm>o%zmo< z>hE5WsytFW(EdA<7cn(gD2A|wbsxE%RI7nC za;6q(8?36kP8gsSCowRB!1{g+sQletq#B^kgeJx@RHKMxT2J!-F28Rc|!?sUGh-^FVF z4J{JpZJWjava`q?Z2l(Y(Y^>*ngnF$N?`c|IJJOyFq*a+pEls7-VX;WH?mnsBvp); zEO%?{hN15l28K-BCb|Hwns~&s`8@2L!@TsJ!=~yib%=M3fK{AJ8(GtoVn%-)jhb2^ zt2U)apI@^tA`Od=wU_ue!qR^Uh@1T|6YUcNye%AQWu%Ta9v&xmgb}@oAh6^VPrkQ= zbl3!+)|}lJy5`zVNWCU zzG29LFK+Z(yVDwG@(k=1K_cI;%$cA}hAjzl=?rj*?_2kyaT5(x6fNr!L;3Irs#WS4 z=KZ2UQt^hVX|lbO&VJ#HKYh@f>8~b4+qE(za8gNcZwJ#mynZ~oycDXPFWr0wKSZ)2 zitFO?Syg8?N!1`Z``|Exq6qr}L}E9{85Bfj{((aXXn!a0s{Y4GYFLml1^=Vz*VMT2 z-z{EQlVf70IOp;Rb-jo>b@lPTjx{y<21%@sC68Zq+KNTs-htilhKB4t1a}R#e|&ZN zt0b>dQE`&^RXkPT#Z+?Yh7Z1$dumxw(5rG)8!`iG!g2PNm(BIo#k#T-w7e@@d>0z@ zZOfHrKepsJu|z0V+=wLP0-)O+XS%;_PLB4ACK~&FGG!1E!`GTvZ;0e)CQY*FFqhhQ zz;vL>G)Cr>kF+Wf7?ZubPVY8GR$@U6ZTl}^BGp;DIorJ%^*QQrIK(zbgl;ku=4D-7 ztT-6DCYYGDFTrdpo7e7XMcE3@<^ zB|PUQ@vN$HlZGBFGneqwdcZ3u*)k9#ie;%jXV`ygcOcnH9XI>qEWZE z%qKd#gV14u!gJZUjtU@^Yl2asv603_w17@#g5MueF1teYFg7p~6 z!2m6(r>b%!o-p}t=dsXzER#6C!4jzbfi3JQ_DvD$QEUN|^%3dYH+e3eT~Un3h`Gf~ zh-yjqSqDnzLNjOdfasu3Gu2QbKJ7eRJf{@{jEE&1pDq|iSn}s7k#5qDYw9nKhrOg0 zhs)})>CxSa@i|3xpeCE)1{no4hg|>T?Q&KV6O0J4kR0gF??#q9b|%lSM;)%IpMHDp zy5~IiWj73EgEe1?X0vn5gl^mhjZPO#K_ReV8n3AMd1^J zIOxd8$!nEFp<%?R;tIY4%vv)h)|XF(H1rrS+AV-e>cE zhOEGDtpV>b(!cvPU@k%m$*`Kt61bEp@5&?CEs<6?AEUZcp|hCyy? zS|b?X#D1Vi>G+ii^m`?8Iw(T44NUYTWK$Hl1%dn9Z!v+r;KDdtca4 zO*ZU#qPI5aU~>eChKHuToLre+Mt_G~g4u9Ic0SwjxR`=uX?Ox_Xaep0?|KIfFZ?oG>xBG5rm=fV(3b|?6Lg15wC68eDP24frNO@Sn`dijmH`y-GQL0FqCxq*16-FJc= zPhV|OYI_6dxJSQ1_*Pa%Au=!mG7l)zf_p>=`ZVsYBFY(PjR=zEZ#4U?L33l=rZV}W zdwV%@ zpIQU@kM%y7xrqIwJ}Jtw#W31QzPykEfyGi2_p=CtQTslQqlw-@wodt>U2-OPe~dhf zkW&O;O)lzb|Hw>-NC7ltB672DrynnXJ^ znY_DMsLyv;3ict^1;~@k-l&LPCa#$geGRf6>EE%oF6fED@N(G#c?w?;MZ8|P>X0<< z7$(feXeLCdrPukp!^48D`xxAsX~Y7e;Q*{(dD>WW&%zWsdc8 zZ)4Bze>Lqy(FBAN^q^8CTr&gbrYDfq4GQSd0joF-^LKuc}-lV zNk{%K5ql9QsE|sNR#YhLdo1QmTclR_hqxAmH@f%^} zR{g$+{dMfYlr+uk{ouTUpLGnlWtYpVuah;Mg`{9%bv89%c7{{@{<~yjqdWw)TOhjK z{K+?S^ZqRO6W~%A%tP9HrGE$WtQ+PNyvOH24`}Mx5|~CPS-%*03G;WmTgaJ@)o2;3 zamqzNC(OswXvxA*i*0(i4%o4xnA9j(D6fyMzFgLFLzQf(rfcRT3XOg93e9tGHPR}q z*+xS0EV(QP3r;M4Du%RM*XK&W7Hz9TyHe+hP3cYV!F`k@-)s3%J6nyp%I2RQir#L@lo-^ zqf9s3+@uLhwNOj+{g**^alVMaFV@)13GYK$p$1>`zW3oxBcn@1#!4T6Jh2BqjaZ zim!-J*#0Vog$>yQyfAE_4+>a0_3(*DSu%y_)$?#<(DlCGO@=;7OT_JBS_qC;Sh6t z{HVydtq6VeYnu3RCFp5x?vkzLjkwTEZ%CJ_jT}O=Gv zcWg5*j_7P!c=B?m-VV>7{xudt+z`qPiJ#%9>SPg2e2l1Ul_g=<)Cb{4?Sil5=*v+$ z9^a`@xGF+(5F}jp2U8MQ`o?HP-9z%e?ClPuI-FERX$0I+4sHBDOnnD5T;2CJV=($C z(aQ{iXwiv2qxaFG6TL+Z5-p70L$pMM(V``S=si(`=)FfLA!>q(_V>7l${kFDz+U&xG zCn<~ezPe8O33$fCW2echq&g`{LVil)CSd}Uq~R{G_I|u7846UYiSgy!JG3e+^fq%{ ze5JLLku=v-@MgAlCwR)E6h4$d?>ICtB} z`{7)tP4y=_xq#!RHX~C-fZjconjB3DYt=4)`|na&b__C^jG@Rdu7>`M@r>#T%?koe zd=8LpXr4R^#xSms#?2ShmQ}S}J>~8zVTyGd3is65I+^T>zZQ@4Qjo3HX%^Ek$iYpx9OZi7{a z90#ldxKBW|1jKj&Af^PU;;opwXIrobU;)w>#4T9Acv!HA3}~7>6xipmWwWb(+wrA3 z@s(~Q@?f)&W;aY(-Q5%hwYXjE4wd3`IWj567yOfAsVcB{g>I+6V8ZZmI3>IQrT}Y2 zSw-w3)9OAJNoV)>eAWC;YO4=f#yeDk5^;g)45Q~rZ!zymcP1X{7-5)3dS2k@LUwV9 zv6+F-9VCf%k`*C3qcsKv;k?DE!~ShZr5=~GF}&0C{=SIX=#XhFE#<*hN37TFQy&6k zN3^&m6O3T&am|bWENJlBg6gI$aLyTp$d35e4f{m;zDAOjqrSqwIlt4iEY?8TkXXCTC*M(zQ;fS?R(x_7dwGe|H}tH2-0Abb zP!6+)lt9y@wOVPa39833?2~n1A7FPC-iSdE;TG|jvZ01q=ILWkI76?{p)ForWEFoz zI#t-i!Dt?EE9oFs4v1M89ZE|YgG??43F@IZDTQLt;mSCq2fPPmv3IWsDv6D8AAqqgXs1{SjkqouvoJyZMK930< z_DGPFUmZ0HS|V6Q%fHY2r+B|u0b6U`X76&$9ACG~VubXQnoS|vqIkmw(Jk2i*g|wd zq(Y$DaNSuN@#e3}D(24Nk7gyZVq58Eo+tenul!^T)*bX8hDede!|px~a>U4>> zfx3u;VCeG988Ies`r+EHDANl_0=6_fh9cRKw5w!PMzg;%rQ=De$#TB?Ui_X{-eK=)jHlp@_nY%#!-kRR)swf2&=z70ZLZ@Y73Y z>z?(7D`al&yV&~JyV9CaoiD}3g7`-fu#3o3A&(u=8FRN&L1aAIYx<^sQlIqYr=&ktn%_<2X<6A1{W4=?GSSV@eyT?VIorYyun#y6Kmv5M_z75eAgT~rSV<}YRI$Bsse`X^ zO$N^OTOdN zOuKMRGl>Umu@k`{qdUiPOF>tZP*exwC$#G*U!wm-%z6Li_ouh)*z9Q51=ip8Bignd z31l>;3EtnmKoQcg=0)oe)|;&w%6R?ol~gv(tH163*csP2K<)Zzwq~+CT){>_+JmAR_B@?oR?TCR$3B%A% z|C!f`d~|2BOguOk8L~*&8{)u4cF-$uf+!Ld5{jK)fCCnMEX}6+OmMW2PXEHNC$sL5 zz*Y-?;rJosfg@Hljs#`bIj^}>yoQBmk+?hYr!QYi7!!91N?wOaD#txtJbNGPlE$-Z z#0z{jI(gr{K9YHrKK)v*SXtl!J<5KXw@*losw7)UxZK-EhSoPkv<>WFHEML$9n2Ff zI-9;o%(1-26f5GO94OV5$3u-i;ohGS0d>@D2Nivf^yIX6@zt~*-}wQ%?e8sWF~o2c zu_?j;(V_Ku5MRt4f0E``m z2b?Y!)z7IbJb5c@_oYw*`8&Fy7)0U}ZMzt~sP1T!Je-Tm{wsB738y<1n*Bx5x7K&M zeDCmUiP7w|2tFL;VR{_UXRk-&f)wEuBMJKKDnFc+yH9y;j4px|`tI+-k>veTAX&T5 zZgwUeuee11lK<$%1WCqRMFrF#n=^CV!iqbia41z1Y;S>2rDS1WX2d z;g&lo_R{$C&AK(= z1d<~_%qLiU@wT-+M#pv>ORqamB&tk0rIDyqRY4?|DLI>0Jn_HtbR?NS?C+R^wN+J7 zoxK=+syWEQ5g9`9Kw>*uGpUl*mTH{Po~VM`6#k#FmP!sd6;siw2!?{2PU2;W~3t zHLr{`8dXD@(r;`++ewNiUoto_`X?D2Z?|;ZL6Tw5n}gS^n%B)5zR|{p+`Z_&mHJ-e zDnH;N`kK3f-2-UGwCufrY181_LPqPNDR=b5@0UfZ+dnSt%Y0sGUbR7G*Y5Sslqm1j zB#1IFI`4%e<|ze0ve}5JN3UH#&G(~^WjxD-N$Y#t#AZ?wSw5Zd$Gmsr#oh#61E^sv z%1{;bM|mB}J5BLwtUquetFJD%2_A4CP#lOIkXH(X-hC0wn{a9}qYUR_QJG)W3^eCQ zI@6^6QtpNt$i|g%qGWJIhYNoCPP9AfMFsaXDAzrN^d(^!iTg`Mj3C^=Ksq5}u`r-= zLMFh7`vMV9K636KpEpTaOo+{-SUNVwXQfjyo$CF$!nSbZ_s~^EavIaOr|DC}H>?+d z766JO+}qyJ{CSi@rsNQ(NlkaVHoP!SFl|El0=m)AW$$|!{{@+cF zYcGY~x`4`x^EYuP+R%V!cjy<`lrW=9_I0l2vv^885KG+n;!cr?Ui#hI*M)8EK+;*9 zrLEb1C=d2|`bYlkWI$bB5kKW;*bAuYYI;*r%8Qd^d>J*0UzPYu1^-y88V+K7hbql%DefC?8dKAw!lp%AD5wOjri%%syCrw$g z0a2?jBe)3>1t@98O#HPVx$IqZ!E3K%B#PP3!A5`kK0Id0^5i^!i{`4G3oNKl%ci6c z$#+hsfdQCkTXYj^IG}MYQD>Hd5K#l^?`V4X@Jr{Cn1o);IFn}{QN?N3m#196A~2k~ zSHv!s$h}u3zdH(ve`nwM0i<4OOz>G9IF~-ZorYIMEY%{SFqbE&@n|~U3tW*oCi?a# z_U!`<*eB&T27LNEjWRVj>`iAE&7$Cu7byCu)+;*dqe7h$}Hc${FWb!NC7Z`4Gzpk{?a~sMiR{B+W`*g$D#w z={A~@%-Rj`H$@c2>b8I!M^q6kL9|3-{jz~+1MciJg6%_VQds}>&Mx-$lI1;1O5shWhnI8$OfB;lF z61oAqD-SJ#6Cy14&$a+i^b397u_e}~*7;c4n!0Yw#smE=*sq0h$fvivtw9!I|Cl1o zF7MF308V)|=U4psBk{cyHk!G9Z;dT}4_=5cG1*Hl|^4>GHhph(Q6bE~- ze51Qsk~?2D2+c{8-6CL12mYy!mVI75A|m$~lwCJCL2XPNPs6C*SC>#z-5m>H zy2})H_duy<;O~HKRFWms`RAi>!;eUQN{iU}I?^YtThK7PX z>_yx+rU_k00CjpQN{saOvsL;?0CoE#QGtvu;lTzE6QCz$WC<$gb zWyu0NCb+jwDK;%Jq$#}gX0;ls%`AVt?jT;e!*`V2Cy}zl>hZG0nNQwG$Db3BM?2-M zU>yPxbSN1%Q$>p(!3V4?xOQ95r`dkG%zWII&5SbCJC}7XTMnEl^kNF9Su_8tQJMGM*SZ) zOpS+%KI@wO9BGdG=m*pMWFLWXrSIE6R@HUaVGCdv{jD#DHhKnZbSYoXgnx>`HFDge=4%- z9)pzsQJuut$1nOJbu|2^y|vM(3kY`)#wFjZEXxR`@v7(+5z@F1ocf)pK^q}t9r>F)y_Vh(|h5nGsVGfL&mb3aEuMUz^kCLB)-P*QQR zg0HGg=zNE-IG5neg^>>jAU8^xcj(1Fu18)951cCu0D^7nYwvu)B);c*12^YpH*}G96fCN{P_;vy6PlGFY zSD#YNeH#K3?fM$3u&GYIzwkbjzHZ`1<;3y=1K-R!w4S)>?n|!3JDp3n^5}a!)h@l%#G+Ry_XED!LO6CM7Dgf!UqweoA*AFMD zP{qSI3hGEqXYwP@qIV4Eddl#U=n3MKx!%H@#x*NJwQ=fFB~(yAf%d>!r^);03*bxP zr27EpMj476Deqz3mNOf&G9~4cZmf=nAk0?}bt=Adfv=1P{CgmX6OP|A0B^Xbv;T8! zu9h16Z$jD>>&o~ydcK(Er#aYpkDCtwGK1>aohB&t5t3P6M=y5@8Glo&Q1u7>LIv(0 z>h{|nQ-)rMYaQ{v84*IFeCyI808S|h-`+~TZqB`LV}oONh;gEIugS_Vpu&1hGXe9l z!Hzdfo0<;JMbs>Gpg`-2G-mFiU|^Y-dq&Vl%+gE5@g zK>tJIRovsCOJSDL3;CQ{lvA82SO&=6?+|LqAhYa zQ}>*=KiAt9oSx8e`mtdFf2;Yc0Y0N^xB?X*A1d!i%=<87st%PpsjtO#ozb%5kC!Un zX7ZNPpiVU4F+}(k^eG zJwk~B$RclFwC`c+X3pn*x|OWaMB26O67sM(9KD>|laYGUTD#GzGLi2~S%sBkp?ONl zgowlKC`rC&0OhV+O?mKHVh(GBHOB8%i_s(d-tIX$E?!C$C9D!dEPS*;u zv=@fGb&qo$JDc)o>C-%}ukG@Eb)q-dl&7i}sD41UzCCp{=F;q{$yrZWdlxUJCUp)- zIRQuVw8oz2ALUsR!cyyze{tJDTj5-BfiZqn#T>rv;$i+hOnA?Wl_grZ>Q(8|c$H+t z-Ed>tj_A7IBaSmHS=hsMy!_ynXxT{2vKQ|K(US`6pzTNJD|>%XqHz!)SHF-Am2Lle z^4HCArTr19as&pg455!)^>Vicu*y&WiFQ(dvZFieM13xO4t`Cu+}_IZSNKx z`~b;^o`e{a=0cXVmWaUhmYGjJFWQ@x`pMGWd1nwPXPH4AN)C4-d;~F_V(W3P2~H{~VF$z>4NvsFwvX;ax*qBI2FN5ppv)AtE(LdKf z+#^4Wgx0KZ!b^6Q45Y)WW4TTvFo=eJ&HdM26-?TjjmTtI@(CE24`P$FH+Rz3!TTUX zbm;{)nTSINRoK&M2qIWh%pZ?5fBJwyR+4Zej9Vkeb!J7*C+bg?@b}@@ z*P%p=@OBRLgm~976a@)bo_uQ#chU-n`m_MSZZK`vPj6hsg(anlvuOWbsbf%KBkO?T zeNIi=+Yb@G+Bub4#kjv{uycuT6CzsV9y#}Pcu)a%Ij#cr!gpChhZ2Mx!%7WKleJ%Clb7`Q8%CRtAaPV!B{|WvJ7viVN z#u?(A4;{k*z_z-cth|YRL|ZYj)>_jL7u?AWPAU3}ziuj0J?lRG+8_x5=$cz!AHuaaS5#>O#}08U zI>XMmLnG^6;pXUepAW=@0L<+fw!C<%==bG&)Ho_A$f^|Cs|XuS9x9x)3}z42v&sT(=cegkcK<4u$w~4 zb{|AwzUql1c5^BH&FpgeXjolsk-9qGWFSd+J3ix;DuGB&s7@5cB!dnlKS!aLgnw$A zzK0g^OzcIlGEfExcp?Z8d4kH&RM3+)X7gDf)jC4)h0!lx1lXlQ&g?2hN(Vm&2pr=8 z|Ge9i165pn5^C?ItqSKFc=8;0%`{d;41Za)s_#kjO16N>xl`*64pozf<^NT*WJeU~ zVF(q9R;^3Fvu+I1Q>Vq(G1fZkGUaxNYk$#0GvXC>Z8MF7lHl`|$7jgl42PnSUpV-FlQTVDdgBK!Ck9 zt7pPKc~$5T;Yw~GSAc+AaO2L^pO%+U9!+`R@FDb|2cJ>EKj(^cL9*~hM88jGbn^WH zeAz|Jp^p3EUrrz!RJ0;1Q=UlT0`rL?lkwuU0O9G_}0Sr+eNr~Hq8j%l3bM1Irb4>L{;Wiqt^>ptH+VBrl>1+FiB@RHqbM+bqBn$ zW`~yqu8PK!7Mr3ah~b7>bS`1#;OF2m<3};5R91BS{ob&%#zu_@%FR8ZW&XS-heeHL z1#&$bA$wpZ>F2oC3j&DFwMEaYucgkhBE;g#je_MoOqypul8*mMYG<)Mf)T+J+`o({ zo2|H*yzRT)1F0_JHR6`kn8Yf5YT)u3FCL?#lu<8xNyUZM?$gJl)W#jcR&w*Yl<0nK zmu`95tFW=?KrYBK6xeh;;^pQ<69mJ6G@D4CS@W+Iw<s#I}Hse0v^48>;R3F|ta#B9>|lvf<%Ide5h z#p8LkK6^8FAy?xH1Hb3HfApk~yPPqaH2x|P$mBm=;i1}nwyH0M?sV&E7h8ef&=wDn zx1aQW7XDqvXr8Sd_`6J`6Ekj4Jb)>7;RF4lQ|B2ROF*IudA#j^aUB$A9RJRs+@t@g zl5y;qacq=vT13r-#Q7(j@NmuSIKx3@9d_7cgZR$E|`I zpTix)-KTsvEgkWGrb7u4EQlrLD~*zuN&RYEfuP$3ArxW!qpW=p1m`CSJKJJi^!-_5 zhj6c_OTrGV!lA{QRG4UVoBWm)A>t~r2x_12G%djI+YT%qHj{<6@IR}9MoWEFB+K55 z)(E$Nm-tX|v#9U^xi{=?vtIgOBriG$r?_~H*fTpXDZ6@uFcOn&u&&|DS-Qu0`Yc8o z{)rYr6}Bl(p3JmW4Lu~kOp1RI06g@__wq4fw&g;Xd}!Cs z$qF9MZ)XQdEgEM2c_69BsU(spOWoZR)%+Gb;Gqy3K>9nK6RhjaI6HFduUk0u#A0%(#YM$U8|dRiCm!fzpt1CIODl3Cs%me9zxr=|eyO)?6hVzhA`heQL_Ukf#(o_qj$;!{ z>Vj;b>$)|6D~uE*rTMhTW3X+P(e}ZQcWr<;%@qEpG&)%M-P&(tXKqi>3vd^lsa_Dbg+wKW%%&< zjOHuLix{O5m5%lo6X?HRyn9}0Rxc11LMMh6_@B;elHTK6H%~E(UXV|KAdUy$>P2GS ze3S6(9g z@ygyFGF>E;CMQQ}B-J4#n(VRcYRGXWGPz!U#WbA=+(bMwgpN0tY!BLKj4HA=!}Hr( zk;hIN#ees~HQcA*Za-e0w}cCGd^H4Mu(v0GdJ_QElU)&aK4(<>=}j&cRzD`mJmJg% z`*1Ib%*nv^P?_<&0{!$6uwmAiap!Akjl3ce3~Ok3^A5L{Jl#;cc%C*MMn4015XH87yTr&U-v%AIpza> z3zc(r&$E`_LFJy~@ozY=my4rkZ&x>s zMBxx-zPF|>e<`CI$_5r&zRZyCr*wC&{qV7mTrAe+o!Rr|owU<26!#S&P0#te8}+6v zxtle<$lH>yr<>l&Gh=9p{4-VhgtCJ)!bc@oWugXQ&(RO6P#P)4o31?NQ2j(<`(SuS zBvN0yxbgk&yS6*vQMQB(S`k8^QAPc|NM$kcz|Ki|djh%QbmeQ$wSd>PUW>|xSkFnF zadz^(QIuIcf1)o!L`a+?`_=&y?)w^Xc!TZWGqx$RKY3$Y*)EJe{7Y<`=H8R!h(*|A$TKfhc!d zOTXWyFIpKAKp=!GL@mmuD@N6AUS&G9!7nk*%sIbONglTSuzIxc>~c`L!SQO0bvp?O zU0$cmRVE5r1u%!vrdWjF`BKj&)X!nH*PQWAN9oT7R0NNVXDf?3GjdkdAW>;gaY80O zpa)`8x&18hiX!q_=~9x0gp7T%(xQsEbzG$4PMV4=SSi!ZmZs%wRppCU6C=;L>;wuq zcjHiop+~%FcwV>UdLc)=*BRAUzt&(wLIfMuo4r4jl!eprUp~#e8eCW>0sNtXiIsET z?3W!8zAy>x#|-doAFNDdLr&t6^h7<-vLR>jLA+a!`!^*ROhM zE@YWS?XK0x5%;_gUc_5d&+6|NeNL`F6>k0*7|Cfu(~$x7a|AfOq}q=!{TgNni~=zY zEbciuVm~6|o3@|FixJtvGREDF<> z33Rip7YMC6!ea!(>K-X7HbyC#fdzLrnId7E9&uvzYd%>8W0YZHbntB;Mt~aV6-^|| zyirCm7w*Y_l2r_dTnq|!5J1Q{dl@PlygDWMcswMZNIuX*wvm>^+gsr|0;onnG1%~e z`Kz2N$ZCzJPq-4)&BU2pL`RFT;NGt54fbpYV*2`zpU(GpavoW9I+3rNT--lFsEM2N zeQHD+72Qitl-Ze~4&7?4p4h%;{$#8#dI} z%>8Om zCxpbvnZ}*Ii-UwLYcb8W8Ex-@Mx;;B5qwm5bGFEgs!_?H6W7{fgYE839n7g zQm9oTC1%ODnwyX)XDb5|0LC6KOvqsMC`cfxCZGvt=#6-#v< zr~Qdxas&X&@fZZqVljEnHLU1G&yVXR6pB;l>aLQ0%J4u9NL*MCbTT?mczj3-pcAcd zWhm$5HIPB(xYFL91tMxaN5(X>1MtT#jR@WB*nY+dVP%vf;8Y0^sfK{Yefy_z8KJV_ zruojyo=NL&*3tk^?Jkdw<;=kGj6ZnBZIBm4?;-&?5y=Afg-^@sG#YJsc&4YTH(Phj^rnNU6f%- zJr4*ELqEK}?|Nt1+?ez0FAqZHh9)gY*~9o(_Zo80@rVX$1W;H3da3-mdGM#@mN~#) zo`PebNSKGGE+oGdW#>7%u>Xj1=nDVAUC+TDIzj|p!$(@gd5Igq|Mo!gXEcmz9c=`{ z_N{_tkT*pa8}JDol|qeRF8Qb^uPJ18@W3cZDIP*Pm^)^!|0r zY+NE27xEHhQW>ujkKn_8OR&lVWKpcT*o~*1PwEyf&aD{Zb%OW}c3P1v)b3Xc{NPb1 z^b*er?{CSNAIO=(g+mjGw0QmV2ICk8Ce$dMsEqEg07qwHE`95ygS=&Q3;sFPk$<@B zjGIz$hq#UGU;mCH_Wo&Kil=`wY-s&-AoS-Slu-6?_svyP4*m#F))*Y!3Tq8b`P0Xm zl}-S~?s1Q;;M%wMF_K`^m|dUNma&?k^uvh0#X6{zL@$gpwcVEbS65Mduu#laaWw!W#bv zJNQa2<2b~0h*EcF?WJfA6530HZ^Y6;8TO~g+W{+~=73pXdEL^4L|tqen<8IKeHnth2m3@50zt{ z5SeI#<2>#dz7W-FHza=%xe#J%A4c`dv}Ywuvb0&QE0ZAtCTT|!>Z9OG-cO|aJo>tn zQ||a&24o<19DO z?i0m`BTD~O#bmMgoSl}Nkj%f{MV@Q0U3M?agmwte=8!U$u#Ywr@D&OmA+ZNtPS!pO zQs#^x9U;qWS&cd}9=0J=Xd zh|xTu>yLAdQgWg#b~f26VYt#3rUh$~Y4NSKT+y>%5innp=8)ezwIIepF$9 zM!mVfB+n?qoLnEryT0HAe@Os-CSPxgnymmPD=_6dT%Y~ktHMjfSi#PfP9eVJeAl)A zFYK6Sd4ZwFUni92zcKF>vD{2#UFyh3!v5BeT4-!*5$#`i3CpRz<_sJ-aOLXc^0o5_14$w;Qitoz32hRyQPIGyC2UJ2~fWU08DHFqh{>D&8aqX_75t) z;vKX5@7DgCCwoM+V8fjp=>8}3xm>K!50}^;wOM5kSG;aiahmc?z^wT$3pP?qSAb#>oLWDB{Ndp*RRrI?m=q4|I^2g6#{c z`CQ^)*D+K?-4L@`pZ8QB@CH`oBb>UQz9`gu4iXImJlb^&ItMw>;;hyXB^5~Akl)wlj}y@ zvo!gB*;tClQz_M2o8$1p?weUbkw^giYUQP0_U;PHG$m3#cBi(8?`fIx^B^voe^$z) zNTTHv){qhP0U=&^EIY4trmc~4S99~dna#BeMnbz;-VoaYeWM7fNG`B044_UVkTpy; zp4TAt5gl&PJI{9sPUJqHmA#t8 zNw~r?;Zm5KmV_Ai^ecEwO8&7{i&GpjsQ1w|!Tv}y2rij9+Wk<<6U*HufDloHn211S z7DUODjhSCq0IuLt1GdAWOn%kd?l#i({C04vXi7Bm&7G*yUc)X;{q7>ng?u~y=K8C4 z|MW@ac9jD0KLw9EtRIM1k^}W$;g{_%{>FdIy#v07)rkm10vQrf+B^(sLcUgWS6aR> z)@$5h>dH#G_sa%6%T;d(atR9GP66b=&WyGTX1@LH5-r1P@{0Em?^%ZNbtoB81eO*h zHx^>4&^cDFbASG2yJnGLc0W=2A>{!{rHDGv2lb@-BWsB`%I@-$H!#mOT?ycfW+jv& z#AUtcU$s~sNvT@BrThE~_5Mul^S7V(ja7oLRr7Xo+O^U4JGfaEoj5NUxPKPx9ryEa zX%_!;X3{axA!2)tbE5%frXQyo?I-{E0Zafyi?1p6F~5}-L4H_`(!uu19nPa7oV4kvQ+Y4h z0*K&BT7COvN4SU$vVJbyz`VWurVi_LEp(sb?z)2ut`N_hCFz5Y!<56qPR+fkb(R{} z*J8l?2-sI(b5G{@*I4RJ|l}{{E z`o~X*qZR$xOaD;rM8}TVrGUN>-NZW(ImVpwJl3tse{LoRHJpI~pWMsAko;Qdo_Z7F z85Mwc6EY}b2(WYIo*VpaY)ubdva6>tUe>*d?}X?WFqJ=f=kszXmBI^xVD8`~PM>4v zumA8Tu*=xkAw$Z*b&scy9LpD*2QNx*Dg;|#cbbrv$2Nu!fe~XRq0!+2vO`4=1Yi60 zU#}g8BIio^Y|O4);&<&fms;fvlYhcJ%kJ2#9^M-p2{%AQV({}aMV2QypNxqV-B>+LM=)ZLqz@F49K_psr`B@boaYdl@E{yR?gW9oaYTIGLR ziUCuk$Y*b{m;LQ3Ozmo%w9#{riM@HwdhkBS*}~qHgMs4paIi+(`|UNU^Em_8|LVr- zFmi$}Yi$bhkTYb64H8EBjylzQSM6W+i1^>CMK`Om1FJTtzD3kZ{@<#Zq1qZ0ReLp) z0P$2a2)ulj(Xj~5ZEjsohy#v$Aa+vwc`MkD(7zz{Ju-{-b`vVC?})Vrkrw&GgrRyF0fQoZmhG64;T#S$!N9W>7W{vw};LJ2Q(E{>iT&7EKNhXP6}18HSHtB|ct#gNw$ z{_jD6n{%=NNfte{_!Hm@toJ;jgRlD8uPvF0SAju3DneQ^f08&y#VIpGWos$x_iEPv zzY7n@uwNTq6!X=vUoVA?jya?B_xhnOsy6RD_VHI+#nW9KP&}FpU60O0JBQ*(<4F^r z;5LCmK;<$cq}zDJSjt#y=+e!V$DxfKdJk|{hRd8w|36`2z(GhL4apUWpjH6%5}18Y z38gQc7da9*a=uJa!x3)e@fJ%+b(SFh4idxSLECpouUI_b5MX*idmDU;_mm{w8|BDG zc#0o|ZHrdxAYKt&2?iQ6Z&gyy*sS%!wDG*|MQFGg(yQ-3Ev&t9Apc2l9GG#M5U~uX zx!wm1E<{A{tMj@wA4*=veh^~dr*fU{qB3H~u=ufi(XAb19WEo~tk_}&=2Lr7PW zj~dL<)A^rnUfUrUIP3xyCYDWY2K)jXIzXFJEZECVm$6C-g1;en&k7M?g$>~7}V*9qk^hCfh zF*O_j(b%s}m6-(g;)vj(B)DA1+ON}J?xFxf!}lYT{n2htKK<#@pg zbfp+?h3k&dOgFE(!1*`7`rswuR^1JK=b+xg_}~TR8T}`)434IN3t27ZFVmDlM+Y8X z%o{{FTGzovhU5wE3)~=3kc0W47`T#;De!|QJDDS)XA!iB2{ntGj)M{fiLU92(;b1< z-TG7{$#fbmOK;u3c4svr=p={Eu&B2QPQ4Zhd7CE6e0_lr1S=MMdl<4zN3_$!O`8Ny zE`iBnAUZV>(FOy;1_Ff#=vPL-{*`mfK-qM&IJ!Ie8Tly zU$h&RNHdQ-#VA#TDmj^6DV*_>4B!~sG+XE1Q+rd_Ng!PO<%G0gV_5EE{xjOGv20yo zc@zs9SjHudbyta)|I7P>cn!^#?H_IrwRSB5%k!gf zv65%)1Lz0# zv0IS+n$-Mcn06`S1Xoi)GDXa7AUxWr=?~wq08a$|HOGyHTj;kl>4TOPfF4YQY-CIH zg*Zy(vpu0pZ-E223_mYlT)lZU0N>m_T>o6+MLbYMPK%wSJL6`GA3M;6{+Iz~_14gT zvE%ifhRW$+S$>Ed>aGyyJ0}r>bs?W=$w$+isuDM{jqnc?AoGtZ>#?He*9;uZx6!V_ zUXP$j5HAZW)YSR1KLFuh;#R|5d{mrhvJRLH`vj~bvy#NV{TpS}F& zoc|t+pBjFnkieQHm<69xAK}_z?`~oC-6mQino3IoL88y{SFINqfe(K5tR))q?TD?D zcoDrgdj_Xmj;xYqiXRsc51kdGRYiXck??=>c&5E$)sLI$BeS5?y98227QsJy^s8yF zQuk=+?)UXDG7y2zgkmOvaqSvm%D_7!z8zKW5|cDr_-nfYX|i$Lc)VE;7^j@xo$%Y` z+}U&K+YJ3q)PGnrRa9d1AHNsD)}fg>Xrt!J;vo6t<4mb{bl5OQ+vX4A(4KOGh$qB} zVQ*%hz(c3QUr>H}4!vJ!t55rT%uBGu6!odLg<7JDpoBVYX0Nyicstk*WI^}1aqX3w z(P`J)k#3QDbjb>c*;}5G7}4bSFe2T*@ZDwPReVV?P-7}#jISo=qD%M|>{%+M{kSKE zbY_}*{uy56Z*Wzq5HEMS5w(_?wJESJNy*|6W zHoLusQHOMOvs;m29Q5Q~OufPjhEI+=XJQF_){I1@P^uqwRp%M*8a8nv3hV zMV~<%EPyeI*Jo*p@4Z<-(~s7@o3gbtJDsbgw&x~CzPL2TwsxWhiTgC;G0r7V32&`= z9_vz(b*E!XOylK+yt zU}#3VOJO8L>4uR~6c_}gkp}6Zr5S37Arw%M7(%+GyE`SNB&DSh1o6A^dEfW@{ReBY zn7QwBo!I;Ab1s*Tp+A~!SsSr5yr`choeYd!7pn+{_x4gWZFbjySe85~v|NB`SFl`~ zLe^@{M3QkE`Mw$9LH>}mxB4+OIqV+l`k7AVX4nPaIk%&NZ`ZLvm2ZNVt{*D)^BmG7wyAb8rQU? z(#Yq*h#G!1x89YJ*?Fva!ir3iSDR*UIg@hDjmcT=I03^ZR_AQG>A|$YV~n{ne*9ii!~9(g&w$bzY+{O|lMOJWZO@xQ1U0ESkS{$7T# zVX$t#O}kX`ZLZ;IpvZ)CYp!_)FI@*STW5j6E#yb)E*`cf`E1N18M4NkaUl!o&rjkG z=JbdXhCo00K?R_Mq5U#SgsOZ4O+%UOJmPRZVoTkQU6V$X^PE$f8c5pP2Oqc`s^;2_ z3d%13%>UYuj-aY@O~D#;B{%=5DuH@z>(&JYxX8zcKZaPX!VeL&&jpU$si&>XT_2vW zuRX1wE`mrN;e99OtUc)G>=d1Wgo&R)@kpnr-h~ts5e`N}TK?gqubj=Dl_qaV&0gF; z5C`6qP^ZEK6xCV4ev|XV!>~L-Kr<4Fe2)X?2v= zeuENTz`mX2`;rKM(Ewz=iZ#5o8$Jd#xE28^jAVnM_Vw}nqK!{4O$vMsceuLfG3o06 zy|B9<+el4_%CU4wd>2`<{0L5KQ;n14pR*OpXJ91+Q#0_{JUo&8uJJ|Q*@R}7A#*he$~x~|?((>ftMos2GY0n`s`qb%E2#MX!nHD2Oy8RPG8>Npt3 z@y#X4O3mSOQ?nMavz@-=vz^zcBmsP=|By_TKoASgEQvktG(#h%?2dP&9}aP4s(+IF z8`Oc93wbr`9PT(2_0v3>K$XyVdenj=IfF zt>6VvX{hr9d>SI>mOGor@Kl<$k2{{^NG;rB9saSeK>Zf?^*#q~~qv z4`-*b80J?SrHcDHXxMmb+S4=%VP$t5Odbyta^R|p6s*6YTvsH_(jeCas997&S2`do zxl;xQ69Qae#|z(Nw3BNE8_WE>S%4(tL7<=!qBO%U!tD*PN5Ci}a+SvUy^P&K)^GDk zK9M&g(;!PtU5_7qK_V`d@Q3bk??zruJuhTV-06RL6)AgR_uxNhgh?bwEk}rv$l_HH z%@P+2lbZ1aX%E@G5uZd}q-4c$;rlULQg)fZqUrz8aK0pGad7kXZ||8Gk*PVVN4sO~ zRhc*SIat2*etUn67klH4SZ`MuQ+X{%jeExrwTny&k>gsh?8kc?^MvL63_4%U9vS zBwxPBz+1WDSD{ADdb)Y3bKw0f3e%y1tv6kLKIapkVL97 zthtx4bw>qDIUh~skhumLu;T)v(aaoawyk})q5d|cy>EI{;-#+6a#-fl470N2>I<6G z13;$La1AY$31WD!aohy#7HEwsjMZqQJsa|Dm4Gq;!+fpiR2wcDi2)Kk*v^A$`OiJ^ zDLOfhYHQGKjsNmP+z<%Z-(&&CpQzvoalo>#GQxj+@C!1SN!>L=8TyKr4|QV}&7_dc z+7pvYewv~B`w?Dyb_EZg(Kgl}PQ&o6QTyVG3bMz#vz&t7B?grgP_k98hc%vUwQ1#9 zJS{)N_#4di$awdI?n_tH;Zq;gG9-Dl&nRA$O8fWq-kjny3Cq3#;$^~K^Yh(2AY3AW z#%_K!!%v2I^&J1C$rfJW_n)n*v`FJW`K>Ei*MEIAVma9F_KoG;KAT>~t6FZ|E5&ke z7-pwau3J(h6eDmui3^Ah=G@06gh9$z<^lYBKf_8CXW~QP5AQhQ$wa$ z2KDT9@rBgwNG)wwjW2zrS6@9sF(jtn;`y#lHoP)Z`QOzmHbcEm=eobQ_?SOK-s+ zPl}k|Vd5lzLIYWjNABcHu=fk@uxD=q>X%d>)_ynvCY$5_n0`w#Zk5rh<<>e;)IUR- zY$&%!>IGFMi|`>;I2)ggY3qYX{sKb>C13`k3K24%FNfNFi{cwK+q{CJ4~2j(50l8} zc1imt0+RK&;lMbs5YYCehMjyd{I5GvRVy7sx$*))N1;){h_|59n9j324XI8l2F5!uRD?Eu_uzfGV?kz-_!P`GmMrRrN1W`wea~gx43>Q{W4g4l|~n4 zN{b|?3n6C}fNstX+{J(gRvv7o3ci!W4#LL9O}HO&Pk~%q@TBqeFEF#ZI@UIu++lXE zR_EBn%0$V}fPmjL59zfaZWC!gNpiVvw4_1?ItoNm^zWiL$@$pl;BOhMXu4 z?Dzk;H{X}8R8v1GkVxMHSLJPHQL?-_O^Q-9*lr<;Vx8C4 zoX6E1B*^=L!;2&?1glIa#Bs1crGS;K9`O>Ab;2Kkc#)OD5Vs%(|Kv%oJW>ed9VY8= zz8Ut-%j5^KNt-sK>Utp6>EC^^<2M^9jG}k(viGNjkQw4|@G1&J%)joP-9{FRbHq)1 zzY|U$b^O>%7FXL9o>p9@Ix*ukCh7>lkh{J7-}s#s;vyXNw@XE(39~+!YTZ@TKAIHM zr+^VfOhfj$R1T;y0u;czZ%7L)OHm()4>`noQWrq+=%u8Q^Zg`C{f&w={dc6BdxrQw zu}ABP3z${EdmfDK+wlutzXfaQPhoS8ig9&QTsqdRMDo%YTG8Zm<09bX*5TsE9b$}I zA=8rf8Pt2fGu#JWZ&S8Z9pR9+WFf9_WW@A92UUbbJY4KQxi8?NPRT=R;D6`o1`60LAYu7ez~2WNBIDv&@(Kp1S8)z9!s>ayE3_z- z4?6RO0*%SCxR~8$hW$IIJf=RMHJy~P+XQC@B|i75uqlO{)=0DG!zp03b*CAk0@BXo zNMO9`y{5nYK=!KKmYAeHZkr`iOfs4!{WvhWdeqI~PzsB-C<0)DJy95UPJ8!uW1g6X zwPJbDC8muf7F&Zd+Orc*9UQ5VpITg&^11BU*O`(r(PB{{M?s+j(Hdsaxe-@)4vNL{ zm+dCrv`_gvwp59=qjMyF(u;)J$c)oxH7jgJI0nc*zsw~k$6izkJjneG#2q zZ7~$lI|%bykH9XqUJctVty@J#aprs>GQ%m*G;>p_n^sQGa6HuLB@?@mP3vGs@nBaZ zt@F@_;~a%Xm)S8gRT=Zb|4Qpy47R8&HxT4WRgAJ2AS)uf)x@aFH%&Jwf@&P`E&GbKI;M-ctqaePM* z5(qqEv!a{=+$o-m`(8sS0Xa47Q$&)+Jhp8L>};(-B8ZzkUntJ_axA+&;o!|EqSjJ( zex$yJ+4arR=0eqQ0iu~3IeC7hKl2DMrH4@D-9sVz&=n{+NFHSAb{FPT#oP!RJ3=$a za&N!{WTiIncorl9Nhevl-nDoq zwRpt00BTwZ`H5HZgEHpxkF)nvBLvcbYn(2F3m(O#lW8i##q(OxIwds29QvwN$`odz zK2ERu-h~E|!wC-cknRX&3*1K5hfJfjQ@&~@4}?^9x%;S5Q)4!Po#0Kol~CWteK4U! zUavNXWAb5JG|j6frjTDP`D923C=?>}EIN+S>NPujbU$+8$d;VhXSGH0cp+{#^2HZ! zF7h9B~X=Yy^@FJ(*&48iUv+aL-%nf*J6wEbq z^o4DVXkUey=&`=@tuP@^(ydrR`MthzI%{-$1cCke4SkQMz<#p4$;rx||LgoaP8MSp zkwW+siq(g^np0zqw=hjXo1;J~QYCC`@Q(M^b5FeaGBVr7)p76Xl8t=36XOrL4kPH@ zH2SZ^wrEU!eo8KN)J@K95OgCNv4y~Z$Vt3t>o7D#rq0BUa@z1Z+#`qiPKc^8CaUjDA*`K1pE-1`73X|*5ljNsX()*&u62I=|A_3nCCgWOzKYouOnaz)5=jQ* zh5Z=9f7xK~aSB9ba$xY}^`%fpUIL%@p78QV2u)htezX)3vx`kQmx`|j1lh1+6M=)q z8-C|=66EvI-Ey!92qfgjUaRqvgvE7l+JyxlCOc1K^fB-CjWC^ZacW1?4_>9M=ICJ( z^(zHsCzpHailLX>J<3)()Lawbpc|Ft96HJ7@@bZSnC>GjzMJ>d5!JkJb%GW?=L&E$J|?m{$+@juMi_g`^C>v1TC7*Qb(fObtwWjmYyDWJt2BYGJ9VC*Dwt` zNFqNHyd%fv^v?zT(19q7@f^oN6$)dR6{Vo81+g$t9F8h5eK_^v^T4>sA{cPN$?~@;;FOE|koBh|<`7CkCRy=~MiKv2K&8vD z=b}I!#j1vrTtJek2RcGCxB7D+hfE-D3eQOz_d<7N>ej-;gS`3+OyxDGLnGr^6yU?` zY9xXp#eyOZ!omlF)y#r`)5F6;T^1jF4<`%<-~e|_-q*)k(#iDJ@6t3o#n}7UkRS2# z2K!@yfFiBDeE*QP4}TUH(bfIfr0kX1hc&#*>ozv(;^2#$6m^KNn)AIliIKa&uO6Rp zAsOZ}UTo^W z45k=ZfDa`i7vMJCOhl!h;!QhngHwF^dbt`^M!;)>bl=e~r}VE!lI-4$_@Z2R$H06+ z@#eGsr6oz#Kr(#3oPgC>Z2LCjUcfzE^S99HkRpW4e0GH-^_AX5*P1T2+Wloi_7Set zC)f`;mwmBEdRE+s)s$8)oEeFFSKxa@?W85nr`%4wh+e}l`r3hicm0|=GAiYy&?rnS ztp5P0XTU)+@<3eW-;bP8AgiYR=%xxn%#>G8Rwe9gY77e%GRj*%E(Ci+6v+PUd-~do z8#~aYmuxQT$Jnvkgu6~C<@F?n{qD|B3%7M-ktJ~I#XuqI=5X2|WM+mMVBxOO-;%&A z+jNu_q{|p}a3Ci9q69Me5IN$7RD{=%9baqEqG$|xC31{Fs*^fAzf(ec8Z6aF>{QVP zsh@tO7{oTrj_B>tm8O7?bDzZAx@?73w`GNOJUU7-3cT~#98N7+PB1B%*+Ed2cK9Ur zO75XEo!BBX<$7QBih+GN>FQUW7&9|pt1T$+Xula_U^{1W$+3iVjf82LV2qw~klnQl zaA_?wsZu=uz#k2o=rE`dT4|7Sb~7+3SmfrXjG4&+>9^mc*i+sKb<2rF=^qi_qd$%G zx&3BElGu3WijhcgHod z_9q)+Qj#?O_!cIs9rV7`<85YA;tzwH2L6f3*l+NhPlP#aO6kYy8JruW%qzk>?@o>= zpAjdh_sk=p^g($QP{tS}e1T94ts2Jlu)!ZnJsb;{eSo|`{`6Y-jtJO9fmg@R!s%iA zfJBe$;h$HaW=jZVL?k3XHNPz7%|$cVR#P!9(a{SYBq~juyP2jq#%TN8whYo$V0sra z`5Zr+*CP;OLl@1dKIvtXNkc8Q_D%+G;VTD)Sf0DyD#Jc{&PXJj)Fnn&S^BZ^DTYG` zMMWNthae8i=02d8uA!~?z(DEpo}Ncw0Wm>D)^yZCbASzJh)#l6^<+C>@1-&&Vb9%T zw+UqO_+DARAs4}{j`p%qNQZn=%Gm`n4mC`&$_C`0Rq;|%K->_GGbJX&M}N3mC-^7H zvcKvHCIcciVENT3ZZ*ilDd)1N-bnIEg)F0T_}UA~hYD*hyaKBTK0sDimmD}x&=;li z+H*CICj3)H9R!{F)Iyn+hd4R2jy8G%OKdgRFSvX-a*A_Eq{jNSKPP#<;7bTB?Maa9w=S~Alq8o}!S^DnR$ z2uB%Iz~0C3)}MtPxg_zjQx~KOu z=#R}eQ-&(*mQ;=;!fVmAWSdC4u1thT743-UdfG)O&Mn4l#~cwboFC;^r6hi&QlOtUZ=<&L>*%9c zf#3-Tkv=i!+lI>-HZ15+j(I|o_|KkW&lBs~x3hcZc$>d(ofEq;fvSb9_<{u3kXs)8DS0aBNE0sl@MPcz>v4o-EapKOqeEmyS zq)Nw@B8n4<%qIe2O)jtzJ~CLxfV2n>FFn!*?>-z^kGj3IcXWuI<1 zd;5=lk3T&+a2sfye(?86-XSK%X}7Kc`@_uzE0P$fU1PwN`8t2e*z-Ar?ZGNfGhbR14dodxJBOI2x4Xaz&0rWgM+#-4xSs7GFw5;rSh zN)xIdmhCPym)qU~=b@-FQWy)AxM*=T*Tb^Jp$VdZOHw_2napc!@&(D5tucL@2Y&HkQ_yjc1-rMn73%OF==Lakgct5%qTv@ZL--iqx$Wq z=M#9E<|!4Ku4qh!mpHci#p;qcJ4!K*%6d+b{QEa|YS{C@zxi9|yKXU)l1A;%u|4z^w%p04ueCnMy zD8)19gz!~|N5(Gra!!=Q9jc-h^~;eIBemAy4l|Ao_}i3GYNkFz$zo{}T^DZc6>`3U zBiPAADqjqiOxj2(NIy=cchfA!Z-h!w!*0CjLcWq~gQ~+ilfVog2=wpxaNF=~waqxO z``;l-{tVPmPcQ*@FGAJ(lyW{+Oq0wvIrouSBb~)T-x#6HG1n_~ETPKdUi4_1$6i!X zq6jaV@Jd~+Lmnl+#BR(zyzXoIm{n6RD&%In7iA#!YvGj-yRAkyR}B+U)qr5O7M&ap+o-bdFvbvH$V8kYKVr7mxc zrw%}QXiS;}lkD_n_!Scb<{R*2j(QeKH?x?vFprnoyXjcB?m@W2@9<8*3%tMLJOH z=ViTN+@a853O)umk!bS`Q@oa<4e=FSaBdgocvu~7d?+US52>|$Sw6v&{k!iBW5n*- zLg88iQ7hQ1ro*)Of3$#}qKvYVUCa z;D8^PtJMHZNKiUwTYK^Z`l+C46xCIe^8lF+HbR=VHf+_AmRV_e+qo&SYZscJkjYDb zU=C-Bn$w-^&Eh20KJpqZ(@p5HIaGc`{Ue-(wQoP#nQp3aLs@Nz(j-U9BtRNx~DG=_$Xh zeMkDdn#OD1rMlE~b79JC{EByYKK0YIq;M`h{X308b{qPEdcSLBqfSP^TOcrALZ3WmWiM`!-wZz131pU-tp>w7Z#_7fO{? z@4PQ{xjjP{7?ry)K`J_r1206dB|jO?#9=Z|HilYO3v*GiWYUdw+=IL@0Tl$EBC zhpMc`o@=g>x2Sl6VWD^$ERE}MGA@C`w>JKWaEbsL+XGM)#O?3zNFBmjxEv8hj$DRs z_x(W?@P` zgx|I#J2B@+j{^)M{vITD{nenmw!Fwf9GF?C3Nht}EN4!jI=Kt~HlkmkP|6R!G1McJG zfARPO0SdrHOz_+Y)}QYaORHnQD>>K|yd@AG`aJhQOFVKQTMKeJ_bJ``+W~3ihWDI+ z)ZB=N0_YDna%VFu7a%#am4Hx+jPGV^H~cnAk~c(a4p$`4^D3T5-*#nS^+*1FO~o{y z4%iC<8+30dLt)g6I>j8W&mIYXXtJkVlAP=1e-!ig!$4Onobzv@z?m%f#NQ}^6DP`s zA@)A>Pw&dftSmWhCKc`Y$&Ye12nAPv1CIO;=V83Bz^CTe^Ky2kud#gI*_x!}VH~9j zl`^H6owDJSVR`M)Q|&>}qKjh8`#FUhVrTF&3Ik88B-(*zD3WJL>vBjckc%b&Y-<2e zu;8Z&5ItRy-9C!aaDaBAJ4fnPD!E*moM-R>IvufAPA=q<%vyr@=*Nj-2rv2jdtY95 ziLdg_KS1or_2^a9ucc1Qzr%H_VTS4pOvOL`QX`(KmwPjpGDUKdjt~b+W7pUKU?cGp zI9lmM>}*Pa8hvd=sZTLRPZW9Qk969fgDv{%I*dMlLgN}5SADookWD_eQ@=V$0RdZV z;jj$*_em`3atdRy*4Op-rS1((DU3mY=^#6a2uyqmnEr_q-h`m%m7nO9s_4A7-Td2` z>9wS!KM#lJb%8X+n%83?|A$cM23q=*=T)Uhv$bmE^FWdiaVQ-dM$Sa5t<7oJDJj+kA4kjMQ zlsMdK<5LaC{v6E?pq>=$M-vrL^#ME%iJnus81YA~pfx|6fCP-qw(h4%MOnvI7F6i4cNVyjJClDnN)# zsb&>Iv>vCb1aA$qdatO2QeQdH7$nv2XSwb^(;S55{a{j4Wk9R)kf0y@4y(^k>%kHS zsFp+&0Kg|3!o=B;GALG>XptLkWStzj&gHUJ%-^riKu0ADS|(YqSZ#vTdI3shPZw0O zfA5xA1ISGLpcF9S6*;7fJzwSVWI0%WXR>^5@;XW$l)N3CEHLCY_~h5(_O=Q4xz61m z+~%7PG&gxvBD0Eh5}Fl!P$SPiZ>jZ$H37_%!tx^PEA2V=U=4=%n0_-1PGM2HT1LwjVvh@Hp~01CEY%rXkoyGZfc?MJ^P~+H7~G&Y z!?IfWmviCKS~}I}qQ+_{x0BFC))WgRh#pV-zkxkB)j4wi zPcQN&Ip!{mk*14+Ox_i$e?7Jrr--YERrS<$k;{k)V z54_b#cFAFiK&FbX6MUgc()gn+>2&4Z5y8WTPW>|V81O0tJBn3#5O_7$F9II6B{TW* zh~j>{<81ht?B3HnE41IM+q$1$j2+5&zXFgJ{CW@cD5{C-bgMMi=rsqeH0K@P|3O8J zBySZ)9H(vvC8m>QiMD7#UYvF2^F{8hMNpHMXe78szRX$Ecyd*w;~B|o2tMV&=0%>{ zqUUCiNkMhSRmh$<`N^or$Ixe8MK)4oo!P7lo8IHhb#Hpyfu=|d4nEdH@TldAq%uf6 zQt^w@kCV>7=LV33!d`EV8gcUs+};w~wQ_s1b)S_8(WQ&50Ty>to5%@;vEnjWnV-s6 zaw3ZVu#`N=>$->Pj@q3W;yUvV4jM`Wjg<&*{;IdZ*mIphW*C+9@$xUYDWG|+*}MY9 z^+{({>a&2-?10SdqaBdY6HTS~ax!@Xa(%q)Z%7Fa?o%()1w1udhx^I^&6g?78}+aI z>c#*7@5QiVAFFi~SmH&MwgX@>1@xEvBo3s~OFha&=L#DZVfL-~e*a#JL6L7?RUJ~m zwo9h#C`=C-`%_?pfD85#`UY^2{WU$%25GxCHEc<2H|U6ZF;k5l#j@}P{F_0s_pvNc z^NiUkA9yi8i5^!Ndohe#k+KaGoBM0xU0V&JKQC6<^1?{kd49?<0W05s|9XF>{pGZp zh=gP?de|_;L~x`d@P@dUR!wmQF5>@vkgbR`Ec5R3WjF0 ziNZ!x09V$halI$FZL_za?-0@XFZFWDGSoS>xl%0EW2Pftk&#DXj{yG1^@|Lr?-Dd%fNjbK-+VYYxF{P$o6wxvp;^haK^tBi z-)Um6kEB3l?Aj2mfitDtog%AUyZ5IgJg38UBn}3|9sna?l4H-Ykz6pQ!Y?HZq0CnT z33I)i*Q(@SN3mwT&j>o%?PXHxJNhvr+b4PZGUWm}kadcZGf~E5KHTsWPBXDvvM~|ewd*An+tUfA3|Y;6 z#haqp$;iHiA!t0a#jzRLbJmKy**(XGrP7GVHzuzA`(dY+9Z+@5;_g>0qZnjj!1R$b zokwbDaL3hy-#g!aHz@w@+4!AQjW=(Fv;TMuf%BPRt3e)AKS2aE>$I;lYTpV*%b1^68xROlXBCv}z>;ltKU2W-*Q9`IYG-{01Aq5V3LrnK_!q4IpyIPzcYAkkom8#&o-GAjsfx*k zXfdc#0m=^rMVZsdVCK3preJCOnn4>$^t8Oqx6mJ|Hu@1^ltBL{t5-K6wry8TDk?06 zo*JM;g@t(+8Qx2~D;rgOr;{Wp1iP$<{&Tb#Y#8I%u2=D>s2eX*$pgjO3{;^&XOG6M z>yOTDJw%3c#7o)Di(G|2)_*Ph>~+x=1NF|Q58Lz8TW`LkpYLpkq(9t#@W~FOx0RV_ z?ESKUX6m76Vzj^h#BGKeiW&;8Rl@dJ1LVHQF)G!yG}}pKh}PNpD$}y*P?`G-_2)3L+n}-L zqs466#HCBc3#ho$KWeNZC5Y^e&4Tdyu(&=w0MtiikaC+6xr@DFVBw7Im|8QI=1r-< zJ_}UvCO+$$Lh({l@luwO{)~#h6ghQ=QlhKekgPQMN;qm+7geQXs4{w=_AS@f^|2)~7Erpp<63*MFdZ1cRf4C;Ip zS~SlrAzF+oqd41{qEvMge1ev{`yWgsLxJrLlH*MfbSo7s@yHgZ>_fa4ZP;}t!26%} z;1&cX>^U+C0&S3y=r|LgAc)ijz11v{tqzOhi?P|U zws9K;jM5OEJ@lD{e0dU3R8(P~-`P?F3n)@;GOkW@=MLHB}dUX4f`lA`5tb+u?c+O!GdVW%mOwRLZJ zU%npDOZ(lkg8YGGd}tGCg;wfd4zGDC6qYGMnFkp(uldlcN*eiJ^MUwQh^B;s12It=kG``TtB-A1kJwHRrAM97SRMaq0|WR6l2WYZ{?{ z@F*OtZ`vhM;&*LK6r-L z?IE>8u9Ob9Tb@q3*5i-#zJ1gRlz)X;7yo){$S;m+{kZr-zFcZLIE9c=235b%R)qUu z7iPg_h@AlB6CQ2|N*6AZ6fi_A(Qy&8D2&nbMaSJ&CoG2-@%@d*U8Q{@6I8DKOm$EQpawq9ucABUk^f0_8(d-dbDp(23R*Fo~ zt~*1#Biyw`<}R!s{?(mP>~}jZ;v;z@>j-46zb^MwtSUxJQg&K7)0TE1cyiT=zr;3~ zwN$waccX5kO$Y1$W#r9o(G=~@LtY!=Z^{}5AYpusKPKJ>&&n3J3le|oZRI8ls4fHz z`roa=u~`gCBC%0XG#3D-t{e$%m4M91j@@nQB|-TM={(3X<2$Dqw~G&{iV60uS|^1{ zD2tKHwkH$5_?i_c)*aj#bQeI{F_S=3MPes6iNTB}VeK<@ls{u&7I_mu3#ID2*Lbkg z=VhaNi65}WfaeG$+JHFUu=PTZdZ2cUf~dLrWg@=tTZ&M(ASLw|$K$MpT+|N+Z*@v0 z6%tLgqgtPEYonjYGum<-%78xmd+mqPI6|wIYv^WP*eU=N%c*S;(22~blJjjadBa$A z|NXIe$VvCb!ZA@>bB|aG^b3(Es5umt#B&?ZFSfzHLWYRz-~A=1@l>h2Uq7%$)8Id% zxz&ZdvhRZ(Ov}H3SN%;FNTWX?tD{&Qp#?orxpMtuN3DCv3!M>4P1i1~V5>F}5FN8tszRi*MLghG5zI(a8m zm4=~OJy~Y7Dq+jwo=DO*)d0h@?$h>$_sn7z-HtTQq8ZhAXI5zb=>>tIapCj~#-oYr zm>oI$AfPRhvFH1g#I=W-W)GpwfgC|p1?KG_fBs&6b|*4eLxMO_!#0NC1LK>GWmD!y zhr>VUOP-Ho;iL(Cwd7cQ^c9DLN?ap3*><6zzDyVM{Xn6&ukfU`HA6`Tf-Nf=L}xp= zT%#bQoNY>5h}8HIUJE!$WFF^&Fne#{pttr9#z|XH$rQJm8_;E(=(b^HMok)L&&~I` z{;3!?s)JnAZ}-m;-B!^4Qb8kY#;`wlRMrcoWX=% zyUK+x6p#4I(o`}VH_>5>0eV)r;egCRx9xMdX{4ARYEEO+3T~PR? z>ed+{kh)bIALA_gu-T7iZaT{{86Xb?)c5ZJbEcNj+{gj!!$_Y-*KkjMLzWOd=7tGJ zvGvF_>g!eFhZ_TAztSj~YA+B%M6Mw?=!u_u7nlC2=Ls23rx#^J-{{{Im>LYvTDK!~ z49iywB^^m$8jT53!{oIfT2uvL)KxAkuo2M=5}+-k_T<}$YSEdSzPb*v+u&0&J&^c> zq+KoBP66GY_I6$Ml3ZS8urEiD^K5vQ@EsDF{PQkJQA)kTJ~~___oo4LVg)37wKmNr z@32OwHX_G-vrP6ots_?Cpq@$iS=H(nW#8+(k`4c>f3>h%S*#AZ0uIA7j`nc`0`V7S z2a%rX`CtWAD1FvgDu#5{e$6C@Rs)sfB=_L09(n#UFPIB@dA1BeR2_{i6$kD;%6ZZ^hawxF+G#{9e{&je%M*b)^B6 z9iKp;9jHXq^b_3`pIBxDhSzib?J}F_ov+(Vcv)uoDMnuzajw98LmxFelOz=4jHzJO zrwIjlQqoi@Tj&WE?61}>3vY*}tzW4C3nqQJupD_7Y@U3E9GrR;OeHLb_igK^v6No6 z`Qg2_Z+&Wq-)T)CBO8Jhv;a5u@!MqIu=|$bak=RVw`@Nc&(H{uB7$dHN>h?3wQBuX)?{^1kfJ97qKUwM4!filCAld3%u8v5j z-!2VuL<+#HVajriatyFHJ0~gB{x3S)8`d{~H9w?80y zXaGnjeO^h`7Cv9e{vrWJXWF2{9E4Dsopn{q0@5Wj6KW3HqrsJOxOe#;VPeg`U1Y@H zkyTwHbvB+Itvjw9`S-evxek3cJ2Osa)$ckh43hE)t<>k~k8T>#4rFVHV+)&4HN?1U zPR(JXPsXaq(R;p0m^XAOz(%2Q;S#w{mq~v4#k-TdO6~&O@8K2XpHJXf%V!pp=+23F zFLLxXTi;p7{Vyr13*D*|kV!?jz(4X|P9csF$BibT({C1*2Md>zlw+7w8#C-3?NN8- z%r@n$MFxsbo~gV<@VakfCy%;RZN4AlSIinO88e=9ee557 z$#LPpF97M9LQN{fyzE8>C=m3&0#_cD-VC(5FPmeqn(!PQIa{FAQQHkd? zvwUVtnYS_}K>2z3+Y_nuD11V~+?8{&^`15TkKD*o$s%=z#u!Bf_>5kE0`PIfy4Xy| zd4gEI;c2p$90!V^KM?Qc%SDT7#Seaw`l)$*cqOSB8?oN}le$ME$jyg!PD+t_p51ht z#I`gV%8N5XB?u`Rz_4#qc~;Q#ylVQmL#qoXoa-|jGOoSWh;94h#e z|5VO;1c~ikyVRn5;3Z5}MxE*P*qFcblTg#fj7pOc?ncnhVS384?jm=udOZGDtKVFt z^rFL`)ycBpenI$fyY#a2Fw?En{fwH=bt;$h6+(f3zqxtd7fA@{U^qY$sp>jX>N>gG ztNJI!4Pu{POe+&~1=mryk?Z@xMZr{#Py{Rfn(CPtW=ku* zap651msfc8{Qttk1<7r2_|dj*f&NYnY+PAsHe zN758P^+U6!cAh_&Y&MLd**&!9OD}HE)`l7e;Xg-+(s@!ZPus7*Xs@oQ>nJc?soM{2 z{Qi=)uU*>^9w6RgA$jX>cmPAvfVCQ!p@^1LS!{c25Id~9QVb{&KSYaVCo`UlUz?y# zI_fBdbRvPKnnQ;eHT20Bx%NQWN5m+cI%jhAw)Y4R@kS1jr`KZJ$R7zmx2EVPyC0^l zk17v!DN5ds#qPRB#$OYMfy1K`XWcN^uUFY7RL45({3Nw6 z;~N>pqvC~G=mg`$A@$h^E^0Dg4f~58jVwHv0{no9sM6xLk|xE@ppeP9O0A9jd#XBr zUNR9dF=V;gqJ#-AZTjv-elDz1Df7Qy>DGGcAjdnRhVfJ((JOt7LB)u^UpY*U&3TlfHhfiy*rkWnj!?jw&74_) znw5iqE-Jnrlw9ohO0Iv#NG~XQqppTh?^$13_`IOTBV4kcm1k0s*W*@{5FwKohHvoO z!y3`1Or0NPH?G(@(cRxr2Tv~Mr`UP}nf##F*YK}%02lxWRVK?2FD$9!wqQ0W>Lro# z_jRPKV4NVsH`n-PIW*~jiqiRAXsx^WU|b_@E%oX-Bc(H9yWdNSbktm9m1w@!lkf^v zMXVx=&EER&K^o%abne}TpdRgadS~od^*_$pef6sT?uHi_$lXDBR`?`=Y%+1sb~g_>lD-|6c$GBBBmh%WL%v-W1(CG43Sk;xu;B*mfG*P8v79Cw<;~fA{zMg4EMHHKiK=51{`&25<>_x$bpgc$|ROyY7nYf4=j~6||51 zU!TicKSUFNEkMT>a+M(c;{ViANRK<}-&v7iLcWiyO^2s~&$|Z7-QS|yr~U9Zn|@R0 zi~t?m1E&A%(*L9lSf?Vu;(q8MX=|GqyFuDczUCJ%j)S_=l(T?F!9EqP5-Ho z{%6syD2PBuuEZ(z(LVLc9UBPYkGy!l3u|lIvw3>3eeO+qEK`dA-}PW|f|-2ba(HO6 z`3d|4XrQ3^)BMw$;POM@uUIGitF4y}*gudU0YpS7SkST%hhM0BXbf0tCE`gTvR#G4 zusJGQuj0}#sqjNqdoAw8w9(G@+PZNiKg<}kDgSpWz!qx4SCj6o!TLbp|H83?;J=sd zO$w4S0h-mTfx(G8ZI7x!<)M$p%O7jimlshY0<0=ICPWRG$_3+!uikQ;Mnl-J)f$c) zpijX{$MHuZe<I|*j?Wj=tqhs*#3 z$h~vOCm4^_Fz*A>qq7{>(J|K(P9k;e_h0sU6?r2E#=$zUqw7b@lxH{*o5^NqW)NnW zXRv*@mc2A#KmYaLg8(q0Mwsd`0ple9Bwirni#8FmkU)mx)wEvqc4s%@dk@Y!sNGlf zz}p^X1CBqiwJ4I{Y1ZNv%n5L0UtzyCi#V@cAbAtV;TUN)ipDR9zZ&(~u^?zV&Vgcf z03A)-uT)UthFG}+I|mjWKVp=@Q(+Zbz$R%8x4x``a{nx)6(3`M3#3n|`9J+7K>HP2 z{Jqj!eo_0=9rz;#w9Q=+r2?-?)!PDldX>z(Imlx29_Jz65IP)08v&>g=PU-%$hdz^ zdm#80oe$H$Ls7wNe5EtKC`^SgVr&#l7RF;tDUirSKAT*&>eX|{yY92J*SV4Sj${|Q z%^wY*;w21JN4++qkj5-9;woP%Fl5nkKefzDl+QZO{BfCiQv762Mtw&2|H-fq2k?Y` z9Nhl{3F9ZXG5t}#r7}yWw;kMgdZGxJ$oN`zH_W4thB)Mm$lFLVjlKlTxS|i!Et?M^ zn4i1!F_5~Q)S)g{A4EH5%!t39hHAh#x)L#9bVl@tz-buuNyD9lt(DoY+gYrb*Ap_&Ytou(o^++^Y5pARG*=u^ z{y)s=Q4;l!=xu@5e?kr_kWlE8YXn$zKcr5->S|!@>YxDTz+we`@ybb+nBmAp6wx9m zyF8e%S|EwXK~F9@O$Uk9@mzX|&GEkNBp`ZzquVZBw->N0HYI!7TOP~) zC$626pY2M0SAk;V2knqVAG2Z;LRmqFmKGTyZL?*v1MM0>hKd*#0b=h4(LMxGKjD#& z<2r75hrhFPlIo)yDqcUZUsnb_2doN|t=Q@2c9L=COD_LV8G zIdsA{Y|+qsRo3iH2_@^_gc}Y|UH_@TJAyznMxaT_LDYjRFaf3j{_qnlkSg-v$n6QD z3N;9h0u}(BM&Vxe0{4OB;|BGJ=U|%u=?RWcNt+aWSw7!i-57Qou~#=owFu>&Xr>oD zqhpnoxHn0OA6`?UlJ1$u;>C&sI?M=zsRr4wJ&tZd!H(;wl&yyiu<}0~Rs-gHpsV8U zcD7E4s!1EiLW<4k>W#X1(%|}}?QQOc;|$ITqxK9rIq`Ig zj&9||H}j`eu=54GOuwG>Jo5D7yxv1}my0dbLFjxTmRF9T8flp++6u?JTk<}~f2!vA z4D7QBwV2;%1nRqpNR9Z87H@TY-vx6k2S)tR-hpVx-uEPxSx)=`X5r{YyCiK<$oqS~ zm*7POh-3k%%8Bovs$eGivm!w9N}$oG)9(G{#+|{4&;mCi%elC~mN^rnz>R^%e0M_? zO<~}c*@F}0(a4b&W(BzwFRDSrfdq;2)xn8L-gCDRcdBi>0~s@*p@&)ylB*yXZ`6qA zZn=^zPQkesg%+cgbQE^nw~qZwR&X5;T6n)B4a`a1h;+|IVyghe^w7zcEK|w^YZ?P< zYK=p+j(zo}Rn^+wtjBW2Q<1_Nxc?Yb$@-3Jf}q0C>>9KxOXMmAYSoiG$PL^7Etz^+e|BR z;sv%5SsHG9a)9Pls<=T{z$N;^%`U(BpNSOIC#~IxkTa`v9kybuyz3t`sDu++b*PLR zTotv!3YOcevjr~FBXCdl%k?}C7#;L&pr&-YVtWGUKy_JXpnca2eQ)_$ z?M3Fff0yPvQA;QP@#5E;=-adOV1fqUb1*K#sq?4CF(-APKs#z3X&_`k7$Qg1aT5z; z`364%oZgAqGy_Q1VH*hu7C&b;42Ra9(6H~7=AgSC0I?@~G8Q9R3^f>MI>(M9o#jLg z2X_7ugm% z&}`zq2ElT{{(hXA{`80s@~!Bc=S6r?^dBVYfsk~C9qQsj{blu7^`;EwWl`Y6Vwy$0 zvEnym!eeH^6S0VI@eJN{_Qwx>lU~9RCYP~iPt$`5{t4C5n65fb&|+ z_E5tk2fUb}NDm#Xz=}dg=j``Q(YNH$uwBa`<-wmm`A=`k*7r2it8$z7Jg>NjU>tc+ zwtR$U<5==sv#Lx<1PTCkmNFaug<{3EZw0!dEiV`jnz)~k>gl0iQj4dS&$tR2w3EE= zv(m4G9>_$hgdRS%sEm;~m82sKA4I*6rocW@aMNNM$ zrwL}H+0=}B#2cRgguB`OLhW=aF11rNDAtL7D{pv9O1_BMbOWP*QS3%l(^hIjw*Oveft^dfGt0Z4 z7s;cN!1Gmon8+7wYG_x7j3I>B7mC3-RKZ^7Ua%Q_Np1wZ{(fX;FG;8hr>KnxNZNY% zQP&?dX{T`&$jV6fFzDk?21)8lwHR)!P4+OjZNWPg*OSUTf*t=V^&GBp&sd7PImwhd z-O!=nSR;K~u6d>1GTCit?=YV@lg6@Rn@)0}$?W0{#)qXaU8*#yQ!brff-ZU%$?!nD zT~G55aDj3LG_^AktSsyrb%Urp9d$fk+QSXpvE0Or%<-Dzd%nxVWCge;-_cUyrYkVh z=UVA;PP)Fkw4`9?(wccysdaErZ?2(l1xH<34t~_{=2iT~q^NG&PrORUI=}_ zhG0JotiS(Ogh%DA)vN+^b-sRfH2ZHXIE`M4csH-+jCCHza`4?2LE1e4JE!5zU(^cu z@T*E^9pDxq6}w=s*!S+WI%Efv$*FWA+MN?PK)I3=xd=`Q9T*5O3mvKP)P)nUBdqyH z9z^5NIkFvP;&C%!cUkLX#23IFMVK!cySIXLzuUMDLnu@d#1v;EBL#@{YG9P}BW&VD zZZLDE1gMZE@q>ye9-wPZ|JG==n#2fJj%f%@%jJm^{bQt789l{{ zu60ZQ+N!)hQhyyz>A96wY)0`>fTmOS89(w~C~aMv=VXx7QTz~?GErUmc&xMeOnCs) zBN2f2w*G^p4fO{b5hgXr`F2Gwt`GvqIX;253%Mn}^B-x=GV-xU*;es9Y6LDcTL-H3 zgFiiT=A%>P71D5Eli}Qt&Th?!&2g&bg`YLp0?(A`7@Yeb4O=l{Yy|c_cEWh<@$rn`8w)9%6)(}48{MoMS(q(4MkoIrK?@GgcBXyuh zTMAA%3(m@Iy@=wW*cXX~ZLuSV+pT3pmT2-0q($X=mdq27`>+VBvncuHQc~;_`0_%or$*~*#s0ixi)goux#~h! zaA4DT;lyhi59qj7<&4#vC{98vmo6-E1&-yJLfUxQQ8oSgsXTyzATs2)5*H!^A_walJ&Kn~~7G$o%L^c9!RJaq=oGCdse!jtjW!0s(`3<+} zKkK~n)}6aK<$sH){BBbN(8!tOpf>>_=Zawj-@|fMf@)|2!K1duH8)e8`OcJeZLQ@R z-zZViup(R?piur>VRVtg1rLz2JPK&I9+_M?{iqGt7yZvLHdX~yDKfoz!5Rbka)bEX#r2&5H(#EFy-JxAI9oOO zbLeqOO3Zs5Wa@iqC~tC3cgvMWx){N?FP>snz~ ztlXlUs_LY_-sb6iSznF;k)FB!aR(QnQiwXR``!Td`~wg$POK{Q90E*`0Z%*Z)v zS&!s_BeHWFQ&q6iD#8>}2@z%f2iUNeWPxU#6GT(&!61^4r-0^R5W`b4!qjidHl?*&gq~!ZXc3P_ zne9BNrm+4X6eo}i;p7uh#4S6AMtu>H2Bd9=MfmXQae4lBc~0?q*xh_OV~=(}S0~`E z;d9;E?qpMYZ)8qs9-i6s;7*Y(RX&;HD*q*HNl*;0pGis^k8A*j^;LY^9tsR(2@G8_ z2vfNOjRG9}`2b7NKqu5uMphfhGwPqha_w!U9pYs=4t5VbhClQYCeJaPOM}w%E$ZNw zRw5{*id5kzF83a|Ltq{!I)xp$L964Iwm})~QZ;fj*mTOgdMxnmNz5+yu0A|7ts}G z;Z|n(l1p|4Pf(P|w(%ccJX2vZLVeX=g+tJ;ZWgt|$y|Eag=%q2UKWsgwp`#+*TP{W zBKz3H5~1xSt(IZ5!ixqn+4X%&+IY>wj+EJsVr`Iip3aYNtsP&aq-u-4sXl)b{%}n> zx2?2E7#T*Op-h%7Ras~_dYsbVXvz5H{}gzul{+k67hggWz#cO5Ah{}Yyp7E58N`sA zpOsEMS={LMveSUU1QPRw^iMGI$o3zNC}l3a(OJ_FAraYeX45EYTG=(jSp;YK4Clch z+(X{F?MQ6>7)T?!3|zS6yKt#?lDjohQ~KGPA&vfWPBCgFe)9700alrGHacBgijik? z`jJDDx?fV2P9vKr1$IPce2x^T%;IN`-@NR!3&lU=9}E!$^mh~j=oz~~RKJt`gTk6f z0JP9r{~PVnnAvF!++X|XZt*3CxlmSa?-+Tq`TYJnUA&7p0Df=dpnJop@kQ~xbmxU~ z>OHSLo3;Vh+p^KOHJ|JQ!g4;P zvmh_;jz;lh9C`{16@YFO$BZ44bqYW{>KnE+-1Tp$_}E0-AXye2mAxQxdF{PcdX#g= z-_WJHj-xs4JLFRjiTlrI=-^W0BE|Q}bBk1(?lG?-*+zE&Cz4SY8ZkcaMJxUdx9gJr zF~0OBoyS;V`$<>s>)nEuYdP>82s10|KxAr`G@Jr>h(Ilo!UuF%5(Y~0u!#aYbGH;7<5?frNh48(s*&rD^GUL__y}-?3H`wz zUGdDB(W#aw-4~a&Ths#jNK~|^gh&SCdO7=F!B_4+FYm2N$#*p0bq?8TC&@dY?J-P}FtyepfaIEs{wbN*C?^Bz(uQ(DvggQ;*22XGwx5 z8JM6uy%1^Ze$yI~1N#E_tw9`kLe)5Y<{Vk2>FlP=cAIt&;@)heKXmpCnChy+E z^V;o7*LTgwFX#yNHc%*v5f967VDJGHNVLT3KCK?y!rzedIZ&waV-~OCQ#*+v=m%=! zsKz79BQg$A8oWh)&nW3Fu9S>^h|(#bM$?M=rkCADYPwdQWLXpaTIRjb{dY4+k<7Q^?#nKXNeN{E;Z90xK;)%_w0fn#nO|gZMkylHP(BS)48Rn z=EsUKzUi{8y zpcRJcghriEiW+p8K`at0lg4Qri>8fNCy_*|tlN5fxz5ITjjul{;y>CzbaIRImdO-+ z2<2&>QXrtkC8}B|Av>({Tg9BtoN;Z!e3@~>Rmb^To7n7E;nLj` zX_VrhDVv3jub3$3;Qyc!)1yxQ2duTKM@8j#X8t%{KSoC5Pzs+}cI|c?Ibr2fAdJKp z3no@Wjrbr65SKHkBMYb&0t!v&bh?nUN%3PjF&T;7BH`VUOHNPg?1Dfl+KBRu4E|Xw zAqfwTXe7S>9YzM? zC4O(<(&!&vc!)mn(j%F-EXpqDPg2Y1+kQyBF;Q~HaeTwZ?VTE@Um#*`@gcREQ+dMK zIE&G_h*Ced-=KO$16;h#XwxLDc)58EdAdW_fcPT_$z(mJ`nZ+Ip098#rCi-#M<+D| zGh7iPItoe^yl@E7mB7M5Jef~VvrsK|iN*!1KqacWYQxa0Y*u1rT39g-`Z9AT4Cf?` z(>gS{tX);6XX{#55}to&Y2dR@Z6&wrCRVjYJnL!fcZ8vz;wWl+loO4@ zGvsGaaBIap2o+pYxSp4d%hBIo=G1!|X@d|3=6;H}JV6yxQcspN?#qCh9x#96qzCGi zD{wf>!zK(yreia@%NNVBCxxYim+34RymyBZ4L2XqM@%K41Yn*)QrzJL@a%Hp^v_bo zi92K=?>0$ZD>s@@eE&v3iyx7EKQO94jNKW-QXRuWO>7o~ky54N$AHw3JV2Lt&Lt$v z2rCq_t2%9zqBa}#ps}KuZ9@I-918dkEYt8^Z{{l`&M&q-TAxZarYHULQ5c0B%~N|1 zk8PVIs29-YC&OLd*mcK>SXz$%x^jC&KIE0?4zu$h*f$PVcEadd-f5S+>sPMSpa$7A z0LbZ7~l?owD$pX$*>{KoLC($N#r?elL0~fTlk4JUyz=&MH1jUB^WxaJ}T|CVkjN4UL#kv#%?y7vTdSGJQ!uRL$9X$WmG!n zyu?k9LM9;*E&R7Km_&{+>Qz#-PNlIxPU9RT6Yd-eGK2=L)-L;}=C@VQ(pX*&t^J?q zL0TY|3RL(}1uTv(Y`JsuDVxQt{@PCsW7uEC1CakJLH+r*pOwE1A@?$~6X9-$b=_CQ zSQ5m98#YK)Ib=Wz!TO!@9S;nB-4z8`CWsH9IMIW$N3@L;UR`51s>7qrjbF%$Ss;vI zJC0?sS+W#D9}rz8eaOhzB&S%4809M9mRF4wb)}F`MXvC{Dx^X$kd=_~HXc+FrYC&5 zvTg@k`~2UTzJX;R-I;P;7AY^|byh8w6=oi(CQB?i9q)p2=g3Le z&j!*qUcp^(cdaDWZep~oqIAvecdK62DeiIV+i_?&+8;(P42X;;dLI&Ao}aY;Jnbqu zZ>_Z8v!6*R(f3zY_Kl%c5M2>c6)pS*#}-(24{Wj4<1UbD;i)u5Turgy5G)0|5-ac} zF=8N*MxMn?{2(FukP@wzbCh`l?%1v+0{e9uLZl#7(y|{|!@8y4&8qkvoz5PP%?45Z zPMk(yfI1vi&6rZQbZ)|oQHw#ZL36ZGzx}H9X&@B?7P!U579P;q>q3@2B{m<+S-yf2 zlxsul|DEff))IgT#Pn9|KxBKFJrCp9JVxx1grewY#t-HSDh}3&9S$RUhZ;`1aYnnt zI)`e(v{j+N4sqrp7aTzZ} z>P{KL9E{K^laRcJWjFM!uM)^l)7%#$8lrTf1M;GFub8GK6Pz-| zZ8hxPCdN+#z0W_gE}nfM<*H%nA7-G1-nED==rR~W=3vo~jn z_2J0M{KBs^AR_r1@Jn3aZ}Lx1hUfKXJYyI?+BXL(ga0|@NCv_)3@of!fR+V-@ZsH3 z%Hqra$q3Ai4$PW~8LJp} zkyZi>*Dv&VICqN0GI$RYP}8CX5+q7#k}1R}IW5Ac{CG_g9iVYsq?4)b=TjSZDeJe3 z-n+E)59w-Pqk3T@`r+7Jv5Fn>Y6#?5@wtj}xhpK*Qk@QyR^;=|%WHv%E<48SPo#Q2 znT-By0n;$sx1fJ_HM&@1kFH+rERKgNmnN*v+begeC+MHB5Ttqn$s3ady z*Fh##j`gdY*o2hhr1dr=?eZq(#-(5yj`_JHfMv{zjE?MKosCUgcfY3RPl*PGNKip6z2MwB{vlz+9Fy|nqPJ+QiJ$Cr04g!xjL$W%%rZZ-Xhn3_LGU& zB3(0ca%#0wH?bwYMM?OGq1g z-u&Cl%7muE@BXpD*d1{C>l*d#Q-0w35;+8&Jn%i7=(l^ zvVDAE949@BE=r_bgy;&1QnjS&eyKhIQ3YaBOW0UDDcakB1(On232G3=R2HLtoldu< zNQ2D@Dx}t_sI{(T7SF|Pk+Gi3V4fXHIafo~AI$>+?ys0VpnpL7zJTEEI0(n6C}$_{ z6o4$rIcUeed>?5N3k1z=2dv`9=2|@VYWu^18M2}zLo#K>4611GAx@gcZKloe@@X*? zPd+y$M+yr(e_2y{yK3yyCS(oG-~AF20wPB_>j%MibiKnX&R}r9m^{%N$f&=X_r~m%ilcXO+poZo_^C77+dL02~MKpg@b9cV{fg z?F1sBAOe(PPCAJs6iQh~tyt&ptv1nT2(4#9;RGJ1pqmO6mF!^vKDf?AtSIE&3WtWs zq=Uk_ruq7NmnZQOo#a9QxOk(ulsB4-){QH7ue2!`e{2sVhf8?D4*(7Jf~7@AMDw`L zBl>l_HC9_(9d5?hz`8D-sUaU~rZ&*Kam3B!0rWZIvZCIl$)lm55%)@1$iSk!28C3a zQ071Bi)MWkTI_YBSG}tjh$UJmli@@NyR&K;DdGmtSzJ1jrDON%!eJ63q7%aJ%mpXx z1v_!LaD78Ro|k>%+nh|x+$vnq$O3wu2IeS8zcacqOq%VMpWjT||1916t+Z)a>Suk) z%Is#}>890J3=F9wTV(0`oi@DIm#~sY%(>?Qx%)46_^4NCXE^BGOS~*XQjVByv z%ojbHX$Semjs>qdc>8TyxjqIbeBLOQckR#!f6#H%7#+qFo98u z=dg*b{yFMa)6WAf1bB$hLI#v7B^~$1O~IIV(Mq2{sx;Kp3QDyzOj&joS+*53R(-i~ zddo9CZX4mH6#X{ZN?!5pd8il&03`;!R2hHl7_G&~wiXLn4z`zX%dg&ctkJ#!(20GA z=tnZ^mF14;Nji)A{9lk>gsOk(@iYZ!g@f?OEQEk=_(yQWdmhR2mDt@@B_) z&01AX0v)MZ7U0vc&T5j*SxJ5P-aN*0C47E<@q%pbK|i zoIpYU%3Z&l+{eLWE~{+@pt;|=#^}3#Smp0GGBEl-7%asUsM9eLPN|@evCmgjF2V^y zXIz>p`e~UnIe$z35q?fa za?y{JMb$wMA!1X01cn;gWLLwMlsay`a_*P8rTdXBMI#bgmy{KV2~7~A?fv^##`~n# zH=~7N&Of8Jj)fJfEPlZIT1xOd%nMO+?@4j^v}EyCd_a;Q!47~9yY9v#fgf`_z_yMP zNB841UrIV?6LK81+J(>#wVFgVv>E!_5TaZ-4nR|`CmcpbceN4(v=e(^#g!r(@hjI* zNU!42pT(p;5-P$GD$5UM(UE7^lKo^Wr8_aD^;!x$yec$xYaGpe(3=18CV=F)xKJaq zt@-no@N|;I&?bA7%V{d`60vsp<3U&Ualq($_8)2x;VXlg+!W^f^(%`yO#VpguAxIQJ ze>f-qq`Ps&*=uid_I@dRQLErPZm{}kM|wq0`j{w$Sgy|d zYrdU3RPllzCTEM>jRMv2WNi)sR8<)^F_bwAcGBZK6!hX%Q;IRh&X@#H@UaR3_dZD} zkqwNng?xun-Z>=zhWL>t)_9EzhX_0uWvD?qzq~JZDRYyI>@7p%{etr<*)$gM8N3N; zae=G9_(-&+nKcBe0GKf+aw^X~ua9{e7&$GtJQW`j#16>I+;&jJfWVg?5h6q?Gz0{2 z6y8)4{V*Rc0@^=SP|w{aFI3OhDA9c`eyKh(ujV87m$64e|4NkJn~66k5pl3Z6GXOv{>s80c@>Vt9O~h zPU%{HU!?wY>de6WkUigp*Pix@^>d#|F3_Z3NDgX+-9WywGupSHgT)gO`}(kK*Z?Zj zT&}rte5ENv2Mk+Iw$&!vVYBR2INFjH*AT0lM61~$s(*Xat8+1?t}vu&O{A4k$iRu` zjY1Hfb+=RcX8l}p)t&Q;wB`yPLi>#`v>=osX4xHHbuChbX|X7!#v34oZTpzgpP2UG*Ze%v;p0s)A~}q%j+%` zS=uK8ZRBG*E?yC&9?HjJH zMLT@Y>DC|^0VrYskJkwL9(6d$HkTs!Zv9^k*v6n*(aa$^jM?Ugmxg853>d zd5oopy#kiGb%#Dw37FHt=jLJrnTI}_uJ8BfU6^l5Oi#U{say)6YCz5Lpu`BtLt1+Y&qiZ$4Jfo>51m_;3 z<%h4@8Wjl@#S(R*b80!jppbx{gb;aQ;eg1IrI9e9$MrIG!1tbgVSU~WMZEEG7=}$> zcbovH#80pU-2`z(p#ZyBPrL=!9>U1hN1~vO0#+vdOhEiqy_+q3PM@X?MnVA70nIFg zhRHWmwb4XiY;%+1ZCX;8GRHOqIUNcT_H(`CnUCfi-U@au_?q?t0MwwMMgk!<1{qVg zX!11YK?;?@n>yi9#oWKX2ut3W8yqu^*j45;DM8PqW&8m*RH|TwLzu1vWzIrxX*>z& zIKM5JLf4>`Ize0^%90D>M9?Aig3O;i$RyH0IAR=E(99?c#Ppb>lqFaVI|puWngxJ>reFbN^>Gp2iqYs%8bNLGw8%Zk#R}oz z!^+eOltb(JsMHE)P(0a3>iTshOj@_=d4SuLiU^Z}6Of`%kvVaLX~9||_W2VJko%1a zDv3(qMK@6FS3Czwt}@;XqUQfvrvGxTrcGaGTjI57#-zV1Ve4w#$U`uNB53F z{;LBr4#|`l^{77kW0Gwn{reGCnt<}+AvPNyixs1)OZv!5G(2P!yhPMN^5D%c;X$WB zqhA_bT6DUMDAq7Sc_(r7T#|nf#=d%z&xOUm4^m4a1t|-~3j-ILe~lfG<}?###tCtM z_t*$V41}!LbzFfSe%uRz|3mV`T9rnLS<0|LKIa;wzxS>DFw;|G$e z6_>urH(fG9#)O!CV2W{4448N=_I=zK5Lj#A!#LJCBz^!fEN^rMdBII6m@!zSU+UP%NIVKRA9XY;*Qmjd_bkxNuD z0%iu{5;f5c$;wrP6*tODfA`;>oP(~XjW4g@)2Xz2SscC=ag6lWrT6cR<5_XP<`)9G zPaxVSpnQ}-Dk3wu;{(@@+iI3>6#sxLryXT}7hv(!th73a<&lZ?mR7xrl7o;@H7*`v zDIOa%+B-lQl&N6q&_dvGQU3O=K=N;vQxCd!(eidH`L{=a#uPA-V|9|Fi>2*$Y4cLM2rPB< zJPK_SLi6N#y|Z|Y|Gx@??CAgF})MbY`=a&p+^?V|%%XUi1$FiBiuJ}>l zee+1uAz%UGDitUF0H(e8C@mV?+boZUG7l?;KM8JgxP9%oGpst=LLfHH*g{rN7q6T| z5hH@e9%?oa=UmA=TFd&kMuBwf7@vbIaw_e0pJEo>`7bbDMWP{N>Uz^w%LrQOY!%`K zG>J*1nju4(?AksqT%DFdU2k5eeVFWDn0C8fh@;l_jx~fFCvkpaOV-49+e;@+U!J`-oZuLvfl8E!Km-tGJZU z7>Bq!!HqGMhciQq7hxss1mj(yc~tb_sxQ3_ADeYL7xL&qkgt)wPAchiyZJ_+evKyX@N7nYud&bKj>gmy2J?9ht zagJB^%jfywz&kM{Uv$B(rx{H|X;gpC+gb#B!oYj73B6uL1TTWIRYGdqTiNp4Nm`f% z*J3ld4ozJ9_mbbQwm+XmBE4FF`vh@h9mpN!;WF}b=^z@vl! zB#3lLY*Cnr^E1=hGcKG3Pod6 zo^Vjf2w3i_y}(7^>N0CSe|?zHjQxx|UZ8x+w{PPwKj6N}LOsJ-@Z2J^lU`x9LkTNl zFYp#yKe?O`=d_EIR?p7fy8J0R^t~~=+KH`hy?=;kO6yq=uSvyOI`|e|T;Ln+ndTh- zAj_v1x5a|hMf>Cc>#IKFOMw5=f-kDX12{sR8}8t1*&or^c?ITzvxPDikt*o&R0k;x zH5`CW)R7kzdSS-=kdkLvc>6b#5l78H7U`lghXFLm$wY&|l+IRzP&izZH4=9L_5BgG zR;O5k~z7+#tCRl)z_#acRP#-yi zd9aq=3x8%O#LV25v(iaI^-3ZbU++Ss9lq_cU>c85mbsuW1epRogLNPU4>b%+&1eSf zYGS5Pyp&uEm;#B$flT2l9D!HpaM*(U@xH!5bm;??j>8}omqa!ssT^^~%iJm+bBVM- zYV=)@P9G_Y+h|D`Zwt@qLhj~o!Y*6VA)n{0`(@^qlUdKuo8U8D#v<6fyg&D@h&r$T zg3m(|^4~Tv_M|!oSkid1w|Mxi{mjPwtR-}fG)!%^TW{RIos%64)|+k7Etj-S*i=mf z2UQfnEg(lF4U8$#(+3sB&(_6BP0CdmMaXVI(*0+qb#n_wNVxVG6(Avq7$6=PWfD2LPW7$~=Ymb`xP-qEoG z%v(ayi9q8De)}wT*CtNu;&y}9LD$W?<$>|s-+S4#(E;1S#H{*2I7feOuc?At zvel#+A0+tMGH9Vkb@7xmkl4ZqnaaefJTPxD@Jy2dw&Ea zi|Gelu^Gl3SD}VgC7HmPMG9~z=^Y#y?KJi_`S(`}MgIaWV$|)9A9?^BCBAj1HF6jY zo{E)R6eUMwcO?XqsWVoW6@d39hC4MHgHS&Xu#z06!_ddBV+29%FM1GwRl77ZeWpjO$}eej{V zI@O5o)A8--R9z?}T$l`8*yK`Cvoa)eswCZlDcA#K(HRFQ<0M8ZLg%;wmTk509Vw3jqLs@{64k! z&E#tCg)Lq4&qLdB&o!LQOLF_AzO|Oym-eT(x7YWtn|>)R1pd{zes`iEJeg&Px?c!gsy-b6<|DJXq|yXr-c**lpT6vDwIs3%D=`_u&8!ePQu;zZ4U)X zvC1sGOk!<+-h%$n2jh88;2-l4s^_ixG~c|c8lC%nMlD~VUrE0DQuiJarru)P0OMTj z8Mkdx8}3a{@zGM&bW*U zla7~J^WPDVhd`fiGXCdjn=@>qFVQ+z*e=C@Hz+Lx05ix@BaEH zM|IE#SPf-Di|oR38Q4{$J2g^54jqH~9a=z*RrPgMqp33&3kjkemEwZgI#`o-;&QMO z+-xC(r9TFHh@Pnt^QvmrI-29b!dbA8MSX9m^UpqvPwVizj$6WCvj{Ri9VZH9FB0)g ztWy7!5e3u(awD(gj4jGEpl_P8td3ktvAZh7yEWw94IHG$f572KY;fo`vzxQMkgYg5 z&!mMds}DJs|D|oeJ6W*4`P>P_I-V)HLLkY0{bQn_!C|Wc<%N5*F37!nKj+lrNPP2G zs{6^duD8dM-=<|k3+_%8g~u(nUX!9#qmB^~SllKRlJ$*?)IMQ=S@7LkHm9s4p+C+Y zr$rEhpduFQSB>l5Y)Fb6W}9&L@5k&Sh0xM5P1MxW)Pnn*6_0Xe;ktGUS2f-?*H3RN zF-;l3xWx@C(4Xx5Gio`;Kn>ytT}AK-nH=Pqp-R~-$&_)qAkpPjFrPmjaOC#M=!&1c z3$t^3v2|&!Y2mJ9)2vzinLaL;CLM#3hc&g8uCT?7H9bQppYF%Wc)~+}$sZRd+K9p` zQ9umE#$V7tde_r;#4?+SevT<*5~m-3)dU9WWDyH=M8Y5Lkk zAQDkT2c{(`SaERf3zz%r_W%Hr&9mVOY=d2fLr((y^TIKESVB>K4-&@#C$UHhQVhZx zheR!MoiEt(uJg-sL*{4NJ00n-L{R)pr-0t`-VgsU5Y(V|Y%iW8O?J#HJnh$Ja?BGm z7+tCSTgqcq6ns8GND>SEfRZ)mhJMRV+pSgF`%{_Z1DXTnpR-1}!1&3G1)iejEM6}O zA$P$$oyN~Q=1dwm#kC`tA8#(dlhlg}-*Bd+f4hhgJ%}MX{>#l_keZH%uftQwR{+td8#H+dCtB;;5+(Y_d z&jzVYk7kWJMI!x)bo!&yDt@$@El_Nvw~v=TKWHQ}*{?#&e|nR6%=bl zkJ8ZEh*4k_Fn9oOA!v9?pW)|mj`z)(Vso(;h zuS$(%Ft|h`BU3aba#;De7$vrSk*Jaz)2Q!iOePYdR=}A_?*1DciWBFq0qio-Y@{Mt zef70`R7?$qw-Sx3I~9`2w9iZ5)?&(CYF~6%Q11SOwzfP0!~$aRaR%}(@Ip?zA!4tD zs5vUo^*lf43{{sc=aH&-IBWftjZzK=sH}I?30df5m!2rIgyd;M;0_JOQ{~wGh&Q-;{f+=GqvKsQHV`~ zMNf%<&BDcx5!CbS4X*4mz?GfjU6u*;%=?R?tp*9Q-_3eqdQOvs;$$!CS@w`kB zWzK_GJmZDcL?}A)7%d$7Dz(;L3!7n!Cqp{ib2AK$C@z&Z-}6HslT*d;e6)6x6(o{RXTX3=kG_% z?#}yfYmz_Z4_f&B+PM;aUHRkfl}MAz!9BgTK!)p?(ad1E10f<0wj<$hIdl&FC(Ir?GP$FRKkY|cMHgjMM^{o113mgWa216V^X>D zB_LYHPr8B3sAj+>Q_&)vTBereVBuPKs7Nbjq@woK(j3kx#n_WBp2_eB|IO;)5xeDI zsst9*9By)gY5l$p(e;qg`0(xY!a>n)4fWidBP!yNtP3uF)lpx(hj1dn&tvc9B|fqd zogr!;cV{P0I~sT653;2|x}$z1bd%+f6Pv!8o88Nl?L3mW?MR5zGCk1DjVa<3TF zy?8&QVbit}F$*b}Nrf9DslaIR3Bzum&v|FeZsOkUbg9geP0I>;h3%{&!sBT&!qxmZ z37>5{BC}b(s1SNN`R#h*x&J(&_)ZE|O>pnrk*#i)>qC)q)~r_$#H%9F%V+*NfKIqD z2D4~gZ1CpTMz|D)X|w&HTl+5FmJmKWxX`vy_FQgADpH{bEsE}RYa-UXnr|EgZ24ek z=KbN0eNgbj5AWbaJNBm+$}|W3kZd9S05Eof}}Sv{)>+#L&%2MtbXdM}|ieKo%I z;5wZYqce7uRHIjBy-+<@IA5qyszFqG>^1mhah>}2O7|b`-`^*W;$O@31gzd;1;gI9 zob=ja*1XShqOf6Au?YEqE2y@f`UbYw`4DF{_zwgf8luX9;{mv&F(`v>LgKR6Or40Y zV+KEgL(<=E_9+|_wM(P|ePf{&zC~v8kTOfK=N`(9Q?I!G2=l<8_lSiar}FRcLbyMkD6a0C zJ`I@|>F&sRBkgj@QMI4FSY)#?X5{J)Dd|pfY1v?aU&dS=tv}Pf8Ko0$fyI`t=eX)B ze-eVP^xd_r3(b2b^UkZA+}+Bth~TB73#*~;ki={a(7EJtUeTCs8f|m_@W37{(pLO6 z04^1`sqSI-Hc><&t;ZB2m{%}9bZ+@(g{y{o7n6Ya0%(9|BVKqK7|V^0Z1lkX+r)f; zeJ%ZEhuZPZ>(Gq$=?r<6<$i?o-kp{ub<7%<-%kE6$}04YeUd$o^h`+uH#zf-c2jJ3 zdP;lL9G5&rrw5Yc`dh3l^yr0+FN%aMb)6-x^Q9+lsOqvR16e4?wAn^MNJ~iNh{*vi z9gM5*KOw*Gc%vHh@ntrx^rToZUUFUob#6*B(7H%|*P{7RG~~4@9ine@V28~(P9a`J zvPsb^G}^C?^tTDIo1Kl%;jmrEj_ka1V}5U;Z`kRJLL9uT1*?|8>5|=s&qpr1BGG|( zQFO-d$g7=FVt;)=CJ?K{i`qh9xikH#)NF1yPlzkb&)Nsvu-qW5RKAdKaJ-r3(?INh zaz^O{4%<{|*mU@|=~cQ(H6|eOSsEN6o-IpjK^WexVB(fBD?Ifjs+^k5zN;*`0h9ck zRN)dPc*yB8=eSn)G(f!)P35S2D6w)qZmngZDY?3Ujdj|d+|P3(G}yAl1?T_meR1~a zcpb+hTooQ$v}0O)9rmsaqWqBz&ionEtGgMMBTvBN?#Sd|`9tJmfw%A`V<`Ec6uE5g zQFwot)hT~I`$x&JX*XmSS%f7_Rs@~fueu-L|(7n0Xxu26-aD}nKkvt5wqH7fz``x9C?x`WmOKUBgl zdbNjsow~6YcK9$^e0}SNun|v$(G$RayEJ+jplDl@YE9;`zsWEm6-e&P=YbO+S4oT8 zhcNynQDUaqE}l72 z$ee$dzDR5P!oZ(jt?9M{2@x=njq&K0$NHCrk$xwm#d=ic2HcVg3!@*ZQTy%PVY=PT5B63<-)>1 zMq?8r^?5Ij5E`hy1P%J6-j{T;axyxHuTa6OUBRns|4zG{Q@>F8_vyfi>eR=gs*1^D zg(9$RQB9?~zFx%X2lefoBMxGUOj&O-{ABD-$Ui=^m&9h>W z`pEYREh`1>r|Vm~;J4&q@d&SO)`Hn*;6oQ)&d_E3YIZH$j#iX4)L)HKDvL|nY{4js z;M;;Q!Ej*L^F9|xvpkC*#%p^cMN&hY0{8WCCH+v`#a<;ZMWgey=DphU4%5R_5>`l- zqyBD9clp~_2VD?}OvPBu^s>YSmJ`K3RcCbwfvww?~-xQj6Tln#ZJR0{Zka_xd{hR1lZ`jac#)2 zMmuX6&)ivX>l5~|`bo z$*@s_^7D3h}BeBca*WgP#SMzM%XB6Xa z%%(|1@|MK;AjoK;l^$4fPTDa&s=4k3v--#uziL#AHPKK-r=OyYjT}1Cy?6RsFV+q3 zoY|i>3}BUWk>03yU`6VEmWxfu?|w}hsYcUPq}Y>c5T>ybR@+2D|2b;;>ig^z_8rgq zsNDAujK(PFr*wX}aPnH6>xkQ75vT8(G_c`?Z>rY~w$zQ{!-uq$$&SvY5kz3t+}Esl z+Sch)sECGYy%VfkyO#5??~%c@T=M;@aMhqhj&wibk{eH(M`-DcNog+4_V_m5u=km( zMNkXATZY7lQ;SekJ%q{d%$CZZ`iZTbf~GR=VqdSOS;nX82V z9wuR@aL3x$i6Bv2cFytcu37;$2nNMmD(-1T+N6c+o1 z3N4uN7`YGWcbGH^Dytpx#1Ya&*|;wPeFw(d7vJZyee2QV4aPFqrYzE@yh^5IH`?-u z?{40OS}!|A)sw82-FXc1ws?{_&UcmUd*npmcuK_kDFo)OF&b{IyJ0Mw*p!(Zeat~c4V z2yQ<;utS2R1*3jKwNGk^_8N&iWusI+MD2S-&CL;=*;ekCz8|FTD*iS*8RyH|RTnyo zN&bmcXrIe-+Vd!FLba|_7bfKEASF#F9CO(wbU z5YLc4=K*29bL=SAf_HL0=Qqw5Cc!vs7c7(&79U4fZSQt|#5$~p{V*L6;7h>aBV1(U zpF2w286rYAN|T-B5BbQmn|BIMjz;FT&$YjPjOaud1#yXyl&hiOK1e6i84^90LPYxf zgZB1vE^O-lC34TJJ(Bbx#n4*Koy6z$-8LgP?<%a9O`{-Wt7LZ`&1}p0(JKpGB?q!s z>ICWE2$^hQuX#2H)6UL6Q;tLVJkp~f^>1B)n`t-_LmKgZQ*{2qWKnEA1fK}c*=fvT&j%~-sel3t>Ovp~` z=P0hxo?v$JKEkT*6*rJ)DGAfytlXozdmgrAb^6%PdFi5cm{esq1DjP|j%ee2L`M1p z@Qgtmt4V9{lm!VpX_9A!&az9?718F>o#z$#a#=9MehZrJ(VI-`?)D`J)l3IwsR=77 z_At{<%rQC(C~1$rWu~lAdgnDdL5ro|;u`8Z)f3pJ9X{f}`+oMMtiiEPgB> zl+(@=%J0qiZ)9S>?5&4MY1_|`EY}4^Bml>ospLpiE zA!IE^pymI}jZnn}Cs$XUEOH-9-8*OgwK)&NVz3V%aLH|J&eq^X6strVshlRxzn+Fs zd`CrhhEe-tgho|%I|d@pnIBpCidvD~D<7q46MK9V7Tqz-thD-g5-5jlnOWn>sEOMz zpSho}g&n@flCO8Joct8>5q$xl_|?pPjKSTaz*kYesZpC30raC-CA<#5=xdRCxg5Vi z>*VF|199$fB!}E2q=>|Pp*ehBc_WrW9o9!MBx!O99J1*9B6Jjut@NsKqg7zpV=WQW z2Dl#%1=!n-%hX0z455|x;?Z{()c1QYi$Xxtj%E2Nq0c2OJK*oR)bNy+H~G)H?6~G! z_oMpn-KGYFwk%*lb#NO<=8BA=9TEH!QUy(ouHqm%cV0xI>eh#%lUGkqm5?1LRV{x% z_(8_+r2gMDsr|n{DS=`&gHtKMs5zCFKKd;cTd<_) z4y~iqsy;j9IDBA9DbbNcr^#t@tJajQoYcj*zpy$yo*qYuTv4!1gyX)qYqTu<4GHeE z8QR-YSy#QZ-3G2Pck}F?cEK;Au zQ?Hv+L@J@LJAyzi!E|WB*?HiT`OLY?%*~I=&UW%Ad;Q&n76b+lnSH+G5UHZH2B>XN zhC;CD2ex>4TU4_|WtGH@7QuGL6PMp@XAmwNpWL@#b+q*Und6pD??tOxt>yPi!JMVe z^9@RnqtvC_WDkMSQsW6SBM3t8pA0IMSA5Wk7I z(*siX(H|_x?%cpq&R~5k>(cdlVr>GOFYn2(@sk}KQ$;#SG8sV^%9G8bt_=a4P9FM@ zQl(e=(A{dmF?$*3XzhimZ~;4|o9OV}Y4&UZk*Vdz+dTs^Keb+?sl9%FAr;G>y+3FD zl)L&&D7SB&-5Z8qUC4Dl-`hkWgBRrZx;7;H?PnRZ)|?oY9aYd??L~seJcCW)!dTuL zKU)~ZayCLFq=bpd?i%uu$9RKh7b)u~!`RVLXI?0{gCs&>EP}#y$G<0oxP+ZZ}9+NtV&$J~Fg$<*@vdH%H1S8kT}1WDXwnfRg37jO;CP^55l> z-!M4$1X1b{Uj_^>7N|YAwN%7hPOriEXAMLyC%2dVY;zxVxs=bI?=9VNn}+2J<~oU8 z{CV5@7P#3|e1#M{U4ZH-68mH;mcY)V^y8K3NvBe`V$_HLFRRyueIsA4sCA?2dn;XJ zx`F5flDq*9CT~e|--=eRn=fApE*IZ35GpzR=Clk)K$@c#1;Ep|3Hd+3bBKfwU7B+` zI!3PF$%`OU8{koBZ#t?SEGaP17v8$BXNStjzmF&Ke$V0MzdlESt7IqlY9YnrqkZ-h zB-}fRu8B>i#wgyZmS3fX4SS{GZQI4f^>E{j_j13;vBhJSmT50tuVPyY#Kvbim1C?r z$JIS|SR3oysY>U3F4T3~5BfS&?ZGuWHs*4Cjhx@3-W@Wt4ZCftPr97Se!Mly+@);!>iZ?tME&G>zWY2iFJ?_tPyrv z+3#v)##w3yIv6mkY9^H`9+d`TYp%1S9BnU)+)Gpr~`n^+)8T>r|4%ZCgRo#dPx3euAHuV}QkSK~XUG zBVsgZwv$+PgE-Sq=K{6(A6xlt+$>V6g1n1gwC_rCa86MLH7ccX@j zoFFoIH)LdBYOg8+#C%Ig*MhBX4qI#-FY}}#MkpW!(ZOv z=J?AC*0OS#n6CeH>rWbM)uK6iwNLH#JlGb z@-uUOJRvlt@7aQS347i0L8~ZttNV(K`Gv$SpYPjIK=<=-m)uHAVqC|wFy8FFvlOIT=$(4V`xCK zPu;(mxf=dX_jkb(!?*+blKg}OV7l%8P4}y_1)l#O)TgnKv<#gJ3|&Gk8@w8a zZkEO`s>@3~&&CIM+1Pw97T2{DX$^(bQm)lZe#5#r0j%50yjqGQYT+5XY8H>p3s;oG zu?H-m-CAh2WI4p+r{A*mkS}0?e+U~hdpZvaPS}t#`Ypo41Mk}1?T_a-mg{6e@zO4M zaUd@OZIvo$KImHFpVkS5kN>=!pHS2ju(Fq8Jt$>wwlU;wT@Z6z%;|4E|KKRJAccFk z@21B-ZIrPvZ1Pakmf=TQXo|T%j-r|w(xB=Q9YVMYk?l;koM3i-Fq^P*W<#NjyFfw) z8-F+Pn+kE79_O$q|Lj`m{QDgBo1)8(A*6T3_0B@;$fw=s;Le<6rLpPqkh#RdQ2*q% zk#<7KpYuZ7WIU^@!8d%z{U&KF9S5@%fH<_lQX+fst9Y|{coH)qx6zqS|7~oVy-$V5 zL1{LWGwn~RX2a9gb=J!psh&+T5`3YP8b!hUwKM7h^3lCO{v|0(uiech{$&X%e!9Ux zKbw-)vfA3R>AHz3jN7W5ZMW%Wg9|U-)=7gLZ!1@&)oGneR zr@P{!!x0Z~t^iV{1GB2988f-b{;H9|t#{{if(hqd;wrIPAW?8vWS-?@^!w=Zn6+an zB_$avlC?q2bwAM;e&_b<678T&ZOJveB*uMw4TFDDQ>1o$nP7fe)mG2eTF-Y(k-}}X zG$w6XhuwYJ#o*!tZ|k^0b+fe}FY8|Zg~5d>1PYfy{kB{ZoWt9M(5^}Bi~36dfem&% zOhzq*5J-v##ITLrvl5=D>ZBMB7usC0MALkOOxG%bt6~8g2{62g46bG8S?|+XS~C64 z>*8QXOJ1beY`>_RokA%}jzo*i#nRyhq&Dv-|Vx2E~p&tP_mCs%lcV< zi3pqSonHcaH7d_Ym}3U4{a|Z$`K9LzSS&g5YayK7zGE{iSGylE3*{$Q*Up*4{PW<@ zh5e7rWLD)uwDUfpn)RdWNw=l7!d4}`@X1Mc;u-MBVqQ4eg{0KbVG0YuZF#V}`)Few zkh$BrJOU*NS7&5%l)xS@I=X?Iv`sew5C{JQvFkq&@B9ANe}17jfJh>p>1W2{zi|*$}X2soS$u7)Xg|oj&kP<-*zj7 z$E+2y4+q5izg9#fu~}7_7_RMOqD~LRIHtt6o9jMaCIgM;okKDxWOZ*htJlpcCBz?x z&&I&_XzGN#T?fyiEby{^3Z^-4P)epy(^izkJCRI#o7=c-pEaXrqskoZP`0CIYhyd) zkaJ^SQ&i?KGpRtn?}_ z^c3bd06nXFgDh+0x?||nYti%oZyl$N^ohJ+t~E0GC%IM1SP_IwMHT;ys7;=YwlSSOcr{# z4v7=%uZng9dtE;jO8$-{CCv=>Jy*kgnAGuxkH;R?mL$4!PYfg3hubOywy{qBqVm z07?eegkko%Q3ai}=f4x<=(I5wD3Nd%w_YBdt3$5Q>n-yaF1@yT_O=f4lgj;WP9eDL zr9}P?duWyfv4ST<8&Wu8m^9B1Wfq$`$9!$GH+sYm+`=tNa8K}!Hra2u>RcV{wgfy& zEVs+jVfAZUyGbWwhdH$e)`ynr0y%NSA1)hk;Q!SRbQBx(DSroz^s;>f5um+m~B4 z99BS}kpTkD_wVkC{3OU8&57vMDT6!8CoRoyhoLEdFxrmXl_0=<*B1#)ZT^+67Y)qJ zJ^K3m`}g%qP{aG(6Gw9X?+uRr*&|2d_0aIH`} zrY36Lzw$&)7vE4J4Q!QgLPnq~ER6zJ7f##yA{SYG99W_VfgxCwC^jhO zhR*`IP>$W1(F;kdj6vnXhr?~FF|B_v*AEkhiv5T&8s>JG{$SQp6R1CStf* z!d#_#n;uM;hIf{>cNUupmImmVl0-C{%&zmgF*D=@Kiv)n(i2?p-AmLzGjd(5{xLKR zg4h|1nr-Zixt-PA3YGcD$r(+2?bj7HWR|kNP}3FA7kM?-gGkIFa4Lpbc987`*}JRj zNB^ZsV5^fw(0iW8rIbdikU%FrB8@4dB+ZVE=%ljUg3zw-{D{-Qicp@hu)YzB{nz3+ zfW;ZC4POM_;;lw&`r0^`_TV#6tPTtQi4oko6j^f@-sZuC9FV&+hpMxY>DQU9ZaLl> zUhl)IBb%VwvwM9zhyJ&v7cixC_;;-qH^avs%-Tn?veYcN;n-=o?mJ1jjIju*+Wj|W zjY_t6yJM;GZ~4e;!T&dj0@lRBlJ*}@iE~2nk zujG2Wd*;r?9OR_hz7XA{RNIVK95SX;~KI=hgc&Hu7r7zUtuN-X1Q=+ge271Ie5+ ztzFk)MLR!KW+f}d_pPmJCWn&i%o|27>>d!@W{YRwTN~$7V zP})R0`25;G;V;G@%#0lFo>Zd%j5hcs7BV*xH~VK%A=G2Z5^@ec^?Vflwod4ueT;M0 z=BDN{gC$Jp;yy+q^AU^Dc$1w<$zVq9dy$Hpy++#J9WDW`lD)@zRLDr!p^t$cz3qla z8A%?ulGPNoE{C=peCn%%?l?GBDa^+uw9T$~1nojaAHHoXDX*4I%#5CJ^yaDmTeu}@ zDs2Zm`FC0@R!oQ-!{>yaIBZeM9b}XsXNLj4wNk8A15HhNYI-N?z>S-uPt5i8Ult74 zc?g$x+2=P@Tq+V z-LW@~1b@a<;@MHpRoa%r_oA(;o?NvM_7xcRoi)z~ zJ_5EZWkr%;Nrb>fTuQWoR=%AmG4_t;(ov;1^v4Gv&4HohbY@;XhY%(sm7B<>+ZHyF zyhv)-OE9!asTV#Ke>A_MvT!unv#q-zz5?uKIX#H>q(kBcH9%}^jxWkkKRqlK6OBj# z%`;-T0G7haO-}>leL7%(rp6OBKH3iZuWA!R{nI%JSBgR=+uK#{2aRNxZ3LXxO%Z+*TI~eaQBSg1RjtPWZwu9o$st_QubR!t1gJy_F zP`5cMMs^dejx@@!3T?y$pOwdkKt-D)8g z4Ol2ZjPrc?-&@~l0&g`f2npQEM{pc=`DZTN}g>Ciq^o1Ol7Tlb1^^|Jr?rHRKsrPlC&1mx94(OxJOwR5f^+mcw) zMMZN^#;GB-@QoDhZJRkt1*C7epI^_B{{7tvTEN6#WMD}rh`LR>Je-s~72QT2WK0~# z#(}t7_$tCWE`VRQFMpQ8YRE$19Yoi0xLsA*lUFA+X;Lj5w6Iz}=SCyW!-vuSqg1a(cNGdBNjO86bl?mO|yNA@#WrLUu=FD$r?1lo{K()$@U-YvH;NKVm6LGhBp4{b zAV>Fg;=ch90@ZU922{&qA?5xw+?(^{j-|M=(e0In&>0CzOOS^itXgd(dWc>U5?En;_*JpW*UOypo@JE-^v2^s$XN)vgqC$#yCk? zb|8Uj<<;k1<#~>OD6$}^QJZHc>z~*YG>F)D#!VzB$^J~a8&WfONeNM|8)DcA{tNz5 zBBYs6zV_|-N$CoI3)AmE(G3$=cAql{eiofa2F%8zi}C#n(jxne(*DwT>-fVs_4vkk z^|ftlQ09Sk^)dEQCd+qq#g~7b zH}fY*)mYKqzaT_SZ&ht!1KkgY*8@zlfKI;k1{tf+5pg+Trk7Jo)t0UyaZ+ag z%|*iVnZBSNnFL<~Guy6Gqqr%MPJ5=hL7X{wn!T@zvIMP)+oX4cpJZn1J$RJ6X6}X+ zqU=7*Yze>$(C!CPt%NAI7%a_bhSb15cE(4M+Rwhzwo7X#54#T=7;vXg+$HUTwu4no zttxd=*M{9K$?KM77cm1Q^d|ai&mBwObXe=&OqdRQcaperOSKqMQ-&=-Nj5xDBxn$Z zgFKZxv|Z5{Ughb|$NMi>OX4&bx41k6&xnjmZ#?8B)1uwdl0Bja-eRqyd-^gsN0H*J zCKbW{V5p)|AlIHrfDL>Nl#TW(sD7@92R-4ud~BEg=mswG16LQ{f>@8;z|198nG|Xd zL8Xuyl%Qhk>U%VYY?h3VikSaQ%7N^Va;$&$aeqO%izSQ5%=9;BMY!k#%5g}GA1R;g zFv_RF-2C}8B)52AsVUF+^2$IM?N)^9XL}g(6A#XPsPu7t{A#;o&=dK~M=hEZs@9_` zY`F_G*+WJnDCjWmQs%|WpoVZ~$pBo5zn(0bxeO}r_bHAwB70Q#S9wr+{RsLm$fMOF zWY~xa`Mzpf12vedZa?H1`bo?}zdlq>87F}rtZA+zrAPIMDd&hQvs8=O7}#;N;k*0X zCfrxwjHvD7>f({O@ADQtD*6;AJuX|`{fo=fsFMW9b1$`|M6)6_Kk%-Wwzj;lEX4&3 zIjz7*|IHB5;q@6A9eO+qT2-6qG+ANUd2{?KCRL#C(vXOiPTWOIn^BdeFykCChlV+L z>Mo2mt}Q7^x+L!c8NAnO$9b^3D4xnq5%v79VhDk+2!J%Z+HY+2h5#5Lj6ODtHw2+R z$}P}ufL<`^OnZK!lO6T0O#0Y6z9S;Y#sZv#r(JM(1P%E)}#Aj$Ft8dtM6it<=^PVnjGuU=uw{J?8-MYY z6}Os&LCrGVDNiCGoq@HK6z@M>{@??;EH`fbCI$yUHlhQTiP#$lA?rd(6$uJ%McR3+ z8p~k(rOn#`Axhp4N3RZ{m%CKPnx&6ts~651BIA{=!6*1zdgRixnGk0hz&U0 zWj%L%ok*SJAM$>{@ra389^7cImEu3w}w3&WC#N}wq6Hrh7ag<>)(Spgg>@=o$w`c&d z*hl)vsnK$)XHX&0TkOc7(bG9HEZE^w;O41;>0ra3Ca;N#!zz5kq#f-qBOBu)G06U; zFYUxU^{_4Q!PAU=k4Kw#ARW?gOz5|~@f}r^a?yaWELJsUa=%L(tcbTnc^d|*p0f1Y zVypb!`NaNW6cKrxPL$x=-=Hjp)Pg^f)?b&$+nGmyZ|TBZ^Mi6%XeIp0*80o&znl;K z#wL>oVq#b6h8F*!n$dHJTcmDdu!>q7bgt+hO1e{a2-FW^*`2qgNrtCYjE8al!=LNRI8dHk(#Ccaf@62}$Ku0{I{P)D4#<)30Q;=xTt!1AtzaE<0zQZ} zNmC|0cWE4Z@4GsIhB>ZAUEBesB{b-^A3ff?R8nPBzVT{PIPorRWN*fhn$LS?mJTkL z$6j2OS$|K=(LAf_2KL8(`6!69xZ^EVP?dQpj3HZwUG0BMAK$T_+4fb)GK}ljPLd|E zYZ?2>PKfC6vQ#5S>v!7!ym1e36WI!OsSz8*<-0jEeI^UzZk(tZ2dEy^} z^wC$$4i?gI*|Ym3`N6!4HiljLy>G5_RhbO~aAgTS4fmvjt;ir%XizCbA3vy-iC4~{ zoE=s7m()du0VALHhTVDiI*z{tV7j|;mOTx?zJDWAoo|<_ZI>62IQ58=iqWbx$DiKf zxW<=q^_5QYvbCrtnx{aL*nzM*czvCDgPHfP;ylOP8;1o%3lKVpdcULs~s7; zOubbsN>!(-J%MWf0W;SS?U%4f-YB-zIa?;38*2<&9pKgI%x?&QpwauX^5zN}W3u>U z8lJI>2#ujzNR2AaxSNLY)!CVR&KZ5a5?JTe%(Rw{-=X8r`}c!NPrgloe06h-0FlXe z#QOZV4}w@OE05`G3+^2yf>zE11{b_4Cn+L>k50z6Mzn9}dXb$kg$F7ann3l*?V*6S6(4r~OiN;xiorvpldSB%TSiiV026iF3Su&9|HPqP8mf zW_)H`c7?G|c#xtdJF}2YLc;ga*m}J5mQJySY}Rf zz5{i{Z@fnzty9ix92ZO|ej6oN$Wh$gq8}Uq-CoCpOPSt0wCQ*JMgT1ylT3uFTbFbm zC6F*(eO|O`B=l8LwxPJW@v(TCOZ=M78>10Vc0o9zX$>90C%nT@cX!j7wE_}8(jl$? zn$Q8edNT%V(jPd9_FT8Mj=8OW_xuX0OrW1Tc-f9Q|`&>>V#%54ks zz$H&Ag1*TcVEsc~XFny>MF^U^O;cAHB~xW?-|b0Scy;cpRjLu`hMKl|6<@Ek>r!$V zUoRn)4zT*p@z;B@uyTT;(!2qZ)!mk0=G@Ol9@jF_ELN&h#2gEFb`9;CWzn9FMwRZ#m_c?Nrr5xYu@x>p z(D6FvEkYfK|5w!2{0$e;NzW{^5FCGraTHNZTJ_sXfG=;n3Nd{Eyu~nU8X0GlmUaC~ zTF~Zlt#ECBLVz)$rm^URox>b=OiDWcBsAAXEg#KXYpaaj6tWTS?~^e#tKl1zGoz+4 z@Gb#x3HW~{PL6aH&fnm8*sSgXa)p74CgHinl(0z=w@DI6r}^;oq{l65#0HhE} zeGDioQp>ZE zlG)Vu7`RP?(|}USF;6~&peOV{vxfo6`h%e7t5z_w$BSjk-)=tGa@OwG3T>(qU`<q)D+H3wbgS;S7m3m#~^FsajB$jd*9^q zgLF+fR#^qwtKR{wy2sLL>+dyZ5z@hHNc6q1j2Fik|AhO>RFspYpH5VZSZ*^OB+z8Ig z&9q9t#6|O}v^eLZZ61|<+vDuK{>M46Q0jpg-mnupR-hIDEI>_`-Bq&V@7c8}Ui%GC z2XA>>TTku(fY6jwrEJQvz|NsTkKu5%NsXon2x?W*m_2~xRv(qow|kCMKmDVTFRANd zTOO`^$ElvImvozFe?oTlKFZT?G-+o>&^Zrj%z+byH26e^BZ4H4u^)TRQYNlq5~G1& zPS=Dp^F`a4qLNzW@C;-(r4v_6`?P3e2Twp+x<*|eTS3`8FYD6yuc?E8v!i()am-J5j@`yz0awZA7JPNtL+TsPZGc^AR7lO!9F9zm2zgWYhEh zOKQZc5ZkIL<0n2G?Ggg!-yU*R=zV{1n-YoUIQ)+#z%RzI;~P&l zN^p9guNHSm&7Rn!KCPZ-uRf-NFSL1k27c^O>yJ)wtsLM0yz(xLdrU&lfM}w!kVSn_ z?9pYTBt*&J2yF~t90QU|J~1wh&+`wtj#_DC%c!=Y9avV`f>y zN-FlTHU{dNCdPyI+j4c&+X_HFkMMydJXS~_6UJv|Ob$U_R7GT}t0+q`YT$jdc`YRC zHTLxFp_FV*ZKba}M#lipRkq2_KSJGI%K7f?%on`E>5^cQ0!`va#6Ug5)sQAPPCul7 zd=uEX2o7M`CHUcCQ-^lEEKqH6jjgd<5Mjs!FO8Tkw)}DQ+B7gU3S?Y0v zcp-Ey=3|{gi#>sea+B2lCIsE~h(xMB;V9|oLT1cJBB;Pe@6CeK?@O}uEnYX>Ro?vi z=i-`9-xh`C`7Oc9ZL;ab*|dzK>;`0u0`0k-?QcFsA}uP{qx4Mt$9qIqlYm&|kQznN zr;51jZ8_Q{oNhO$e-prTH=y$@sm@u!jk}!Fi7eXMkwpj3EKh*hS0xVr?Dt7zi(OH2 z8O9wXeie}71r6ZYL%-|>-=YN-M+SLG6W~4^NFNujw0nQ&l1N*NJq~9_tul2`ufmOI z-RFBfb(2y~@D*ukb9{BV@g>$%R7V-gC$Xgnf|38~cZ5KG)Hu)-b_~TJ+dr{m6?#V5VKujZ-ISpw-nk=?2Evf9 zWa`wkEsgNL?cgw>z!R&m-+N|c4>*)@;=RrhsIg!xWDx!90qu-T zVwuLWd~*7(oqn%fV9JQi^o{+B{Tbxo(oQI&>__i_cWIxcnMOgTNG$R+V__>h>TRp^ zu~hsjg+!2gL1t)P#}yv2kp|v54F29MJ-+M|NEfc(7%5+iU>rfCGN_&t(IGk%z8xYk z{m)F4n*a-ZlOY=7-;C69)n@SX_Vz|=ldeyQ{wie=tI>PQ?&=bw*ea`vu1PsFfrIQ6 z_*6T3@)w@SJWyNz2#e8zsl7ie85UQ{u=^B+><_ecfHE4$riaqUS5!du*WogQ1|1~> z|CV_&V@CB_l9HKr*p=m(HKcFUix{~qH?k?r@po!K~~MK$!IA=@|qb!j&Mx%m7L zH?Q~3dIYH10_K2PPT?zw8sO?5s~8HaJ zzTPaUr=m<)R395Isa_jZ2auopBh%D%tYW86cb{#Vi0n`RAwIm7d4>I7srd&0&OrIi zrk!6RAcQ}@+B3mDvBvr>!$fbHVO>d)q5=L)XSHY;#B)d!N5TgX*+^ ze!+H;^`_yiUz*+`F-=j8_nO?Y#$|!<$;duk#VN}^gct}%jevQ8S zOuZv-KA9pO6_GR_GyE62QF7G);tg#g6~F~~%s?5dPm2~wjqtcM99kBoHH7mcUTBON z91pMiB5_a~dj4PyZb1i*UM&pWoH`OG-Lp}z|Bu03X zT1`q-U-v>e;r+5Z3+vpezfN{ zO9E2M!SJ_(Rc4?K0`F^mV|mvXD@Op*DaagnQ@mR+4r?0MNuJ*|;e;|y#v>i}Cm)`* z8S1X-N&2tzK6#0yvCP@9+rG9p2mq`f;cr(BF$#5?&g4~lytXrOLv%bcY|~{NWbfVbwAHD#yiIQ zeLru0Fb& zDjl4U))pSt5edMi+a_lH5RatMEP^NOqtulr)XV|gxA8ce&U;WnY^6DWugQE06cIDR z=W6C3)Cj9+tj*?Qvxy4Yq!S|1MA*^^(;|9@>SaOXuL{=1bt7Jysejz8!UqtZny55b z&zz)GVsFe+^bK>m+?d@(1MlZ<77Dan4H4w8E#Z&>j1)JhtBmSpr2^kWhGYv;)hHt( zmv}=YaFz_^T+%y0PRF;j*@94CfTu4#$`xI=E}8HVoXFzowl5NJMt(8DSwp5+(*0ssG@@#cK02JPoMC0Rwh$85>j&SZ^&L!@G z0N@xvpf{sBzOe5p!L|U8YAyg&w!lInPLdJ>crlW)As~;J&F>E;sdKmOVx(ml z^OLPe0QPnGV!_7pJ1#0T15dIlHnI8zBRb@8hOi^u7!Rm+eangrJcqh?ubb!oE;E3p z2J9d6ugLcc8?5N-`PaLpf6X9>kVfooA zVlZkv#-y|KBY4Xhen2eluTh#$xN-Ia8|?rHhC;Srflsh1tnGneN>Nm|pK*#*7hGhn+V0eC&Ey3e^B=EXyLR8~3#M(l+J|&u{b3930<40?#5ogB z*MnAHro4OJ5&K%`F<{^^hJAtzQjNGKG3jF8Z6>iz?Et8uwg;f#eD_i(*`8 z*4hU!xy^!wl%1}-K6WDl#fP^mtI?73Ms|sVO{I?tsC`D2(>OpfN9@gJw=WLslnm~s z+_E~wCe={Fb8wY_rOZ!Z1mi$gF%$dS`dw=mh8Pj0$7UIm`sg&rUf?hIIAULNObm2R zwZ2l$ntEDGQ}?8fxQ^EC-hhELwcpBER^%dSuJ@p_om5IWwvnRjI`v>m=p20!L%CR9 zS?gG<-Byk7z@{fN4A@srh7R0S$xJtEeLJ?x=tE(P*Dp=LSNDWu^<*YLM5NP*g@}h| zyeQ204$DRy%c(qe!y8~aQh7KOTRDhJGMh{w(4wdP#?P)crZZ|u#3rIl!Dj$r`)9NR z*5X!2C=hlmI4VERD&x>Ndv){Niz*BH(Fq);;Z80BN`f!SNl#(-t#Wt3AzM$|%8a&ul9zy{-)c;)zKUiT?&&$-l_deHUMT>T`(Wc1DRWuj ztoTv9f4aBYq}fH=ICHs!;Hv`u6&WPEYcy2Y7Cz&4ZfxTDoW_m+qz+Q|Sp0zUtG-By zn_V|~k1po&SLyurKKv;jXCbwd@2qmst5!++W^aG`x&cC+#cpG6c>tjznbg z3)IXo{E@4vvj<49VImc|3bfmGR*QC+(PRKB2XZ9=Nlic363XZr53QC)be&Rcn zUri;Ss*)W@8^=VKim6}@WMq{u7%6f-ks@oS(D@Z!b|am}vM(Mls$IMQ&#zRL%IH9v zh28dwDBxc`$^BL4_4H2pqab+ow-?dnr65p7lhg6kEBRZjumc0#Qm1@{DDW<=K$ zpyH+&@5Gyz{-5$tvfk(x1??jh^CtIC;hY1%8I~GzIGsA!Cp=*-2>%YgzPxBUZ-IL+mmZ9bq-+!nYJ(B53@V~gn^%T#dE9VKyiyguqo9Om%8$C($Z7oPMDLt;yR_E~5rKVRIT0aioVu z<5AXabAy>2Xhh&>jNW186jpn=uSeEOmv=7+jvE5t!L!NiR)Y5Z%lVr{yg}KDYmjki z^O$@%h--G$OCvl(gyFPvXONRM4IkF~d*#G&L-N7aYBWDT4J@=c+>~fsy1Fz$b6-(( zC)Sc{5ly+2(ftSq8NEAI?$&&Bg3TPnu)O#9t*XO$&ZrYX^N4Z%Dh^lnt_=V8?wxw2 z7U!lM9;UJ%W_pQ3sZWlBLZ%Ceq3L`I2RcE+Q#hE)IN_ka!`$pFG)7-^ayqMktIK6h z4Wsp-r(CRk@a;g?G&9OC26=K1f?T-XM7T9CI4Rc!x0_CzZjpLSlS8OI8d+FpMewA* zMLWT)z~9WaDz(5~R!_3(-1<%{2ialXxMP*#+~j3lZ(O@-bH03cyEf5)eCPDP(gWO4c#^CW`KQ*|+}FJ*O7E~s{u zFUaGT#Y7Wesj$|XR%M)L+!1$j>4Wc68=!v4Q|@M~SMKI*;9f)YN|w?94*@7u*HLI> zP>=n->Xf&;`&e^wmy7tLM-Y6_ky`V4c`Tv7a~?M!b`@XOhx-C@_mqcZiFibC_sm$A zr|Wn&&7$$aFZUUE7;M1dD%N?(f(jZ-XrXd9G$;q6^=~_-#$pcCvb$mQRaoT*n7FC2 zeIGSYmMW5XHWV|+IwhgVmXlZ0dNXSr=dE%HL>2N}!rV_2a!@c%ZjIc)ZF)ml%B@4@ z`GZA*mh<+VIyY1KDC}LaJ^$Jr;*S@8@CuOd91M|t3?S@CU*$GfOA%iYDEkglHG4tE zY$uB$pkg$z;#K_7=c+I2szBBN9OvUeCj`(D2<7g`prjoxPRPm-*w;^7`0|Wa6LqJI zSra@<_rXvB?>c2~%3T7pbOwi&;sFFZMI%D_TU)4K9u}%Vp38$Ep~_kl#O#c&5_dl8 zb<^>c%D+i^kt9MWVsm=FIk+DDpy67&XnQSFPcwMvq6~4Y1^-pq>lJUt=xh8blk- z@s?5U))e&ez(dZnDn;NKB+IJlZ@Dm=(vQQqYHYeRfx-H~+&sHs13QVs4_%N^%}xk! z^)k&5WSkb)bXxh_iXF_f5%c%wDkUPXnbCpguyL%#8oiaOZ`+W+k zt%C|~bq_qsxtGzJDSzYzO6UwAU1t}l0m{5$wKwtI#V8|8x$22>=6kh`LiVa)T~U*v zlUr6&yDy|3Am<_2<~)0h4S!}v^5Zb1v7oEpe89z>HcU4<6)D7=6x)>TAlozr_{|FPgY`t@rKe%1cWX zD@%cAl`~G!E-K^q<-naurBRcP4yb`w<0;)wSjs9w z%|?@cUd|Csbs;Rkhl4WW&FAW(p$gIO@FEikyWiS%kne^o81dFfIb{&bh);I?@nHR3 zf+7TMGrMyd^=j4hI*{$@v`2So$3+kijw3rPpW<9wNS(zSq5aU{i}uBiPSPcBN)Gy5 z)Fl5|Gj5#nEO_;BF=y`}V{`0_hWt67!{TQjEgl~P==vBB(vQ+e85*fkHT74B-&AdD@}}CYp9;=wyI9~qX@LGX`br1L33u4<%o369P___8k`

F8JSFm3R+VILgyWuA@p&T?x%=A3oSO!hewKot@@e!6zV3a$ zk#x3R%`m=PaH_gJ+G(-r?H>!m3xa5@t5$xgnno(442#buU$IlqB*ehBC>?~YILu2o z_PRxcYR#g}g9=OJE6+i`yymcT{Nh>tWFIM8Gh)vinzrVbeeo0p9AiFAvx@i0Y@q@? znX0QYsu2}oCBS+Ce`dzIt2yv+?9Bk@^K()Mc!`Sckp))8G|>B$myPy(;M}qJnW0eq z^QO{HRw-do*P&$Ea5cXlDHcQt)wY_U-+<|(QLiyySLq;N>b&Zxf~jWmbyy42wU{Vi z{$68zxYJK~a;INGZQD=ME@#y%Z`SWCPd0xur`pBri>)Tmh(`Qz6SPS9!8Z^BhmE>+ z{l*Vn&A6v+u?X|4eU@pf!zm`|`ir~hrirFL-^A_JFFwRLj)h;634NK?YdNHMFcl$WUm=Czs`pUrq zA;1fxGKzbvoUf9RL^1nYP0^83z*d7q9{7mZ6C@GKyQ0c8l%-NDKf!9T2k{rr%m}ln zSBfIE6;5|SKcXhT7uTV3HzB{*R3Ll<0rHxE(^*)4cr(u1x`zX6>>XtjbGv0}IVOAM z+90HyVGBk5(plPn>Xp`f(K=XuNUmMtZLMFDY# zZDlqZma#*fYx}N-fzjSReVB=9rMGp})vm#Ty;-CL;Tqed*fWaLptFsOkZ<-^)!0_~Q#d!@4!KVr7=ZJ~-Bg2_^jKO!e^{%ti_WNV4ZT2E4LxOTXMMqSK)EGM)o_(^6rHO z;MNAh4?62rf^b8R=kTNe)(q;wbocb^#a5}^>ON3R>FyfoDMnVwDHUlcn7cKA^EP5B z6NhzFA#-e5+aSU&YIU~aPVPf=O~^|-?Fo6Oiq@JX5d-zLG#dij>U@cE2^wm4nb0-- z(n2YhoiYXr|EEK8>tqTE2z8zB=?aK`xq8>2d!REueJWZJAl?~=St09&z~~~E)Wu6x zdV#WWTt!#1I?V`#bk+iX-~hdaSJ;)U6Ke-uLz>;wIaB~BXLbE>MTXW|?;>=E>n8^p zo!#X$N3_?GJK?mqS&iGi_}S7GxIHzi2zW{xgOE<64m>QvBC2cCSbtfVM=zDpt)w37`|%KY zdLqYD_O#q3D0^O8zuEfyggXKFqIt`$QN5X*sLp*%?;g_53wd4OA?JV&U-jU!TRELx zrWRzt)YqkgzCxw-V7r)dJ-tHZaIAqh($oRQR$^0M%j$j0v6qEb@h5nj^3Ft6BPLr6 z>}kH;M`njOBvG8?z7J~M=o#3k?iaw_=v7uF8&n~WTjei$hr1%BR+HaLl?dW^kh2^vzhNhr`@W^Fsv*l5 zM;EAfjw}{36)OJnVR!{|^D%<*iQy{2S@0gWymat71Z0CFF-H2R*kZLondO9TOoUTX zQ#lhtiPAchQE8839JaVM1tST`JyJH!AF_ zulydIKWv<%jxZXUS>~hyl0))wZ##BWt*0;m-NhQ99IezL2^pY50Xc$T_a+M>eLdcC zul9q@az;H+XMA@j9GG@#x2Py80PQR{0ak@Pe{o@`_3p|Ew!vB2I8v2XeMqG|;_a<; z9uB**TpEXdQWLrX!9~@jeganG^;Fb-odA<%#jG8yKajQs+1_;7C>>w}*O6@%V+so^ zyLk-8mcl_*Zt9^)qe%qzQ?pX4#}s3}%O*zkdx^TJUsQy=LSN900s;wAWIMc!?E}vd zLmH0-4!03_6{vKbLe`n}?>mjzPujndG_8uEX7yh=VK*z9XZLBbzh$%tqRb*QhaZxwVx9I>`GBm~+mDU4)=yIgC?NJl*3+?c7FWsnlnh)IjyP*J(Pv4nc9|WEx+*8%veYHS9>#2@v%SGRdErXCo z6~V&@Kw^1Bg+gz+*BU~@^*TE|=OJ7KW#15L)-hh%C{_s#iSuE@B!m%>A|bb-WFG7C z6s0>=o&4M^P8^oKzn!9cV3YntCmMhOjmNn61o)4Z@@NVp*VNbJ+JSCwl&sqo+Z97g z)?4cerPxqF9(Ggv__?Hi-dG8!gZbC093g1?fOgzugHyPo3v}dj;Ic1C-*M|Bi-q2&Jgn6; z(GdW~oGPn=#;)&3f^|ZITxGeL;JBq)kf|qwH$TusfNErprObPnEp*_ZGywjqJL1zZ z@pI6c4{N!ixjQ_mg#)kLV2J7k&L=dF3V~9U9i|92LPs#?R_NZ=Y&6(gDqRAp=9L6FZI_a@Aa2RuJ|{-JuUssYQhZp5hzhsR9y7G3Zz#C|>`Z_Z5`P zY9fku)PAejWf(IK+w&5+1cSJT5%gQ?NDpJd@*u}_%p|TzaWlK07M*QMAd_v0|2~0n zwj1ejk&$)MVc?MpC3Oi$gKJn43t)rTHk;Q-{Y%N?tfm7r;KbvcE1~!Etx)VA^Z*ZI zq>t=HVJMu>*|FB?U(APCu7ag2%)dzjx0nOjm4r!XL!2cS)mggpK&M!rhgfbqxOJm1 zg0p&9-GFUbmyN(E^#*lWg|antxZKq&TtT>eW(cn3__Tc|`yKXCz&2$=9!79F#~?=Y zpx6HHQ4j)8g4+Y#s^I;Q^2nZjTet^T=Lddi2vQOd{*Q$K4B}t{IMg{RRA)u=*WYU1Fa9Gw=B`{0j>j+g(^$0MEE0s`rG?J*fn|?^TiqFBA zvt2*BD4lemgl?NOMc)p1Pi?m+z*FuW4XTuA?47@wU#@n)tP-$r!txIukn*VE=H0MK zLgYzvH`!yyZ-!*VA(Wt2IA()q1@Oist_k~X`0 z_HuoxEuCDcXWz8$DBAf+-APcc_-q|TH7Rqp~m0TrzF{=Q{S4jsw65x+{$ zTC>fK?2u;wuE;m%L8@P-{8Kf(J1Z;P>Kpm~6Sf7i#U^{(kzgb7Mi?dNTZkTsO9#n4rKJyK0aiCDbBy`GMP1?MyK{$;@567CKL625GT2wsI- zol`iXS`w|2%)xm(f~Jk>T9V9-9h9}^9&ykIOj5VJ0o#(C2?1qK2=BVTiK^P_ca_9K z+TDHO`h_oh`f`0~xara|({Tc0liTH1r|L4uPoxSo&EmmR5dJ9CxDx0t`bNX+Fix9||M$Lncly$O;Xo`mlRqGJ@LYl*FpH9|333AmXM_B^H&~cIT zH@x|erHBd;j*jUv9Cr4;b@_um*%8%i#clcl`Y+^Mrh}Tvz+P$^E8d9!1xI3^fEVEk}wk0u>1k=bhtUaBO=h#N#nAB$P zX~CiD`pKYW>QyWfaex`(x1RJ48+dqs-<5780E~VIVk!?r6`{P%3}lk>9vg;eLiB4| z#?Z9OxlLV*O-fzVBJO0Laz-5VM3`6iOD~SCh}jTO_nd=A7UU7euGEmJJQ(_t^+AY|Bwr)l3Ku1%~dUX z9LTw#=>myyJ0rM` z*Itje!VMF4^as-?|Kkh0N$~pLo^&t}OoAoIu_k6K()QY9BYoa#WWm zh7L90>a6qMv=s|aA8(QGzaWbzRtB{pxL>uQKVzVI7?qp{Rh;<7U&2UHjrmoP1+2=%50JmB(PriZ2)cwaiF~m{? z*L`SIkS9DD40`d9|MPoLBwz&y>lVkmadp1pAM>w(#G#x4tNTAq;H4czN&q;&daTBO zEouka8*&&3xZeKPH%PA}KuXV6_M7M5%6zpZNLhn!wU~E=KU)s}zENIs;AmGr(E&E< zpU42(lK}D#D`HJ|E=$G#{5l0RAE8WyKLzEipM}fclY)AlE~w|tBK{9Txn^@7BHFi~MHhUwi+55(2RWgrvmL-~8Pg@#h};K>{?Z z)Akhd--P@tw%^SC$x-P4e`13gUw7fs9P=3HngInW*!;#Q!?f>Wr*;_smc+AaZnN!9 z#vrC+X1q(NgKYy?a%Pi&zbah;a6=?4Wp4Ms$?CLUg60u$%20ZApUV9PCG-|n7Ikmc z!uF_O=lz{gUB}B_D~LGU>54EW)tjGPLjYAsWsQu&5@u7A=PWy~PY-Uhz`@9Aq(EBU>Zt1;`Y1-6^C|Y z8b^qcJMWpU2;YT(e_e-zM|yypg%eXZF?*Xv-iW8ZfBm@<_-8!k5{GKr>2@TC^E=gS zlAlAVNTq0K5w~T?7;c*IaPrB=!6TtV=+L*8@TQshuVzDcOlq9Ym2k>>P>HRRZRHej zXf1OawpOE3W2(X0>|@xH=n(E{47hoNcpg`CDusZ>akNCALr6G1?5j$V#?(a$;dL

@uN`tW4up|zkHGG1?~C)pUp!4@~dO#`n0m+9o{G4#u^FW zcf8Wpg(C{>W!*Z{%v?4O8JL#89U^Y{UENXR9RzKbXK3#ZyF(W$2Yf|p$-CouVLaZ% zY+jADSJSHxXlvD|&pT3yXWcC`sY1UJ)s{K5ws~ZtllwzjObWi)_uDAfFTcow-)SW$ zZ>ywQoo|b^_?Eaf)o)LIN#qtkwAOiK;@sXa@|o<}w#57ZGwcd>IY{BV_qzid=A0LE1jeLEaw(c5ZCe(+8jQUi>8-HF zuru;C8j(wAkRgZrhw-p4uW*?ThU!y*9*Onr_Z0CWfZ_ryl8u8yB~msL>yuFgx2o*@evP zi{tB`qmsa6GtCRN9yFU>;nm}@TUw~eUS!%#*|@|zlthZtxM`cCirvy+3infqPZ^gm zgsimuj2VkZm6-2RKoUqw%n95!C@|@(k)qQw&ravGoqZsw@W$7^meH~CpJ zPJ%u+x~}CW+jIGk9JGH@~M;7JnzA(mY*eH0(w8ha@Pg~cn>I{y&Jl52PML)7Ms99H2v1D%7aLr;%C)J&LVDo&?#haGt&u3y|Pt+2;7^W?a&~*%=FDiaP$I^1 zKpdksr4YIP7Pho!qX&Gi>;hLNTNDh#&Tvk64K?ct=V7&PKC#=E@0yme^S!j$FsAK~ zEMsibSBa+&Q?||^T>;}fx>K)!*J3a%gu(Zg=*zUlk^*A9;hzt!nCeP1O7w+gn*r`>tOBFw$cVEO-Un|#MmWnfF=<&LQ5|Y~E=@7R^85v-Qh~w6f z+ce)CTqite;?sJ_Ip$QZQZEAOij+5zFCGp2uEB|-fcD%fM|V(~jt|l>J5=%~Q4iF(BIsAbOI2oXP-?bSeT-IG>$XobX?bE%W-mDtXh_iV>Y<$rJQ&vt%@}tE0d!yxpoc8gsg;7w``8z)`zeY>f&&+r*&R( zp`Y&ohbCdb)@Zdv2IutJludS_tuk*7>_K+l6?B-wPSOt@O8f0YJBY0<%f!n8?eD)Mc+w(r`06AN`;zBH|Fy+XzE`wb{YX$D)bL%KTO{QF5cxIe0DP@{zJ1fs z1B;_Uy0^3+x09-0S#=}LTz|(0uR)7$Ul?js5%pWr*Wp%?9CK9`H5x3^wgu_X z>e($XvPY&b&1)!kV)o6zDA|!@(+)mp3Cn4s8EwPJTN0Q(24>+U0Ti^J8hj9R_JAs_ zZ{DmR@W1F^Q{{6k|8QV{G{=%ZWX(3aPl4NxC}FY2F{V*J^p5?nOJ!h}9#cYc>@OuwxlSv@p)%81$u3+^EbZ5x!z9dKP?d zPIl|Cx*7zhclM=K`p2!a%$v+n4~SfmQw8gZgUNdjRFW3Pa3&L4IP1(<4$3pwDSqM_ z34Ivrg@0B@?OYrD=)jKtf?n!*i{)viehFqGb>3Mn{LZtn@&luKvzdvQwZ1V09on`W zKKox}1IuZIF~COR;Q_V2&HgqQTDgqfTvp>)xZjTteSkFlDlT8zno6M-gDaNy8VmSh^ozn z*J{SR^UpHd#V>*;H>w;Re6hx5lj9RMMm}fmQHYk;ojsc>hg@y7ms`W#>znx(x>Qq% zH@CS8t=E^$kINF}O&lrFYYuS@7Yj}fkIFgPqs3C;Fu^ zBkYIg!c1-}9G_rLG0^gMoQ?&tH5AUfOUrJt7fbIi_q?m?Tq%NavXT;a#*b_9rzSWZ zJP}>$`^C9Hp&M@!^(iBxJVf#}>^0|9Vc)&s@(tpL9~v`AQ~h2QLZ=F$7BbM(wm)$a zsH;hs2t+Kq@QQOcFspT_XFHBW*m*T#ytiYPE=Ee1oQpO;QJSyv;iqcC_CXW4LpAUU zFej!T`2BG-wq0@O_*%7vRS^~hFA^2UdiJlb%xDv8GqbDy={>^;$3+RJ?CM}vr<|v) z{a%^f!CBfuduTkqsQB<~LEM9M+EL1}iSymL0z|UPjL`Y0Tqfi0aC#d;jh=kTA0Qyf z!Oedv##PMRv+rB3<3rr7Lz6r5&Yv&7I9y3>%U1|+C}T6P1+9XKk*a|j_4(nj0PLsk zOe4V6b-^7CymVj_P9Dk?j#AB6uFaj;9tvXWlJnMz1nRmr@y1!C?zDz6;N7pQJR4i# z<|$>qa3KnF961qcj9;&%t*=5wqn1>wgEp1o@D%P$93{%oUYOrb{Tb$5V&XO2^8VcG zI%n~yt@;H88qVNTg49D7bD)`ChIP=x9n`yc^gjuMQOJe+!s0R4=4XF4&%>`w4n8UK zwD*c89$0g#Jj5T0irDmb!QZ@}jqx+&ftislHR#^L&Uoik!=mG+N6?<7V)9vih~&|; z2A7mfTsepnlUWic%^A!w|HS}3xJlWJNhz2Ye2xG;pU25RGTs8=jp)EEmlt zh|8>aGupo38+vKpf8HbWBdL0;a4Ykij(}Zq)~)Zdp_BeX28Oga%s-ke+N{6PHk_H2 zDoD!`Xy2p%`(9~qhh48fDU`wfk^)>Jcx4Dr3M?v_B&=K#2du|qia4VL`%WEg~T7Xia_WlEY z$P^vA(FA2Cb+mh|NZCX8WMZ<8>y1+ufD+i=Q|3x1t39bYf3J!6d| zT8!re?~~s*|BM)AUjGIm?1MYyhohT{q`T&$=jFKt63OJ~Ts`!L{%xr&<|Ycwa%l6x zvr;hum2U>yn*NCx^h#gu&D%7Sh{Tn`Z|uCeDW%Q=m^@0&idl2b?90SN<&gKjI3KOp zUd2DZ?rzHl`tiP6Eq2EA;#vQ7I1XsXlx5tS-f8WPa#BAStj);$uHwF5SAhG2njk#q z;+JbNW@7Db6Z**dk;gBGYBOV2 zhU<_&iuO|uVt4PkMm4{=i4az8o2xJS3hT}>PDEA4;$Yhy75hJG|C9Aw9?+FBfsvOF z{F2$LB_4e4`sg^VCyp0ou)m`h82u0V05UAAxX&Mll*_l7O)mO}W@Sn*wEbwV`d3pd&VC?WQH1<& z=47~O>oQU||7=HBSDY#&pAr?F91&HIDtt>p@TSZ2@_Wx3Yo81EPw~PSn+38RD@* zFy|ws)#!Qs#?4#z=wAN&;a?{Fzal{b@n#g)J@5ae2`v9Z6By{O@GAjfK%wP<;nf^~ z6++9eXK$pVCnLoBe}{2Gq=TI72+o_XI;OhryF?JuJ$z?mNH5z9Yz>b2l(05dKdRluZ2NKucMttKn$q>g8GU_tp&$Hk{ik&tF)>*$ zzLgwo(0JWZjWCnp?x zZT|3aU*C^-v1@c#F`Dg*WGSY;^a5CT8@@Ym*O0=$u+&4g;>q_JaNK~FOUCX1b!?|`qq7p|?QXe6It<>x$_xubvk`KAI zgK({MGJf~rYg3KTFW+yGqx!F{nc7@WGNGYdVme9kvS@91&2kviwsE4smVwI!B^JhJ z&=Z)?$jlJsZ*RYa7S*MDc8Gp4+sI{(%`ZMVuR7r?pFoA z2(g;Gaq~@zR`flbZ+NqBlmlk86|@GmMd${ib)pr-a2KBIqccE{ywbG?iZYbQ^SJDh zpJT)YQh!l+8T3;1LsZd?VXZZ`2WU-=c;6pbx>w#)qc>+PfUmeS6j0;2`uX+@*|uXX z#U$3I*PV|xTiULV>QOu%cs!g6BK+1s9*nF4Z{l_5Q6z-Kltd04A88Tk>=nkRXVTCt zNn4`V=uThMw4W5c8|JAMen2J>h9&%(1XqUSNlYnJPS}`8os5I5?on6^tFDmsJ!NhU z$pVrjh$iWsP%f$P$7EQNA`b+3MP}-xJh@c!Xd5Zz8frK2h9Late{QyR2AMxv(c0PTS2gzV%gBF7uYH+5)-!?yO1YhJkxV5~09RCaC$ z%p#JzkQem{XHF$3cRuO7-IL-j0=Y|W`s-qGFB0iIf0fS>P6&5NMs-ew{H zKpasV2f-GhuL1)?;sP!LQ39e-N>s`vbAkaX0gwz19K!q9E+qEW*@wLoqHku`zN5@; z&@iY)maL6hm(6Flbrl3_epI%iczBj|xdWZc4i64beZr94ligwTs`N)` zA1|qv-v>%{1`hH%+Rx8Y>G-N!jRrR4G2e6dgor)1QP!`Ces?am{~~}Sj?`NjwZyo1 z(m+Trsa3iiV_|PDcFw$wpk=q^#GO%}(ZSB3-v0dc=|{#56SRDv!2-3hDhUVmkJU5# z^{YW<5VIE}TWx}Ef#4R%d`Y%YA`t>TrQsiW>xMKk?sify_+pXfpZ;?YF=!K?MU^n>&hhiQ8xhw+K!>RqK6ZDoy-?t*Fc z{Q35s_d69eifi=>TB=qr?-&K?29?rh71xOr8Ve0%uB5F%@q=O)>Q-DT))PjX#)cZE z%sl$82j2LK$oUZKL9Ivgp_EBJkJ(qP@tM5OU90a`sv8VEG(Gs&Uu=hT3Hb=6H+>4S z8(`}nV#;C)fBp%)Y^!M2s>$MPdY{h)Gj~~vA+_oUJo6)#?e9%L2saaNv5z?Ux#cXA zpCuiXcdPiRqzsM^`j)3XH*yhknOgSjOCabZpyrCZaNP?yh>0y}H4yCz>BNqYV@Yyw z-{Jk{v+eJT`-WA~mb1Eat~a6JL&0PlG^$WzyUIFytnTDgJ}TFsfJL3nEy1mB{q^6DUgP46sgR9+{`ONT4XKnU9If^7jVh&gS*}#t>{p`BEwdA3fT_tY~f?ikh(OyIx z6-s_a=*sS*6f6~75y}_p3OEXwa4y>Wy44mC)i>+Y@Z`MwFrp_n$=%_k&Op26%a%#c zY7CdiWL7=P@!)~kqVCdMpM%k6MyB6nZavol^ep8>XRj$_c}?<%WJFRRmxC+v>5e0r znf}7m;j7(~|KXf6{0!3|e}`!dbc~S8pZ}{9IvSy*95nt7!+oeQn#tzn?T!<4uX~}G zPwu8c8fnlWR_J@dbqwpIBhTXYoC)R{GHI-tiOqv+#c*?T3RxQxUpkB;)Z8hA!<(9D zINor3uqo2e{@&E#;zL`iIu4n;@k>Se&zBoxa>nV1l1&X&e#b&y60|^ROC>{upLC#g zO_4-DJ?^GtIom6}Wn3*}_-I<;A5zBm`b%6&xJY;w&ek;-rs#61*oRhIPw&BF#H78F zMb!)v8%BJnnm_(*Nx>m?tXLZ3NI0g0?1#9Vm-<4KlUlOKcY~KDd`QkuOgPMy=nql1 zPDOn45D_5_W@`^{-GfiL>U}@zFU1u``4Kg|D)Cz(?|GqsACrXDrgG=LsOMK&6n!0^ z+`jndx1}=tKLxs=AY(x&*lvyPm*C< zHJKv2hje*zjHA%`SsU6|$yi1*@>>Bi^pB_DCF(oldb|28>)Q|~mOsjQ;H^nk;|H!! zZnlM29Pu!2b8WuAZSucri>fYcwMpi=$~)JyXyJSS{!QKb3RO( zs=u-OH5kez8LGIIiXZr#m(zzWz|;WZ{==Tod5T`0v9&7SKcfg7=fAM*nQ9UDXs{bd z+e%%fxNBf3&#@H9G21OkYjsh4eRdp?iwa|zW=O|m9-2fpQ&vVXuyP%hC-}xh^lb7L ze)D6Jds2I8F|rBycAxH32ZdqI1o7a1cnVz=e8JAx?^r>%%j$AZ&P?ue?{NFdimLx?mlLGw|3bNCS_iwO-geOLqFl*!^fw}f1aJmiZ6(9 zI6PX%9sI&DRkW%U{@q%R6(#7D$5^sBnuPCr)#8ESeH>10H0f#%wn*y@`D((#Oa~mD zEu&Q$)348hE#cp@dOxKoM{srT^B_ivY*KNs$5Iz@JB;OOe7Wc}=%|p;-X#0H_?tKO zktsn^CkbLT>u^&!qU4hts;8{h{lhAL_f8P4)8;vMaUIi~NmQpDI`c6Q%A6Y8WY=Tx zm2aO?W9bvGRIFg+KG@!v^w9E(o7!sDltbjkcFXKmFTTDnn+CBn)5Cg$d)N}_Z`CJ( zsj}F-%KzlRl7TllcFOSjs|V6cZj}w6gL(ExWqfYt^y!zEhKGe8v(}`;70@Vu0E)xrP^wi;9<=P<5YF3|E%D*SGFBx{f$imy)>k+O~ zIia{qm1rpTWYaqVVkRHT0N#)!;YPu>9x2p3*0N*$oO=XHl&K|e+wA5zMEX(h=bH)Q z;8ob&o{%pee3jLU{l2&T$Cn$)IEeEq#f*O5c(1I=pLSykwYKBIW#Hbj$6tFUdH;N~>$)i5jR4pB!&3^^UmScZd%gPDm%|#{F^=Q*m4%$`c=5)KgJ5nU0$a>L%0z z&pbqq;U{qi4&lVi@$Z^qrF+W4Pj;|`BWU`t@ES(m8+IF+xga)-;FhC1 zdqsOl^*fTO#1LxN@_zWY(l&>0^!WFmWj##(S}Tf*F;qLbhlR)Tq}E|21`TzN*{~gp z1R)7x#NT>$&4kN6q{Q;wJO;fW4m+p+Tplh{zLq`8v_6z?Dd9GzP!-`~n~P82=Sbno zN19`p(I!lv$ZIf=EN6Kd_3oWWrCT(Twl`ApMcFy8)}qT;l_m#mHcat5y5nfjG0J~2 zwdZg?mhv9yj>Q{MvZ9_ne`rv3_|W@x=0}FF4{wt`5c4stNYxoVz<+c@Jy=1{PN{%} zJGS{2MLk}s3O=pbJNpV#)ZyyduVMy1^3h|7;r={~yNQ zIxLPQiWfwJCrAhqoZueZ-624b!QI_mgS$h3;0}YkySv-q?(Ph-jq*;%4=UELfPU4g+EW8@@)zfRSsrIT)$(r zuxm*2Eolh=+o$r6r*)eQAv|YJ{YL^*~+8-xWpW&7{5+3R3t8%LdA0~ zl6thYey+)*fBRL`iA9=EI{n-rj<;(;6b&_Ku{!sSZr zSyYH*GLb5q>3P41x6PY?*)E7z#l_#Ef09BkQD!nflfy+pJupJq@hlbajoN%QG>WMn zW68z)9w6|HOG1KFCXEvRgGhziE<$MsE}(9B$+S}g_fsOi4SY=M*Yx>c;f8+&08qyV7LteQ0jqvZ{J1?U~jwqj5*J%7`&tj3HKccnvYl^`V}fS z4jmsRC1A_RcCokr2R*U;)dqYwqLDrZWiLT&8vO;uH2{Wq;Z+%4J|$v**H=K7ujT;- zwh1nx?o>pq6IN`|EG>v6>GhVWgaXo=o)XUq^NY6oGw7=kuDmjjE;p9gIy>sl=f>JJ zWv1dd*Fhau^HKwkpd}h~d2~(QZwL9OdnamfdY555ovbe-&XO(pu~H+o>46lLIL4}P z*8x+a1gfuO>w!iaST|TYh$7^=ykQl!udZ)L{Amm<)&DDtitS&x?|-(aIGO)XEvi#> zjriqy4DWTFt_G=ij0hTp0yE?3h*K_ErZd-6tcC4t(NfXWZy0e`?yEyS=UssbMfoD# zj>}1WrV_rLkmD|VX-E=ytw^>PH;66A=PDn{Ifw))V@X-y5yb8AV2)4cN)|XIHkafe z#b|$br5`p05(@ti6C`MDee%!|lE9XT36Zdq^uv!Pln6P zt@>y^y)oxUtF!(*JGC{1?h75d^?k=3B0B^LR_@0_sp;<$)NRrHtJ0s6iC)SRVPXKn zcui^FrLDCMY_!jHxo`Rd)%>XlgzG#3vV-t}HNUPCH(*jBovw3Vl`==77>BO=1OVFz8PL`j<8g?fKR4Dm3#j$AN{kfM?I zn)kQ|Vb44 z>!s?48LI~W&<@p1NX91yTG2G9%@jF?NGkXlAZo-~gY;(ILO$$W|GfXb8Qk1SZu?cM zmm?Zm^mDiyj@!t^Oh_OldAIo&_saufFNqL%8;@tr-`oRH(ZFh#vHn=fF>4z@KIo#7 z#sYv+B_2>|!+ocTG8QU7>m)JFLbH}W3TQ8@%bc++Tg{!8S8G|QaU?~Juw|KWU1NHV z5dYeEIC(^H8^KNr7Z75wqpMBbJl3v>CWe{crj(Q{APCJzd?1oeQB3^4Z({v8?8zwE z7AapSm~AI5Bwt{Gz6Co%Q{3_4?4u4c{Tbe6RACi?1yq*qbz={DkytnOyeWO=sc2+p z7$bksT)!4{Kl}Q}CX0~iDN&9n;f~+NfiK5Ahgv!8;WzIOBN4qRrAbdM?)BY;a}h7{ z*~rzb*8o!5$xPof_M3Z0G+1}uZY!9@36e*R-3TC8P%VH)GUF-i<8$ZfFE#(ZH%i8r zL$+c*9@`<4;z6x(wh`MkCUP8lA=QA5dP;ML?|uy3P_6`b&PnV1jLL56WZZBw+z#9u z^QsYsvt&E_@pfld-D*Ye92frdd)N#K_wtj*#-H7;K5$UkV6HM(l=^w07@a4%`B3BW zr=7uQ>9JX&&mtu;^B&prR`eqVCK zJW7r9;`gRF6b`YNmYN7XK~!gmDpPdwgVfgM2r6<2syM ziUks2YwLPD-L<@|Gd&Cm@*Em!r&{&f+at!!i{gYbI;`gv{$%E6#BX)TLq%n+X!0$r zuDCah(yKRYW$#!|ywZKeE8iOA;kn=%yo832{BTB5+TZrGddcAC?&k-|x8s z2M?8RIIASW*1)hTgy#U>M^t~*sE~(g;fQjD6XduBFwn=)D-v>H8}Vu+#6K3P}9 zTo&ys_#W@C`E z@3+oMCK+8x#T({%KD-$Co**#I_sC&sL;Qv)d((Znaufe`9oue6_~-l9F-+|h@C?f{ zs{5+rH=ZYp8L~ytl%$t&HD5DH6oyduZjkuJ)0o_M9D2VZaj1@=2V&mND^zX^dpX12 z1USM~>*5?SxTYkW12<^*Ph~VqdNg}KUBcseO=8}C|ymNB69N&*!oouslZuQo?Whz`nDVH zZctQ|ib!)|s8w-;SjAk-Wye zt;j%cPlGG0jSlDMaI*#2*e(}66y(}f@K8?JccB6d=){Hv?sE&}?)k(zl&336hMVqo z1IVkq6Q_~Fv>i6V?0}TB1z3xRH+g;;AgvpchZHlMqsLx>Ih&f*IW7C>=@h~2&wwdC z>K7?*qX@6`4(8s%V}(5vXa zXQCH{)p-~e>3_gbH(8yH6=Nr)S&5Rs0hj)yF4HnFOI^eH<}2^s?3hW5gH7_QrAh_t z1r>P!^)c5{W3?!~joDUgbc$17+%X942|_@FD6C7cPHWjh9dp>3IrXbLXzXLd7YnAP z?2g}&$FBS2l1J|A(sHe)9&){Uq&y z+Z``Cx$SJC9CXWQuV_$WqscDlgACQ+f zFho>6qzT@0)2-W(wjD%XN=`S4Hv=CR|Jm_(mII0Go%hpa@7Fr|lQFJ1ZXEN|J=DdH zMtPJ)W;Wnji4vtU>g_IOMar))_8rM*HcmB<-h;L|P4<5Cc8!h|P~V@kQEb%%ml6&k zDwTR;sBWe$XU&}{;^2hh?rpqqB?tZ& zmKqD=|JPDuWM*goKeg1nl%=DW*-+chD<lT_LrsKd!caTRv?ZGD8}(*Q zIr~(725^TLwfpW?LIC^(XOq9P|7X4lOMU52Em+(2xgm0CRh-~Bbxsyx)^ohWI=@jo!*87Ig&i)PDv zYY{YHV(5(7iyZ2KH*Z_Acsvv{(Z}`eo8nqvgerG*&-dmMc4)mfS&Uj|(w#6K!eION z&zYPPM;t~~^@{fhpk21Oyd+&AJ-XHrocOr0I|%0dJ{vDlU(PeO*XET;SuM>(jotW-?>MHYbm;y0Vq3p3uLz*fE=Kvwsx zUu)6fhhr|$F#ES3E7$8?@IGK(hDiUmLi{SJY|=`dThQUrIx-9#w6L)wdn&Gs`oeJT zp)J+{YU$X-T7gSt;gG9nC26c6Mp(pT9RdCt@^Db4NQx=d*M5%66Qzd)y|$>3AhrvB zZ=c#j|1wGP3+|`yTAkYbB@a-q6UyH{h2=3lIwS#-f9%&@i!5tqTg4>r&u^7o=F@FV zYq<4A%~C>pJSD@3S9hF_^HF9qOON_q>Gn9Iit9U{u~=;llMw1vjfM6A2^VIjX^yF6 z#XF-aeM?%^jvT$T71_-*kd}XR3r&%nNU(^nOG_u3A{4)|R|OrYZ)fEd;(kr!p`kxK zmz_ZKf)&U14W`bJBu}Ye))!ek zZ%X{ieSU-(^BsqCdm2Q%TUds}=Ad?O!?TjE@z_vi7_A2jdGR<5q01g7m~8sX?u)tc z?K(Yg%4NbI3=ExdtxlAi*&0LdcmJ>;&qJv!Y{P#NA&7R?OxNJw#hrlutfysy$y*E) z70OO=_T+iA{;qBfnyk};6O_JG#yK6s5&=OhnVrE6{QWZ=S( z;20U+PC)1ek-N@4=U56;Vl(URu)DG0cw+*GW^3IHA>lLfVQZu1hNdn>#Bzi+nxp4f z+uA*hhPC?zg8!G#?M?vJ$PAMP?)z9ta#Sc;I}XJ*@D;wpwRj@Db5yU~rT|t(&7qS` zAv*AWo}NUhGoOUh@a%U563){dxUZyQk08dcgnT)7$dv9di~fw>JF4hJ+4x)q4xPN1 zlEFF#Rnt?1{JNR@$9M@&bmI{MNmo3Cxo4^gC;CzW(4S&~iN3pU6>`QM2oe1nAjtLb z#ChBe@Vrz7sKG>kw|_XAi z=(CP}nq7I-Oy2%f5d1SEdOM}JV56#y$Z5ISM0Nqlyxxg?zYAu9nb!A?V)aP5@ zw!l&PJ=@!gF+T=E?SQN63&*`)sq$I5;xU)*M-CS#YN8`*Z{C=;ftDljR%iQwAfa2g_&WJJj(^>A)@u*+W%K={hQ(Tf7aIjcYA&+iK^1S zXTTZB>RA~PQPMLov+0=HSQ+WK>DlNw=vf=;+qfDz=$JS<=vnC)+8F4V{mr>^&=E2+ zGdHs~p|>?Orb1-+=PEznD`cIl^xt#o-Wl}|Nz&TbM#RkEJs`|KT$mBNGuj zC)5ALy}wbVpY}Eeibjs_8>%q;6cHnOuNQT76jyZooA30uUV;7nYOMcUjqm;Qe{-6d zk^MU(>;IO^X(w&c<76$<`12jP93(N1Mn0izK*i}DFcY2sM_~C2Uimx&UKL+TR^Cp|JA7VmJ6@7r7JR@yZ@2ufPFlMaP2!Ko;(Qtv zyA^M*6-#hFBXY0cj@JpF7eb$x^|wDhFFtQTpBJ6C>G{_YpVx(hvS(KHHjS??Wm8Wt z*Ke!DGQ_*D1h7;s&vO%BBvS6moX*zg=wh5tz|hkag7Xy$O<$_d&rM~#8@|}T0l8q= z3tsR7HSfw|t^-8U(_^NxqCRiGJ=(k-EttNUz0M`#$y4w1m)$K?=)cIltn7Nd-QSjI zfnV<{)}3Esp}_?}<>$Hb=XoiRwo)10a^g9-VXYV%7a-&L_EPZ%RKyfMxo<#!EU;lf zY%qG~Qq<-$iA3>8$v|WMdvFoiZscUG!E$N%{h4r`T7idbsa6cfJuv z#!CgN+hM(wCDyhTHEYzjq}Cm$b5+XE^{N=(7wk7W7WC)D4kcUhm4jPQ^91m7v*bYm zs>Zt6u1V!F)*aLHsQ#fZE2G~duC0x+lP1nu85cpI*5eO8tCrm3vUBlHXPEWln`7h# z;MNHbF_ck{A_A)xiciS)#~%1prwLe(%17_PHyO990zpC>RrX#kQ>U5Jy_GGec`Xxa zLO5PN!ykG29I#+|IvZ)b@1zqergyROwaw%U;0V};{du-TYSjJlxzpNL4Tui!Ox8W*##FDEKX z>ik3TBu{F-zTOl*tC~uJgh^*k)@xeA$1Bw}mU%C=8;RcYFQ;Xzf4UwU*PdDTHPR!U z{KEK$E$DVSzVzG-oG9wPVC1Z@jVXTwD}S`^*w+m6wY7j$!~CRwM^+oEds-ISDrzCv z*HR~pz4B7zdgVJts%@-1-6|u;z-<{6So||d{CuL;NXwC9ovNg zk>ym8wt%`gZ`tOwe1-HEHHzg|#$rT@ske=6`a-N7=-*dh;7adQ`7f<~Dot5cXzX z4=@(=ysWP%nrW@mxu%RWPTL?uKQE)-s;EY+A8oP-D)Tmj=rbDwDl3hllA*g-0K08k z4gU~xIqBvCLn};!IyQ$g?A0hD)JUDvYQ0DfNflzB=lt(&GDS}&=`b)Xr`K=L6JCA4 zhB!?hd#YNnmU>D}Ut;`>sNHDQu+UrJCpM+|JVW>Zux|um?eZ*;ht;{6`)QbNGWqp5 z@nol>LKj5Y7P%1x_%6O>EeE3JjI(e*bZz=+ObZaPO$TN8{_JhdeE=*j>aB^a-j#ta z>)H3>hnpwzS6)Vw=3fcebvDD`m~`AshzLJw^_3ans7ou7nJ?y8%b;;gtv|h-$C0q0vIm6tw-%yH1^s9S@R>$4OwYmeE-Q*G_CAwJL|5n2ADbn-_D^F?OSXq-(2R@c@WdxI1OuS z%MBr)-EzRP>?;uZi4lhqwxNb$UA@qde;Ra~gCD8k#Z#@V>{j*o$&HGL0S4TJPbr^2 zAMN?(#m~l-d^&?>aqYXMLglp=$m@tc&)I8J?uP#vtsI%lU&T7lWr@zH`0l^dS<0aIuRHqCwb3ZvE8A}2vc(a(?T!XW+<^+ zED8nL?11>Q;nvaCN#63|PVASMey~SYANtJIwtbZ;=BTtbIaaaDM~mHtN{emIj4Wg^ zrOA%Rv&VzRiN_mlv^Xw_{lfepfUKhzk*98J4d&&zIDcTH`5x^K7ot}PjDmieQWvgx zsXq#`g3>c&Vq7o`*6C?|daZqN0Y0B8s=iG~29Z1o^qJW@t1rhl4htHB&M<3*oo_dc1eS z5t(LCy4Pe}>eKRR5)0BMX{-y2FnYUX)u`Icgv&bFv)U68fx&fMVFf<1<`; zy@+z5E%owUeVwgkAZ-tLBG_=M4Q^A;cICQc6}R^|=(YT6JYISu!WV)$dLH6>x_;xJ z9(wRhmE}@8tF4Znxy0BQ<04B%fQyb}EW!Y)AJn_631m2yw&;Euu^6k*i)4fR%{S=EohQ+r2X3M`-d70P*%hzpJ2H?R03Si zJ#Ciz^55{dFO8AKZ^f=+KLc2Yo$95R2#^jOD6Q}Pbl#vawO( z-t`iBz)Tl#C~)X-i}kpU>xB{5E;y}XAY+od#-WgqR6C>FwXG7iEJ-s25-Em$X4PiQ zdPGovf%ufms*?+3dw1sA85~FH3yi;ek*hN-6!G=&O9`tAD_x6u;U8Gc))q`f8&sM^ znSh(g7P?8i;3ro;qu>fo?KSaHh08Xi1;*BTN9;p2f67~~o5l>H8}qi^Q*Z!tb%PN` z!aOdd8m^fNKO(5R@h^eA7wZH;Q^xe3_?=b|PT$Wq21#hV`lr7e}wX zc6U4T_P1YgO0j^lMWXF3mC(OrjrwJd?Qj36^X8lZ0QqIuXr0l1k@YvptI_P#YxiF2 zbIO9#6Nyr0`_^{}X4P(cd~+KLE<#I0lbd~NauPg`=kV{M-7=tzXdip-;~@e; z1pZ{-xi`#*R$fa6VZjX-J6@_rVig#1OF)nq@t#=jNg*=0vz8GB$4i~WI9+s0uBI}k zWh1)YgZ!a@eLhYF<7&FoFFqnL|IJsYIC7YCF2rt}>V(eg3Hl7sU(u-uk$C`ODSU~C zZRWdVxzJ(~j(t||B03Ozxq(^=((m$;r5HU7_c5rRB;8kJ2K+JZ%^^c<)(Vm-&N48`KSWUdqw6X&(naSgWy?VbyejFQo2-u_;ZUAHPDL&>vq6% zHt@;@uc|7lyol)d!-I6`m?S^Rx6hz%SZOJ4t4hL{IMNsFPllFsl+;RiQd1szDZEZu ztTvpjZ5>mN1TRa*+zz)OJ=x`3Ws}%QCyz_$n}_7gF=f$Hxw=7MVuUXPvld_pJpCff zkFF;+;cNam7l@H~pKAz*+X}31s6TEc{C9S-U&pAs_jNZ_&D%$DU>nuDc}x)ia`uiS zmm4fx@@ucETw}Z98x(N1{hV}1&)m)HH@1Nm$_*XrID6(w8fVB(BD2*^NeY(PmYvn_ zmSCYfl{S+~Ps#Z2Q`vik)_>Up>_>b2HK>R*@mTQd5nkU+%>B>NVRA)rzD}MBz-=iz zL>i;`;$c_)Zc*|hbcPI|&b5K2qb{yks)S2A-1!##TIPh)DF#5-`Fj1i%mQabs$(|D z>LHoig({3)Zt=dY(10%wdaf%1sF2{i+n`+iiLmUcWTjOL-0oA7PX5=+xbN>c5~STe z)mtCx>eH9K;uXwoltpJ?ye8ds!Q|ArD~qePnzxZO>xCTHTgd}R4-`&uY%G#uz5QMh z*@l1ya)knwX9pD$cA{7*sK%f3_Q(q;@#1qP9-(# zm$_iO2C&mPXnELA^<*$q?n4h4;9NCDLBqQR!ks<>Y`qi^53mA4`pfAIAe`RNVcDXk z_Y>L<^_A~AGv*zPES-?+?x5s7haVH#-CGcnlj`+ltyXO6K!`bKB+mcSeB8(E-x@%jFf`vvu5;eO;7&LhB%iBX_{GcQz zijgAs04l7UU0p6ujmkgR5}5Y}JxoalspR;+}Jk@jyE%YHXX1 z4T;8tn9~r4Leyf@qmc!MuvgtyG^phfK z$>phWPqyMe##=-qPJMhAL&({}rO;tikEmD4&p7BslN?yVrOn9k%QsqSeC}?=Yaj%{ z9o_k?Uki#q&j8uKx34GlVw)FvWk*KUaJV&;(k^WnFUVms^@0NcF_a47IS0+dskrZ{ zaM6heTk$bI7RAks&TV%bHkI-G{oOWz&5Htis*L(ff_Zekdgr(zwVzsc%M1#>&4(MU zCbR=hl-uCQ)`xy=PXmV6-)A>lG#;0UZ4Xk~o<iB zFcM2`IuwAsIg8eb-)~0^T9UM8UfOl?TW*W_^b&4VhbwZjE=p(xQOnFI)YWHL4IqpJ zQ{Lro`0KnB4pAu3-n5U=e7@Y}=pk4@^G$Si8_iYC5r!_Wgu^}$(w*tHnFL*aB`I_K8g zr$xJUOlZ^{oUn?>gaN8h!(+>tz})t~~&UDYZzobEMzWe||e3&O?!ed_Qle`eI=hcG9!X~*YiPN9swzuUO02=XgvJ7tl zPW3O_UR>7tgsX2(I;tG{CeKAuoyo+2!od-jy-Ir=_%Ew!-SM zVnYYS<+N_L!k95C%fCgbf2fuY)Jth{?PUZS@Fn2w^>iXSqI4IUbyD$ptMOx682Bl* zV+e#)#ihMuoszmzLk~BrGN7Je%0QyemeT2@A+{QHlwE^s}qi0P?{{zb@ z;_JMgKF^v7-k)1{)Fi`Su$SSnm3hv2c_Qp?s2cggEo;q;E3i{uj>$LrC{;L0Q**8= zr!Sh&1nTJIXC6 z_T4@-2p}Jo_-ZRH522MoRB+r?%|ml0a3)JRsa+fLWtXqZ*w-qhza%kMAp~y_#4$&{ zcp<#&Hq2DXs3gx~-Ah<>`1JO9w}FqkoS?7Q?ZufepPNnBSh)yjOlofGqpeG9==#XZ#u98cG2edk zN~RX;;b!BOxXY6W%U^wxUXQU^vK9&Yt42!^AIuF8GVr6RS5^-BjOMrztep1qol>~1 z7p%*q)14BT?srbh8Q_jYb>#u!EkzXPWDWx@gx;1@XY^-7DEw?@|7cLHLv7Af9O-EI z4H&$iQW*(sGMap>c7RM}CqM7tQs+q${8rrXz2&oBz?EU_(h@9o>(eokm9PB{toFnS zRU+SVVYR~Ui*uW~%)lBC`ZW6(ev!t}yX*Mre)$xqz7%BN(dI^O==iU|x=;#A=R*4$ zQ4|%iloPKnW56JAsw0Pl*Ao9>=`KC)oXZJx&o8jEC#AEXq`I((*E(*^Sixf45U)&~ zmDrm3+Z$Rq4v9}cj%yl$B>inMS}h#U%&3$O#~EXB4nSz$VOhv>%92~Mhq3_ z_=cSwrw;b~mp1i&UABu5aw$`PRV85^s;y+W?ee)E3j(Osck~x6<$B|=ztKXeZY#U7 zBzU3q$hXl#Wbc1iMTCf#v6EDU3M;mJz+QE3Lzo9%!#_0oEwwFE2m!`%L1?2OPCqpd zvF{c>BH!_g1c%=-8DF$fE)G96ak1~mt|H(65v(+haT-79gtIr*(B}P-^yL86TXWMY zmnPlQG*(!X&av7Zo!$WrRN9A-43i{KM}#;#uY7^7_%E}X%SnS7rWA1kG+M1|(n z4$BKJ2YXYCy_1iEi`r9;Qj6O|{~l7_fBvNvdxsqLADcTE3*%Fim}*!^k1~u8426MO zh2}o^d_;L&t1&CVn+O!3%VXC$=Br#m&&+s+l7Jg@S$m)_!BKPg3fl0H?yW7U0PVmQ z4W=e&@J7zihaH8~cJz7l5+d+Yu2;!&|5}D!aiz%n_G!G5BdV-^OxRYucNM`wG0bP3 zt+s_Er?dUtq&;n|OB(HT2XHIUo%Xv~od1h%b~gZ!|8=!w6h9R-W~D)lyGupu(|H2daDQjRcJ~4Q@eg za;ZSqB|SARRm^xkjmXDgTH><~cJ;os+G+EKgeW2Or z-C}tmT_t@ba3d03pf*R(F(eMrmrjy~{^Be(!{StR8wc&gi1F_6PlZ#OdB_8xzktfc z8FK!W+KA$+T73j`e}+qpP7c`5D4Y7HQp{Bc_Mxxsl?qs1t=AhBujsSk^(=31ZVLu8|5S{%5P++W(d@r4VKgP|r}js96!_a{3E3$0 ze;xJv?a%`P5FN_&j3+AaI^K;RRIM2k)(g4~>~=~myKFcX84Nh5d%b~m+LN#Z-u+&4 z(a2JfA(xM3M`laq;>!O$?jLsZDxz==GqWZOL(Q5|JL*@uScGjHXrSM_URpThP(is%e=`HqwP4q)65CcWzLlC~kIPl#Q z3MPR<_&aW3MyfjP(|o2Ojm5bo!oZqwtfn^WhwNoCS_(U<3ucoOv?!7G61gYAVoO=_ zcZ#`|)0C;K!^DyH1US3D#5m>tR^rW5#^x_%fK9qsPm%aj3N1KG9o>J-hnDO-eY1u^ z<2`FO_AQ@EQP9d|-X$m+E_9nEE%_?*>`R&J_Hl>I>MoAWLo&5BuTOhgpTR6PX@|_k zX;B*VPYs@6$)5-EiU~ZmQc*I7rc`J3zV^Ab^qaF=j}C#s^L?%lu|KGj*s`rMu42%z zowch^FZ7ldoULMpqOY4@27R9>{(An?xjP>%0Cn6R@l$TA|MjG3gB}@f{_Uhc(#?kZ zQJ1K@Z56>v9^Ab!iuI&FxEPN8uxreH(kmO#F_y9hgm7VK+>?@hghZA)v=6mhe>m)7 z-5xSacPtdG#ylE_;rheF5zdJhq8sqVpM2h1pHQg3M)5wtBxjbfqQbk+{ij8ozpH2j zO%2dAvCLtwSzOr%6rJ%L#k;EL*TRDMMQx4O#MkuY(4SM}rQE=+2&)$zU|>#P>m9sa zaQW*c^maYMq4kq7T&nOB>*U9H2R7ff+t5g;jX)JdzleJ44W69>#^D^NZ^2Z&_pi550*j#;@w_z|`#+tsyhr~M+9>)G(f%hngr-ZJD zv5E%&(B2j5)vMqZE+>_DZk)F`Z6#J^^9H(Yy7@Y+{PO0hSuwx!6xT`4?LNJFp%zPp zc^_npX%8l~np3T%%LTnU)IXt7zT>gyzBo;E7oD&l9{7B3s?z0ZC1nZ18jW+w7?%Eu zWcwsJqO9A;(W;!ALGx@jP>;U2LK$|?mYh#jxWuCCU0Qa`R+Hak*w`1jYW;BHGq^3a zqD$GQ_V8=nByP>+gLy~D8I{6O;pfrVF>$xJRgx2vah?ZQJWf&u(<3l_N(|@f>aLgm ztWfCLBsZic^SWgBcK@-8Q8WF%tOu#NPqS)##88F9dqXO6PH`q@w(QQ3xtQhJqAF%y zP4UEVma14zl#ZqRA_b;g``ONwn$gk5)5-FaP;ia=zUED44UO^W`IF(IOVq%Lty5VU zDit7^up;+d`S2YJ164`U9%|r^surrD5|Y@zVl+Uh1{W&(x=f;n9JG(eB!LXrbGobp zI*7h%AVxZqyvqRYQ?Z)?YmwkpcppKg{~`tbH_oHtiFgi#4)GC!nbC;Xv7QeG6d3*# zEg+wJ+%m)9lIAAlKUv20s}n{}4qSLe^pZ+-Ii>m4dBfbmqbVAzg$X0kfAtUsO;Ox) zT(-dd;UH&MtK2?);tMS2`VssbZLVsL#N}0}kkm9AsS*heI*X}S3d&>DOenf@!!9?` z)1Nwln>oS`-{+*Am%DqDP0HxqqInK*;K9Q*d*}hmIGhF+rRz_R0Y*rZpt_f?lm83=e~R{adV*o^GeDM;23G!8q=-8016t#w$pua0nhz<#7LlWuN= zbL|cth5U(RnvG9zVAfRWv)S zc~t}v=Xdf_#~~c-qrg5y7u)bi?`02x3Y8UFDjbSxj_;Ld^0dF7H;P3yiAI`v!aJLP zu4t@~_l4c71L{z?Xz#3w(5SdFDNG#SIlvCoq}3@s%=*$#vV67=t1z>~UG{Ar!UvS8 zZq9a9_Gu`;=Npu@7hL{}j+MCQfAQI#B&DEK)yK$LPXRzFc+ur$_1$}kAxkgonQ@a^ zrRH1J)LO;Wk4@LBfsiHt5^1f1^CAaM@NVR0J6{6Tt`a5oOe6S}y#&W|5wxkTKd)A% zbkV+gX$)?Y%ln!r0%(-$3bdIljsSs-rCQs6{_7swo<;a`ej7S8pWf1`-QPo&$dA40 zUR&dQb`+V7RdOqf6xKWF9z%G`{r^yEXA)x+2=fZn1Sr1>g;@9ys5L&6icFV=^pHtSNPaYCdPE z#yeRp1Ut>83eB?hzYMz{uZ9kav}0eHQ5ncRh@>?gX*dV@wj*qwTUzJHif!KRr76au zo4{Dfayr#3w;_*r7gC6&nN~?_9X77calep9IJVis3$vh4Rtwr%5r4xZp@W~AAKrf^ zEzoI_+q`LGao z--ASFNtSB`cE4k_U-Ht=BhgcWPm)g1W)SJ4f zsgDeO0LCw4lXu&{Q^cks<|+SdibfiX46U$Lm}3n&Mi`3}BIlXHZlvDBb%NVam)lHA z(>BHjw2EKJxkbq(ocB#Euxg##>d2egH~Gz9wQda8Qn-E3hEu{-pEZ;LXCFWc*6#yH zojxtebI1rlw<=TR@HX{7Y_p^YJckHEOMkOb?Tt@qkQPXhLetv&xFX-q%f)ALKXnM1 zEVG6t((34a&0XAu3=7^DrZr%MqlOj((3tayBt&p%1LAROwI+f?{+k9Kw5Zp=Q{9Bn zkv`l%3YBcFiIWVyjXj3aReGp)K{|^UoK+`k>b=cdd|$<9lT0aZBC-C;q=Z`C*)yZ_ zDEoU+G&laiQMPc_HainrL5IkGt^fGPWXuYV&|r0V=G0_^Ex%q)W=z@}WLK=%h~9`0 zBB=0%MgV^eawSt6Zblcgk)PtG!{WRWrd|I^@uNCUG)4wt4W%n=Pm-Cxva7#}YrL}S zbyat2Wp_9;_J65DWMa?k1nHB;J9uI{@@K1!OizfMw7DX(g$lf$ZE*^`LlyJ&6r%$o zYxi8x$Aj8qRdud)HtEHqMwMzv+Gd?J>8+{COn>G&NtjAwRoFJ2AsQ}l+xzxEXA*Xz z=keULU7uYbJnn$@3u4vz(ZSjAp1oxf7FKjyqm@qyTK$XYC+QHt>$oaZ$8bUDH{ z{iGdm>3$vGuY6{nwLAXb%?5$ zIP3K=r=cZGjrf{X0csq52pg*dmy8X*EEx`kOAP2PrQ3p2CI0OIEXip%iD^hlE;&gq zQpsSl!*7z!1aXeOq*`*4%@T3+zey)jj$*iH7=fY+jCX}fEF1G#?t8zDM>vD|6k(23 zkr+H_U4q?%B0TrOpoxh z4~RKrjo+HsibOH@|9BK+YkAVrCZZ0;&UNhYuzgmt)Y|KJaUW;_AI~qhzkL9`jt&0a zUxH;#o4FyCgFL&@f(aGS*dyxb!}IQpZoos+7%E-BhZ^b&@Q9uXM)u(%bIcc&@B9Ljc#3p2Z2N?eRW5DRge^k)e4FdA0A;3^@C=Vo%Ru!(K~SV? zz`wY*&N~WkBRjA{+ML-CRGOxBdukwlF+8K0SMdt_%_H8~qolPb&c@N}8iw_oenaq@ zG2>ch#S`-Heuy2Xv+gG>R_3LnW?kf-!W7@sleddyx~d-eSdv}?Fgh#wZea+_c4E?q zhp?Nr z@D^H$Uk*r^^P~qP?4a9X-~Ut5s^_kDKW!wF(h}RP1;=7{QeJNNvcl~|)F%X~ldlL@PJv6(vT7qwxSW}h z4d5;Vq|5#g^!rjkG+FPf-B1@$_M_bI@zNB@)CUe6tBA~aes8~MZ5G#h)XG_^`Bkl~ zmWIrQIvGYAOJScq38hBW_|4Rd?sSuxtbn{$L*+W3^n)C;r4I8t#@Uro71klN5L|`IlBX_$AMaiLvEq&s}-X^U?NI#o1A=fZnI`9>qLMlyGk~ z-{BsmcPV{lXs)HzBabDd#LHI6dNR2i_2_@ zY}YX2R6DA7aIl^xi`S%JW=}BMrpn76>ju}^px?ITL@-9o?5$3AAL{L5b=d-zbHA$U zel;#%Blb}u;xl>DA2q_s2i<3G$fz5BuovBe$&`!4R%>CV&Gs4qs-H((@>tWjF*$GY zoGtfU^PKIS>mK{Cc#tjw#pFG6Y0W-sDAg%hnXz9rw!MQMMPU!#X?q51F>N%#E9;M2 z1*JXi{a>i~uq$#5A_U9g%pt&0t_i)@G7Ash-I<+c*)|N-DEoSZ$cw?99n7!km*)XK zCePg4{P1sG4=DXUsIOeOcg^_^X|Z~wRog0=^7ig@8rlx-J&5p0Kor`hqu4$v=OO`~ zNm8aJ=J!Rrk|a$fC`~0qF1J)Ji96-hE39!XcQGxn_6r&I3le8IBU=6*&o3*9JDDQ& zoqm)9-=bv7$|hr%)v5;{z9Bt6Z$<<3d0QZaPo-QpGJ0>Yr<9x;w;IIK=@9HiR_T3kW( zx7%Lc`jdKErPFHySG>!!7rtI4A#Gvxl@3Txr^-Usvo%_X`MwS0DVZa897Z3i)KexW zL|-C4w=Ws+5D>pWTI!w}xZ8Dt#O1J@CX*kvm&7f?iLTMRElM@8#OIr@x?E%PpwOy0 z;?bO*BSO5vmO5}xU6%)E*%~+vTx#N89kp~m>wm^xBz+k5sq;P4God|gV^AFDtQt4Z zvdhJ8UaQ>+QNnSTZs{;PI!d8LY_e)8?e_7q^yGhag1n*=X|l+@t*(%#-IwnvoandG zQ^i^DrA-LVENNqfNg4+GN)D>S<~8!aG&IgA>HHjD<)M>NvCB9zMXY?dFY5zRNK*gg z&3m8etDMns#T*sD)b0A<1JM7lY{X1?!k0;&Ha!OU!lX+*Yi_iL+#WNcz$yIR1t&RN zKxQHL{3uiH^x^^=GuAYeYb)-(dhB@{Ps@xN>4HRZk0+CYLLYs;XRqqe4DWYPTS)GW z_U>jvO75-K)Ae7!E%5PIqn&GR2WO$0)<|id)_Hm1i6elJOhf4iBok!-9zp$BzMWJ1H)x=vmL7^h$ou}j5=!*aSWlf@xy>2O&!(Qk%H<}b z?AopgEByRM)Sxcn&ye+VAJ>mDZ6My0k88(Yp&n1omRH`|#hqi3J6To4JCs^s*B#DG zJA53>izrSAR{dhL@f9YFzxW9l15{I)+68-)2rxHe;N1YzB9|LG@q&=A}`1W$sy1%eaYg1fuB6Wrb1-QC^gaF@dlJ6zvOzWM$8RxMMr zJyqON?B2}ur@I&N${l77&b&I{zx79@FF3W7!DAJet||?kg>4f_O|c}7O~EcrL;*<_ z6C705viDp+N$w*cJ5CeBcoua$B@k(QJweglpYJJ%*5!C)HL=V)0k9;O@r8uIgkWt| ze8nq`z{=oeI|XljcfEQ{PCz@5kT`6@LkM5six)XC|CilC;75rMv*T{4Q-Bp%WuB23 z{%mkg1KdltC4$Beb>*EY7UIz-))H(>Ej0|53+$CN#WCl-yZCCBj#2gvecd8B7I>;N zlQ{@GJt=o}`yuEw_Rfd^MeBYk7Yc(MW>?yM8eiVF%tzxp6Lm%Er>eh4MJim?-=iY6 zeUA|t0{$KPO9lG18#|4D9(ghm?$|SaCRqNti%YOvY9OpaMQ}V2!D(cLkXNdSFg+b4 zT7*hTfOuc3sGYrtbL<%JC-`tYO7j$9E^~$P!vfxAP}iTLcN?g)M-1@TzY^Y+iggaN zQH*y^FX_hMsY$`+w5F??ifIkN{w0EV{%33Gn#Ola=!gtbm`dxV$!lGGCbLtg>Pc{ZZiE_?VZ_xXFp`!zW%&_uC=c9cD)cez%Yp1`hY+58G_9HYymo9OPo&P}P)lou2l+Jxfq&*y(lA*Cezq zr`wHKXi)sWn&bPmlLY34ZHz;d_eW^d-x;z%@8cG^*O-x?4(*Ex4Y{Z#M#Cm>PgT^G z)MS%aXcCNmfdmX6ijPG&rDLfKmx^h_%|Q?tLL;D*L3OrDbanoOcIFMA^YB#d61-yb zksU!lH-xqPan>eb;Br9gnH_~ecM4W&sJ;2YQMK6CZNx-j zvPAU?n~z{EwmmC#f~GXF%46k6pM!6E!0Xj;x_)#@YS&#GQX?&WR+&)C?N4$EIRxAJ(X28heR4AbdkL zp}OG!-7?>NN3)9lOQ{5>5J-AjV?Rr^@`_bmlvvsm;7B zw$RdRnW@b&pRCG%^9EG`Q6;C3Y{#$!J;o&(UWEi(-mNyk9)J}BDt1dpZZRgHAaR=& zpwyTCRuG22#78qa*Cgf8PW8%`ghz_U6|%>bteHib85IacEjY7y8PbUw(iv%dz3}&8 zis3$XGq`v?^AI9G^ZqF08kZ=&^q*aa+I!CP9eY)krN#|f@g7Q=WO~@R0-ab)_Zx_~+SPieC(Ft8+c=BFw zeJjPx@o7NN^(S*iP}9kAe;D4M z2oLHOsB@S?SVd_IQJIfXVENrJ?q^KX0L7{EQKK5LXSKuOj@j0OPJ;?MOj$%X4EJI@ zG#26)ZGv;qKZ8{Zx#Li@E{1WA@)a;AQm3fAa)tzd4H7hbXD2L4pcOFD&L*W6&Cu(z zrz2sKlL!bRO?zCPmUTI#J5nZ?nb5zM$p}$x7}q*SVb%yI&(>wOHZAI8G~mx$BuO54 z`(UMG2nEeB5uepOmrNOUx8m98rGp(;RRn@m;XYIa{7z5NEKW}9`S#;OJ(V5~SCpcu z=4HN*V7%20Z3=Y}Q!YW2gqPe^@nOVeiLgV)JXx8~Ml4E(%TMYZdX^2Gc7eW~aaPyM zg$K~LGua8_R6kn`nQv>~PXn|{Z_<+p9x6lpLAWen6pdcePOwCluh4dGIuseos+r=VpKB=mH49VhYC zlT)?}v0l0|Qhg-g&q>Z>OUG1-1M9QUc(k@LL0Ok9etkZcB*y9=XUJMFmuWA3kA8tj z+S2PSMOpPxA!Bjzl;C4hLXeH z#%e40$f_A?^Lr**)SU8<{^ho*nk{s%^L#{NxdL z`KlWINXz?9d{PKFiX>tlgow7;=a75c&k0Gu6vjitb3Ng2stj^L`kFoj`wH_X?~lZY zz;gs6QIq-;UgTNQ#wXqBK}B_T*vXsUDONPGALTCsKeR2ddlh)tyjdA3>l%DgEuo~; za>OhsVBa2nW)=XO^j9SpMl# zh(j#92L^xoHMwd~(s!Zxw(h^C1W#^rXopCoiwo-`D>4%@^RL zpEr6d#CI>`|03PBaJ?t>%`?B&EyK)ypId7W{j3g5kH3y|LX}8*37B;d&O6YPVHO_f zvew82eD={Rtu4h$TKUYBl5_djOJy1VkNDF3&6Z4)1A3LXLGd7TCx_L)Xzz%BO2jf@`sl6s#uB ze&~gjP>^V`sYch>wAlDH4>~~!q7yenW0V{Xms4syC*Y^%ht`Tl$#!Ic{E?vec)^9me4k3`~!8MepmPZ61tGuV&YU7=~Ej2C@%`7^o2 zrAHq>y*0Aq{gtardo>>gpqQ^;sK{Iem8+0X5;PtS!PII&4(3Ga$7fMBFmre<#F0wwU;)+AJw2_w=Ai+=+t#z;c4x zu@by~PuWTA#qkL96>3`IQy~0Jf`pxP39+uf&X5-C+08fks{_?Hd48gH1pqp}cI_oS zuI%K+T;76*N*o_RWR!`T2A}itxZ_k-_CQ6S_9iGJA+hECKtu-@dMWHnc<;WIU#46$ zoAS*LfEiJ%)*nvGvB|=@EqEL9x9KW%t2AKVJ3fLu%Aad=5*oBzVp&(IDe0GdmiJXh zrI7K>gyY^W;f^**-IG*z36FmmE$$okoyKPBPGs*AlQQ{Jnsy3&ar>;LKA7Jns939A z;Bl9qcDkHzb;SY1VLE}bay+8jdPfV07z9IoZQ;?W;F8FyItW3tIdIEKi6c6LW>ztk zIic>q{{H(if1{j%M%{E%;x?E8O|wfMME1m1ojT?|_(i5wQk0M-IOn>FYYP~71DD}j zS6#vyQn9Cr!hPSZj)YK-k7QV;G~6XtOqAitv9z`xRTQ!2NI6 zDeYj>XmRERQlTp5E%~osQJVy&mVT)uJFkeifu-j^st0HRDNdJQhPzYbrIctBt73F` zPzL7^pfh^JGiAU;(_2;1Uw^}Q^v_F~r&Mtv?4Tc+L;xzB;*4x3u4vwx--=x6C!Mj5 z3c;#6`GH1f0;k*U0xlIAJbcg4ZNguWcJ0096~1~Z^Au6#^N=2r)sk?0Fdw*v@}k(B zF|7`P(}_r_8mM#HQ0wLnl7(LT3}t`|!)A)aJ4a|AbfpZvsqtH7XkP|1ER-ZF+FM|c zThxsT4qx9xM~BVXt5LbO!RIpyDFOLyen@T_&7+1nSHjq03OS!vzHxvI5oyL@eVm5B z490CI@ZE~~WbCrxW|W`TCo%c^v}*U_&6xEDh*LWYl_Fywozpu)(7b$wqdhwu4}f(H z<6Utz8HX(BnuA+38?jSWg`EcIg(vIHX{^fLg#KZswwIc<9KyxASp1c^JiH*>yLAwAz|V7OLNsN+Tx=zuqw_HiZPnHO^4n2bWxamv@UGl z>H~+aLeELOZxEWE7C%g^Vdh@1)%;}jlC0E%cyJ}%olOC^!gh)mWErIe?f(i`5vi!y z%eY{{l>cw1%g+mWwkAtnH{Sp$a7=TtwLhPpBj6fbENvP`^6&Q5%pfq7yaPwH~!3DS37k|`qd?mS*AL-4xXB*@o3<7nWQ8%2Vo ze?n+#&=_M~sR(kgd==z^PVwpCkEzrk>Q$xlr@PqHpkj56MvaM5NOAFxq-kNi0=50y zj8JhqeX?dKW3p2?UPyw>y|MSlj97)WV5G|TT8^C&8uD;U`+~1jBkr)S?47GyB_MVL zJ7bB0)tY$CfM~^FqetHbu}X37{&4!X%Y~{KvuMj`F2s7^*G|SDwOy z!W-~||y(nFOtP*d*<+d)}3C-#JLLr1Pe z^i95kw|T?~X}vXvlC^izX#^{?yyy_T2GJ zxpf`_c|jnV5-~;?WKwIYNl%H%KoEEo1Eyvkx zkJ=^pOmvPN?WB*Dxj4uHOdwy4at=|w=(awACR8U*i-CK;hNBm#m5%7^jCtvr&UD@r zF^g}qlilgGD0=I`Y`3)!O6vYyRSsyOh5JY8OibWI%nlzki+qY3Dg7gEfs^POE!9E! z$N!-D(D^)o3&v#6cxr;nzw_=BDwC{3GI+w6Ij3bMv&eSwSU=M?c^3oq#gy14(Be56vfmhsyP_2vdIx-EB zBYyM0J9sZIPQC7YV^AB3a%p-o7-nQ=d8tlVQS+Z~*^nH)d`)0BoD}n?WLEZ-6iA1V zQ1rYgr%D82vP>;EM5s1sw$#Q#d09k!hb^BGNr{ZO2Y0WY^`8=L$4JF@1&%$erJd|R zd@Pohozp%IZ&!z+^R^L+GJ4tPG+UD^WkIa!tlh00^E4Fu*L=7X@>rJuR^3xtPWh%Ibh~ww%#hnPsI_ruM zVfhC4gHo*|Vtc8kE-7g61@2#c+A+&YL|J?83DX~+x1rKA*cTUyy?uYl2h3)3LN*LDnMaQoCXS9H$M2!eI(U(Dgdp@z%$)4a+LJ-Xhtl9 zil3eH1)myPhKs#Kgr6Ocs!i2)wne;elE?gn#n-{=<3+?c*Q&n4==Y7%@9b+=!_NHz zlx|ir6KdUaEu^=ex~~lr8V~7x=g&9B(*O{~6OR>*-*FCw(V=SvhWY8vlV(mqZ!ReI zNwxm=Wr8O8`2yM__HpruMPef?-UA1}&T|19MZ=z;_2<*}^6iqKgr^~0nn(-d)oa;4 zR*A=SXkPDW;ZS{-(5G?kGuKqHO1I-KMSc&$sWT4mI`LYSY>d&Fg*Cr zWA6~${%SZIZPhmD5rj88{8FlZDc?0Ld9dc9_mFv_!v9bp;KRXTMqt9{G& zDfcPMB>M4Ys6=w5|G|f1YLla%10A4UvjV_iZG>t^fL6s(T0AHD0DuUb;J8!>9dB;F zf`UG*Gv*TXCy|^Ww&AVnC|?C9zsOs<7ph%cNM(;z?E)Yz<4L0wDHE|v-a1q9cQ#5{+$zCWjz`sa&IVFgZeanrnDQ#I<4}1OvPp>1L}NHnoqfYaXkcIs$CbOt z^n(pgtHX(6Yx=%9{TwXUoN5e%EUi>|#0Oart!lVlh=)Zc<8V2R#i%1ywM$T$9cN_f z2Kyv#<0@{LKA2DN^a_LDwGHAJN(Ehe2z8ob^r4*Em22F5nn}Lv0rRD!rqlS&o#@W+TjCBUYT#pu&pS67I6S78U(lp`;E?`hhU90fmxQmzw^xold`KLt zAhY_pHJ74g=*GsB@_2_M@XxAubmuH8E2g)xzoS(eCJcyLB(t241vX4&JVYKHHb@Kc z+OkwcjbgubqYL!pTP^~mo77C3g>rB-;(t63V7tqa`&dH6L^1_INgiU?dSQ(xOpX7R z5K3mGi&FS%v*Kjp)V_q-TY_3mD&Jwsh7}YLPEU-!f7Ph-nhj>GnVi#(X`24;L{xrD zUYa{pJ@relZ_m47@?n@YlYC!Uo$B|sK3rjYo_>mGi8PD!%Cz(f75P#PSJ5=^0Eih& zRjyFoFvX13uyi3<3iglPRi&l4h}!-E)gW@&IJ7vYtn{`eRE5{NmAYJTRJV-jB|RM5 z?By4YJL;7E%^+9hPkt;?6tY%p-L|xSx_t5TrsoM&p?pA%=|ME)PWU;u38}UzA1=fm_k&1xk#2xZ<-$J;E z-eD_TH9VtZwsK#4brj^ssR%C{{N9n6Kz}9AL=yf%;H*K-3qzDw1`ZbDGOqZn<&g-9 zBP#8|vRtHK`j^U+;Ma0ibAD@lF?i0;3?i`B#s!7NGSShj03XNdZ?;V~AxF-?HmiYv zPCoRO%CE43bH$jeymwd#O5~V+ZfmJYU~kfDwNAwodj{#ZuP_f?9qBLUw)|k?q$G>e zO#YGeVT|i8?#1+aD6RuxKw*d4=cvtRftPR_F0@(1_-iG7KxNdS7|jRs9!OBK~sta+!*CTju7 z_E;qhLBQ2HdvuOZl`{8u?hpe0wyzV5vQTrgoFKK1-axT zn#G;XI|R!O!s0l5rH1BE`94Wel(JR_6Epi~o(Sjv`Mx8n!uaG-0q4`X7!Fhe9ethA z4QgoSyKz#4Hp$Sa_T6Nt9OLhTIl9Z2=2keWzk;g)a-i~C!Oq=rUNdz+j-lm{p24@= z2odsd`9d-&bOs)|0*7l1rLNE6)TLfn>`ED{s|lOxBbYM~xjY|#Wgm8CvBX~&FEQ|Z zqNl5k?;~g39ge|3VpTuOgrYqf=|EsYBMd@)n9;Nw9J(rb z`Yn18lBE2jc_Lf{Pqje0->qbf$WHD=oWKmF-k-JDGl%Se zSa+F7mf%|tBB1ZrB2gHwZK)&6;K?Z>-h;XkjBAze>lym8HgVLrQ3)Q40m zfv4}Su3#YaOf7ZteGujo2)Rel8yUVm)9h{ihbWt7*Ob1d<8a|=u(U0EI$%y0cev1^ zktWz;)O9HynvKfC0a8#o&74Oidz_MvpsWAVq8 zLX?F|ZDQtjf|iKyI)71+!QEr2Lf1*3I(B{HzMi>SWql$QfY6Jmfk})_iS!VbRBHl%UhBToJ`zxU<-Hg|r1+m-8-%o?z_0tBa%xf9VDDxFaU( zRNXO`IEOpyBE2_kFZffZok;ddmrqa)K>>){V-V4y&%*?aNJ`G{%7b8gT%HK7GdXZT z23hi)5Qx0Ls!^_Pl7unGopM_#8I~tNC-7RU!s2TIN#uKXBF@vO!jn04`ak91UYB$$ zCFmWO-B+}7s(hJ+rHIfx-CX1E!T2UoBw>GFyEDJK4t(4bUzfI%R1?&jql+kxnUQVA}m(iKQX&tW}2a~h@W6QS|;l+3CJimqKmm`b_I1R{y zJDisq&^ z%trhU7TCpE^BK?K>7$xdHnmu@Ej!&Hdf;|miNcVM(xCYU&8Vgy|A++~30g5h3Yv=y zUTzZ1lLV`#p!;NksFurQf{2!@WV)!9*+0$IpHm1H)iRS@Va0kHc7{}doUGDC9DzU7S*aJ{K}MqbfjddP&^kI^Jf9`Rl>t@e0>m)i{ZIBr^_LE zfZI|6?tGs{_TIv2W9+0oY0;EvN|KE#>%rIh2b~s^(cI|^dCUwd3HAl- zNzr)Hz0D)Hr36_=_Yk2 z{M1Q1CtFzKam8m1ij+AQk`je=-C_E{|7Zvti@h-9lr^kq?og)A zDI-Z#6D!ZR5Z6fC!C?TuT}S3MLUO`*SB*bO*C^M^Z0IJuagj6>2b)rZp2EgOY}rQ@ z9f-l>Y3twAyONCV&7?%lvu#}mvR8ipru^QUiS||QDqg5}lVcQEj{fSKEz7=LMR;0M zcWGL+KwIV%4yJ(RXr8rjs-?-WlrT=49VujKq=~SUph(*(2+ntozJ86rmWka^n|%^i zcxk+U+hBWfUWCJgf2gtdaTOw9E;&{~FtV`i54kxypDb!TH)mUrc&U+Hw+zd@XFpRQ zm~PC4JQ469g{UFEhHn{-+=Sl$s_QM@rt`)qV$njKe&yjZ7ox$d+1}P|Z*AroT`A0} zD&jnxvbL{h_Hg=@7JV}+Y4v*PEK_kn*DD^`RA3L7$0ZYf0=(r)%rg~t@CVEUj)0%r zb~ir*mN@<%|DO&ApqSVYHtL(@7TfaUj5~(>q+SP>d6npi-LHfhnXjh6>f$a=SOzBM zTw?WFMNQec`7lxjz8$sBOoC$p)(8j*n7U6uh4NEGNqVoLS+dUQU*%%ZjDkZauL`{C z&eFyG3cXkUCTQD>dz77W6qR!Hh53b(Im4(BJdT{2a+#d+j+r@=nc2h$Zfd-&N_?hB zRX2cThB!~8TWPNGEt}7>``r!7H@*`cbMJ7Tw~bD}OW{BzDkGpvr~k^ziDjm?3v`39 zyGgLR`dp_cXUs9m4ZM)rUx}i{2Wl>f8 z--U7N2wK$}=g)=lls5f3mmVinU~mz%8V~_^lkHJ1RPv_{`FD;+iw`#Bq=w#ZF<^;z7`+9-*6uo zEb!~IEjST}y_cOp0`h)Kokr>H}Fx2CIpBHY8@L>t_;UX3VP^NCP`*W`kA`Sn+_fflbcZ>Z7%vxuk zcK3NxHxTSa3pUhu_VV%U3b1?1{=9UWgZElx^)({?IX)PT>gew$lCF-;kIgXSg{tvznm$Ce7CUGHhZ9 zcgxzrZ!4vB7;rwt_0IMUT-UIfPNCSvn5{Ex7MMcIp}>{Ll<8_GV}rioeBvCTwX}i+ z7gx-u^*G~t{vlXr7-pCfnH0Y%q^mb_OFeEfgG~3 zvY%KEM@<%YKk27n%(a^963q`?mYoiXw(@zV!zuG>ox~6brlX}(XOoy$EVJu$WM`eA z^m6@rq?wL7haV<@zTGJ}Rq9`sEO_=)c~33 z!_S3p81YAx;y00Qu8>98sKTVUxe-+*KK}ujhQ8|g$Ufsk{a|U4%X$heTl;p)b#;4w zF|<=(pFT~@B417J3ZEtb7hX>Wmmh^Ahu9o$S1LP7ZSnQ zL&V%AVP=$&t{JGuX>`LmE2QN$_@_td4a`VL2QGHw%%P(f7FfsV#tT-hfY$I zRZkcjaFzQKz{Z&kJ)l6x5e(nLYKPG;9N2c^R=%SEe^4dQzRV@AzUr&d(5T5CNHyCW zbeXgoaBUNu0o3|J?E2PtBAIqeL;)+Fin+_NB_7-^7`}@F9TD6i1Os_Vit6mKI1vNh zIm^6*ldSR-SIJSNX_M+y^$&#Eq}Gw6rvO|m>gzbW6gPz~Zo7mIGg_`|Po9iHeIO%! zorvT*Q(g@P!FpvWI{pAJo6}OCuNx+1>B>m7ACT?`4}A_lzLQdf9*{U83&ZyBzPXYq zFbZ6m96qiX{f5hbVel@q{U@!mQJ`KY+y#zM{A}kLxS42NF*rqUYD! zxpEmfQ`^C@)etJEsm`5Jp9$9^c*#txi(BXyyVBEZfWxf1-u{or-b+1=K$A+ZAzJUG zi#19WIu~z2)XBnyet5W+N!%$wZ<>!%exz~xbzawKxZXN5IJ16lRn4e1($eWYaSevi z|7G@BQjbeEeg~H}E*I$EEM)wn6cQ*yf?%qaJ&Fw*TCUorrKWdxSd^egZ7V5uMp!`3z3~BkufI-|CVU3D$OI?f%pmqE2jYAw7ZXG3J0lW)QddV9&dxJ zI3|APUWcbBYe$cgT6qy%@HN;OhHS+weuTJD<&^CtnkwOYH`nX1C#bl;Hc6=|=l2(= z;%y1CH8OHH$=0SCtq0t`6Fo%|HKVZL1_(ZqOPq9PvlZKW>UCf=sTNrLdLMmW`IXiG z7XleyGVFtZbw(N+n(`Gj5cILt6m9kdLHfrpCvXPzje0x8!?1l%Uy}Vp$vs+YC1UaT z-*QZp_&-SzlLN%)mv_t6sAy$mm=0nT?%yQcr0TMV0&daC?B>!>iv40xGBw*hPed3~ z`X=6J|J%M)#E(jXa1BQUR$B?-&rie~Me9PtpN3uKgLfz!CFEWykve)xi{fRo4+Yh| zBd-?n`0};riaX5Wcua5a&QkUL9^(M~kaq+frAor-j~^e($nFmPc7FrlcV3J!tOy1% zK9oSK0=+n{CItx!ntQm|o_vwHcC_XI@D3m{8bSPfF(iXi9POzd`qO-q$zBhk5IA_2 zk3)E9E~mP`FF?(GS_Usra;p|z7MBgo;l}?3+)rE|>Y{|Hb_pCK0SZsFc}QY7ljh#x z;u_>T$GFvhH)jijx#WrmRx&vFd=b$WP3?N}eVkVJ2Ykjpn^)r~!Wo|u;jB`5yjuAt zEJe~^RiA~#5#X7CvFlpzq*Ek(B6~XYEy9&&vj$M?EiTJAx%R7@TjlK(Xo+2%73v5z zhc*nGDr8%h_44_gA$O7+E_czmF>#mEdlUa^^*+D20lQgn{yaB)a?JB)D#nkm*@K_u z)i8O+A!~B}LhV|r!`k0r5UPTvI$c?$x0&GlrnTJp|YtZTYmk+^9 z#0`4Vc;tvRngVy3TrB*mW4WB zF$1{?H56P%u;H{85>aNY%4z=5C8BVZ#_q`Bx5GQEgW;W&i$|(O`!d0Vuu>-r8i3#0 zrbHKv_>Xe8pUNaGo{ypZ`QAfYSSGHmK5azJOi?zOD_jd=x!8{LyWgAv zhmQJIAh{pTw(TTA&684ZYBC+VZS#3IdZJ| z?Xq7X@dKwW_8XD8|lf&ZqCBmlPw1`hhM68{-z*Ysa{KdnpT_qd>Xwe#Oq?Ou9eTF3aDFy zm_!2RK#B@`s$j)m=4z|J0usv{Ps<7c^KJHJtBl?3!~?gbUL=d{oBBYU<=!xhZ5k6K zSzQemiIrXj;>It30}RcO?6FF0$9M!|X3F+{C8N!K0@@cM*VZ&3+NmMk#KoXKMQYmB zvl|ql_tLTYZCSM^S~yW{?zIaIV-Nm%Q{51~}?Dytf_wnHeb_=*4XCpTS3iE|g~uGiJB!5NFs4L5SNi%n5f^2@tx_)|n&ce|>HiO{Tq zbddEVHY8vCdP`Pup{SKXX02TF->i4H_I7rk)b$Epck@N}dHFW{b67VdVqQo6II=xw z+R_A~)qFnv;shLwus;J$Z1|}n7lg}DW)``Fo!(9Lk&8`S-y;U* zRiz?C=98r&M&^^h|7rf5LNLexnpwI#%jnHl38G~fGy2>?$G1vzqN*xKxcQVU$5g=O zqk55WhOeVlmq9q9W9niFX<5d}aB)Rq5(~WLk|RaesF0oI=A;^GTXDayTZFjcO>TPd zcx)q%5|!@6W#hx2OoD3KEjlo|`ziky$cI$TPM2@xhYL8JMWe0cku=@0vLVbZDfs6atSoby?hHN4pqJz2G`m_fQCc|- z*bucYl0x+tSR{EH&F?*q=&&8dnBlRpWTp5qh;n~$g=(J9hr8`V9^g1*r^Dnl+xjSN zQX5h7k`l~o>@$E>qzrMp>8ecQfwL=#uuQq2)om~? za!b3VfS!cZ0E-o)VjF-;3Ds=mixmI1%7MqJa~2Slx)F(SI46hO7>7l_sC2=WDDibH z^Xw<$`Z@1O|1ejZuV{=rJp(+=A@G*pMI#_8*?xbYs;lg%xzpLDuTxDgvvnh!UPNFh zM5}zAdL3-@Q^AUqv+G3IZ#fO(JSNmK9Yq86no_GG^%+vDBlQ{I|1^J2A=ux6Y@g+w zZ8;ot0e5B&n!Ne{Q1IgA%%rlp1am=cSsF<9qpoW|1o}^(1+t*n>qcuLXMIo`Z|>v3^{YVE3YseDP~quldaB#& z@2@Q7)fjk`L(Y{26$$ZYJbitg&n!2%b9o5lKW-sw-& zKNiF4`ecPIW#8W~s$*?V*zt3`Oiqde_rtMDal8UJ8}px{B{4O_>An{uK}LrmHprXQ zM0b^v*SntT{KfC#G#+~ry`l@wEsnS~9%T|c>;81%)&8K>1te&aOihLytm)s5U&@lW zEi-hfH1<^Nqi)+%H?Zl*4Xr}*GIycnYQv=4ON0Ka*Nj5@Q+`*)x=^aT z#ABIqc4_pVG*UVWO;HLlc^EtR*ixvGB|*cK0y>ZMYlUl~u-v>`;~YUY!30AR*0`p$ zYF%$jk3XBVIXwwF{SC6z)?}uoa%8j?zqC-Svlx5_%Sl>n#CLho9-q^+R&{Z+^Xi@l z5?=vKN7w!La&|s#ioINeS2JrXXye58mFCrRuDeehu3je&Vp%JwzllX3F4JOI?MQF@ zcfTbxV(c(Vt;W@(aP{Gvn*e0vX)9`iw0OEhfsA46ByygA#xD zFUKg!6I*b}#(O@((I|vIiM;A%^DDI7c(*96ZxbJ9J?O)+dr++W&m_cOQMH^U?Vh-_ zZG^RoE<=j8DJuF;!dyJRRxusih_v&iEK-9XDYdf3PvTrX(f@!0?VZVsBRh}C0_~Pv za-L8Nchn2!^6Tdd(Ofb&$?x)7&Deln7+RL=qt#gRXqhpw7k3;`=Sj67aZYN#nDFr0 zOYxP`T#K^*ZC46(Si>W@rDO>{5@*NsNQs!o_|KO*p-16c!inH1Ak5E)A9Mmf~yfrD&fMjU!d)qww+tECP ziNRre+it^suva#```hHM&8oz`Ze9^aC+jiHpAp>pXo%eUj#xD0zZi9&!X8CTy5-ev z9Okp*pF|A0<;856l>h0<{6)*zABC-1w(t*7RCS%ybtN3~WvYe2WeH9+Y!)7(<$IaM zOcbKXE1lMFYe~Ft^-5Eu$0#>Xd3z2`rFDjF+jsxw87!^|)L*-V@c<*ME&My&PfI5c z*`V`D)&Ot)XM){LgtyUqmBFr$uL+k`;ocN~Al$dxZjxO5j9mPc!|-IC0K5lS92F_=wft_ zSL2IY7qjp6c|EM{k?>`NgqU;@cQ;4COe1*nI3940x#(HjKHuRXCyD-*2hWS&OZ8<} z+0<%f6}YBbXylHRMoTBhuJAK<9mn6}Gd45l--8Bwmr7k&q}fo8eh@-+4(WZ=E*P}# z+~g%V8Xat{t*Nxgr=vR=9c`_Rtt>D9(-r-LI>2a7@HrHW=?@!;LVT!CMHW_DgVOl> z?MEm}eaP?cdv8u6P8N&2@Ha{Kp+c%gx_~6lc=oE_lsEkw;SZ`kCg;6UXrdCi!WZ|@ zO#%CD(p@mFl2~`yhRki!w$;i7f4xO4c%h_zmhRm@WdYCTXxHsj9`u8xCG}YwJ=ec!Is-2d0BM$xg(} zRs>3WO;&r&Z+15DAlU{7+6G5A0dRyM*k$*NHDNVP&%1Qp2Uh-zsV$$!(RW>U7G76J zZ&Mqqlp~RSQhraI1I{qNb6+RtjOxaotf@tsxwpbYRCvo8#ZHu{5Yfm&q29qG_?2?e zVNpFE>~k|+>8WAh-AF!Ykt5TO=7(KQC`d|#zW*B)e}SE*Q3EVoapVW`rF zZX_PIb7%KM@$Nc^^R!Tjl->;oZf(FR;`#^yw)a?3W8!f&7nA|pS?%0VQora0<)Y<+ znGgwnt}=N> zXWW#qi{})GN9_L#+yArN?mqx!TK_{ux~nmVGp59PX1%UWV%>_MJUu4lu^fCbUBD$W zf=}u@B^96l)1$&?`p_lGT^t;1>Qo)he!A6(`7*E>`qCkK^KBg=@*3uZY;pRC?oB^~ zz%Dn{ISM6Nrb7}{rRE(*P1C*&%?dpm=|1PL-nR)o{|S9))M>kBJOYmvz!2W%ed?_J z;jKK&suPoQoqOAA$2w@k%BiYt{lx07b-4o)CEB*WI&lWFy5kT?9UnQvT8~UsUpULG zvmz;6EeNvTNP5vispOk+PTN6dY=FkBk!V^8nx-(4ybu{!lfi(+TmC4QOcM&VbgjOc z9UQwX#WKXbVL_wK{L1$h0@tM+DCr-S3y}p)EFGlNB7IVfUv6TmnrN1!dNwS|1yn3` zXaRroU9n_&N%3W{%PgANa~|}0JZ|&7Kp+{uj3gZh#2Y_ul*_rXGsmu0dVTa(e93<- zK^?fif~IklqxuROzaUJHGoZr3gmFU+jcQKW4bOVe{`|z1eQs-l)x{oV zL&`tR+{PZos<3B*wYde(y09nB{Nez=y#;P{rJf7t2n?P~+-H0-m!EnIvFejgTepf^ zw;Hf&TDD@ZTb%&i8acVAo!%;+-m$}HYB|9ocSVgGCU=WvOI|~|Xzcn!)xGZb)C!l+`^L8;EBl;OeYxv3 zCeHLLC}B=Rf4c1SD@1?0)qhZ;u-o@x#{|#S#5}V7YA_FuSXRa(Bv0Z%UGr+;GHa`p zI-?Y3;&-|q%^6adGl+E`%^Sw?LZm5+T+#ZCsk7&bbXMz$g0tswq3rri zNgE%iP`2%4?(DIC>QT{SR4Yad$hmQ^Tn=BL<`mYMB4TYdqZW@SM|_16CWC0y(ju}s zo(sV^1-PJ_4rj?uBQQN5T@ZV@D9f1|uR8eTf)CwQ?y9@57R&hFA%QAoMdmC#J@`-n zk~}jEnM)^WZmh#eSs%GVRaT$I?pz3*QOtWjJ3Pv75;-$?0;oGuwrdA$mv@>izW!?D zVALQ?Vh9?;9{PW5eFack&lhf63bat5f@=+jV#U3X(&8E8G61%hj^ z7I!H{Lr8(*gy2ELOZ($L^WMyxxpQZ8$Yj{vb9c}8edp}8idw4ba`|g^HLg=_7_{4f z+qcZH$A!at6p)MA+q;@rpCXXdFKOltW(v=!f99oZnJ$I3nGo+Mgk5H&G(1(G?oE+c zqG$y*K<}O^tSUZQ4wxm0M&%E$XIsva@GS9WzRxYM15jcMIt8M9e$npiM^3i*>}?Cq zXwd|Ze<5CJK`D++5Z$pKS#|J^(MW2m32O~Jmxy~~=#=msUcRwXB7)URJ1d5jQEKTV zGHe&6m2Yg9z+v%%^WU3Ui7?FXS*)ZD?#TE}Hk&9U38ZR=DT{F)vy`M|&BB9EnX{JO z1TxJ$ulHI_Tb)ib+A6L0-*rRSqAm_FL8sob=q45%lHzhZJP_N_cD8`JsQG8UXv)GN zd&q;h50hpqYYpp*6$c=W!u#bZIL`fOL(%ez27QA$Zk`G5q6C`KE=N;&wIAl0PWvP? za;3|der}#^Dls{qP)1C!;^v5A^ky8t23j3sTZi(ra77xZic(L-ba`3`APtQFH9h`X zjYSg;MU_qL>bLzth7@VA@XBq?T}~v_x0tG-4!+e{xjEib3nxJCME$n!x{1E|@}5LD zb}_SC{S_hGH5!0?cV<{o^25lN4{u9>dTT4y^sY%CdQQ>AKjEQ!vn`8ySSYIc{Or?WrPbC1X1EOG|tujjSZq zStP2BYPjxI zgr3!)a{6xvZ%)lBp^b+wVcVBLY;Xwx5Ovbl>Z4m@pj(rC`Gv!H&JO47dD(MaP)!T~ z(74&Qb;=yLduj*ci^GcGuc&|b|6ikybN(=s3^UzIho#KV7OUfDZqdj0@?iNq^hMP6fdUw3`KphaiIBbBy#?YMHwPA z#)xSMw4JM@ZK>-C#imKbfjk}ERn9nxJ|S~7?p4hy*EF=OFuDFziCABlhBNf4Uf7#T z>K4g(T{Jv~$t1>O$$B-%7GIUeSy`xTGJF;LxoN?g8c3kbxPDkk|4?C+6Ub4U^9ADw z$gM9P3$u2lisOSj0CFc9pHGrXi*RiBn}6e-u3`GTapyfi8Ny>08KP)StIe-W*+uPC zDlqtk`QQKOY;#aw-U|(EkXRb{W*1#>w{rAxWBS`5|KE=e>^KPQJ$w zJ3oZ;rclgzK!_=*s#9!YMR!G&f_0ljoibwP!>f^?5)5m;x%_^M*=;@RhGY!#mW4ea zOrqsW74!~V-@u@C->y}kpp=Sk-JiF_?5xJi{q4lCLw+$Eu9aH}b$R0N8T~ko_SYgU zYivP>`OmO>HXrFA$~h0Gpjs{t(txQ>4oS!4|9XnCXR7HseX^2`EFcSxsh(^<@rpV= zOu4MJxrjGmna*$N5U81`LKK&m)dkHy`awVHXE1LV|E`$4!>WcoHfbe2b`@LxnRu_( zFG)+(KMPG}eNOKeKUm_^EetCQ2`-Jp!AXL?eZOrW`LzK-C{*`G$l=xA%^xHLuOP`v zks;9!ZsuH5=YYa0Y45p`T{#H&yYOW%Sj5t4spQiOM}WmoQDwfIHZl!2k%Finih?OQ z50{=6a>R3KJtq-Z^!EL%L&5rY5cN|ahtxYJ@X7-F5oS9V?vzVMUqch;sg4J4oyL9y zn05(Utj<>-NGJPwB^Af6XWlE*fKAl;+0IQBy0%6eUG@jK3W1x|TYY$2lUHy4%ueMq zMbe1wcRB8L!H&%{AB-yWIk2TJ1xlO9BGvaxS6Zf1aloR)?+ttKnkA> zk|t|AN@Kq(uOWY<^;i%b(8#xPZM_>w(<6a0vrW9*1u4`*N8pch>zDO_0^Zx8-A_hi z`$kOO@=oxR!&=aLpzBOe%Bd<`Cgd1bi#!F__)oxN+D5!-qb|Aj)do^d3YJfWyvo1Ql($=E z8S0v6TcpvR%h<3d z>$1#<^9?Se>xS1@%jT9JFzV!aOu-KZ?LNpnTQS4*bqIRa?qD{|ocAm0eW(4uF&~-E zb$jdE`U}x4w{n0Fz$g!0^?$!G?Z~ zoTmy|irKW`IoX00uF*sIpbkXEyL9n}8}{?wwEX0*>`_Bo%OZM{*L5ja$@02!P`Kf2I!9tfbeh@EExd8@Z=Wrk4pP*$xTY z4(Zjbq}Hwo!Wxb3pAAsNOF5gDTFZ>V3?>QJ2Ka&Q(G!do!W{-B7NrvclXkRGl%%5n z3;`S|v6XJkbf9(#MG^g=h=|Qf1}yig&-;PIiq0C5uRC-}QAE6VmMc_#T|0jwFfy(v zA4U`rLX~e5U^y*07F?kb5Jnac*)B z^3RM&ML4P%#A^?I3pzzPX(b{YzN1Bcdoj4Aku}T_89Na?tG=Fucst^EEE9lk2_C=dn2WQ1~x9`H`P(y0&vGC)S zoXmcs5tZub83QMRNtV4Rdo|>kakyV*e>iaHm3L>oA>o$U@1SC27CSC zm$09(wg204_wVM0trdy%GX?4+t0RN1c|~f16r5pE@s?dnZ>`w-Kj>5bSCQ$ zgO8*4VUWdu!0~rHUPoqy)vE=N0hE;qh`Hg~-|?Lqb_&=$UXr9i0xyc5 zn;7v$X}hSS5@%lEF8?IU#I#-dgROt-Y>XQna%SpORruFqzey`Ut)4ML2Ed$Jfuf+2 zp((rl+F1vf2pHeofY^KP*TPSXkOj4;%S-hcc_kY}K-J2nCflKtm-aP8jsT}|=v+T^ zZiT9G209l2@B)1bH2Tz1+ACAu>%?7k2L035V(IG}0X%OKf^q+Kf+_?F9Jz6K%b=k0Yz5QKUDFh4m+QdjmN{tUNWJ;L z)ruj*T*b5(8*WaBwi0HlOWp8I>!xplE4>C^KnZx@^rF4FN7la%*zceCA&)JQcHO;h z4Q)af=P!r-HLrzR=ZSmO6i1c6F!p`v1Q`6}^IGfUJ8nSNcUJn*dthcv>3@7p6z+q@ zpFnD)fvG1!@VLZgiTkAy{Z6W(KLav#K4{xxm+ncd4-rx(51SGt?%#(>_hUIGY1Y!5 z6E$DBU6;^(#(coYV|e`mAupxXu8I%2_6{RgyzNO-Z_M(4UN^)fI{0M-z85cS&)HMa zpkY|7VYX3Otrven$tu8W|1D8{TZej|GwO_ze6%`o53iBo_j>WoFs#zdyq(&)pD1aY z8g&pibx<1bIfOdMofI|Hj_qs5nlD6hUoDnPGW|;RV@pPUILzFi`pu(Pu8Wh|pN9KL z6#twxTKlAGEC8>6*|t99oU?qmzY~3KM(3;DDto>DT|y7X!t<=0>$5n;(|BianrDXa zxk;&eaL-9{b)a40kyoBm3AfLhSKmq|I&ST#w*uzBCUPjX-}7s0pcI7Ea&ev+$EsK3 z1gaUUnZe57hkFZcvQ0~rE7e_ddj8II4nb)lq{qVD0bhjd7V3WQz+|`1Mp`%Rz2{5? z2mGp$^A1>1#Kn-8LI-lp#rydj8JV}gP^9@zQ_IY@bKO}Q8VAYdgxQddO?_EHj5%u1 z>(&%(S-Z2aPr+b|fks{ahFxdPP;XFIQ~6>Ca904fm|MDNVcHcATkO!^{h=qd{l>`R z;Maat6S&!J4DCxLs=$X{GQyvdTQ6FToBm|Nl={R1o@7X~0?TC%ni!LA?Jm-qEu@-p z0F;eGjR&B{t5l7%P~$*=2guChl>hPuKVs>|`S~$!>fh94A;pbcM z##B-G;K{ifI=(>4$XzNpcwY1?(Hcrx@NB;xZVM4clxh@3&Sh)Kdp^_Vsf}fA-oaQi zRo#7{8gHvj`G&3r!=!+_ao1LIIj}Crw#42jfDi(G8^k^`oOh-zwC4roc+}v3G$3^*?0Zz=b7X(C zg{Mw3G}>YUx6x?7UcJ&_y(&Xc%S?#O{c?c^F{qD2n?Dro{h=XqiwvLJ!@t@{ zkqZs}>+j!a2&f(dI8)kGW03YLrg@V~1*Qkv{dsi)lgp;uz9T&A+F}`?2OP`DZZaqD zQpal^0Cs4kVZ_U9#+p!Z6Pf>*cDZf)Q8^O%?4@x&I$0{R>=!8N6~smT(mz`lnU z3AC0rzm4{cB~nfmEt#-E07dp-wE+#jj}b7xBCYY_2b{(PBYw24Aem*J&FsaXxN`^a zs^{gVP|p!)zPn-RoBd3j?z{@-;(lL0Fl8CeHsDD$;5n4IDLCMnvfTcfU(2b{Wt!Ao z*6^9YU+Lzu<$W>=%{o8n?cch9$*ZydCKMs&@UUTztW6?q@6fPq|5h9!nkXLz5|eb= zdUk#`R>E7EJHfmcTJ+}Y3 zn$^(LVq&xo8bd?i7s!+k7;qY&eh;D zmR`JNde&X4_aANI!_CxO&+!fjgC_1K^66lMDEHA;gp*R5WpHak8M*?MT^nw0mt86Y zLB)DNC*SlVjhc?IsW}zu!V{TQu`k(h5oVS}wl&+F-a4K{|1n5D#yxChxRK_cLSZ&W zYBaN3zd`d&sK=4IvMin+6f~UpNAx&y_^Db#%qfvy?2|fLkghG0=gq@Bl}T3g{@ISW zAF=f6`3U$dS*O<<|4nILOjDbJ|H(^vn6aSdITfkh0&0W=USavY`L6;*Yf1@Z01y;d zFf-^2{1;a8ZTRPJ;^|$JDPbLXlP_gpz*M>66yNyafJerv>#N4H{a&?zlGjsRe;EKW z6U=Bh4YGpvgWN_KbD*G_Yy(eXKVb2|$jRari##3xNlvEE2zqd+#W*;XPdTDM`Q57{|T# zJ37u+Q#tVZz^~x=R7^u6*A#-x={lE?9rLbSpIdgFIc*IH1h=;Gfl!6znDHsB?dI9R zVc_X$tHVDt7&TSX3hE<`G~Yh}?!Oq7J~RQ_n-*D&E9BVsk+S}s(WiS~$7$QH2BIo} z)qV@E78tZ^5Ufy-@-i%{bQ2{jn8Yb!7YlTDdkh`^BF83A1!|+oS&v*u3L9x~!i>wA z(FW-+S2-aVM{HX`3NA8DI90-ckyR+4?;1K?oY6BK@Mo&1u5AN85A*q4eV&?I;N~22 z>a@o6hw4BkAUvxm*lELizg#Pg+OZ6fW|YbseP9=S@B5YJ0cRH%xw5l{U%rpuFqzuKyatd1s8Cn)Hd~#9()AUw5tf z(yYT$>P*9m2>vC!^=cwc+#*hCj&l$ZCwGRP7M}4#(^Zk@!F<(0&EuZ+$LY3)H?j`3 z^+rX{!t779QxA#jv-QhI{H8IC^_za)CYXZFw9V5Mcxy_Ta~ZzrCyGDoeG}=~q5+>* zo_wvF#S_Fw-8Mqqmez%F+V!qJKC|4#n(ty~7BP@r@A~6GN5=g7oxH6u$?DCY;Vk_K zx;ay>oA9&2+TK^9%(78U*YemORU@Etfq?DS$KIe%NPSBz)r=#+3yg36apHEvQZ=4I z=L)G#4&f$SVKc7d*Y-dC49^mq5L)j>FxQ-V$3bn3b}56k_Ykt&_&Jios+ssZ^+@cdmbmoijZ14MbaV1e^9 zIYhQ-inB6D7RP+`227U`UNB}sANLquI(!l6v4Y(f+9te2*U1L+2wD5qw_XIgt@@`D zz(Albd<4@{x+qh==v2~h#x?Iqg&F6XAK;o_)oVs@%?DCp9z2^SqdB-u;}Ri)8|rC0 zITmHOTvMWig{!>y)kbw({bH9md3CmlJi&I zexc=*%(Lq(-?j6UK2-JC%}3};&vr|5{C2FBL>P!zZAlGY#o$u2#*$ij1!sK`5ioNQ zr-mcgnq~FkB+XtAn|~Sai{m@TE^Ea>(8MN|y7x{g={^2XnPd&-&=!vd;5uz1#*C`A zN8G*S)mGouxsltXja+y1BDdLhmrKham@ROZ1BnyY46VNH{JZAHAoi*lUd-K27L{gX z#o!7(mS(C7iKNo}E+(DS7G7zX!Zfoq%DuP94}NIX@(M2(o|k+y3}gHAtn+2yPtoHa zYGJb$RTx);vY^Y(O3{{$H06D8Gy8^yxP+#T^f_>2p}vthsM_y%Xmdfd1pm%Rzhl_1 z4rh1ibI9RN+Ej-#e$@)XI73YK`x+;L?o}SyR$kXB{IISRNfz(P`dyYsa1ciaRJ@ia5BYvKGDJ#wDilnzp|157ckE`&c@_G3h4Z#~Xf}_& zBxYE8-$f@Aq{b9^hmAt@1*PS$#K?B`Y>u*~+ZT&df39HnZg7)G(1C&;!(sW0)!3XL z{)ZxCX6l)@C>fN0T%c@3g?U>2w642ZQd>a1M7Jk*a%`*aRGiJ_S$7vZykktc-wQse1Q1$ry z)`94kRotFu9Wslj7iC}#+frYVsCM=`6_vcee|3ob5)vL<-O)O;fZEz|_L}`?#to@o zLV`Q!E!o=syuLv*P8yQB9qYKfJuQM_Qh~^M;uQ)pMM^<(N?z}tx|3~#e_>jJ>+e=? zu)Wn6Uuj-vw3&V8H|;3BHSRY(;5WT`Sb^}H4wUW%PCCTfUaV!K?hd#U zc6yi5SF`|sXE=)mY}@X8sP22j`%0|%N;qVaXZ__}(^uAc_C1F8J!YjcWHj6l4qzp~ z(`f1ADw<<7cx6-nYfRhOaZ_9y;#idB?;`1No)#Cpzw6BqjNSES!Qbld@%?`K#Id_% zA|R^1%~LoqNa(m$lv=Z7+wfgD+BCR{h@~ssK={X!pooWMVx|Ek*AVhv@<>&%l(qT? zlYc%taKJ&6(z1Gxs2<5Vs|-<)Ji2-yfOLMelUiE0-Vm$2EX`D0&It45P+qez2nRe0 zc}=)kl&N@apdwaT%Luo933{&S-;?FNnO=PnW)7Oa=TjK88o7@I z?;{*lnkALM-eY#5Up?wN(=L!xQk7@td-kX@L@oI!w|d*fP)=e_P_@j-(1eG7iibZZ zyk!vHlI+A+hA3G-l2|`7^6<~_^cO~&n$#N#T?CYoF@-mG3m+XPY4?a(ggOVVI!|@4 zx;t|F`R|-9q%DBHDqCpMfX2->7hWvESI5DjS}L1QTe?ws`DZBd0F=)?!Ylb#D-Ah>D5 z_p^vD@?%J58KQ9gXaOGB@Hb~FeDiNJ)hP>a-8@={Uo4|eSg`FA64l@4&zEk$8IQ@e ziIMJcDm(4T0HT6qE)XR)S*=D)_5M;BpPRPLA|nomym9)T=IF^^P^uxx^dP7RWy*d` zL53D@;TU1)-9^Q0B;ECw(HUbsk@uwqbKh#@JbZF`Hx!j?bCWjt!658P+;}s>R4Xid z-ZT+$FJtlfNV}6WW{N)arnK17Eq&RV?F}+jJfn~fY76he(rhH1Dp6$~EU}*^dCvbz zcE)z>3;1QR>xY-c`q|IiL%yg@02S?_GexBb(pqOS+StJ7`H~P+P`%bhhlad+oPBkir_H71VsiR2oC=7@CGhQ!6j)_JO49qq!PM>pIAK@4(ZV+{^N` zE%D5(6Ls#PUJZ|KuIllDtr`vYH|b-KRh(ywSw|7l&VGor?fo>ab})1$(tKfFTbKgF zJ=A2f?=;nnc#iQJYARWAWo~p!EcO+bD^2eb9@#FO-Mr9Ewbk8RRyhk!%E+^RuQ}||7LpvFrF%{C) zb4&X7?bQqZn%botK`3*G;}R+azkS#Q(67<7t=QVA5PZN3)cn&Gu6d}-+=OLRX@?ar{B;c$T;{FQNUHM*Exn`YTBlb-x`-V|S?Y!?8blaX9@3@%!|tE?l*=HH%El?E072pAlTM19d!B?rX0gpLwC1k3!B7){X`9`pPasiB7b zTy^tZUflBBE!#RzzGXD691R;z)pM2{4@+gX_VnU97V)b=_&uATZ~Gld^npGn1%CDl za)pn+TD*|cJ*XnN-@Rkh2`9OKm+poH`%Mq(n|XQ_$NxGy&h=aLIK?kwRn(`o#|dSj zBy+=^mU4WunfBIev_MC{&%VfG{wMEPwLaRzn#EJ<3OGK`?k*=!TR?*{FF-YwR8MLhFaM;;f$?@_qkPPtd}iqdioR+KCe z8D{qa#J_pvJQkB#_oHJOK4m%RPqp;e_uM(Bgq=M|Wka8)NSHbsOt`vNa}0`*y?DMI z!X|i>$N8u_i;YCkTtmy_-Q5@s0YHWkLdg^ozoZtj1Z-M7r7bDK~fb?^_Y-b zaqQKDPK?)z&lRjrupK9XC%M@pW(C{hWm?yM%jE)y%|eIRFkjT>qtxcD)0)%N=8FE{#6R~}^r6g<&M?WPb zcr|A8mRR~L`f8k+oZ0N1>n@WWF0~vk1rWFnhs%Y!%jbw-^}0)*x-3ydVTS-B7>=Ie zd=H#NYENZM(jPhW!|fZlhpWq)T&qv-m8fjKE+Gw6%^iN%A`+~xe7v75ubmwBpriX~ zj9xyS)NWjF^d;U~2EP^^OGkDuEqaT;zw(v_CI7xATsI1O`xC1??t1*Q)K20B;dqtC z+|Q1e-xYP_pr1QW0=3^NQFaN(o0ZcN?`K=qaT#?pcm=4XbE;tNIx;b(-a+a|Uxd6$ zx;_EMWf0bb0GRK63I?qoA#Ly7DWj_Nqe3tW2-4yvnJ$2E#m~T>?1BnbPf6U$Pd}(Q zXnSY`N*uk;`iB~rsFw$(2sGyNM?&?^`xC3;#DP>C ze{3fvrG7S4;-&{wT7LcLtn`6aWht%`frR;Lg-mtiA41T}SMY2ygN2+%R?+EsuV! zMjrppCjS{FFcuSlhGdl?w;uHQSZnS2-zR%;b2IV~hR?!2`W8*I$w1rV#d>6`Z_d|r zzcXhxVcJnYBh;|CFNdn8jy$hr=Pgl0;fL8<7E zZ+iyTykZqGc!NTEt1%k&Ru~7~tNIxOM#RXpMHtJuKB@rlC-zl)g0?H;N97;gp zj%u3~FuV?1O*JMlUn*LZnTrHut+6a(E@Dy zy@5$y1)PJPbz+CLX7Varyyu%0`86~}_G@Jao|ZS!EL@7&S8aB!nqrbCNV(4Wlw_~i zXQ`RdIbDA-=8GQa%Dp!#L!#RoGFZLY;v)Pl%io6p#P1S4%3zvIZ`>xRq)EA#{F>78 z4;=6)^wk(Y{m%XWVQ14B<*nO!!M=x#G&r2bNM#<1mP23cZN8Pn{30W1H3*UgDDN5#12FLH*qjPC9to`3ezhBe? z^K^6o-gMM$B=S@5yo=nEf$sf|o51ZB^D*7GJ86Qms`f;E|BLx}u{M}*_xc5T=PxPk zPoN7uD6h#V;DlwXGz*7E6n&B++)QujY@ofpnEH;C*V4ub>9*OkfzSS@wzU1&S|5AkzC8XIYV(1q;%klm z)dbC;x=TMp0xvAhmNmbc}ZWt>TGgY^^jOcqte@xeZx+MYXxK|QIHVOkq zE_;6<4Z-Ae=)Ry*McSDc^R~^uF*W)V-Qw2%Jp!BFpkXs%$|eb@2~$@YVHd>p(W7nK z92NP>*Y}`!BUx8jthu;c#EQ=V@&Kc`)n&}Sb^qhT>+EJvey_E+DG|MW`@lAQTruSq zS*bE~{W=?~5$>6{)|L84P;#TGEUY%^wml!A{R7Wi{Cr`xoFs0-r7h|P{=5chMGF5V zsflWQNp1V6FGez17pO5aomKRr{78gHh}TK8bhz{AAa-$Rdg&>!t6LI5#w;VLt{N-h)-HhJh*+X zzcfWJ2oS*J-7R>|7W+8jHe&Erp#X@GP1}%?knUdWzl_5x!sew;U>Iv4Sd}_|3tw{oX+4}7GM{{8@$X_e*Ix*K$xE~$*etSk{wF*P8?dR<9YnirLnqwRe~?_u zMnu?i_i!a5RS9-Gl}u~@qe$}5J>fWi#EDb8ITM-lNz;p861wCCPc|5x4K|l_AV0(& z0>Q+HxYVTF=^#Z|P`d8l@EH7}u180vd#{bJbftuF2wL5<$Yd~i|q4@H(ZSckojmq1~^^-|qT zL!ijE1jB)9rim&fBSvE0fI?;01a?|R1@AIxlh5$kBhizzc#})CW|T<)X%BGrn+7CMK%M?%&jtqXm@H1GoEPbT z#XRn^xL$u!c1)GQ(J<%@kOx3bC%hxuS5~ZAxr6lCNu2gg=pW+Y-n&p`N^EjSw?E+L z7im++Z@n&E>nfAvM4|op3B;ng6`ajQOKQVTkhoiFyJeu!H;>x?J~KACy>EBnEK z8cF6SqNtc#r&>@-ku*=`J2btDDhkjtqmOj971OVBykF86>-_xBj}ihuqxj?X#dMe# z2U^I^6~9#`;NR@DcIW#<#f{&&L|qE+Xu2bwyzh9wF0~L^|3t{tBxmzKbQ|xttZjE{ zlEMDxYSaubHo`ybWACqf?kh+YD#_-R;z*TVeV9BGaduamU*Vb$+mwH{B8= znEO)S7*(%@Wd1LYw4BHJRQdQ~9%}sw9C7Oe@|ob#UJOr9dz%XCreMd+>%Ymnfe%D@6rfHj z;~1w-jew$m2z*&2DyQBMbsQ|@b*UunFn9V)gM@^dl&1Ug=cjHunIzL|`a@B4JK8x9 zJ4hp5K*Mv)=6??e1YMD;w3m87v|&r&W*5R)Sj1io4OLdqlzd>|@ryDEPhF-va zHaU)&E08`{n;|?m!S2+5HhHD>5qY%Z%MZ?B4so$g%65Ic755k3pH>u||o>`?S>>S{ij@A(qX zj|2nxhDUdQ6qzFCABWs$Kf2GJLp;+Ih;zp30sFf8KUA!3vVVX~$6RtPcKRuQ8MAcJ zbXVk|r5w0xQ1;<*D1wXDVC^Pb|5px@`&4)G8qf<=ck1={uT+9CjpitgykH)gdqL$* z8tLL2t^w^G%|2-`8xICyap$A@m7;1I$$43$<87~iJ}%yuafnr9V=qcwcq%)M(x<*eK^ZjX1lA-j~+*G^> z?o+5#C-TBPNqly6_^ljRE_*Iv?x+ENBU}KI^tuy@)?LdRzHc#Z}ZFvltsMqn(=p5|-dbLAFbg!O%@obj? z8+FYizA`KsYOZOIFBTdx+D7BN*!}xzX+I=eL~xSqMJFdvK2OLQi(m^%GO@c-8*;rK zasT{eD|siJu((>Cu&wur19uY#VW^GQ@~6QF2tj^D54OJ}{mo(#J3zi}`tnhz8YA@O zcanqm-ji3Hvh$?7_q0I5=zYQRnf#Rj@6NV)N%B9Dd_viy3hC2PaGu4-B&@)|W#d?l zo+fLDEKgH2iiiw3wR&cU<;nMI6Dcv@!r#>4b6vMrAg~^TM_cD%GvN`#~x(MCt=Dnc!G{8B+&j%2R4{Kpi&) zF4o7f_#(kw+`enzct`wAV(w`4dD+2B;hPVXm9@A$`V=m;6T@-&Alx&3_!Vb$G{$?j z{{8{ZvCruzGv6;-i|*?o<+86IEziPclf>Q`(v%!suxdPjO|-stm3%kdyo?b9Az-tj z#J9%2&DO8HUUV*7T{v4uN8Z+bVwv9do}li)*_0H*>?I)U7x4S75vq@0$lUj{eg79@ zRt>iy-_HYkPxTLPEO`rQRG~82XE1|bwy^Q+_x`z@@8|NPBj<`ZJ4u%44++e{q{Q*a z->#`2u@^o{Nc0o(wR~0+~RGG+N2MOSC^W$?jQte`)~cn`lNr zc~RD0xf_)tulHcl#NPDj*OtHs*w*UKUF=EseNbYuNw>0M_pIJaF_oBJi70`D*x`uM zl31Pfefm$YDFvp@@6kmG(0$@%eXPU8{zUMfQulSuGfYz|t9 z6~ACR$o5rSz6lut;&NktV*NDk7_772-`d$Ya*W9 zE8PcLLLT=CeP=U|Y#V+jIh{1krCsfHL&{&#J~8CEetsy_G3mM6+&vCuHLoRkZqUxN zbAJ!Dh<9J;%Aesi{WBht+d9x3Lg!=7wYn?kNxy%*y{m*Ruu{WR^@8g)aI?dMd(D?6 z8a2;+crR-G_YRC@m%-nT8Uab}J%rmApvE{t_PmeTMeKpOH{#}lg)!ib6B+-@kM%-( zJAd?pcmHGsO7$Fd_n^vUWLAC;tAk>&25sMB-B`f>zw+b2&~UJ_9>>8ALn6(&oUh7e z1Qu&)UZO?OmSM%p&tGjhMYu_K6LlZsx#gW~^S?Dz?Pmi$o#H!fOVa*7gmZue1YBj; zo!%5QJ5o)Ze=dx4BAj{}D(^rwbvMrCyk#+!@!^-d56WhsSj_eXFL|rfzl(=lM*82y zOU_1E2+;ZfPwM)CU%;4&SAD=szcpl-SAFBmv;I7Z5rR7qT*kBsO|Hwy$~}TEFN?tOq z^Y@z@Uv(&-dNIE?yGz-%V*c=MY}S8%MI#gRn&Q%@R*$3BXXKszuPF1mF9b*f&|&6^ zepZ{1zjmO$^!n}$A}`5G_8$7!UW$)#pVL~p+=?07cda-$^aQh8p6ESa-3TTdP#YnU zWZtA8qjmMX5fr*QI(Dcv7?jG}oIBssUhR?e;7isgZ&rOL5bY zpOYw{Ry@3iGOeN9>J^A|PEXY0OLL0pw~L~#X$@H{wzlcV67 z59d=innFF?E}JsHs~RgnK4&kEa*ve~AhBH2FMFj_Qe=czLn#{R2j+}*{wDA;WUd*u z_vVR&i^^cd! zh1cb3?tad~f)d1g=k1o9o-S|<XF~g(ZO&(63>>9 zG#O@u=k~xXRg%STM<2UP;)o*esL5M}RVXdSc;i+2)xMvzGpeT^!@FzRN-Yk~6(2v| z6!T>-JQ?ec#7W4FzM%b)%}!mIpw$-BeEC-Y>}XfEDjyC8zf6fr!aZVS0JdLgThAf_{s?FKuYwgMwCh1=mEkMWa3q$#6{}KmpXqTME#eZV7+Ck+#WYMh{}}! zmwbo)?4|D%(g__89?+i+?o}>{BU0yeWJF3e7osy?Va_+^boO3MV!OzLnnFcy`ssGQ zH4210mK)=#5Puro{hh3e!-4xYTdF!9)$x#UCKE#2ZEiAW0~W4Op+3)Cd`ugK0^bxj z^$YSE!{ItLaRkt<&T)7~WMD>QtcJKVWX= z+ecQfx{m>mIHu79otTZke|kyqVa*K8=E_^`7nw&s;LMnb5|e6kH3+i6o_BAb#31(= z@~+u)kUVrZ2zrk%s^4c2pKo)SV$@tego9Hh9cMjtrXHuuDmc+m*1z@jAYRx zhtGfS{3Heq>D(6JJ}cVt4VTv3X~`11 zU?CwEXG#As<}!=^Qg-Kq*KEyZcZ9%jdU`pdZtgWbQH2TV%2oKqBi)Q5gIk7r*U%l3 z_Nz|S884mW`9J<3>N-|KoATeh@!fV@-PcrTI^+T9+FS}wi<^SpZc7ekVym|T51 z^GlJPpe-#<@>^TM)E~e?){)rY{qy!^X6Z9 zZ`naprMpk~Qa_Sr;+!d^KCo{sNW8ei1k&j#&k5L?S?;JBXqF>WH7$jL~2X%e!U_mlx%#+OXuqQ z9S|nMMlYq!zL{9r54OA*XH04E40@<;eW-2^f;fkywalzIPojrT4vGh`((zWUPW9JGJc}%)eyFdeVpzd)h3vNT#W(pOv{T!#f`6Qy?iK z$x3oR#Yy{>z7A#I*0><@3LvnCkBosbIveA~D1+N%!*{F~KRUCtStUuwp0>I6UM`4P z_Hq2#ya=hx(W`+{@v4TL;%;&6;ZO0MaizJn+ikkjEpj^E z!7fvObmTAav??i;*gXCnH)z1*TOIv<`IjD?Yh4;R>0p-GB`%yF-78D~RYxxNVe-~; zIx&}7OyTjF{_yp3+{V&Ld58kfSFlc8EWrOPHY-}_ba3x!r|gEzu%A(dpYid8l>R5Z z^_|;R4na^1&sk&=@X#Biy8g&h8~eLA2=}|d0NLfiKXpBgj?(|V!0mUFW*yr1N0?Q? zZzKN@0a9*7UMOl$Q|kWATgKcUxvC@IAUDpC&x_%sX5l{QMCC&jwZHnDe+=Jo5fk7# zO-3*5O7pum#N|9}$~a%zRe&zKnETK}{I6K{@R)AKuTeDLkZpAIo-vJjG<@n(DZ7Sv za=8c<4QqJn_eWHRhEMvS2&IZI<@|N{MD~6iDP>v(|4cYFZwGNnFzNV*H;*InpnVPX zf`pR-ngdWd_JXKf{d~ul`1FX6*P4U-61Ng8=%~xHTcfbz#n?!r=C~#&{EG`Knh)rm z<+7-Lg}SS9o324E)JMV?akz^xZpf#>Wb;TOUnM?yEdfW$mZj10V`N&(%@fUkDK6no zX+6lOp1`GvHT|i4A7ek%K||?TK6WV8>v-`PR2?hiuoL=qdND$2cJ!L}ve{uf`Eq9^P!;l7vhkHGc%v5?c0!*NKg|@L@7m5Pedv_%EGt0J}!By)cDYcIbaQQ0G^A#uW)BV8@G}mFlaur z6(YR!VcfLx<1kOSiQ%LjvFpp1Y@D&9A6kqO`^Z1j6{zEjp7GXZHo#QP`vHj=`G388 z;#J1(guXf0$Y%b)uevDpn481=AyI=;WO1!z-{^5gQEJYeD&AtY0Bt$b96Pi+SA0F* zBtE}8j1W^{gfn?BT`(Qcnv!RH4q5ypTLb+4?z>#76mLYq9dn|G@irgDcsWQ$AS|FI|J!-hDc{c1}CYb64+YK8I4yW&Bo-8B=ul?&)km09z zh)EdP0@D6JG+hN$luZ{_Qb4*yx|eS0?(XjHj-`=i0qIVqyOHkhE-3-&?uLIq6}cHTR;?=uQ~;YMC=bdL&edr^@y)9bSkbE;o=6Z~^2kGj8a7uE!4=w2aFRxMFh z?%kbWn^QY3!nb>o6CkPn4=_K z!=RzraC7-)Q+Wv{=*^}0)f!5$FwEi|I!{8H*5`RS4AdtlL1QS|`EX+LLuu8E=p(6f zeH(0?wy4AI&IhDrgiljJzyIbA>CD4|WRWHi@UyVFXc_9f^ek>$C+$3ll|EYWFt}*w zh5ct;2yw2Bb~xQ6Z)b;5a<4&s77+OuZb%nL_Q3-JpNYW83`Qo;79hpEN&H{7PIMBt zD1t8-?1!jMG3%);VqK9-MV03;{Qhz;@&y{YHk0BP{DTyH;CH~vnwhG=n-E8x_%_4l zPqTIUD8Dhhh3Kinx6y`$RRleb)pr>!k$A*GaPO{ja?Yk9$h5_e2F+=sp#=V}KEt8& zma1=We2}ZX(Oi@~(Rj=>!RE&v=c>Zh>ZQgc8U_D>3Q*y|nr6%R4pN$GD*~(DsDEw~ ztxt9<_8hZsgSapx;us?Le9Zlnl`I|mwc7(YThAd4%B}cpYtxj>7}b0m z`NfCeXJDK`;AkVL%7E8OfA;?nSuimH`XG!}}NR(SYdA6xnzQp;X$KdUi`n8e^u z(|mcP58HM@PyhYCnMFb$*EOH zF}=oEHO&_)Z*^Pb;>PzPG^fDvn@wE1v~RsM!%Wt|Tlx(BD`vIWlTw6m^6E@&2gBwT z)fu~$Rs=IL{Th_pKc`WC2;u2K6wxl51}m*MkB~_|I*zQ{b4ecC@J-M9v%~ zxP3f+xEQJkeWg}Syf8Iy8wpb}Pc~^80kCEPacm1$P3tnp zrusRrh+QrJeP#6DR>uGOw?tUgyP#WZM=k`CxBV9zv#C;R|M<^dW)Ee|TnJ#8Y7Jfp z*sN4yC=Edt?{>t=CxQFFqSQ;1T6lz*i@QV^)UT1{5#UZvc$b~F`4+Eq$2|fOf`0dR zj3}c*!i}!+zp9!5noR-jfn3uco9%exP*#~Snv3xF5hfIDl70~Nu?Cv|HxITDc!guP zo)K`u9iO3XpX+hZIN{fbz=!D=i0jEMlE!|J8{N|vw5IJ|=lwhAx=#rCp`Q8lU`ggiSu7T{9>3e%{$=Ddz5(bdYsOzC*AA!zg_jI!lgGL zzfH}*nes5*f(>*=8I!hmXkQMvdgeYtxlHrd_F<=L*kOqBSDj7dRH2TY7;LzIE&E=0 zfF$-;jU4ss5LTIMusbz78kuo9DSnq5x8&iQrIyQ4+P!iejFhKTj4_-NRfHw-tbfwg za`_il(YxBEX%7dxc>WC?+PExe3Mxd=TvfJRDn7OD@2k(Z&$}Z_=JbzCVxg!)Ad^MW zh>ImQul|lYi2w`|xNw;7-C>OKU>6iiGU0qj7g#o?T>?~`eN@ibP>&)#AAq^yCjC9i zj+%TaL5y%N>66b2`R-hrM?vd%Aju7E8$Y*cTGzs3w<@-)x{kcm?-d81r*Mbo z?Zy`;9Y353O3?-DMuJ>pEO7p9#=!^2{x_r9MNH^O*_!LFZxExCU`I-qo)Zw{4tC0< z@X3}JtU2Gh3fjkKaw7^)U%^qw5}ljk6A0Dug~vgA@uyrV zpAq{coN0AJ24q#Qbd>7$9l4fcmG2|?+_Ie&8@#hb40_HDPYqg!(DC1HQ@Hr=TV82e zE~r4q_ou5D>u>wD(}^6|+`1ztjaYo5sQ=Xu6cS)$P19}2+74d^wW<-;)deL`2srng zy^IZChy{Gshb9QL+xzG3nW>jS?h&*Vlpw<)i*GfZ$-x=q>O_*o;$~FAZG9iD%qj| zITo55E@7)I@cF5bHfzp}u{d642K*lGA||45OZqiw`!Nkw3VNpeiL$36G!> zC`U2E6Z_j*iYBH&{Y??<(i-8Dc)>~?>r@3TO_+k);ucI%ky8NYKLCTgbs-phyrN4+ zW?*v1{~M>BNk034j?jp4^sLbJte_dH!CSKsM=uAk5xhJif#KyU%p^1oxgAtCB_CpTR_jrJ zR*~>E9Otw7i#MKDZ1O@rEmK_{zdD!pyc?E$>h$EB+gU39=9rb=A&k=xVj(KE>EQYW z>DT)i4U0<8bK$l~uX)y6$8_~uAArGJHSBPa)6_<_ZH3^A-aHFn=h@&wJ`b9dGQ6^- zXCekiP6CYFbQm6>m;;ClGORs!eKYMy(N%9^fg?-9=%X1|OM6->Pq*LG+GhzbrYU(Y zOOszTwt2^ATd&u%WZkiC1dAG8T`-QJKWGQ%sfd_^9{A{?~Lu5el&WQE#$ibpl=7oyRE$&Gs7gFtkT!)>!b`w4L1vJ<_ zy?+h!c=^qjy(^A@qZ@&bY$Gy-o-|S!?Wutv1J@P=G%K)v^m(Fh`$`~HU42}Dh02?@z7Jfe zQv z+5wwyQm`wCJQ8@41-r_N+^kKIfDxC9AzE??J~`m6#G~w&p3%pC+`)H=PivYNUO1!< zSyHVrIQ_BrBY3lM9wN~idYoX9H$U~c+T`W}+&{O8zR(cn*UHJn4aO9vW!m9cIi+Wcw&xcFjC^>HIDr$X`o>$d883n=gulig0 zr!qlsp&`A`GTB&1#yZZZF}MMz{l!GH09cGD1mGsfYpb{54xPtj_}T;8=}OX zL0ixVMBYKX>oPPBDsb&A$#Hm~F}7zX-4?!mru9zGVG4>Aw3q38dN1Dz{J!^ zLY9Zvk5u9WPpc1s-Y1Izy(HD9&z<_|J75}S3z(?<|8;0c#7M|vhYWweCfJVNNaPz> zL<8_Xb?w^{#@}Sev93UXLE3QwCmX}qM45gETL8qL=#6FHtl}SPOOyjbIn%Ah12f+&wj|z-`Xji*GO@=x;c;yq&_DoJlVh*!oJ8x#Ix*JbQsFKUVlGiZ zm^6&wS$I)MMhIwTnx21NF|I|NMa)`1Q@HG(l%t_**WA*q0}-cBs{n>}WrlSd7Fu=A@ONogFY-#Q!+BFuM1qZH zr{dXawG1PkX?xVdY%g>G0IsOxl%#>gfhEgh&U@zb#S5V3NH{%R=B~N4sGe7-4Z;BR z1zJ9@gq6y!u82)O%-Tct(Vi~xDAsKMm;nWEHr%@$;qtZd7aWsKPucK`pJR*S6v1N# zy6sCBK*iGJf7S?a^f$j9`<>Gj$AQ)QkAaQjU?>oL?J%r_gNi_Dso3w~hOo;P#i=u+ z?#AAhVaRFW8Kqj9@K$JeuWktE|djhT1ERCIdAa57h^KKDU+f((VdmbhFXC&j!WSCr01J; z)7iKTOSVifb4O6=>qT3u11bq_+Zu}sC=u=2-4ud(Xa3vqMx$31$>^jIbONnP8N8v$ zipT1}w;uWLS7Bqq`vIt{;3EXM%Kxy;zix7@>6MYVrk)Pi7>x@j z!L(aH4GJ-e3|Cd9VQ}f_`VY|rWM!(fLLUr3GuZ;FmXH2p744daQ@7c6yj)V>vg$wD zDxPUszT9Gz^ya-q_4l;xAtjM~XJ1g$CT|0!yfzk#aSlr_jwQVRY@+)7w$J1%DsuTl zo!am@6>A0dhaV=3Most3Gf5fNGpI#Oh4XV0wb|yt`Y>OE=^e6ll;sC9c^=tBHUGqNZOsv$6X>j{P`AbFR$>~GdOGWLb(3|O; zgK8vsRX&_K!!VE-!@Kt5s7@TzC@c>NYbGYTi&2MeaBmc)R=nKnq-p#;&%VzIZTpMA zA!mEhPYn1Z-7z4nrF;hlpp3`Nmh;~zGkBCz9}d`eh&FVEuLw#*UIucsNIYS zVCZk(>0Sy!D%(ArfmPA)SWJiDlUMeenX53cGF!KB&;Hdhjv^N0JC! zE~JSqstm8l8ie>~(DgsC9WeMz#5lYlkf`W;jH2<@5@SZE`qBMBQoTut5xBYK>Iq#m z5N=AM<9)+lxRd{yEghGa1w0JVgYJZ^jnwVTGs%t2$uNL06R~!900&e08kR-zoC|Pz zo6adVFGa!RbM5vi3B&&d$80~3--n1b%!n5_R=*_IB>dkU_>O3%H8+kCm|djTtR~)D3sCeAHpzui&NwUMo|j8`;s~yU$Mx@ zRPx5})Q9psqRy1Yk145EM~^tWN1TFMxxT@POrT~Zk&=lz?ENLZ@hh~tov8frmv^Hf zhWov7{ClsJ%f>;U42$7C%Tk`p9)EYo@jD`jH4&T8F}nh(PD%vK-J-jU<%L_nM=jqN z`0h`3?W!Z4U>cE%j-G2Ou?{*@c`vPAA)Y0$%^RCs~lF^ucy|`9d#9^@iXgSpfJZKqe(7C<24s!&PGoZY!Z1+@ z4u>Gi10Xp@t(&SAy%moM#?N6}Hx%3?|2nqzW&i9hBCsW?qC=9Wt@mWp8s=DwtE{%Du_IY|Kv6fL`{PF$aoUaNmAWH88))W{z)-yAoe|c7*8QboJ>eKfp`U$c!e@vQxZp!JGaa+({aS_;EF9kaLcmfvke} zbE8g|&TZ|9>JB@l!Gy@#Z(N@h#}k4F4u1auG9AY8J$Vcz%QNgx+`-7P4`A6O(@~TH z0}^8<48vk6dQ*iZ#31+cTN*PwzlF=l3+x7uIBw3JH7cRSZ+#JU}^u@+A%P1D2@xZ=R zQnUtL>$!5Z*;uW!+gttSqaaQ;0gc^fXzWv1jGtuR%JQ-X?skdEU5Gy}@{sdYEyAqI~$i?(7i zDh^;vaZpNRW2YVU(0d`5=Hk5Hb#TkPUTaFIL1 zFKEN#9OmO6$D4gW_u*=Jfd8j#kbpIBSA+3kE8KgDr5g3-oOhB3Gt7%z8DFn{npb(q z3N7*~$q0MFJl1{uNpJjarbgYg)x)^fp=sO0F$b;)J0Y$JGO=^sxZjJ|Adtz(hMN7LeM*+I{}ch0syV|O-A-@f=nz*s&nMK2!FiD;)z9yqcN?5!eLofX8;QgjAQqdkm2m4fHg33A?}i`#&! z?+ZyKyRH;5V2QMgyZ@ipGXH~GEkYZ={;7OAQOi?3_g3V=0HVdbR#RIJxRqCgxhD@Eo?I`=A@y^RLETO_u(ASZb+1a3K20zUX~7_nQ_;>p6d)`ODE z93vbt9`b&`uEzSnr(83k`}XLjS+s2%)Yn#S?q3yJvW^K>@ITCncJhC3`-c^yj?QeV z2xckXIngHg>hk&iO2uY&Ana(2)-Q=x{}sQ_eR(eRU8`Tk^2_ac#Qj~L4-f1fjlR+gx;__->|C6&0P87^{=Pn0c{^sG=6b`{2&L(W3vm zbLsDHfML6UT19J$gt2V`AqA;@7SxZ|x_7`azQ7@bfoEw;-d+Py}fEZqC~CQ-q)B>wio zCr8$XcR5Djobz8ycy`jyMiq7`5gZ6?>6(VF6{6~Ch7~p3waX_m84hI87!AVM5g#DR znMgXRq?xxq6o^QQi4cYF8%BKi3c>U@ErgnIzBwP^54mngze(#E+^Yj=e%+8_O~jQ$ zuOMaTsprzr3N8%zZ#1+5s8ZmqnU6Z+>JHY={&Y)fW z3Ap^Z*#~j8J;Y91IJxr2$ik$l_1*=W%l+qO+rMOe;fBf|Z4cavt<}9x__T~b0^lXE z*$R|1w@$v@LP1%cKPq_!xm3}Y6y1W1+9Z1A@P4y(gmvD`u?JkH z0VU%ohRQzC3>E7ZOqRL9oFCMi_99q3Y^YoOw4Y4`8`I1+SqB4A3{D6TFC;`GvoT

0(}sV_KEcQ(1c^H>O4!Z%0e-K{9~8ShTs}J#t>}vGYN0x#c~Y zzpaw@LH64BTHI|9U40;MJM}7R&NyD72`BCQb9Cadx_Z&Pdii%;H0Q-+1usvX?g7>$$F%9kk1;-j=JZHZ&cyYtH#xmOS#*TR5tI>&wxCNCYVQ^h%I0 z_i&_Zv{ZQXUTfg2N}tE^(_>ZlGH*$jYJc3q{tnFS9S4|>qxpID##Mi~bRee()sGKC zaYAdr>E5D?ne@^f!S~W(Wv+9{f=d;k(V!uP74hc77C)pFym=B)@AV0InT#Gl%V#yi zFVsu1r6=6=wSVR&($oo4u|*3amCmjGvr(K;K|!DO0!V}P`r2s-QnbXRM*&ydVrl@?drY7n5jWil!!?%;Mh)jvP0y z?wrIejf6XNU9_7r?tJ-jf-lPkpRn+=7`ZK6dU70c(DHlOkXvL3+^7iD@LB)NkM+=> z7zT^VZ%7$z>jGN7&pP^^f1wS(j1U(r<{nSZA;hO*J=~sBsk=Zd8|LfanU$hQqXIX& zMQeRj0u+6>sJnoMvAg>}$me95Q8{I=Ou}eupj|eK6imq;*O*7boa^Gj!=RvQh5|f5 zk7-un=_^7QOxDz~2+c4>Cmsd3cS$cl{4}}yj{*iZ3bb4RANY)-{|ZRwUv`9M1ZAJc zy!P!YxRaOiGDhEJfd!d_2!L{21I?IGF7G72uY z;Q*85FuT!`g}Xpi#Ss4i-I?FLDa+?_HA3rr^Tu^h=frjpvc9DOE+$0ZFhqJF{N})x z%oF}o61rrlSNc~QywyLp{{RZ+PNNF|J5_CXs{2(&;#lO9M2wZEybHBqq0a4}5nne~ z?$jp%3NleFe*_Pn>RP!1$r(|l6fwvy4)P3g0O63X=3}LAuzWkK)}MWJkwe(Wo0F@4 zQ*h_pd|xC8!e0L2G1z%^K-;~1)!D1+g|R*6bv~ZQ=%CxX01l9mzL^Hv%qQxCOI+6L zRK$6MaFSMAR*IB-R(gSoxpIoLND*BAkHz1>q8-aM>73;Ba`ha!IgvT-ecu=y z7Q4ZrQG*X+lBmPX)_-863q+!K$B&;|j;-I6sMa-#amDvV=k#Eny(V4~X0rtq2q+5p zATTh8_B9HwxiW@rJ?TNN_*>TT+qs{YPGjO;B?A_Al%Hglxr_Y7URKf+FHf$QyVz}2 zXZU5YAj=h?e(MWQ?vk&+5&!^#ZZ`2{U$CaLqUL z2H7}namO15ASQq_l51)#8{Mz+w2bZVXn>WTxUB%aALb2Rq$HEaUT(NgZcDajB)K=D z7-*|*xICnY7Ipu5c#0i}zAg07q5P8Pj8q$ZQE7T^NQwRsDIZ7yp42J-K|!Hk2eE>M z^zQ#_{YE6y>s)VgGDhCJGkBD75Ck}>G*Lw!2)g68MqZa^t^?IRfp^5CM zY-qZp+Il&@lSk#Ti(V*hA3K}bxwCYBs#AUHh4*Dn-=K^udLe>FnZ@I`4axp8AdmOA z*ZCv=F#=hdP+_RK8s~wd^`4G zl{U|6p?h<(d-KG(OM`o}7tbnP)`>FDsx;5)u6r|hmN)BWWxt!i4VvMZq@|evNgp}1 zG8Bx&w{f^}cI~j}$>Gh5*G_<>{g=D|CcmfA$BzC(dXvB+10k^s8gP#O)N*_oRYXcbTgPf<<3UhQ?7)*p7qo|bQb!J zc)(z-$@#B7$X<-T*bRZ>$#-wQC(e23+>l{1mSa0wz)QQ^OIW9l_&^-q6{B^#U z#`V;q2Syd$^BdEQBZf~c;w3(o(UnV=8CnY-I6u^hmoB3Xt{6^p{H>tc4wavJ#}#G}hWX|Nj_^+3(eGLZE0zbUS42!f z<~rV+a|>FevY2=VP4o6^fCpW_2G8F?+fURdQabRdwC@vGh!7b6aj%WvL+Yqa_SqaZ ze3h*D6`Q}dZbFV3@x5cKomzWP11ixGCwaC4aekf2IF^!r$y(>)-b@mA*}tO}X}LtI zM3$v8!*!8Oc);%(I|nL?ipJ7pfYfYJ`pJRX7ocghT#RD&45|Pex2}8Z9uEB&HE598 z`C`i45I6K^c*rHsl$pv?HG$e{*yP3Us7)~Luz8%7<5bm~W-kU19yfm}epPnEe~cEJ zDllB}NYV^@TDuh$<)~0)piP1XhY}eI8TNVoJH1r?kJ-)B!_mxUmR4ENU82TM2fFO^ zF50FR8r0Hi32D>VS+Ry{q6}Ikx8H0@aWoNR%4cE`)e;dt%mlUXT%Jr~lP-p)S;3Ge z8@1JS#!Y5n9d6PspGb$z@dd=_b@2I(I%E_!> zAsllna(W(>6&{nXI{lW^;_6?aGDBWl`SY*%UL*8h)9+OA8t&}+N=k@_pW#iknI0{+ z>cGVS8YdO6a5V##(>`CcyjSh^3S%~xo;4=l|t5%jCM(y7MriF6q?)K6_>C6`DZ z!aF|+PqTS_LK!|%8gxa`XiSw_udc6oM03fQIUGyS@=kLYC9JC)hD z<`!Tp2_PB#wTJM+@Q}%iop-M79tuCPKz1P{( znCq%Yot|3IQQeM)U<@n6jdO1!pSfkkjr}!l_)2eszr6c&7ozHeoH94Iz;v!q6v>Mv zrY}FX0Fr004yJF->;caSru~sAvvL-?E6+L1!a1%Znlys?tMjYm5j2t1>M&Q_Q?Zj@ z1tVe9Yt77VYC0#qvq>YofQfurnuiB*-9yDZZ0jdE!R1mJ?DttmAXOFy*{OpTEy6P^ z4pAhvFSAiJZw1kWMRlRXhfQMG1Gqp0gBHiRmHOn0xZF)6Mv)r$V(wf_#1nUU64q%Y6&Oo$ z>Ze2F9t~(D8b9{W2Z{Ns z5Nf2c);Nwr^oHbH!dK%aQ7FpH=vCEmnCT@9n-%QaZ=@^)q-3^mhf@@y?~L;=jAl)C zPJ>GIYnP+Iw=c<6r}5WfNIlQJF5N7NKEiU!xnlY}L*9A9jSwld|WsbGS z#SH6ny$=K7!RxL$t)DZHEqTcbk>O13#I9-);V%D-i}vP(zzZ1N*3zdZ753lNU7U=K z_GVZxfH9)Y{Y$ES+mVh5+fYl>yg7Z3s>(gW&TEp6S*?!QrB2A)CpVxbeUH^gbo>d^ zv~A{ulo)sVS}-L-X}?M4LHp!e`3ml#x~ZkTSHp-2!+B=#^HK1KFYeH{Q1lvM_VKJ1 zGsa>>3#7OL-S<4(7G?cu(7R@mpeEZd#-*aR#N_mPjAK(8-`FDFHd3ZSud{TJ##TJt zdGe&-CgWvr6=O#BX%25Y_IuMaoCQT$Dx+uy@)$JMzM{)BaQ6&$evRtP<|+RKOy}+> z+&3^F+r97kI*%aJ`FeId_*`~6Qi$GW8Th58UArR|%0fX~d($mwGdU#Ttal&=b~X z&|7ZQ`-qUPezo2(Zx+_{-S6F(dZDju{-*{9+Gi=>Duce%YaY}-o)TOM$p=E?~WH_a~(lEGR zy&i#vrfzw`2`BR-3}BxfKJSHJ&O6!8n7)9xK;MUsz=Q>e&Me#d{A` z8%Ld@Mx2odZl$FroRA1GK5p-G!bamoWdx$3!Q#uWT=*n9?->{acy}fI5JDC1-^oJM zc%&a84PaNQUEFB~*#EXKpl|{BtWf|%Xn)E>>9^j1dM6-G!yvua3h;u8Czg+nUow9V z7VHrGEO)~@UX=A!_jbEs^yPaf{}fwx1pK~^tuw)Au<;9b>n4EV#qejk!-kLf!mx;o zDG>=A1BJ2F)nJFGXterLHl}$gUZK^PP;>{-Tm)(*J0?c*3vG)wS(+ndZS$`x17)0% zCK+NeS5>9fY#GwyUi5%Pm1L0Mx^ZjJfSnrI`+25QJ>a>e<3K5_k_P9-e_k~+H zpPrx+E>B)~DJU)IcT^3W7Gi$I8zrDWL`gkj z0os&d|9Kd z8l`~aC$dDcH6{ID(Zx=23`K#cvO;+I*FhMrH1MqyOTM>@f&R~2*eRck|s zw}NkLdZ@8i!(||!`+;`UZp&o}zom-G(6*ayNwB zjK&9lug06p9F_mL#8IoQ{JFi<@~)!5uq7?z)ao<%$znyp#=j>&|IYk-@~fhW-SCy= z!QS5J$@)qi-&vMmk1*#|Z};kV)`V)9@)!L2HQ-f27KpjUu*t^HeM$c^1vWwUcd)${ zq4$i|9Yqad;dR>XAl`0z+PUm;7khm-d#o)-`2r8VOFIa#HPeEx{q4`A(tVBE=JmyJ zvgm8I5wPoQmC@VJ;7$*GHM+C=)Xp7p8nW>S*>fAP@rd37>^WOy@?MhnOq%<(W9!Yg zc4zbY>i+}R75ayWl;0veT9M@3*HyI`>jumql9Kl=hG!o|xXSk<| zx*Mq0KCDb=6hpvq&=`KJVrXEHsHnEJ@ersDRwufS3R?<_J&hUVm#-czbrWXe_M;Q; zuxziwf6F(8d8TexYkWfK>h5&T?O*~JOj~UfN5b9iMcyT7ag0vTaB(3p*;?`P__A4~KD|GggJQ+CHcWBWT~t5$tL#n(ugTVGg`&s&b+}x+vkCb=^*DoQYZetS8k%$&*H7XELFK0xW@XV+jRxK=v)=4KD`1{=s3H{DL^?LA;_k>eJOw_`) zaKJcVVt}-+Y=-9!Q4R?i9}L?iPK`az@TzRa84iU+PGyu*BTUMNL*7^z@-6AKR5QwI z@#}wk5Ok27@wEK*(om558Qln@c6PgMUz zU$fAVzw%OvAXTFLksA*yr+-lmW3nTiSMdqr@*#^<>skbb zF)PbM%&Oq|*_c;D6$Cz1s+{ ziR7RKv(k#z+N-LpysE4hH%BVHx{Q^4--`C|#y}HN=^ZZf4BtolK|ym(5PLg3!<@d^ zc>WHExpu}*rD8CZk{3DOOY@wMgfsWHa%|<>LpLVkR`?C9dL4E}7-#l}?A1n+v^Xy2 z3Jadb9K}YG9dAhm9CeYIEB0H`%C(!0U(;JLzWv?xyU2-&iR7>C5G|4DaR~$sKN1S~Q-un>!!4!v}qGM1F&y z;xf=MNY~I3>|ElX{L-WZ^=)C#3zS>hH}%=jYtEaCzGX;pgE>9hnLqN<+C9*kWSOJ} z4wMd(FuLx}a3qY|tF#-{1n$_d@7VY;nlD;mEQZS`?{NXN+2~$i_?@wQ&D!;XP_jP1 zjMp-JDsyOU4@yo7NTMKk!1B!=A^EiB~*QjEHoe-R2lJ++c`}=u-#FfhUK^AaR&zFU?S@@eT<{+e& zdBBswbdD<%vEe5b3J8Iei7ernO6=mQU?wpj4R#-`z%6xB|5=YfF~CMQE-69cG3tYW z_hkIZdVJ;$>Rzr4A=M{xlE4{7L?>_ijU-0-K@bJ)X8H#zf9mCzEq() z;{5v@cCTv(v&vl%VU!}8u>m5DdoEaA_uyW$Hbmw}Tgbx?-H|Up#=T$7^{KU3Czxta zv|#WZx@pe~BslJ4z)x8@Q?63(lD5vt$v9O|oVrn6G$*@3MJn+rT76J>%tfwG=9_&v z5}{ndtCuT5y>clG0DI`mie-xsvp{;>Mx&}Vn)(l6~SVODn%96#;b5fEOLyjC@F zT_V|fiM~trGO11{)Yp44gbx!$drFnItJlB2p zNKF)#zX6G3H+EHOY4pm&?l#nXS3um}Xw!PF0%xulp&KbJZbs@KH#bkEH z4RXCdCzZ#Qw9Uyn%GRgsWerS)%>$J@6POst#Cl-ti{46skZ>Ac&D$-dEYQt!Zs11uDTb{?*oiNocKpEj8ycAdJ&jdVCnZwuriP&{vG&JtCr1+J3u!T||zhav9A|^N3 z=roYRX{mIJZYAU1O>D@t1I{T+yOu%g3~(;QOC_{fz%$J|N`5!C_$4qXl4Z4b1Y`ZN1RB ztVg*XU4Zswk{lpIED!LT7@h$w?3Z_y`RD#!*5&p3SJS@*WAs8(g+9J0p$$=`z=*;@ z3F<}s(^%S*VA!i^X?CI4f>DN?m<_~Cwn^#MH6A_jp8;WraHSL7bWqhCqBfNAwGNl> z6Bg41l*79INOW&X&uEl<#c8yAvrFdKAXS)@gLJR;h~Y-{AD`12?dk&Xt$eMfd`~=P zGNS8$rwyt$0GWJ@FjUiHB!7rO7svk=MVl9VrT2dJbGZmekT?OaCdHW~L}a1m$0f)Y z1DMVTrKM5U=Q#}gEY$KNT4rXkL2fO#h$PT98qU_f)|JgzV#{tC-Yt`wsRZpuL_P?| z^s#Ggw){+FBN_g$=MYtGIv*zKA3X}8I0t?Tlh%l6X-qCLOVvkr8a7#9l52=Yl) zz%K7k`h&@^g#(gptqU+OpXq6+r|`Cx+cd(yOdv&w;p+Wq#oD?mb&R)nO9Er_b#n?7 z)TdOM&xP%Jlry0US>U@LSzH$#^LFO^wMuex zEec&$w7|st?oa-Qm78hs!{dtEq4RRvglz*~!}HYc&t&k!((X^~?Bx?5yKY-81i#^f z)CrX4OrOMZpUH>P2iuR!+Pnl_rQ%E4yjfnQp~vL}?G2ubYX|3x+PuTyhZSwQ|G1ak z)4$Q^)qsC_TZi0h>11Krq2ANViS8BTX*O>5a9Nic%`eVp1FV+AslMr!phhEpz~CVP zZADLni+{>=U%x7J=x1I|+0PTNo(bJ->t`>rxejPoVhy%(fJ0`l7qYU<~!`c<$w&h!Kg z@=}-HM{?DU8M%g-+Ym6d zpdJ~OiP?KNL;(RiicT~;RQbW<_AdG}ojD=nQpuQm+07)GC#4a#XEH2dG-_e%4+xMI zM?-cEUet5pZNnt9HD)-QTWPJiRPm-@WAj7m+FvUX3~ONLpNWXrBt42#d1+ zlNtka`&^@mw;W(znMz?-GlnO{`eTN*mt%~Byi+lSV3CaH_Q86S;?2dQVMyWQlm|}z zIaZ1v>KKkn(W^OMiMUwWW8!+pxMfN5d5$glX>1Nnx9oz<7%kya1HSIIjTot?WsU|j6_k7 zNc4c{yo&YfD86{{7;uWy`fH&IjC&$D@SsSx;hRGhrG#+$$?#2^)RXQwD^kbqBXgB7 zJdd;RvJO*=wvfN}I`syIZm1JHiUK&{ zeN96f1ojx8q?E(Jv@ABUncUy%ZtjQwWCg;2cY=HY--Mz9HR_>ta6H@Cw0#n-t;CxB z4b6ZRZ}n#Gy38=g=y8p2?S1E?8&CnmDW8c?svi-_%c$|ks6UwEHlGI?`Jb!Vv>Wz8A!G_;UJ z!g6hLjeo0Ap~u>yx@jIr^4BWhfO0Bl(gSa3Bk%KDT#dF~BmSvXT@5CYl^&FCccLIg z6bN;f;CsUlh8#j1ABpjhgB&n|Ix%(sDbDmgYlb}1$ug)OD1(dxNY)Hqw4&yUyz0zQlwpgi!F~of|w17PvYnXGfh)oSyo=5^(z8^i(UX zOx>BpMt|7GOd#vU0DuPfPK5Xnq&6S8Y4sw-TR)NOMVhyM!eR&+h%h`i;@Rv2fUjG9 zRqjkYdVfYoYbx2?czGA)4Zk>OBi|fTAEhq}D_ZoogWOqfV&ZD;$vyy$k()}t{tc{( zbf5Po4*ZX;tB#85efo;>r8}j&JETFnyIZ=uTe`cEZfT^I?nb&3COn5o@JtG}aTCnS9NDqd1J%KoKcO@Wdjj=hwimMn~Uy#Eu z-rWDRk(~W~RZMR;rQVdb@d0yU`1h+3+6EakTuq@= z^)wa_@~kQOw9(Q)nX+w8LfKM-UB5w%zVP3?HCEezhYU0#Bt0PJ2U4f?GC8z4rXeK^p}1J*&SqX-$*b0kYD;y zpex>1Q{=Z)*tvW$=UL*V-g_f?fkqihk zoQfrj*blh|urCm%ozfIk5CVXR|A#&sIh#3WGW#`n3E6#WRR`WjL+V2s{ZNy{gw(it zxz)t|u04}s+PIctY)_?m5Pw}kP#K7wio`$ImHid;)9v{=-*DS9lzd`VkJ9gRBqWbi zXoGSHoSe{%_D3q=jGzOyHzjtNlUAaftl|_d`i$x6d*XyewBJ=cEiS-MKn8EJV~*vU z+ZeP?n%857{ehjyIg%hMOt7YjPDV&+25TR{dyapfM!}{8%lqPeyZ1<!I1%z z9kG(BM|kKCQ%=mXb-unU@-Gl;=ecoOd5@76O9{zk6prHE>eTqke=%29PRJ#1{KC?m z)@6QwlXU`DmG#{4jy-sIhG*1Y80!N7&D@A<=QeI)-ByDnF^{L@r1RalLsrK6G+}ni z8YjznESi0?%;=kym1w?8qFV&} zGb-j0h%u2k;R>=b(3Up{5In}0BMMVckJA3>B=>5TE8g;xHz4-m^Gn3wHZ?u5C_b1& z`Z3O#CNp>khp`K@IxQdr5)hxu2*j4}*zQq!!|RhkOhJy?VMY}eB_o3%kD%DN9n@&^ z>IEWCaDCcP2Mq$w@8IIQema?6LT?{wyq)k?&;+bjF6gR1nY0yhJJ9GZP22E;&Xq>v z#FIwxIs>g{ocPs=RQXp@OGI|hS2ALaiRJi>B>4EpU;ZHp9y?;;gFl!)CVJ#s4w~<+u^rT8fQJASze-7uv zMd0?En^B}$>zC5&6H%V2h+U`%m`~i}^lMO3r$Kc+K!5&7mkr)N zE1tUhcNie7u7cf74bqld?((~estsa?IBU8ca15vyW>p(pGz zPctm>wZh`@RwU@pBOZ0RHxx$S$@cOY>(Q@mXbtiM`*#na51#)Xpx^z!i;uk9u4lnc z9rJ}0VCu{6sS+QHn$MDiX9k}JbN@pM5+CPmB$;_{Hk!l{K{5_4Kth?QW8b47ptF@q zfBwt+_5^n+4qp#{)<5k+-}xq>;e-1MUB5=I*PeWv&J!g(CUou1<|VdQd}=WVreAgh zeno9X80?#J7Zm|j%4GrrjXyD&Rplrx9JZpgZ&6GlTC zArV8F__Z_A%qa~;lN;}$O_7)X7IB!6^Zxv z2BX}QOni`bQ>)0OXH9_SfFs)cTTGEHvdi<{YNVBIzp`)Lu=T?^8$Y7oAb{(2ru830 zym+`cxEWzyr(@8VBeG`^$QIVy5U>n`=7OLR?2nxHpd2^#2v*Dm7ts>equr7W*($~n zVV-5+Brf6dsFPXeTQ~0%m2!~iW{U~#aH@v@x#IPaMso|YUn0HTMY<6EzFIaY>oD6} zi0ZwRG1V+3ml9Wf{!!|UAD!7mJ``3~T}A4*(~;M{D;G*$(P`Q)Xz%XTvan8ipX(^+%Y8Nv~~#v&ETfeV-Llh3k*Kk8Me>9Nc3*{vi+R1M>@r!fbx)`zA4J z`{H8?B4T34`aTzB+hHnG2tSurP=jc~2Eka`-`+$o65N3+O`2>>+Y(}w`kOA^*&xo^ zu7FA+x-tn``5D|*t4+?02B!JC?kjAnmztr2gjs$*zcTzn)*a#nm<^!&3%L2uI$%5e4xeKwD9^Spwf7u0qSQdHh?yKm8$*W(O9nobh9@<(%w_V}gIlzXvfs4$C zT!K78H^4s57AJ;)Z-FlreZR<3Fu)e`=bEeSj}ogMkwoZGe%EKHfn-u#ct!Z)3O4fo z9`OaG<}GNdNdphEcd@E}wll2A<2HUZ1^v1qfsWV%(wyT;MNuVo#w6yekEL;aWgOwW zh<7$jykqXo{>GLFFLI{PjHx#9c^>RJ1}Feyi!q>kO_@H<3n+99mj#%&eiZuRX2`hK z^^G}0G-Ff%cRo!RZyA7&he%1%AB7YYzX35y8m03Vw_lVH-e*iK6TE8Z z%rudrw;uDuDN5_q+meTZj@>R~PA(z2t!nt87rLeo^}fE9+d|0BQtpz!V5f)svXkh} zKXK$*X#83zf9Aen-|yi%VC6bMF#o(n5HNE6D17oL{PYMF2jHp2){vd35Uh}irSTnL zol5B=eU?yzX6*@{R<8nve%P2>_YsC~*gbZeS4WvedicZhUc^cNi9?`ah03b*}; zDzIH2v}HHgCEAX?hn)Q^T!6wGU(UOVWlQ1mhvBsnaH})6jXbSg7RqGb?a7KQDbIVq z1qO8RD8Gauz`SbGiE4NJjPzGh;d3sP3oU-woZ1TgL$Tkuop|3n?|AI@Cy*Vs*@}9M z743p3`pO!-BQ_OM+b@JeS7=(`$2NISjL@b{D(i4G+TK;IH}OAx@X!|ZIMSmQFGF=Z zb?o#iXa=LQww!o)YH%(0adZXjNgZh`H(%BT)o0R*Y!5n9aUe&ZBuIElQ+y}Kkh}YZ zWREOPF^~*TT%#OFfw86eT?qF168q)~`(|JL$0_{*82jW7`y{dABdc;B*dNi;579FS z(Nn)e7#~NH$yxWvSeYhL0Q-PnV`BPg;^LL+#UZXMrUaSm8kI}R(%)QrHNZv_?`rhM!Y+AK4eGU?0w(I2S+YsSrpHK#4JE| znY{A)9jOj+5_<3|J%(#<^Q4$MTq%of(+_LCr+6F}*2*+^?hW*-tC92+`XYgv zvC*7bCr%WRc6)kWdxKH5QX4ly+_mXYLZ?klweI^I*7K%}vyW&<)}q;yTJF3_yV~Q8 z5tsg~zpzx%$R6bJ0>T6?P=+X9L%1MgvZ}5SSpgJa=}nm?1j@lHK|q2YG~LgSdMo=Y zatfKh{MiRQYpBq=b;d2(^GtVRapo;@{2NVujhe59Y;wSB$ah91&Zr@@(dnwZe&Jny zcHZ|(4QI96oB9La+M+l~Rdt|92km@Itme!0o9N?k2`3F-UIs(VRF-rb#K0O2d#?0j zI(1Y_%L*fgKWdWaKvbh&b~QB>2_QUvMrX^+aB<9dg+tN8zA}S;u&WR-TxR^o_XJ)2 zR|y!q{5s{Ih%xFBEe5P!mbt@Rg^y55Hs5r|Lq%O^guRh%0Da z&674#kY4U5>hq2A1&UP}G~tOaPSy8{LGxs+w|hu?e#l)f_vGtO1SIXynebBTF|bO= z%k~L&-?nqWz1&?t32O6R{^WY;cRq;&92frFv+~ zvz8g4otuU@NPSlhm5v3Pqw&wXbDIjK3q>y83K;bikJMVHfXLC(KyckK0S?jK8gB-4 z7xhA$D6A`9^Cx=98|3ZtjC$zPZEH8xM&L(buH28hiF9~HXT6>SHZQ6w=@ZY)Yki43 z)!+zkU+&TZx~v`1Rn#Wz+f@Ix$GFj;R5@PeBpc}L4RcR1gv1?-MEyv_53-B{4937V zwQ>($CG`flgaUClv?Y9hnmfdoa*PURi`jc<@BRlPUoPtOTJ#fW?jHi!Gb(dn^cIIV z*$IC}*}~6d0>N$R0Jh^_$6dzo)YVusAZ02t8g`u497y7adrKO%+0ltOXnQUTWh+{Z zi?j*Lad9FCxXge4q#|m(#!3rsaS&UM9$Ccd=v#6~cOVbieR)Z!m&rXPw#jtr9PvMA&@;=A5;c6V??;IPbJu^8EQhQ7D^YkUW|;Yr)A_X#mrXf8X5a=bY2c zdY=rYo66&48(Z9O4i;#mTI}B`t6L}-$r}jcAM@wYMwDB5e%4%)|IlC^wdH(T81&IH zw}_h^$>Zmpv0QCXbA&DFM8%_(!be_dPn0i9+ctT>@@jfu7)-95)6xCn~cT9 zC1s4i>V&?^T3nMQH0IxE2$tw^URaZjyZ|nff+us{?MS{?RQZykqw!62(|Tijjba)w zm`2N% zA=O(r(7l1@7ruJ+5iXv+1ak;GM=Y0Jm>PS{hTxZ=E6PLtzjA|F*Jc5CN6?U~6JuWiIQy{iu}ApHI2Lj| z4_SON-h^0!+ae*g4}g3y&vj1+r0QR z`~>R_%H!A+WQWGEsEz(vt$)7^`3!OVkTotLhex4>U`c^NAGH#c&uJtq#QJ!%R`|65 zwA$2PnH$%sX85CG=KwYa9;*VuNiYdQHN5~K32GVg!IhUP6s9cjeF zu_3U%TZw`yrCv9v-lekH#ua0-rboo?!$tP>;j^igX3P?+wC zM%1 z$mRzh%;(da`A8$rh8~5h;6U;6Q0dJHHS*{8v#l)j!g?X(+|&0Q5oZjS1P=}nG#$rmKa9+(*BPHH)*O!on7leo zJFZb$!L)+HK{$tES7TtJp*It7EQOfO?TUB%xg@d)NK#67Gkikdtn*F^pa6aK`k{kv zk)O|ZwPbITbb6LVIc>T7zung*?@aA*zq_-U7WUGb0(r*=6cBzQH#+=XBI~0yE%`&l z>Z{m7+wf`=KYX|qcE|)&oQ{LA>#v2=U7;mc<5tD#6{y+Jr(nlptKzQ(dGF?~t>x{2 zD|e)Y6s4g|sd^-5Bh+fOnf>?3(viy#PPQi=9(<|KF0;k=a!`>$A6BJBSI5a<(@`v9 z2f1l7=H6Hoz*;bd{`!|Y{#$p$9rS-^>UiJ|iYB(?3;2cO0-d})a;&J@QG6n~nbW^h z2Dtrktul=RvQLX?dLJf5-bj5+HWV}D{soH=ZfsR0;g2}|8EPq&&nY%xykOJT`=1-x zVC?8pQ&yaaLBN| z&1$84JdeGjxzAR~9agSAaj&V3@UN(CTVTSJg>eyL+g4>GU+&rtzzzvWKu{hC+kb}tgYpdR~vZ1I?z|bM&A^L3D^!iI)ZajPbYt`ScnB`+gAx4U$mLjle-YqN$O*)GD}SZ@%%S z0t7ki=pCU9T)6Ehz+ICjg-ICtETe9<*O>iEu9@Huogw^|#9vySC>AgKzh|f|_m5iF zZOOFd5Lmrw^NI5lJxKmnO2@k+%s^Q?lkprq^Vl>@_xW~67rM=?sV#5^3cMwVkQ@9l_ zlcw$$v0fYk@vHAX&Sz(T0DXkGG>lE^yB{IY`_qYDK$8#8T|q_u59~+_X~#k1)PGnF z6f=7+<7J%isQUf^^Q=M)b!! z^Yz>Y)*frgxfa!N1R!0$hG$8_9)v_@-Q8&g2s!G)=uzx0`e^$izQq4Swqu zq$J)9new>M5gjW@`H1Kuq0C(dRXB!$IOnm}1uuA0XuE4cJ}bbY>sPNrY}bNH&~?=# z$z%=LcDEk7ZEO1}1)TmvHb!Y>96F79l%2n&oO5ou3l>Ei(CUSJ3RKNEI@TPatbblm z#?|4vUQUAlsa!9Yre2|3Z`lR-pZ0vN-}Eb16#(%VgL)wMzwEG(yLX?hg3_&A z^%B9kUnd{^brQ*3RJW}~nD{u==X?i?KB<_RlPQv$3KfS*hL`KOQoI5B4!+bBw7Ltn zd3O&kSB$RY6Thz7k*O*(x{eA_K5@(#@!`IA#-k3Qo%od$jNxVTz?7CTh7)8~wkg-$ zn(5E%Rw0n6mw!uqYP!OlYL-y$&wQ_f_sdr|9ASTT#|U`X+WW-6^bF)RM>vF0Y*c-J=J^ZzrLxK*ojSp?>Y}ffNPrrB6@NL5HnghkCi=%d;&3)E z48Hx)DcnuPI8XzMphJ!>!v54k{$uM&Odb0_xpEG&W(9HzM0E;hoHd!0XJDZ%}2cs=)3a86sOCehr5 z^?Gz-V;(T&==)7MY8wn3C`s^%pJHC}JeD@1TXlbOlV3#_y0^@ly^Vp>Pd9eg&Gs$) zv7~bJzEM@NS7r1BHuvMVM=ze7yXkil6W^J(s|w;UzZ^^m>zZSjHY$V6WwKIU)fXtF zSgBK0v6?lqg3MiieElM*TVXk6HwA4XC@XzHfrM6(#!Z!EViyMa|P;jX%?r>;b92@nuxFo|hJwLo5H^{`7;8 z96z`0FeP~?H7_U7PaNb`x94YhH9ApN2PgRW2;QXE*qR!VFa@MLmGoK+bf%Hi92Gm2 zd^Gx6CI9#y+KI+Zle_Ys%HecG-vtP{60w-3IJBn|^_))|Y-itQB94`CdhD*^j}46c zliWeX;AMke&#=m!{-fCPdwR}xO5--B;OyY9Vd=VJth)VEJ4DLeAax8#4;aEa-tM3A zOY=nsP$44VN?jeAG3oD+@9*04aG05_}e!gbX~3OhK-k}` z$RW7k3X)xBXrPa($|^!1?$<+s*S+3&OCp-M4B5YT8e0`d5GyFJ;bFOKOWFgK9lDd8 z$0}$1yCv0pUrr?;{+wHILP`U^UspmV?&!D_CDw5i$x)BTOp#a=XA23l zaZ8Y1^03Cmb!k|NP`c31@8_=pa>`4Lsmdsqz7(`)1?`jNLiX*S`5P|`<;kR2+S^@! zJ?EA0i9{C!jT=*&3XgYRiW6)N)kkIPJU}H?oMjFx5N*18Gwb1b7{&GIW< zeK*XQ+I-6DbjuuXUaWVkjF;SYU5D_RL&|90A+&jwXxx47WfvnF%ArjBMvF_TXReZ6tM@9u!Dhv**DE8Z)Hta#!n{01cZ>;**@~flw z^>zFHpW-&eJn!=?L3NC#NCuwxri^}g!?#NFF*KKi&a0$4j%TR2sj^I-A^?wKblL!{ zY~4j^@&1yAH|`NtiNmq#Hkzc-+BYmZi?oVB6GPiY+Q0WudQsZ{Q2FqUN?z!}F&Os! z-Ew`vnNxya+47gv0@CM1OkkJst5mV}0v0MIocSb-A8ts-GixyLyr@5fp<<+^xw`3g zaI-O#FVbLtsrmBaAN#-}$=K)WCZ&X|?}mSWcl&Sk zu#x5j&z+n+almrj*oPlCqsG82vOcX*VGIh3>!^#OWaedl?*!;}Ed9H+FahBTPdJz< zn%G$U!)$Nz*p18%f5z?U=x~+1qp;*sr%(y8DgFB4)6JhM0NTFgGOO}mnFV0)!R&7^r7R)^n-_@au`+S1XJFZ-4Et3V2!$-ze)Va0Pxe{ zSySTMWi#JcWJ@^bQ7WO|X@F1Y;C;v-boOL-V|5XkOYwO@NCV?J%^)!*A?L+ngF}g~ zGF-O?1CTM3ez57v(RQ-%5K8JV&iDOGy77RLlg4*$%*zH!d+;Ca`xyhc1nJUtS_bS+8_B>8p?GiK9XAE2MA(5IYaJgQ%-Lmhxc=4c(|h_ z!sW_L0t{NNBs`Qmy>j+^OAyiox5)R5>={h|yLuNW`+f)} z31E&pjH}Kazcc3-+?ih9;`^O|6U&nATO3@T-G=FM&agASDd|<4n7g267w&{#H@-6U z06VPY)@qfO0~g;JZ!tHy{8_T2$y(=L#T>}5R!nq;`aq0%HWc1wxKV|H0jJBp)u6KD zSx)ct{Bejbd9CUhEw0&o=;o8?A9*Og`#TcOQo%u=dW$A#ucLsEsvxndO3hQ2o4oGT-5K@g=0-ohdHy3xjdq`u5=d%aG28j6{L_Zm!E9!9IfCdUEsI z!wZ9Sy=5sa3zq|L^X6R{N~x%(VohW6$Xvv-ifa#}0=eh$r$e$5>oxsuC)&gpwFm_g z?do{G-2dZsN$xqivLtJlEe$67;5BO3L4DyDe-vsG?63I7SO-!vzg)Zbpa(~HM9Q^d zq4}pA693e+;brWgWWObWEKEnJOtr5_z?ae2S*+Y86$a1`6`SS0 zhsO3$d$GLxYP!>de`y@|03oGJkg%@tY4IyN#F$zWzTB}qaCz%Xm7;KipWY{t(zZ7~ zAhok=T8a4#zF#XhQqSuFsiRwprZe+#oN8dEbQYwls#sic4lfCQE0sD-A(&zLVq&N^ z@Vzv`LpEMIbAirKEr%i(JGqg2i#lCBEZR26`HpHo1wygV>m~8Ek;L@W;B`!$j^3M9 z(?oIO;K54dEE@Gmetpwr>@sKH-Ge3_>)@1NLG5YQzgYUSCV}Zu*HUe8YC1wCz%-Au z4p6k{gSK6#`@J!UG|>!L-!P|g)dYUeL=)^b#M7_N05luL-qF3-9o`lDV;jN&ya1+W zG{3XjtpYim%`S=_eaZaLJe!#J zGoz#rLeP!SYODA3TzuW0411bE9^grmJbFyK;->j4wFnzJ*i^ieO@k40Bu^F7k#M-LaK?{iH5PH*?{MwWBnV;FWwc+lx1xa-(z|53zzA_Xq_mQ^=p2B zOV>lf@sOthYd6sMl6V>0Y@~&%7Y4e#0$uhpm=MkSonR+A21pb{!!lw(UKvg?r#`&< zZ82HASiVdD%8ELG$e9J!Ii`~o);a$_-u;qqwDdV6+$rC%cPh)G*i7>3{?4g{%p83O)>7DHle6prl|ZXFu$M?Wefo;YkF!Uz%JfE}ws}lzrs3 z{x;<;4G$+4hL`@A7Abriyb;DP)gOQ$^EKtb&W%ER@@;QzPe>_%P}1&1Sx#W3IvmN> zS^wVe>QzOHu?IZ_C(%~UMQlE8XC&p&`msB7a9J($${l@B`?sAwqcHCHt=fY--Ayq@ zk@~?A=pa*3qEjraAJ)N>FiQ@B)bl?0%WH!Np;KWt59m{DpkK<{gmJiX81&?=tKcuL z=;evQUs}&J*$T{SRohNQH(SLvTWLMkt@ug}r*+akEQHtFxe@IbkXRzRH0|+D(TCITRlv4W)x3Cl z2+G>tl~wRno5LZM(L#n83Cb$2ol(1;if-IFP!zUJKYaW>^Mb>sEO6NN-zS#!?iRE6 z;?_%MY+mx^Prh|(be!ScLJz&vlO52v(m zH#8fV*1xZl{#t4NgHwWG=OqPe{OWM|5+Ino@ zL;qR8?qlhc1g#=>sU=QE9~XWcRIkTB4?DI8%BOtCIPcnv-im4J(ZwiPV47Ub^FLPV z_Mim3r~P|S0_ZTP_#T(y{h?Kz`xWzZ{3yE%J3NaW0uC-Ni-^a7hn6ZjPM1-|6yjKsvsNZa1qHM9dIA^~$$9O4iBISHl#cbOLC#+}#@()Be_= zY`&;iQBHq-Pm3$m4GSI3u+_8h^t9P0*VeJ1eK0%&)ojEtZ!vpXT#1r5JoQY_r$d`KN@}(Q zuA%HcZ406os;fQ@Xc<+3_te~T6@#N|!%2*&HHBz@f^Jre^lWx*xL`2M@Gh;gXcpVF z35HN$&^iX(c#*&;`0rxzVEZLDr?aHi$$IGJHv9m{C~z?gtZf?VDNW&Ht(lMvuGMD2#S;}xg%=t;G}JVjmz#cyEWUpe1V0sCIv1zyp;UcDWVDDNL!};7 zd87hkp{$PW2wi(gP$eS#2|z3*6a;d=pHw2bJFl?iAuj)srMrj~LYd3v%(t}G1h0u@ zvj3;i4M6nt@BEu@3=q#VQ1ciCNQVWec5^y}#ellaHoR%1QB7>yo+4d06TgJ||#=}%ECF203>7)D3Eo=XQPE*u!(*Wc9N!nDq0E5rB zE{(i{84PI&OKWgtmP~ZBRg&sae^({c|1G|}xefwY4+5}!6MLuv(GbwS=hT|g!@JLT zh&kw~xMK5y@pepzjl5SZ2;^UL!25Ijv$CFdDyM62@C`fi4UZCuKT4gLwg;`_*WiU3 zaF1&NP-Yzy;sJ<3kSZU5Xk%uah0d@mc{fxu;YKv3M(p{eYjHj_vd>{5nM}2|@$TL- z4y31@_O#zO00-<|!YS(vg4XZAt)rL}h#+{`wK2zq9#3Gf&GPOx$Ay?0Zy;g#)?xT| z+h?%?Wc>X~>I=2RFl^Wp3y{C`aP668*r0`;ow&tT^6t4nK*evBFyo!LM2jKXfwCM^ zoU1;|c=^27qK2O#oK|im*?b+W1(=!YhcuVuDpxlahca}1PE>7*8F0S|R*AnGXh8DB zzkCG`quC$OyHe(ff0!Gsa)phU6)}oRDF znzk{}evGFDO52M?7ZKS#&W{@B2Jh^9??sh|&XaK~!oUsQ+SI)NLaMeEnN3j-SFISm z(A>0E(YQ8w^>?dTviwMtcp{3))wvo@=W$cWH+SHxU}d-TS1vO)qeLQ%a{EIp={oP0 zbN`HHWW4^C{y=8HSG}UcLsQz1oxx|!aDSsGdA9}X1>K1hWwt9(WM4SwHlOj!)#kW0 z$!*dR05ijajC5oby&mY>D;s94mXeV`PZbdgb(i1lP05D%5$mhLa4Ag#-iA3Td)!8u zipa%b`p||!QVAOIKcP|4D3h*aS%&WE!W^ybU_{oEo$4X%jwt_41D^u>TobSa55=VvQ%t>cPg_*vh z#h$3%%ZyR_r77U&ktQ4dJ!MTg=kl8TmIvEc&Ky8;Ky7jt(Luf{nEPwJeEi9Em$bxP zsIfE|Ur7Ej*Bg|N2KermMGRT0==$N(J9u!&+`;*vFR#V9ge zg(?1N8y^epcISG|^SUvxiWZ63Ml(gN0bVN)*>%-wJ6U)df;E>0ixaZxsIMK4otsb% z1~74^>`#3o@z3Zcbj|Kr%N}7!6R5A;gh3Q3Kd{XG*rq zJlGJLj?CnyF-$?H9%ZG$LFaNAYV(0?a5&~=zoydowL4; zZU1_Nm$}T!Qg3Xa)l)b~5w^&R-qykJLMKc;R2&5KklgAUXNph)*T+N;Oe|n2OC5E% zKlf*>u@5IK88z7Eh;1NgO|`P-oI$HYVzU<;oPrYb<##0q(I>;LLDL}sRF#Sv%E%7d z5d9fsx!M~lbV-I*=5Wu`E4m(ISH#yBNC^`WhD$`_YW*YnVf2i+{FBD8EA;ATyC~`5 z9kQiDQFmC{onN-(pwsY40cIvJ6$cEU0F8{8#^w)W4%+&qrE9C2JW`I-s`_?0Vcc4f z)!jr5#ZA;7w_91y&J?E;9p~Hwn$^8=>*XOR=@ZaevVJXSeg#uzz8X4t=5x}&0*w(@ zUB}c?zq(=YNnSxIve{&6MERCcd4%R{CF>FhPU6VTw22bp2$a1H1QSFUfAPk%$U)GV<81WScL`k_7d2?t1KnASPqqXW}zYH_tYLBjeger0KoJWabPV4;RU zb8e8P>kZ4>Dy5jg==<@OMSKyq$XsvC6|#(tB8)vZ(FCvUjeEm^8A>BJF8-Zc%_9nW z@`E`psqX^2j=+2l@Zd&*49v5PrLs<&TXAE zcio7WXRCr@+7q||wN~QqzbDCEr^_WgSATi!#`q3|zQ&0-?>;ggxUjZo;Xewn?O1_C z+GuQ-q>No#zuDo6e-+OoJAT&A!G5=5;SkPz7~za~r<=}=^&HH-wQ%3jU<|BaQwT1N zs=jfI@gI~C$;xe{(!RvIzGOA}eZEtcz1j(}D9$ua?@Qv^MC$mE05fn5A{-2aVK8gz zv*aAw15HB*tkh?g^C2SFpZC0MDa)X7-94q;Omu=3a$pQRgUq^pIO80XD5mgd7fCK^ z4|4;ICVss#ur5vbm%e+*PpTk!az9J2e zP-z{AxI-ahYauBb5nm^N8nTPvtFq%Slp_Yk9@@1vT#`i$N$(2a{s|xFekV;)l2uQb zAQo{>M9&ozfnUNZ`&Q2A2E#2$yn`tfLnbl1ac((tlWu#3gY@oPyU`xA2$Bfr74xUi z2AXoNV*|mzKnEIAG`c8HB045llly84kb7gxPp9FYbf>I3pZl5(6s2-#x7hFW0KZO# z^xAlm1-XER8kSVxzNh_g0wLzn^nF2>YUUqKiQ}=-yJb?lOz4A%16RSzxGdGo28nAh zFz2SKK9`jWa9ynznyMX3ujMsZHu=-j7zV$&Gm!Fb|}Dk?Zrysum3Gy5G0oda>xbxbLS;iUh{VAjSmRFliUc64B*J# zyIg$s@%Ly0R?puwE8iVHbH5wY;C>fln@mnw=VD7e=NjK0R~jJoVVZG+n}{=wC=WqB ziju=uPG-V}fD!>iH+%M_Ud0)6q0t`Rj)Ex*3hG`W`1sCZlRbz1EWxWOblXs4o#FG@ z@|Q=O-2b9Z*o?Gu@1$u3O91l5>w-@i$qmag)^=+rVOKKvs*0DGIgdgda$@~v;o`J` zyRUHPQQ9itrNQ2aG zE<9F@-yU{W_h$a;0!Lzeg@zTHEp0ei8@-f!= z#>)OZpTkihVuGsQF1g7%Jl%*fUv9xllz>vNo7|sP1$NI|nGip&ctz@7gD3Nslk0FB zJ7?{HCr?n>4PYZN{JL%k5Y?YPk*@=;P$i6vgImKI&MJL?l#7Vx>!jCeOS~;yv$$E9 z{@=+1ekeo_c&85dU^#Yg!&r7Aw4EktxNMo@JBdaAioB+YyrhAiWBPMxPyHgYne>f2 z1Z?T0wvZ5$)M!O?e-|{(Zi+hmTk3jk#0Q(OfSR?=qBw(6_uQkNfV?2&2vZhbGfGHM zZhG*EzWC}^TT?Z6(ycuIAz|R*ox{hE2lP*IcfwKT?12&G=x9Kz_Tb=h>20g#``~{` zGFD)xDH)zkVk?ie3tvCFD|e$nLzeLgnbs-R+-7*DnZR!!1f7fJcfqN@ZN=*&AWIIk zY9;Wy?B)@{>OgUUE$!Qb$D|N#e*2yriBqQRQ!%u`bO(b8nOcpWO-Qf%TogCr--$pd zV64P0%Q4m`wfsjgaV6dI&yW}fLa{LHoHbSG@I*r!WwQ$2j*tVpM@)@{-y5R%etqYK zJjQS{AL87l8{Yx8h9nAdE})sgI4slle#H0wxdrGuB=58oKgqP$MZv^PjXbNGLqO?C zk>LVPz%*cR0HY3NrKYCr53`#_!k;A*%CAl??4Mh&!R71AFwzS@^n|=Jc=)D78;toz z#u~A4)g4nMhXVx@%Ni5>(#5w8N!h|G8updwq$her_3NHDsLvVv%yVZS5&QWYj4O(N zUw${wz#YNNvd11eNJ42~uDmhZ{Yg>33vQ8nV%=oQFUiVtH@uFO01Tey$u(K-AMs!vgqXQ_`c;XKIK4S33vi|&0 z))#=q1PkchT9l`RKxfWGW2k-h)uvX)ZK)cZs2X-6vcK zE0z7Xtw{GTBG%Pm1@a?J;`*gH1Qezb)`iZdDKejJQH|JC$?Z`?Na zj^bOS_$g5On)5b)5rQ? zK2v8iUDXIq$$|KJNth!7Qp}!K`6vg$Ck~!B!o~&N5eO6i5p?>aP?86}(+}j=Cz;T| zJcR@BEH{*P<}vrgG56#$SA@1kL^GqU-=fTvpcX;PeB0Of#q((<*husLki99cU?E26^YD%&NP)Z$)Q9xK-f&EX{iH$o#k$>1N4&ueNXc#8L9gXmX&Oro9Dv z57qyRqbVy1g9U|Q+C9r^W zOLt4Bpn!D43QH=fbV`SG?g~grN=iuAQv1CKzyJJazL{_4%*)+(2VL&o_uS{6^PK0< zd>lMyv&6*rM`hs_4rcxKNEWrb<(~aYu{a*ERh~qDFx%jufn)Pv@!Ik4(*3da zsq||xvMNtwZS3d`jB*iX_6D07noK9+Gvk+mzuj3I$5)m9@&Z~Nl33+7jI}0@oU~uJ zpCpoBYkxg!87C#ktPrh1u|_T3vb|~MLAJsuny)XANp5>9b)&Y&4C-2Dae?%6dPo`t z{xh%pD{c6JP&%kNC#v23t>1tfN7;(iTGZ5v!(k5W)I|Sdwu+~kqq!Ln0MQGr(w;>3 zeZtHZqobc^a=>B}o%fw;aipRK(anGeN9!xrcS*_{Xx5V`F$H(nEVgcK<*0aA!rZ2h z7bqK_V1GnfG0$G-mCPDyMdNS8&yV(DjQ*08@lx&Y?bdtCV$wfBjAY;V&uD(-8kyR% zk89VmCLoBGn%`EK-%`k!O6-KQOHlt9vD&j_!g zc3iTst%muGI9uX&Dy&Y6l({Movu8{!`8~744?An@D|vMfxbu5|qIj#wELUHtzEWBD zGG$w-0%{4%b{W?HSU`IBg=MYi$nVKvyO*<=A$7nKK@;Wi*JipDpV>C>f^SG2B<#@*}(F%E5U^^jNpOc%xboW~mX1=+A?FY+1Y z?U{Q~ND~vA!2NTA9@Fw(Fx{9LG1E;hyCju0CO$C}h@H^)!)7Jse-*fMBs_eThP3ae zUvB@d5Yyy&W70qMV~@ou#Q+d{5OP&a^cdi?b=i05pStJP2EB2gYKQzm#3|S6w@r$f ztSCHRbr@j_pzQ5A%vp0FQvaRT&6Bm^FmlL$E7&?UW-=s*7)b>T{`xxTtAMeNlNilJ zubz2=p~dw;k{OG>+OhqL)kN>Mx>F1zs;|f-&0PSX!rJXJCcac4(65b>hsRpM@kZ=i z=lAk(*@U3TAC$4h+jEH1dR4yq>X-T4K!bzML3gx#B;^-`I%9@9YW&SeR1rNsz)#m(Q0K{Gbybu!_o+!C+j~Q!65{(9)P}^VJel58KjpE z$2nS<|L(!452zLcZ;jHLiS;|TTU+<{bN`(h=B5@{ky*PubSPx)9%n-oU8j=+6`L`5 z#>edK)?|2Nhi?%ylN&Jax{GbqFxoALv|8Cs2AA+P24{^oxaY&BNCh!TIm)!XRP2#r z^vWwtkAmLAO7EX}eG$SV&OOqk;u#aNqz+7TrEUzz0@YX8iq)8cU2k%1lgE_@*dolP zW3*}ekRl6AJC%r{m`{hoP5Z5OoemUHKj-~@`-id}XSzE7wBeI8-c}~ z{Wsli;>^ifIR4@?M+am>N$|nIya>67_SJ`7Zto$CKcO-+0b+xbN0o6GV#B*=zje)L zmV{NGw@b3VA4C4|p};?uIot864=*bql!Esm8gM=66%H!sdrAUocQ}FqGWr-T+y4if zpZZ^h{E5+_CMG}qIy|7)1^A$U5Ks>NW91ZQJo)jD)r7>GJJ-OO0GFNZSW_}xfM=*& z!O_;U(jZ?18Dv9<^X3dtqC5J~j$RMPC-dOuBm>F?tBpy^%%AN-ahIL1(p$dVx-gTh zUqfkh0L5bVq`b&;0habk_KG^~Eoa(wi5H5&Jl(>Ek_5!;6mD?fyR0j_QL;R>*R?a) zvA)rb`SR+9Dy{X2<-#*_fnjL-L+hM9+Mm<}1}jLtr`bostcu}Smd|{VFZD<` zx{|b2JQhJ@I6XWcNVS3R=90cPAw;9=@*a{N3=|_$v z@=?2+CqYA;?yc5^F4e;~R5RlnK-m-7Wf80pzT@Z4gZc-L#J_T+X0QVcz25v45^)ik z_Q-O{c+brJjmNhn`f13Y@PEmik`wAW#2C@Y_wP0d^#6fuImX1SA4@K|^&CT0#shzK z2IgCmDE;P@?+gS}%(7eUfw%-@LA?vZVi7wy z5Xu<_Z{8WQ`Jy4jpVyvl3Pa=u`{=)NIyY9%cT^S4BRY z&8TZzCLgzaq&Km|ydfpQkbnK%cjv>=bWUcUb0!)<{$CO64LKtHa73yKy{mMYJF!F# z9Be`mJI2|sS2*^!3!edo$f4eYt!E}N`*=}03hATj#S$Pr!ApNYiS_EeUTo2<8X2OW z$lR142-ow(4!tkwV7_mwf-1sVliuX5oGDk6W}VMe?Pn*EZKF5l?-kPm8`mFwQK2PV zbDUVTQNEsD1lwlQ#M|_cUAj(-*b^j&8sxUQ{(X#%6`Xlgss3| zBlc{t#*vp#4j52w1LE!h=nGdt?H7IiX;WdN8ou`@iXOt9nAcqjOP>0bAI z9Yf^HG;HR>8v9T~dqS(UIVMP&62so|Y*<2}Kn5c>tMGARt43$MoF>DU??n6F_f>Sk zuD~f-eTu*$7n88r%$dlSy^hyfm4nV0uf`Wpzax7nHX@<9vv`GQ&qQ!CUiMY+1*w$u z!oX1ut!(>}Y5Ko%^qF|oR^P<4yFb@2EIt4cKOfSfMJ!!@WY=W$O#7B(RZM=*hKyye zv7Ahg{9uInQL-k=(Q{V}yZ6wBxI|_^nqPDYP{EjY^`WW0}wt8QRf@<@I ziH$fY!RRJ)P-5d3ejlZtf8{v6nk3#c;RL!RmgGN78qiqDWnt!nc&PCAt%%GFf&pCA zgx<3e_gA>(;D21^iTnkVZa8zjXUinkV(EjqKGH^~8D{mvxzg@=W&Pdcck(arQgkj+ zXBhBj*0&Z-zv%)}!R95vK&qp5O^`*$_=(dAMLy7DVV}U=kZ!&G=(XH~wQt^`A`aQ2 zMO4$rg0$CR&CHA`DE~6PW^C1Bh*4|b+j6HcxB0G|jC4isvkBq(Hcf2UR z(_aT|KPXFe(SY+ja_aXeXcVs!{ll5?quFww!E zddHJy9-zM({TFc>CG;=jw#{$zYST9r^aI~CeJz&FnEvZ=i)&p=;#l5p?9XET1%S7| z>8lHretGV-t8#9g4m1T-@8*=wGS6NmJKYQjTv}!XRgXyO*Q-umCwn3+=Ot#ItXBT3 z;o3#m-O%g;M7@7(Jz!*ale2qU+=Yjblo-D`4iI_sn0G5-`E2B`=h23ITkMvS^KeL# z{B8#T>RA0RmM0a)eR;Wx!V&lAIrYk>M&j%bos4cKLo5ff--c<;hYIFJoMT)ob~S)a z{?#T$A*_oiWF%Pl|9N95kf;$pGeUcc$^UYc?fh)-taOQn(Z(vX(U258GHGXPlcr_2VFq2WXEFOl{G%%@l8YL%>VoSM*cg88g+?p?*3<#@2Z+4$T8P@ zc&Cz>UN7QfJlKR^-0~RY1cVS#a5M&DrBTfFf4WIe>zfdCKnLv+)%*ATTQ3 zZTB!m@9BCh&|Ane9qAtR-=yaZVGj?twGJVeZQisEAhc(`iPWo3&ku&q{}nd#uEA)| z0A4wE?w+PqHiI#mXWct@tqHvZb1Ivw{OjkDO>ayoi+f4KeT({pF;sisvv&>$;&~nFW(WEhfLCE1#ey#5@!E? z`~E))F=Fl6jqW}%u)u6;*wkr!`VPxml`+l+YelBDW2aI!f`sD`Y<&kCxS@+Iu6q>5 zAe9L1kSP)IjSW^M`8in3+unDK=00=GD-Le(0?WfQhux)m_Qr|9TAr0le*=@6)f&rz zzUCIMHe-9^p`DeE?XNQ*lNe3-m2_@OUh64%i8)ZE4{Dy~^*KyD{c#BsW6qc2dPvEO zq)pOR?oa%w+Y1GVpgLA`KH!ob&s)2s?&iMVqFp-7W-}k@xDTxT)D+v(k?8y5Vr>;O z@`ELFq=}Jt8!BMWGHR(Z{J9IKZ~I(s$(j%j-gbcb?)tV!h6YqT5W#P!Ipo2ki)3c z?-^hxrc7`67{40U##&=MYXU#oQ5^reGZ^Emv(f9>oLk}Cvf*k;BxK*Wk^%B~C9n7M z$nlD;q;_yAK&}NaM>(;#|IF!r0NerY=ih4ISZuvE1jR*8{V}}}47wCVz!ApU-{xB! ze4$$HYqhT|F_jh4beiCmAT zN7@HT%8m1FO9kvKb`EX(8eiq?G=sh?0n$OJ=GFr8-I)+0P6$;^i!P-pVMq8|imvw9 z-;2GKE*9tY+*h-tr%u=ifv_NouD09T`z{t@ZLyJusXK@4!rMA(_$3~n$v!j-=*+71 z7^ulfsH=_$R8hL~uG>{$4+WGhhCpzwJHc~>_B!J`Yu+}fTGiR=)zrU-qZk?fK2^h3 zdfGKT&`SF8oEVR{OplK7F-sU@T4RDgH+v$WM*p6%bX&kJmGf&~*)^>6J>((%z=gM# z&y&=!iOCcrmT^4~@0Wql*Yx>4kPsoU$B_O*Q`|2x$LfWTrv@pPd^-4yl7*KBg71?l z!nAm*H+4EXI}z8&0Z~t@B*a@J#HSP|i{j_E#^oLDfWB;BRFyhgr8HAMZCn;hjNGk9 zoNt(o2rF$>D#hW4miZ=$m)wGyn>;D(j(!tI)y2%SUUpH13;pzvjC&%wJ1WU#PDOQF zpp>(Yj=^rqb(FEevEWBc+^M``-*p)!YZ;5L+BBJ+QD-ZVQUy$pcMkd3u1Q2k7*yBf zAZqNP;Gyql&x?ACkAG_?_j{$O-ZNkk(?(4*Hi1P_-T<>}PW87C1wG77fgM7_*J^zf1~PbE}Ddv3PRgnUhBkVPN4 zSzekUzU8OikD?9z=c=sgP-1*A=}Gu}=3rs3N&1Uin|15P)F}OEp`f1dGE1&u>&|ty z^d7#IfoM#$1S~=8*JZGG4m)p+&zpEw@~r)M7}cGJg$#4#if_C53@eGWS^5F1Y!X5| z=*%uC>N`#Gszc1d+3PS(hy`zGS1XkS+h<-?Of?Og^($-8wLYX z7bbYbgp{Rme3QApS}Fou+8=2)a2lk2wB-&WjwA z#M4}idZ7MRo)(4U&nMZYF6=iA?yDXNw6A}9BJkXM84*+Wh4#!}y_~O-PI8&VE?8jwxCfMa#a;PTtJB z_xLI38Mf(kO%aObX=#PFL|(?aM%_YRQp^h1T&%ffRMv~Ec;BxTg{{u+TFMUq9*fSx zBg&Zt4llubnGJ)L{N7mhG?Y8#u}dwo`i#X}GZd;*RZ7i@Vqe1>r6}}3^1yBc`o%QS zt$IdS4hl_r(>h>nvt)clOAQNM|565$jmPM>du1$N2;JjuSNItP z`FZr2Mfp+T+UtsZYc|N?alju(_z!pz-bkmGPhVs9-4q1MPi)O!BbcrbTq*HwY~65H zR?kg+81F~5NzHK12Y&z_LPRMu<3l%?A5-%Sc9_&xY~JTV+nFn0CqpU*Ht32fTL(D5 zxUGJj@h9?dpM0V}+iK+mwxP-q+AnXk^nS^DR>{0)n9(xLCI#u0a>Nl!84jA^t&!BIoEYy zTj^^E5N}Siz;~uB&#sF}i|=+%C1c%v*07XU1&|d7e_p$DL zFKw}BKg+7AYDVajF=OBpsyvuFiX;8(s>ar(JhW(@G2oj(rrymyGRGf6H5Ek8dr0Nj zpSP>5zZf%bZqJS^q07*p7N@^h5pj0-^R*d?0^xUoF%`m3=iM-v3zZZym`npW)k9a3 z_LG0`71{54+WNfqKI6bfax=Mhp88PFoNkFZZZf&UY zMkL_d-5=wk^K{rr&Tl%3uQFQ?HRre@X|wSiwnZE`OqDVDm>~XD6Wrw`^taQrhvux1IR4i+ z>}!h&d9=Y7BeJ0isr|h9nO$!I{woP>0prVRS`w&{9!=qhibG!`pfxws z#zGwj8ZUdZ+j+rtw^j_N7f#=E(diY1=|`Hli`N9|q^L!;`bw6JTvLDYUB8Vlz-GP3XYv^Xs68D@VYSF0MIz# zxM>>nql;+s@;EN@0ouQh_VK z9b~Q!3Z#J9%3qh}xTL5_;0JvU*gqj7W?SCihy3CUc0ME4(wwIRqC_tc7f|F|Z22 z*gnKyUe|nJ%BD}BXNT8xw9*)zessAQ+{J>ZY~1iZb+B>TYkmd!ce6pX7E-aw!?3MtC<*KuSin0??YFcuD><8(6=W z4REJRMJNg?nnat-x-a;E6?5ylFJBE_R%2K`4kV8{$INCJHEFSsq1F`$RoEp%D(y&u z`@)mRD4DY(DHQC?3;8+uZN8(XAzxIi{LvWb+A_uDE)izm0#csB}j&3NZsl`kJ zLdWWwRN4O$!}7#Xa1HQIi#j=ig4V3vkNA~oSsTthl^-mir_ucgN*r{AvS>!x?3if0 zs^T%qEpL9~wf;%VOL_FVrzyFHKaEuZwCtX%ig1rz-r{MHHQgiw@}BS@&}%x=D54-Y zi{qTTeYFsgTo#vHaci0;RB%S=$cnT=qK%tt_sHbU*NZ{_-t_p-Qd2Uu#v$$Nm)7<@|7RW}4-2m@*(h49 zS5B|g2TQJbhSpN`e{t5l4ubRqLVAKA6M>ME!=ci@srnV|!}jgNTkXRaR5u}3L#3lL zJ#Wcq;LQh-?RhW3{;Qjh3D=)%k1qOlnI7yrX*B{5jxsvHMPb7^^0V^81#sPB*uCQd z4G?-3oh=hnq^7ydSkJ3;(-e#5Ts%1zp-@acaw+t>!Es0SWB_>nGUKgNGbt&8O@>)G z<^JM`mxF%_S2S$sZ!};3;ovwX<1ICn_Q!P)FP?%A_Me4VU&p62zd`pP3<@m!u9>`U zqs{fqz-G3GKAT|Ja)rGwxoFq~bhQ@l7xUMUuGarDC|jq^5k9nP^ZDu<+8;Bjp&Jz) zFZ=XxJL87u+Uc1K$usE&ID^lsYY5l-RT7GP%KG$vi9IYdM-!Y~As7jTd#4K!WPzFLFzzt@7QZ&~0Ss+=!=dN$tP9h6G@*uMDqNCyYc z--slb(&=rbQDR{gcm+KF^*XFKF0_XJ_l^RoD39nrqY#yj{EA~E-#Lws3o59g2b>$7 zrthBqhn3>UHUkY_h{_>~N*;Nk{}d7!5NGx~2y(iq(7jz`o(RFCpyu;-enfo2E|GYe)+lEY0H=GAoPc%Me&k}Xe~hH{{?hOug) z;(OZlzNW8IUt^qqU6uKf9{+9Ud8{Xc&zbF|U2Z`(v|TLAE!2Mg-WHP5eXsY|PDk2I^DK~1%Qb~)om!9==_xsz}8HgKnE@2zhS#D{z z)PDC+iZ6}`spgUsJLtq-vx=v$pR1C>__!%xyiZ{C&>}Yd#=>}=fh|YqFC8sy{{+}~ zzn+}zXbS3>$Q*x9Ovr&*q4J5LXH;S%ShE&Ow3QW`vgKpfYV?5nCiLgBX5&O zG0m?K=Ra$0xcs~?;bPZa4aAeo^O=UMsH{Ade7=}P4Nym9?;)dtZ{d(i_IJ9~dHR3$e+=j? zJ;L7(h3%+}m-w{3JK{owUjop<>}GElv3s+(etX#kki@^ct_MLp25H5V#-{ zL|mrVhIXTL7=UM#IgA*%&Y44OmRy-sSBydmE?DiPmPy{PdU5FY+n9+P{!msN#C8Iz zrbjY48CL`B{5bT7lg*%GcW`g1y0F($-^0!SV~I~<0nB-sOES z$ooDeX!Dol!F78msWG2)Su4|8xx=cB*tI;!L(T}~5szcDbT#L#iDo$QBJ!mGuJZdKU(vWFb z&^15vfh_AIPX@i6^)gAci~!oOZB7>Q%tGX#av{(Y)(bZ!wEMYAjqp=76mze8UlKDn znWkG^x%l4sj6_?;+;-Rv1qCW}@^~8;i!6UG4B~vdHrkCRUSuj^sq+VtO}tRM{VF#ojJ=+2rA!B>Z7_e9I*6>FXaz=6kw?kE#-y*M_^yplE@Zj;Kz8JQW7>-W zljs?RK5>qJhf|Y1%7G7(?}&@dVVq>%YNa#nYYhK9v%xmJMNKywW^H)QTf!-h8$p6b z^o)_M9-SWX-x8rg!$ zkDb1#^X3%~uSL@}DNs!wvty;=x8R9K_Hb_RW1wt&bd<3EM?W8?xZPRoJ(w`DZalx#8ZcDmQWSbt_xSIIe1p)bf~fb(GEBfkxymv>lxNXlW=D7TWPWC(^k z7Ff6*ICL-DC^k^5xDIQ$5&H!5|2uTM{5=Ws2gTDyZpw;CKRR2-HrEn=A;i0{UgMlI z9U4y_Z&}~F@{-*tb3!bl$>3&UED&$cxQc>gw(zS(6uuQJN_?4qDxy6UmjFWs_n`=Pj6=RZ16`IwW~@WL zZ0C>0Uas=QI~>^N7CXA@7>Fu}l^u(fQ>DD)8MMaRZ?^xM$QnDU%XAGD9wU7ref=x- z6ys!(>Os&0L9-j!E@I~fwvJf6QQbvY-dmOjj=c-wn_Esxm z#>7J~ApfX3;0>F77gGdeomfX2rg;kvUPI|dJ$?^=V~W$w_p_Fl{0u$fh!CZ9bwCgH za;6lv8qA1fPQ{eC7}ei`03^=3UnqsY+O&S<5gM+DB5F3_%3r z%TT_%bs%Hp*&e;({w|mcXOMPcZcv1^5D3ot{>+Y__54WY+~62MML2m zOEe!tB*oBjh8+s_&?@|a`g2eb6pZFY3uE%_IwMRFTQ5WIbh2d~i9Hs9`Gg3MV$_s@>XRXXRoJ1VUb6 zru{^4L+mt9jycPQcZ4xlSVET1dqeT2^vheX!cbPPc}FkkL~6}Z)32SDasg4z;Te66 z8wQ>c4AK&jKouNN!3cC@@i^!?hxF)sq3K69_Cjb5=~#ltDbm=315Kv&5B4wd*00Tt zcx-4F9@%!DGdS@J>687H(Zetx&(Q)rdN1>Y^}}@Y5~*r&Q-QnXP~qwPR5XPEm%V}@ zY+UY*Jb*cAGzP}d)1>E0ogboo9O8@TMU#AlxN{<$%hA0r%dXjn?VPbmW=atqri}8T z#>%BB3f4@El%L^OB)%yqPh>M06ZL3ZE<%)8Q}k@@(w8$!Dj7<*zVp5Q(^Lb^&`awG zxdk^)ue)Er4h1Nl-|7}+AwAhD{3<*~N*1k?@#Gs_-+IHpqS^P&$yaQUh%yx_H#26# z#9on0>=pgk*~t1RD0#HH9-w!Eg63kWo@Jo_uw0pBq6&jaMk0P|nrrUVfQ7H-3+^zn z1zH_r_*ib!x{IeY*JLzAXzf!DFUTbPBmc??Su^p|->wGutuVM)mMcPe!AtJ=l@%bv z{~@iVj6qG3Z$w_KLTN$g&RczJ3Tf+8jPWp6_uwz|5Pt4zSH#FMHBRtV*%AmR{Na0v z5l^HtYZp0mQY-t<5w_IqxYK%J9WiF=2{#r-muSngXMV(=#sQ+nTj(I{4%4WI5fjDq zzyo$0>w8wdC5nD+XIaqgfD_8i;-JUSehF|>AEr90cE5thg#Z2hl}z9 zBK4>u3e)AE=v~}+WsEEpewizOZD-S4?}BrFhNs~A zS5GQO;cs6iGcpc!?+iqRPb7$64Ga>I!9$0V8E?b#(P{bCA?{8StbZ2YuNf|0hOObG z&Q+|huHP(XK4Ja1v3Y%ENOlA>Q{LT0%##svQ=3bEgr+52PaAt}eqt^;kE>PGsz)i+ zc&Pq9|1?PwRgct-QXyOkQVHmOC9fo;BuEu1TD+To@axCjPa~Ik2QyKh!p~^UFrLB(Oy}SA ze+_8S#KY>mk8Jm>vnHy(fv~H|ztZ}@=SY$+@wR!m3+)cD=2_o3rf{+u16Pp7R+t7N zRv+~1CN$fEv6r4r>bB+nT0xZk?MU&psMxaOD7@mE9Ve#JRKBaEo*cD z2qi)cLAS8QR@#jz4f%e%@`7b?mJVM0SzHRvQiNp+l&H186NUFvj$MSwkG2VXus@I~$OmcrRf=p3yjR^kY>vSg@_x`#Dq@oUBt`me1Y@nr4 zt50b&qTX*RHvY~#;b*=}zO2Qgl}GdHjGl*tJvj>*+>jcRl*!}ysed+kJTmpqCOtr} z)848qI;kwaRVfPLdLERRm6m>Xo(U#(m)SASM$I#uR*f4e&1|iOY;Y?92cX{-KvUYHdpv$-kF3* zm8jO?AF`z*XFqKg|Jb-PRDeef9b|$*+U(@Y@woRCnNE(7Uamn z@%kOEO|?(mH5vYUyKDc%Z2F?|@}JFK0Fj=S3cP>sAX72SRiDt>s&i!$Vk$_BRU4@Z+pVaM{AQ#ce%Gp07Bb~*S@qk1BWo8=JIf|(v zCAiTJsE1Asc*t^K6KY37jO=iTai633^0u9>x$zp>R`KF$fzOC5$1Ar&*HT?H5=W&h zu24r_v*h#Fp3$Gnw)Wh7a)6>v-q(pAL}&$LqgwEc858qtn&ZEji{=l^BjYY2pT2Pe z=iTsQo~*ck4rFx=_?UOoqlR#kx>l089wI*B47+$De;sX&Mn`eV$s%DxbTNn7S9c*uZ|#^+am-qNd!U()I@Rka;3}`Jb65`ubQ>Q$xb#)>BB0{Vm({ETQap zU}{KeJDIlf^Fd?dyq(cpN9}eVe~ZS<&7`3LizZ&o4YCDL|BFZu92Ll~s@Kqffwfic z`G{S7QLTpqCP_fEUK#yTIPk>hOnm8X5$HN4gnn6*@2z##o^At=~i)DC3ihvah)!zQVLRK0VwHiAyUahzJn34t7Db{Xy@$%J{<>y_zlpTh zv%$ItBt@&2viV74UIR;(4xUS-x%dTUNZMf#>AB}2H6}blGX_+8k+z|Ct}PIGHf(pR zteyF+#J*K;_M$LJ{5gO0WPS1JI9*-sNtrTj`M0*R)DtJCZHkiXd)IQqvjJTXApd}U z1Qj?wYNqQSj1{*4w{8qT-|oJ6DXkb8Qz-p%HWI>C@8#|2>y6l+A|iK2Z*b@);@Xy1 z8A38vuhI3QapBu&4BbhQaLiQX<&>yctdgFeM|6fs3eA3fV=k|0Y~^oW+sM@bq**pTt|~6&RIPII&`>vaC6kQ`ju)Xw;?^11jXpt$Ca zgi2BNj6Ne%HS;H=DztPN@)$ScL>SFo)xLLUp(i&_su!p$SbSMihFe40S>P^H`CLl& z!sD(35Zr(sLdmmC))a;4u@qLVAqaJ9rroz^$WK%e;4dF;k)vD%l-Daw{RwL1?4H^W zZVUH?frqvm)F7!Z!_xQw!4E19LN5iXjeG|*xVmBfkDgWKW z9zuDJr+H85{6F)^!^z694vND1Z@vmQyZsGgG<;MxHTeqX3BWy}3S#4}M`A4Y9&wIv zb&7E1O=)bGf^>2Q@ePsfwe~O?BVMK)M!jnei$F_1^3B5~i0A1l36nuTWD|LW!^sMU zV*-&69TcU`F_0#u$HxU%Z6IxOn{Ea((-X}8;`9W#T&FA>yEimA(c;(zw34xn(KGg) zWE;A=E4pB!J|}=^fF1}Yn0F8K-wiKcT98$yd=fZWdQRO-9)lv9p4QjQ#R^aXmyt1>cDLV&`(%%13 zf4*tAi1r-}lEgqU9zWvDst|I2(HqU4BNW#gm@ohHyQFekDYfm!VHF}s8*jQXfainH z@z(oIH;%=h&@~GLf*kmfYzMz|V@rFLohhK%y?qVg_fE z=(GGrL}i`*>&fELNj5kTF#df5sDw7$se=L%p>seHHsYZUy6r*sTx5+wmtNV&9wI>( z(FeOj^~$kMkS(p6S>6XEG+8;3GTm5}g?h^Gd>$P8UogcjUCj>=yjXtuNQ`o>m&-98 zIa`74$Q8^gyW{#P3UAeFBajC;`<|LrSjuru;U#+3)$9AAB3 z^AA&1>~PRp7gh(3w+Ec@wR=7_F}0lDU`uci!)IY&A9m~z+^Ejd13QQqo~c93!U5Jp zItPZPu!{Q(D(X60$K3}t%xRYHV*TsWGt*!V!&vGb5w$`4*7BYJ#}&|LTHSdO$@f$l z2*aY;pxp&cE`z78h&D#6|32xS9o?Qh+TY+v<+maKZ1Slcimmob7);8Gu^P6IULS z(9u5IKY6+mE0nsMVLgAa@Mdw}6;tPNiWO1}&YOEgk>x2Z6IpSKw5;qDTJ(IbC2fTp z60039caHqaudk0#Rfb>p%qsB89G-d0={pw2(&Ggq~k)$nH zS?jj+XC|tvqiw7RQ-JVjEqM;8Y>Y??YOk+0yn@x(4TVlSuV_fges^$#GGoZus_ zaUuwD5el>EV7IrP4rK`F7Gef7m!c!8y)%WaU!s6rBrHn$GT701n@g;6G3dZV<$7i$ zH(DZ%eV70X$ABsQX;Ps>4`$6i^PN|aV`@UAZ&#YQQ=K}L=K(|K_VuRO3Jm=A!u%^m z+b9}rbnJE}H1Js9$hyn+!anN21Ia0C-+RRo?d};E$@1EE2oosG4Xx+?fh=O%AUNFH5Nr%2e z@G+?6{cQ#8LPTU>dM>u9UM$kxXRITCa7Yu!npSROKg9Kj@LJ6|j#ZDxl>Z?LDjR1+ zQ#scMOu|nd%IY_#$z;2OqdrB&@s#0K*)H*C?&5)cqb;RBRV>Z|MB`qz^d_(Pyi65S zS=mjq6?RY>C`q(%pd5L<)9}ioRWjLiaFypNw{P&fD_0^+AC|pfwd_IcV=K&qQS}a) z0m3v1%tvA=-oNksyU<$QN(Y4-Gtdl21%Y@j!%r;9e-Z#4X$)_^l$6x{)gjEgtWNG- z&9@tRRC}Jp>|NdF#;kvGsXVM*Kd`D)SU)$wAOHO0*+OY|4$FEEL&r{AGtrKfs zN20lB1L8ot5+4*0I=3xmv1yH%!2Q=neVMX181f0~>EL@_W|IiP4?Nx}x07(g+wg5Q zCoK(MnA?(lKNuhO+4w%vYaYt-!pxa_9KA?Qhk)$1TqTr+aHgipU8 zTbZITVTS`f;LL?BivoXL}5<^t8k6f6W*p4E(%Zg-CMhK2#NZ6f033f;L6q6w~|?a@ST*b};&P+1&Ka2Fa-h1h^yBSQ$Vo~p1y z-+IOXG`lnhPwXu1-n;3##$|Zm3$);gMmPY>lDif>?GVIl526g-ZgdTF;~BZODZ7ju zszDxT$(d`~dRl!E!#|KvS>P_uZ7`PfLVOOVDeqz2AbUIjZsu^tU*&ScgmR zlbCxkKHHmb7xU0sPHd-@&>id!LKzCs#hV)dIb^YB(k|t^9zsT1IR#CI$4`bh0R9t@ zMKKxTAiyZBHK~r?q>p^Rg+eus~(m7g5!j1rpco>ByB~-EAPg?Iy7EMIwL2ZmpIR4 z^X2#Rc&1tSoqf;q^`Wu6Ts@vd5!i8ivwTdI~^^=&VMOCGIkp2R~|{a@l{`RLAXYZ%*o1xsa0lUv&uJ6=X0(J!*O)z&6$F& z9B08Zg2TX(EZ&>B=hje4P~ejiPh+98Cf+u&ec=OX2V_FzYLo7Xvc|`p5&|e2dd^$P!cE7GhVhCJE3F*ti5_hRMwMll0CNKnIJcwRK z^*y4WKUHZL>}|eQ2G76uTS(zms4%GcRolG6W*(cK)pNl%IMpbgCw~=hi{G9l+E{Nu zlEo)!kDD#OsOY(lLVOTU-I~!`*+IV|*L#)F@E|ym`I~&^$6un~(}+PRwE!Y*B~00G z_(3#FKSnQMcc1qh{kiaFfa|q1JKgJCqoICXd`Lc@Z=jR1ViJQhZAdPIJ{v^(=<1gv zybhjZl95*~nk;qieYNeZns;h{F*C79D0|||{|{kr9TwFWb`6Unil87VE!{bEDuPIN zBPiXSQc8E%kdo5jNDLto(#(iRm*hwe-7xPVe$V@Te|+C_UHjVCnLR3U&OUqJ_qx|w z+c40UnU3)L(l$$EO*)C7lG$tufUB8@;2Azm&tqdKH^1eO`(YYGYf;(5G+lCZ-}v{x zx$gh*!jR}y&{+#@utgr*+0S_MHEsT*lciGAi@Rfj-v{~=5E|C8lC{a2E9D{&99$3b zc#Vn4m7bkTgd_(g{};nn(+e0MXq^QS zXSRR7;TCri@aVHmblJMwmC{u5@EL&gwOca0zZs!J)L-Lx^Lj4!kVF@C^1S^$!nE+# zn^EEE3>%8VT&{0g&^dWE!7#S5lEp`Q;MG;UaJiy$DQ@9-g!rP8;>;G)Fe+&f>lqsF z-u-5*yazWS&063wghJ}t{a zW{bG@f-`Qq_~L^2@?ZE+N|e{5krrnqE!NqcbVNe%dXfVu>gWlkFIrbqJ*pmY;Q-ID zAcxdx)>FI;!wq{tFu59Ro8S6PvmU@v>_#eRA6hlOeyjb3_-3`5+o0R;+&Vk$)04@Z zp^w#$dG}gI$q7wtG-u+odbmS>1RS^=;?XE_i9C?+<1{RK;}dH3^Oin6Lesont%}{2 z$ga~G!LCzj+s0D&ceE!IF@ozQNweE&D!1gdOSR?{XqDENSzz{vJN^ruPYdt;1_i_5 zR_vR7`XXciI1pg^XcPQuj7`zSzwU21|JY{o`zDbmr~{P4-t+b32dWkji2kdsM9Pin zIMJS6Q|ZI5I4)sjI#qI6xi`mmgSaR%u^+ko{K%u=P9tT!mC{0y~$H?OX;?z`hlv4R4?UAbaTw|+`grOfaF zpHXcAXD&d_B$`l=ldJBGY6aM8=P$cQP+vAvX5q(~&;pP@@9a{-XazNktYGK+8R5JD z`fRAqSWNL{Sck$`NU@w`Kui(BL>lP`zonVv=`Ri~*m&~pJRcJ?J~H=g7H))ZdbC2k zJ|{k!C`+owbT7v27m{U!|Ga>_+SFI;UE$ygPCK)pU*=^So~FUN#0E9oyiuBuKR)CC zYWHq@SE;w4EoRFJS5RVSZ}^@XL?xgBP^Y^b8pNR=y%V<3zrXF#48mr)Dsr%D#WS)j zBZhROcRqH@Q2ydwYtM^eYn~h=p`4R3Ie7Rf(c?$_HaR7Fl<+skj$YBSz?!0%Gg*3^ zdjZUy148nWKi&*0um%>sFYmnxfLz=%^((q})z)8X{W~XrYohr)Jy61Zy~bf%S5dEJ zQ&=){M+p4vD<|BtUYoFG;$`2=&jr40av2}OZf?C93>(4kx%P`&m)g?%IIM-?V|AT8 zrkKwwd>oJW7HiUvPo`A|A223Q0ZIy}vwVBtt6_u8HuY`rEq-A1so)d+SiXtTJ{unP zV9M)oRc&!y^lFU-R=`6582%>0GMrzH>|>O_fnWF;-Z?1zU|@Kz?d*&e*6?tgBpa

56q4w;C2ru(X|6|h}PwsF!rRsGcmu1Pip$-S$U!JlUVgWOL~bi z@d9LeE$QhLK6pOIap^FK+FS$91$5YwKy;nC zpm(8fz^+>s=5yWxXAr|jV^HXo#zdd7 zT5ldn8eW91^y75J9^NVWkI|n|cYRc@vgq=hFUPMRQ&EsLl$ zdq0$(P_@Y>M50wd>U;`MbIVd3&JX;5GJcf|F6K zdCC|^9GQkt>goB19)j%@A&$&wMZXE2A94lt19E~O{mV7j(nWsOuD)2~5BUPAwC)w% zJD(VBsDpay^i}ehi4`Y)ur6ZBg>nAbU|nmJ470|^xOz*@gq0ly)Gy7a+~9Sa7`T(& z78@%tsMWm`CCrz1nd|9ag-K0DarW$~hW92G;ex)$CB^0{fP(G>bmN!b+yMw`a%Si9 zyz}^9g7n6m%EhEgi#6%%R|nl5xu;DgM=9#cwp-A?v%J2h{I6Oqr3O&5c#nP>hs*wV z33uw6&UrNK`2$s^*(00JI0I$x3hwOozp(U1UG}<5WIV;smkie$U={U^BJ&BJSQY_W*(MXq~)q+`VBo zqX&1*d;l=wD#F+I`BryqdC@9WrJg%x=Y#b@Y%j#&gUm@Yw+Edy-;>BOK{mt1YMtng zg_{pri`AYtA4aaf0X{gFI32qPFyqU=lK&c;+E>Dk%-oxmV&s|uz|*w1RP;`IAb z57uycMQSDQ(O*z*ZTT-j1sCX_Q$G$eaULb7#Kr)<5zGkf6K#+wA^-)_g=5hvfMn6l zgP1-7>&48slZ=6FPLEyXWhEs_Q~!<{KU1T1gVA$weiWYo(9Za@QP=Ii3t;4G{Q4^d z8v*oNG$ubFRZ`Y4Ymhq(!@Gu;!GzF= zn^2#--jHAq;`aA!cIK_ghD_##flM|d# z!@;R=B3BA88~F43A>u|qQ>J4ZIc68Mi0)j^{>PU<@orP{7YUb#g{~hoskN^#Gi%W~ zbowiX`B7C*%;hOc`{KbFA<~m?*H|LD#(QM^#M)HeG8vCwB|@ZkGuex9tA)VhE`0+& zU}1lD8HY*6WR^a~I!`eNx&dzVv#5LACord{NMx4JbNfP(=Gc)~1f0cv!H^u7UhRo! z$8-~Wg0J@lM(D^PKZiYb*(0b>D*dcJd4nS+>>;hWEM|XR3~|3Se#3o_qQKtIoi%2_ z`oUUy#d&raLbqKw6hH9iLunuRgHZL6D1Cq^ehTD_8D~{9 zp&k|_d(B^e=qLVGC?%1}8hoAy_mws-ae70V>=l%*ppISrCka=zo%e;5L=~BF3HOa0 z@)Z6^ZgXR=hh))m;F=1kMo{?Ka|yxEb2xTcsSd-QKX|}DqSzSd!FeiXTbDK}EQ6>O&SxD4_u5D# z+gF_V@9DX$dwq?ZOpO^qlj9}HW0u~K{}P0oQ3O38FQ+%x0=Sv3!z-Nbq4asw5HMak zPH8inK0X7o_j@plLLgpTWD%PaB%Pm^s@%Duc>Sxxd&1w>71(TeY)uscL2YWZyAx+ci9kbco8H{uIjMN%6pCVH1?LXj z%}l5wqjy$Tls>WePG41z3#dzobdimNl(90-MJb%nS-713ULaJvXM~%xWQm%KD>y7W zE~$Edm_XVQqSxV5UB(jeid7)Zv*KNVh9U$wl8$P!9w1 zB_>H!D}cCD#>_?)ZZ`L9k>D}uvzpnI!IaZuzwV&{j*;kMr5Oa5K!H#y9ekHCFZJArqBrzEjFh`PC zl*a$ny&tbSM!2QLOn;@fs&X$Tp1M45Hh6Yl>k<(Dx<1@e{gH@(;0wePeddw92Tpj$ z_4<7y*CXiXPbGh|!n;0RRlqLr82qe7&-Wmuci~Ui1d$%yh&_RRJ^}w4H}KkixkSHx zWi=q~H^zB{n~SBVky%dR%~JVUr9>e>6Q~S)$)iJO<(2M;*lXM&QI^pH#8p(h$$E&k)e-OD@{^Lk+RUB(lp|0(@*Q&8`PyLwuKE2ziE?P#rK>BC`Eu+vw(A z=P@{+rXo2sY7v88yxyeH94=%z$TnXrI)`;hV@K+cg`N_tz?k{tcu5wMhMAV9lZ-&2 zr%o`DKJO4gCn>i>^rh`m0{j8^yML@|aAr>^rxt=VOM-WAh8r?@uW66Zq&USfk~4 zeyy$=RrCweO1YBA9QSZ6PJb4;DBJ8YD|574iEiXzeQQm|m2}0%Tt#_p$!c6ztBuk*?aU?(9+G$fZGEc)+k}&RKj1CBdArV&U zy=wYbQj{me@52>9mT2o?y6QI%(LDHckGz51g+%#|qu(V)SL-wF-LGrhG>57q+0%S< z99m^(`>-O5ZR7NBv1B<2Bf~wacAFK0SLPskC0x;2%;E0$gifN*B9@&y6ude$VC+d; zFaHUa7Oz{|553g7j!b_Bxg923ybzoel!&CIGZFlJk9W-ca>GE;N%4AX~9(@A3AMZ8-@UovVZRvEXpeiW3wI}o5$b|}@$ldSs-aPliYEI|JurB2Sf|8FGw7Rj4ftT@E7lJVYM$hSJy zE?JG*`)vo?>Yr$V3Ql%XEE(q%FN%(-&BQifU3_u+_Kvg4EzHMyMOu($#Zr^)$U+pM zEOPXdDng#TtHF(9i+z#k7~7CN$Ars9Gz-V2C1$rD>Q__xg5qwP9OY9$Wmf#CAP6&~ zi0NFvoF(q&MjI2KX^6gfEo9VzMKk)H{Y)VI%p0b#ne;=8)oI+GZlt&-lze@J#)7-% zW!#fr{6Zxc@ri$gyz&F1lrQ6x5E1~o9v_86|BIhjER>ci7@=|V&(>wNW{pt;#8QM= zz0mqtu}I;&U9K*Bzr9X!Kb}VxVQz6bHj%DdytH zVOLo+@`Yq;^Is#x{VzlrpJze3vybDoD$oCU6!VH=yr-PC7M;+FzyBFXx!cyYWV%@X znD!7g+K+hJV;^4gC0YZ(RNb|BnmzL?QMp-!iJ<*@jo;#W^qY&3ELJGdXp-81=)fQ^ zSMsp;F6oN1F?;*Z!rtdztDQyJ!*R)qgjNG^mTYh9eyxE{8I7n@Hx4*_Iy>j&^nBp( zeBkmtNKC@X%P$Y;ef`?AbG8womvh;~q7g{7O{=dKi*m#kzp|yAE3o}MCoFyJa zssah8R10%qrkYtq!tcQ~#ap5MVW__`%HH2%fBZZ)61Z2fWq>Lu^sF@v)&CP!c+zTc zVRR)oe!$4@AQU=psx8OlHO+Owu8SLPD|SA|<)j84E>)m5uPrEWl`H~A2PDqNZZg^4 z)%b4wFWnDUPTu#97YVKy$BvnLE5nTG$Ev?6eOX8w5zuVj6?HQN8|>oGxqMmDcH}ui z{G6`=Q1$bc}!Zq%y_btm6F&(}w$4k3ieF|#o9=+9C*D`GXic@+tXl=ZzruR?q zM_a&D`Y}{fLLGb`22|q?*ANt)5ekX!pFEl^ZYE)wuh#TQc8+E;`C}??O{5_qbL#h6 z_Y^dG!sxp~kb*yJiWh8w9dMq{50_RgNO}nV{)X{fb1n^GJU{GZcaE4#ED1h_(HCkt zM6jo8tY9czKL&a=2$!_%s`Ww9E%ItJ@kPs_Z&H1+tat89XWh5FnECTgcve+NLejUr zk;t79TX}hP-ipC;H00H82B3!g43~r(R9VCj3r(&7G@3?jpK?e7HoYZ47 z+`1x1q-p8P@Rk+E%~z5p3g zn(`S^h>6|DeIAj%05}r9;`cv2U#>n$T9|DJ75-}mjPpO)E5RuIy)q0GEiHsez5U}_ z=Du{zEbeLVi$Ak-)7Uhhl8LQP@m?!aCY+lnY=OU{Oo@%6b~C2nXnwxhfo1&;P(MCr!qMfr1uHm+xt44R$jtGDP5i`4lG@Xz5Gn^5&6uK z%hu}cdqqWu3&L5GxY1Wo_i&4Cbq3NYKb0t2$rI2_LE&E$(ke%V&J3JF6^9byaOKab9J~GB!P9f z4S9znf~AFr_VB&(zedfSHH$VtF>449xL8JB>YmTQdd|G2za9mwDA){)&!%y^M*2YJ zNPR|jicaw-UX=f<)28u93Hq3xT z`>X{KeXYe6%4ZaKnUt0Auc8B7(~(v)KQQiSZu<=MI($C`WD?445(+YL#Rd570vc6B zfhX;{v!YY_gk@A|E$)p&1ACotKB?wep~OeB{=ff;{$`YXyK^Eknw8<=hbl@*I;qJ4 zoJzR7>k?Ho15F>PtJR3kx~BYAZh;vVMwFOR(<)Glm-og0+~t*K_H|D78NONdklGuO zN>klr=DS-1vsEbn36wX)^*g8UzV9mYNa@IFjwyMU0YGr78<%y?9u`oV>ze*bC>RT^4)-4d!vGz5caVSf=d5 zzFwZh?#W&HS075~6Yzqgwd7q5>ovtbun$oQtu?0VvJ*TFEzfBH1 zYKVO~D)JnPn?c>hIMU1LC4Jyr2;2u@j_ECGezY8sdT(C-mqi3rU7O;-5bavyhH=4v zRcVZ!t;@L##a9P$X-aQc$^>AT*vw-^GlE~xyUiLsV6u2b&(ib$`MJVmZ}yAyE0OyD zA7G4f$Xb^OjBbIV`dy%gAJ6wdpl3tEiiIIN#RX-96ZkRSbw5`gsYgyN8(lazq0sG* zPOxAn{b7hfqY$6U)0f2|O$R(;B!3s&bJFdsrz^kWr$KwRj48Vmie&+9!AquBH@s~PH5q{`uqHFxRCnG`avtwGp-nI)@t z?-0NsRXEsJlXEz=%7`cyj76c-2?V6nKX2UANr{hqHuq*clXCGvd% zkaa)iNMeHoGj{@`o+oDMiFeW*{80bBsqLbhjd;fIiau_d5?rh_@6dmSYE zMPS9mIgndgs%)G~BZjYdls;k~ho0y`deIyEEIcCk4D{gr^r@qL){_PQ{<)=5< zkxW^PxkhT)%;?vz24$mu@Fa}|+oQ~KA5EDlG1Svg@S!&cW^VKhXu|Kcv^yLSxL;&P z9-yqe0s!d{M46%hb4yI{jc|^#AadigcZn!Kea_s2F|~=M!&Jwzyew}2+wwej1dgcO z{sKg>2S*JxLFC@kFzirRf!U5w5|iQ==FaLyH+zkI=DM1!u@Opvo5&~Qa!&M~xmSwJ zD?SI~<%=0P;+B;)0f9Xa7f==S@#YVzFjq3j7h0+pUw2-F4Y*f_Q0`|YodLxY7n4KR zr9cInGt(@hTZ~?R3~g7gV*LlPsX9-4vkhzsn7ZN?&K@Y_;Doo`S>c-4;(3O-`d0R8 z>qX-I*YeQ&=fcOnjF(9#d&*)NZvd!C#h$k?Z7A#ta#Jl3*S#+SyjEA-J2UlJ)7M*m z76>buFubahj8s1+pqhWGwAfVYkgX{6^gaZjS!nQ^d3|$uWq=7{8i0JWmHU3s^QGY1 zg7(Z)!OD~T9B^v#z)*~3av!#tS^7fCKzuEhcn*dJ2-3gVQmK2jquU)$qa8?c;lhY6TPLi z4%2&MnzfRPNb55Y4l(a90lyxAMR^W*XUts84PJFKK-hgVdVw00xLC=#6cBsIlhNE_ zp27+VN)%-2FBtgk!Y{^_`p4ao%|cY_5NWlc`$S8G+(HK2vV0^kyp&$qYVD0RyCv+| z%jP40|7`Q3RSYzD_`2NJp)-X1*S&HNxz88;MX?D4=n^p^Q)!+7cvj5mk_ufaYK@G; zbobk87yna$il99%Z#P*JduIk#oIJ^RA{BU;h>&6dPH74yx zKu1=fBM2ekhr_#L)>;;2x-Em4uC3>1M##{|v72Z92H#OKXO~oCNYwi|R7XxuZ+6b= z?zzI|3AhptH-*EO;5a#`3`l{;5$aGkAj1XfaWvQPZ*QQ%?F{emc;~S zy+(n9-EogRNv`|evI7sSpV3ekyIc9JOxv%WcOj=r1fNF4tMa5pezH1*mK+v%@S|

EPmDuMnAvG9qc=5;X#Co%;G%xGT~s(OVvMapIWSMD$a?D zhP<)oNkP3fZ*6D$NmXFpHsj6pA%oroF0+YAiKz-M*01cCSH!NQq~1W7`qTfi?uDUo zdF`W*tz8xs)#Eh{)JIW#8M$c0p6E{i5lc<&?Ji%j5%~!4+)t8z1Lz95)Qemw0>a-m%>``SR85 zvHUX>q#aE}inI0)r_1=_pn_StnW%FJ9XtcCZRTDg>*u)+>k=G=eztFv0G+)d4v&~T z?e3{qc}n`tUZ+>&QdjHVSYE5HZ=>lna6fUm2jE8SPwI&njZQ)g9QZrD^b zy3b{4e;44)ILQb;W691TteDH(X>LLZA0YK2QT@x8&QO%HOKv^9b@nW?AA(JcKxS=f z!r&IR&>Zmc@?-hQ{JQhq~aeacfUaO5&L(yN9qiOT|d0SH7zb>*(u7LyJ+W10^3H`6iF zR(lo)qSw$AG}GN)wSc}1o-pPF>eKW^Jix{|U`U#P=ibjdW%k?zqqFh`@=mT;&$Ka{ z)z~}JTkdaEE91#}Gab+MhK5GOAhGb*d|=7aP!N~dP>CkEeTPK_KwyzjIsM$Lf~EHX zr7qEE*AS+KuDgk@MnI|@(Z4oVP)aaf=DQVKDZn-q3lw@SOsJyh#4#~JzD?CpO{3vC z+&01=gVf)r<5koDv^!*OCw8KH@a|rp1x}sR$yyu6Q?YR-w9;YTsq$sFi9p4h3^>C^ z(8f;_RfbQ$$C;ZSM6#9^1rldijG}^(eA$y0z%e`mWPx;k(ID75UhA!Epa0ID#2pEb zW-oKD@fw0JdaV_$+3QvV@F*pF*k=<2h0Y`b5g7k_#;bjuB<0Hr*|TY6&xg)@GqE*r z#w7lj?opFO^t-$^-Fk?<1N=c`pwCxVoJHDK=?e^GRNx&)XTNW~JtWgKP}y~W68!Rw z;6J^J%iU+TItwM*i7%L5)&u9~W%HpW?G7bdQ3hs>Et5>#VyHHx_FE{Z1M^u3v4HIe zL!@Q~`n1WsOu-(b5qUExCF(_Z0ABjnmU_($Hb>=(ANiF{+ps@UE_tn9T{qzupZrC-$ZBiMXizzmEgS&*5QcWjG zS9^yZ(DXU1))GrsmdmLs+95A%*l*;RDk+#4 z{7qNco#}NHG5UU$4A8g%Q?}7S7E0H{EAJ5R(Pj;Ztga?rYa6Ou+*d!Gbn1)2Z(W-g zkJq0hP4P!NZU~$34aPsOaU{p2N=b%mxx{EZO$NV7V3zumsZJBzX9i?9r9%ISsf}<& zLA!@>xK0n4*RXpQm#W$*T`WE)eg19*IQyjg%LQd{4Q`88VIAHQgo06HrT4bJrG2P) zz`Cvu@h!gl{yP>){a7Y^`q$dnl1~o{Nq6TyhEP$ylR{rqoQZIhNggxv7Z^8l3-t$< zwZ^`vu)4ABj`4?+%fbTO2YeswgHy%5R^^@hj;LfXjT6|gPZMx z29(Aiz49XEL6F z;B-Ku5}7kUKF^NNR(gR!_F%ShBt|P6P;6>i+h;%iIow;$SkODiV6P^;mp{C0_xrF2 z0Iw03{3HBy?MojrtRLV%$hxu1^&gzb?wZKCYEX&jZd2t&?up?y+^znyJ_YAinVVLb z7uStb*+e0|e;1TfUe&`!)iWmc!JI^BL;yUIjT$yG6ZIV=`MNMwS@c$r<|AjNhuAaE zKUkSpvAH}4CoV$TObUxT)s)mLH=rTv?FZj}$-GU4-+J6hbJ$vgtFxCOnYm^d6IdCI zesGAeiG@hlH`A)uZe1bHq~^l4-W<#wEMRky*PcOP*Y#9kqb(Bep!lhv&ghY8!zjD4 z(9PbJE>or&J22pr!kB@l_Llc&-FnBN>1`Y}kigE4>Na>cg%hwb*PFjBpw7Q(Ws+sc zL#zp{O~QcaJbbuk&a=mVj86Nei073hSW3&{jCNvUN zN2}J#lwQtQH+5>sbttGyq3mV5;);K^&AJ!cs9ak$jBzB1jh+ZxSZ;_;SH8q>^&Sj? z#s0!WspGZ9J=_SA1AEcN;LT^t?QU{q5heinE#|whqK|Um8QPeI8#sLYW#aDJJ%8Om zOiG@0Zs@3ZW%}EVWyWYTd@A)RwEYao>6B1e36B2 z%=i)g-ADF0rjIWxKc(G08z@xxOAiRWnd#`c;;h;+mbgAL-!c~uacbFQB+5(;k8C(z zxq&v=U>u7B=`*c(2Lkfj9uRa7c*2Fb(51c6Va8c(tyWrT6$2>MDn)%u%LaNdV%oLK zIb2b}K#%s;)|ZbuA@J6Nj##${aO^H~`H`ZQOuiH{EJZjSU21%vNwx2VdRXX)&^!4O z1(yzHp0_%WZ%v3sE9XRs-93nw524N9Ic<3k{j8fWBhA4!sS|lw(ZY|H*1sxD67TN& zS(k4)T&`9jat2V2Kwtutcid4HNB;a*ojZ_RU7MqNB2jh_(}5^v`L2zT-e!tDvS@cU z8bq?EHreEz80d`Mn)m$nUv+R*umUuTdrvPZF7x+j_i@!EakyqZzoO(7(mrX$Byf=P zl*(A?-J*6uGk9e{w-ULV>TB_Lb~ja?heRIm4DO_V!YTC*O>{3%k79=i@DV5mSVC?< zbuOkz=MD(j1HENP)v;0Sz5SkwOk5G@Kk|V1Amp+TY#LphE?zBxQ~8M9Ex(Xc8^!Hf z6d6eWVys-tR?xuYn-L_v;UyFYG&5DDi&qJFJS9T;rmyXAU5~54VskNdRf+>MV0F?S z>sljxlAIk5&Of|!DHmYCalm%RO2?=4oaWU}q8w|^xB!JnW%ja?mKRAJJ680xQ-;rP zVxzOi6QRJlZVH=I5;;BxlKl;cBCq7Nxx=P4nqd4u}lhsO1{G%gO`q*#E z%L+69@{n%cfu|Q=ERW=OS?UMnr^PrsIqWzQ7R6it3L~pFJq2l#Lp2*kXDtm)C=MvU z3xUeBtrn<8BsRCA2tCNhF9U;>o>^piaA*uDqSGbG2#mO+Px(Jz7!x${$=^51p!|F# zSkWwmNp_tH<-mgTm2A;t#*U4giG^|-$BLrP9Y}Q8(B+=Uygm9$YHU%EeB}mVXLN_; zPm;UvC;3fBK!E+7^LaAMg|d1?$KicCPnKc8*W@J%Kw+;c`9?!x>sxO3Ms1GOs&G=a zKYVDPahWmtvAn=u<6#ci5e?0PoqR1qT0k9h;Eq}F;x3GQGfSuvIq)7iFptDWl%IiM z^@kG9#J1dv%r&+6ML7I^!a}TW!R?)|%#`E-#cria5>ICeGpPi&fdE;nCb$doPY|3Sy-Fv}8YVI6Xeh=9p_#t!mC5JdY`DW=o$=$zWON(ACI78^m`mF$&Aax^ zyIajXSCW(|&mBTBQRZkY&TReo1Y(3Z{mz0)05Jffw@_@q zq0p0t^U_QfLkaroBhy`@y_1dlL{{m@II3CM2ZZ`BCgNNpuznM}En$gEumNH2gcrF7_^L4kN)fb@1{3!gw z&zW}!0VXuL#qz7TKDV@0Vb7U82kN%)d#Sl&1UYLAD}ovuyCfI zLSH(~nSP|&COh-|UdzAhBWt!G4^&{O2<5^iEhDs;dtE#HZ|F8>gnWa5cF>F=W207B zIl}@@hub^IpA;UOgbj|D9dFd}_*mXv%(R%1&IjQDiI7 zaJEbl>+eA+3VrV>QOJPYXt1Vqhqq4eaUPvZEMz0M{IzNrf3s0iOrM;{$BTt_(s<*# zvbFi^_=@YiBt%{vGH~i6M{?RnK!1!=2LI2K2uF~Q(w~nqXS&7n{J3Ya>=Bj1;cx44 zPXaGH2rL*=d%jfulw2-u9gui_Bju-*HY|d2wb52K-ULSiBBuzW8f!GX%<*?gWJ;=Y zFHi!&(>;k*pe{ls?0(=GoL3P*`_J_2+<}i+OE=dSrw;2bD2bnL2|dM&2=;NZ?+!h` z@UNr{8e8H{xubXK9n`5EBEzFtOjkaDYs5co;rs`0an;w`+YQ-&ElrqrDp_<%l-9M@35d%yVN4H#Y|FS!%r~js|h!ulZ+QpFzqnR7|z{ri15%^-W1qBeM zJOHzyIh41Agi$+jZYmv=c4+1uD`TcMrdIv?GH z#aUk(9cs|i{AtryS1%PVJd?phX^;1D`WPnu;U^`FSqF|=R)MmkYLSf zD%GjQvHue1eFh@DNTVm0J&r?b<``75*Gsvoz^f~Z)Z7=o>;At=M6EC@1TF)%K8ef%N%lc-K(~` zJV%Qy;m-wPB*X0rc@^WmF_^jIgvrd=nTyA5*3Q^Rk9C0PI!>_l3 z3*xRt{b!{HCq3H*8obdU(K2q)NYHiT7ESUgWC(|lc0hzXUOliYyrc|y)I!p$`Vx!r z&nWlX=?XQO$J9*S>OVG7C?J>%2?LpOQoDyp;?1vjg}nH`+?4q4=AmVgRp$EZ)w zC6-M_Jy1|!WZ7~|n_qnWDy8-|L&(~xd(uv4h! z;Jox_9wU5UBOW0y^f53^4|e*?wo`D+@~$csZmL2>hwh4b^m1sGt6wOJJ8ApVO-r~k zhwHg$+4E`HJ85yeZ&jcUNY0nC9@d49=m_0DN0udnSK5xY%*zKBwrxg<33u*=9=mp} z_%aVm1CkX;NQByVJRX4A2nnsft&95wqWDQb;ENj`mHqpc zl&!5R052=oU)J1)=1DUz4F2!v&ucx^1zR}5J^e9gbjLn%B^?!0G*mU-6@9|r95 z@G=KDq(yEwIXXY8OVz$hRq6M``)p_7r-uR}%$+)Tq1uW|gt`7$RYFuPhVHxoM>y+c ztB8B61abP)uY$^!oKMC2`74SN-=B2Qd`K_qNmr7i9D>+_%8T%CLa-v#k-1Up4-_jW zYydXsH9@~CtMB6eB`BF`JFXI{@^d0N&`thRcSfJjF`yV-PoaDNJJ*Us-|Out`|UK; z%7F^RG=MY~KGkdGtdiTf#vCN)XZj2E`D4pK>GHZPzDB@pQw00u73VcKyXT~QSxk5BoGbwko{xRS~{r~Fp7RK!abP9h3M=Ci< zl+x0E%BO)`;eoIV4en)&r;cU!fr@l;~BS{1xRR#2`x z{??bu+9<|7e`i#!T8`?YLn6*&Y^@rzw<2@L_kH5WxNGfq@~xV^r%7z&1stXE*kME1 zi$Ygg6kqHTWByDAl$oC!Sm3eH`aR40$nI?QAXh&zI@4pQY8n{lY#X1M^2&R$2We~x=Edz zwPfnhf`}9VlKwxCrDGNp{251e)6uyP_9D%s5V0nwn**Ew>{h}EY4GepHuK@M{>EyU z$EMEZW!O;!7NS3Eh6roU+YQ}0?i9 zUYu}g{Cz5V!i*99U;a$<5{lG$vjJ)x=seQ0Kg|z_Zb8pYle<;F;EA&C$K#RA;ynZs z^&WT6x@<)<#kC*-+|Q~u&~*N-C6DqFb1a;fr7D~%HD?WUSq@<6K3VEVu^Sul&^k>L z7#r!^Et(-^U{0n?+>6|{i2bn7ehUbft)UV*FfT8$suv^?_Y2%s50^4> zbXIpTd?mgVyY+i9ON8bkCm*;1sh=Q+h2hbcW$#bp5<4(~?%iOjaC)k-4ZfiQ+Sl|6 zXpbIqv)s>;V<>*#NNQYwJ}#sFv3(F1@D%&~)Z`>`t1j2{h< z=LFPbN!I##$zs|?KBM1elgnut2i!i5>c+6}KLl!OLa1FZZOMIlCeCz8A008AVNG7? z02YL&xXbNh@i1z3@agl_>_e5s4rp`TGZuSZ^XKEhkD)X)P3AZfLBOPmIXs{XTchOD zo8aR0Qn{C|QYILES2`c_#ZkC&g}*N!!DjBgLTf&@E-4w+gOTbUA`=Csw^|(~6(Pn7 z-_WP5-vDQ>T%bA?^YyX81Z95jTIIJ1{&KxY=8Ebt&#KN6jiShvdMB&i1@8T-a#u62 z8no6p*_&UDe_i3wCHnBch})D?-kiraeC{UWu%zkO)uU+ieJXxOzP9ysr$a;eCM~Kq zyuYu0<^2fgA+h_^@SV!Y_%3^IQjO=YhQEKwEohzvKJ?_yPmS9tzY=;l+@Brd<`6|T zQExg;IkrZ!x%j;Q&~*AW0@;%&8a1Yxi^ZJRwO;)C^-{u)FmLcNmtkly2d^~AfHmLk z@iIrL+Goonk37y}y-I9a?pxsUyvX3z5)DvTQZ*@e{Q$OPG${wnvp`)DGI2u$50VOH zbY9(R2WnVibx8_UqI@qLInbd6? zl?Q?uU)=0KbtKD{Ai3PH@bsp|+LGKXd>o(d?2k>0!4eWWv-HNwqaSHLYCN?JNmc&i z$aJVNWX+-rd88f|CdN$tv4FX~f3Gn@>^3Jczo@er$^Y_UyS^x);p7YVqr&y*-Jj;9UM|Ly$iOaBXbAA~)nY&xe zdl30qy!YTg%Nq2vfXqy6TwMmw=pJVU&*_e54Z`Pi&sv02m(z_5&SH1{t&2z3o)?8Y z3#Zg4;BIyP8;n=AbH9{Am?Iqdf=aw8i|_GH^gk2cD5s-`6SQN6(v<_#CH4Mt_%415 z$Y_)#O%;o6nphBCiFCT!z#}r*0o8U_K&Z}Y3(SKn?A6P{g&Nun8cB`yvq;jp!@B|d zNakd5yiiu%vlT^S9qQf$0_TZZ>TLe17D)``qVTg2IBMnERem)x_c7II>>lhi0+%S# zash8h3g}6Pf~0u?v_(e>VnCB#D9zi?mzR4L5Q$m*C_%VZpwgYwtB$6}end%x7r+(# znrW;gMpB`Y#UO5$w8fS4n7F58pI(oReF zmnt+_<2k`y@^bN!B{;w^%1+zqReyMV-(eck`3Q*mwGxvMiB{i>e;jyT0;jJ7k|~Gp|A(%t4vXrGwt}Rjba!_*j7Uj$ zmvl;sfHVTq-65cUa$kWW5u-*-klP#_k*KVyH6dlZXs1F1Ns zz6A-xqql<=W60#}wSeB8GVP#50;-PFP@w~HD9|$aK1>~ZOX+(HwFtPwMd9H^FP<8W zTX>`Ro8W9leVsMC&s56JERblVWYM2((z;MCSR$q@#*(Liz=y}IIY1#_y0%24>K0>A zoOq-}4W{%X{v;Dc3B3me+_Sn=k40@tiLl^aV4>6Oe}OxEH9@=GisFn2bWy)oJ8&NE znVeb1*QeZ~^1TX!20=j;Z^M1cjn!GCciif!Yzx0y!g*drmA{}PgR-A}kLPlfFT@Ne zW`MyP$N9oYh)u<0^w8Yu0(&}9J1dZ>W-V|k>@a|aUB|~kCyV+Gj6>HpQ0E&mwH`P{ zz1>P8{{HcNXKvgf^e--mUKp`4c-Szc`Z&N@;7fGy&@%Ahv>K@#&Z}@-FXEi?;V1y| zfxLd1kSqE{Jwojvu#1=_6V8eAnpHHbLS9XoQ!3*`b+Vu46}bZEW}ys;e&Xo^bK85$mh){+@?SOIxE` zw{Y6zx0!ai&J9l8y&bNz`I!SJWOCX>t!pMuNY;R@@eof@GVlY_Qb28o&o>`YNN&sV z+A{pn$anw7^kqVZWlbmh5Ff%9m?0Ht*G%CQ{uZIDs&LrHAwIY-JaDS@aB}OwCdTQ> z;E*N99nkj^taU(?=o#Pn61=EBJd8eUZR^{6$`qyw)xY4sp+c2RNFEQLmvJe@YLMo6>njx0>9%~v5rawbHQ7qrn5(>BNe zkLZa$l?qEo2I@OX`XmCd_5i)`Omc=ee}9{h9na<9ljo0XJfj{9P4*hyw6lK}xqfxC zVos4;8BM0~yY*U^WtTf?Kg#TZr2B2kJS3!aa*5=IKqfdbQSO*!(o~lr-sSU==e;*0 z7W0iJooc*J2QU2bW2t|0ZW33P31qr&a+aWTw>cyC4@*zoKS6AFE2OfEOHe?mOeXFp zKxrWgQ|iox{3G6!C|sQR%z%MqQ#(c2I7QIdL)f_JQQZH% z@oNI_XV^bo&O}=x{@hAV8`HiE;cK_ZMI*tVkL9Ar1xjH7>P0f@JMSS?2(8Q)V8a4( z>XwD?(p}yyvtu8w9D^FpN5gPEVmj+k`ui{NP({A#hVg}bgAAR*k!j}g@*y;R1A06a zhQ45xeWTIAlX|m*tJnGa5v>T#WHydqY)J3OPR1^r)MF;FV#C)r!!s+{H8P-{3 zkC$ZOBO`CSRLf-P@$ZPpZ$k8MK^|oqfpumCzqO9N(6Jz+p29Mi4zDq28;XHUUK}+N zE$VX~QdI~kiTLCFuwridi?0pjbVI2ye3g+9VR8}RT~MOgan)&pi)6*hE7-3a!HUUY zC*EBqg{+RDs0z!a>w^UR@%!Sj_5Nt>X#3?Kj{fq2-BcLANEu*s%fy06P$FbP(&A$V z{$a`q{uscarHGjN9GV?)?-KZ=)gOx-MSm8$u6ME*xgIfvpF5F^_+CSUoop7ZQ@x>W zd(pI$eyKZ*l4m_3QfS&)EQl=h{w0gn?xaZL1Z6_qS$gDxtGUlgzeTo?OoNi&t%^Dq ze|tn3L26Z|6q#1J^IKD`RY|3Vfpljj?E!eY8(=k)Yn31U?na%Ene-&joOm=8#u|1C zf*q}^JEP!5!P1;xz17bsmqK#ayb}anE0GYs4XdaYGVTky%6Iz1Oprd8ISwMRb5ecC zWdKr(QKWvl}F^y=@;x zWErglzeU^Eg$rtp6%>}o>VNz^TNdwSoSWpBbXk@!>PW$e5KCvPZl9E?#X=HF{kg3#EnEz>!0E(M^Oq3R$+WI zxa4#^9g@F2Rs*+=MtNo_9|48J*FDg-E3ok+xdHgVnl3@<(Dm(y7K39K5P{PdzDeCZ z>Wk>O@})}4iaQn3eiPsxlR}A{VL+{L3ouMImD)vnad@=KPAlvigfaLaIbQ z!eM|+4E@b);Z~-$&okrIU34d>F;56D{;P1}PaAKuRxt60g3+Su!HjrhhtS#GSNYR_^ zj1TCr3K5n{(c^Fn#RYMs7S4vg+ZhjIlPi#-A6Ypez1hU_Ywq^zqiq;ZqpsI1Ak|8e zek})YDyuCTIizNz%cSdpFwxb-B1Zu=f+OZfAMUdb-ocIzUf;Kd^`U0-TiYd2>t8Q-Xi zC(6XD7dFa-y7a@824ZeyFC1U8vki+`b(-LIyrM!Fs}1JcDwB}`-jWQoJR&CUjW{4L zQ=2OZi&lsn`om;xZu`-*eU}r;Z}4a70F`BLoIrnnzILoP{YUpTVn3cTjyJdKYVKqC(PM%c`GAJ@YU_Q;T9E5Q|~Tg&lv28Sxf36)p(MKfX^ z(vGT-DaYPNi{TprbuNFdIT}#r^t{;9%B;-TBFkqv4k#F3KNqr@)^LDG%pOE{I`ljHA<1~_N8hEa-))9M z;bpwtp^l@@GF07blxk|aYGN;NS#_nb)4SBu%GZH>9Ij#_meUZ9lzgow&(Y)Q=lmF- zz*|=Kn_|nRe_p#^snDQuWXX`N0Sj|BuhOc6^!jK@MMTlvjFQ1nPvOkJ;%u{GaOYs%$zO({*!UNrCmkiNv$ioW6IIhF zGXUw$^Hi)33#C`v)Np?&~>}qz`^o@5ArtuPf zdpi8SE9*SlZ~bju-_ouuK69CV>^*IcOm4 zqIm|a!Fw^gDSC45k_&HfoJAh3+FNe<^mG(?Tb6u?e|$am^Du^mS?|KFW0v8CfcTVq zYQvGWeS5qkmtsHC0m1syuQ-DnxZ9@(Uk~Nn9T$Ob{`MUfxo;kb^*~#WXZRt?S>Sas zw6KeVkupGvT+m9WtT-XaQa6AmH@vV2-! zeq-^y+`l8Ksr&alZ=6CPXjI=cy(-%-aC6P>^t-6hr3Ro5f)odyCWEb5%Jh2(3>u@1<@F^3)Lw_~J4Oe%|W5Q3a z#-N(SE3x{0d{f4;mEFY*e{d~#LYaHRwpH@m+J9G=4DY5E%6u(t8hZ?xLiVS|Gy~r` z<9jHt`6L-g*f?vS@M~knLUHhk)?OF&1}XX3fJ`|e@~b1Si>e|&UjbCN&)5HvN1kfC zpMHs?A&DR+}X1s=G>lq#_GDt>iW=1-|i*@8ei2NNE})i@tbKA$PobN2;|oQ#jWqq zjaNrYfAcgxKwH35`TonssZ;tZx>8rh{m9zgD_SmMh#`8+bs|D?`EbScBB%ugw5szi z1akW55;i#41+sE|7U{20$yT%7RGH8Uc>Pp$y~I8(a4k%WQhg*7(^c$_8*oxP8PdIT zNd|~X$?9e-Mc~Q$_V11**hN}pDO|G@EcQws@t3RHw|ntkCSj|Uv45*=AU;5_^p&6TJ${o`iEE)Zx+ zdg5VrOGNmpm$lW(C4F}a!^RaIFJfo(j|}s{o3CnVb=eA(`&pkhkAb)lmTGKhH|WvX zx+ctA;cGh>;>ht)9YBaD#A#vSt2$^jxBuM?s`&n6DGLo}tcbzEz_dQ2R|uk}3SpUo z*|1IucJvBZPE2bSCVumQ?+QaUqISSc7C#5PsPhNpPnd+fU=B2Mus_zxQY5pR^wj=0 z_GlsWEa6IHMbq>_;b;#a!))i=|=nIGNLrW}&87?6`~@K8T7_weUG85CIJ{e0iC zQ-6Njq%5;*9IXh0-`eZOe!mUu+;>k%%nj%2X?^CW8aCexUg?hNwagEHjW@J>`-0Po zRn}81ZL1q@8UNth6p4DT$=Fr7gif-llK$uERDWNM&t%kg8+Y*RKJ-qJ`LxY98MoQBe~GrW<+(o~v512j5tFU5}jaI5sReHe5UM?eY_+ ztk~DB*c!l#*_n7?yW^zc zERfm8EOo00Eg686pRQs%ey~eVBjgt-2p?PyEiShlrJ`lqRM-9Ry=k8574G|@_|4^e zV1TtL`S>Lr0Hl>ZdqSBoR(l-xpnHOAE!WUN=US>wWQ6BgY2EH-^-iN~KVHOQuD(1s z3-F#Ea6S`3e$M3D3A83R5M^g1O|c32R1EGC-Fe)oi`N0w;dhPKmGQHIZ~39z6JPe> z0Xn<=7D(zn`|Q1jop{Ic?Tpm7dsX`2mZXVGvFVD1!Iuoi9A~p!c5#qu&-Q16V7t39 z-hn@Ua((^@VaiIt;Oyrmd*-siMWCr3?|a5l+2RWSwEOh@9c0nyIde|s)RmAa}7g7IlIq0FsH+QH)`%@_)N2f&^ywc z@@QSZNrMkaU|u5QdHlc4`<+{hFDWjUvSvlRPH>bbF>f@Gj6{C~&mW;rk3Og8v+Cwp zzm%fpfl?wFfflu888jC!|5{N}o3dVlqwajYBf1nm8`S}IoCVliBd?{akp6StMb~E_ z*38)fnG&T~-9DmDH-p@lC3WLX$j3N}5{a|CcKfgVS)8C$e*3N-ej-_9W|3Ah5`_w> zmjZ^}>E@TlQP}DO4dDtrXxWW!=xUx63aTPaIu?}w`NVfC&FkW_CE;`_pvU$#iKz)@AdZq36=5w1|JZ9A=_h3m@Px4&q4w|!2RJdgex2c2jAnh zog_~11pncSWnf^1`ppy^?~8QZ%kM(B?i{zE+jo`wP}}>5?fa*|+&&=Ay8_fTD?9D! zsix*!`T^~L5ykxb_fdvI%ei-7{)c_0Fw!B<`0pm|Oz{D_Q=eX;u?42l*~vFOwyF>d$3-UB z$8M@_j0Qct-ncV|ng(53&S=IDPpW_?+7D0cA76QRvT0XWi&&(StlwAVYN-@~CKqM_ zdREQyLa*Eu=}>!95~!leGY!QeXaCe)d{SZ>`WUB;L?fDiYp*Gqg>Y!;DiR-X5h0<|phb|vEBr8sQ>2h35EaF>gPnCB zjn4tSMz4RwLU@GPJGUdpwY9qV4^u6i3oS6`_Mr>q!viRlT7pSlC$?4vM4pV!8e!-C zQei1-xAJawIqzf?B$DWNgd0ZXSto>z2G5godAPf4+@0#%EVNeiEzjC47^L-czTnFi zzH~Ec{{*3Lv^G zOaGPvRtYL!!kEGvqb%hAn#=n|R-U?b&N8#)ZlJqxuzO^9oz<4Ub(3{*MLP7_Qi=s- zJ)e78Y6))^eaiUe7~d}$+^>68#SkdE%bVNC5U9z9`$7jN_x$1$0^@vNC=`4&`gO&vF)6Wn2ZRNU8u| z)+X@Pq1eNH3ur4`aBJCb8q<=qg}IVPHb`BndEr>U6i)Ia29&b+ya%EX2H!^svCmLF zZP8bEwcPvldHklnH5xm@z1vsqY^m~iB;aX_Gv8jnqPe26CsUl~4G*D7ItE zM-CqWUH#hOM2uaoVC;I+@mNMsFZ4v#M(P;xxgy^CPcQYtvNF127|vrFr?nBuQHXNMP*t!7~iVpTG{o|=+5msH1gSBWmUk2gD_iQZi{XP6FjX7N=t-A{2n zm#Tkw&T*~`L$xdz%Y@QA42>lFKtem~c$8sW^sXxRq=EqQUX}4)XuhM+;xridE|!Ca z6TWKGKgr;w4EGjkaW~(0K*=^gjiz0IV+00;1ZPF?F}s4VDHv5bOK-;Ik_l$4z2Fyy zA&)9>Wn;_#xyiad&DCu%G)+Jbum&~l$7 z*NUm#D#I2$a_!1k-WBG|SV6h&65V^Ei=Svm*VE*GD=?;X_gpPnV#V}(YyfvEmZb9v z1+!zATwPx-V>kCa6C)yXTJ|SALV`%wC%jGCxt?6>oYQmFx^Q%S7XxB_F5}E2oG*aI zs<9@4=JFb8qP4}GF2^5JdiTWT^>-$>yDs_E;IZ8YF??F=&guN-3{s;H|9Imp+ z&P?x}UJ~}on(;!=)aN6SinAX@GN#gM-#7A;lVkKMu8Mn(RU;tzctbL*Dc+O6j#Y)WO_i={Rfgn;%F$GY=(qhhwLzi4 zKIL>Bc_fgp_r~K;_zN?iqo`dI-<_rKEA}MhFd$m?<9_f+$KoNIj)jljEnVMx$7q)9 z4fi7sfrcs5E`jvh&hg!-{JBb!5eE`9McFx^>WhtJZX>Yu^# zm3%!k<uWq~kVYu#1-4hdJ^t8{`+yVP9qIs6*>$o3`3*4L|hd`4+Hqr}(53T}4~0AiU7_AnN#_jifSr9 zDmIH-R5seJ+BG;g%#AljrLRZLDh56Clr`T}=~0Ke-fBMo9Bes6rNuF0 z=@pK|%O5u3_P6HEUdgx|?lG?e&1EhvxZRZ>lCFez2_R34FeS!xOU{u+9?H9dYMbW= zyP&G+HJ0}c;SGi1^$M<|vIUO|zE^;@iB=P@^BXcz&`Sw_ z(5wBuK1qV~uit(*#rw2)ET{nP5Nw&{ zvjvb!T82bF4wWqeLkDuYr5aXh^4(J+zSz@aK99Y^olti1QYRoly)#7s#$`=HF-Rd( z7^X}uO+~8^6B{Bocrw5P(x-52)qUDLrce)2c#40;|v~_tGakq`jo3TYGeCMAYmIxMD=>yqNP2>3y@EH*!826c%3KH3h z`3?(ZZ0&pOpWm$zk1dfZ=cg3(HYQ5`3O?~Nxmn(Q81^@0vA$1K-b zZHb?P{Gt`EZ&w%Z5OyEO`Tu{A!vA}iso!gz)Y6OJ((hq-@zeP|jQk{{d~36vADSigUaic@sJdLXq&k$8UTu95^e&NMVfNv3)L`Xh<;bR9GP z?k`vnO$lF(#%=byvsKuKF83z53(M6aPwhsXP(a58Fv=)|oeVs+x=b_Xx|x+b|2?ZF z6Z9%AhE*4pXDcIY5Mi_q5~*`z|GXBZLaKv*p*#NtuhN#)IQw=s zo{M&UyD-G|&DGwd?ZL?e>`9njhu&V6T*Z0FH#|Q8-L^fT1+_G&h-|kO|@X1sM~$*Vjp_Ey!8m5c!P|?3Ue5C%2ENLP8PC%f9j2dpP#4^i2XWuu zx!dlpPYRVTW~SXdv&5+WC3@AeAhQgb4!Pk<@Jmi>1w&8j$z*lGMx+qCOX-Q&G{uqJ zgNi-0v6$OK=d~(l(@OzP?@R(dB~)_ykQnUGQP`hjug{NUro1{tuwFf=Jj~{${%~yz0wE?ArrX7j6`h5SFmVSXkMkCc6hPTT|en z)3-=e~cCTD`l3n?-$WFdFV~&~F<75_y zZt*kzc~_EU>9&cQO_hYTK`*XaT_C4xfuMlRHlO!*Luydn?ih{eG^ zRClk2&q&LQHKE|v*6$3XS#!NRd%bP8#)`T2Vs2@7z8-8Ld&H-2!QD7AQ3L6Y)+G*f z*WVmaaS`NIxGH&^w*n%#y{00J7x&d3_-$khSyC19qZL-5K33tz1# z{t+NP|J|VULHA-<3uGX9-wJX+4U43R(Se!Jewq6zp>pAU^TYX5TeeZ!uBW~B$Y}^W z*GTh9{JFudUG~AK_I-86`E`ouox5fs^KsnFqWK5s#nPGvA&Sr$>b^#6xPko~^D7G0 zOWB_S?{$w6g|B`DgX#35)zZ*pfu6=A#tB%ySm_n25W_3Gr{sff^_%mf0m*F0czRXa zhv(iE$Ps4k9C7>>$0c^@LdDLLISb*AM?N{2JG1E`J&m4LeKEUpSN8o`t4&iClY^Hh z1a@;{R;;5;1=sH-u7!K|Zsc7YVzsPfYhgrZ1^4ykN)iT1(t$s|!@`(8kz#{x`u5hz z>hW%1pDr-oehpFnJLTflTfRDfm6pGNq^WBJRdLd$uh6S^ zj$R@*)P3dRZ%t(E-i>5uM088DJn`b-NX2-{iudlsCLPPY?#}w{{Z?jvfUxu%x7KI3 zjw`&V>b%t5D4Oq($SL#4B)1MmMA;8gS&e%PpWL6t7b{uGTA9htZ9kLadHsbkgN{aC z4q2m!h($6>o8_Ax_pAF76;uA{hp;_U4%RDq6l4fd!s!^c|tN6o*OC_^G zXOrk+;LAgHT2o?-;5<|^&Rp|kv?QIZuO#!|X8)ai@a8~})M$=*&uIqkf(7q8^O$Uf zU%GqJ4HOs1s8xRxkLg$OKCK)Rj?zp787E|5%Xx-$0gCV5+q9ck<{$6gnpa`&{CP@l zsx*J_gSz5}tnHMzum8II-u~f&*KXjBb+)mksVZ^OVSun?pk#@xS7ozztz5<7uobfM znu>58b;=wS7q}zt3tudL^v|G`!P|Hn_HL~08_lH0wS4Mz>USdPMC(L4L;dVz#~Fyz zN4fZw#Tkh<5V?=C%PF+s^`~FXZ?3K{L`Qxk?IraXpCas{<+g5KhB$j)2d^(2ohXa! zlaMEVIRau`ft7uGqh;y z_Eg&~y&)~noxBayxuyUpvtR}ItH&9odffPAMJ4ciz$@&1#U((v?^$x_%3u!E(KR8$ z6RSw`zq@OA!Fp(@ygQmDmFwABW2J=%C)PjxHCh|ZGi7b6X&L|a+^L~lhHMS1o7sA5 zFn?;N>I3AU)P;(BrZX}YbBsFfmNmyjCQshmFkrViQMa2?Jv2`9I+3d?)&>FksytNo z=|+%jwc2}Ti$0cBtEoE+Zb9yQ)vCU_^t|tt0pXEI*)n`oRLLpLssoj+sR?emKMCNL z9+{l6VFY@lS}st3aWyr0bWCTq-5hqHCnQ z9lCF`?D2HyGvFDvSSZ3UM=fE@-w3#l@uBpKEB)g``Mrnp{JBkar7W#f=@juQX&#p` z2f)}{n9-1u;4#b}ZTUB&@xVjaiRwoc)y->@N771yV z34afS2n$myEfYHPCLw#7zu-Jj!1`pK+Ibae?rHT@-cUNIOYBuxpMuevRy-HSA>2SZH}tpqJ>2iHZ1hQ%6t zZOi&FFO)QaZ+kC>%)BZuxPoWB+O%O_D3;E6l^U)}0aIG%SoblGvw=3<@qXF#t>vq2mKcu zChSh2Xk9ur{@9yqgaS)}ydBZ-p+p&f$G31usJ*#b8D#yFfA5dM;%JY@ZeB>iNBWrp zH}BoNUMXJyM<>gQSg0q!DAXxQAtAETc>JF(sHcTS)Xh)_$oP7lY$8{02#x5H#*}Hd!pR*O@DW#w}F>0ZCtE0kg$( zl=b9y*S|?E%k!=t)V)qdYb-ICcNkfnU^jh{m6Z~M)?I^1$k-Egr5V&i?fxkPfeL`_ z9?1PyEUx@}YJVTYNz{eVvS^ZjJkR%yc z6LGaPO8Xo=@3YBPvnC#wbx&KE*=?GSVU}4|ca;N1skWU$w#}@?j$zyUFWWH|I}uHG z3#&0TJ(Dh>xiRPM^Uisw9Su&wH)n8>=nDVM$5C@lu&L=T;&*d2=5Bz-ZFkZoA z|5VYbWuji1RMKf_YuFc@MQoI9QR}2Rc_lLA#?;#IW@4@m-mhR#4p(#c%aZp-_45DrROj1n!Jxr! zZ9OlJHfB3RRmayQ#@9X3dt+kXBv;on71uReHBBWZ{XH-#v_D8+A*A(Yv4tmgGdi-j zr9!#KY$AN?#;y%|^q`87Lr16jgGJ2}DOg4gVN&o{OoaveX`4t*RyfRu*_3P9i~vh_ zt29)A_#qq3GqKOk1-e2dpw7fXZ0c$uCYfIPeYlUHpfo=Do%qf1Fm4FA>pL;Y^3p4G zy{(eoUhbH-)*cjf2^4y=FCn^9l@0s(tMLp5ofWkeCN$^Bx^uxuiPc|XG)jRHr4bSH zF#bCLW`OyJaB2;!w>Vr|P?$+tvsLcqDpPg+WxDDoJ2{?<5UH9I+W0JenxQjX+-N-- zdG%0}>emLQ!PeEVGulu7hUl~^OGf;~Kp9T@<_y8ksaTrDi)!F04WVKw(8#&+D6dV~ zQho&R;d*QvrLg#8c#HB6qpOrxNh@9>l~oOeelZEJg{?YNa-ryc&B%&DtUtY(TMggG z+wdl>E>c0=pop)bY{%Se=(`e;zLSBO{DZEW0e|dbi^@wUc+1MqR^w#JQo7CWW#Syh(gt0;SYktF$`m%b!9u9qW@03{MZ=Y}o8y(9^r;#r+M8BHoUQHw#%fmbSUB)GP~B*E zTu)n5CO%fWu43KKQ18Aq0n~gg<2(<^i0+wWPaPS9pF2zA6HB*XyVi^0Lssr(X{wHp zJ3SD1`=^F3T-I<0wG}OoA0@;} zRiXloyYo3dA8)hwo4zw-$y%6i2oVeg5pC%ZZykmgH~cyb6#Oo|#3kdk9g`e(-Ah6! z8{emd+;J6&mo&GJcp2n;8`++!VL5RxlF($N*3QN?@{_a)(J}qe56T$6O{S)CR+3vp zcj)>ZKC-5S^EGQj3w3DG(&1jvk4A>k?_-*2ZIh(7huxz$XS^WG=HIIZyK0P9I?>bp z?$o%v0_Yzx3v}mghLr_yi8S+l&SRgC{~L;T=0Z0eDNpV%)aBBVqAqMUcUC5mpDWJB^R2R!gBHdEeB|8Oo=n0GS4cM7%%_)(`cA1MQ z{FdI{Qi}|zlmS}8fJT8I0VqdTJzdxn-(F52>9dCL5h(!AzS8}eZr%%{13QUOZvcntd^ulI07Kor zGQ}G;?b&};JvB0Cz2e%H|Ae!*@aZL#);MyZ_?FsmO?8NIy&w~SiA!ura zJ0R){du>>X-ChG~Iqz-uy0uw#-L<4H^Suz}*1~CFY}ZG#wTmBp!+KH6zOTWo*<2aW zq^{3j)u0NrgBfC4HRjo7F^DtnfyxuR4dSfX?jUFpyCoYG%8pLUWIf1TOo8@E-FMPX z@^d{}8FT+=8T{kduuY;VW0Kv6q_E#^%0qFDg?JlIHzYtInj)LeDv@MSB2P3rHv6z+ za%RMZJ`E~-06_X_I`u$oo}S}%bGrX_$_z)mW-#*teXr9tDt#wYTomE^0$OUW@kEU+ z4Jvh~^aRe#iQv`D*ANRyEmZmk+DeTg;`E01kq*#!uSG;=w!HhcZ4Yz8B504^T4Pg!`%dJ+=!>32uUB#F0YOHt z*bPC08dS3s=d0OO7`REzvOw!sOL7OKuG0BMNu4D{X}Iso|8Xmn8tVzcyw=;kuI+1U z`E0c(e7@wo$P}2T3HPmNa7gdDrF0O!Zi2>awKn4JUb)~UMTtn~>bvHB+U62$n_8YtA5G`->5>~zhGf_jnQKm(^ z;6VLM$ZPP9_*ppCo2sS53n>}XP%6^D84W#8C?$*HWdgPWNJ-Lg0i#-5?PkDJsTm2S ztDkB`aq#<}$k{L0ltk`~=P?2Y7mtDdDYZFi_ua|nY5>_=UrS&Ey65)h#4`K8GnVRb z*FOSR{WxaS@jn91&7t5~b57?fy;jaxS9K=TE`A%Wzu?_?V;TSrfua>`9bS5o$S3__X5V4uME#C$w;~&BHlHwPD{kZ0oY(E|^go0e3`w$ygE*!YVaageVTH21 zo1V>ddQX>+jJglgNnjTTj!ODnaD3r_TeUa;WGur9S_5-uONV0m@zR$davfqJsVr@h z=!U>Ru5_D=#((@aVgNW+eY#$f_AxO^@G?Gk4prYFniV3+jg7Zd8%hDUD9t8jDHIevxJZ^{vp8a0%J{0clyZR{;vktlV@e=69 zfR8~e+OT0p%H|C4_gQ0rW#*on!d_cn$LEzSUuL9-?3w ze{JJ#>a@ofA!8fA{=Vb! z;tJ0&&f0ulsod{zAbzTJ@p}r0`-Z^YJ?zHLQesdq@18bpSbEP^OJ9OMqO@an!4QdK zT;3rAW?Q_xcWe=HTv<8qq(-qQ4MPUwmt}?ILrJkuFz#izI^7Da?ANdpR&|JeZ`Wn=5l4Hl=`m|Oz`_YsON(?|m3q`e zgKPh@?>Yg5ef%;V0MC6pL{p+H$=J$~ztuV4230Ue^o={jyn9GoXxGMj=p&K9K66p@ zIS*hzy0nx;@8?t@K9>^=_tDJ)Q}95gXbh{w@a!N#NySV3shN(rlOVWXvGTvLg8WHo zSNePGHS$;@3o$R+(b1n3C?u%C?Sy-(Ki&-RT@y7^Ef%HjZM+pQU_oZ`;+q;fv2fuI zd+KwVf>)Q3VN4x_O-Wy%scT=l;ohi+%Rj`lr*Kvq_P@b^^#;I6cCF@|WA?6-K7wpl zqi5g=CXuaOHK$`LW7>cQnTbH!jH*C!%Jmo}WVJ0c;GX2Vi$Am+=V`1$eno!Ge6 z?i(5F^)2h0IcbqPK+@0emFe5?2nxk)g|L6&U7`%sSw)Oer?^Ey$T@{b`UwFh3PX>$ zPe#ir@A+2e_|4?R-*e}iTTa`-u2fAt_Rx*t4xS?x8NKoRZ#16U!`mE|Np64$`YXiQ zRBF~IK&F2B`g9PqRZ-eK+r1F(_BJ7Z-_i%ILpR$8t#OlnmzQjB36BY^A(qqrVy^K0 zEK37NxIi3RJ`&qc%}}6?`&#~pseCXjhYx_MtHM3myRl@~kt8s~4I4`(y#P_go^n;y zuJ(1Q<;2T_qDe()-i-0-KfipjfJ@$juzV20psYH4w7w5)5{r11pjAe>n8}uX4+vl| zWcxiqEN-vDbgT2ovGmK=Gy=`x7tRKXLwSTS;B z5P4UsI!L;(cHhtDkN%DX*9)Ax-qaU;80bGd^#^Q@vk^b<->dqC>bXwU&^qulUTE?Zht3wxHNvzY+1>~=9SWv zu|Cf|-C_Oyw8TAk5%^KGBWX&beP|WQ5BXOvv7sACIsO~jj;E9~gP_28=p__3Ol|GT z}U3%SPw&-=Q_Dm zmODM(`lCBnz22>%FzD+-Yk+tOx<)0_F_rC*-7ayaV7l6}^7f0k>*$q<}Fp9_I3G%|R7bj{v)9(x7^a$?2#KiF&T zCi;c?YFo}VID>eJxt$J#cNjp0%_di`&)L(pS)kl@C3CdbEb53h)Cj$GjmSVjxhKea zU%{fm7pVJ}Oo|VkGx;u)l~SzsxWD@Bk;+Bqp5f~fRsQx_A&U}M^@W=v-H7tH<76n| zp!qy(o+OZ6@)fRo9B4cCSu>yG<|||1gn5NP_LFsg*V8v%qDr@p8^UykBh_j`;$3ha zHUXA1P2Hh^d;ZfZUW>$naXJ@R_p2liPLHMWaROMPV)T zxrO?C11@+@UCsGbI~Nma)puCTI1M^QMxYHd^A{j4Wt2nIDrNrtxP-8AL08?)&Jne} zRrn)!(axzwCH(G2t3RCQPkrwo7Zf8CmcvobDv`^~09B1bx9CD&tA6Fk60a#Cx$O-h?ifwYBoG zx@k zwjHz(6G=(i_)s8@IOYYgF6n4kQ;<a+IhKUGNgws4wlu75j-N<9heRbL^Fn8XTcuxL*D5tXy=2Qw52Nb`dMX&C-tZH;Ncq!_`+VL>r)Q z-a@(x9|rS8tI2P?|3X53KPxKYn%nS3w4q%AhfAy04$!bV7UXN4;ckUG6u!>om?1w`Br2qT#OcK zp8#wo4N>+mr!dW+|Ag!0Nf*IaI{JORj_a9Dg0LqCnr$_m`|(?f?dmPlYC2kkNHV($ zy!+h$$1>f!29m$av(KXxhPso`dT3g!X2Zvby;SBV@cLrHr`gkf#*vkmXUmN=s?2v! z8+hWK@4Z${eCW?-S6ZZY!kU)1%h9%uz45qQg9kT!1iYL^Hn_CB?uyorkHVU6M3zxg z$k9?Rc()yeyL}KjLzB2%Bv{X=WV&>VB=e0aX!(mdRO^2j`|7AF-e_$Q z1PMX98>G9tQ&JiPq#L9glnw#u2I-dW?(S}BknZMuL;SwG*8S_QHICAR&N4T5(w@8@Gm#BbXHUIu0nZB6P$ni(-r%Zm&IiWu z&+P^hiqbJb_MG9b+x*77`S1L?{cb-w!Xo zuv1v`<*LiAb00HC^Rq|G8Ev3#ruFpa91a=n4GLV&x>nNU){dLg9qUhbJ?c&C4Bj3w zn(t){#k_AVQp*&$zl{{Pjjkp}7TiXcun6uagrZff@Pbe6?mvc>f)r=*3-m0A{sopv zsgd(hrF&xZ$D$f9^%a~Jwa(fIetZ)B%94sW4|uao!r)72jB?w zr}oo)>wqcTtDv*J6W2Z`YT3GOId}mnTzz@mazq;wICW=Qnk=RPWdqog9dl$S1UZ(j z@6nAA;`T2Qu$q5L-6|_~2LjW#5}ZDfi-J?QGquLpI7l_q@5iV;Dy3AYjjGa)mt6dn zb?T3VwBWsGA&ZBMQZ;xdwk{z#RXwp~j~no6}eZUo*b zU`mGr@AQAZXzvGc7ITh=Z^@nfh zNQ_n=U>oLf?l?nq({LE!(ps^;vnDJvP-u}1lg@eC!i|v6B7GXfSw<;^;?ysP!3>U? zC8n8!YG$P{&tM8kHK<2OeHzSly{p>%E&WUdR2o`B^*n&B`C?(R5h$jG?*+i|no95Q z19%#oZ7d6*Rt#xpmG4}3kxo<1(YqS5MBu+~hJgqEDuO?B=@F8ovct*-Vq&z7q(7}$ z-hP$Xg1#zx(SBPP@owxaRuW4SXH6+*Gg(${vM z;YiEo%L3MnO}L-3*RnKn(Oo`!s7pWOC*xuq1Z{+EfDVD_@6RLPfs;>~Hwf@wx4h1- zc-J;%dAp1yg-KoQ0K)32+y1YdI1ctoE_RNWhZd7d58@A6&XJY z27!m)jdEI4ND4dUCqWjDSgj-(X!_eItS?2)A+56Jge zJFzR8lX#PD3$zq5HiUm_7Z91SU`X9Iys~+5dajt```pgL>(ho(L9Q;3=5CLB7dIuB z_o`lxNxYzg)BBps`n(5 zEDj}{`_p@}AQR*K4mC5YcOr@w;L-R1%oiJG-7Kg1KTtFdI12N)L0=Y7eExh&9vIa!S}eM4Vrhl@n3sr#Qsy$#^y!@$bjKEajjQluN#?LR6#(?n3q`{v=YrrQ@dpjQ+E$d&&ECtnmH>b zI2bNcO(>Xap4UO!yZf_kun7=#G0-LW-vU)-cRD%tG2ZAyr9pGw#)E#}wXmt-am zX#dFf=7>=y1+i+Iwd1LNr1zsPfg*?0r1FMqG?DErC;no*K&}eOG`QvsuLS) z_c%-D9BwyMB)Ge+h%vi{5vgJ#wj9SrMZ}3)_xlN>#Nsm3v4~Of>3wC-`SK~q$9Yc@ z{<9$t2+PGEfh(L4A4_O8Y5yK2w;3h>_`D&{Wi0>LY*e^%Ovk#2C zAyt3{tt7DHULfdq!a@=TO^5nI|w#Wq0obN!e4GkRU&)2>=P+?z)ed7 z2w+!EdO9@#F6A>-I6&9nDB<4X)xYHAT3-W-L3`AzR!d&-z9qlNP>Caw{Qo@80(*nUX8VH0DI2l`t6gsg)p2$QDr1hj5jYf2Wdu?p%E&|1Ij(sYDQJYH%)t1kPPGlHX6ty_(7*og zym``JiJu(8Oi0+E9Ca?J>31zTFV2Nj>ub>*Uc0or=8k%dfh%b?y=AjtlM zq@e*QqrSE}^eWNrZ_2IIj{3O?hjO!sZkfUiJEZUMVbDBy^OI>00~m(wE-j}(7-6k7 z)mb_al;}nBMfL|z49h!12qSzAQEFLmyvD922Ph*hbTJha^Y>lHjr-DLMI!IWs#8whk~~beZ9sDI_^vE@~Xz1-JjbJF8R&2Z7%t7 zf5bFr&Z~^u&7E{~9o@7K?#+OyB1Ru0B=h5>~7K@?k_)r%3-|XW%3@h-TB{?!W0jv7F%!^vUhW{rJFaR zXPJlXW=oNtY}Zw&q#OiGWAP66vcJpEWkK;Ja!vss1Ni<(@H*Xd(?aOLP;=$ued-V_*C20M#JdEGF_}=jD(So4KV2mrXx@mp; zT9y8OQB+t~)?%gS*ecytUbrDJz}(gkolP-s+ky-(a%KXOGP ze@z-px=g)IebJzPpb11?KPAhP4Po?2;|*0eTfIEMP+ZC-&xTK7I~@r!QLuM%EwnORc8}c_)4q2-b5KG&X>cD#U!8>EQBtj~|WLD-OgPrAY^`UA2AVM)ro` ziaz%z6)&9(i~q1&PO}wZ(Ti*N9I{}NHG%#ot=$;5iumW5N8=3rWf9FMtGlw1mRP{V5 zG!WC0rZcxbPD8z3oE=N=*sn#nte7+werfmP37x4PyQOQ%+-LN@jV1XlH0LJ1?eQDS zYhZ8!)N>wpvEEYDrGax+?hb$Urh09@L=6|(fzlE~*2p{=zNLa#b(?Zix3PcjErD9AUS?1^Zy%=v&9=0r9-rEx}iFJV#Ky( z_z>Zu+k#xm&}A@UJ_Oy>xN)7xB^fdTefIgRt?|ni1XV5oNoM#61`7e11|ZYkf_U~F zHF^Y=1Dz6_s%0H?+#0s^Olqyo%2@5nSoN$76u$@#bT6fd*S3JJ!b+@1e0Y4ePMb>< zP^gLh4R+VZ#^e9)m``=_{v757bMVnQmI_H@y%M`{Vb3hSz7f4>$$JDL6o?naMG%n2 ze)>vD9zw}hSlLP}AEWzJttSO1^=`!^STA^piuN_Y9=j`kq`h^i!~AexIHGoAT}SoRZEd=s4T0G~XO`ERz8Wa9S@-UI}Be z>Tq2$-_4_5UH~9FSF=)VWhr~y19aSpF|{?IuDC#=grD3uD-(^INa*^Q!^>rWb1#->8400XN{Oa=XmR^Rue@wu#lqQ|pl%NgCo`%_sUw#HT^- z&uFjV1^hjeS_0Bq5Q+I#R7H&MnAh(`zJZ%w!iYM7biNq%Zh8PkHb}gA5SU1&Y87jH zO}^D&ZtpiJ@u=7`8Hp@?Kl>C^TKy&qtu+E7f zvQ26-Mbvp;vuo~J=orVPeT5l4 zC#Y~ttzt)G+tC{?W8%zzA!_WcG1}wVSx#>-@-gyUufDlp#Vn#!wgl}jkpvwvNbkKZ zSmu4nqFX;2&9(hjLnjh_;MFxWs(F8wNeIpmj<0B+t;%xWBXFJ4ZApnEbNr37v(krs~6?jin`!TKP6!orDBc7gIB%`lpjn#BCgc%%sndD-tj$JTeM- ztm7#G!JEC> zL)d>dr^g_26(#sh>Z^nif%@oLK@|MSp9e{@pAHUuq2&x8X#i3WV@Tm3-FMPu9*V9# z@BClBWHG+am+T#QOVieW1yspA8;U5QQTB(i4b8bSVxEjw609G?mGlcFSaUvQNf|!dz_u98IN$bGVSnINRSoYs-6o$fWEX znk_$Qk2SRWaO{-a@tP>D9=5c;(O;1Hr=^;_>{F)_r7TUc)n8D1ILxq^d{@^58sVf? z9f~q7)2N7IG_5kiBrMpcmh|0F?`6pQN)tmv?z2k?_({ccHIRvfGA)~bU2MKo89f&O zdtpU_z=Um`Kwem>`~%0*RT#4|M1p9vWnNPA|8OAi*x#f%yPu+AYNd-L(8~}JM+pZR zKuJdwagG#9|JPPQ-DTHfU5Xd(#M7(KB&%=s(|=AxU)j}R;pbtpp4?|WUTpR$QC^L6 zSC(qXY~-Yiaa6tOOi3X^5yj|azp2dEG|dgvhTZz|&MyQ|%66vb_D${mu+o+skopRL z1s zb9VJo;~rl@Qx_z?=DJPn$k#lp5n;nzE7z5OyTNWk;y1&>DaPn4(a5Uq!&y#D@*Hy% z%V+w;jM4pBK%ivjuM5zx6&IhEtA1@Uv)NX%-`l&+14G~T*VCOJa`p40tO$_!qu$$ftyXM{Z9Lh+YtPLbE%Fd4Ku8tc~E)yhy zJ$9E}LItgnx`j^}+!8bl8*DTb{ENkG5jeG_-)!P3YrG}x#bG|kEOY~f6;(m=-=LnG zUhnm~VF=p7FS+_89CKa2ufG@D;X6SaZuKnZ>JZ^C>Z(%D1Po{!ZW~#%3jO1#3;lBCaY8xYAz28kt`W;@D&pCN}U$Xrv&Hj8d z;|D)vT`CzOqZy!YnA0>-@k66NJP=ENdiK>GO^1WwviuipAj3n?ga)sUMdk1wy%V!= zx)aBo1RU~9<`!1D6cl~l(TS~HYZ_i1^s}V--wSrwiw^ijVp3EL;6bgYD1|bsVyE(Y zNiK=Dz>rc_O2#n4U7*KzD#v8q?Kv_vbMuw=;SN*Qh)T?;FO^(j~wRqY364La8&15`wuo=h3r8MbuV)Z`;;-b2P z3*Iyik&5*r~AK zhk;?jC)bu&5TsJK1yc;{_=i*)D3?>$iO9%*^5!*amox$reG9@z8`N{Rh19*OWp~y+ z%0yUq4u8NpvU_V4@-VVD4vU}(U0sD zJK2Mv?;J;nG_cuBaX*1Frs2EDzmPI^X3*ss|CNs)Ubo}9Fc)}t+LP7vi!w3OO!Ub( zCP3jC^&hx0Pe{Ua6jomX#cWI|^Qf559e58q8qyM#?|f&Eej;lg;X4}7`UP@)n@vGN z7`H#?juQD|>I4-nh3h<<(kCb$(7&2m9q#|_V(4f7sxYpX7=nrEY_p+opE2A(&s`sbR&Iln0$iv+rHH5vxN09BCmgH6tFeWw>i`Ca7##bX~&YWyZn;I!!yg%aKWHzyt_4W~}UNik0yTo`G zB*vZ{DC-@KST>5|6q89+`A6&_AkE7Y`NAu&zip=IN9+XR z^OIf5m<5K3;?;r31W#lt6?gm%po*KP(;dMUfV)>818(S> zqqVM2hQ3@cDbow<|B)PzoW=*ZW0*Zv&nuW`0vKmr<3w2c4R>gGTNC_1~Y#owz(yn;Uj~a1T;%g2mf`>O1+U{ zN&F487X>N2Srt@__NG-Kf9;ajNWoO+HQ9xfdy7Gif5pW}p#UqU7#pgdf|+=$6r?`s zQgY}ptpFpUFbmb5P;C=R){9^ zF$wo-%=L_~X}8G*r|`}s5m%vh+hAL^p#I%d`;1g(lQMSx2t{ECkPX2qsH4{g;-?cj z^VY>B)Hhw`Ubsi@-XI~1U)^1xv3sD%D&Pj-^WApY1l1TkdI9CDyo;b`Fx`^3&;Q*F zXo;jQNPutnP`nBdWA0C|j2$D8cyFISurX`yY=^wlJz%aPO21K7%p=y16yF?;!@pbM zmCJRw5Rm+0i0EEOb_3&OSNz_nUSlv#itZwSvNL&?6dZekC6|_vVbK1yKGzjzOIq$r z?D$|O_{Yb4%nRIA{ENgb9)Nmj|7S!v2%m~LwQ-XqbanpBE0d-=GYZ6qY}iI$|fcpzj)u& za|@g`E_jU#JIfs=q^7CT`{{$z;VTmDysJXXK*wo`D=go`N#_EjWX}zZw${-^pnEES3*! z4Ce+A?M^IXChHt#;e`;=V{W{7xwA*)lM)$sM>K5e54J~P{Z#WR8%voN4vA>RB~df^ zCA2L@>O+=F{?-dCMCn*Pro!jPF%5}qq(82Y!D0oz^!7#yX0?w_`-C!5o$+=^V~rSX zNCibObSwaTn9xb>nlD`rmygb>q0RS!m=!fpz<9P;gG^dzxN7#oEiqw4s*0rmz$r;g zLT<&AQ7COvXJvmu4dxZCJ?Z6x^u?LSEz{}7(jPmaObuD$;=+~F3BpDS=IoRE@6`c3 zoGB{#lTWu^G$n2<<2B_^{h9E8OtmTo1h5tHSlRes^s;-Rt2 z_B*Vt1FUF79WX|j$Id}*>y^jv;n(1llF2r}jQDlGlViWOeBoX1J$#SYrWx0=`t5v| zbF6Kdd7ODGHq1#D>aeXS>HwOJZe5-S8gi<%jxmGgH6uyYjALrSns1@R!LMQmh>GorD@N-ID#0l+4E*SsRS)N&p5z zzkllCL?H8BWD(6Us-}5$hmsa=m1e0K|BUL4n7W_`a16>PfW>X2_-~?Ii#Mc~4}cJa z4Y|^u1(0vw$7q4##`Jo$D?~#k!m+2%)E&}buW*C#{YBoY+VF>o3}h)^?Yf7FAPQ$t zQTmQYm?W@});A3_F5y|@7ehr{1nyveZpoP;)R1mwkr}q`bnbMcJ*%!6T)4~>)9G(= z>vh9D4tC-a`|7?W;j$2!y00Wy}={Kw8s>~4vX;D z&(g&VLZ)OK$;XXV1j_kYeog`z{wbguwY|Hj_NV$7a1K+~)mOQWM`JVUG8_yB&JMst zyo&aoqEg0?W#)#-@=(8l&s^{xUIRia9CYV0WY{pH(QBFMN7j9#S2ef}+J{8Nfc|-6 z8<_Q3xb-7K;F;;)PZ%ESd)OLuSDFzAsrKE5b}apy36w7|`>m>` z_-_mSn`cfB(kT*e7>N|p%jbSkIMH{XjjQzBa2N|`%#(7)EDB+PxUrD4eb2^FOKsUm z0S&n;0mS!GWrehhtC7^)y}CBhAk;)!NwLVc^F<;1OKdcZPc7pqAs|EEMU$T0&+Fc> z`VpZcjaJ@^dKQC>YW6m-ABG;k->ZL-PLwM!~DrRWgU;JOclh-or|w^3k7S z$XSIy46I-%+4Y5YPBMUp?G@`bx*qD)QEI1DlKeJA@+8RzS&&{dBB`JyBMEhZ^9udd zVU?+TC%E^36+%guGFtp*v`8a zafQo#()1$>kdXy{jYc{pn_iy;TuZ>K4zZiDIvGDa8Mm^t7Sl>}V^4cJ>Q4E@wWZ)? zc(vzgwdXAlV|?s4nXV$EK*RyuG_J`S=e6?tYKqK(*KAxMzUSUmV15WUI~laJsv)t(nS*S z6Cym8NWPPe$}4Z@pmEr)L0w67EgtK5TcBz~vFGGEnu2~F<=ladpZ9|OPR}*YkKOpJ z_up~vzjFyZu+JKF@NPMu#|XgWN;NvNBSY7db#+2@b?Bd@NMoxo=*5W7ttjSNwp+g{ zu{Hhrh_Jp6<5B^{KASWw*|irM81NuNK)X8GRTo5iZ0$U<`8N^IDpDt=8L&r!1sJ}Q zh+_6&7(7RfA^L3q-|#F#82K>THe6Z*4^Cn(Iu{-uR1PpDcn`;mK>QLpbMq&p5oQ3+ z!dd{Z_WzD-;+aSc^C6b#H8|h+eYis-rom#8-iR<@D(P^P)IH(7j$N81g!L4ec zx7X8jW)BEe(!tprlt2B0#(_6yHI*KQ!k%J6n0wW#=f;IZz8>G5PU{7De$`G8Nu;%k z1(LH7Gne|%Wia)T0+UjV1dxS{6F*)xTJ3TSme>H7g51$v-9ki5pbS|rx^e~_js+&?DX<<;U+8}L(#@p}my@_$a`af;F< zTz7G2j`=Q0Ho=_QkU;CitYgbwhs9h9-i-B7P?n**6=7Je=E}ly^o&p5Bi05_y?|Y`#1{bpCNeG=NTt z)Y-#$EnZB*40`ko<8p*TeSs1ybxDrXsJKoil?c9qp3om z$%dm@Juq8dRp#fG_c}|cY353+?33sRbU6my&U_EE6JJ{yc-Z(rY@`0;_B9x?pFA_? zrC*}FF+<3oSgjqccdo(iN1Qv}Cirt^4dU=-n>GqlI45>eQ0fX3^DZv_p+JJaVj8E1 zCG)gO6vDkprdTyHO2796Iubu9A4RGBGHQ?ga~Af2#W zi6#uWDCH-XqN=7Psq}QGbvBrXKstX`3Q4}JSQ53k=y?%98t5O%(MNc$3q$G@RLlXk0|I61W*jFUUvWJ5{*ubU#`&}!!Svz^O@FMthoeM?f zVyIr;+9*X2kwVxX1q97m5`l4-m6Mv^m<7*51OzD~w6RePg-;c7xm{A)#J|Sfgt<0T zMvjT(%S7PGx<0bX&e(+J83y0dmMHKaCUSyoPVuU=bLLbmoEUX(oVPjQjBQ75z#p@n zbw!&>BQK1N`aGOgJMtfMcf1N7ji=KZrahd96q`zIC%hc#ucN#`U?AJ;pJl@?HEQ8? z%_^UV4p4YIb9WeVf`a`C+JY04BlV_Uu7{mH8T^b zGNY%Q7GBz6G_$hb%d8%fI~&o1GrZxrVSE(iag8G<#au8d4QV3(RV0?fZXpR2WvbZ} z;$5lSOQ~jpTIJV$IH24MO;!b@-YfL6rTXr- z!USY+T}o(cC2ecRa7odviEm{asn3fNPksX4EH7$NemsQpvmAp4Of#`H$QwWRaoB zF3CEFpHdc4wgvm@!qfJuSLW$U=t53YZYF;1v#Y+fxk?Fbck~nENMbz-Fdj-lSaRyE zoaUjE8h7N%1*82u$;Rxw@61FHJ(wsO)f|58-89};m`a?;^f=CIkomQSepVoO?%+87 z!~m`upUG0+R^eC2G)(`bodWaFs>gbtyF622pnvmf1j`0_yzz}wl{(^ad(Jed#GTgY zP!c~aK!N2=g#=_bVxeEioM^PEM`TYALvSwGbZv?FS00xSgH##mC7UN&h1<<79pK?^ zkoq2~f{td8BwcJw#-1bK9zkzu^VlnYf2{nyJmyVhBB)&X8&*T!+C)&sM6fCIt@5aM zfr%hm<=-YRyY$H&p?eC@mJ>H#rRIPb-eMp)5AJLZT#2{}93dP7xQRS!mZ3I>A8&F- zwQs9-N#%P6iUeg5VV%M>%pDKO>Skwfp5mjy+DASM|1;KVg%a=V0|7r9We{N(rE7J` z$YjaBZmd&Sg$d-A;*^M5;LObEq{dHj5qQs4oJM5CYJ&{~qhr4;Z*v=1F+$8xwP0XCl1*t`YR%H4bOWyf*GjqE+yQWC z_BD7=*Dur{H+Yap^$4b@i?W32^aVL8s;-_T8HYE~b1EWep@_OgH&ifOxu@o1Np zVTkCSJ5>z53u}4XwE~gh7J64sJofT=IL2tS`6O1ezWOG-ZaftQuGG`F+1xRxhxD4MBlkGkYlKwdS|(RHhaZ~{*oTjev1&w$4cYxk zO|Eg|<}L9p{xoosO%jnhvX8#TI`Stu?2xU#n9hnGdlM}EYsh6Yo+b~fW@S~ksNkPD zdK-&~4D)NUFxuPS1}aGJJt}lq3m+?H9OxIO#NoDCW*ywCwgl1J#71z~xY(%XkDSZF zI6@__6-&pm4J_;_gG1@`Gc)MFldu0CE+WRh)mutkATP)kk)dRUQWXEg>>liR7Mlzm za zpia0~Pq{2nV&c=2<+kVAy<9)e_7_TWYhD!9fsO2_SaYn&fx4{5s`5QY-t&is_o~=_ zxh8k92|tD|-!|3WI2k@0OsHZqex&4`RGALZlq1mvB$r9<9Ob#Gc1z8rx`@iUiDZEqu}f> z9^xF~TA6y+!8^LwHG_^NNmS|WnPvVy@a>D`nFL5kmA6j5L9PGC9e!ZI;FHPX-9pYOWQ zf$2zPRuiX%4%`5FQrvzq?(8xMIVb99+ojmN((H6F2*96p?kl?lG;_KIj2O8gP0&ZM>YuV^;}e4ZnmhXp zN;<`bNoVCKqHe@CwfTf5P}cjg_a>iXMn9Pc>wf&+YGV(7KdkCZ&G_Jk1Fs)~tYsbV zw%nMj4FX(nTNi4B@Txa;+SkFdtQ^%oIbwR0F+6r6nBT+&a|#YFwgAgq7II#zUcEV=^%|ktM$UL?|b8{+2d=ZiRmiLxs-;}a+b=N za-T^MGT40mASyWTx`7&t9XuZiaTiz3{G!8?EVeC(jtDG`ZFwARid$7=Rj-R0ozLDD(|XO886s>RofEplUM#iCxi5i-Q0(}>eWgssBvs?Z z>=U>zr~mFhIU;F||HDOXZY3)jo(!W_9xAk>kU+Vu=E@Wo=%c0`V5!|n5A0B}9$D+O zmCT{dp$n#iA}gt+nK(uWBU8~RIR^fIwi{`G1AMpR?gbFdTFLZ#*H33Y^K48y2Ud9o z%S(YuP!Wk7&LBRWLSP}nY%AWkW_W(B+XY?dgL?1NWlLr|&hh`a6tWsFDWB*o+S|-^ zg&*{VI}AUz>7=f7WUIQlxHTBmZS3^l{v&E$cOSHOivrn>*d|O1&qW1{cL_^km9N8R z;M#=syiPUu=h2Yi)hs~>mNh%0TgYWuJZ$hK-;(RDvh^%6GJ9Z*YFJ?GyXs%^ zPa&2EW@N9nads2kNfeJ;&Psm89k=8Vu~`&3WW#+j|4I$-y?8rI08cj;?E4+Hbue z0eEryDtYG!|Gi~7c{9DieYnOwuG8q=BkC^RU2z&VZ_RBc$8FYfl&9r5`G@--5%)iv z1%>d+O#Cani(hybqj(pDTQv#vb8OdvVsmR3pXQ6_)#i6(*4&o=wnmyB0)_*3Pf`9- zp?(K5ES0j^`1Lznv<)$G7=aQ3K9!&=i-Fo)2B+`PnSUFc6Y4owO^DI&GoH5MsTkbLQbk1>`4Ie_AUE%9R zsF`*lewlhcx)6*0L91Lq6kh+x>O^o3*8tN;tWiS z5s86r zv02eqGdKDo)fxj%i00V8Y1NRqj}O~5s&>OkVg~g*>NDhfw+33N7Bl1v7k!Q{rtP~j_P+!@!g%y@ zRk`v09IaxV?i`)&k2>82&j;0iF8~Q3fBq4a18hla#O++#-~-x~7MBNx@ZpjhW4|yd zw$>b3{Wwd#UK=FF+n^m-O80TpF6fp|_I@t_+v8#*QA9PilXKH@xXHWY>TaKVnjL>_ zO5j_Cr%}hBdFOhm>k$533;pY`*`!t8_JSU%asvaHW-`mX3Il`PxP4*`X=th$t4zdtRfE0aHS$%1yB3y%w^dO&e~zyt$Ih~58nLpO%|;v_9Qu4m|ImZ zPN-DYSZMH$;GfygVT1_yE8on=Rsxz#UBiD{-EhMj?<4P-VDFXY&$4<2lp%b+R-jBg zbt0Z_6D0G>HGdqYogRw}sBJiM+rF;3y=ZzYI^wQ*T(y26<%e%pJ?%%;zeTmYzlGEB zT1~rwEBk#9`L@;TWXc$DK4ebr=*z7hBDF;H!EwFd`aMN3s=j?+iYxOLoi3LD0KkXx z6u0t}CUf^-{Sb1N2IU8HZiIPS$;@~WUr4?j%;HEd-${NZTEYZ4kB?p13QTsNh$3%6~{HJBqA&R95&X@Z&~|FbH$zC zcut=xHom!nq$~OBtYU<=?@{xxL@#|paRo8hE>5mv?+Vc+227_6VQZ)Did_qD-Qd4% z*%Z(GHfKANSrAu%ah zcwks8P2iux=frhfHEvri*zOVZPwIVD05MvD>UEC zGtWiLp%an_N0W$0*RylvMYcV9R=oA(1(0?=zGHzNBG(8o+1WF0YwDTCAXew^<9GFz zV`+Fa--}S4wrbixRDjUvJaqfwDIw!2agD^^cLvtuj&+M8b^=Kh8}avhx(&v(g*A-; zILam^>RVIR1zFvO42m!uri0pvS3F*=xX#1rESd*xF#I6|I^r|Ssj}R^k#b?jKL^CY zC`ZA&a={C<=i=TGH-?jG+ba=Io@Z6!nVKoE_g$`< z{$$pup~<4_BA>!g(p!umBkBXaeLX~i+wenCXpza+UOd$$;S+7Ox_N_hLC^3yrfET( zmAnJ=B*q>*d@#q!ccqw7s~Dj}EI~t+nik!-PR>}f3ILXWGSyq@U-mjpW9OAUIQ~T8 zfeH+SqO z;BqX!E~dODW-;{sBes(wD(RY77FeqSYI-`A&HwC$0A(-r>tYcyFQa>8!_H>Ojn#m~%`F@?gAm$pQqCz@I-hE5cr(U!S4|@8J@0P7<`d z$}$2xQixNG!b|VCi%^pAnUmGbM&y2iM?))@H8F2cov5YSk4I)>0EoV{qm4{KZ`4(Q4-Jd!$d)p#0iIdYuQXyVlFH@*oMC0CR!ACus2ux59&sWkdR> zqUj4ctM^jY6DsXUNGrs}h`nh}3=*~B584@U-u=?FgopJB`o$=Ur5)?cBtwrVI#XMs zX^Gzn^%NzzQ6|J`-VSMdpwlI5fDfJrrN12&(C95YLjV-8;IUIt-t zZi1q`cgA$};Nd{35#X}}fv^={JzAJ9J%eIACj{QNJ(YCsg&VV_ol)lfRK<)LMdMKK@A-U&-yw>uo1 zQT9OC70=bmuPkww7D?uOOt|s5I;c2Gb=Nr?+DvHr_->MJWZx342wy2}F2RJNW!v~N z6)tNdp{dy0W%_oo?a7}KgO9#rTTkB-A1kbH%;R-Y8`!C_ew?!1O5AoooVHCZv6yAr#&AIVcP{`J~k>^p5M#I?W!Al{AE??rc zXo7Hq1rNa`NbrN;?(Q6Nkl+r%-JJk|;O-tY1lQma+=DxZOK^917vQf~ubx#6TgxnR zyF1g<-`8LF;6%&{-10`8XF6wqQfNjxASKBXXbyoE!TZ_o9rBw<7iQmZhKP+r)(rW;vEum$N-)UU%_xKl>{#gX6w6h8zuBMoVKD76UrO8}y^1 z_BLjx_rW3;@)Qr=_%D^ z!g#YE3@iyg8wTCOk5{!Z)Sj&*q09j!T=qgMnBh7^-*RT;_&W26$;LbNBG`}LChJLD zg7`b-_{5YPPbWkzS4r&^StdnMyzWuZ%v+c4+WNe}Bg}~IH3us<>Vk#Hof{m~XqQ0Z zgX44CM|R>;gZ(k=Ue8|kE*pM_+g(y`{!X7&(hTOUZt3wt)m`|7G`I2tRpWsXWmEh= z{o3Jt*He*82V^OY1aOqR0r1uKsyTRUCd}Wqn~Om8q>G_0dju}xB;XK>&W}pYave?= z(+i2Lf9tL-Bu}Oz8e5%%S|vaYHnY0(3g^=otaml{P1hDrgm1nna??;g_q#;gnvTd1 zJC+H?0eP%8Q7NaWYsF(8f6MyL6Wi-0sQ^ruI`E6)qhP*0Ao z%h1h3U(Y+xdyUE7?|l^!T~@T3n0lXlMc(>+Ge9^_z3;kujF2Q7C!T>=l{+v^>I8#1 zsrQW274b_*1qZXiv+1*gg6uox{DromJ%)KJNLO^tWInsSI`Lq5sqo)H$s-IN`v zl{IdJRbTVh&w5!(==j96T5&_){+V)~*qD^mj*aa1EML2eLtG}_-Dob=B{>JL=cLf{ zn|OwwvKhwMO@aT0)LX%4KG2FB^XV?wX_ z4v^{;lh*fB!qOk1Vg|jyQp?{|8IH;dDfu|*pO16Ra((LyshfkT1`VLD&mbS~CYSN%(fd9Kd1+OBW3TZLk7 zrdyCkarQZ?%rarRMm8$(GUto+-N3(g>D9eEZXFe>2QL4BZ5Ngt=f`s@i6#_6pu5Tr zbm&Wm62ZzJ!z*G`-x%5$dO3~kos31S544H$EazaK`oOaDz_S14ocKXK@dFIXVfcYA zj!1@R?zo_slhf^mHth86XWPGpc&^_`uk4io*AE1EbBg0ADT8UL?0D^Z)5E62D@{c; zfkp`ov|tKi0_j{ot!j&f%g6lfm5tDFurE7sGmm~Hk9}m22@O$T&S{^OzH2_0nCdRk z;?3sd+-8(f<5XGVY1xtef{)uVub*D8yyRzeV@};~x1~-_piWEA@G*Ji?6+{{P z`yLQtdrVeg^zz8%$24MfH?VlAif7CGBqdN{yXli_LQUnoKPg^xGy+n{iu=k!o^g4~ z!@$rd;8#%~?zVBZW`Y^ViW+vDIiAt9$%L^lhX!QFoCTbVF zOvse4e#8?2wr=hBm9ShUdjCX5xTmY3b!n4xdX%?;Tx6#r$L&cs&4t& zN%zCPr2`UryRAQ4c8@)`esfyt@0zG`n1oe)^Tqh z!c1pKM|pYHiKVJG7Cfbj&(Zzf0nz@LogGANFWQAJwQFFNFUI9C7CPQFl{w6EI=bH)UIRz{Ik!n@H4uuB}g}H z_7P&PkGmkbty9i_L$Qy$q}sn{0~SieJ((dB@W$Xfqk$IXU5QGzQlvL5UvlTQrtUJT z#KW#!(ooIsUrhaUC%PD$b4)WUZXfUDk&A^{hCVuiqAV&};Xb47W_NfNNIrAg5Wjnu zb^m({%6($y`gB`j{X-@8da63#mQgTd+i6@ryMXNmeWQ&8=1o~vV2>>4q zT1$fXOM>oO$eh*D8%u+}6$kZLiSvzxY!l}&c2trPH;@TX-SGY@fw|L{Qxo$-!iiqn zP^u3p4S3gVnR92V;@QksS98SUq)suOAO%5m`9HV@P(-lce?{Eh6qY{wm1Q~khZR^o z3f^P7&17%rSCFc5=rTRjKAo{U8+8KEs6X6*;O_N|V*dnXlZ0lG*MVD)2IT;8l2tI39Cu6fB*+!!+h(3zxK25 z(k%}B66B3EI;e5s%q&WkzlhS95BywAv?zUcr7vrI=#LFf5oDLOBfR)YJC>PmNV0ue zcfhd^_oY6#_laN_pqN&u z6yp$^W7-FP^C~=)*y)zdo>uEW0n3qI#R~Q>b%X#$!x~L?oO&Fc$ePi(_u~na5H=B< ziG?d4v`Wok6!o8jEBZL;jQDZM-=M0t=A;0Rwsh(d=cWwVN6e5xTP$2Gld}Mb7?K_T zj!AZVI znd55#v5#>Gg?9v@cLW<37I9}5akpil^=ZJ31>K1S-7j53>DF%hM|PZRcAR_m>finV z<6%I#1I5MqCAWyF`ubolGt&JMt;|nO3wRTRRbe2a)536dr!y}52^+AFhLr+fKC}`9 z{QY|6Ie?#E{9}!%RFF49dhbLeRlc3M01P8L2L{>4r=Hj#;A_rt5{kq#XEv1ah=r+?X0AotwkBFI)4T}Otx^CfU zTXE8&d5phYPLcEvMNe3~H_Tih(jB2ZF(GzMC57z%(^%ONX!~WAXUVl^w`q4SX#Lz} zR)&9r!mL(l(@0^W$_J-U1zK?>SoF0a9*Vq<%w9;bqEowE44&;6ia$Ic3{E~kJQ~dv|H@m?SsN%e zaIQ_`-$PVq+qp&2f}Po>Q9H2fu&4iO1KCPzk}wJm)0SRbIKyuvgOhF=`o>xJLggiH zApkWE*;2c}uEv7Iw0uQH%Y!J*o(yfEBAB}(j=Xr0c8Y;Vk9XJriy*PWjbknaAE_h5 z#IjK?pMBN=;?AB9(kPFJmz3cDA>vDZo+q5&wIW{oYOD{jA$LP_YMc#mVW!^2fCuZ! zT9X5Xtb(QpE=z8V{r<6j>{{Q{h68rBJRaOzgl#0`!MAC(TH_r2rT)rXGd>7d4iv9^ zSON^vZo2N+i0_5-+kY}3*~?x#r530vVj*I$wG1k}+(q|}$-qrW7o3dKH5T`w5#CXR zn$_$<{As`AYn19d>a^I&*n@!v-CaVm54c;sgnh+UX#M1=+CIy(Gy|N&U(<VD$wL-zAe<66mfGOG)2#QMJUd1|){D)Bo36GzB z9QSG19;cvVvBepW&TrUGZJuF%srz}>n_u6NiJ>iquD6LH5{au@Q=dE8R^_mjb$ji6 zmjsdg8@;-Fzo#4dF&HL^yku;~X{eOX?>Kx{T#2VL!1)EVZb+)`slw<&y*9B3c&h0c zU}Hcp-0lU3$#iSN*CXk`%*j8zGJ%sgf9bVSxIyb?6)OLFu@YgQsAf@nTrzeKF!F7rHV-c^na!9v;F<;T^|SnL2U%ao;}YLRU42g zSwt3}9NHU>*ei+-v}juvdf>sozb%PW$}Jwo&&yTc0Fvf^}X0c zsqe00_EvJd1=Tym8W`z9DtS>NXGb^RGg!lno>dgT`f#g-W8|qIveH4&e!p%n+<_?=MpyJjNjM zfY#85#=nqwfcJPS_5H2(Q%E2a-#a3=b#)&;11_i$gvvzOHs555)RXF~l7 z`TUKfX}PbIl^i{pCf+D)K0ottflm>PiJtOfZE~9ZQKw;R6S0a0DphNFT&iQ|x*s3K z&vh#wgp?q(ih%nRn1=TI4P*9W_6_6DN3t6W>WK`H_N{#IZp`nWVIv7vA4*3!+%@z{ zZ1b&v5R}d5Qvi8fa~Rf_d0U6i|E^{nC$d!}uh}9+y)TCH4X{Bv5S*f@ZP2Rl11)l) z138uf#%b6ssF|YavbVJx->X*VLkP9F(zNmJ)o+9#5Z&K4obs&owK)=;GWhmQ;e0E4 z1|*F0_qpXI%2<>nYb`oxzn|yQ+~2z{k5<=1+{1L-Lo38X%8Pf63ATK?p7o@Ki@Z>g zTCpi7@=KpDWL2Y(_$vfse&>tT>`VS!>x6mmi*LnFmc$(;zxNZKWpf10SMIeej67k9 zj1%P2yhPW>=G=@QLZx5QH@tl8wXB@)&Eh#Kvge0FtouT&T|P7fV=qpGSR07{O2uA` z!CpL2am4)4P>8+wqxEvxP*6aSG0`np?gTJeOQS^a?L=t$$S4}c445w?f@KuTCsS=@ z53=|RoAy875%qk@S}eJ5;heLVI3En|+U&u+;mO;Q3yiJTQLAPwfcZ|+m_R6uzInwX z>HK*A27r|4Ntz$N0*H{`aE9#c^7)bE^K~|nh;i~&cr?y6^Q{x+Tj4e)_T>227cDl1 zF3KVaGK%ZZIahcwn<)3(;1(r{ zQ)zCDLt2u_Z1T7No#ME$hPEV&g9piMB%;dGlNW?64`*vHQcBjKgtw=uS}2^Y5DMO7^r zNVSg1&Kf%^Nj|}8Hk&rTpg@8RqMKLb;=F=dx*tfP0JRUhWJqHdLIvgKN^Eo2D>pZq z&xYd??zq|lyn|O2i;w}o#X|dyf2_)ipK?0sPV(`WH0;P>B8Ypn(6tib-M{rq?9Vhf zg9Psb0A2>$P#exLF942ekTJv$wp#`%6I~oCr_`?kLahA@`*<_7e@oMwNZ?p5D_;dR z|5j4=7eh_Y^RcaDo4WJIjITIClS=Vfj`PA`FpmN#>OL)|a@p$OUc>`-CIe@(o>>Yt z)?nNMjdRbz*32>sfC=WutC+?ys)?7g|%{B?s z)uuj10Zc%qi+{)Leh;Tuq>ZtEqHKPB8)Swrg(+VJ(U=PgM2Q?QytwOK!4ipHMN))n zXuNX#ub9~mb6&B+;$mhF(OM$HHT2p9S~0YVVWNbjh?`XSW-%S>gY|{sl=^I5U!*@N z8b^d4WrDrk2j33XJ8Z{^A)!9MQyjiPFOD!@~h=agg+~6#qg^r?wl~0#Pv>sR4PmRoji$?sh zPEK{UgZszXoC8FFt%%6Y+Uf9^boec{M`^>U)-JbKbgvV zizLrexDXiRbLJDx2#81Ad0;=-y@u>W^!9P#AyFZr5rJ4&>qyrhc{t)>C~|#+0lHqb z?GA62i?#N(L@j1w4e(K@FATCj#L@LEH8M)c*z5LhviV+95O+o{9`T*P)?00h1(!V3 z7egjMDr)C^&)#to$VnBECUUr)PVScRy|=iNM51=d7+@UM$JVyUQ9u7Vg~q)DuQU_+ zX3i;cJ0P=SN2>cOepr>F!zWgGX~oXto22`lKT z%D8#6bIX7u=|tBJ$Tud19q25Pt894NbRJjs&kdLq?@s{Wimy&lscXNyWh1Bkn8`_m z{Wf)rSKdfv4l1}wzy&`*uXbgFo=W|XWYxC9?SD-2zX6Z5K0X`1eEs+DEKg)yk_Jmc0loUX@NiO-Xtzanx-;v{&(vs# zX*WSRoP;R&!`oDnyZ9VVp?L86BXkc;3?TVqJL!qY8`e??NaTk~P9y$YPjx*-_j)&I zKvXfIT!vmU*uwySSMNj8WfqTMzg?p)L8j%(`T64P>h53#+c!XOM~jKl6@bQlqVBN$ zF!_10I-eUbUYgUqqdbQTa)&iw;9K-K#p{nL4@xNy;!zRayU;vf54^(3lVUD+Ly}?U z3FemZ#Y<&H6Q+?Oqml`U<`bsbYazyj1U8XmqR-eP6S+`XrJ<`x<^B5;xu8^-Qt1sj z;CJ!AxZ`z|il9to??geA2^@HvaG1h+A(b=jQK(8^sgER0g^kpZqfr?PU;T>~rZS~k z^1FY%ilXK{>wDu>DVhOM#5j3XGAK-)_caL2k}5cF#}eHbedAM~aB>eXShIw&;nHyk z4x}Gc7T!xS5jZ$^NEqHDZW=vW5kAHnWeBQvyA{ig{_(aa7J@v?f~uACzlIWQqhLYZ zyb!~g(VebcR7&63c5lMNq^ex%W*N2GBK}XF^jpvd$F)mgsD1sW;#VS z7JaOXu0!v$w}=la^D?R0%`7tD)ItlrO34;OA>ywdoX}mF`e~BSVV~cFK_qx4Gu(zDD}v!W zFw2U&1#7THG?v!UDs!bBQf5W`>%H;T)#AnLJWaE%*WJRMApnx2#!i~#HB-FR7({&5 zOzdR&+!;xN0|q2!RBpp~Dk3kIp>StVlh;rziu4XkTBPGWl*(%h%CXR}zIE~-zv7tWuSc<=8n#Gv?~1WsbaqBm=mo4u zS9%nP;UqW!;;pm-+;+wt^|*D?WNG+Cj39y}gxt4J1Q|qk%9wp8fhotg53`DSuMNs(^(o>rw|%b{fEqW6YHWKZq?ezJ>- zpQ`&f(yJ5VA>D=VGDC&qI}Jm#nRpwY2ievax=_S^P~j#%z!VFO^6A9S936Huv9cw_ z$P1m?VK7X4qM&E6`_QSSYtXvhY(*W7(L`D&Lh`JIYZABMhMH>><4sI1;7OP+g4O-qOy<%AKBYCl{zfS(;HiM|Ilw!?`l4E*UOepr^ zIGfHtR`QX8JwL3tt+n$|ko;I&LVBHv0JX{#NcW z;|!u;Zrp}wlSI!1t#3%AAJdsL%%~_Kj_u715zleUPi2kyywpUg2 ztVnykNZVR>Kc;1F<6)BFWRl@#(*2SA}V3x;*clZQBuuXbkZN zF{qJZD^bVA?I0w`=8VOQTBjGXQCDS1rAY+&X|Fp4nhRSOzy2788)>k~#Yb7D=pboO zlw2iS^v~VwgkI$Rr$F!%uLNhh3TV%;{h@P$Pt#jK32lQFqeqTCO|_74YC;}7odi4% z0Q7!3@rj0o{3cl_-YXOGXL9)VYca!6z~}DbX@66?EGfF>FktSmym7>%Zp9bciZ3{X z!IK{fHU>3T)@jp(oQXCj|2BuA(?y)PiU`5YqVIe&= zW&f+T_bK?q>ELDa`52|!4)ts~gL>Mg?sv86^1=;cGk6qW%%GKjV(b<&;JrL|k&hg1 z5KqVa!RV)s3tDbJpgNk44{Is~ND$HWCN7|-&o8*cmvDI({PST02__ilT3mj(mR$uYk{E5=Ft z$58gR1ykdxwAy^0?v#>)eM(^rqwb+N`OO@!m(|#XQ{J?N?cOi zYY)-`PpRy+_vg|r=u_;T!mTVBIqw~PofB_5tHX_RUxuaQ?yDO|bgT4BA|K?CWfaoy ze=o!L`qK3^H-PoMj@FiYQ zM*OVaZAgz;3cGKQCdx^IrYXpU**V^mF2sDGYz*2|9`mn+l} z?2-4p2O5*U9Kzk{;L!llLda0Zs@Dczqm8UdgZfw9Z5!N{ z+W4f2?!Gc@pm~Z?rrT9?+`>C>ntsWqu*%^1eCaS+)$PTt@RE`vu*y5XS}dyN5oi3q zmcKab>r6tMh2~F$pOk!B%h}aysQB98?A)uN%}xxHY2AuHyU5mqh_-j9!}xW2qE;Pig)9&^92^s1$O2&9qofO%e^aM^=(+_5*aogaJkNG#8qdv;_oRdD7{|?Ic zssHtoOm!#FMSjyWPLZV`x>URcU?2M{t%fdXRwLU$gC%+jb2_pO+dY!H%0jTc{b4LxL^HiY{E$zn zkHa>L>Fld(1ZEP~dT_SHL2V;1oB~32qt$X7?XeNz^Xw`z*AmF`wQ)z_-8`!=2;UfZ z8wox6IZu3!HR{8~O1J&a;1pz8k5}=#X@F@!&CSwG0$2cMcYN{B*AS>G9Lq zzr(+8A$=boAt5&+{3>g_Dd|_!OX4Bw*@B3ItVW0lNEMVhNm^2kaE0IGPB6@VF_~3_ z0;JX{V_3Shv7Y)~ctPP{=WFA+{ZzA^RI^K){65a{v((v*)L9$wU`9*w{ln1S$a2;a3dcL)tDSB{uA7mZB{dc}3lerJOz<3p?5e-O&P#BfnQsLi;#)Nn#H<|yvZOy zBYi5J4iN>ImtlHS8h=5P$-l~#1|K8q@bZkRN*a*(w!HbEByZ0h7e~HwX^lwlf9tRy`a|CNV&}s_f$cP6v17uhhi2Vm2|<>!OVRQpISDb z+S|KXqX$bKAFjtt-`#?+(XYGT6zH+-d}DN7cW(TWPUCdN2Ym& z)2suFX%*FCIEcfHk#Q=E>j;jd*qQ8>37+J0SOR7tbAAC~^rf$#L4-|O&$OnFIts1!xHd$LP1s=(zE#f@BW-FT z55H-N)xMHnXOF4nrmQuKLk9s(TFF>#`XSIf)_xyeq;_R>ETayRnNu~*p;^NbTn?Y3 zoU*}F!5LG*-n!Hc#hBXD!J<>aYqj!(X6d$_v$)ji)Niz@iDN2w|MaNj(E4O$!t8Uw zm(F6W*0&1t&HL?swOF+-zVsOaVRw$7^72g^j?|^h(4V16a4>@;$RdRBW%a_|m9nm? z#Zm{ZF9j0aq51e4WZh+9x5@k`5~|B5lE?1vP(lqwM$)d=p*00yNRMwcJ%F$N16 zeEROL<(K8Ta_&>m@+_Je%^oFz6OJLH@0jJnZSq8scdm-8{N2sm+v(wq%CR0`JZ=+EUC)$Ci~D zE}@(tpqmTc7Gbg>dNKcJi5Leumk4u3@OxQN3j@v0`aSE+6A($kIHdw6XD@OKZwhKT}a z)^4Hj6cMXXyd%RN{_tTnK07;&^9kB5jkyMeFhc-ka&K;#1}JnjJD49sORYA1VW}wL5UsI}+vzYIE5K zM>U>*meYx7FxmRn%9x&|s^7{uo~^3i%NRRZUEE}fjMbuksF-r7ctfBHCs{pon9g}A z-X>7pqu1mE;ynKL5GqX)JBh>}BJOtm3kPVb9$RC{X=rWx+~9kiK~cP`F$G2M>Xka} z4}4eUM>jk>e-iXfBE)&bgdtnnD_xv6Y|j`4*{%#-J@c{T@W{O9sA#NVo#@Otb?vWM zR-)rn7CV~}xxz_|XCXPQ7gS0!dVrAq9$T&hxfj}CQU$Z{*4GN1S|nL@B`5>L$Bi%F z?du=kqwRX|R$+o_e1RAjj(aL63lgb;1a$Y0jGmQ9U@TpPQ7x~lx$jyGDmF41kf%XGuYmB0xh+t5 z_V82|BLSb5AOuBrZ5oCu%Mcj1uZXp7?k188M8qZPKu-^Rc)3GKz2MWeL&`sw&A9^K zYH6!y`-6g7(+sWv2b_;o8_G@DHdmR1^0I=`IEgQLkV(ax1 zqJ4}GDuu?m7RUVQj zcSh>rV)y84Jxk&X{B#QY!+5+S+3@5mK#CWtpC*-9H{Ee!HT$365G1X*estTqJgB3JAE z^S;~CVN@?@6o=rt`slxY)y?;?2sYZCob?@ zCcY;aMk;l%CVEOspnkvE=?ED@YJuXay)fc4bstt2;Ov&L?P|Y7hWf#-0+Gs@#i3|j zgwvk=An>vA6mfLA)5tX<4h>8Jwfs7cO#XMdLaCc~m~YhBjSX{={Sdd~vw?hZK+#ks z8fgehWqzmZPW~j{ko*|seSpu+Z_wfu1ou|=H3ofhjDx0KD5+Mey0E;HC&m}3!9P$T zi`VQ>Lhr|y;UHq8nQ1YkOjz+qf=m7@_7`GH^l=xV*SJ6&VSP zZR_NWL0oRhE#w8Op7WwsMNCQ1SOQ4t3s|1l)4%*PLI5h0A$`>)2>*Qy-3%-Xdf72EA47bm6VM9`V{QNVdT| zY61Hem?9X3YX*rbOYNUFYrOWIyv48}+wX;==XbkG2&m|Esp-W3@x6jRflHK6kE5nD zRc$rbdXyAzzEN$JFb-JLDXQz*M5$=Z?PTZ-dk`w*gTCz(!`_k=iOj5(lk|G1ltC(H ziPAqsTRTZ-5n?`Aen`(oZf8GtzVM%Z4{N>UL7A&J=%!cefWm5cZfSvT9@KBT`o|%eBo;0+`7bqzm?g~R$3L7srQ#@hhJr^6uk@h`V2rCQ_(0WUsRgFQC`kpD0~@3TsF&kCNf#Yn?-o? zt24BGP+WxJ*8cV6awj32JcQi~|74vy%rsntSmJ+eW19?K76iAF3ol^k$(z}U{RNMx zo5m`J?$)V5j7eg}D8Tc@uwgln)QQJUeQ3Hh2qH7oGq0BTU5 zxM62B#_!gfuc8ck$sTgAtlm;<@vZgWe>|Hx%J3LCYi+kO3oY{fg)q;R!wnx0w{0*0TgYt*p;o8z0b0K)l&+mN79qAb$z zTk&XjO-jbZm(e7mvvD?qwyN1TeX>-y2VBvn?R7)K;QMf~eBGEaFt9yod?H38T+t8n z%P_u2ZNJ&@RYtq4(7!j<^GZq0k0wOqO^0;-f4PMULMO(OO1jZf7mKfv>YBP|<2wi! zdk4fv1RDi1{E|jW9`~-bLt5U1)iew1mSw=M@ys^2sRjRP(dhKpEUywN#hk$@!JJ9> zf!XGC02{pv3kkpf?|p1%=V0k7Rer-?uP_o=_nj%n8rF*x33<~S~3W&UsmI4y$uk=7q)*Ye-BmPSZpU$Z7;X8km9jNB@`!Ktz z!$NSBy-!hKBgUGBXYT8`4(PIN>Yvim7=r<=A6JZ0dwr*+W_PV@%(^~raqM#Rbody| zVKOoi$B#MtV-RSCwv&m+?HzOcYt7&AWYIcvO-Rkzy9hWBgDLHW^%*+L=+4R0HiJ%W zttB1&vjG2vtm)QWPm=CV_R@>KV;2xy23&EFTcH5yzCnH?#VBnSJ|Sk(d;u41EaUK0 zOY0WJ(&garlKIAGwAw~z^>O<$Q~R;rP*zAU(Z!T*^kY^hU;~> zYG_8i9&YHs>vR(4*2o%Rpl2N*?g67!MTk_$tUHw`B{*-STLQk60Gn05V0}sO5h7{zh##Z2_B9C zW#cUU(*D(>Crn8yTv&P)-r5ST+{5Xsgqhhww0R9jfFzpsM|q=7jEqP;*^ye^`PD6% zFhso-j45IMq}~EgVA>eanO_X}s!%#MrQgXaK?> z&Yp~bhTljAo()2Nj5U2T;?Cb;1>>z`X!R=d)fD`TpjE|X~=Z>{ThiC3!2H&wfW^rd`_58%3fmxnv@d)Z=v zcctHKOhF+jWH=de2A4m$Lea1|bl%v&cTLzm_VcHP#F|BJWWTo>aqj2P!L5M^9S8X5 zpWO{!%ZS~*dZ!BD9Apc(jId+e$gZ<*od$dl_WY-9-)bM<<2WpK+v4zQ z^sI95xtR2S%D;VeT-Uh7adK0!0rX2M*8O8`QNO?cE<&}ST?HEv^XG4v#^wxDdj5z{Po z;aLb(BpJ{Aw>!COJiPaxz}3Q)JzHI<7=Iqx^uV{gf=Oc`LL2T4+IRd|D2^aVHVCvl z6kEX$_BTR&Z;SF@wA<{l$<3jeqlfy|_kx#ie$Y4EEZGlwl|4%PY}7aCU=9+KTx3MX zO%D;;gyP1bp(h3n-sQHshmXZQVn-KVuPLw_&y`0lPR+({RLd?-GHhR#KDGbHiMMF0 zZnn{)LN3FD#mAzu)4$g^Y4i?w*p-dxlunyRN$^GZO_xSCBrFFcZ}FusoQEzr{sNXD z5{tqJ1zPSL|MqiDy0M}6Bke!YlOT=u>G*#jMYl>v%D#6y?87+ga@h699LU5eF2+Ydstl3&Ey}x_> z3ty~b&Hnrf^;@7XNQkp)Vldwi@SQXqxp;O#HG2M{lh2^%0dSy%V9D)Rh85V17Fpb@ zN<)^4EwVU2Fhh$l84(CUs>}TfTPjY?<}7M|<*aJ}`;zFArO;Z5O?)1}ens=m%e9EQ z{BF8G#L}Ph*pLVfK94%;ZtS3EmFG^)Bt?HS`~CEK&x6ux&%+o*YJ>kDv>jRw3q4CC zy)hDWw!Y_2cpn{bkE33$hp>v7=Aa{H2uzqUHTo`V^c_rwj6)#Y>E|%qf&T;+m36Jm z89~&yD*R+{+};=jtY#Rjvuwtd5Ih!~gh=y467*F(r4#s^kq0*EBrHAuRsmWVzNKdG5hIZp;eOA`5BhJK3O%^&I{vil(l7(ndf#4C|aMM8#s2fx!p<8Nz>KAFb|KmRG*Lc@#O^+F_pcu!9`1412#xQK;KAo45FZ}(#;9_;NemU- z6lgSTolV3j&<7_CEoM)*NO>HDirqEKHtDr?A=90MZM~-8xVF(Y$HX0_Eo>Ekx%%ck zkS8KoB)w?8C*g!{W4wjKfzq{O!^3|VqiI6bNgq1ZCPY^iPEbGH2mbUH{nYYZy!EO5 zcR~wRoV5Azm-FNKJC>&IV-Ll6QrNano3;333Yl+`qFGTb?LbkRM^dehiWZ>P zLeK}EMe)b`d`PGpe0X!14XMuMGTI70JCuI(o`$G#wa=;Nn7y>l-g(_h_&lgeqRFP* zcX287A`8)#=GCQT_NvH)n8#~9+Rak&tvPlE+?`FKg0eHQ_@Pb0WQhTE9iI4;IA)E= zsEc=v=5H){$dgbRCajWP+XSMd18%Ae7ah-PBZ+3T}ljgb)Qj6({&-h|zQMQt1 zIB=EVAQ4CN8Ju0aNjC+)La)f(`zA;$lb_)bf63={XJ&uTsV>Z+{nXTjRkWYleNIp!L@k9Kd6YA2G zY@w;HP_$9L%YQf#CMHAeJwaEl@E$;X>~9ZG{OY5FE-Q{ql-Xx2$SO3#j^o{lCT{mi zamZ`vC8G}vm~DM8GbIxe!)(A|tg=~6=|B}ZC=)+E>Tq|cW>un})(1!+DpAW4vCoGH*+3OyA(^mZpnshhFPOacVc~`x$FV6CZ<2S*6_+`N)|UGNU1lOTZ7aCD zxFtGDkPxxruJc~5boESXo!o#gh?pe?uesKZOp~6wwD&K4**e)z7B{WW6)waelbocs zaQdX3#m04S!&9p9T4zYI&Vr3ntyTkItkI?Ke)HKg`Tj`R*xWrxg2|l1w#wqsX<=nH zy?D{ID<8q-V~Fp=lfZn5PkK6%S4usDoM7Gp5qISZoxo$^BdxPL^P!YaN0nnK=1hM&mRdLGhT%oUn$C%smUF=-Jd zOCT_co_7n`{(zaM(zVIZx@l3NJy*dL>mBeGDn(S>HSCXI#1b17+Gd>8M9Y>G*1UWp zU``=b73sg(m+vD%nv(T4OwgUK(kDzD=Q33*U#1{D2&nVpfjx1AA1p_kV3amC*7VtX z$LZ&82;MjSQ86hUkoi_x$2-@JL1OkPYva_9I3WrBjRv`xP6fY4T*(@#q=3k z0P!|-m+Qhno9aCs9v?>X1w_?~VbUJ;+g}N*ry0*WRJY@0oPZr7@(Bs#XwYTNDAREd zYC~O69MS|`STyu3q+s>p5nk!r`W?UOD|)~E^%$|t1(L%f1KXx=EB*)4^J4wGLe%fy z*Ss}NS^11OrPT4q{$l>f?==(XKnRo|Aw>_HVl0L)4k>T}mcY{c@=wd`B|_hci~n$; zb}NbAlt8;nxKSIwL)!ay??xdMWu)|R;mR;;Ho}q>?Daq$%ji*?)G=n^`cdatUuuT9 z_h(LVd3z6kP?n!x#YamAjUhzXDH-0PnTYMd3hh9ER8>`4<ESF3eEJ?8my!J)kV6w590@`!Kd?e$ox?Lm=Z!n<9xg5J-aF5{*l7N%gLoZj2 z=qYYW5U15_YI^;OGSnuQ<=Y00UbbsMHl1U1KTg85D+mZF$?`cOas25~h$fRLkbJfBn@^VZ z(w`3rd=F$79X1cA;gDTb_2Vp0NtTj4>EFVcfmjOmzPW&qzY6mC^#<|GT<(9yyJ}O<1=+*F&;;P1s&P7p6|n8&fjs1W8DUzIOi^9gW4>m$qa0=G5?llJuewdX?0)Zb(_OJJXk# z4;B>yiOoijX3sOFk}9z&;62aNrK8$K})unXL&GPm|kmCNT|fhfLz zZl?KF2#@A(7TzXJtQqKHaO1{yR+iVBf>P&fT)%m4RO%nIZo1<{Xb@JO3`JCtaai4<-pg z91>j6SC9z#D}46D4(zYc{d{XJWU(QFtBeY6m1`G9lK+FQuZ)VLiMGYvEw}{@?(XjH z7Th7Y1`Dpi-Gf_j2o~HSxVyW%%$)?jx8D76*Q!bL zbt%zxQX&*5);et*s?Yi~7uwdFqujg;tdh3KapyMhWz6wR?A$=7!XM-tbEc0J?X`&M z=iZ+gN%466DU8rmaE_XsLJQW;6Bi&oIZWX1Q|RqX}!@^Rwr;%;3XQyzxN~ zZCEN^{VL-u=9uG#OP^+^iISgDdHUz_B}8L3O-OfMK4AHTzcc?GDkk_<{@ugfo%e0} zE8W4`DKOfkqvW+^9|)&_*|WfGrhoO$Uf2OeQA~B3wY;mudf_NnU^{fx`?TqoABp0) zm{zTdyS|=DO-l`jIfUD>e+UA4g0zW&C-|ErLHXGmIg}~k{^o?gQ9GK!6Cid5kTB@e z00`iH)l}&f9CH!o58r^Lhp0LWA$4-+bZW5h-m7)&I@*vKQ?*tBv0ZWUiCOxO4um8ih%RoDC zXW2V?t`8Zhzdw_rrvPbKc=@5i$_Ubxr97mRn|I@D7}ED3xfaIL9#!(F5xouUn6Rka zuHV*$XY$Z>S))-zy-`G?QANG+s^M3rrOQ_IJL8);5vu@)>vjm&HI-9OlbVh%r6>7jN1QH#7m0X@e6!l_ zUk}uqdvR)k6rRT-OMJj41|P7%#Wu@(tU`N3;4QV4{n2S`P3SX^^{p6M5meCN>^X4l zvSgCQj3UHgkkkgrCMwDFB6&lHoMJgK;+>SDcLyRRG5^((0ACV)2f#a&>%un%lDFtd z#gk@6q+QTsR2yOp9`1BYYQHZ-MkMgSBMai|ZwNAA371_DZZUMsyj@)| z%R-mox2J-Ol_t;Ns(a1$^h`zl^b7_w_p5UZTXT=+xejiK)8?ljdQ={Z3B`i?#wWz( zi5IF`@Jz1A9u!DefpClrlJG7yX5M%ojQ7dh2P0NVLaI@NHi2nTXF7#9|MNvJ6AOEF z#J0;5C|fu8#g_F5_XTl{XcQk8UY;4DFwdALvf4MTc#GLP)C=!!fB$c`gE}+it4Xah z9EroC4FoK0oayUD&E1R>Wfy$qMQe05MNzd-{eYqGQhBjeDdc17kmJSRNW?Lwd?S4L zZe063mx3Dq=C_PjtM+^q_Uva`O(*1Bf^t0p_@sXo6fOzEWWvvy3Jnywa1eE;?8_`Z zce{wP;={{wZhVk?>b6MOlGOlm4Rn~k5{yMxnUrOm|` z@BH=&WiyJ*r_1zOvRyz+^U=+FR2u?8fH9a1wunfrjCX6wNlLrC5O{~Mc$YT~t6chR zd>n_Dg)#wEY_(fVqS~iz5M~m3yN$!Uw}rcNzMc@9WdNcX-^T}o$tvWLJy_0h4M5c^ z0D;m5mXgfu9wp-oFLkW2BBK;X3WK^fm~8CqF=fs~6 zK#lvibhmi&(VYbas_cAo$#Afi@&2wL96bPR3*m$U;e<^4=kFAw{b)-In)c?}`9r|O+=O&pn4VOA*-{Tt2))VJw}9btdFl2^HF`_jKbeuo`J zEGhV=km1bR1UhWtkY$V&nq%B3AF5n}l*9{DZGgDAzVgSh4}G|!x`^||e_;Z1kz$*g z4EI%fb8b{;{6Do%+K==|BQMEhRXSBzWyaP_Hfd8N%L=H{FBZKhf|7TlysUwxgK8U} zA^#<_a7$;|qbwz#EqHB>#0+EIX0)3wa1D8oWLXRI+P0c@qQ}TOb_$Q*DQ0j;CnC*PbC*8ns_urM08xp{x z7S!FJANb$doa!YWX)lt7G|22PS`zl?^zc2m?kMz6UNjaqkKai5gA44y$=qHj(zjeR z$p-7lr^Vhfilbumx7wrU-o3N>f;m}d+8OISv~c0@MljUA!PNv@UfKKhjy*p`$W?lP~{!|AV|6sU*fJb6Ujw?Yjm z{e)1hyMi*IlTBid%d1&1j$*x#i3T6Mb10}i6Y%D}p-cJm`b*#b^>=yb-hML8et|~Q zV&ttiN50M36ZwfTV<`N>mviSN@NCr7+t_BRfl=lT$p!Q6JmY+mB!d4kXza&yjnxUM zk`{mqXQ?K@tt3igJDrfi)$EMaQ`H6mOZ0G*{CQ`4{Vx{6nQ1&TT4=b@(otd?Ju0Xv z6|7$TOzF?Qj9Skwt{g)CvMCQkNVuYWN!*ze>o+;_JGB@+PPx0*JS~b`fi9Pzmf$o; zp7Yn*;$4niXyZm|N(@vgvf}&PuDj$1iTBzPEH@MU)y3?&@j4J-hXWu7MogfkR_j*O z=vM`UKC7QBc5FKCaWXGI+l3=YydD)SDJjz*;~v4Zdjrey&5~8CDJJG(L#U3pLq233(!etr7)#%Noz;Hr1DI^_KG5s9-d|Ed+e|jv zug&+rs_KkC65!e8;PJezM$UYS*7Md=cnVw^{P8D_Mf~9B>E@9#hRFwmWXo)flfk*0 z$oGO+cbFP9;pNdC&Neet_~T8RA&0K+`5O$p3l6cZtF|dG8!rU*iRxytv38|u4qD+ig4$b1NxM-!C550ol!s5`FAf@3LxJ~g2 z19h81Wakof^=ZGFEOr4M$1w@E*s#qQV!uu)np@v24Ev#-6|^K7yrGLF_~8@SVZ`fe zxeidBDT^w+-gAzOuTcFOVHw~Q#8ZNQODzv@QG>VWVRT-ok?y_!e_tg&JbSn}bA~|x zCpfk16E0z65$sn%Hy^>pqJrsJW=yv^INzed_ z^8GjHU*v9+`6sI2FmU&3*y@|FXGua{+d1kfrm(Pp`kv1%Q#dp#Z&rN{Sk$xS9b0JV zGVT?>I-b+};oyqR*U)S(Kwd0kUeu`@f+o4Hx;@iTbtQ$ny9)8XhdoddkJWyZntJ*X zzm?|g`ur%;VQ!MmFh{u=N;jc1n8i!(g%&cJwHX55$Y%i_PIL+zhcW8ouE@CEgKS=& z&7O0=0gULk_qpGO$u(s`A)$!F_dtp!FptiudT7m9Q0m>mK3i5YQj{&KrT(c#wuH#L zz;a=;%HcM{H^!#OVmmMOB-wehSRK!+-l7ZSRWbRNpC zD*z*-i=H%~*|rt(A;~>AB!exxmf3%+AhW8@Tr(v`7>CVZ_LDY#DwtT&R}Ed;54si9 zm1g4kz*_Jf3V#b`(7(_(y{{Sc6uI0x=tUH%N0pyE-bvN(DH(`1r{K;k#Nd#vLpb|s zf8h@Qfx+{(LNQwqu%qowu=R2EE)ZeZ+|WB<+jNZ1ZTeJ}TCtH{Ll*fYjwih6;}qeF zn2>ZbjRHu4#i1i+b3VT6FWqL~+FM`E{*+%p^-{$165`WQK?fhaP<#C3OyP9R0Ll~w zd;~>2h8Vnbw|H*HyB`eog?djyIVxBJ7EU7IbMAVzOz^KuR@8F&FlYGK@Msbv!Btwjox`<_?VCxi`ClI$D?KcF1 zWg#YtDiD*X8p{?g3u0_jJa96$009wQPW3(8y9ui7D@8kB?9**GIsw@y{X*c^+YNNV zc)+-NE&tSU^70o~@qH6X4w3~O;hH58#REPym}5urh-)$w)j1Y>C&JU{E~UbrQ+0K2 z@9RvqBH2RnDSo97rrMR;8+l(?mEFtM8f$l1<9z?|LE0U5q!T`unuFCT1;neQ)hW#r zPYX&nzlRBU?y?}r4flE`AW6pW)yW{aG;PfeDIP?Tobcj_n@G2D)}*C`P!PRocF-OE zMA`=d({Rt5DM_AJt0}j1o@u&Y!|n{`0o3yVQ$)J`@4S^7ov-78FC8bFKa=no?!_Tr zZB+em8hDi|xqu5Jm1bRr)_(*U17SGul1Kc&8R|P;qVet9?tvGQQihg3^Xe($2lqga zi!-hpt97nz@~`71qasmHX!gDusUPtrcC!66o~WaA%OZ`27?9mXh0iG#x_EKpN_zgr zy6U80unUBflDNm)82+cv>|8r7cd;ctIg(%h+|b9rq+qm#pqwx&hRVy8x9Q=LwnUN zx)NOb3kEN{R@TclzPpx=&i#HD)65OWlR91{{=E%)bE!5Y`2&~Fnx>i)F@q=s^^Cs$ zO*^RFy~^c!gTSfU+RTD6;en2r#Q`O zO%OvDP&zzLK0f^R?&nAeF&*fn(UrLj0tbCaTo|UoHR^c0skM`Fu0=I5Rx|kq34E36 zLhPEjh-PXg`EWHt;Tx1cCwSDo zz9)CW!_ZWH0t((wmIYZCxYQXYmuc0iSbzRT`)@wuxBPk37D}TpNt7F8&8wa=3cLE_ z6#BR^M3+Cxw+kxV7;G^aY}FWS(HU%8JS=rCC!e=T->49S5^z2-z*Zq3_FCW+Sf31# z`s?_PmGqyk7J+ zrKa%d;nmU5_s#Ayo2K$pEv&p>?)p~3X$J9%%;&vfc1 z2^jw_SVi`z9vi?Ts8m-7Lj?;kzSV_^z=fMCELqp-8d1cfy;U;(zw0WHrLv2q#&X=HlmHCXnjD)xq1#v6y_`vm_`Lmx_?qG+tG}h zeo`NlHA+d45{Ah`@*ezHF3SLhJ}7}*=nB$ez?6(J_ z7MdW(cB$q#6+Bp?_3q4bbf=Ea?(w`fxmHQBRdykm-Ey5Ha-2nXdCe_-lWSE~$gCf) zdW$5M`E#p9C%}9oN3#4)3)qMawNM{G3!SgpDaFFf`o(s~k8}I-e47sp;$C+ueNkT` z4m(0$hvfj|2OY~d2BLo}_W*rIc-Oulj~a2l(MOb@k#E(#Q8X8C zku=Ku%eeZ?u(V3IK-$ThR3rBH4T#lG*sUqVD0~fqCkDJAdS7AT1?XD0yN)haF7kW& zSAn@zR*&(U5`%s^K#m>&@vdl4%CJHc^EHV6P!2Y6Ink}8awT~=j;|R;N0}^h+T@2S zVD^MqvV5iwzh?xMV77x%5Mp%G2tsz~-%nw-F!rawh(e53lF@fWbJ&*;M zU`*oUD!kN@!E`65kW9EAQl@a;!~>&%MY^cdgXy^wNPr7r{Xbh?di&n`1FLICZgqp) zyxRa@&x9tUe;*Kpk6YLrg!f@BQ2+}LiM&seTh@*Vhr;ED*7{oF<@m{qDz}&{)p^7D zTYNZstrW-5taMv8G9K}Bq8YtZ?Vk&=H*SzI`u3pW<9~}DqKT#Ml6lB^cV?lfZME}r z@TS83<6Kl5V6o~<681w?D!M6{1S}M&l+fiBGD5az=0CmiC+`Q<-dBN^>3XX-Oyxc` zQD(bzJe9ZHm$y8Y>v_-mTxoe-YPF#w1E&FsiE;+-)6l_ADBs|5?v__kiG7!EzjFQg za{XVTpCx{5N2pwCnYM@-f2QID!@`}a z8}d!K%s8a>Aqfh1+S%#HPbJML2^M^!D!}!mBhb1O(l#~Ad*ra29Th(TSGiqNSod8a zGUdV>67Jc-S}Id$Hg%cRtZHGksavGp)SS^J6%s>qe=vx z$zDX38;dN#qFvvKghFLFDLdPCPVdyM`7`R$KL4frH!)s=wMI?R+X~1jJ^>=40OeLk zeD~}?tuKwi=kO~BbNpZo)wSji>(3cP2|H^mzGlVte~Op(#z#`KAFkN*I^8B_BPnaM zKATyO6kNgT>%5NW{xa0jX`}9H;OFusWM;9D%;BvSdP)l1AE_TqGP8F3#KM_K-D4sn z6M)VtC(P>T{x~jFg1|!O8-LKCL7$ynUudI&sG-SN*^DFz_ATAS_ShXak^aI@i}chqm7qBB=sFCkv)@uqmD(`70VGDyP7ZdpC zM$TzT9jU|Pn;d)Qn}PO@57sx2AABDo?qy`F?uSEiXw5~mra$ufifqzS2c^aB%t7iT z$vr=NPhG4lrp6@7s^~I{#0FY|6vAsKkxzExKzx%1t`YreM&LqtkMun!Ddahi))&vz zqr_A9u6(r-?29!($t!zxdLvu4&UPs%!lvBorJuk&rVv%e+-hKiw~d&E;3LYbaKc6y zXXI^xjq zm{o}^ECT`^-SC*!Q|yyeyB~GWLJAIys7YEb^eMHmIg<3>CE|6S48~@6#3UEu6cR2q zL^nZ3kb^h39K>BC%)c(Aa{q7?7{M^glAwq65AjZ8zX;)Dsg^bX9Ai(}Zi z`i&A!p4akWEm5u!tLRgP*X=e~Z4BvRXBaG=$vp>yd2XM@GBUZS60zDid=XQd>1v$S zld7~~8Eboz5lcG=YE$Q9D>W$|Y(rkgLID5T%UBEGU;A(8|Nn@{Zx;r<`JV#{torxzlZp2m-XKH$|SpQfazNN2}%As6{QTvG=){s%I`hm*f1Mr>_hV~0b z4X*Dcxex|Z7$p0azav!oLrP%B38{n{N{Z`#kIX3chhYld%ux+aP3oARSXIo+YHkY? z7NMGO5BEb?5{?UC-=(?+RWkDVwtApUfk3Phnz|-A)TmyV+67Y5RbKL@z-p7_`)lMQ zLc=QB7;^$IQ7*U!v~W|yFEA6Hd?1o)T0507){5smv5hXN=p|dlv>JkIS`U0_3GK%; z28-kBa(?=i&^O+gAnTnzOjL`g?qYlbE{;A+MwR>h3%BIGnNjRNP`VCa6kGXZcG z9-mFi75@Gv4rvEBfWJV4-bhhi=tF7s%9k_w^Iw1|cY6T(4)>zHt2e?B+vYvi1_PFY zXauFZ&-Yr(Lc)oj+jz5XoKP04TWXT;^X{ZZ!8lqI<_I+xqM}p|q@;2rW(cIz$uy~E zDWHWQ>fCRlp6-P|z0jA%mZD(JW}^ukq8E~AG=5L49#YI_smDA&-V3D zdtwI}!lYo}hnHWPPL)~Y8%bn>iP|KRLMhr7m+{C;hw5jl-2zx7Mcf2A&;{nT%Z!a(O3>V=?+8b}s_};W{r!`&h@Wi} zyOhkB>d}`){Jn>>a|5a+bcds5*tHI`;6(8AkSXt1SkXSM@$gQVo(E(wiZ7 ztrXSb5o(D->bPVv*wf6wIpH-ON>>4x5uv}TEg%^(#!K!O(qjOC7s}?)JkUXcJYn8W zN+mQ#KYmuofVG$DbC}>Hkn{Mf)R*K1J_>WGF=TSI9M_!^%Y0-`i4(?=0APs#QgDUC zdSVMvP$8ANgauU~xFd3X-{pP0Y4^lI=wuR?%b_d}bZ%Y#mq0!d(Nxvd>T8F(?cudy z&&_l}k1<&)+WPmwIunF0lYo8|LNmCFSSA>92sGASlK2AxW0bc`fY+tW))CeJPEV=) zrDeg+YvK>T|By{3Pz2{A#KYj3WS7D)>OVw%TMWZsrt@`L<9mQIh{^>~@4A;cP*#@t zjc;P4@H;HK|MlKEMj9UgywPR_4YWefv>LgMp7HUHoi~ws7+c2EXnEoRgugnhfs{E# zsG%pzusK-H^z3NM>6WK8xwAP`TWva)P|#PTHR+ax0l)B}ilQ{%Y%|VWtg+?GXkl|+ zvc`3cn{kf$*)3=;T=Ym3rh|neRvtZh{qb*zzF>3ByObaShq$mXeFJ`Id@mD#BoyQN-l5 zK$)l(r=@6_k1ESCLrHKEA9vkXSYR!`icyr=*{gZ8?|v2{u;melD$F9J?G*_V=9AN! zZv4cL=M)Npa?^HrKynE3cU0Lk)gx9Zo@G?u9nzkT=E?JZ1YpQROR3gAGl`0_BxzH$ zDMu$X$&v&Vh*SHDrv`+&V#`FmT`m}3I<71GOMb17eT+<$yM8eRf6SgUI8-_fGP#lg zQ|5PU9+z2Ke*-E|_$drh&DsQzjz6rR@WcRj`FCjQQZ&4J``}?rNd9~h)=P&NVXPZw zUD$)0k!{E*)?o%!tNMrog%LvtJ>`%}hzWi47t*?pj;{4VMn1CjMtVoZlw0FJw!&9G zi5s_#X43`uZXM``P033j^9_=NTO!0tsfS`I&)&1Uj+-_Jtv6Ca$vgCP0kv{5|w!6AQq4m0%pR0KqV6qUrVhTL-K+XE0}LkD zrOiB>iUXS(BKQ#^zQkG8mEavz6Ki4(wR2MaL^zGxgB_XBoihYZmqykDj#?r~4Z*Z? zY$nxgCKvzu=5i7l9g(CX+?sjZntNQ*XGsferz+vT!f>4~PEeq~!iJjs2ZGJ-?>fGI zyq5h``-+Nr)!=f}M*UReP(+NQfnfVsm0G~}wo>Vh~2dY1c3eV_8?x{cdq^K<=V#hyX?_c}BcZS)JTe+~@?szjg`mM&t z9X))KZl7uA_ROpI%rExL>-Wstcm=Gzd}fcXY8S6+AFo7c?=aypAKgH3#C&SyYYlVl zZ|kv`OB1!fPH=nKr)%G_lq)r-q54+5SWcf;`4m@jnqML^!?N0Yh8)wyYYq!Ppe-0H zj8*mZc1I77pt%}nga!0KeEhKJUlP_Px`>@XoH&sH!D^fl8$ed0J$)D6MwW*6PgqPL zdv0bMlBbzi=4|LBPN*VExu-p%O9K=Ob0c<&Kam&21yNK92dU+zSWIGA?i+D^f-abJ zn!eA z=w@@uIaK4=t*v>kw-n@ttGIK9z)7Ep124eO_=!h9ZHhcH;30Lhm)BRR!v@UK9_lz zpE)RW2$q~vUIjw}?P#6N>20*ftdE=@Bd)`K7v&w&A<>R=NOE6?PT)ieEJW$l%IkqZ zE6gDea!BHQ6C-nHv4erWd)kpgmnUp%9TGg8>fK5xDNqw|P#gB!F;2SkF$-(BL>%Q| zjLk{6`kVu|RC=Yg7L!xX9vd z>`Y?=O(4f^X1f1}_6IbYiWTi6nSyO!xo{Kl;*4P-N^F!$*R+HR*>XBl+1o|gmr=Jb zyoet|QH@_K+yFeWUf~5g_mVnmIV|_MPI%p*9^CtQNC`q{O&*U`P5v~gg6lcvzJJ5}{yIQQJ7dzG(uwdFaA+_D>DaJAK+ zG4?&R&8adFkxjf@5to={D~y;O9Cqne9c6uYc{-U2$?dr!XG|%zhZ|@=5%|VkG9_5r z9fETQQfj_QDZAOEa+C1UPGao6ZEQh85M2S;riM?Vg<&7gH+0p)2;l1-2|=6ukVe|9 z6~*$d3Va9t%s@Xjr@KlJ-iwNQ1eob?vnriL=V|?hkx%s-en*k2`z0KhZI5aW3Gr#)-M2#N6;Yls_khgwhYf9(xBC`a+ z$a9kmda^>EJR4>>zs>*Y%`$zIqO)HnbN2OMN~B(y&9ISK1JU{kCRxRpyQxsYKAvMe zt{Mer1|H}9H5;O|#7zFY2rL7-pVw9ZD=%xKf4ddnpMQ_N2&_K&>RexDsK)B>lIm2A zFpfS3QSd-(I5=qHE5O8%+$?Xp=lUY_!6FixNrOypx(m5SztRQ2!kX1{W&yRo`FYXr z{XJ^i=0((iZ7d#;gqGao?r1A}O%O5M8Hi`yy00~#sXoj|w1VNrbC_q<12T8X|cTkJm zZHzVhCJam`hMAUy8Gp{JpKmRN4C_)IUA z=bfE$fG(=-or^=+mNk#5GUnFtetEHvspq<o=afsR(Xn4B}k0~^o^_J+G%hXpT@M}tbExtWRERbKBi#Ag2l`ZD7sFO_9MBr7j_ z!uGq}A;e{Di673)34`egtTZ|G$795H#0l$AlL@Mw`rVL_WfO4u?a3=R;oo8Y0@(Bw z&rtMlgSDg2re@M>9mA~x0uiHi9J9nYfmOUk@bc+e%(2?rBM&^GxFJ*6P|?F{T0gj{ zgqriI4?Oz%w_@S)F2%l9$s41dXk{cVDEqq7f?vx;;mw$f7-&-G!8`@%23B{@S%Xy7%eBYaT$Jf@FkyEDt zhh~683!wkzmBP-}khHQ*9I8 z;ufWKDFB4ib)#9seSvP_PugG&l6;|lu+>jpaA}neG(O{@i>cF+kw_a`wxj!pJy-z2v&w^oPAj-JxR z2J_`qbYt$y{D;e@j2jzVi6M2J#ItC-)$|v^CAWQ>xgUES`@0?BE40Auj+PoZlaMiE zMBJ2J4XGw4Cwi&1%ckluA7;liCxQe=+Bj1^F~#(yxFzSU{zzj%NMnZzO{~t}B@IQO?}9f}d)fGY(Qyxa z-3C&o7rxf7_8I_=D_H9a;zDqC_w77}UUb6AsIxp0;v@y|#i+)5b^Y<|WGECSA#k?kQPZI|}l7mbTlJ zvMtD)H-}$&cULa8u!(|50WH8J#Y~C5!;PFM=8f~jnr&x~7QE5G9(dY9gzHccls8bE z*2s{%SDHok&lfh5A+#ws?9TFUQs>Bq2A_J)B$D6=8nEL}I5+OZK=kt4zT`Jlq|Q%g z_eKA(fS2cWy-0poaGd{B%e()QS|`ztuibbwX=rAXCwzdNio`UB8ZEq{-wiiGI^ry? z!^6}%MxF}QRhy1mN>?Xz#%N-&PSaT!H58M)iybQygrNwS7cLzkpVl$>TxExIfxt3% zSbIImltvSz=$x4}?bXLvSkLXZwcE2IklWF_g7fHBb>X>Ea39q+QuORI%mD%H3 zX(dIUnzo`UFKVsIRb3&EaHd*C>i#L(9q=TN`@=Ps=8^Y93O2rY z`)$?da9j$5AM4mY3F~a3dT z>nlsYM*BFnBF%}@%-7kuqJtG_KK=;0(O-ifG|Q85rFpEot*La>MN}1}5RWK&I;KDF z?y_NwR}mYQ1bL5d`@{{{6AvT&qI^*mPXRe>G};GTA{ zMcoNb={}G&0dZM}?aHPF_Wiy0BFh|G4E*L7jUPM;`kFfG`H81YOu++~9=ql7DKd*N z)DnR#tM+*V-z6WQC3_J;i%zgWS_>*5fY;k&2P)m%Gl+o)Cci}Y`<<^eZ2X-b9V-0Q zA30=W;R(g-_iG?;>Qv=@YvcU2CkGo7b)&)|c7PhOc` zFWcR3S6(Qg0N1Y%$9653--G)@s#~E5W1a)&dC%`7Q9=jI&HREu7`huXgk&~vA}s{F za+#^QndO)q5n}^G%_zzV9#_|KyM+D?RTj6BQqbML@e*9t=}Z`J{RI;Z_J>3{AJh05 zbi$XR_Ff-TG$jT1YZ@9APJxAg9~c0?1f4E2j7P;gj5&7FNg_>Cn@NxuSxwU!`#@bYo_u) zw1+^Alc{^S+^Q9a(y69sqjK7VpQ_%TS=sLA7R@9#kNyRgxF?P8BY-b}m%4{?_Ca3( zTc5kBUFt62j(*`6rjfr}q%PJGzSEJTAD+0d$a{aoSN?75qf>qF-Xfn%6QrElR-I2qI>g4^{4Q&uvx z`GR4j@Ny(}>i&lQp@mdLnd&<4%zQ^?;430#O3Rb4-v^HhVu!sh*F5EfN&f=$?a`Bg zAeZS_q{?48UzJmTD5eVYKFLR%^pwg>ZSWqcXu7;pPDl8yz~WP!aVjS;HQdSHPrARm zqaNGNLL2#nsg{tx)U3jXpa5iFH3Y#hGa;D0RSdyDbANvdU;W zajWX92J3HCm}x4H1U>Sq#5l4`(-%Ou?$Fp`_pB~VIucIM8-6xe@^IDxB&!SU=;tpRTtCn9;@#jpGBCs(HhXG1*w1+ z_RkO!$OXfh+6v+0Q>*vN^F=OO*W*#fdiptcD_%8p#gZqcnyuZK(m-iBgzj$8;!RLo zvCm%;()n7gRwPlzT@7}lt%IA5oEup|*t@8@HA9THK_48m)cpMh|3nu%^aY&l+reTO zbaBgFE(SNl4}B)Mi3bMf#unlmbCJUvub-4zk6Ust$(~DG_Euit4Ey&JHm(S zy9xEDC%4UJw^q-mg>{xcokOv8-?){~jlRjG-`L0C<#|$iGZu`NMJ+%;?{A0$l$Zn2 zAjQ&@m%ZvyZS97fV;)yCIbq*m*oO;Uujf1VTh6keCPAkVvU~QJ!E%P>E-e$ z_6VC%#&hYDEAemQY%ZK57^JrzDnMaTsWX$r$G9_i6E+Gs0QzL9{)Omu@DEq=$I7@4lEX*ZD|OY+`6{}V8-Qb zB${xUjw!`&b?ZOud|J@b*HcwV!#+2f$Us3-c;>xrFm4WFPG1?uFsg|p+nC9>oHX~# zzp8kr)ep~W<@bv6PJdHje)|gc>g5HP(28I~khE#|$)eU}&2({f1v{T&QsBq~e9(`q zid|bmDs@H!pWw2AMKb>yaMpK#N|z*KJC`I05&c#(qhrL=Fhjlqi5^=XIeJ<1h|neR z3{}T;B-t1&)Z{?5h(ev|JG&8vH?G!x?4%sGB%nv0dR*RYq)t_?^j8m0w8#ju1IvZh zQRid|-wSVAdH-{VnyqxVXQUO2bz`+>^e^0MIbLpMeETw?2N|&#-Rc<~Arm_YiTcp8`8?SZ-Gk)44&gbOR zm?RbaWCQWPMlJ^pPktJDv5cJ7)nJ-h-GH&TKEg|r!)OuH-c{`xT9tn93Ga%41q%9F zJ(!a{piE>OdR7Y;-s={o!^n4v*o$AE<)BnsQl-Uv3E#B?PQ3SN&Q9d63h{Zl*Fsg+ z=QO|P>dUBE+xfRa8XD)PFy|QExXf>k^+(U^wE_xf7oVMXh$EQE8}JlG;##W*tGD$u zXyR3CCSXCgzO60&3jL`9Dp!jG+PbB;_r?T9fpgc>Y<>MDK)9@Nx|G}Ac$Ynq+mR3!&aQHJwsCkqcJR)e6~}7AmKPQXtvjL}^@(2MoH~cU2z5d zD71`zJPm%lM1imi`l~jwRHWVKEy5)nIHr@|-gZM}SmsQgY#qzuU1c-RRyPJU&WzW)G$2cN0SR5u$LcBY1Smxcm2n0KZr$W9Ff(ElwtD=U{sln z_^9w6vl$C$>|8b_E#;lRB*)%v0w$gXDqo3q0UNK`y8w?1fX!>R20-Bo;0(}0#|(d+ z`QrBZ#8@qfo;(l?+e9w!BVDz6Cm(e!Cl&Cb#UzIyB?@t-pd$T19rSO$uu>-HC7J`7v%h|&eUA4Uy`zidgLMUbEq zP{_Meky<$L{+W{@3hBk(;Dl1&KISFE;v}ooswc{^O_AxWz!t6Tdvz#u<* zTcw<-wuA}n+ARMxFl&Eic6u`1Jz`*4VqkelXdIth7#xw`3b zHG=yKZq<67xek)&_Ne*OZn2A6kQxa;YsiklsjKPI&QJrezZqh0sTr-ZX{1?V&}abm zRT>RTi6=g$vq9fjPV&`y2@X~f4k*&D^Bxks0S%IOKX^+O&n_~uMBFKD}T^CC-O+Il)E{tR|3n0n@{ybH%sP>;#$9@HfK2Dd(Hm#w9 zXFTGRc74?JrB^?xXQqq#!eVIAV(EDor-GZy$01&nm#fl-jDHrKJ(e;s1Zq<>4*Od- zjbiaEx9PcOPhH2SjAZLltvm6dL~H4jo(1%RyeNMLQ%Xt{V=NOM8m2!Pw~qV|(iR+a zq#q2Q;?XEnLO*vY4N+?r61Uj)1#Z1b{BLO7J8ReW`HEQZbdk}0@a0D5$=3}Zb!K@sU47y#!VC+Zdd*vGiu&TWtSm0Cyp!mhNnlRw z&jc=Ixw`CY*r*ZMn0GcO-+kV;$cIwt z@$JisfcfJMfZ+*HM<-i)8;86dic6{yCWV@drroQ@3(fP%mu#%Eb3@UQ*1lm6dFOFL3eFm<+N#gBZ2eH~UQi>r)m z{5RhKmT7urFZGj6?NcZo!{)}FD?R8zJmYvh*|3e{DPKB?uvMmkzOc@~{GO6P0U4mT z6Sn`&9(1t}i{V4BJ1MYcoRbk%NnXU2$x=sF^QTRu&GxW8`MH?Jj_1X9UFTU`?5y}V za7rDowG1GP>U-?zt+IT6`sx*J6&cvlzvOmjz$^KAlDZQX6=SMbwEUo>I7%_#UQ#8F zED95rGF%bortP|;IOX4u%;2RoJp_*rSY6@-BB9+OeTL(zuK(;k+_ivkg_X!vGKjIc zcneBT*+}pQ0}pYMXUy!4hH}%@B7GdjTlU>{FGM|6aL$tC8yBW_e#OZ?Mf9g}euXbe z{0gUBmANWfrvhfHk=_$Oo$k(o)3KZT5V3t(`3mYnK#47bv2tUE*m;2vPS#>ZKCtJSgQFyj#pU~J}#35jtR9DF?V>eYBh*xBp8 zvnR9tEzLp8YQ#I#C$yY->Zza@j4tAoq_%}|3Gyj%^H$ypfs$eYQIGoK8e-W&|4<%;1+z@CS}Vb; zZ7P%)R?elGNt)HqH+L#JL!nxvxwddD$0C4MVm<>p8Lfyw>??0utZ*E;sYsZ^903h9 zYfLaCU~{qMVv5iBuzTO5BMyZ|#<1Jcl*{M$Mh2YFE^Gvj5U%V;Hw?6$ESNs4VdKG|`32gFbjOu5pd<<=NtzaZXD&!74*a3p zYMS;N{18j?4ruZJCFc@}7zvl6j)v9t)vmhuzF;vroCIsWuey(%GllklPOChah{Pi&Ss=ADXTLDyl7tDhLu1f^5UZ3y_)Ud7QVd4f0ZAQV%|KQ!8lGjuID2P5jc06LAG8TT~x9yqG#%?AeFtBu-0>9fz`R@MuxMeyJ8vg1ix?-(T*2%4(G@cxbYLw?%Cznr=nu*+vUqrv2rJ5 z60)-94d>K5)ZpBBD|cy^s0BA4nQHkd9sjGn&QV?|jJFYljH+lS34FVuEsmy=no{#C zQhS1vy{cB;gX-W%gZ|sr@_8n7!p?OLyFpOnAdpXndcGWM)R5sfO(v zM(y98@hK};WQQeCM2o*ih#N{mVk4L`$Ax(a<@_*w1nXr^W!cJtRzCbWOR5BtiYUrc}g_ zVuLUKs1fZp5{T=lgo*b`>loM`aYSk3IA%d&Kq?>}lx-)FtNQAB9qK&?c;9z$WDsZw ziQB}pDCsHu;#|z!paw%O7tEQd2nMh{# z6)P)c_7857QORozI(^~#lOul&G=4zjDNG&YNiWH=Jpk4h&VP(E9&I+8$l`Y&Vy~Ni zj#H&(TsCBl%VGrD$6jkwpRIYz8#=!bN>lk?g}@oHKf)5tYl}rXITNL0R}E@B@(tVB zLz+X=St!=MUC1(Vo0a$-!FSDq4px3od6JQMWUTs(0|fz_eelw1@UooV6Ofb8B3$Os zd|w&+po=P=qyKzp35S(%X$-Gv&^3^L3bm@v=$JFl#d6R2SD%J$ds5JQkE1enL72&g zwWFohEYjyom66X}87MyW(-VUHdm_MC7>DoifG-g@FkA%V{S#VrXClyx4J3&#?qIEs zNik^x-n0Pw`8DBXB#p~Or=hV>BG#03d=dBGmM^k8O8W9+zo;Cz-=Jj{#yg0D&f0R< zfrqluxGm=%Wb@z5EY`&hW03Upoyd9sgwY%daG3mVcdYOLQWv+`c%1- zn;+>|)Qd)oN#sMA{E@f`n(RwS2daMb1a|*a&hr~wYiJQ1wXUYmdHXg4V$4m?fvqi{ z^vOq(R40Iv(!1zG*Sr2s<%ZfPJaf4+-h40p;fOakOMf`x&1IRPak6{y=7(vQfh;$b@0hpSo7g5_-_A<-K9HUe}dEQ@SCN?BcG}*Hb zogz(W-j_wAHf0-@=OcP-LUFIVnw9Fh4Ub-)a8Y%?4EnUNg1e-RyL5o7)e`tcg7>m{ z&64!F^e>w4O@BV{Jwi%z*X-xSxT!up{r%ToXH}wuX}B(%S?sqT`Kwx>@54Ame#hE- z|MiS!Asn`RUH3+|Brs2eB@V%YhLWC>b;t^LQG0Rnr=l>+KBUD)!YQt;jOv`h#-c!X z@wTY@hhxtP$s@fZBd>gu=Jx&)+a(*#IS?%l{9>`}=@7hzDwI7Um}Fo(AZ`oF+$ zIH+D+47WW{)uv2GMC<|)boH0MgY zizG_B47W$Aooea!w@PDXDEfAKHbpl=w@hnnWHC%wu<`ld`S4iy4AFe}vIw)>*Q_P4 z-*2CC8t~JF&p0J>`b6FBSq~2T^pf&96IPvwS|#(*hR^gNk3QZ^gZ0hD#PyVK^i;&n^>X5Gr^;<+hU8i9%YyQT zl&a5u2ChfLge_Uir4`WqD>TetD`|5s4x^Wi9y7=9+>bsO224XL7uUhf_$3_Xm*?c?`>_y2Qf4=<= zULYF@Lw*bIurD3aUPo=P#qb%U;yZeBpxwbuqCY_^H|aYp-Jhmkj|(?uRo@*_r@`Bm z-hu6ZDwNkuvbgE-Tts$c4*?f6@AnB29bW3>ljKi9U?=j2#+qbk%2li8tyT(jcLF+b ztF-_fx?N&`SPnt=ckcVO4)`79aN{TB7`}%N&?!_#mH<^GiI@JuyhkZbFp|RW@vvcK zj*n$Ovc`6V^QOY2iwM#Zevi!T2yfO{*r_dSo&J73L*USZ5oAnyVqTBBaqg(Fy@I-! zvzhYCMg*0F-e2-|-hogA#G#L5y?td+KL2?v=UB>K{i%T?>;$j-srBJS`IBcz8qwWcMjobybqO`I2?45`=DRC4(c{h1fv z^Z8cECtr7SvcYfQ`7I$145TvPyNl4Hac|ftrF*iX zA-dg;pHt4=QlbtKpP1kZ>ccxQe_7y8I*E=vE=NlL2kcxs82=S6@4m7aqN@KDT6Ojs zrxGF7+AXlk!7}#XAW)q&WHp$@!m0LJtv$gu*4oIkXuFJWZK{cT!_5+^+FI(G!K=6# zdImqRTa;~QDZF*@K7xYw>U(`9-cfEW9yOo>O@Boyp7gHIj#DNbkD2~y#^f>R%S_Nr zIfx@L*;nfh!A~r$c7m2{5B-HpWi4hl;&R`xe2j|4td?YX)(6(N%luprYB75&MG=&E zgDK){ubp0#=ezK=heZT&Y+5+lRN6-U^!7VBFLwXTF>Ejwtav{-##q|ssyX#JP*22@ zuzKt!rDRQ@Noz|6R(~|a9Yh#$h~fPF3Q0wHl`#$h-?(2`F^%PwJkaxM)z)C8{{$SK zpIlsvXzLX_;M7+J(KVKAh$YfO?IH~6#OAcEZzs7Ir)}o2;cy&$bMm}CRgT}EWeE&AL8ZuMXjMrxev>F<@`r$&4 z)5Y$4N+uV*8`2afhY7aiwov4DNNzF~30sv7d3XvUQRD4o6U9am)4!Ffnf1J+Oa>BK z9cFn7?d@O2(bAr=wi8d>Zc@Wg65?wq5*dosu36c*HucHjzhKAjhrsXl&gb8&KnQd+xxv8-Yype!4nbu%`W~-0TL%W3x82t{+YKlU(lM}m zV}z!^@pMh%5>Fd>t zYE?e$J8pt&2ZvA)*Rzvx=PyG%asSl3USLlKPM(Kq|;%sFb)NhZC`WIEAo;sytor}=8i8l_l-9maaO;p5tqtV zudA@uH#-R!f@0i6afxpY-MER^47iDu$TDTQiE1QY8@)T|Rb7%6dH+(|nTzO0=Su74 zS}WSXZ+-};{nWnYVNVK_d7>oRX|I;aR@ZQz(S0MRJgBgw?JT!*Fj_%0^%ZUpJD6X` zpm9Zuh(%qhs(Az#*tZn>oEUHHAW`VfH|(=cJDmCL2m`qs>x7BbvuANmJe~kKsVs;X z!zd*eE@l^g!v46LG@tWR^7XjfB;qp|B)b?cMY%HlGKdsq)kypuo&4$~ zMqI@Qmg`5VV*uqM5gt2*vB~ad(ku{GpNrih0c8o>o*L10IAix*F9PhS@J|FQ5InB& z>gEy8b82tqKNP^sR7;}ZGy5=PgR4Wxm-kpv*G(9XWG!#)fxKGKDfc%yO$|Lx8=`O{ zlVJwgI10yp&ms=GS;W$GZrPHrkS7Tbh3!+zq)lO-tO>MAPb76 z(2$kHS<8rCl(5;+&NUk|9sC|8s*M!9t#hlu2J3$x$)zN}n|>|L8rKl)ZB*} zfo?4HamHfcN>kw*zH5K^m5JLe&8R_4pZyEN^X7k6p;dJ&NisQ zm1gl#X6aE@w#?DtL(CW!rv5f(p?Wo;z8Kz?$zT>Qt3 zejB+$A1rMNtyl=Heh_|0OP~>2_KZzD=0>f@L+yRM^%W`{>nNN*#INpHv?|SCp}iq! z95!f4SKI*7$3S%(ZJHcRW};zqq5$Y)B*saT@$%!B8@#)6V)>SuXACTxGE_$}opx8E z1!n>+uRdWOvKAV{#{N|O`$k76Ao}=5FS!gJ9hoQW>FG$f@P{#ae+X@_gTw@^EpWDqa=%}$b`?yi^qF0l>f`tx6XlZWsI|f zUN)vQQMQzHn6d0B zb7CDsCvW{0(p{%#=QVTDFWBos4CuyqcU=4yo`e#`Mdk6wT_?0kDtIy-*SV$4!{6nU z;4#|!kd zPQCZ1-o@Be%(L=%<{Yuq;hwa1JV3agz*X8hsNFia(mH6|I_PwzKYTurI;FKyt+jEg z)qT}JGELdJH6R}sV4o2IkLK+KcGC^^B; z?99gy!7&M{00PoOfBapQ;Evequ{(;=#-(I`#3XwC#IPt=v*(C>`2Yh8-GD@j*4 zec2s@6qE$p2uE%^9f~zz(Jq^*{y~b=8%qLlgqy?F4;D97ogzkAX>aQQUtP2t=$ROnQ>bO!82w(u`HI=~Ap zZ3^$n)r{v1?RU*L-LYKkLbcpCO-Y*1Sejkp&JJ)n?0XLU^lbC?7K+gPrun0aPOenX z)@m+=y76J+p+@!YXVxv1&p5hdQ4%!x5fhs4s@yEUISu29T2fK4`nLOa+B01dS0%hM z_)K%(B5A;gCuZfHJHr5f0{j0b+lDR}MmA<$I9xy%CjuI?c9eK=e?-!lz6v7O?fEnB zU_^*XDiTWeHeYI9Tu}-m z%3y&JfK_%>z%ozL`}ctHojc|Hk!`w4}rM z&6MXs5gZ+iW=4HT;nR)?^VL`zTe)xAyR%+=PtJ9`tYYru@OcEMQ!WpblhoWNxk=3H z5M=7i&T<8@dS;z|YEX`Dot`f02G>lJTpz~fmb{D}5B^>Dvbu?kv51tBbz#m~b`;L( zbJk8)$;(HrA>-og?jj}_&mkX@msW96hAgFoGfQ0S;FG_>f;>mip&IQhkP00!;4SRW z4ptbLKaX!9;x|bga}(CzDZW$JD|Kt_O49Wt@l0!+f7@r?GR?+q=Q+8t2?-~Iqoqks&Id1<;QE?#cGZ<7%x6{P`=x#GdL^DSDm?Q)nGe4 zhd6w*-!F1IpO{&ie5G#glHp91oH1NBOoTiDQA3O1vPGS2d&{)-`F95jlF!jEN5ml1 zxFq<#H)N}n;;9VU!6-<56f2SgkISz*9GVOKh5ZnT_soU!@e!WN#wGapcJNYwlPNQ> zr2g`kxcRTnZaRb0cnkv4=+#C#98=ymVyFf_U4JCSSlBfy@JTyP1FtpDWZxt;tn28j zL2ADp*FtbMhKIkRcx2#TbE|^mLTLfh)g_Xd#zyFc@H>yA#-*xb2**iDmB(zw-D(6> z{+0Y_0n;#0P64(f;S0fLgIGf5xB< zG-FvFwo9YOMQK(ud#qe;4pe6IIW_B2u{QIo%zlZD)f7Oy84CN_R<-h!@82OnPiW}q z`6z2OKYi%weg#{gG6nDJrDzZdXiTTAM0idQ;o%DhU$}K8fkQ)b0Gt zv1~LtD8=T`g+QHei`Zj4AH2SZ`MB<<6j_wfhJkt-onwrN^K9z%EAO%j`3efF@4i~j z77P11qwFf>3rUrrvMGVaL?ylA-iuGu!UuX0^i{%lY8bS!We-|?%0;(LNTT>R&N>vP zm;YWHW&ANGCK*9Ia3bvoXKh}9NaVQ}5^@`EcKG<~Ca_P4GcbSs=B0C`1v{yEofm|w z5pH-YCk*Vt8Vbq@^!pe*SGOn-@TP zwD>`1qA|R{q3f!I@@_I360*n}v})MXpx?7u%w#5I%ZehiU;u{{UE8yM_>uzz{2!zd z^O&Do0HXHckK#^i`oTlCs<3}7b025hNzwokmWkf`k3qPb8s*olXQe`T6HMVgo$vz4 z?Mp90uy=Xi_=Y`a0eaD2HwRF^MkULC4fOi+c0T^OHDF8u$)>ieqMN(zXK$?>Dm6Q! zQ@`t1ZmgUr11{(G9!AT|PUzHUIPRq4Bxf+v&8?3dhT2KGM?KD0Z5Z4uP6O`DljM~@ z^E$(w9ZUpLB{#1U2GUigHGHVpzb$z#022LHnTql+rWBBx|k zy_8*A12=r!14y()Uje=yGH|shK6ifyW4q*Kd%{}dWMY_#@EmI5afX+;TL$&OJ1H$3 z!%Q$uTwfUZ*Qi^%cA9cBluk2-yFoh`n}GCN614PbJXp?^5)+pgJ`lU_153ZiwmlU-z#M(zEk}{jH0! zVv1Ui+s>DMtzgHL87{4qw8(zyS6F50GMkR|G+o`=iTMf8y1$8T%(o$z7*?WxW8~@&`98vf)8>>_}DUn0#RqW~3(M1I zjPt8NB{ipvuRc~Y`a;r#MQA=jGw?|_Qt zo{i6_ARu2-(s7Ek!jx&+FcOQ+Cjmo)5WV|T`G7VFaO*wk>J;MjuH#8{k`mROWw;d^ ziL|Qx0nuYIum7(#W)9DL!MsG(?Ce{n{itGoa8edMloh_6_{*5MlkkQhf z(bD_~pHLAT9N^u;v}r8nyGOX6g0lalqvDcTYI2UNsbAO7ILIkIqcL=N^O1JsTRnf#?6XLVx!J6P~)CZ*fXkL-1 z@KrOYW_LTeo( zlF`8(8Fc)$!SPd2j$bbN2|b#aW0!Gq*~g}}y{BHG6ESiInb4N{y?u5( zR83@tMlzDWnP!%77yh)^(Ugq~8s`z${b9Os`U&e$1wXHTt0nKl6w+!EO;EJdR~oI~ z6Vvm^&kGb8fIh1iDJdA5bjjZ3&G;!Pj}>G%p8l;)LogNuX^<^TEVGnm<<~Pjcevj8 zMEVS>zgszj9sZJ}8z&SrY4OH<%x!K*JWq1L)LjsEvxM5M+uKeTe25Dt#D&nnxq7Ra z!h;0iDBT}w^S7oI4KQl)g0kzm>@xk%tTg=hnpdEa%iuQT71Ug>ULWHs>1HA9j!W9| z9di=G#^m3@FI5J@5e{ASQ&qVTshUg&^@!}d9@v9&TzWXLo^M=6N#n9ZT2ig<>6iy-km(UA z1b%z~4)4l0Nv5i%?;-~7BJ81S&d@&x9smKq2VqROX|29#{RW2WTzDMaXeHi_H(5>u z_TJ&Fx(Eosgzw{;3aEYeXLjfzMyIK|O9GOY0|uG|)+7UG)NUGO!6(>9K}U_}eUK4n zUBPpd3~u~V6bs*eG?p|q9t{jqbCExWf`6VQ*l9Mp&8~LBUwZmTF6XU|_fe!<4x6SJ zT_-KftrQ4`i!ItO4C=9=H+XZ>urCeAWsf=?VQJIRcj#X@JH-T88V=NYiDaOpV8Z}$ zHoSq1k5NP1*H=a)Mn*6OO(Z4)DDz;XayunENB)id)q7;oL)2zuxE4rQxw7P627Req z*fnjOm|`z0TaRT_2ow?dt3;7SBW?tYJqa`Gm+>sY{{AuNlHc*Ox4hIsn50Ar#Gfs) zQgT`taT}5o4H9Y9&u%;E_yJxgvV)RaI zT-IAhN@27j%tK04etbV4jFn6?%5m>^P2{rNxY*XDmziVu%6BU8 z6ilO4sm*nSLSaoP{n@ZgeRR&$I~Xbx#h#pNNp%?ijFGIleu&-`M+>tit*&IozL-;E)1% zr;aWQ-^^p>pA11a)vr6fG0<_ONH^S~W0$DLny~WSR{5T0U$@kO5u}D=SmOjrljX2} zMf0oSz_-n#Z?Z86rkoM%8|&3CNe#rNn`3ctD!t?q2QP-U|IHVP0LHWq&2~v^@Dhgw z(iLhMinlZey&<22omn90FM@z&ge(Q~>QOTIGo_O+&onRDKvoSd=8aZA1ZSMeiJw~% zHgf#6O6wEJClr6S%}TjtLCuXeiTR1-todV%%wN9y{~+V7rCFWPnNP=jMwE$N`UU7U z@8OI?vMX7(L=gJn>ei9YmNlnyDp~>XSn}rjk^s#QfjEK@Pjg|P5ssUjAFRypSbgnv zjZMryPJ`5n6<;)%cM(S|T)OGy8|ADOBz(K?^i$GBD=3-=jUsgXM*N{5an?fg7-Rfe z-Aq%*-F$o=c(QO;MzrXc4y%%mq@)>|&F!o)v=&)#5L|e?DPGK$<@LzJBm1200Hw^gzKtJR79GUP3U8@)4y z?307Yr)JDeo*LT%;xU}d_{~5RYTJu0t-$S#7>bp)r<+p&t+V+*<)m$XL^HOATqn7F~ z2~fRpak$zxzBhBLw)6S40^7)4fDxtbAAJ+iFy^e5y1Mfq(&mch=3+$_mdfVl8r3k* zFn!_Lx;n|I+r43-qPvERJ%W05dR3kx755E-#&%zL*atGEwiz9!^uMq!ivVBRP|y+W5@@q}-GHY*@SRDV$?DSF3fUf7}< z^F8xvbHMplkSyYTibAI;;spJiAN9K)OyBdzG8}8}{_p_1l5&|(#wQX-!Y;TNhZ=90mKmedC@l;gu zNBp?{W{X<#=?d`TZys=Cix7{R3x|)>L*#(p9Sd0;{#_}XBZ^wiq z?oqfvN=d0rhTDXwh4tZ0nEepo-{ss^=pjYx zulii3J%MYqdWZG4=Z+X}w{1s;Cqs5;oE0}t-zx;#*J>I`@G}C{QkmiI13R4yrQ?Ag zO^P;(y`+u4f8S14NqyMeeea(tC=(e=%*3dvRpdyHx7NVRvT z?OQ^}x1_6QhP(tD{i-6IbZj9XVC+cWMv$-&cF?ka=w*N1W{4M6arQjcDD)G6xeE$l zbkHUnq#%564()w%q&lX@jFbB2*u6REnmZ}8f>J4d+8a61NFLMLySTK@Ub^46lj!E@ zKyJoJDF-@^!eKJsDQ2s!^v4J*1&m>e*~G6Zd*5_c3%xl?|G!m(-tqt%dWZB$mUQKB zVv;)1v1pQ$B9GJJ;Gh(StPV095Hy@v?p=E}qL{Cmc`St=lRfsyx6O48cd3w((jyTO zf32gXbt1@avSCE!`&08UAIFozp8X^x^`cY<1EqtR?!JZu;=-{nSz}dN*2hW}9k@6$ zFDaW!%@CXZ4WwGbE!nYS`eT&%8;dh7*@<1%53p)&+-kOL14ZP0o$jg-nXruK?^~{C zARhC1fajPSQe)ZCzk=HmQ=jtJ3&|h;hC}UF48<(ef0FsL-G5&F z^DE1mUsID(W$)zs`x)lWS$8`2pP3#@{YKbxoLGb&fX_~vdq9o;nK=fS0!qO9BCkfq z&A7O|YqPs%DD0zzea0coNyTf$XPR!0iqi{JKc1hk-3RkrF}*pFXyJKic9 z-5%oyn7>EWJ@6LyD_|AlOGc&;L+M%q_t!NRNOKH4DNbASWYvkn98f|-HG&=WCT;7$D|5`@ zPzvQ#46aTd3kgPB=Ocptk={SDcOo_yuR)cEx;jMZJGjFGIXX= z5cx5aS6}U=Of!U2q%!+grZmNJ%JUC)Pi956*c|xD#()$o$R@)8{tAM zS)`JL?qGV`Q zm7{(3&m#R}+hc=Lk>(-9tmvoV(HS}t=L9>Nim`#rW;eY3B9ZkVM(wj;knji~HOKo+ z;k(W{)CYITPVW4eY^PjoC*nunkYhXB)1RJyU2U%5TunJMD^d~YM&$$&;NK#&)Tpmu zf&=KtgB1I(07ib~GLHu%U$Vza=;aaXqf|mG^?O|Fo2B;Ha|slNl-^|&efMGkHCk1J z6a0B?w)!=BpMiJGiEzsvQ3Jmo#5EoDC$4~?DA<)&X8fee`=##r|4tlM-IIoEo4Piq(xQa_vaHh)ii?2k6KX^Gm#TB zQ4{tDGiL=!vkF<4i|Kj5`ZqUXz#+zSxVKd`S7&6Hv+rhqgN??rFt?|Skve^|=MSDx zH5SQO=>MD;-x^db@UHfwyPO^MCHBcC2p%5RscRE#jmpERxS>m_;F#K5n{BuH6N;z_ zJK_g@dH0}WE1CA-qdQj-dV6~w)E|yjFx*b4(!hcvMUyD7$p-d%;R1*nr2L~#b#n^= zuE075=Uv!`A@+i{$Rx`rmUB`NYcWD0c>-3~Vu}!@74ikoL#`V-M7^+(0qsC*o!%t% zt=IqO#f3il8R6Aui4MO{|30J)8SP5yv%AI9barA;KKK4*+~IfC+==lR_AG~&BMO=> zkcf}|0LsYxu@zd|T-(XBf5p3fU#DWKN~sJr6eK5WDBda$|4tA6!OOL)hT3u3@f#aL zL(i%v^i7nS&jUv08dkRZ7A1%!*Egp%zkb^zGtw0#v?@hO)AGTu9v6xu(JIOE;n}Dd z^eHFczq0tO^8Ozk+DET4=eDk(43|w8>L}I`yN{R66Ibp@j+j?tek~5#**%Y514SEe z!EzqG9BYfFV+$2qH#Z<@isi1{H&)*71;{iAi)Vg9%@|-P)gu1Jnv0Kmh+7G~m&$B$ z_yslbhq+H%Le$#EX`jRHS}x$!A#z&r-{>Ny6J1S|UyfIYhiOyQB9}PsPa{x#=lCZu z&gqSS(tuthedt4qlUYx4yXgNd&`jF#J`x2hj}g!H9W(GTu?z(k_uitoNC z=Vp)Ld)TiIpbfeNLuoV_mbjzrA7+Ye#NlYAIdc!+FVleqCKvlG{v*8{yThYT)7Hx? zNq{fU!b!oP6+m03J62M!yz4ma{1X%S5zPODh2Or#@0aep!;&C*9d#c0&yxBDA7$*1 zk$LSQX4pd~W#18i?{F;!3NpHm=x0(RtRXFJcT5D2o+?YO8wcT+nCm#JT6dwgi;d=R z+Xs*fr0EeA+2d^0Dp9eQDH~JfJm+?+o85q{d)z!xAT?}i$VbXJSXZWsxWmE!F%)L5 zM%yGpPr9HDSHO;u8ADJ&R&v7601-I>I;aD#NDlam(DJu_o{u>TR^>(|H)j~;AzXYR zH{krbYI??w7qvTH_(CB1D;~NIghmNw1v*9Na>7@fAbDL&ebX$r*hr4|F(w!gY9uP| za26e@{ZwaKO!|mG7svAs8K8#ln{!$uZTp{p40m`+H(GQ?BDR0C2szpcW+1gH2~9R& zfQuG$gU|$=zz}#y=6EahnTL=3k{f(k=`&E1Q-*VZr%P7T0L#BW4YmWe7E9wZH%S7P zdslAkx2&kkNO{GLQEM79caZ~1Q=`TGe?LE{PrxzRA&8aoTm5UZ%n_h5YR|Zg(oMV_E~{Y zIX0hz1>*@)u{h>!{Mnh7%M<>bTPh)4c)f`1hxxn*GRa ziN&S=E+g3L?no6x;~WJ75(5-J>zio{$DQWDnIuASyLWjsoefj*tuT5KTHDmx0ue*Xzi+Wi?J8!)af(Xp-q_~E zyg+cQi9=n~wix-TI4eGN`-S6tSG=xO&@{DGW|&XLf@>4G)Jf%=)otyj@(oNOgvoS4 z#J`l7Xx{cvkTFIHq_DOM#wOV(emJm6%!wZk;NpC|_YLV^i=z<>nJ_|DJ$0F(TJ_>8 zm*PL2I4gq|6{rdZ)Ep5%*h79$uTahNOwPQYoZ+4P<@4da#~8E+0OEdJ@as@rxYyR5 z1Ut!~w05gv9`Q{7JT%=SbPRCf&$u3BU;BF4puK3Ty+}$QVpQ&|PS}TD zF+XOdnnP!|JK5rZ;^3Y>afL+b`?0JpCcpQlSSjXiDN9E1JFmjX|9(QSLH+7NQmw^$ z#W-bqun%R#hfIwe0&u=Ld;N{8vjY?y?hkT`^E=I>SY>VruHGoHO@9qhNb2(fe7a90 z5vBjWsop4N{QKlFiOdS6K?bs7mL6|%P;Kg0jH`^qtL0QS8j-ImxirH`SEBs^p1E8@ z<(ZzF0gp*vAu{FgyOL|4!q*-Ks+a`QL3*^W(^*J)Ljx!aS>^mlnNYQIZ+Su^wU=4l{^O;#G#*1&!0t^N`ze#TRWIUO+Z(T#fLP zqKNBzRL_N`3F?DMRtREKhM&p)#{i^?S+7FaNvit14~%Ib+(?z&XH0RgNVJidJXpl6 zB66>)eonU2JuU4e1E6nl1_zGlRrXBpK3Ft~He6Lvr1vaI+G$c#-3(DPbie2hOE8Ae zUp3zj0Z;UK3Y&-5j7*6RGh55{(1`1St`fG%)w8-b=6_4{Bwu+Sj`t)#eO*0s@s7#S z`~lgR_`u8L))M@YVS}%mptbs0lkPf+-1rg%q0#jztK(qLWUCnn^MR{ zf9w}?ev?9jKY0}smbu?{{M;@1S6BUMDhxWV#de!!=*Z{vb2ZF!H5gd-M-67Xz`tWt zCEXrI7+Lmb4Q406&NTPvWedwn?HNHgQy$Qbj-W;=8`5a!U+ql=e7iku2b)_bpnCgn z&#W?}kq$kk!8Ml0GG{3{ym_l&auq>13SF~Wlv(u1tb)H)%JM`3?7qi}20s}UC~W!; zV|@KW#k8U?Wqnrgd+nm`c|s2EcO^9}r2Ho(y!PLaX*p@U^lX>gd$D8l!I2rZ%Tbxk zB%Hw9a1YP6lgSlp|Ga>p@xWO&-v)HnlABFOCo?`r3O1Gt<7`jd;f`|a#4$E&XEU03}fM{zitbd19)nxSP)oLWxSEyp^K zFPy|B&}k)cD|D(DXsm81RW{zp*wuYq8Mq3!2DQrf&`$K$OaEGu+>o=EA93d@FtVh= z+MkLE&L7;?y@(06=Pod6O;xO}iwQp875nngWZV|F+usQ*vlsJqugKt9ET*RGP9yE; zV4}X$TQNdHEG5ippaIKx=O*^qC%L4|z)jl>f=ma+!^D2>%+R zZXUDc?;D!Ft@r*G-=YsUteHQabPYDshN5zX$tA_40t|^Ab&wxw;)ZE3?+3@Kr+gS( z=`ef8&v*f7x}i;rP{2%g`vO{hiRRXAX#5b!XlC#6+ifUzI;~G|LB>cXi-GK$8WuIX?pJ_6 zO9G49ahdE*z$cht~|Oo1LNWekN%i_eq6!3wgOc3*&<#)?dN z8Ge*d&et^t~A?(0Q$4L_xZaE&|VJ&1kR?&JluuJmkbS4}~wCcYqJvDw|Ei+VQQ z8thgzm`~zn^nP2ehJqO`P3yO07o(d`X9l)Y9gF^j0`A>7`n7?r%c;vhVkdXUbeBF% zk%Mr$B_du(!&E;>q4oahOV`@c03n;H0{d5keTNz{<9BbU3}(cbFbfS|^Tu1kvTa^Pnrcx4f0&voj=rkYcAxM2PUx}fMe}--Vu6@* zbKYv0YzOlN?_g}K$J!-wv0bVyd#VBf@`DW@;3%Z~hor_2Mym@2TVcuVGx}@sPoaR5 zHXfw+{TtRU_>fMOZT?4ra2GM$aQwY^i zLmLhgQ1B~eo)aC!V%KKZsA5M!pB_BQ<$IaZZ8fW(7Dd@|IFT!|lDeAxFLW3prnO&Y zQfioxBSZ!rqqTA{LvZXrMpgfHI$?$VlR>v72aAFo@?0#++{-`58QyDAR6m*oNKbiv zsF{9w)6Bx;hzv44LXlvR(^sqMC&VrmF+J&XiWO9R7re*3=YSU)@A>?@2;RB^9U0dH zmwzsMs(?@W*Nh9nY2`g`K11blj`1Qe&yR7_o%|`+H+9ag>0I2@rFSL^v9#S?O;H)f zF*35+QdhNsze7|)IyH6gD%*Ktjre88gs^+Bb9`BmIbnmEgRE8-b^boAJbrQZte?}~ zYn~XE$<>X8pP%&Pi}I-a!%TD`U1zB*mi*F9?yHLLI9SOXP&rk8{gV9N&FMhtL ziO9`Ni03|{0t|n#uR-qU4;W|?C0J!#-#Nj0-z}F&?nu2DAr=1@U4!P4 ztnlmRZa7$%_66$Tue4%seQ0LKrP5#(1DMG&+oQsQz{>!`d7ryzt$irjfZ7~+7(*CU z?)!0=pt@|RV>^%@H3&;)!RM)iRv^IvEq_>;^Dw{=n3cykTu+?QNmS)Dzz)9$R%3Zi zNa<^F4W8TrMwrHKTS+!9sBcB7JToyCKI9c-TsK4neiFr^XsW-Nw62}5^RMb^u}|Gs z=NYs!=TsNFTJ2}m+69p4lgFFDVO_fq;#6M@bDVgFH=#voz^-AQeHCg(<5DS_%&XoX zmL!DAID-*)1LSpCh7!}&s=0DA@|~3G(GM~=X}G!`dKQQ0&K=?9smp{|NP>Rjj_h$} z63AmSvZUgPZ;g{K1)gXkiX#m$)QiO-CAc1}97_y{7dn~w7z(rB%jpcvg>m{GD*oc)|@RZRFnpK^U^ zl>c?4dY-6ra)-nxibrE>(|Tty;WKq%<1z2JaB<^=VLV{&I=^4vspDU(5EV?MB~Kt8 zYwEqg8K|(e7hoYjbbB3>29Zh7I6-9$cA`(|E`3az56L$ z7RAM0|ERo*{dHWLyMCU=%(jaCY+O6H@C&p?X0G0pRh4d{$+pynrR0d09(p`Hz&>0= zD=xzB^QU3GXsc0CB$U3EtY7}Db=F?#0g>UJn{1~r#+{kjKokMNgJa`PoD^ST_Vj`_ zp)mB#!|Q!uIncmd*0{o-eC|~zhue#dK=tpIZ@|!l3y+JN*15Z-TZpAQl%o-vvIHFh zLoFVLZ|;`<LU0Z45G;6bcMtAv!QDMraCdhL5G(|T;6Z~14tIAu2ztQ1 zBk;X{Ue&9bx|^N7+S}df>FNHp9Y6ZNGJaIGxPGHNwBJ_F@k&FMa}o z;+4${;^Jl#&~ZNit_EGr3#{t-E+cyTrW8fVSRwV?I7LH)F(NLTX-m7(+YZN1-}@!! z^^No_fL=8wtMuCr51DxfyNVY$&T4+RQ6eYGr|p$uy`b5?{_P6wDPHe5`z$D(B30W8 z@NKZ&of56NR^R9yRUA(+v*ie~{`tyvMDNu4tJ$({oa0c>Wt7)&hk#C+tFFZyWwS73 zoWo{Hudd(hd%_brGww7p1Ip5K`{XEOj|)KJBimLk$iY8Wb+ZY!;q{C^04Z4O*i9w5 zrk;e#=HU`JSdpuG~_FWjrqddM~LY zLv8z-b@M3|z|%aZ6dx0sO7d}b5a3*(-wZDUqrk%}vy`phH|55>u^kYwF2$?_48=#s z9!q`W;xmLNuPRRVL{gR>IH3~{`k7Oc zdgqgDtMBE?1D}pb)i64}9y_%kJ3l|Qad*)}QmlxLTd?_UXC_X;-+Q5lhuFt%Z`_YN ziM;-6Na@9?ox=t^LMEKnRVqjD;|~Z{PMj9{iKE(Hyy-L<#kD-FA#*XK`;0vpkV3`=#fAzdHB@ioE=W^jSNFFkfkLp}&Bsm6q z0I?e?sOFhjOu}mPX6du8Lc!#QWMg}2LIfc~GO+Tt1l5>C2Hpc*qX5UR%Co6g5eHZ~ z6g6GM3PN10-it>d!OBUEj}za! zc`4JiW|VX)|0WKxpxC`4W;m1juDO)y$ti*AY_o8g#jm@@%{PCOt-vWb{JVeGry`$eCK3Wpzi`a=+^6SAM@cb>ZI+@&h< zy301p@}AB*W@rQNs(R5K*;3+8JA*0SJFX$5iob%GZSeTxfAoA)WDX7dx=*9%DAR>n zB-p)`_9Jw^P|cl9;27a?V+_N|Mkqx4%{b2L>x{-vlGC^X5qZ=HzU*+E@)O1R!?NId*?7gE~d3cr=2`Pdji|ttmL>vr|3V#!Z(Wp7-1N{Y89x z4$urgo%uW&5PO}5zD?Kz^?Os4*pK|)aE46L-bD$7YIu1dl!X0wQ`Gb05_(PPyDSU| z?3Ts3#8xf0?5WOIRl}}x>FRB?#Q6A}-HJlNQ|VgV45Inj?^n#6D7RXQCFfYd&aQP8h`Okc=6VVFpq2F;T=|(Wk5jBKv8=62(%D5YdV0 zlZ7w;V9C=aEK)2SK25N^zag*S#%a;X-)NV&tgC*p5PB@c^=xX<61v@QYU%L7%YBk4f4>M@GzPb&|;=%)_nT(N!p#&WWBOG@%?nP zM9KbX=V+f!OLbs68=F$<4?pSDGvb!6Tk~Z=`&>@L{+Lcn9p|cc9iNS#Mbz><>+-zH ziEYNIZ4IC9{TR*$Yp%$pxw-SO+$RT(C|`CQc}O(nZ#P}7b6ic%iV5|<%{YJ49q2S& z+Z#GXHU<1pP|RtwC6aEEK%>_W#5e*dQ6I{eN3@b}RJB|yI=`<28~XYDbn0aOXt4JN z!hmBOdi@n4n{T?qSXi#V1rugXr+T+TY zb-t2voo0AsG_ad8oi_*LV_`YYwb%&hCQ6Tr(vE`a zN@|l$=i%f5s}6g>lL4Lczs1x1?bZy6{ytZKAwui#*+=^GhT1yooSJTziw4~pgkNMe za=ozJSPAYG%r$PY+ocfEOY`ujYQ`YFT&sGz=QFdRTCLPJ8|%OOVVI>(Voo1lQof*3 zZoR0dzF1k_=%sE~SH8fhKHaFIzPMAqV6NUUT4B9teY>M^E`Jea2qu^IEdO4ye+APQH)N zma=ANa3HTj+g|qq73w z1hDpvB$PEnteMp>rS3Gy+!!{L@uhpdtEQ>a1AEXRv5-@B$8OpgX7M>^jbff+^yh8p zMvw6G$3^P=CmNjAF5om zjJGB0ye4_W_KEYT4~Z1u=(%+6K7fB;Jr>Qc0N6-#D}pbROBvR0XA|Ur_i(Bsmug`= zA&F7~-B{!^kYvc=R*_T}k9t+5FLVL|tsXGoZr@ z+etGEPSvvvvj>UwfC!7J4XiVA7}J>RHZnidz0*?N)~IGoax@XGB;FCqm6MP3`7*=~; zh;Nr}JTe}g$T8a`SyIB~k}zR6n!dYHSl5Y{&M| zqyNaeJw9_MSasQ6d3kg_8@Oy&b=omg-8fSX(CJKV$bES9`jcOESy6o{$XKNzRTnny z%zsjCQnPTd3+s(p@4dxW*{@yI(mb-X{PMeKbn zz-%!b7A);O`2_@3$X`kO!lCZ$TcICw4RkN1ihQ%-PABBe*CU3zu;f@o5@oJ1nfvVb z-SG#iW6-3NBV=2O1&?of8Y@*sH|7eGkgc+^)aDu2+|uF%lz2t<9h7QS`bEO@arcR; zK(l7_i(m`yhX+7}kM>L)f90&(KQT8j+&2@Cd^)66?%4vM`;-m7_QoS>y1FoV z@~XBu{2$L<(jh2L92!x4DndxqgtdSLMRFSaWbzHbjKw5VZ1U}I6MxJ%wVZ7$wf9quE}Q1a@0DeLFV)8d z?avx#5XzIe4=*+22bHv&+Aj=rN2$z@vOh3-G^X&W!hG=!5#q)a@J1e1TPUMH+vh>Q z$WIdxOu)PxiEuVJcDV2TK(Q@V7JYIHF5X8+^CY>rUyYl%6c%rZkHmG5$NBbUR+xFGJN1lIZ@GeO>?AS8 z#_t4+x>Q1Ac0kz;_%XCqr!J{(utH68+yW22vFAt^L;Jp|PjpnB^XFU%oR`aU9aYzC z(a$!~7~kaHEhMOG7efCHlx{6x)Lxm}<*+7CGKm;j?QkqL3P5*Wi?>rO@xx@3R-+9r zljHrYpisFO-+WW3zuh}|KYReG<1n!&YF6Jp2w7)#GLG3LTA8Qg(?3U_-%dQw(@h@Cc6!}uueSN;L@A1uKz*ReLbOTddb+s> zj@M@y%vf#2SZ#Bnx+%USt2^DB8!k88*_)R4>YMEh*rzq80vZ$V+mhk;-{e)H7Vfp8 zBavWSv*(+Ic@seC2Iv~q#c}dO7BZeU0cGDXg{rMCe0J!y!i%J}Q1eTb@|2J7^uZt? z6|0qz?i44biI&cRiY}>4&2pK6&VeMwBWehQm2!=d@>}ga&_>zo`db@4oqyO<9wmjx z>OQdB)pME;HgMB#aMexc=%d39c;|8aqANG*faKWUa9B^fCwB!&<>FVVi*9V0-^6Qb zLt_CU3{|^UvJp1)od!JALwq#%!_Vx3ayeA`)bnlcvb#jH^PxD z=rG3B@SgCZ9sSL`37p+`xF~sd6y^NreU$4H0!r^9g<-P$OCN=;B8F)AAxVt+FB3N= zQmpvry8Jy4Ap7+b!2C?`bEvfl&Eu4VtA#wd`WZq zQtI-rIekg~xWxnKi4QmUOh*#9c9M}dx)!fA1fwl6;V-V)Fib-0-%@^Y*MCJu0Pf(? ze%q+D0{%+d>q$zP@FT>E|6I7G%>tsyJjsPi7n@Fwz2fBS@joUCjVLD27nz~hT;e2q za46|af)eG(`bkip0@Q0z-e_e%UOY>IJ^ti>^8)wl=swo3AR>W%Epq@qkk~vB-)Nm8 zytJU&L${4DRJelo@K47=f#Y<`(0gMPOhoprYu7EHE0{Dg`(*HERr*fr<|!zH&3<@H z?hdE^Q3(uw*ZT=`&J6>DE*U9t)H0o{R@_xDzC;CIx)NgUnFx`g70s3_f=5V>-23+Y z>{Wm~PekIc{j9WugP`*@=Rgk$*C5!(j;ttdRPr#=?A&ac!nX0{_u1dwW^?2X*ol0= zRm;?h0|{?D{rewpTlcwauk0$f7w0-C>6^W3H+>|EBW8n_V-ZqRa3|B1_G!K)m#!e` zpo$ekl35VY2~ewj#!(wmJ$<1sf1#YknqBiuUPHgk6-WQiBdV#v+ZSsA^fk?}2b)9Q zXWwvWoZ=y6eENszBV1{v7jpB4Q#4<6hxV=RHbmc0@xVGhu7wyv{cJ)MR&J~5?(udo z6D3CWSd9Cotim}abv2*tLEmY*0WTq&odjk(-HZ9-fBK`s zIE~un{T&)#skWdxv!O6QtjM~v&c5=rdgr0TWMg#IQmM1FH>-2brD{&q^Ws{!T>bI# z8e9-JHQ}%^YPfpDo-xOl-po!JtJ0G|NK`*_fW>L6^_8`eZ7A7T&L|1GHnaqQVmI+vFKh*MgK^rr<8<4yxO^LXS!vlvf{D)yM;N#*$_`+g1!?6t(1-~|Lvl=-ykX=)a}`M zCgA|+x5s7gDh~FCD8yYX>@f`NF&?^X9BhR+#59Qzn@B{>2t?kDv=^R;LLK^eOSj?o z*5O^%JqG?eAU4;ducj@YPEbIzBu6nkY#_!k4>L+4nP3`n@Q3GTa9BGaC%4m-q#Pra zZhLps<@v7dEQ&Zaka%Vi4g#5Mj6Jks3J7n&_NTzC!e4TY{aG0pQ*ol%bV`AUz`kFh ziG)>c9gyz>chz3zm0zq+@G#nUWrI~pqDsBjee;zo2;C?d@lpN9k`-sw+?;{VObRlY zcuIMJ!_oDrMCK<{oI_fhuk^ya?D6<9{jFcoTfV@n3IqI7v8os=cJl?*%F5Zmt7yAr+E?yIN zt|buF{IjIAgj>X{-v$vVa5)@8<>?$trKD>|$iuH5-?e~#{&FLOWXhi~_kj(;`WAOT z83AiXSLCZ*@;1mY5lg6DE=UxrwpX?2dBr}2T9!owi#v>|JEoKEh4(Zg#)?oTtn2mJ z>%ma*LcWdkU?75w3-`&stAq+9&R<9T9&GVNS`wrPZ3bOyIbpT0GSj`z=neY);!Y8Z~b8L zLeXN;bc=Qi8Q1%IZv(~F-Sun!``obQi!*N$_i-SEqv|KiwC-*={B6dN1{WT9kGER8 zD(B&pAVh>T4%@hoQXvf69OupA`dL5L}!cf664qCV` z2d1wY(Fj6z?*u8kJUq`I3Kr*&rJ6hJwf8P| z%Nhl_avkj4Ng;c$F%oe|b_0{&JHlQNlR%46Nq&Ol4cg*M+$c@6`pVwLzf&ioiw+1nusZ!xh!~7 zXQiw3hNDE}zZQ#95RT+)L~{6~f|0@^DP8h5fQyD~YXU2tocT==)w8yTo4xaJ437}p z%Lt|A4#)X+DP5!$>BlEk{NWZzWU|L=D#~DpxiPSde1z(Sy9#$E=$_+Cmi!J*wW6I| z?(aN3WG?6%MS)0OOW99F9`aYe^zRA1T)wor@hC)3_evD%&GCF#$-(^u;xDoVTKLit z0-j(K#}AAw3LgtsvKtQj7l6q+G`JSWI3~w5kdjce;Vt%+#4lH|?7R0TI=pd$kuCv- z?OI<2%2-_xMq7vETh3&b3X!xD-wO7wW)it@y5YhPz@SEP#P|xt&xH%ZM?hJl92yD1 zm%N$`h2V>5d{lw7>4oyXT4;RFm!3@@vgb~mLL*yNar~-95h$V}Ge&USPoSLXXv)N` zQi=ZjvuhZs{?&?tzA9#4!$2IboiQ7WF2Kab=7R$dq+*?&@j|hhRYMeAM%%kt4oek4yU@#VJ;{%-tmDcdx_uic*vEo2yh(@ClOEWC}V$XE^l5{5U59gHk z?}U%2EcO^}U7*8IrZ$Y(dgD*n*|gYHBfr|O(Gg?!$jJ%fBK-V~D3|f6(M$;292FZ-dF)h}+?T>b;V7T~`XuYMB)UO_Lr^m`NaWJ)RYY{t zN6L;vo!4?YF`Fv2P+E9As5)iXUF-re2}P#Z!U^_iEY59~Rj(ktUH2#QY@jd3dVQdS z&OS$EEc*0d5A2v)lEmB$@d zy3D3dWM?-vI>qSCC0pV_0L9cMTtv)g%WPx9)tH#6&9GE@x*{^!lD89^QV~=nTFH z{nAgJo}52{gv+-mBxJCNMTDK*Jp&*8xI1g`Iz=KVLoNuHZ%_=9Wp=qHSKBOlP<;YV zZ_W9PjeAznjhZlw@a>RRnhk)G{fl|$og2Iv6W){_qgL9xi40xIaUV!;0@A^>ZK_%s zojek>g}b@gqUNs-E0wAJG*=E;&VdO^6Q}ZRHu%S}L!5uTaULT-zkhrT{fHqqHSKCa zZ!sRlv<5)E`n16%xz5!;;()x#1`5dBheVW2*ausVaKt?SJWHLl(hA6xaI9a|UZ4k8@4xq7yd z*G})_0H^JFgbtaoAtTu^dVoqMW;W6{PYRTON7X3{q(_MUF$~`0Y zdDAvIoMr1oKTq)U+r!2+U(j+yOXyt&wfpvJRevmx>Ll%7Lbk9EW#j5e&+5te*U|}P z@(nE!oz3xFdLUTei2NNP$JgR~DRSw`Zgiu~vd(*-Z^PqZKM!t|{55QYFO_oL1(SO{ z4;1-G>Et)NJC2@DKmY1H2^v{yA*%!DWP)7fzFmVzno?FSLPxjFZqS&l20oC~L?U7< zH!lAU!B3KIQ!15Kd`gk#HRT^Hszi{By3qRbQ%Ndvpp#D+ckJ_9ah(t(=0)}civk!* zRVTjoPW*JIBd|!4`E^)M;qC2r;!3CUZ;PvLix`y=EzLgLU|gRce&32T#`UPr2g(<} zAdwFs)Hy!tF`)-|Dn)2{S%{b!AZTh3| zz4jhUp&fWwnFwrWR#7F~Rx7gsQf7aIAkgbY3e|e5B|#HT-tg_vi-Ap?UMp^;ASFLHOGsNYblx z_|#X*ER-mM;y-q@diy)UQZD4h$a|2)gWvj%VY0VB^FHdvbsB^T?1~VYj1j+4V8b zVU|ge^v|(1->;`~w~0%15GAQQhCbGikg}*VrCWnA0+7rS4PWVbPAwpCQ15 z6m_qC4k5gXbz%5hoWW?I{4uUlArGW5w#VU;aD1XwF!MXXyYc7kuKl6&#DjZAU|p=j zQ~*a+T`*L=D%^+b6vwAuAmzrVqUGSA5!PEa`VE5G9^!@vS|R(Ncr7)hex<8-$yPGx z40KeFTFfYgSTsnTbuSv5X+5`Csrm2Ud*RDuqTvSHL+h08>D=*4T;VNk;au@}=iHOH zuYs{^yy&StU!2GpBw;SZwZhREscM3uRH1u?VWU$aX!sMhTQ?+mButdB1X93Ro>}{Z z7D4~ciBc$hz)i8yWt!bzDOC-&fEFUAnDJ@GZk5u)UcuF_6LdX4*yx8QgF8Q$m6e{F zae|;V-MDM{#_K|(|(N4B4`|&UqIk&cq)(3^+>bQqsq63})Jk zE4}Nrzu&p4{Gw>oyK;SOgrv%7$-Z*^P%4mvwYi@RF&F_nUv0YFx*im&EdaFdM|1Ow zMoiR0HZK6TI_rN(2-h%;v*TUm7z5v;)!6x4@jBu(oSD&cgX z=s&|=;vI8tOqA}jL5!$#KZO3g0)m2(-K0KM2&J&V3zv}P?#1RqQ-Atg_?rC3yN3aZ z;wKw(Dw|aR_H3l|39)MWcE=pUt4*gv*Qo)MzhR&}0coK<+u7W!T}TDfN|P+Q?^Al* zx9E7UF?4=1kr3dctOmTFL-7MPOVc>vQOT1@ay5T-)GL`dLrD(we%T270iJotUr1tC zJ8}DRFqJ7*L_RLLx+a>!zjaygD;D_-b!L$cK@Kzv#nXSC0WMq`3?rVmZ4e5FirIA5 z_S|8zNj24gIk?gJXxiBp!al5HN6BDVmstm9eBQh~`1d;pHszk&_D|zn>G74z%a_LK zN`nrxnZxWJr6bDBDQ-%Y#YL9-9h+sRv&w(S6DXLC{F=JVd!_7VzRiA{zK_938Z^Jv zU1Q&I;2(mOA#xQ{jZEm27L`sb`N*O>x(ds%7>(liqe#aEQ zFX4L6g)avPngKQ}P;_ERD6>qR+v2l1&aZRQ{u0?d~I=4fSn z;e?I%A4pj5e%Q zNmIkvv>^tBoKBDB%TgH2GFCbdQh5pT82Z^wik2L6g^2YzMYg#6j|oePY(n?!E|K9| zewi(D=#`pLPaUG*eb>wu=f*sY=}q6csD4(y6G+`Yw20kOt5!Af*g3GsjtXIw=x;kM zNXXwj2_s3Mq$*JY&Rk$Z(2L{+a*X{Ms{Bi|o~SYOK@iju%Gg?EG;D8!*QeD(82~$P zhY~fuO;8f0Vr8QRn&M>z?5<$*@kt>#;Xt_Ah?E-m+ft? zHugBpS}?oWAWzWd5n&e!mhASA1Y)zUR{` z=K8ao0u<7SE+agqTeh5CigDNGS}$XR@4*p5y%6Qq!M0-u>acZ16BY5+t9!kiALPGqo-Tc=`BxVK_i?QDL;Zz#WI7+Iv;ycNfN9yDO*!)-;VTM4H>8J7iNJ)C#_3tkaHzwg_#Y8XI5I!4~z zcyg?Vy^MkjvhVNnVEfRRLo7p zA@g$%^dN;s?<`mjGg%l>Nw3My818LX!X2O5zI3$}38TvUJgK4-SYJp>w>NsQZ&zL_ zm4LkhEVB^E`DYa1Nx@T2pHEu{ET8Rjt^=ypRL82Y2bYlZCb2f`Z(Q@v_6^QxcV{51 z_(|%o^H0GyacCf2GwBn)-E1@5aT(a8zXq8p-!R-5`~1#{*{e}DC&5_2fm?7fh9)?7 zcjrfCzf!`tdy*=N;}U-%WJsz~+`PJ}e%TaWy}qLAi=!; zSA7=Y#E1xSWT{H_YOk0ii4X?Lq8Ae(7Lh=z*T|FXBr1+7y$R2jZo|KdjU(}~xFo*G zG}-fTg#=zW%-EP|wKyLnO1UE5vV4H#LF3v~@r1^dcM?`*7SNh_!SsvoRJ6&>6i1?x zDa<&fv}8L72S`JXDW(%gv=%P2Rt@ zi=$WV9H>dIP$7Qy{8ky6yvo5#?ar?{!-BCy2@T1+;a!oYDE|lh4F6e{nqPhN#a07CfzvX97XW(AOt5BA57FAt93iRzRNN&o5P&iR5&G)$^g$Stahqf+TyE1!~-ACXYEmND#% zlKkZKr?sd!tgkTsuMO*m?tbWTNi%9eqJqZDBp2Xe^nhq+f0w8pP{7(z{-Z;Jmn-cV zP1R+&BYw#U$EU0X6)8!_asWM(mLGY&KDW{%K-!^@2g;pcMdOliy*WkWR0z^H>TDzw zp^f@$O3~QBM4+EtU77(SU&1***m1Sx=h%cE&mT9Es}C3LYkK_ zkTq%`SJ4@;nbA(0go(Pcd*pywXyv~SEoQMM=OX0BuMg*Cv`?)qA4K~K)4>xf%MeY& zfcgNnYs{@N-X`6tV<&OOjgSWH6LoXyAe$~k`9bI_u!bAvWOt|!>Qyog+MncN=n7)T zTjlwJ-CgT#m2Rki>$!}$l8VWwT0z3i;#k3No2@=p7w%X&H#}XuGwph@j%bH9cRO18 zf@{|cyx3vr|K2~ZP-Jzc!noyq7xQ%5ca>25MSA_;if#ef#CT z&dru|D8tzPZ-(`6tB_`24`ZK9T=hbcVx2gFQIof5Onk71<`~|r@V|MlA4BO;hnz0X zm0V%bRbkeZ{0iGL^4}0{@g&>Y-|JPmxTdAK10n7{EmcL)h4i1B=Y$v_2&%da=SVd4 zksA`hZC#hR#w}lTk9g`i{z6N$9X4Vb0_N|3=)z;j4#1H{d#>4I6_;O(NzwfSxWDnL z{-Tgj#Y%mX1GIWU3MCasiQ6Nr&$yabweq^+MaVD0q+s8WzEO_975kgSN&-n+C@z@vb5%xb#ky3HyZnZ#gjDgWQE9nuQ|7nq~A}<96?5#J>+&xN^QXV_v`xU z1BwA}yJl_G_Kj?4u7J$8Vfa zG!FyxzZ2hZQS$!`A~fCXMs*!2^>eggOrG zZ3s5e&WTS0eC<^)TI8{2f4cBSZ5SwaR_30#WNp2Z^R>rRI#cJCcb7i#5MYL&Ey{z- z?E!u)-n!p7+06`dHjM#ziN_I+gH>eQxT?pkt1 zd-(Q!5X)#tr&wKtcQhiXwq4B2yW5#wfe~{IDS}bNvzO=2rpg=N(>XIV6k>S@w`tZHCg^3Z`btcKJ`&w@eUb<95n#AWb(|{q7w;ODB7#0{pjWY4*fWO@5O(WWkUm z%MW?tF1M5fkrq{+&eH7@@f%R^8X|imrSs!75Vyh#`h4%OW6@mLm#TGfx_K z&~WRit!YS-;u+}(#w~^t67_bdcWM8@${1XS(Rg=RKwH69vq8FObnYAJ^<254s#nbj z9uV>RpQ8w$cO#gKgo+hQ!M8j5&hQ(~z#Ue2D#l7q$fy(0dbu4crgZ?faatszgfCMx zdU-QZ*ayIFP=BL$Lh?e&uofL->6&f!eQhP^<~bLtV^k?0zJ}xv{8adr*s8;WoHCT( z1mREa4KkwXrB=yr)`-!eUMx1g2u=5E0vTkGy-o186Bm3v4{<Gc0Ae_*%hWeu8GJ6U>e|kAa|7&U(Ipl&inc^EwwPy1;QV-!2CVBGMQ7J z%Bf2dWf1XN{ZOL+pX&{Zfh!|Vs5~1uTe`O?gV%?g*y97YVBYmo4${dOjK^jmZH@4b zo}=f0_mf}((VhEcu$?~QqcLNoW{C)6M@{6Ql?A%LjSN_LO16#7F7x%1^!?Kx{CRnp zbx7tmNE)~GN61?{c|1J<+dqArJRL&Do=$X{6AsZ`CpvuAh|sgGTS~|Rr}tM;c}#VP zy#G?M9SeyN)IJ#;^=Ds}Ir-)r^s-rWd5i>e2r0=O(TZdG+g!J9XQ>z6-p~0WAz)=l zg5Ux|t!jOsJZWAfbF+Sd*st}IdcPn5-u+>Ai&1>_Je``>e zDfoDKpHn>ZpQhZnQ3l`_vnQl>z0|IfGJh9#)wGhbz>&9h^mbl0w%1yIVv6W@UFjq- zNMIh*Mv7^=Fl?9Vlctx3wV4iSp6}ntMw&98os=eniJ70C+jcDV66h&hG7wiJn(vp9 zjSxKx#SYuQ^A~uJr|YMfl~kPj=2fKSx+E+#n2^g{IKqyQ9R(Qf1(&F`)suyevV6Tu zlI_tICG(FVMCZ)!qU~7HW42S7o0UZ932NwUU;bIj`=GxS3h%`KizV_C_e0!7LYR;W z{(gj<*b+If3^@?HL>Z&VL+`cIvztM2kk@a#Ld?&&f5+JBP$C8ZHOC}jvm6zvwMKcx zQ_AwRg*q}3REia;KPT49(S9() z4MM$6w92K_AA{MHIFz3B`k-~EJ5Fa73srW@=27pn6U!;!qGoLBP-k(Xb-?Dq@Hj#& zE9f%7D&V5>q>2rHSO4UE@|*T(KxHn@{zyvPgoW&sZz?!2cbuMbym3kg#l_Bao5O^Q zXw^>WM8kP~+SzDCXkI3@(-=(v^Ms>u&P0<5y}PgoV*k%8dE1n@T|MWQSE4&UPDTE* zne1fat^q)0WP%UbETYyDMM=@hvVi-px63#;kY{w!y& zGw2dXpI1-Q)MISrCT;bD9;j9EqjA5DS5>+3kf3v}Ro30227q~$E_1}tPw4nuuOuH) z<_jzVE=d>JIY}WR3PEXNH3h;}Ae{<%imo!u1+Cwqw*>b7yMmuZks$nE5ur{B{XEO_ zI;YX2tUo`F^Qq>=EFE5snIbwh@adNF=?>>qT|CJL6{{IPW7CBmlewx)Gd5#(II49n z?MzeW+r{2?-Wn8T%7ptsHAY)&`)*-&O>RL<&E7HA+M<6COiTw<)sp^&&?tK)-_M&@ z(OCG+djrqzGj65#<4oa(H|w&^wG}QHO1)A62cLU2BrByXUAI2>b_|&7Ly+kym_*Gs0-jr&XC?A3f~)&6LnD|dK1AU)QIb7)#XPZ$kAFwShG$hfBn<` zqw&TkZdmQNd6`Au3HRU0q3Lqv=CbukhdId4w}=SV|h4JLTeN54he_XZv6_odI*v)Z@~J}xko>ocqOL>)H`ka~(N!b$$fD zZP~`fZliPp0kwtm|4iIdJCgrtS;g@X(PNWVZh((6l!4Xd~Kn3?qjBQlCE-E8Lt99 z4|#=-?DVP&h|%T!Hmhz~lHE?X)#2g(zxMxhc&e)7#`|JZS6r4y^mb&3;xTcO=i4j; z-^{I?z3%FeNaCB$ay)+Ery2k|-oxR;zr~0;y{Adu34m|WI6sr2ajK`1XOTep7LI|# zKc@EP452Z=hRUK``H3Nqetx4|UV|fAB3hQkPNkR}d^~TB8$G%hpx#oa8xyLO+aoug zNL_*zJN#DxCL+vf`~~L`#;(e@B|j1F>>ck+*jx$9x8VEyDWZg|ru&Yagx9g@b6ptl z58f&y(q?b8q!)U^({jyg=gElk1Qb*c9;X!3nC!2nr%hGfp0e|G1du+qE38UZulCo- zwT!4ZXPDh_eluMR^(S2Jh!ON9Z1*AbedPSXXkg`rtf65Fjs#+8{IoRg$c zMP?E9zNmBPb)4Rxq24nYgnDD-(}$J_4O9zH@L+^SY{a_!zfha_wbGGqChgmTVjpey z2!gSI7jV0M7Mt(z5Vlz$pyKClnsvAm+J*K&q0PGgA_OufG*~GFUT5GJ5YPq#oR{Bv z;ByLSl8vtUPJEM8Irz`_i!O{y9$k8Z z7I~-1(R8=B(v`K&ec#s^i_P{~4&e(z6SNXnvVgYr*Gzb_2(nA~aiImQjUhu2cLBjf zrJPbLCB8G%|3vxG6QALVsWeUkz8bwAWWKuYC48NW-Xh7lFpI9iPj&v)TP=r`6KyGJ zD1oj>$(oh)8$>CoFgmWpieq}|>Vhst;Nlku5U>P}@e7$R3`k%L1 zDVdM}SH22KV77V4YV4Hzk`jl%Z7Q4L z4x6zzdY`$-ekgjqaIXycij{f+jDMTSkWM6b+Buwa&G6t<46}nre^61dZgD=Cs}=s8 zJmTu{Ly=b1H~+mV2jXy@D1J0&mG`&f@TB1awtE?A{Hpv=f|3DmzVv>hG8D|TtY)wGT=><( zV&dui?>7{X0)UC^A$X@5l)@UB{T0xs;qEU`MMAaql#YOP6-k3el+JRI#`U*pMr*e? zNO#6s+2-dZoxe|wGhSs_A-_Q$?bhr9h@b%)|hid)u zoqeCliwB1d)NIXf1nSb8Wro11a#ekYyFv>-u%?gBQMx84DMlHrZR6=X@)I`$2AIZu zRs5_QNR|->7%EuI^o@@};iUJuFN#yRSlkt9n_@&SAv5e)QbjQmy^{W}@`<{AA5|C;rG9moh|{9l7D!P?;wo!`CjxTzN8D7{w8 zTT%7ZQM}w2n0`8#QT6@&d~o^i%=5w0Wzppa%Dffog=WIiHttd)@F13Pb!)OXGJw7G z8e1U)w+aB7WPhjvz{MGb-=@F4P=0%{{wRx}g8Vo|FfBlLe&3N zYVh?2SP;~i1#W%900y?e%J)L%V6+Pe2p)$a#b#*bzkO@<3p@nF4#TMNVUMPUktk{< zv;@efsU*ddDoba=0`VnxO;#nxM^$BykwOjhkbEYvEI`bPnL9~{UCA=i(9CbmuFc61 z_MA5*Q2G_qeD*W7E?qc6aM9CzGPyzw+eFOjr>@F;aJE2~F17Z$J?FL4Nd91+!yE)? z1~VzIUG9zda z>}MlUP!QOIgoC<=16RNJvR?jJt=ag>RkEjdyJ<0F{B)QW_A>Y4eP3i zxM!+M+jr{+yk!u}&ubIc!-2h(xQTYsB3&WLYrp7|2Rz?}g#5O>(k(5jO`R1>aw)nA zDiDDoyIUBNJKIWKdF=p`GxE__qYm_&6NbU@+WPeCF63B@aOr6OcXs&Na6IxO+3~f6 zrP3_i^3ty!*ijZ(1=F%iAbLAQ8RojK9|pzoV1PCEaR?mda_UC*u1Efwph-Djxftp@ zqIes9RDCl8VouGiu7oKmbT!Mw{ejsS|8K)A?9|D7b7jxN#&iQRbK6EyJ__~*clAT`^EbF zk$^ouPoJ{m4{W+;ZAiV~DbeGoZaC;W=kT&SF?Ypr=mwhx!z0l4{)!S0L|87NVqno76L^HbZjS?R|4!36*C%MbT693`M3oL z+_C{}I*0Q617@N=Vxqn|Wh-8yKGAP?v07iz+V*$zf)w-i9~=1+j}I6+*u2fvtFG)< zmdIy{R!_gz+@0U(?U>6f63(arsLlV5*>+A9rg9N%uL1?oYmnM)Y7rFT_Wp!G$0iiP zISqc)O6=MCBTDC#3N23t8%B#@_(nb`K6;!gtn39tQN6sr=X73KXSGqQvV@pcVpaa| zIr>&)){W3~0vq20@xM2@)FaPk!Dd4x2vA~kw3B?^eRUwzR!M@G8B~ImwxHQtSRyAP zFJUjzHt;Lj%l%IJ-F^VC)Pvt(qZJ*h(AlLa2aFEEV_kc@Y% z-UhZ;keNdqJdjx&FpXCbpN3u};)UBYtzJmI@{}U2{#tqbVGUNC9MsvHIR zRvcnrk1i8F(lxzVrYZjL3I4D>KGH?i(0W@(R;kgF_!XH~7?zX|)HPp!N+K0)wdOP` zEeh~|`1;DIxSC+w2n0w7K@*(dGDvU;7Tn!ExVw9Bcef$IgS!M7+$Fd(xV!t@f$+Wi z-k-Ntt;6YVe$33NQ&nBHYj>Q9qsaQ5v}To~NDdS=oJs2V&Z3KHus&(>V?}M)YeJjp zupsc9LC1&1N{ZDwBh&I~YF^LPx>@qkVNjcVG&IA_Qqge}6 zF~&xfeKTV;qXtLUT3bx9s8E!PCO`|UbG!}oihd^4;GV!FgJ-mER_vjGfO{+#>F{5R zjG{8mTZzQMjPHca&fF#22+e(H?t{`t22V0tggSnQ@CFu6pPj2!?lIgf-t6UOp$lFt zt~|2|X8gwb+4kebo0HvhF`03i>;8OL`Z#kLeH4=;JG(x8s7*mdS49I$K1WDJG$X(J z2i~H7a$veP7?aDMj{P?-IwCJ455zJBFC3l)vb3I&ai_iUR)G!$Oh7MPlJ1)n*3%ve)uW zrfYLmk=quTs3db`wI)2fb5$7+Ec-^ylDF(ll254~JqtvoGKHi`O0)$Uv~~PfWd7>C z0$9J}r7RPIAItQ~6s)iQ+S4WHUm!nMlpQKeT)};+NztMQRuz3qt3#~w8pU_>hjmmu zed(C2;7!?3BXLQUPpY9N5t%yZB@=JQIJt?^{ngn$oLYgmBYHfyh5)e=mTx9CnIy^j z5@QEXVkv<}sxB))hS$Y(oGGj-`&M+~)D9Al5A6v3dJXyrnVNx2Jf7(@cn2nf)UH5S zZb8YA)Z5aMP%TfaN%B`TmdS_I=Xhd`lzYjQCu+JoIq^ez?dxa=TeEu4{>!#q}8yRkNJ5WvLTp%!Ep?h16QzMb8^hv1* z>9K340t&~ztsAc=2|Hr|%s9`#_9_eoI&4FMh|=9EHXHmxCq)Fhbj}Qo>}Jk!U_FI! z&)SR_gE+Mz#TC;j({zenXPGJLfDBV=Gn#ANPy=A~`!u~CEt!H?o+O<3y7mA3Ee4+5f$g+SVx>ko5=c1Bk)@ef;#}5IXm`0Fr4tl()my zWt&4k^utW>!MqXfux?)QsjWWY_QF257cw;P)J zoZJS%`v&0sb?|tkbhuGQ_S)G0%au`5gQ~xZD=(7I6xMs zYOJR58&NQ!ylKpN$R;jLueRXSd)RXwqq|6!pp)#)Avx)20PZ=goDE}FG=JMqjdUB0 zaGPv_w|!XMgP70TBD$NN&aw4V5?h&mQEus8fGJ_Yu)JJM7eMZ0Gk9F*``ETi%wsYz zwJ}qW$RT%zMB$AIseFh7OK=Zw@`ia#8{j0sEl5l`N1R>DtMzT}}+%xMcd z(HA(?r-uLy_s07uep)u+ie~gt_o&^bZAex(l__8LpvR#YYhIplB=CsKz)aXM-lyI1f2*|TMWt( z{Mn&lKjE2J=VO;WBy}(H>zb1MMQ!|^G#854GWBg1rPX)^&xOF2IOPn1vcNM2Z2Ou6 zyxuldbWF>|IcMflQ_rt>)&G}+wYFm0>GxLpoGx?C=wFUbS*P(0XHovcZysUpPz4BB z3#24qyX%lgq-MZys~XOli&ojC77V57~ODaifa2`r!Ko5{jIA>VhKg$IZX;L(MPi{i@la^oY4S3+SbIH9~YG0?TdoJZf#(Y+U;X&0`McnaGn@($k+rE>fQ$D{C-^l zEaOpknbXc0R(`Qq#v@6HA8M=F$w$NHe;EHqC$u*ko=`JY^x|}< z8BKoSgkeV>g!?c~C(M1`PtSF((B%s~+9wM-ILh94ex5c*48AZl%6AhKGo&9cHihCZ+u^c^;P6<#~GSan@$D%tsUZD_|*}82z_u? z>8Q;PDP5o5A^DhL{woTw?$lnAv@jP|?RfEj`e9F~qt1W>UuMEiU7wX)45y&m!X-&q zQf=lv7h`~(ny`$wX#cElt=#IZ+_N|c_~kfWNj-kjKymcY5DC3W)}$qm&CwKzYpy=?RT@`ic(bQ}J3=qe(h)@84ADR4A^qG(V17*oX z);b~(0f5NJ9^gQ=OawIo&`DnLF=7;6BeJ}I;R~#pYkzTty{Pq0P^9xxfKAp{T$s{X zX!R*RN8Bzzo>o}YTKHa`_pXK@hdhAEu0|tVj z{m9(=KxxqC*x_~B!SyoW^A|6jpXsUGp+Xdv)oI4(Pg0$h?!2 z={u*E#YCL1gs}U>o&j8q^MwY^jEOPh9-NaVWNE-KUCvaI$riExofS`fgE82-qP}at zCU`FV<&k$RJDwJd1%)V>Wz+G~s$=5QYzz4AjUWa8qtU26qe+lD;Fo@nQu4RN%l95* zzXBjvAGOJW`_4aZqryG#b!Kb`Tlp6?JRhe90Oh7giL;(lV|0__5$2(o$b8=xxvV`$un$~lrPGXb=Fgx-1D;^M z-03Z2a@nm+g~wgWJyE0Zp%rBDOYx1ib~JqmFEe*M+*NQ&c(-XG<6i7I>=$f9G1rMJ z1^gv)s+!HsojsoDx~J4Cs2$=Ulw-uJ9xQ4xVFi0Q(VOG-MN9LXvV5jHPqdUp()HYA zv`{)WH;9`sgRJR>X?r49w3J&CdcKW)3fX-hp_SF&ga_qT5;vk5Jr7^~bC8zxK=w?? z;DwK8WX@0RV;6l-`b`SerEg&wHtQ61wkeX|%nxGq(Rwh>dQ5x~UcToV9VhD*OZmI1 z^p`mA{S!1eovc^QP}b{rhksj8$hLad*{z01=h-b}S)$@fJ()#nwN9)G9b?uds{6OG zs)_>sOTG{XC;(15IKlrd^G6Kl$t;7X^m{?2mW^Ip=W+NeEPf)L;SR3EsgI zIb>LiZLi=%6EQaKXHWN7M=$Jd|s%rCeJ_1(zXrO5idZGFtuuqUC&4O+FZH=2nt`T znN2VDgqEvkzBU;ZcTtIPUNox~y`3*8@$c7F+>~uu!YaWoB=M%MqgHzP;grklW8vCo zZP`dgGgX{$Lct-Y#tMiPavqVtGsmh2Cb|(Yv3(b#67r_^mIJd$n*p zP7%Uk>AQL!fXL3&ZRn8?wT^ZyrOWKinvBA!x%$$^^-jrEpm_7DL^r8k;P?5DO{e5+ z&;purgAu4QWVbcH*k4ngj#0K5*~=~PDl+8C-+AKoFZuH?p)krmOXFau(n0OFa|A2p=G!t3e&rS&O+@oIy8JKI z{4LY6xru6sz6A@xrtonVg?bNugXYO(mgp9-o`1z%$DV;0zEK&G((HNmxD8R3!t9^n z4543qGg7${RFRIw#MTVYGXA9;Zq-QVn*nI9br8s!8D!bLxT|+!ceZe^p#Jee$ST+exHc22;$$Ki9SDqtrGJ_X2 zOLf-CT{XTM3=r zf`*h%2e}umJ)QhTRpS(SGeN=ZZ?ngU(hEL|7yB&z>Ot*=I#K0d`<%FC#i-7L&(9mq zTbHkWmi4~LV`eo~314F-c&3zqc^bp!4jj1?`xJ$9^re=8#g>7kmhDQl^u?B0MV4xK zDWyn*%7Gh&?W^~t<|+3Kw+Wyb%LXEC)r5Vp(WrWFmU-VbSb?dgZ4>Y67GoJs3exkk zFJPcSskI!?hi0UF&B}o+&l@v85tei{#-lk&fiR=^8s=T9}Zie|pQNq|2xvLijG7SUw zkC)xC=*DxgDH4;gTr%s)zNQQkY)TUh_vb;FZXF&x*vaM#7leJaT>DrGe)Q!M4~=Dbc&o@#r@pjB45jL<$)SDc(GuN;C;6@k_=6u?dH<41_! z4(+*-ZTi{K4Vz0LGoMko^It?)*ToF}b(PA698$qpAqU=&`)c&yJ_Y0XnF{;6&MLTi z7`^z;nA9MPr=#;mV#Zc_?8T4c`n}0VWaeYbgJZA-tbx7(Z8KhpX%Al0Lyet)?J79u zL5Q?gRQ=upWO{G0iL9TZD_~nx*dqO$CcR?LB8cdDgPQhYVE|>=+k156y`+>=0(YFhE?H>UxWM5HVyLLO3OwZNzrz!!!A8G!5L_ zQL0aD0%f9o-Eis*!2o!DL5a1od%vjsRpf>IPw!fa?Iro3_7*O2Ec-uDYlal-hbc1l zL+yWepfqfIebY?KU-a1%UMh!wnJEll8!|;5u;U}TKiK3G3d68F+~lj+`zFuvNp4gj z_655a=HpBsZ>eZdy^-NXN~ogbU?(tx8OnO|&3i8|*Dn+BjqtNEPmPZ>$3tw~?w7IZ zrLnljZW~b+?!C$;iDS2}t5RWp)#Iy4a?pgEbHEn54v${&!G-5_+ zpj~wl$q2EfbdIj=N%1>|<62iffYrfm?XIXym%e*R zwtL4zuM_6&FFmhoP#K~_3hPt!`-15#kU zA-YgXPoZs3Up@5MNFiaZ-Gz5`%*XNvpyDz}ic%^gsh%}#Z2~g@8(JOAPdzC;m;?u2 zYlq!9NO#NEubShTlW&T;F5A>Na)}~PS&KEA6)OFue~7N!tNak-GtE9bGKD=7rf$8g zsw_tntMV8{*VTuO`L;d6^n<4ixtaXmlRGrC0AQg3;oS6?@{eQ$3_DZh&gnz}Y)4=38Kjmo%rFJs0&Y2j`Pe-_CJ83C(R5 z%ojd+66ZhzFQ};m-sgahyt+v42JtR+Y~QlOCNGMgl^DCt8B*J@f1LAmmdy=Z-&PxPBMkhwR5*iU6uWWgAd;6iI^jiZ32#r z4MgM91vV~%c_b0feC9q#ja*l&ir1X6?sZRdyL=HNk9<(p*u0!#SF1<5{$!)m6=qV0 zgN!8%ss{CGu;J~Q4`51)#$hpbEn5;zKzB47ZNU+~k2yoL0Tot5^W>!RoG*Hu?4oCr zy3hYPNp48(!{(`dL-!Twu?|m{R4z=svbNU&R?YD%Z>lcZA`L;wl*Kn28w-?{CgA4s zm_9pO{x@LZ^0@jpkbGK!4(KJN58Zfe937KQf^@Z+g(tofkTG^FW33z^+NcCLJ3om^ zfJm?j&?u;#K>$i-GK@S1o@c#Dh@2`dA^)EIWuJ%so(FXd(ujER#`57wF5Z+pJjs7I zmj7qz;Y~zap$nq>ZwiE1Tz@XRgc02vRpyZ1kYOwE86I1{z_M0m8B9Y`h^+UgT17~y)q7ty`kBBr^x`YDvpbhg@hB?Q?5W788$bhDZ*hT z7|6C^aLJ|Z@M_Qp^p0;gXS455IeL3kaHAms%N*?ekeUuxrF@}1iB+nBqiKcE>}K+U zX)+#Zt`Ts?B4LK!R%Sa{^9Cnba{*0e%5@lg#g%w({`-`*={9w7UsC(-N%o#^4li<@ zyv7i)E~h++&&X4b8<<2>`F8r3un;_)q)i}3g5B~>MEY9RI3!J<*HQ2 zsR%aySIr>*oHso*bA?wwSt~nmvbk{jBqy7Lr%!TXBzA>m5`ykhdj}=h9X;JVyTqBi z=`P(;>tw%{0NkX1vMH{`6)n6f?Q)u=bM>)vD0P|OrlymP&QkKMyBT)r)p0?P+^zpb zDe2Nn;S#(<>}YBHb;|`|mpFu(akrCO=qM^~+Om5cdC<8W3S_K{;tMuN$km831Lu4_ zuX4YHI=s?Me}X3^y@*gdk#CN7~D=eWb&ZXb@$ z#Z*lpp-%LSU|JznR^t(V+-gP-o{6!ck5{VBnwyUdOz|zZ{HSlAq!d zxIf2;T@nq}v{h~gd&8(}0w{G_8&Znnb$(Z$oIFXz^A%c{H_M?F%PEfU1mFJlws1r- zg@_l$Lxc;BP5aFI!NS=knXug=rp-$DG*f+9l4hjw7D*-mHnN;xUp3oe&Z^AkGFc^D zD4^+5c+!(?BJp*dj>-6jfoC6(~Qu+1Vrx*S@~MWiJ@m2i+wi}sgV?^!650kB3`Z}R87eR zG3 z_w7XOY6WL~dZ0~_ofKPl$BE+9g)0%Xmg;`7fCG6rcU`CPw|(rakUyb-a<+uze>^y(CIN?q4JD@mE$R>y z;@d1-V0dIO*RvWK`fa$j>rLIvj*yBj&D(hFZ;d+AQKUN9i{d)uVYa$dM$mR)-dN#j zZhy8~uxYY6Y~Br0QK?fYwA0)@1eIE;)~YX73TK}m_`e`Hy@j#5ZNRvHm}74ZK_NeT z7bmiv_V-ZrFP#x3{5>$h(?slxx#}si!Ju+)3cENVVXeU+6esKrv%5o<#zr_J8&#xK z+pqj2|8A66J3_H~jpLvSw-M`DzRrE=RGyT+3={LB7)$KwkKh2D~=jkh?cwd0X$zTG#43s=I$t);vf*-$Qut~{79 zL3!LRWHZkHK;NYW0cwCx+JN`>EW)7q6YZhgk2e!#FE~c);(tXH07FyLv`{YLwj#36hp>{Ei(F0~ff|gNq&uhHA!5t+ z{NA|IVkwh|q=CZe5QG)FXFKB)R=?(l(P=~3)^g%udU)l-rX!f6js5>^j@8-n0jm3Z z#088OMS$(DbF=ArBWjDm$)({Gr$Re@g#B>IqKUcPKjHB8px}fL+O@0d!b9j@>JY-O z1hbQ3=>tq16T$eZ04oQKaO_1QNg}DV*N}>B2nsi zZ~+{b{`B=ikcH;PW9|HLutp z2r_wct85XaO%yL;km>=+e=l}&NU+XRG%|Kc_v8#seWkTWtQ1tGOvl~TZ5i|EnO!;W zde!!OPwX^$$N!EG*~G6&ye9xo0I7Mp6_K#zvshp6E^xTFI*cj}+Nm)QSD3!lww@rl zvUYD3tSU)CK*iOzZ~vrLuvwqzWsQmY0F)4c7~X+e?0jO{wJ? z?}jL9qw-Ozw?M0(d%Ea`rvnevt{V& z3|J9S?+?loRF#*t962OYKFw!hHRp`oKB#lSYvY3+t4yi*7a75s#4oHs2*rH zP3~6c=M%SQ>3w^jZP8^5dx6M^-_>W04 zJ%?uYye0*dAf*e2ykQwU7Y#v&(BbSK>dWbK101ZY>8YnfVZ+>-^11#_mW+q#tg{pt%ITFOJ88V4nHFis?BU1d?7n7|?7pb2SJP>&Ot8Q0uvhi$-i-13e2f%9 zVHIlqwAr9-M+Y)IL5tE|e~WeZv2F1f!< z_Z}WTGe)vsCA;#j22^%soimtj6FUZrSnkjj9^O08*&>$y=EMc8$r}#OCjskaf%Wt} zcJ09W<>7gg;dyp0J0mFnGMex0*;XAXQEElSr|`1bV?yzW-_iMZxYZ}^ zyHsTUOcVK+a#@R;*yona&{Ijr8=&LgLQRR-=iF2IPKC0ET3H+QN68>SCQuty(=?mS zbP9#2Pd2l^j2hyOW(G3gay3PCAIvVL3-&HWOq)oZadU+<&0^Oy^GfB;xI0uz92`kR z95TjKw==Le56c_?d-oH1W%<4e$&;7`8rVV~A+R?G#7xBHl*7fnL93_bOQ#-L_A0XP zE55(o31bLPi6til0g*K)T>CZt?0apwTfn6RYXtbQ}h9+p-+N;K6au&|h2d=PWSI;S7#VDRVhlDgAQ(Fx97PwV=AU zPkW^s-}aE5o%st!R#HBwuzY&ALl?ZRUE-<2`t0ps5lXC-MgmKNyal%J{lxm!+8xMU zHuLp#$W|1YT|N6#M=y0mtl3a;BVYmvTic_TmPL-fkcb3Z4@ED1A?b-v6chH@E_E1- zl7`<-D!>@Aj+}@EF^VI}WPawA|43J)MxSdc$TY7l#shvgh ziMk7AH&aPQ`Q674%kBub%wzCPpZr;Zl+?+Dxkf}kcy@A}T4$HDq>2fOn#35Xu*4T!D->+V|4xz2G39<57(xfq z&;q0T*`mJ6}nT>F#XRvkvYO@x8 zPJKtB7f;4JFD(2v1k#ADY|73n0}_8UhHyF_?nF@7zkXHiEAZO=Au4S_ z<$N%cUtH4V{k<8c`noY%s}A4DTca{TEr7U*HZ`epg;R+9xE3F#2JXUiR0n z%WNVP^wcp>XaA-u+nO(zeuJGmk@4q$+$|0G6PgTsuqH+R>=oQ`#h`F||Kn2fpUwu| z9Pd8$9iobYS@g}ECPYU%SrBRWCQ`dAG+59^-kKqu#>h(r@V6f(7p!! zx)Hr&;1v0zL3KQr(uhW7{>6o8C#SWA_b&1$X+BG?%xloYCANDw?gtsM6HoWmR40EN z>Hrxugj~m|;=5flb}P75b2d&XPmu^R-|LwiSyIqfVwH&VFl1~b@~ zi8o66^lJOKj4isr{`ZT0J2f5}mo>qkHv8c2cnm1Sdu0;X`Bka;e^H8$Cj2_1Mi`nFIQ`ZUOaD^ErrfEJrvaE2D+|x7xjDl&g z_cdI3FIGgs~Fr!2yJC@U-qI z#ZRMw+~^xrhj`M;hhpYgb7co3kBurN_{0|;~m5FkC>K(JS(@-OST=;fVa|wt9Hz0 zoXRXFcYji#h$bD3A9@8ZaO+c;fq=q)In`n#-IL#X)d@1ADx=>RPLq=qD)bSdjJh#m zui~;z*wN&vf76;8>GnY>0753dao$VwjxULaZcr4>6U?Inh#ZCZLyT4;gF4SV^@D1y zhXGm|RIAkqlpS0V?e$%`M5%W)1={{_o9DCno`-X92UVDN?AbiXZzlQ45d^7H=c z=#hc)DS#zV+dfOuf2KpGBBpq*Q;q2qK;m*w(N#~h3L&`m!Un7m%1r#lL9gV5Q}jyw z<`jr+RIAeo!~pKE(u^BXKLjwS$^^0If#8Wy+J@gtE*_sLo&pn_JJJ!PVdcJ7nP!g8 zESe1c0dn8Xi5O~9H(Z5em7#hjIMvokTN>$R^dZz^T?!In-L8?ZF&xOJOy}A1S$277 zjZ5{!Khhv$2dg2X=qWF$y1BC9^WwaX=IgrT7w9SulHd+Z=HoPzmX?o!m(Py6+@u0M zlgPXwVmrDcJPAw~N8)+gF|1RBoc_bsNy(U1DF_w+_k!xLc9mc4s)S#mn3&o!qj-eV z*&}Cz;U8oXtVJ?q!ma6hEbRSkWEsED&#vw&EO&8W8V1;KW8iT&Jy}*gMNIhXzg|{i zU-Ac2M%wYD+VK1{qF`qhQ&4m^{WVVrMDGIHG}3<0GYGLeflxnWR6_ZZprlFQ_WLRy zqgm~-Wa6OwkdjiH(=x>M8JpAX2csh8`P%L1E|TH^_`myh7(&nd6;J82()|zkB*jIe zb<6y)FjPG6SCdu(Fm%!_C(J=V%iwH)EmLK1k_)jHsq3eA!j;Sd`u%--MPP%kyH1ow z_q3;~AO(iwlcIs48_nEG&qUkFLxzlVz@uHctS0|nsIm;?6L9A(Lb<%V#k&MvWjgWW z=evfTn0PUf+KTJG?vN#BJ$?tuYZ5wmq%v(1IEb^ZbPJz9ivW+w5<5Np^*0yO^>$(~G&SDgU3tS@r2b=&i+Vomd~@j6_@|B-p40#+H9GDj z&Cd<|q|9@2TgH;D=bt@hwJBV;AGdSzFi3YeQjzn0-XzuKZ>9P~wRP?(DyKrl1Fgcf zNEQ9GyniR`*%T-@@C-?h1?|LS9MvQIG0RFLi9paQz{PV+$Y0|H2w3OPeR?V!Sy6G z{n=-r8Mj3JUK>pWYk(EPooL+Tn4wj|ZH6O$E8Y)AqJ!!h)_mPFtO;I16h9JF>lY+F zGO}3%gt8kw%~a@q##?5|N|hRCe}5(&_>Y*0yn!@kY$WR@i8Bl){h<)i4-swEkwfoY z+H~TQAK>jZC&Io-dC1%HDtO4-@d|ke-0{kP2;6$SJPx6Aj|+$R_ZWa9#P`lnM`!(R zEh1z8M`fZYY z))eIkfRgIh$S&y!0FD$o{ySx;M2AqAM;)ph)}T;lV?Gx;=$Jou$0hCVmW(ZdUQYS8 zLfjvxyGC;y$>Fu|7sutF`Yb5#JqQZfO`YEc%XrfF(7m|^=|yEVZB)F9z7vH|v8}rL zN)2#i^vd_o2#(9#X_HE)uSjZFgMc>~7vq#@)@u?i2S6##&Qn&#y2jQH+n3pY16t{L z%E{h4;`lgOFI7`+E&UKzoNj$d@|7*h#}&Pr?EOW<-qMn9%uI#xDC@*$=fV(uQrc_7 zM9)fb&Z)VWN8_i2mgy4-pI}E86E24t5f!w*BPq zNQ3E!z3EXaF_ZJXg!QrfcH|0CCW#+Gx3D*t!44vQZx= z*g97}2+&x+EFnBu{r7OjxTLKdN%syrOV&CKYwR{UksJO(k7jUeJk~YjU%s9uU-q|~ zyfgFsI5JH7wZJk6f0-j}J`({_mbYG{G^yTh_JU2)879`NLeq;bA z!%0)WQ$(1Ei!*U_^bBHTnDaGKQlgMhqJU5~CX9$ajCx0DKW}eb55;z>+v)zUh2s?D zq?^Ri|#9a!C8G*}0j!E1$a5OzLTt^_%=9$g$d-gLfI_}aFk?zWf7k6deOUqkMHpN za<66@7@d)+j~NAdS%NcWbiFfaI)@k2y`g$4z;woJR>m<&pRTnEF-#X*b;Ir)v=rH} z0nDFP*GnTU$n{n!70`-}Ui7jXluikjV+@J`cs)lc>G!a(!sBj6wGkH{-ug2oQ0Y6WP?$GIc|gn!l;YaB)L)%WFip zQz*qO+r*6}q?x6Xg9p55R3R(Z))9DBwJG5%O8a({2sQ5q6NM>n;5{ud>c7{+s;@S? z362s?36%wAGzNEuurAtS7GYVaEqrk~eaQ;mGMhptdr7Fq#HlCQI?Kt~sf?;FI`fy+ z&Pc+kAW-zC$42`!a6yF&px~3${1(W(Ua^6ry$wB}ieyOve(h7;gwQg}eyLVx=4|?cWEPH@ zZw*sXF9^p*iJ>2V4=69=lW91+=VWr}{_hFoLJlZ0$%}s8+Ou}QO>kQVipouQ_$wgR z3O=wEPBRAIMKW5P{tWf0y4RLUMx`}XZ`^aLhx9)`=MapuyY0nW!6T)USj~4z`B(tw zuR{xt-~D^m>f47^2xET4f>O(T@>ZE*okYkY|Eb}9NIJ=hb2_l{2*_FvhHh|;vJ7p9p0`7lASgcNi4W#zxuCZ;KZL~AKCKdWK6~7U~muI}XT6q5Tb&6mNe9 z99`+-KAASUsKR31&k8a?+_A>lxJGPm>=&-?!*px{~Aw&)=q@`W|Oib>rx|qTP zICCqSy~hTbdBuwT_-nZpmUC=b)Drs7@}ood6$}a7$!v>w(R*unF8%8VY+dbg`n3GIBB$g5q7KQZy82Via*I zgHUf+rZ&oI2}3=Nb#0(hOp=|zsPvju^;P{3zHOT$R0)6tw(dy*Y3Z=Q1ZtvLg((86 zqPScxFjP$kRRmFb$l*&Gv1pdMT3|Hctl_W`AuDxkE3%CVtG;(BCf1z~T0CNj__U2Fh%=l_hL^?18)Vu|AxxL}lSaDDM0k^sDq()f+QYYzRDZ5YMouA?KoZL(8uVP$_z@7`KFvWS zLhWQm@+7UttD8~spLyIbJ7|E5q;^s$=?JwjImyew8yMu;j-Svqvy2zrG(OCceiYtH z!%jWW*2xav3hz3O$~E4m%en^M%gNw~@>@K<*KfZo!Boea=kfDy5!`qNecqL)z#`3n@1s1L?$N_nW^&SqvBC7+mq1&AC~=KU;RDOna)OP zCzOWh5=<+15rDVS+-7P?;1q_gX&=nNuqiWiiW4y(elm$BVp~Bk*sBRh!iPocl@DPU zp-NV)0Ul+Whl0;bFn~j_k1izDlIWXxG>5un2HLcS*G0c`>dZs9$b+l^vFhrjvbo3?a8fXb|S}Zh5^{gFkk=zn@0v6vrD&K zRP93vBWO?b&6!@Wzqh%KUAWP&<({FDcHE6!IMM%hqG2Qm9KcvZ)kHo%2zrq3ny1js z|Akoq<0Ch;NHM#MV4I<=eQ>(7&0X5OxG6{`hU=Q4oOs)K1D%(?bU8ogrZaksUtA@^N*jPa2lCn=LSt@yKEA{GVF@$4${umV$9RVVetGfCmwWnC;~5 zOs9-!>?ndw)_aF^yizURs~BihxqS;Hm)#1fyCC+HQ@4O+c3zt?tWt`u1g6vMs+7ig zObHDS3E8OWQlYoGk(tvmhFZx=vHz^PWKXF(pC{LH1DoQXoBP>H37XQRFV;bNG1sJ? z+U7^$ps|N2fFs8B19H2KcgGK~giXsI9rbL)JcolgxCHwRX2G+RyM;}#4?`!VDNb$> zQuS)zb1}cQCNO`63F|02$j=$N6Q`N5PwD0I4)TLJ2@@LQkYHoSsviA)g z-jYq$qSRbzf(LhSkXy}FnYM4=bG)sY0&mQuXNrMZcO=rH+0Us=x(p5(rh5;h3xe{@ zzi+TL_utESJxnYo9X+Ili={OLNe?*AtsamvTIUVC*mv~1jKTUzF~%LUNhuD@6EJMq zcO*%)HEe;t&8HU=;C-*tdHlqT5jZ@r(g``&I&&1_bq0B0x6|Q-ISN-i|40h8u8cSk zE@v@;T33wL`!R^Cp1`Q5x#I#0hMi+{5BTY&*#%-0Gpft(+1ZADN5^?RGM8oXcXhuh z54nje>F5G#7B@Up)5E(FyahLN~Jch0xAlqEL zDF&FX z#RdkR=ek}{6?wsdV{2C#$x_dG(X-D#*}VNAE?X5{n`(9id^Q;Nxi7EeIC|3odG!Q0 zL<&wzhZ=NF1n=reGn{hV@j$JU_&=7~_y3wt7a|X`WXfyUdXCFDQ;{eCPBaNo_T^-PovDz6 z6>)IiL10vjNTw?>10zAA0P12JVt_C)LX8m99AC&AJ|YB8Sc_2B?=bR2!P%wjAJs*V zU55hnhfbXmso8jRvP-iysfQ#U$~{M2qC+v6@(<5SrtA=o>>)uHoFT-35(Hg5pX@3J5@ZL;l7A{ zNg%lOPE`(LhS7`8lam0Uv=HVIS>~5KQmo zghnb39xi9bN&z#FK$w2tkTkh^1g4HNUzK2oNGiso#j#(w?xk%!dFVfR5O;+bct8Xf zy+$sz*YBsGa`v!$^HA6bDL4e}^c~gb0Nl3v@GB}BO7=b1YWCWw=0Wf27@%FCt5I-zgZ$)Xr|w9mMEX?5V^2RifgCqQ!xwVS_L zE|;fSz4Lv>TW#akT4)}QaIcEltpOi}Zro3t^fH7=DoEiX>H+}i|6(^*rw>M9@TS}N zTJo1iJ6!ZhgV6`eiVcCv(3!-8WoCyDn+J863V#BX_wk1oY=RPp(U(!v)s-3hig|(4}45SfnVnkH&OstNjy}ry> zKzZ2;o8J8SRa*>EP(UUOn~(995-uXCz$$*PPTXf~IJ6LWPJ+#7yZeNzD;I_a>Ar)e zuLrziV>YP2O6n?TYF>Av@tB0zylq8vXifBN zV-NLXE;vIem50(%Z0zO-U;8)9ii1h1zkBFz?`_>!l38AAqOV0eIbQnG`u(o@2!)2Q!#FX+S;oy^(tOg4%X|?YxOZNC_q5Q6@iaRF zbR}}BSuVH5pLG6*zl*D*&|~mcyKT{peD0j{LlJ0_#Ijg)UM{w-n#{&bawQ?9qnJ5Z z-3*E)dRkC>T=>;2zK7<~Nea}X1?rIvFPAsvNp;vs9OH)Vi_)kj0t_@cYaY`x<^(rn z{d2MF4g;yf-`Uq+W_Bf9BPx~JzA02@_gyE^6=(Ow$b=_2#VW##lL)6tWK>yUU-YQ7 zXlhdMv}aYa_jf;bHyqo#4a-b5GM z9BwZ^b<&iPy1nFyYv<4rclKr*hW>rZlnUj2xNIdg?cE^|5&~=x`~YnOM(ee%0@HMi z2K@oj2T7N<@81ywxUh|_MYtq*YcPT73F0P$RIa|Il=9#foO>dkLo4=Icwvt=?&KAL@R)1z=LB`5EISr1A5ca-eB zh8L%d;8oHJe}CEp(u!c=^^TS95*57cpW#~E0wj+np3eR_`;>bIXuud^sc{f{D@>gd zHV)X@H)>w>`ST8lrA0`fSxDer+Z{vyl3D)k1nWo?>&WnJ zi(e}`R_Cxw?n!g}0>4-IWp3Z$fZU~pInqM1MQ6l8b0u{geH;&LUJexdR2L&kH?e0m zP^~swS!`S@fd1bB;^b~X_6cgXKLJZrX44<=i7~B+hM7|-*sY~-wn(}D;T$%X2&)0X zfbgiv^hu%bgl8&-T82j;ICHj^?vWTUq-iw-UWiJc^g+)T!@OtPu7Hn#mnzQQExvvx z66Ln}$!!t@;A~rqlpzdb>u-g%1sFIheWwXU#ZH%+9^M~697t7WaB0LMpHFKoM)G41d$L)6%E zUq5FCe`OikyDTEYk+UEi8P;-3eDj_QY;JI=3GijB%E2sfz$9#m&!)mHlKNgM4@4W; zb1~6h-|bbXE%VQJCiX-Rk6%R7)`tQ`4m2WURQ;*U=_gXz;BhUSN`^7<+V*v3S0%Gr z43FYd*$h5yupHrw??mDR86&f_L1x~awem>sI%&i5eg9NrBxDB|{9q8b{gQSjM@7Yk zr1Nsd^!M7#+=u%?dkOG$^wz19=z=}eTdY?DKFS-X!K)FkZW@nhT;5iDF_tU=Qbp!t zu-at_2Y2KTsoac3Br4LdoUjRx`!s`YVqC5UH5qR?jjKhQ@tmq^M$bdDc|e>jnP-(= z#`XjwYz1!bTcrni_HqG^#<^DDF)b7HeCgkqt6&5o#DoXx~mE%Sl%^S*dnjK zmsKX!<>~G&M=ztU44j*5hTY82(o0K&2&_2~baTZr2d~_BG&OSdG)C+-Bw-rSHH0evr$(CgxG}P>rDeuzf!Uk=H$`=SeIE9U0_V?f8s}H|H3?P-C^6$ z4(_Ku1qTxLMB*lmGbXsChJO8NHeG2!jQJ#09y>5L`*q3CUgN;Z-@lF`N{8U(K<#%M zY}ItIdI8Niv&@NluGcG7Va%c!G*^Q8U%J0KIt~S^iyM`oguQ83Vdv+S(ZTE%b%b@4 zG)p54Q$G(#tT=I0ZgD8u0|f_#S7)|6wogIn4yaQvR^3rX0}K zZ2H5{fdm-#-l)2UE32f*)XV*o`I^paXa;Mu)@O%LD&pJ$$nAR~O&956vGT>t^E|kj z7GNeBbu}4$pO4%tG1l1sLd56wHXvk; zr%!Q5lm0@#SB5xe#*r2t2Q}hOf&KgB6-lwjo9DWYp=pCmk5YyTq*vbGBmDU-n+nKG z*YyBj0{HB$zF1`6-*`)Ej}Ub;B_Mj0^wLXG6j>CB;>mF9AqI&@E(dHxKeXe{EPD!S zb;em(hAwaq>b(gOevR1hm+g&%E->XjW?+8G!2Be3pG-d&k)Zt_UdVVbLdzmMKB*;(#N9g!ovWXxyGn6o?UtazwxHgFay(RvHgz97a zW=L&&F;;m>MgBffGRv1|dgV?dSi7u>hu$~s)}p22!t7V~$C94sc-Hn@aF1s}_(}f< zR-J^DDprZ}=vUFKPtlYFysC!&rwJ8B@R$Fg1_LlfxA5k=$=2S8t8BsD(A|2Ds->3o zzbD)E9F2D;G=E3XC#-_Ihgy2MTYSGMQv%c9!DUo)FhQ7k(F`t@zgwGCGa{L!HjTxSt0sCVN_}a#!ab;H-j= zNsgX3;9&ilHM|OomQBiX(Yp-02-FAXqp97*#IJH0Z-}4!(n4?8y^ZG=$elF?;}NlC z1z7N#C)hjhzc&SPdtt1a7vPs#S*E-}$Iug2oy=El?A8MkpYz`E{)5{o@un`wwO!77 zKe$sK664%coqJ*hm!RcKCKJCGDWTvm>@XPz2t!RX#FdKAM{aQQWm4KE-AB7D#)NsQ3-S( zcN~R>L^mqvhSDX<=~3n}~!73jcA|W6tX4sG|jHg*&h)Et? zvOnGMcGg0!hvYS4aEDXuQxd=Xz^(^o2B;j_jd8&MU|S~K-9f&;=?o* z*i>=qHNP?0VzL|5YxpqOoY4RwTVP9(h+n~Fy_qJP-T}{AN>lURJ<0>fbky0H@|j6< zB0;T5QJNsb`R9lE9xXK>MdiFF((a;7MYFHgE_-#*B_#?M<%~8jyj!kzwfvx|Gm|?f zYt!T=HkT$gURB(_wcG}_iduSHofBbQ6JcgH-PSgNzf-d6y3d*+lq%^oH8hWRj&RDu zd?~h6MNBfb1n~wz!QpvFXYuo+q!n&HHTFG%Al{f-9?CECrMrTLcBtx-WJJe~uql`H zs>OIkB+-pe?b3R&K4DJ|gaN2LT3BE;HcGcy^zuYK+^bkZICnpU3EY-1JJulvA1h=$ z4nL}KIBRbVaI@LDs_QKC%s}cErx_SVRlV-C1*61 z=m>m)zWqw9gruu(*g+Vgb}Gf?r=p{69ePkAC~&0b*v7_p?+lkOkMEw= zvwPL7d~J6qW1)G=mUE5ovzDv0r9r5;+vY(diE=^GPi`|Q(00gwrkslC9i)P`$Cg~V z0A1#916S4~|8Z`=Lz>^HN2f|^TQ(%hMX}A(@P>NuV<|N2LId4=^RgaEc6v7t{cbZQq&JsQxZ( zHZJ>edv)LnJ4!yg8|`DO$EY@%6QQ= zdlU3OO}6mS2bc}5QO`IJS&DznT|?KmBlvp{EOQxd1H~R9lPvT27rD=vTp+7@ql!8y zYj1NkX;Y`>sSDQJ%IfLkKElsPB7k6GWst{N-Q|4n4np1-PYhocv zQ)8|`!Tu+7fjWDC@#=80FS7>3?%`9cDer8g4mRU|e9ORO$4yu&W9u1EU+54jHK&x6 zRT6w7cISWfoBS6Ie2%^@^O0PKSxGUBt|t9HuCvK&)6DM~4i{Xftf&`V{4F0WBUjU( z{U%|YJauZVPn_DhbV_XwfKBRTGRCrfu~J|J@s6K99e6pBZl?m(XrJ3MoMF6U%oo%f zw%>bY=xj1qk8uS#O+_)4aR7CdfiIEO(pCo9Z@~$1d5`6C-f}UY8(jWVW;o1FZHQ3$ zT0)`pS6Irp7wud7xY0U?v@=tp5~^~X^0`DPl^D=|KLPS#G69IeH`Z5?5jq+{BNXZp zk>_Bb=(|;%VdQwk0TI8N7}pc(`2{V{Z*djsq4+9?5J0bWM#4QZ%0vzAiPOnrGtQ3= zD$Ea>;2D`wrOCED)KWFibNztO( z?UiK?)&5e($`YlJ|NgDAD!sC5qL8ejXG~-1yStUf6!oB*nn17->Nd3F89+Ogqd)$( z0#44>Z|)<0TqYvy-7@Fvb-tY8aC#KS=>DB7IREAKYYUt)Qz{Fr>;d_sn&Wmn90d#y z0H#$zUiyz%;24fX$JNrUYeVc(9OyS~q*`5jRP z>BzOC<}wW^b(qe3w{rk3tA4tL#V?VA{lR{aowlR535OIj)+#Fl{V#8dQ2X2fs2vMO zi`)eMxf1ZLw3tc$gr>phLxI_yHF&c4p#WguECHi-+0|B@a+tU^Y*vo|+uBgNc&F1^ zqLP12j-rr$ZBrH>p0vLXUe-@t)lYsyoyV`mAlYc9z*l%@p7?>${MS06ErYkmNNj+Yc3i(9B$MoMmf5=`_46}ans*`dY;X2Op6-#$Engo&{BFiQuW9^2UvC^veK?m^ zlTywb&vAUau?hI~<(D1vdcTl-j3i?Zxjh_NlGR@F|L!s!`xru&HWl-6f)^oHW#?l| z5=e1XrE7H9+D~s@TGu{RK3AEak=DsitHSsb{49I>#moj(3ux86UBWOSo2nq~_#25E zkn7hetme%>?h=iHV1EhCP{8ZQlF{|n zG2>`7{SFe?60U)A?cA8ba@O_NtSdZMUV3jtoP4_}kDdW-LifKA!mfRKGBTLx4?h7e z={<{v=14!~O@_UQpflZL9;9~I#f*AhM3SM2JDqHX&~|1Wqv1X$ZzwsdpGHi_2ExzxKMsDg%vkufbnr}$&*%j zz~=3|c|0~=Lv=dR}ExzYwa`qz0x9WFZZ^y;rtn=&c1raNS7t+nXt23cJtY|Wz;RfC8@yn z|L?+rj(RQ6(th1sl4c)omjMm=EDqquAZM7Ni#@9z$>_UswAN!F84#Dr)Yq55m4EY> zg{hDnWb5h)%Vu-#ZjkRD{QmLOi&6PQc7pq=?));d!fPk&*len@gta(d5@N}Q-8fx} ze~VB;5!n1ysQD{6=YA7N)Z1> zlDSGrh{cpy$=BuQ*@kB@yKbdQ&mBGS8!*9sNkD!#UKQ(f{U0 zD#4IOJnhizadN7Ni~P{_nfoCZioPIt;<#VzjbhHw?DFlvsHOd7|BSRZ8W;4f(WMc! z0h*TUcmhtAEkt*u3k}yc?e$)l6qL59-(TXhI|XpOc9S8~8@j2$lch`U4{4m)4Eo5H zq7ALnh9;Ei>6PgbZcU6ea#z~hRob)ZKgS~d=LT^zIYu<|8GAI% z%uRvakcFV7aJ8sEMKb&9bRO6QLVza}U<_O_|J-^Hz!Qi+#w~(@A#Oy~zQ{K`+(*x1 zp5Lr@L>}XHv%5E;GQU^b>N{tEV!w1BZ!NhoKoe*nHDu~KLLHTV={|C6I@v?yp?1%4 zG`f~;VA9<9wCUS*tOfR9b-Ud>Yg6e!JjU0SfAWY;t6t}56wqiCRH>(Ld%Q8hIseM! zdPn?r85(LIH4%HVdPhr7hYC$J_llp=;Le5i7n7g`v>IHY)rGAEL~XYpUf&MIFj}Ci zc9M~eD!R-lMls(uMVHDWf33wR!WVU)9?%zCI5YlN^fj*{Emg`EzMC^&`cR>nFf7-V z(iQtZxjhWniqh*lmD|sBW9Ii`Ud)sVL9{->c{#@Wl#zyz#3ir#QmLpj?6SPNEnXw)5II+_9} z&-__s!6OWP`SIQN`#;M*jdFi@STXjiU90^OfL$|0L>;H99s@@jTMT!7m?7ka5+ z3uW-7ZH(2Pb18NA;w)IV+`Tpn4)B$piq9xbv;nWjLs*%b&RIlBOl|$D1x0nx@GlyE ztRuIm|B?)-BSOUIQKxDucMclB-9G@~Np%|ol48^4W(C^n{)KizQVgFTfBrjp_?Agq zVVWL=`CH-}Zc-K|2n;cCkjsw4>6$k?Lmo2ZzqpOC8@DtV!HZy<(TI|ee{)VmFeRyH zvxP(pm0*+#DZYN+$$yVPyZoXhnyii$uZ!fHiOO;OnnDpQ3X|dtDN*{1wT>0v)i!G# zUB4sC_ZsmKNak)fML5~%D;;_+7St*IFF0@=LlA(I}5 zwc2cUk@Ucf(wH&(x0OP|dup`4Qh<4AS`DyM%oclJaN+N@#n08jR)tHi4zC0_nnub= z0tC0y_TFEDi^H^rn^&7ON8JaQw#!?!P_xiY!+3NRGH=gKaKlSouAuQ@wd_ByfR5u# z_0|A=HNbZMjQBD-vXpEWW78CM&5UG9(linnhM_e=oc-Jr7D77mWD^c*%~mZFsdV|H zYDyGXo(jtbI%+}VG*_RSR?n&%y`nFTejIojCGUnrm*)=+5=X?I;Y^J-uQhEaAJ54L zbv_O1zB@XfiZ2CZ9sG#$_yV|}i?($>B|{TV#P1Pl$lt`$DQ6t3JK>w(DM7M?oJWVV zF`rvO*|^)m45M}Ou)>8{llgh(Zw&8PENr(=1KvACihaFZ(7MX*AKq~Iq7qwB^7E*% zGtm>IvL{Lnf$oCfSFOiLqsyC$6{M)ae=~w)DAj6RcRjmQr=M57oiw^(nubfYg#*an z&5T@oC)Ya%)>3)73C(cY9Yu<*`DJSF*q~iShFA1mCaIaK#un>)U;E~lv%F(l^Oc|t zXlS{A;N*-eAj~k#M0TPg+8?|EQstiH$mC?GDDX!EqAs#xAaJ&^%^Si=j=#%YD&CDC z*|5i~s@`vQj>w}KM`AxlL zziFtFy}(cC1Qv7yziB>>R|?5_+}9@bHbQ_df+m2zee}bf%|jqeAw1{35&UL{9BWm; zA)fC${g|3CP7T7CF8IXC!uYbXy+?*h=^JLU-=E|N zLi*8nh>qSWR-7x|tqn2v?_M>Md^oa^su_5E)kFF$q;87$fO~qd{tW9WS=CbNh+-E4 zfrlx<`^H;M4Y{h`%HQPx+2mC|Nwwv+@QVecA&UH5z=*U>-Xbcr>aix4EP5ucp^`tF z->LC_yt~TmlcBHpzn`EwO=_eWBh^2LJS0YkD5t&5tioWEYFL+te(hh+#NpGM6AwHP zNE*}lNZaYiHrB=meAAPSiar+AMB_3HLF9$Z9~Ux;nsEI z);yIdie>rkEGTWKu->hnQF3N%n=?WnxfLk*stt=}vER6*Xr_c`nWSqgAbGcEr6V#I zq0s;Sei9R{3Sc?z6=4N&J`+17&(8mpL`JDrmi;NrP}wWk!P#3f7L>{wENRS{f+GIq zN`QP>gYcV@$yxBkEbH^7Y^uGqoP!@El0eOB?IeeeBX#Cc&M904ix2zG3XHEjnxS?iL%EQPlxgcxem3E^N{;2m0ZMaXM=X15< zwOqGht#gXy%tzBBK1Xllnr^aljfgz>J)o!Jv60|SffAEfYA99fk-X3e;S+7#@4&rh!g8g1y z*vA#rpTUBj)vD)HZN$HyyXQ>oY&D8s+XMBGI@%$RaedT%}mw%p}(`sh6RU+<1 z{`U~4=YB{7tvHL1MG)s{KZbyZMU*ykZYH1PLWF|gJ`}n8b z@1DmiVdP`ySMr?o(UCW?*)JrREZEqKq$?3QiGdU=_yd37*@b2b328MHuCl^lMN(#P zLIe>>d*j95aA`CIAO)l!&-onJirXU%d1FZ~e8SIdBS3HCWj!%Q5E|{6emxiGdOTKO zp;%z1C_Mh;mL7Fa4^J9z87xKT3i3JdbGcZX?F{GDJvnV4I6X*HGsDutc@s`WmT&%q zNA5izWQ1N}VI@;d;)w^w!Z|%8WrTaVhKB48U})gw9s2Uwgy8W4ws$D1DPZw}7DK>H z_rK+As%TLfNqW9A-RttT$iLDzqfybNP=;PphwTQ~&1~}W`c(aE-@*c?@PRd1hZAF~TyF{D~%7QW)oO`Frj}go~A4UX0_@u8ZGTm=9 zn~xIdE}`q`t?XbTHg4+cJDttX^wt^6*K)Hres_11uD;`$TI#l0WU}6Q8CAj{fOZS&SW}J_E44rao~Ur>wh@tp(Wzu5ozgeP z0iu2@ORZoS-tQ=@50RmZnE_=C1(_7M=D+>L`g<6coN(@*Ns$`LX8>P2@2eA)=?}iS zM+)pGcoLS<#W(}>ZgfM1m7Ni^T@j|?YKp~vxJp$l; z@|%_jLDH;bhIOdzMip7}(6dx93T}2^zF044`<+Mvd9U>J7az1O{dQ?q+#;DMEI7GV z#LtEVhc>>j(e5Xhn$jw|&tE`?gNkn|5T75_o*$Ljvnt)Q>h*qk3BmDH?m2`+977^b zgvk#fIKIlWwN1X;9(g|B&A`0UV$Iz<%<^ruxEW$hiWn)mGlqh~i_i9;Gj|6vYm;Lu0u z3NM~H!sn)CexY}5kAbg>k*r~Ys_~DEn-g`e%@b*_HCq362EG`yLgtT5ok`Y5Wxijq z`hUO=ibT2!MedO+G{>HNNyCftqS>i%JzSjbO~!F|RyO*);qJVgD)ySqk9X((9MMib zX)XDMAJ#Pe52Q}5_^^H5iGfL?4*`eE13`g^V{&ngLt>31VjtyRqp`GB;~7b1dzl;m z+!c;A6N2|g#OP79pEY3gtp!n8@tOZzYujOKhg)in5)1JJ3(>~7AkN81ZFZ({e$}e= z@*2^s&iL)9JJJvy37Lwl6TAR+$#1ZeA*}d9z76!$g>9i?NG3Z-U0fCY^ zE_^}#Mf4;2KiO(QNo@PUt%X-nzWz%bfTIahYy)m>yKAgE zAT;XgMC8^*yz4HtxNk%c03saG=?m%if+UhJ($0XKLFZwpSK*_hd`4Booets*Qlsaw zu0jgi><5fn9?z7xZ)^!bF(!CL2bPKFXkj+`cirYD6V%K0AS?IE;+i34XGHGL_uo&b zbp#h5pAXX8^mHbeH4B|E=m;Vf>2)|%I_cyWD!!hGQuw z1QVs++g+Si@QG65N{eO-n~4(LYQv5cSH#|;`JC;5*9)5on+OBW-IKy!(bYL05l4a6 zTlBSB_WGtfFJ`7G;&!~}wY@P3Yqh}sP0l;xyyZZ^%=EM7j+g)ZI@8E!tw|EUsy!6& zlex`CqkQquIu)i%Ii^cp;4wW@N;Z{)*vOfG_TIPby%&}5_6z?D#2ZW|e$hr2Wn#3t`|K0sBZk_6!TMFq(P;0&_~^xebzmhK z)&kpf&mpbhhCYdlk`tf8V0^=Ryt9(nR1Z4gXE6TF+VWp9aq15Kh%WqSOz|tFQ=F&Q zmQb@RWS&#mA-%vIt?u>@6?V3O6zCvk5nYumr7xa!ij7*Vc1*C_{mcZuT}`4v|38p5 zEj!<`f5(~BC)M48I=6FBQd8@q4Hfc|ful+=TWD0LTWy!Ab?6(n_iFF%V#b-eN#xfG z#esZDdp*uMR=U?4VVqyhXU-u><&OyAwqVW!wq$!E0wLM?Mfc`M3mdMlZ{35cz4|rZ zp7Kt0WWoQ<;k`@RRXau_0qV%LY}Br{oeL7$bJ>~Le<)QEbnu0+cNDmOjsvhh{mv*c zkt`VfxcO;NG9Zz}Uw^^fVldD$VoC3c`!xDIcK?H;2Mg3Kwb$D`U3W1(dNIASTTpy4 zJ?mgF%EOZNU{K~@P1w3D$KfZs8@OUD$_XwIDQr8!<$yxrZ+)SmZ>KJ zAAR5LQdh;p+jWz4A8D|Y>Q3KG(?2V{q(G+r6tP=PJ^yK&`2(JMVQ$fy>v*Zs(*#2?kWej)$;QM|~& zhe=#tzEMa+Q{>X~^7utA1C69r|5u9ccA0B3hgz`BeExkN8u;MaC{GQ^zqKVO?-zZ} zL4azdI%o>wFfHbVU6}-Vf1td7?aSA#Xfw(@A0T)*jq%7rGRzLAcUw)uTQ^lKOXAnj zG+kXF@zL$xN+LNyvgjE3xe<7C@u zfq=4@48(~@-#=fSMGA@-@%e7*lvAG!VWzdM<;@*rG_87~keiK8h3vgBuDje7FA$sh6*#-(ABuBk1B0| zK3Su3)UGJgf1%dLZlnuNMFsLuBSpwar5(^GxxYixsCE5I%7M7>L%x2YE_^bS7IXEt zLR*Un$qFrrii32Q`PRPTW`c+elaBAama7dw<#f`Mu!aR_?0H}&*Uf0%M$vov` z=+-X5UH-%4H4G8k4&Y6a`K%TPcZNqCRXtTMg`OLDgTxR)x;v_6AUJuRYq=PG2+K*7aPKrCWT!g1}@0FbDTZGL@t z5%j<4n)Mmx{Q3=Ty=(TIJvE0n&X`sry4Slm-a2l3k~h;0REq=3Kyz3>Zu>;ckIsfb zbh+keE)lK7u%U7KCGlUYX=pr?C6*_bo2QuzNdl1CK0Y126kQRkS(tV>>}?mm(y;)*!-8^t6%+XdC6bo zIUlNV-5s0{bKffe_=Ae+zlRlH-J&sc>8I>=ec^xcHZ4unw5G%1=6STr_RhX9#fZ7P z3*8JsM1Q>giWyx=VNE@%;!X z>9*IF-tZr;k0yHj{6C7JeztnE1T;cNU6YxV@Zwt_-~FNOuQAMz*)~`T@<`r%RByAB zQxK3>Z+ouvjO6XBdb(Fsk{>I8?QB4FzPMVB|1j@PxLmY~M$HMssv4akAjBaYic+I% z_p!Jcw7VE&^Ifa+TVp^pY`EJWrq3Lv>s=1oAqN#(Tt@f$`@|)1C6p>dUw>FDAlSH4 z$Ivk96KkR#!CJt5_=Q%IG9vB2_jsC$_~x%^MuIvhAF(rEIxa6$M@movp8G~`aodF3 zXJ@|DmoRnyMb`V3m9$yjTz53dLcsuF#=G|(o83RVxogkOi};@gYxCaTaQWgN_O!6# z$gtwQn#eJmIF=xE)=RugAD_2gXE46sV!(yLfxq@z{zOBOtNqlZfD9j|kxJYX>UQF{ zl^SI(gj=&?0%~Gi#P;cD5#s0~0g9{MUNu0UNklwL2!2H=S!dpwO;}2_^mU2)icd$# zdQhV$^o(VvvA!w~TYvXIU;e#qA>%9hOFq@(g$plSYP!ozre3vdT!uMjul)6nqmzGx zm**89SEi@9@tojF=h~zMC0dHX`{NVqK>fWs@Aez651_rm)q95DMFoq$G+|s-v%Qq8 z_=aq5xs}P^@`7L_cd=)bMX@L^TzVQuZ9uxknP7gNRB-59B;D7KWDx#ng%Zno;inu| znjS$$J&1}6&-hB=iU{X$6F-=ZAFN@oKhs_xf+peEe)XX_ zg0+N(cA}iT0|ABFWq_SOTyFMp_pI zd`!G7RWh--sYqAoxh{jjd{H;~QG=-RL0VccKT_Go*mZ3i5+F^@JUqKk0r7 zK=T@l%rPy2TYKN;G1W903_`|?vlLnF*i5V(YHOTfF|pDjt_!QG4q8=+yu1@JI6yx2 z*!N&JXW5~9kWlCa7Jt4ucaDwaYOr3@9OksD7QH95@a^z`rQLh8LJ9-AhG8xh~I(nGK2^5E$4CcD{hQ^#}@jJ9p6B)zsJ%WiqZ!MzkW!5v@PP z&_KYk?mXHZc5z4QNXA`&SdUOLM=0$z6!j5m_yW{-Et+@%%D(`WAED5ro7a(}Z|Ubn z&T4xja3So!m_8RBe2Ns8xUW$BQy2&ToebceHN2<5n~Vl~pXOfDOU!RA%qF{_3e>chFU*Y4p{=m1crr}&>Wa^ETjUU%Z z=gR288wi3DpXr=Rra^Z&^8MozHk`Do1b9zneyx_1V9)n|o3VFFn2J$U7!^E!? zo_12Na||bQqB4S)?e%;^OW?Q+}W|>?@W2Z^?FNE{naU}X%Gx==oayOi>&2B-6taZ zqH0Gy!KblS_t1iMx&PNBc&oTbRT4ClD6)JxXr>$@MwWpz=AH^L?xk`^r+f+CT*IJq z!8V7fN}j(MuM~Z-q|52A6cMYkBQe(&DsOqG9DYqZPK<5yii`d5JV*ual`p%`XV!1Y ztIYPyG3*F%wa~6eue>$&mg_zp4%?wVkD%kMldiju#$~pdNoKfaKBKc+3Vz?~ABAw% zO)Fo?q(NL7>MMxGl^1gDS=&8*mdNY69jeTwO?7Zxb#S@Mf*Q+%UTtM*Bf^;A%{WkDuUOj0!Hus6sHzRe}K%Z7J>5G zQEeZbhhTyO*%Y;4>9SDiGI)*vPOSI5xY$YImkwL043qnjT@NU-KxP}WVIi18V-FxE z_lLS3K;RD`|70C~I9%D}Ipy?(j(H0AnqfgliDnO&`brk*2pu_+KMR^aSf5*ZF963- zK_@Hg>o>A2sML7paxBF$j=d#zmtnVG=2#m3mQCxMoJln6%rLvyP)`d=R#9;ZU0Zyx z!>;}O_q8JX;LspnkNf)w4`uM)w^(;;!qjj5&Zqg!9mMq12Prj=OfvR{1&=T)dTCwC zkA)T~uZ^gOzSk<#4a#`N%w*WY%S!odO<7WWu&bHj1!jXOUw)Hg*_NQ@eZht~KBA)Q ze&5#ieiYL+wXBh#}mTye7o+Q8YK3=9T5!~9#mX3g==^k^)qN@IKs9avo z8K;b%?M;b;z8MyeB7~p^ED)0aIH8pWgOWjJj{^Jch$Z(yG8TV&T?7GUsvpv4;B|Z& z#Ohjv#Y^GUI0MC*0$@XU9Y$?tV}c5~LmGNcz9adqa&pf+P;!%&WaOpFL($;W97Q)In{= z1u}HYY&KP*!BlelbwgFmF1z}xv&pNo4TBA8tFz255y%(litnaRF*|a8rn%hu?`ML} zV&kUZUgG8CT9#jJvZ1_|uid2Y!747^xq}?N&%ARdW77$RppO4Jc}s2>wj9;TY`8E` zHNrsaKPuTCWg*-s2gBgL;5^~+Ul406<;t2M-Dz>Q9qNPxfCVxu;S?b6U7VNakB3fY zB0upPNN;jBbo`k=Z|*)DU;Ta-jv_Z=IAuEb3t)KTDuv+-caKiAla~`tMij*eGEdb> z$jKiWC>|Ope2%l#D5x(OKR!>;aL3d47zD;3OP15;c2?PgQV!R)NT(Tho7N9L~?O0pH2HHQBc}j@9)v zRmmwM<6P0ps9g6T^;R}L%k1_^891gE*OXG#^2^mxO_^9^JCBC>YA^6I zpFYCcrm3l9a@r78lc*H^Na=0rkk`ytOCwN|R6X~S+G-)J6Bu@bIDZGNIjHFWMFD@b z=E3E6rTlW#j6D+gkdh%(M6GFmV#0`X@U)IIYm-cNyLFdmGJ|oHpEBIU+XJE|eRR&U zGO?5EE+y`+2CSCX6`c)l)^D$iVZoj|zC+TeAq`K5vXyC2*NXFTZI2^p2T>MhL{H2Lz zw(DhmED-loC{`me?k7gvSl}B!yadhFoJFEUN zVrFPN!g!GJH8&$g%I1Xr?&OiItM8&4b^USUDR4?w@8VglUT*+| zbgG>JeDpv#y-~FDg}UvTttq;4}j}w}8?77+?bfhpOG-(Mr>{rW}8e$ti z?$5ZwU4L$31cl^*9_+oa4j~MFzaQ|G%%E0HbEl}}bWFp$uUOc19MWiAP&!>y;1nLD93875#<@W+YY?tXC%E#?pirJZA6 zl8+W+0}NEtK8Z!z?}xB22|MJ0JjR|{uHN4p%ScnO5!=nC8o3___#q3)%Pz2DP#C)ucCGifYZRtgXwf7=S%E5jnv`nQ{GG4x!qav31*AaTtU`}hz!1j z-R~e-ogw#K98!SD_fJ79Da*4_yWg{@+D{1fZ0#f6B6*=uHsnKWjhSELb-CkoHeBw; z%{4r)O@%p_OnR}&8Xp9ew^6fv-@@K*d;lwLE5GfMRoz;%SR7fosJzv8*s8B)6AS=; z-N96fM`=}|ixcRR;gFvuhwd4mr(i<${~61vvOa_&kO+E?m@WRKp`C%*`8f#0#US-e zu(hFd;5uD-z%nCcNQ6Ga*IMLi%;%K(Vq5KKs$jKR8Gbjwo#D%VVGF0|jorE7hC-=+ z0k0<_7NKr{*1VkaGV(5m9VS0{=>t7MFk%{bo$z<4Hs`$g6Clx`FBDS@fI(_9_G>hf z_>&Nk#m#eir?Thuzi5j4W zgATN6Ezwh83VG@}bfF5BN9e%lwuQgCqf+90YinSlBnLcp!4QpSg^<(ZvW(>l3%dfYVFy=iGqp(p3nJgMc1I+j=I%2&(GB139C}X zu{9;_+S==oW!EcJ} zqf455h~MoemB=g4!OD&BP@;Be`k@9qMR#%xkz&um0DrtP&b32Ry9F4W|Hwtin^OIi#}2JHXacYp6Ah4dSG;F3zU%-^Mq+y@7n(VG6zN@Md-bx zGm@)#Yz$N1IDHyS=Ul@{cL^G75MQ0ma@if`ckfFRbRA3=SexLIJ+je?9hm$*sU=;$ z*0ka?Dx^_beKC1_EuZLv4^{NqWLOEEec<&=`cSgwGZkz(^kX*@STX)oisS;l$mtOb zTw;Ug$Ca*wa751f4w{USe54DMf#=mN=hcvFlD(V91#~y1C8DH@L*0u*QiqmJR~>(Y z_@^^f4L9^UZEJhI)@A=m&|;OhIvjpU%_yuC4s_u95d0J=&tkvq`i5;$yC?jaRJ%l> z956<>rxF9iK200(e708%u0H$UrC*N#EOru{HWD+QZAwt#S~O|0C|9j(P^Ie=qIIgP z4;@1d8nOV!N++NmWpgJeTmuRoBNA21v1-4e3W~~^zP)F2^C<%aM%!`0bkaAvI`W=T zdMtH;)jO@wpfryZ1c)GHBc<_+SOgjQ7-a24U~qWZR!35;@1qC_$Q*B4vn`i zXzN4hc8f*eIWo%+REVHlJcC^#%l%qI5sa8<8dGWb8)7Zf*}oh8mB&5VEmGPf^65<^ zxik;-OQtr;-%8xLG;j1tF2C)P9Nt>9j4W7<@`G%*I0iTfIvi)Wy<^G>9f;fKBG=Jl!42_QVsG4rc_x zw>U}n*sDkUx^l)Dst@crNo8qt?Knvd0CxBGW{~R_q;&!_Ihtq;y)MZ$kP}-pMHU6x5jj${`sA?Fa1=)745a z(MvL!C!_9sH3sF8><4&|#m{-4yuCt%g%Q6;dsKfx<||HXz6n1c#Q%73L0}i0XScV_ zT!e=6ki<161)Ij{Lqdb6JYjyrzKfNeLo=n z=}}-@*|xL&bfmn;42-CCi;=DA14Ytp2~cgUe|q!mTM7CmLIN#8=N)eiy_KLBgN%+r zl^@mwN%PYPK90Q3ni1aSf;kUnR+I32(JKXkoyR1|O6H!dOqf|81~Gz&;~D&2^*q%=rKH!Ja_8iasonhz;`5yIJMa6RGdpw7HT%cR9ans=xLvdA>%BK9{Nmm@8@}9VqP;p)N#%Cr zo9WsPn&fuWC?Ckfqt@!jcU2fspF|m2tG5;S&ik7dX!#50~ zc{|XfafcwMi1$R&`|Tuy2C@csgUnG}MbNf8dpMG@Khtq=MKX4`9Q07~xLaItFi zNwEwCzMaB2x1r6NsH$zK_I%aeC+ElqN!82G>u6uzh^(d13Wnqc^97peDm!5%eTHcTBls{xlc%qrbYbn~lXSDQZVOB2^iWcqMru996ka7!##t8;zrqy!U3 z+z^())J_7i+_R%A!ennq{VoPaTAC&17wa4$KFh4W8cGEH`qFH5h}Uw2p=?&eHii+U zi~<^RRna}i{0(UihAQ=?`T9B&FH5k`?Q5g0{K<(`t~M(gE0F|_X_#g$LK6bj5WJNP zN5STK*(1zk&!!&JOdx4vBTrd@n^4P$PUgwmWRe)mfD$WBS_x_!=AnC9efPXriIk;= z?mg|h7e9U@nkcHp{pz2mzrwMAYLIPinP=X_818`X`yJY~TWDN2&hfvsiwkxn z{^CF;Tkp$Sv7rduKZp+3J zCu*}c?@W4#0?AU$C})9vZrkLQ9zP0b>s;w^cpo(D+D%Nj~ z2U_d>Ti?@PGvcPXlQ`>Xe=6sSZ@H{_#aYHLm{Ct_LR5=>7DlSq^r5M=gsgLS>5<4& z#J&Dht7xEdqO-fjPH9_h_<6HSD&OCAym|Ga%u=UhcFOkLjxY5-9T3h+@3py?n%)Y8 zwnk3v+42>AH6LlWHQJpK#mM|N;lr`j0v79%SOaxZAqE$Jr^-#zJP!_k)E*Ge8MY;e zMIT~Oa_3(X6$BI(>iyApJ-v>benluEre{-9nacgDWl~=zD+>nsDqq1K)B9ZU0 zC&bfI5dr!_Z9miH=#5C?l*gTi)Ajwo&%_o4t!H>lxGdE?oZDr3g!_KTRN}|!6*dN6 z;v}jW54xZVUZOlq>$y$b!HGD3=z7KX0hxyOABN1ebg%J55rzyrI2Z9j8Ogt^b}VK{cUh1>$^ zKs1Z|nrA4v`dGCx7KnI0-!Vqut6if|t~FHKQQ4s>lv%!HLI{IdS)H|O7FMOY^$#B~ z3}6_Moplm&`2s%^(P`@!dP0h$Esnt|VlsKQ@Zf{C-bio7_Dx0Qn^a|C5vu$&~OVso${Mfj`)$w1Sfx= zM2sxD*&iCBJ4coy#WU02#V*&ZH?)+-OFgiHiFAEcVa#I*OgY`*`6g z_dTHZ)3DEDik*aXh5X$6>Q3(d0JF}#O-|~Npq@~<(xCxv-X$mcjBa{}rhJ)BqLp^~ zah+9{oOy(s($%AU%0Qc<&hJ;oxqt}`tf0Hm{GUqT98+MQlGJ@^BAlv5F+g&{(FSp3 zyWa>`8qS69kE_}xyP7uF5Y2zj{LTKS)7^%tPD!NFaQyC(yJ_>Zs-4!f@)Vzj+mNOn zkIann7@vmu5V7HH^YdS-A&=HfRL=v4f*C(N=?|;=Vuz-*hQ1|B4>~`^v}!rrceV{b ze;08sI>0V~_Fo{`{#d>LaDSu3vDLHE*#i$<9vAvV-ieAvN2L^ZdgWcRS2{7~#OXqp zvVJ~(bvo&SOZ6AzFDLAg8}Ev>0f8rX!xyyUrBQTiQtFarWEwaIbwr zl_&HL?zvCA?ib;9h~B|@uRu3cs;nbtdIf*?W1*X1r|>T$r-#|5lm@TcTc(8f_B|FN zuh=tsFMdNr>8(ainJ2d7v!3*oavwcm96!E|HyzIUqaH!)B}`xauht48sHwqEL%1pMPQb(j}+X zwrCu+pOSTd6+Qb{jA4GrGR89WTNB4K9HV9O{@d5l+7Q`W_rNXt)i?!MvBnuNn}E~* zGUbzjQiz?srHuzMpNX(un57qK!GHtw_xyitG;06!Fy;|@IPPiU@&R}6l<^=j zEH0i3|CIugT5yH+N81(;Nz5yZSZ`r3M1{Sm^dAoid2L?K{E}kaDqbWQLiYR#?Mb=Y zKuTR=b^IOwt(~>5%J*x78n0Nn&wyPdE@y}R0x+QOz(Y>E$R*Z|obp(TzBg^D*emI9W-{yp!9ximoe|+);gNWXcW-uCF6(7^B&XrEep7quC{mebml^rjpYqwmvU) zlUxM-JVSA1BYe*pmL0FE&F;DVR>r`1;fnhUEl8n<`Q{pv)%6}W=QZF>4#~;5ANRGe zjUL#7g86QBaBylW%x$^VH5beqqGAPrIw*%1X8|ZOL)VPWq)mZ4=~p7qnv0L&PdTEWrUtKebB8}oZ8d#SR7p$pKH>8ClbTtV zlBtYZeLzvADUeZSd{_qPUi*HDW2dUibFhwvoA22xE6rae*wT1LfH=VHMf=;;yM2=O zhdKvx7nn37I;t!7=JMJb87Z<)SpEKd7L>SjI1|M-oBS6DX14pZn=AB}$kF)p6W z$|Jm^M4*e#5_4bz7ndV^?=r$0G`g;k&+x81hkP~EH|)$qU~2t0Vi}8m69>;a5g@-^ zuaope8;KbP9#5Bw+D0U#4nbYNFYDNxUCB6yZT3!PFY@#l2%OxjW{>haFd?V;%M7t+b;PEDPLFc}Xe^@q9 zwy!uF&kv~5)Z5%3zyVzyf=Hth&hUOP2_BI$eO&!6c=R@-w}${RkPBA0O4dTr0=b+} zr&T5Y8h`9Ml#B+%dIvRPZR>&XkPD(pRm@O?cg9tI6Pyww4;rF%Vv!-OyQQtuI7C9- zMmF2HQg&t~p~03`lGWZloYy*EP)Gg@&1!9Z&JCz`NP>tnYWHMS|a$8Ri5 zHtGB7XSjvmnJ~%QfD8px@4M`1pd*#eAeyKTV_=Vriz9={O)Nqy-k2K87{}Lf>AR>( z_}V$uss1VSX@Gr(R^vMugr!O*8ZZX)kIWN26Nm?&%Mft8hcf}W>11jlttcUpY7ze5 zhCsQbAvIIj>$Hl(lifERb2irVOap}lpt{Nm99Q&5)!*CJsrgfJF&_`h3gU1NeQsdx z?XaW+DT5;BChxbd+O6LOY1#8J*iC2aA;dgl_R3HPSe8INT{#oq0+?wD-E<3LNZ&7V zzk#Kj4kJP5*i#_ij79ojwxWI+5FO;=5nrE7?}>%RcWU^J+^ zJoMTq_Lo`AP%9f<6)bI*JYc^9MV!tzWvNoDr(ri;#J{VV?iMjbi@~7!m!O$0gCTVG zEWL{&&3y7ILA^RitN|YJCESLKGoCk(naD0dom@$FDCY9se-qqZWO%o41Uo@erlXcm zc`T&KI3wxYdS`bTf-7BLIEl96IuQZUP0aEqo2s+BK(V9gU|lrh?mH;=I?@t_VeRgL zINIm*aW4Ppli~9%YBDZrl4kni%?IB?KJiX6yxMN5vLpNt$`PDz%8vd%P`<6+<&Q}= zs}B}aDfUw8=v#<<*q>oYXD3drgB6S`F&j43$NK`7`+^$$EU9QKH34zMpy4P;{DU}vh2pCNplYw?%>9KfQ^2^q!D3JVB$1 zSy>_oh$`HOV|xVpCdnKj-3QVmz6%zGi~MNY%p9o$qteZ)7tde}w8!GkD)v5;UW|CI z^3QOxHV7qnNF;a?vyalS5QD@LJY6F{7$p@ExC2xgwzU7ecN|m*o#nBluBP!cY*+Y+ zAytX$@QGNRgMI8yBKN_pEvT6+gU3G9dyW#1otY*Li20I(Q^81w1bBn-%Z80milM&N zy2bc$hAZP@)c?~=9+TkA*xI^3QkL4BwQB)WwZ91^U2bF#m!~jg7ETRR6)lYm3(i#z zR*;qqTT!Scju#X@a!r?}e`2@vmB_1V7b0G$ z4_Gqmo$@r5GV0%chOBq~%hOEf)7eWEK3;gW&iQtIIo0H3B32nJSi_gDKW0pPG?E)8 zV6^w8)KyK-X70yz$d>mRupfP~F#@H4sB{dmF0hbZ)^|wBvQ20%PHQgKkp3X~;58T8 z_r?;&M%I6!#AS>=*AfpQDzMfhIKKj;*7WS)?%u2KqpRL;&@D>PalCcacYA1-Vbo>s zWqNsu)^ZCi-gOOtLpv+o&hr{Y$(aoq&-Yfif#mL8yCa%za1XL9e=knRr5?Mz(c}Z@ek@`8OLdK=Hia)`{Q#0*c781SSDP6Okkdg}w5Y_K=v% zmH-Qw#>8h0g4D`vv_HsemuxXzE2$Ff|LF^CZ{NS{3*&6ul=H886NfG4RW))purZs=S`x4qFeUy^>!rr4y1NXrTTXO4w>BixIqM-K+<>- zZbE#X(Q2Ut|E|HuHn4IOc)zUnWeDJi{K-{H2T6#t?NQ|p>~&*b%bM3RFL9m$j6;|~>U;t$Jo$v-!$Sl%?$AXqDDl;j6 zu+1nlW0Sj37sC1CP#)xrG1yl5+W5T-Dq4Wzcefn@pSU4Ssix*Vcd zolUwdLuN{Cw)x3zTC4uHJlA_$r|Tm_2x@hvCmQ*w7P>dJ%BaLHY}dxtxVcAO9@V$6 zi_hTIYxI&h#*kQ_Q>k3&`Yy#7L-^D~De3%WgNJZ#4^&iZZPv0+OymN8!8B~b35TfH z#3({PCF08hk5gnp8IVZgq(tA+M!b-4ig>ti#&?UU8JuP-pc?OBHQ=^(8_a;H&_XGl z0t#G3xXAgm#E&aH2Z+DZHHQPLYd?O%=SS1pIZy=hdS4I+Y-}7jKW1P3?jUJWf#Fbt z3D`{J+KQs)f_{SR6R_9deE2d@MXJ!A{|9tK^}(I6aXeKoIF~!PkCetF^jJs@YUn^| z4HrvAOn%op>kv=rVz^0Dj!wj$R8|k%&d`!@7%HYdZ^OrS!VuQPyd4$tBL=ms46m$r z(o?i0{?ZHdA5JD~y>{kAE$pe9`0)(WLraIGW;Sy^oFx4vyV++|@q5fj>^zl#M*R$T z#@#wH%!(%HFa(7(Pd`6Mcpj7M#sBa-SB8pUcZd@17N8^ulS5uS>>`&Vwk2K>S4zTq zh%`QLWzch{lyhDx>3y1{kaRKTJy&YwftqNgX+Zxdn*lEt8Q2qNF>}2if=-aYJWhE} zVXfpeyHABV{^}b@niE6uV_-hBIro7QYL@x4jBXX-o1K$!Z6GAKQet{tCVkSIC@p=8H8M7lW_OiCMP1LoMUx$4*F^H zS1K-1-X+OXx=|tmEW5wO%LH|zOBWKv1dfg3@l4i@oCtUM#5|l%^q2pPUrRL{M9NUo zJ)h!AsURq~FgSGFMT%9drBZMwoG5PhGn6N8eaX^g0yDUtrEi$Kp6TzI3KKRx!uAWw z*L?&~pGLpc>*T#r;R<-ZIG$&t*Q~f!GCd--nd5 zhk>+0*rMfN6irvPE7NQ4ks^Jqb^n7Db6_jGqb780bG3$Q`RdoVUyKOI?pk6w&t5R> zqUWG}MaRY!XFz`fSJrgrvJjTog3;vw+aHssuhagtzIXerjz-P(hpMAW*AQRLa>gaY z69?f0gq@e)D5mW0HGcl@5j_dcIXBX&ohV=Xg$8c})IcwaH_vbhMg9C`<7nud;?|q? z!tTyOSyRnU{^7z9PL{L;69!o~6B->_Glp^{J0f0ou42x|;P3qL&C;xx$KQg-GG4lT zmAATQhl82xsmQpV!Acbex!2}9C>rovWnXJnRy(Mkj9(v z^anJHt}kj`7VJM)y`L@Q{CI_{CgkwBx>OicU20o#e%wX=@rs{e1&wIPG(HubE!L5U zEtb^ZX)xQlUto>KOC{uqi-QA$I=>fEEA}z=A5M%ZMAKN`NjcTI;@Gw6{ARQZ|G@_{ z_Py#VKxJRJDs5vy>=%rvgvt<>=CWePEsesh`im$IaRk%y1nc3Sk9LO>ww|$G0^wsb zAX($1cl^j8dI;38YS#$+SP2OR^_8qy*$39U#p ze*Pg}B+>17!0f+JliDeSaSck;93&tdlKMGq}zALD9vVU2{tBZ66J z#q9^YGVO?cq^eHTRHpUOQL>Zg zz>s3mAA#EXf#b~lBT}gQig&596y;RDOkq~*4KgK@$K~aZR_6~_*N#?yhn<`*DIJwS zct4s~=6RJuRKgvv=t4@Lly(WV6kM^(n8Ud8H^-`ZZH>}8YAZeozW`hXA%3o?Ewb8TxVi7B>G zg28SEEkB-W3gQI*Q6BrW6$wV51a6F}JjxEhOMasacuh7f>@aap;#t4L`rlo=F!ASv z8F7o4;f8-8d*aWZa8K&2HleKiT+_Mis7X7@W8`+(3te<38(DW27~C6d_C69#DiBmk zDF(+x2z$KFv`bQy$y|Z)*wTfCQj*6;rAd_A8Bn1?jaQEXSdS&r7xXd@O7lfZPBOI` ztBXCR*N5j^tzItbrNc`5GWmY;l%-jRkDY_s8|_r=iBRcR&`A^{Qs)d(jMBQP*a2&y z(k}o~KC-?K)i_LZLGNz380>a=-b?=~-0iaeRe@@IlXZmO`})BqcXrqsd!_!5@>LF(pZWzcDUGJMD-y#MpOWPeApr^7z2xHEwKK%$LWz-g#1*C^=zLi9JD}6 z26bEQ`3+XtmCsK(+}RfG33h`Lm@X!7!d;pK*c2Mz6Skav)a2zVPs1aaf4-Y)eGOF` zqYuQ(lE$=lwpyaBKcp9CwvYR$5%%k45@**K@#uPM`Pwu7f9v=>!6WGOr0!SctP2+_ zAY{@^@4LldYldTw5}PKbyh=B{FB^CC^RU@0PxBeqV=%PRc|z-5q}k9^C2}?Fco#)| z1|=8u;ghQPq}58M;m@Yx&kE6T|NZ8yoRcWGWU_V+ol8?h1!~|5 zBC4Y|kAnVs?vff^7WdqLlRpeg6|d;y^1}$+4<20qh4u0=JhTx4eQ79{E5DQ9(BG8* z6)YrDB2^YIEnJ?=($X{j;Kbni>85yqb3*l*AJhbrUT+FB?St1ySI>j?KjQB{lS7lV`;2EepGSDdSk6$Sc+Ny>(h!UzljGi zG?Gp=rL<;G`_u2Ln=ejV4~uFrICs8_++H?TgG_%*Z( zRgT0v0xKh9*HI}5>Q&SmRAyy`|3j_=tAPhT7nQ#pQ27 zzHdQ>M!<<%6QzM$(=`*0nI2c)6VkE%^wI$N^|{2lf$l^AlA>c7M+8ixi@yZZPH2t{|+DOILIVD-@&# zWju%C_=A$VMvWpRzM=5;Z<`DV)Ho7sgM#EEN8V9a9K0_ppFE7K7o>A4mt49ZJ;Y|t z%9yjT$&zAK`n;zBm({JD@&q@@heRVxyJ(G2vX-~jl;V(KkZ0*md0ev+X#OpJ7;}Of zU1oH)2Q~0znc=Y@Jdh5$ltS+&hO`81mXnj+-c`+)r?tz2_OH^4kH!3G8l&?YAG4~(MvDnokk{^3c7<&6H?8yk zF4WwRd-tu=jrvnkT#3_WF%s_#9ELJPz;?hSsOBr^6forgQXy*XJrdG&MmOLD_K3oJ zHSW!>ro-E3@ey06eCv@$SYs9|At7(HcX`r)Ngi+mOfpyZH=P2Lz`%MOL5ff+2**{h z#x0+_9czy>NF<8jy{YC*H4_zH-1a>pSLcVkf(PbUf zhCe;QC&HKgx7aeI$Y>K+$t9I!4PIJ za3Vd~m+2MJN5P}Cl*&}_bzx(e*(hPADZk}QBR1^!R>VT8NTJtDy#a3r@xTR0v`m%r zsr^uc6USD3obGhcrrxQ>H(IP14V(IneEf>er+KBJ`8wgd-ZJ=iB7N7Y-`XgKk7S0C z%~Ru93kYY48;2_S$FdVPPQEqUZwA~QUW~EDV2o;Ymd_ZW5J$EK!_?iZu&j7YDB*Mf z>e>F$EVq+cAJf=nxO%W6x#xe4i9rsjl;=RS9Y8;h9+G95wzhu21a)50GcQ55QNAh(0U0nT(8M+f@xsn(Iyw~N~+Q}}#Pz%|)d{P@F z9>Q#mZ!G4rbFQ*;0I7h~Mhze(3j7r~aLVkew`%9AwC-B#`$aE4eR#c;CEae%dh8I` z0>mACh8@uZzGq&C>5s7;f zX>3Qk!d(>~B8+E*{0$lW4f*_ss%=0j$bt*E%(WS<)fug|nOLE8cQ;frOhOtteBYE` zf$gh&5~AmfaK^!m>UrSG#;$2$1{%yK&ZkZ4rq!$)_jCIAtLAiv%$c7k5<>L;=c4v; z=yGjXVX}X<_Onc|!{+g@DWSH*z8)LnQhwDvE8bM7Cq82Q;+o+Io^u4J@z`{gyNJdd z<3su@+#nJ}TrfXFFEY!rBm{FuRM_@Q1T*?+JsuKxY$i0yX$a!M zK3dsLes;F%g9GRPzmLz2;eW| zWnRt4j}&{X*uaqXg>dGjFWKGj!stHc@yHp6KV#!w>85F@L>20#H)1fITs_NHuT%{Y z{z08U96gv#m zO(^zIlcmbiqNkT?jWDC}B5F#gYX>QU=d8M(N9r}Yn-2Yt$X>!Z_vME2d6d2#>e=yQ z#e3AhuQuxKI-o%(!i6xj-=h5g*VZQ^;sLR;Zd(A&pn8_jST zd{qUXou!wPMHLmzF+Rlu-Xf5IZOjw}y0fgBL?Bsg-f14_qyxett9LQ^@^e~!+m-5n zHKGI?-AS;oo0y-K%aX%vqleSprssQqo&XXfv4g4hwz+TvniWCXvalE8ah~h@dC_O* z*Mn)XE{-oHhTiC%*o5?dE~c~b{b@O{%jc(kOxnMu9p?KnMv}rjVls)i2;}k&*rhZi zA0ID#l0xI#rhI&wSaa2r)Jaov z|K}@${Jc&#N|_&buL^?v_4~9`=@Vf7DZV zFs7Jb-Fvg-=i2hC-c43tPEf*b0^QG-baLJ{F_T7+E&0mh2SRTZ??oAe22NfxdU=&g z*;d2^(cna1+ zR$Nbv^12A)*dE;nlZ~uh*Ac!&mrPh=znIR?Ek^i4zK_G7ta;xNm4n7VV%Jw~Q>TsT!z2P#a0M<#6>{ZAH1z}ysc(#hS|NWl3T02VtW}=T2xb77?p<&n<;g5+SYj)q)C*Q z7?qa@8Mn$8Uq5(|I04L~VAO!w@s!Y_T4TVg?NS(C%@WbO89r}#;)3|fF6~7Vb1Qp9 zg;Mv7J&Et4d)o}Y9$XRoM_hB*JxP+bnFX0(#jcr^3X6)FP0Wx$31`}^2g7(z-apCK zhV}V=M2S;%P#kR4Ik;`_+%U?ac6&(L3Z>Np3zKFudGgzj4;^Zv;UWf{ot>67gdExA32F6`(U1hd^N0 z<2G))JG(5HLvPix9q?cC zvlIL=2iv&$R*i2RiFr4Bnb)oNnWt3a`E$nB#AmwUD_R1 zA8Y%4iC>SS;k+SKUaDC1xc5iq_9n#`Js!-~yg}aFbEfwPCHGc7J^^Wd=hq-emQJ@`4yosZ`Kl`(I=Rk`sj46XO(9IQIT->aq zHT$!lA;gBaoS(itzged-h%?ipf;M7B*%0Zk@?PXYCPjqm6B(w^uZg+a-b|kw4xJ5)83|Lo?p+|xwV*TLW?GmeeDX@` z5PGNTrdxWLJ@MF2hS3~}!{p8ij%z1_e2Vd#z;LS`vT-h=9KC4kfTWPV>e0YGR~KuPQ@J9#-3diuO$h5Uu(2KZX;py zaj{M~{7+|4s1P6lup~_Z&thsd>}A*6=Q;{J9x6N@N<8%=ZH{EdPF~2fjN#0TXVk_z z*-%qe6KS!{P(xYigUu)cix~o^5js;lvgj3AS?P!rYJO6JMdF|(cDmJaI$FwLn~U^@ z!wXKF3%eB_xzDM2jO3XbisQ#|0?Z7W#d3tL)()e|{+Y>vzBqiBY~35YbmE`@Y*y+*LV!Q_ zPy7W07T$TMeJL*G_Oi98RUc+qzK3>=lce>twd}GPm_K8mU^5tJ+iTXnn&hbdIHuR2 zjI4;HeFg{5w~*CrX&t=cD#T!*RZNR=<9$Y8jkzFgO3-S*ld8k&v?k3G%bt&~6d}{u zUC8^Ap?vpe{6DC%#gW^&KJHMF3_egtVi^|gSnUL{W3DvjSD~4kcg2<>RN4Oz4cnRb zAAXdG^8Jw1bTRTnH<7X_?O=4uHIzMq?h+QjAwbDcE;5OF^NcIgeS3%0Ym4ZKj$Be5 zPtKaxP0XSeCu*S?b-6_Li@qn7Yto51L^$Tx8%(-}2a<2@Gma&#-V#|tgopnUfkl2h z56wbNbGMtlWe7H6NlA;8)Jwe>RWfsl86*mtc3p~nBHr#zxCD-)6OespCj8EPm0_!( z9>Fcfr1Qlt?Z!_w$<(XVF5}BAcVf!7PE5nN_Lj<;Edj2GH#SmH>5_YmY0aDv1q~c- z^t=i1KQwLQN_?sV$H9^Ch}6q2rxVSz_qVfLj;Y-r;W}4J{idjwhCN@{%_0qx%_4z` z5%sbUT0^HEqw970@aU4|GT5b`DdQoJLzWL=5GUv!!`p|v|LHPhzbWvQeCf2Phzl^5 zTUP2%fRI2VfCYq6QWkjA^>oUNK2-$!MouJ*J&g!4XvAp(e5pUx?MxLl*aBEc4ZZR- zA2lf=^P>RQil1@=f_Py#n1kjt{$ul21a>Q4+dl7qo{t=?+LQCG+V`_qE$?tXGZGFs z6(qY&UbdKFh|9FAe_Tx;*k(~hB)Kd)R|gK!<^3Xhk8tg(x%&)GF~gDGc@~KgM#nJf zwRjDt;S#KHLKv=I{j*{(9UHGLMHbX0U%q-h2hl5fT86yiZXALkVFNM99=y@986bCA9I@+Wa(=kihdXRnfkjX-ijX&%wq$Q z%bFD(Psi4vTFF>awwv4T5le13`0mK~7r3kG*=`?Pp+Qy*I39M|iw1Sp^o>Rh#6>C1 zL@B{c9}$p}C@PCscU#DJ|97``WV&g=kfcL`bCp(OPW~%!AAFwu(jPPj-zCgwSii=& z4nhGF`53_nW-xPA=nhkLJ)&+&Knk4QLN+&lb%Qqb%bVs4*c01sc?3LDtmzc2mbHHX zo};c*Kv}(Y7(rem!&I)o^w)|8^@XUMBxLrDjPgS@-=UOo^ygmv1D}(U(ML*6n&u%l zQ5@V2=4*xf%4~bTga2btnPP()7;d!CRlNICW&0oVxIKlsQEG{2zFB`)Tnv`ZQE&t( z)nUv)Io<%b@sUcU`9{A%7y0+M4T{G)=l>y`%OtvL`Qb?a*sVCK4AvN#p#C)J&FC z%Kuqj66|0eiAmw7W4@Pd+3T28Z5yI?<3chS`&gKR$%1GT}7(5vlnO`5S`!ihUYBld`mA){W?@@P| z9zNS?Rt1vOUvj#3y!YOiq%lY#OM3i9BmQQh{E~^z6_EIsOo|uZY$AvO8qq)BQy%F$ z4HDjm%DRD7qYQ6gJ1Bfq&pJvT89VzI+e6XVok=}j_gz{lZow8kq)4sLGW6P=4XV$I z3X1c6Ycn~iLK8EnKa$gOM$x7Z)JARjXR-Ap>e#9}TI$JOw2s$!)pVrbT~N~JhpHto zx*(GVk6$-g^yfu_q=5>EE5p_i>qnqei+`rd0h`TigoA^sI^!Q` z30VW>1jD7@3T@**x%G8D0qp#p-kR>+xXc4{%zB%yrK+h-lMGM~KTM^b&CxKu<479U z*;-yT__GvsdrsphUVkn{6IN(`=c`)hZ7D(CyDlL2NdlL%n==|7@3_W-90VZ)R3geT zQsI+ADyf#qEy9Z@NxtE`SD9Yi)PEh?X1dXw$=I0{{UYBSoYzIFadkfuz7Lkqia#aw zagy}}(X}KI7`0=8+Qibx{-CqAXWsHZI%T9{_jW=Q!2~j^r45trDSFoV>(D*ZM@I=! z@dXHlMnD~6eF$hTw*Y)7=dmW3PA|0!HfScHVyfj9p*8!~vNNgoKy=w$F(i*ydx~Cr zDqr{WOS`&V=YltPo_3BKXac-<2^(hgx!&8-d00^V(^&bi{?=TpigQgkfj8s+%bxt} zH^~_ayJ{=%%r+_CqAQdio5lR-@7Ha+DlPMQI1Ruegw<=moi#P99IHaZ_TpU4OBs8w zdrOQz`>U;W1JSMuo0R2#Rw(4LGvFdSXc!^g_>xbAl!T^^vng z&=c#)`8S-Th@cLr)!?7d3jiYyy#laf83e};m;e=dWjqO>=n}vQA;E~!k)tYsXGdkk zL}h%7*d5pnP$I_B(aRpQeY= z5?6{oMYN_5&UGRN#dB%5w^*3v_+YI3+C69`*Wh)p>;z0zzD;lW!6^Y387$dNzX%!A zFSr@w#P6r1Ov?dBT`D{gvI?1Ta0K`z*sA0j6~|#VMv3+X4({<9UDssv!hg3mW4Jma8ce20p{}A47G|s=iJz8_ zrS1`K41mP9PPt6MZ}p=WwO3i8UStnb&&rVg?CLmKHu)e@hkuw+Q7C(C$VksRTS@+Oy zjuXg>#Mwfe)PIIejfxf446o&HE2Y2ZQ@m%er}xDZbBR{lY$W%uliOqZ4bgEV#LRIe zs&`ssYnvdku{4sOF%{j7jjx?f_w!q`&2(gWuR zG>^7V%`GY(`1#E(LsML(av|Xhk-|Cg%St!YJAmIQ^a7Z&G{_*1kD@<2!5(kuW@G!Z zO7~G$&kt!RO!ZJCJXeH^E_RYkpafPjfTP$(e$jQTd3`l2R(hB5xQv`ha7!>i&X2hnx#gBzeoH>Lhz6(e#ia5f8(1q~TPHetKWbAYnFKgp(ZfYN@oUU5V-t4QMOMU< zUZC?bIC0v^hTn_)QQqn1hly9f1nA+9!P!ZaG`Wm(Sr@P7Mwr}xI=$iWeFZ;RDHlj$ z6puSU2{&~7UAVWk28c_ki>N#72^?|DX#jTfkLN_(AyZq`H^!Od-mdL*Pc4cA1?eBI zEv83*JyBX3MF-`Zr^uLbhIX1}Kl5)gO2@Hh7n_iOhh z3qlellM_ew?}b&v_eB6F(0qI|NV>H8t27y!2HPz)@J_w*la)OfxCg;Kgueg8G5@pY zDzWokG^JC$PU3b}!Qr5nS!4^38ZtGZ=yi&7PW1ZYKUp08ASXizkMS`2U5tyCzBt$K zF0bM;B3qlG(L+8KRGHh$bdze1-K*---4qv@LE5vL`=z^&e$*cEdUX9J)3#65TzSAh z`MbFBqPTmJ1<|8Tp*bf@>F}sB6_q4kZ!!nyVPpTS1-PGFFWpp|Z~Qrl4GQnYetgyQ zN<~YYjCY6EG?&pFA&Bbd?l=!b4zIJURQHN)z3#~~J^J<0yvy;@9a;MrUi|#2CO`65=D|;%@yRtH>+epBp0<7IXDum&SHM$eTDH>0h9~Xk%P>|A%k*Y5zmQTZLqY6GIZXi%L zUBj%?r{uhIQHy{l@qz-P}{1PHKcxuKm4h@T1kV*U_qxi>R-(_O) zR~qB!E9h>k=zK>3!Y62dIX7(V;K}rf%n<4UDw+W!d-nMEYFYwc>80>D*)n_w#dR`L zTv{y-ULJ;lQIkhUab$dg2l?*$?uJX%cP=Xud6D0lo9fSceo*B}Fcd8JQHayKHbg^Q zR0A-_-MIeqR8(!liwOd~73)r({U4u%oJnDU$!{&82f0nsm2uApq+X@uw35S~(24~o z6xF<{PM2(PCZ6l~#4EEr@{u>5>P{KD#{Cw7bbZnB{%sCXgJwV^IT$kco+*UTFarSc zPqGO!z7`3Y&4_JF{QG-MO>B+gS{6B_O?E^L-SN_SlxB(aQi<%}A(V>@H#~`xM%26B_#%P`gKs!AA@#RW)&{4 z-J8Q0k8VKVh}rkCly+DVPX20nHWlnE+R z<74mcWXDJz`4PM0cZkx;#~Ax>O<86^M4D-l4v)rUUnTE(JJ<$g7$(zwy_*&@EZxJM z0llI0^FS};D9?u6@2@)Y80LS~7aV9w{-lqeLZhzj6Iufa6!&hl(pkO?=k)4X$$0A!x^0p1#qXtXRY^qoupwS-Pscw_)cn{4UN({w4f!lRT~6Ht5KcYC;H}p z*36eTDmPafoZL_zFAPn*t^YjWz#tJo`qx&EVQV-5UZ$)~2?oK}8g!~APfxS&R;P;k zS(>((r>37;SjzVEFu^>1`QSo(5?7x*4!L@JBG-BT*Y)@T4uy74NUj!(9$i@L`~+JFA2S-Qo9Ke+yT2-v11peFy|v}b=F{CT9*i&)!1|NrCbt)rs)-gsdVq(oXmN*biQJEdh*KtQ?# zq&r1gx;q30328xc0O=0t7`kByVd%LB<@)#9j`mYAB zc36kgX*Q#GMd=jU`J&e7`b0$aK8_p`E-rs^jlo~12sy-7dX~rdLomqAUX>xSPo&+T zZC|%*U&{A4g60-z+{$iYD|avdtFO5)5V(tVkL_j|7HjAiYX+OF2o`I$fyCzv*!T$) zI5syS{U^}V3t05B4|6=|P?uZi&B0#A!Jdkn>yVpkUuLGK#hZgtHMh6pnG+X7#q&B7 zA}4}-N$ylaOFZt-#G8<{qD19t?qpN5U~{wJbC~X9(rnTdKO33X*A20W^+1J$3!Yj- z?C2CUy_=^82b=y76fCw#H2raISNX;2JsTxHNG9z~UrA@)U5z_b(y7A(A7X41RX6IJ zukCqhZQR$g8au9U)OQCFfi`O8css%J8+iZS&@2|;N_QYfRax40hy=73#dzYNgki#U z9=Y>@GH-J&@#@Ffx%u94z!vb?MtQGaWMlY2PbAmJNl6UZ=H(K8%jop8mv#!U@X^Ny2I0pG^}Ta7Vgs52Gqz=z2#8j|>mk+E&7~@3ioWX3o*>qr99`RMAB9gOG~D!* z;;PixyG{utGy&U84hwDK-T$fvW3)X&7Snm$qfwEKu&pig*zS6uWacI^%19F-lX z?BR2KeNU;2w6NfZ8BjpK4>1#U7s8mFy|6HYx}lg=5`l?SfnH$;2yFPuGp`m4bwc+O zu?zl%YR2acDbn-nS@7*FxbyIp_i*Fd)882#W+Zx77^;^G3?RY z7q2b3EmqO8daK=tU61fi!84vsglpq6DvT z3SOI$nhN&ue^p8Tc@!Q`KH+`u9X>q{j}w4VWd zRsfQr?OBFiOe#Z>;uNL`)vy#J3}PVc{^=YgN6;P@v-O(C;>igKS@s08sq(n>pglhxm~?u;O2r< z*snuNOuR(ega;&6;VZcPZur&!pLo|^YKPhPNAar~OQ!al;(a{8|FZE=7qz%C#j&WY znMVnW$(pr6nRS*J<*%HC55XeJkD$JA#MTS{B39dkj}j5Bl=m5cm{_Ek+Az|LD?@S} zFYm<|U%`X+bk*XLiCAj*0nd0Ly9(!n=VMqP$7NI%=J!>_$P`f3{pyO{xNyJub#ukj$fOrG?lhz{<2r`bYtHvt+k`_zah@mbbaI+! z_N<_lz^1e=82@yVH^|aUzAt4Hvbj)IWR#=0@Kxksg~x9$VY`Z|SQnp^3%qD$^;;r~_vyVC4m;?#a^S7n6Ici9VUL!Txs3ax>!mt%l^33C{!uPst} zs!~#w*Li~@4^Mkya8*ZKe%ivq-Z14zhb`-R!cv*VF@Dj_nMun<5&fCR0RE-4&B;x0 zm4fwQ9OKf6ZAw=BJjHNo2!6=OI3bOrTY{viW%wUGVDR5GC4*mAstp|4?ZpsZ`?@%{ zG$68!;=Bp!j7@gX$bMv2eIbjN*Ptno1%b2apdI@2qHo@;H0V(iyk!5Y2k#O1KKM!4 zRqX*}RUFg4T|l3cxSSBqv`}ZwNiX2!zpdyH9RtAlv15&z^R&Qge1gSf(!ZNx8;)-6RNVCRuw-;`M&$t2_D-idv zi@G7^tvL3!gxQV+{b@EgJe%gG&=Mh(k01vjgftOC8@Eo12%#E8Mc39M&T2)bdB$9m z#m9ynh&~OxLfEs46R84N}?Vd4dWOpup$zP%yQz$+GT@x$`>=={eWZEbrSny0^M~Z*?0}q-9H!@I&cT@uF<;OU(Y2I+3wXZb=5$ z`=`lkwh+yYO=|LkB%JNY?%!n5z)>$iIYx%F9~tte%VZ}~VJEVCo(wn}a@Iw=NqB9O z5CF{<`eyxh6Su@^Wa0*1nqjde8tu|iByu(fCxL|?Hp^Wtl1@a2z_z z5q`6XiEhM?8?B6KZndUVwy#W-uU=Z5<b+* zA`$|v;q>2g_?<127W?4n!$$SZ*$Y*nXnVC+g%Qj`WiRJCl4?7WLQgY~ZQ7G8m5%9b ztg@%avZnDXeKmNElzE@{nY=04>mnDCf8gQB*muSgEzEeJMv-#VvEY$2-33i;%x+(> z!mPw}+l)2h{T|kMWo2?d#rm=nacqW3v#i$|MXbH`3t`W%*I)T1D6omomBJ7!HdY=8 zYjdvzPVv1r(~IwU=H}FmysnsSqQ6#(B~N1n?$5aNo&gAY&_2B%#OAdBEyTud|CRu2 zn^^4zy|%_RP*gCrI`5X&F70hrY-1`RS)A@ki~dCt+ydnwZ%i^by>@7~tB(hoU3uj2 z6!LM;Z1Ex|_l~lAH`LT8QgS&|eAkWa{dRNR5fNF>%)A^@^Ralds59aA_B3-s9ah=` zNuAhC?Fr`L84`{haOp27WP~EnCflbwp%sR&UumF)F`E$@0?}|U`JWY#WfdO)2=>4m zs#winX8fUK)4Y3$1f*Xcn)Yi(zfV59-BR7GhBYekq?#blOvhGSLL}D6s3t*CIdL?r z-Ezhf7yuyegeQY~&F1o7C^R$S;OcxC3lp*6^tQ+}Th50Z8)8mwmLOLfiYK7ZPWczf zOXr=@;B%M93NHW^>|LGik?*MXajb}T!lO&kC2L$!uHcD00C;S~?vx5^X7b4w$HNBh z`_)0nE%FNL?iE62?SSmn`FMo43u4A3AF&5Q%mBycZ8hN4`+*?*|Ic^k@e>4hJFIvF z!GR!-{`UPqB32&HRJP$whhGL67cK3WpxK8;&L8^MZsTz=u{=L$ZW})XTa45?BDiRb zZ=xfx;*izH$XmxEA+VlD82IhEPXZm3FQ2 zN3^+@20x3QQ^Yb+E@UhpddI5?$hQNuO66&vW_dw$T(1(m46dwLsgTdP2PO2jt(hL- z*Nod9c%*&|uz}$T`>;r@w#bm@ z2G!v_y@v~p&)W2>=q8W#A2$a&GK6e}_)8g>lg-jA(sJYuZDtX=?^k<%apiQ3lJXX4 zYXDRXPEhvmCO*2_ntvm*6d-Q9Q zri#5_+usBeK4EDLY)c0F|4KImc%}m5^+P!IMOx>LK-OW8_qZ7G!{}vro?5eR(xcL- z#C?&jap-O05c_Q^wDgvbZ3t(8NFCCbUY{@UewK`5KQbBE(6!mY(vEzL3|LNcn~&la z-L34JYVJ-GZ=(6(?Q;&sZZNzRI%RPPR~3{~RkV^`{G@jSQE?jNR~Lehh!G*K*8J3O z;WG$!K<^F^BPPdwbcpUffPM?P92Uciqz-r#$Hs7Q&TO$R8j!K#Oc;6DAhUzyz?zf1 z@st)#fSbbv+Kl2?*)EBzes@Lxzf%oSM%h#S--qk~dlK3B zd70LA^cj@{N%UDJs0NlGA_5i>8Ox+N$)s?!2w9wAc5_v8a|OmWft77Yt+~2qV2F#} zoF730J|ceRG5iMVGy&IJ7t6lPQui4yY}y1tPl^C}qgUBwR!PfdF>HqOneoGP`Nzjt z4aVej5Yj2N+vGLB)EkZ!04u^dLZnRF8Z4(Q`hU32{1Q>ezYpytMt6 z@ZwS^yo%QGm`JXd_1t&(YWbDWYJZQd^a@c6aS=b$br;m(VaQ(%ancVrjO#4$^b)+K z40a398Fx!GgRdW0C0jHgGq4h!XOLJ@=o{*+g8R$T+-A2OS;nTs4OLKWuJUn>? zO~OZBgqu$GQ_+d6LlaujiQXnp{L)Gg`eyA7tb3%l9Q{wV;C>FS4NVAZi;^UGw&FIf zsR9k;B|_?tiM*>^48_$j{mtgstrIX3XeRIaS_$#;R{R^$x=d#nYz}3i%+7pDpjz44 zJYHZ`_vKN+hQKO5Re4LQ{^G#DQ~l}8%>`Rnw0uRv>6MXeZ!F5G;6Kfv1!V7>0&v1Z zc&K#Wpi%z_HdX6jaO*55V-&bLbN@>VAk6h^J0FU787}gE_=O%ky|yKp zD3&`cbmeF2sO zz1*=sH40Hbi5AhwT<)+NE%{9|5BN&cDVf0eLGKM!=Bk0%M;TEj7sPu@f8|OnsSkwb zc+z3&34qH~6Fw}BjFtpQk@zsNU;cf{ioXDMpF;G@3%rHNpb=lDL zl#=6_fVNM$O&F51*=0H6&&1|HLAqD0J0w%#^#eB|W-kzTE)JkPHNDa?mjV$Qy%x&8 z$HWtDBv?pQ(%v50$M!I@D2kfdDKY#p0>EV(L`?wN7g=1iT*N(3x&JJwNprPt6Ju=&p4Q2m@ERnHwVP zmg7C-_5pTgH`VZfx@Am)R#&!iH&qfE(=*XWPdt%6A1|w(A2O^)i+r=RFZ0o!MEqFA zYol7b$R0nD0FKQ~zrGWR(+e$+TNlq;J~4!_1meXoWalJXeNo5xx{@G^1jpEBi`0dL z{)LJ+TOX|&{Vv?M56_w_Oe(1CD3tvu6#VyKI6_xKe=$Nx9m0Nu{%?M0xf1FKP$tmm zcYFCLMWvk&#YHqW@xmLa)WZr(Dfx8f5$h(jC0861g_KmOG=fZ@Vs^&$OVq^_^YAig z@W?qFm%bDgMdyC3Dh1MAYjwJK8X6fmQ5a-$G}$^ zwpiN?I}~4-nN_L(b8MWfn`3T~mQvU=5zeWqru#g;Yo~`-NK3Q+@p!(a$~Zmp>BkSI z_%?XntpM4YVty=e_9fv5RtwsV&oftHDbWwxR~c*)*>P+Vnx`!ld5aNfRhJ$4k!u8m zj>voq=T~PB)(HA$I|;vLN-yCrd@iEk1;9&Y6yS+_7d4>E=f~4<^l3pT&&d_8&xaT` zQ~;jmqK)q8sEA8M$hCo(a0PG?u`kzi5ToSIF5>lq*7Nw*be~bIRW8K1Irlgiy&bj0 zdpqm$Bib43ZHW6+FV+~mYI>VVBl(fiEUfguf|BD zV^i3N^t$@v#aT8L>e=2!_Edt8A41$d*SGuqYsKyMdV47L51^-9^OGdhGi>M78G?!o zgPk&GJ}mjU;5#ppF;w6#Jz;uwKgI`ouZx(D{&aoSVP{eSzgonvqiDDFTB+Udw?*L1 z9|AVejSW*!K;+8`3=ljpGBcfEDefnW0OJI{%^r$w{RQ>>JVvIW2_R&&Quvv1!J^)K zEf(m)c6A-yGrS~>GlKyXf)MXLoRdnQAs8On6m-1Lf%IXcAI>HZyidu5XDGzp_*9*| z=gNfoDt+A<;4Q=otOuU-*(>%R9uZz;gt|oEEel7X%=VcX0H0*%;r8 zw*ymT+OB+R+>w+Ml6{6}?3=Mz|kL%nF5h-*4 z*I1lpD5dvDJi_7_k#Qq&_wWZE`I*<{y$Io}zruV8vqvdMQDW}hKW;*u$UGEq|(~(V?0^lX3CEfrcH#*4)c@VTzhWde2XJl2UMPU z4=aUy`;`(o4sHOUeKe8o0)&<(UM;wuO}kkqEOMEC5^7(GlvqpHrb<28q-G?87n%Mp z?1?=IXX!t-L|_8?JNoC%tvZdHqU-aeR!RjsG=BUkA`t#~OWmkV2E|2mOZ< z+(N#8%+8=dPJzNXY;QwrMP^A7@EHilYn1Y9t5_7+nD+|TwQ-9wy~VbQ0!M*z6UTRQSYKy@z@;wxR(~C?G&UP!&&Qh;UsuH^a z)rLe2cud=n}ntJ3fwn2C@PlFWQ@>+8yJ= zng3LEGKB^n4jL|k#~54$f-G6y=(VTk7O}}oy?%7-^>1>4YCn7#7jvPlPSZZlvlLIa=bJeJ&E z`&ZdjXZPz^eTfo&d&0!(NU$h?4-+9cp`)#V)(F8)J;9aGmSUKSUTo8mhn|D5n2T*` zljzhtz^`^SymBidL8n!koJ||{^UO^jAu)vbV?KLU{>?D)=_Y;TxNK5uj!>ChN}1o$ zf&?~H=ZR(xZoD@ct6q4zsclgedXRbS&t9e&NTzAp7KT(t@d?LRHR)ZupQA#>%< z<_!*ebRE>;;ab$<%`FF{(VL{q3^ru%b%Ze`0ngMLRx>FI+$b~u);8(~U{oS#k zX5tpc@%VP`({5|eAF6-E|Kqndl<@28I`FWc_0jddo9FH8Sz1?6sF(!e`|b(UQ`GM& zGYc?K1ITmqA;O$p@Z{<=Yyt8asv%Qm!n(mXg>z-R=SHBqA=pY-aG4DR@O9@F;I45NbmJnZbw5nET57t>Si&rq(S|b3w&tVH%+1J-UUsks=zS5c=H+_Eo>} zBgpnS)bzR#1(6Pnbs@@DB`DTLL?RI-FzTP8c{g`dfPwd|v}|7CR@dQH*G)Dhl(UEn z_mjP}Op5U;%)5#!L9ht`W1q}529ltvK53zCe`s^pR{%7?!at5*pkCKf+33rj_HGwWKizidoovYG9D7@A&CkK>~6N~RH)9jwR5 zYtH^wtsj5*>}dHW38rAQmn`wpzd8QINQVV{2G_&Hz|`;8#kMN0Vo9Sm@fk_Z!SQ6^EU2e>ASd z?^1YQ8Ao&XujpHvr=<}Izx7OvCWz@LrQ`{}+E$ip_Uqk5y+yYZqipYiG47X=K_IDz z9CE^eJh0Bcl6RN<{z$5LYMj6>Zujf=CA&Zx2BQey#(VJ!_b;{)aK6;OE4sN}#@T$d-$iJ@ zeFQjg4k|>2jW(yR7Um`+4YG<8N<_N z3-D3N+WGQN;s?%vL}bk?N>)rI`sZfPQS~S-v^pJNe3+48F-CVhws8;&dr_Axt!YzN;zUe6~C9=OPjRY?$Cmret z-`|5CRWeNWy~zU^;|KrYp?%3XqffqIM{E^Bw^}6_gez`XjFHm^)1fW{28(cs!)v?j zMXmS8USFQpR+7d0P@gBsR`X*5Q>*(1+I|JO)ty5-o8O36NX9V)vQTO*)B2b9=*1= z3%S!`o}1iwG-j+cT>Sl%8YezZpDhKx-###bZ)LKmSbq4T*qSnf{H_INj|)iHJ_~Ng zYD*gaU?Ulgf({#&0JWSTroIn~UUv5PeZiTQv4X)1{S@n^JBkv!L z5**+juzZzxGzy|&)si)MGzwg=r=uZ|s`TGqBTP@lfo9DxkdI{9)yFu{bTry9u%w$e z368i-9StbLv|IRL!NvTJ-lUJ(g?O<+dDyrsVXQ+}dF8v=j?UjKj1BEyRZU)p11equ zw9)3i53H06vmAL(@|27A^i@1^Hp~&}3e}vdcY|N#*MEZqp7_}z%55LR>KiKuPl#La zugsr2>~=q1ASRP}4+x4b&m_A;9D$oMRG*ePcXgbQOlEQFRG;=A1Zt3OL4xN#$o(b{ znZJQc+z?;5g%JYKgYHNWQuTD1uzX?FRR81%5n*4tU1hyws7n6DKZLu>#{t3C7kl<& ziJiXfN(@y4tUWBD{ku#v4BqhKVX>CEGF2>fb8Un_^YYPq z^8Ec}vRP-8fn^Hxb4?U)jE7(p5@nFrxn$*?wN4Y){#aoD+Cbbm>UCuT-_ng&IMQ!* zE`NmyT7+DujB#OeZnnhd%-RHwB$w8bla}=v{T~P#2v1nf!0>1O9@lD#ZYRgMKX)<< z@|Qjc4my8s2}lEAsUGfqIkx;9Xb^XG_`_WfXg!oQ;(>|VB@{F}=#+G~mOdg&ZdI$`^AZ079&o-F$+(GVa^VqNIZnF&SLtWf4@ z9$UD@VH3f+u>}GMv#bbl$jXK>Y_A z?1-_Kb(4_{SV9cr-c%LujAGg(RRK5#F5u?!IvBUre{AtRMw&2*3BL6(j^3(mNhuQVPBteP%GXL`@tvIYPJ+WBG)b zX@sz!*v7Z5bp780KXDHSul6PDsSyookfgxv*$Zm0eU5BE2v`O6oq>?;+P^*#*rpTn`E@Hu5NsNtP%R--C4nN%`$$DNhzek-0r>{x{Syzp z%9EYQt8t8{%&rH!=vv*8+8(PJ9duxZG;_W*Q@&zzJ{y|wK*dcLlLC!=2HuiUx{|hk zodX!%NZz(Z>%-n-yhNiOx4B?#5EWcOo_K%_BaAloeAkqih31l4pQlhp8~fb zc1REZX`_byJY;Jd5E79pDHL@bwX6BHLP=XJ9(CC?ABR(7%Ti*oCAL{%CVO#cJG}Bq zaIRZ16RQZ7GcH#=F7BCbK@~jI{worNyXt?!C&Hwz!GL+uw0d<{ygVr;UJHeK%17yA zR>&leY8350>}O)O+c1hqf+A#`aD}zTvx}W$$+p6; zuV5u;4?OhF*+j;Z2lRu90~9+3TVBBC=HF+LbpbLb(`d*bMy_gb^I=GwKJ zq{*)qglh;hpH;pMx8KAI5DL%?I<)c@9e)S^83UR!S}Q)!j$IR)FlvFS@JGy}tPANX zT}Kd$amB8&eB^!qHa>0c-5r_>PcXpPC2iS_5<6R}a`#`e5qY?IHHJbZ zUl6~?5SFjs3nKO1oRdxdIwqWvp5|_I#?Kr};t#UvEcdeUPPhF17klb2;}{};Z-%YF zqvkx1ZY~;5wHHQ3j?YzdG(2;FlXj9RL_W8h`cxiEwLzu2P_XdByD0w_TD#7*)6ZRM zdR+pt-sznCM?-<$Zw1YWM8G1QtF;lhfgsvB)KHSvK;0EC)Hg^i0T%VW&o{iQso3PSY#!@>hj7Fu3`pr4PWSM&0=vvAWST<$UY!{SxtrICb?QrL|A z$^oJJ={M%1h8(zXE<9~SWF}tb@Woap8092jaV~ICR~lxjE=7vc41^o-HGMF!_^~L3 zQDjTra;VF%c)639sN;}vzNADZerLt*)PJ~@Uqs)s-!Kq<-ws2McEX@%{JPKZ^rbOS zlgNxmSjqzosqh|83N}=^a(%aw#lkq45T#jZC|$f~i7pRBKGoWZ-e5rYF?uP>{U8&5 zkxIj*m5Mq`a`EA^XTJUX^$ToH8uVc zk?n64^qu>wXlIj@VoAjt9KG~7Bil%iZ2S|3^?YV@tEaVhUawjpk}JTL}I8{OT-ScCFU-#eb#0f2fYq^+H$gko5COZu>fkFJ~h+*IyBm+l@uJ>YM*A{#E zotHhE8S%H-me$(mxyGO5=98cDrqHX48?Fl`o;3j2Ql|G(oY+HwAIGTffir;9@o&%9 z#O&0WMnb)_At9H2@akZEo98%#uJPE+$bjgOY9FE%+RSOGoHw*{{+jlLty`I^+z8eC zrp2*?l%@S+#@5pw7}w+_uJ>l_>693Bx8g%o6_u5!%ixv=5je2O**P`niG(8&rKHK6|+d1Eg6KVW2#NJ%3d|2eUgPJ+GZP-A@=tA56ZI(KUG0q>K69~nv zGxkDhMByBI!z%v;wp+C_@Q*waI8N$Vl-;#*9CZmND<>Rs~y zNW2sQW+PzX0n4xAX9(O={-J(G3FGHe`l{2quZhlhPW_jjSuN^NDwG{SXghEO&(X*) zbnycRu$Ya?Xx13eX9z06rfErSZc;r7B&b?}^C;AJz1D*suKx$Qg zZ)X0%m19%ss$6k$jPBt=sIYg%l6yn=qb1HDlq7uY(P9Lsb z_I2Ty9^m(;y&7iwHt!sWXz@xE5UxUe1nzqk&zC79yFlF7n&n=K(#T{>r)P2~zT$vk zwlS(#IH`SNCILd<7?sxyUCJ2MESxlfkZ0*dBl>H_0l?f_-XRJ!wTe%)1%|)xuJ-)k zTHd)Oix-tR8Z`Hb5sv?9Q_f{-ku4Yh)Gx7395e|eA5^YH;|q(cR(>n*4VU=$Xn|9t zFSx8w>M~;c86D@Q%x9^^PX7__1luxkHg!9+BM)fMT&sYBi|P6G!P7NQ9!Xw%r&HpF z{9QKiLIgvkXt9f_4~8%J%49!vn2lucRw`a*z4Cd)SE&2(c)XL)xc7q3096&l8pj{i zMuK$z1EX)P+zPnc+{zr&6?9ppcUYBlSv?t$3#~h8KwS9+br=GlfzkVBPDaTq>k|`R z**-TiDTi}@T`yMP6T^Auex4X*f06V7$)$8zrN#ltgS&>r>z2>h0q(Tbru*sAKT%~R zmy5*QBR}HkT?;AJ$m`j|eZZ-2+oFv12~QlzHbMb=o; z)J3r@(fvJ?=ctl)g;s$bg{2X#qx(-QUq5YC1Rvk8h0Sv<53IMXD%p8_BqpNv#xl4S zDBXs^df#gNfmnrkryA5>pp;q8#}Vy!#*e@1sR@Qx1CK}bqNRCFy4c=Dro3pUmG@BA zjo8A=)AK1?`Pu0e#Z_8JQu5(#cBii>(oVP7Eax$t_i=|1m#fR42a1$>#-WdL(<31U zcE#L+CU>kIjpqaUCi%1#`Z--w9K(NgnBS7MuoeZCIb8<-UUlM2v_^J(M>OHHE+{-* z`bBie{F#l?sJun;`Lk3>RtNp4p?h)7iQ3*__Lwtvc_Y)mG)9>_vm!2n>q=d0I#JHf z=hzR3+3v)&Dx>fyqj;qswl@;Nk+$@heQD{n0YS^*4=NOlH;0c@y`){JRnNcDd$;`{ zxMvYpA3FwUjuRxLW##-{Ln$a`WO^eeRn&)}^hRBy*fT&g{@kko! z+)ALT9(-^Ll1(&Q@&HDf>zw>!l1Bjeq;5syH!73f_Ap;LPzeH_>BGK{km7 zdjQxBj4oQ|W4&FeZ}9^yoYy&g5k>ax#FQytf_Jwd96Frz#JsJ9#)%Wy=g${@i%S{G zp8tpRmhvf(i>mpybQyaM!?CxM_i7_wU@GKG=IXZRY%yYV`h>HTMg_c|oA%fbf3B4b zq($ME@}TUxhs##8$W*bQubW?KJ zOIMxiWh)}+zfh44+NbqvTPPAqs8p_-46Oj&66Pc+h=^*KcX|AbndrA8YtJeUgs*Uq zR(y!}0^SV1^P@$u2UPjm7lAaTJ-LrKh0vj`9)99Q1SK-7tq|r!? zSU+cMlwNlucYLckW)J|fMz0_UEyWy3wCQ*xfq`jLb;fCeziz;U_*OEq?V;;yk)1!b z*gokpi{?{xGpDw$9_ji};H}Ww-%;p>yI=aiS7FCWw^}5xIg!tSt;Ckkei_5X>+yIR zdCgs|2KM4oNa;sDroGc1DCe5NeKi8G6lT641DR?P8U&#ii@uz4fuL|pNTUC1CAD-H65@a4)$oqz2Wl zb8OcOWXg7b;F;0q|I5IXwT{=$(%bGxh+g4?<9g!SHk@TJuY`xzz9mV}-~`r|g$;RH z-3ZnL@!2mQ~ zUbH>+d(Ha8B_H2STAKIWFxUVD>}3qU*!LdDXsJa+k^4I6zxKg=>)tPsP3m>|(w;Oi zi!ItIMo>FbwX42*-Ql2=dnofwmry9lrXF{caVB|%;xD~_Aey}{~bNMulDQB8ZB##_W|_0DRnW-R|@!OL-_crb9{#orU( zd96SNFZ&I?chy$BMKfTeo1Aq>#rd$0_2qErrzE-(E7e!#4j!#WY@&ft!gc3hYj=x# z*byp+iiL5BWs8rKgc{nh!KXbnAcB0IKh|0V0F|k~6P74d9rkLLA1;#qt5DLrY>m;w zNk08@pMR0EShckd2Uz~n_jyAJO&*R zyS)x_-?NX`%X~O`xJdL#$^ekZY|X6wQxcTGM^g4b!IY1xTL;R~(iOaEbEL}7+_v;{ zgk%>RDCi28a*>g8kpKtAg9B^-)p&eJE$Xcz>P<%}ZcZs47=p9D{E8)|iXglZMgOVn z9%VooQMZPj&34SWmFkufO$l4)BYmfA(=$A`HwQlFNNxolkj?ki-g=w1SZ8T{)CQL$ z96npg;wU99ogefo-whiyD5L0I7T{crh4^mEK>p+!TwaFm(R1iRem!f$5&AGG{Km&yd@S2DxF$oN|r}PdNq>OYjC#@x`su0su*b%f`Sxd}V1~3wx#6`2h~Q z#4SZ-2!X#WVmd+5;O~$JwqRFWXJ<-ViA`n9tw^VA6Qz&?;0nxewOiDWNZh!-c}Hc@ zq)l>_vpctli7-1|&vfAU#6e*_iKBg@QJQMvUA0-O&`BrHzrWdSnzmol_8yi#i}c%> z%dCgByT|yb+I$uZRyE~ii2XMcnL881AliGFk}G|6t>1*tfQ_2xL%R8EqCCJqW$~MV z=fgPZkNyZC75GOX=>*FgpSIwEZ~7L$4|ra1rgX57U>}c2g=@Lf^?t_2FF$;qAREV| zdW4DcMJlA#O9R!e5m97M9 zs(q4c`UJ-ebM|Zck36)b7DF-X^LxlXQ7t86cr^Zt5-nD4bhse*)f?R;95uvA{!Lb{ zjwc|6!nY4z3*E9Sc7nE)jZ~C%TYEdRy^g40aL|8Z!c5z#8CoQo#7&nZ4GMm%$+})g zSD65H1X6Jtp5ZJ>{>^l?XoACpKvk^A+Vcpl5J-tz#o|g7sPI{KpzBQs*U+u%NI2Rn z-rF&{Tg{U#B7fOYC4!pv=SqWlWSc9b-~Z;qKAKJ2bcRLhfKF^6mtrE)%W3{5-f7uR z0~jPL7Q{srwI9^&1}Fj#}DA3}GIQ`Aj5nB>A7uY0V;;ekacwijg{ zLhSfxVbTR+)BfbAoE`2+0c(e7aIDc9CZuG`ZV z)Jt4KErM`sf^gl_5`BtY&K*s9r4EfSG#kx?o;+5{omeJ3Rh+OYjkK?_==mA=X8&o* zzRigB;Wsh~I$kB-vP`3rhVL07f??i>)rra>Ak|p>D(FW>#|O$HY6hM#P#~IzrfIJQ zF%Hg4(=ae@x@?l5+z25-Xs+}S`@c1oW2Y+VjLQ4wykkLmiUpkv08`_yi8?bBUE(jjeM3IsT%Z|fQ3eu*jUa1k26N5$!V703&3 z?RF4JH_^}MzyHC_?1D9Pz`RAwPk}U1fm0yqUEmZUitHxTkg)gl^-^8YLr4MUHNV!9 zKvApRyHC)9hY%iO2z%UZ8vMltC*hVg2QPeQcL z$URCqB3lW-3i2%Mxw@1drJLlPls+4k;^cSnjIN)Bp{XOt=9T*fj&H5^o*3XOGnlBo zAy?B@MNX%#F6b{Of$1EhnZX2D{Gq-QET zdqR<){}QjW)nem5hGjL zStt)yHte3w?%3n@O9z6=QePLQNU3rmM`5d7mvmqO&DhI<996E*Nyez;6!%G8?e*#Q zAMsyMECfeI=M}0JTwqUx^=-1tHbkl}|^ z3V&j4qP(y~_M7&msQhXNWGm>)%tr<=VmHR$+IVJPw&t1u4*i%nzzg5s#KYRCTu>$;X6qB|$S_*BKLmd&%%*N~wrl znV3k~0phY+M4sHJyyZwB%+$ENMdk}g!>F7$NHDP3G5u*;RL6Utko!$cwA2K3o_^M# z{C{p)adAx{AQbF);8pI>+gPvsgr4P3^uED(eY~s|{uk|x{qNC0WCPT(0e_faUVFUn zwNywzLh*-<7KaP=Bs;95>p(t%wlurg)Ju3J`YlxV2@TXLS$rBSKCMY*<3wdMhL(QT z#_m(0?o&}HKD{YEU4Y}d|M`YmyL+Zk;e`c5!wyq}Xt-jjHto*B;aM1g_4B6zyw+>1 z{`LSRZ%-mAo+yt5&g}Z$> zQFH}#ixnsvBBD=#75Hz)LIc7|O=4W^N`=|UFj43*W22R4@KZ~2!e{1GWc5tsl7UYy zX~@=T$UYp*_m}AS81UqFKKJ8atg?AzQruYyy`d)Qn_;|Y^SBlS0op%{Aj%$-O`wVy zykt9P$q%S>lS$^_=bh8p{Z=K&@6Gypwr~y1K@a*~IEH+e>jGIqrL)rb^y1j`L8WuHhN;a| zvlMMoR%-R)%*vZXzaS*qv%`0oK4`SJ?3b0-_eMYTvM$B7mYsQAxMvPzTrw_l%mX0^RnmzPkKDyk{l0^?enms`9! z^PDs+XUwCz*GR!ZsE(#CHyrjyV!sx(25)Vzc`Nc(6%7WpL_Zv{&;=`n%j<;8>bOQ$ z?L9M_q3@H%$czM|=M#oi-Fvg$B!0ZwyaXQ0R=;>wlA^RKA%Q5|4rxjh*v43010+KE8@giFi<2RPR-L`-oR#I&)Xd>Ce15hBBWsDTbLYWMZTK80t25nV%(O6LrPX)FV55B zqO1a^RSyNoY&}%I&{mqGl4Ffouo#YZu(>TKnXF#MN_tP`SzEg52zl&n&#k*<;0;$X ze#Sf1576um)Kriz%9wcg0aK}fxkFiFhcEXxOYZBT5BIl@LWa!-Ew94vj>w2(ps!V0 z)FeKfIyh6qRh_9(9lj?;9eHIx{;+7E zUMbN!sw~iBi$49Pzgp_Zlq625Ohu|(Z5Y)@qn&2l`@omCxS$c=sgIcMG!<6HPO51HF_7_5JZidAbRh;cSa|=D5H)eqnotD8*aC7q-yu}Mh(Y@hqxL#P?SXew;SlnD#EO2m90&j`< zrL_2@wD_jLl(3y&Nz1?Lx|}9VpFL%3z1iOx=v4V;F~_DPLCN{`{5>;zm_L4$Al7y~ zV_MuJ^}O#zVN5KDntDcctEx6{dr&(MFyq5 zcwBd&g`h|=Q2Gj@LNC;R2p%iaLnH#FOMA?*-_VEX0KV-DN^?eFBCa?f?TSGcXF#m4 zoGj=P&qyH%PjQY^7Td__9U@je*7xtLCF86RWX!nob>=O#PsS;kk$SUsbRFoXY?a%i zKzqnfq3J#ntO21TZMnMrw}tTC^guL%0GeZId4re3lOsQB;Yz(HfajVNk~}Jb?ekGR z;`A9qWO!Q9+Hoo?wNjCXP~BSW>G;V9M^`w2`jQ_oxT)7w+TT+uV=`lEJ|mHMu51o? zTGP&G4qz|`+<`Ba*{zy?g8m!~f&;>TC(T9dNiH?P8$L6Ui{mBj*3ntZc#JIKf?Ge) z@S}Z@z<8V*dmcG(V{QhZuTGG80bE_u8VBl7cMf5ZW(Wn~3q6`zZNvpyl`RYc_qTi+ zQif;}D?|*=Z+QZGhOoURn6F+=z%Lf2HfmT5$ynIZBPr+?h3oF!4Bz@`M{h&+h}au+ zngvz^HVsM+5@7k8?N&_=pX}=zA^G2l$}OAja_G98F?{_3{Z@0J8E+DvZtuFE;WLMO zJYvXxHYy6fmWVjMuMf(=8>e~}te@~p^+xU^n_QIs4Xgs2hL4HTJ!e%~=NxGqco$bkf?+;2t9>ard|=zgWAknRq9KHj z;_!4Nm;%v`Xd6AO=u&;D6D}ziYsCCoC;WTDT0oxi(8_&w-iJ!Uumo{z9ngrw5vn|@ z?s$#ePk8khYJxbgHmtn3e1<k>H@>GlRs8yowT`t`PyE$+`AlsZ zf8FERnQ2~d0>kqeNDiI(m!;eErZ6>{8!bYdrm#hm46E(AgHdyv-Q%ZJ4h;p&28O5Z ztY0X>p>E`c`ejy7&BD*Y+WH4p;X%vQyNLe=atwg0KU;fCUl(A}YBboEt>25sGXibr zJpHmlT{25}ocvbb9df8!om9vEPy-NNlHe{IHbN3I4%7f0ef#a=;~k&Us&n)jOi<%2 z!OaVN9@LTPGCA85E1v3J)bZ&uLEBjgO?U_pxIMAs8Tua5e62sT8C1S{n+1Gd#r5h^ z3r1;I2Bp^bo{7bwWtaoEFg_v6%4*WrG&as|_@P(RSW;8`yRPJP`_+2+XvTJ4sa$WN~?@ z+;37wYIq0HRR;CNR9{9109G=iqT;sJugFUy8`Ph?$*xn`%zT?CWAhWlvxvCkdd9p# ze$l&@SKQfZFm%S8+Y&LZ6`b48tSn|jLi**yLnHm_;?^2F;9aiUa7H-aHLw$|aPM&B zP=6b`lJ?{t71)Uv>Sl2tvEiHHfYBJ_kX~BL|8{R8@24zEc2Rqcg-on;&iuMdE zR#aKxSd+!_(6Y%-SmHTI?NoLR|2GnwO~+~}Qc5z2b2UR>X1iYc zeZE(T@p5494N1`+_B+{sVQ+q2^LyW@HR*E$8&bLPD{1QG;&3%tZTWf3jW4rHEBhVd z^5iWmdb?qX9CDYmxk24OQ9I13_&=2D4j_j0^(&zEUZ3cGFG;=M_r4hmqY;BS$LH6# ztfvl7T6BsrR=gX6fomDiC0x1ll9GBfVz@OKfe&=%jlu0{o34fOq2n?T<|m?!5^bX< z#z$w8`|L7YH$@|@4N7y5CaGtk!6$GC;Ji-9$JYpCORi%ZDLwftCthKw608$6MweWq zu4S`aWv*jo4sHH1-j`-3K|{ou1KDzqP0J-!jP(Z>EM zzdMNO^v94~JNRYCltxe9@bYxB%g3)e^$~l`kJ8Uu)ShQXhbK;xhNKBba0a(JW36!9yjyG1(m24_{TuRd8P<>Z!cNi$r1LVVC?RlLA_yvn+? z`ufQkx7m4V-33b<3fnTBValOY1Xt8$MUUlQc8ae&1TfKg4NLZ*=;pb&3>ywm;>;E+ z>P}-cyUi9;bK1I73HnvpO=p%p4;(PG)g^LjdDaj}bUJg)+Ze@=VAOl-?|^?Q2BIvT zwNDDzwCpt#%uQj?sT#@rN~Jk`lWZ4@bA!`zIxknUaJWxlJJ^(Lkd)G%dAhc-zI#OJ zHlkKauan3;*roKTy@~%QMMunEVSoOkvUF`rzn>jeOZ%?MLLIF2e%XN@{yiJ+qO9J6 zwr~Q7_+;Mb*VPu}4vpo|JM`XEl!eV$SSileH)vWaHg20}WiA(BYdY$?*}8cMISCa9 z`Yq*Y90aF>e6FHw6VnK}f9qb}KY?3==!$go_$)id;uy;lsvDfIrH{DV>J>)UzGf7a zI}5H_u%JO+TOV-?dqYOqZ{=N=ZeO3>2fsP#Oby;oX>o8rB8vyO^h1Nk3d_08!L3pm z6VGk?mR7k1@aGyj9HtyVs7F8z_MJ<>-X+dmdlq<*n)j%pT=v<;08nI4@`&cDu2@1s zy?gm{ioJg>S@pt;vp?X9SM%~Kc3H4c{WAV?25oER9^$ta@TII%?wdjamwoap{ad&V z&Am3P(mkf^0&OlxiExNwI7WgrgoCNJ;8%D<@i1{C^2egS3kHb+%W^TMz0uL;qFk@8 zM#}peXJ4gA+YZC(cLBnm@I#jaqny?Rd1r3uXRkc&b8tfXTc7cHQSTC<&D{gJfH+xP3T2sQ?m|tKc;yLu9Lfd5D~;(!*%uFhXUQ=zx2D) zfA;y}ncpa!>xPu}UZ`zHEUQe1yVzRXhRWS=arN*!tQEG_w?x7RZEtkC>;)_WoI+YS z4o?riQy|(~VO>h1dEY2MnBczT#P|_|+LZY4#GtASt*Gj=kHp5HPRK}^;hLScT=_LG z`MnFcO&d*23s0Viri!9=dw0{+JyF#?@mKyYRh5HC49OO?_Weq%g4y7+EO2f|&MH~c zhHj@Ep_BCMYsM40lL);oGJc1o%HszBm!`T4-cFp1 z{kW%+A(JB#P0aQ2VB7+qU3)5XEQkK*RMA+D1AzK&+=2;d1>6Vc!O~GiNVT^HxMUJI z5eL^ZM6ns0h0)7VYWE>k{M8Y$fTQUc2G@nq+oET4rv(E|zS7$cDsvYLE4})02eA2S zfMJO3cgv`Gw7GVI)<(&>cD19mKeP*q$dw3(=n0L9j3}fubh2{n#f(D7qZJ+|aSJ|b z^d(gNvLr`d!KWr=kmtq{pR#KHz75bHkp=6!L9>^S;DQm$Rj{r9YvFn4+jmIEbg#+3%e?q7)~qVO$@U|uS|4WS1RPA}M!vr!8HceA}OYJEtWC3q6xqwml49@?}M zvS8}nBemq92@~BIF?L; z`?)5Mr8(^}jhTcA!&D;N?J9p-Q>n;fszfY&1gJ~S{~mD&H9;IvcoL3^c;n{+)9gdbb-+D&GhlbF=Ab zy?7K+X+)p;4sW?@#gA3Hhve&4>D#rkCmWOc{E*JbonW#$`p5$KA)Arg#iTMss-@*3 zNbd6-(Xlr#Qw&dK4G+S?hdkBwMwOlT$HIpYl*8vuIjFgqK^duOju2Qd(B{+&icB1fXTT%OmE?@dWC--k=*MOd+UrG{Lz33+x-4Q{+|+eDM!hnCMZ+4 z2W=m*_M5v-SJM`ikj-qeTk@X$9ok>$(tZJR(H1ZQdoats6aT)`(~HK`i^dM>k`f-) zeJA04C!CAM^ovgq17j4uAmi<$8h01!v8UP1CM7nHEgOvUyOuVI_honR%lQ~diXTQ2 zQ(O`;mJ(dHAM$bV1Gz*iY2ovMezVkz>@S{_prW${nWWNVV!8jclbf(&CbZ|Qck zZ%mQzGwM*q*1_Z)c*O<}1z&wxs4YE}k-MwLIu~ZWWcp8c@pJt=9m@NLE_Bojh^V*w znd%6f&Or0jL4R7WC1;r{URi75KYi)|WkbZ2-(T(zrm4~iC6W@ps_=(4vK$0F+D;iIv;571$=bhY}=$gmesSJtR+5urTkAGS`WgLAz zyw28%ZSi!=Gr?$$t#d;=V3%(_&3kLofjA8M*b&aPm>t+)ksg)2g;whx{U4#97Rzi5 zwe1JdY`Z!2@1LVB1w$+sa)j}c@a+)8hm~y?WV@#$UVAW+{%@Xazufx1qz6~!8>mP~ z@2~$&b>VSg<9qwrPFDpV)Mc~|Xl}pP!cAj%OXW*PXLmL})CmWCRo`S) zJ!Yt+<}y9NoVL%uzVIq{ToH-c!~Niz@xc|f$o|E2E1l}d_YZYZ3Z(AMoia2J{|bi? zu%GUr^+H6hmiFFSFD(9;F>|%EiOAsm#lmV)vy?5WzHZFHlByTyV0|lJH~m9Q0cNo@ zJU;Se#~iacNpVSjd_)q-eRj-oo0F7~P=0B+V>0o0uBj)omLp@vGY%Ny^poAtUjSVuC|J1d94moNU7m(_!+WWFa^iaKR#(ID zT}d5#?yhx`MCvw8E$`>v+Tyfj ze+Qn!8i#raZu7bPz;g_um5n24`iiwtC)t2XsrI)auj(ztC57Jg5Zr0d^FQ_GYvnwffo3@Uxe7o&_gE>=gUYU>DF!ZprPwt~UHz8W~-6YEXGGgU>(wjNgNS!m!c}oeTjM#FZP?z84c(f4-=r zgXts!^q)cXwbbUc>S{j?w`-aives0Xj3bs-CoZ$TpS06k{diWTySgID2K}e&RMNHG zG>Cx=`$?*RF}hJj$^k%&?J(HVSH#(Mx%u< z_5abiKbY1UQnWhc5ee!>pHU{nYIFav1*t|P2xK$V5uUu!ArDPJycT5acD@p|Zv$P= zNd7YzNEeX`B`{5=Jl#lS>Jxgm)yat$;psRWXqrxnRP_r*bBZpA-u#05Es9FXCzJkU z?8|-1x!ap~W+LxJ%cwE*^)#ILLwe;KJ}InPgiD?Ro~*Zz_JZ#F-ILV~bH6 zU$dsmjCZd~rw-H0Z{SaH^-a6-M{QwP4gU)+x!LdU-ufM%dC=ib?~GldWE}3^p~H!8 ze+9yyUvV(O(QZkQtHA$U587+;Wrsxr9B?W;J8TX^K#PH((w5A{^Mj-0>FH!tgVT4d zTllT!OK6*ay@<=9wySe3$D7sq^W)>;1;r2damJ>(nZsmjC{zKCAfX;qU*E1YuO8I< z*4uGtutx`tmlo#h2klSyPz+?q#w0VEz9u3*J9GNa=fL!Ro#6`7kMyT+li1J2v}_p7 zW^eJapNcO7A(w=Ee}iuK1Bcy{?3M%PZ$v=>cHvCurPJ<*N3)UCDCeT8B#k5_GXMOEj<{e;F0TH1R> zYEf(&oGgW=d#Xo}x3A7y6;&HlRBuU1s4jQ}SAEyZd}4F4QePsaeM* z4ev4`v9cWU27nA?dnp4jAxGh$2f{O7$&jM7VBA5D;wNe zdwx12)9|CVx0b<&l72{}rP2ao>DB6+(G8G;H2uHk)+}GPG9=#JL<8 z!Qr%R!~ldYP6^n0;PNig^C1jTY5NqgJ5&<3?GW32qwDduyX;Y}5KW*KtO|xPR!`WX zLtZx-)JTxwcuf_KNhkIMj+NbmcG|&J7!W$SQwoopYT8w{o+Zw$#*ASt@4k9Lhq3-5$j5nJ}MB{0bd8yZ7-}>QgjxZ zMWV$9b_=sh1?Cmj5^|YGP;${>bOQ47EGr2k5utJ}=K*T|uW)gMwZyR^`V%gH&wVwv zfdEMRiDLu!6@GB})a6nkaEQr?)sj3fm%^E8Ncv{Ui>ir$mG-<`cuTSMvp_|;8(=xK ziQr#cA6BnF>nIAC=uYf!kx6yGaBgE4GE*(M1S>oxM)q53uWcVa9N#i(U zz>f~jd;)zmPrHy-E&O6(J>~%4%sUkc1FHciaOI`Pdu)bHbn~G}UvF7e?oxQu_}9Z@ z<4w&NB1%)~SxL252Uw&vqhqJvRC`60nwZ7Y!|>tuGF?zuQuHNsG!_u9i4%s~0#~>F zB6>6;>NWN~b=f4SVTWY?g?Q~v(4;Qg5%ILfD1EDxROq24y2Avt%ZY?&IomMDMY^%` zR1Tkqr1>I^VKXh;#n#XQ*T@kr>FFuLurV{F1-FE$a~L=*7}h87hAE^vEQtGF>$L-I z!(Xha5l(e=@+Aoq82WXh6(vsVvDX97~V%tkx zQq=fqn?Nj7bII+I%t!8-+&*v+^K2W&nIrt{+F%@b3;%h`@fdqzIqDZlyIW1_%#UMU z%R}>dc-O(98(2)g2kjc^zg$lL@X*!bKBxe@w)}I`zemurJcX%zoRwfO7G-@ZRh#>Q z^{L?hRHY#!oUmZ+0WF`<`Z0Z=U)zo!OFJU)Ja&1WF#<2g^1U2|t}Gd#6eP9z+%1Xi zW~`+^a`y*gH?QMAt$UX2jHQ+@$UZU@DFa`-S6vY;f**=k1i*gE4<3Q zbGi-v=nW@UgX+7n>^iZg%g7I9c|EfBiqFtm$9+ArggvsFHB6a4t^^fBwnz-l)UMs9 z93MBWB|m+C2*GK9VJx~$p`jO`2C8)!Rm4Aw*;_sEFAp#?auj*<4g>o_=P8D-ks~8| z3z05B)Yy@4QJ8bK)cjgKeiD`X;Oa7TTrPB6_;Q?%`rt(>zL(Uu^2g%eJzjFaBE}!K z1eR)OpN4MxiYO~m{4kdIV=SRsNqg8o@a*L*($O=PI5C!RMrs;Y1CUOj;6-x)+AS?) zz^eiTKIk{8C^&`Nw!n=YhTYzXOp*GEDO?f}V=j5^$?*1w3n|xOkiz+w1*b8g-Vx1>7#zNhph8mzVodT5dzGS)weU`A#bBzM6Sp6 zp;%GINVmbti1SpGyg9(@G13n~Ds&3!+zDZaQvjn+o#&M`_m%bO*)#%wG_>o|N(rgp z4Xof*dcbGX7e#>~r=tCJmsaQED?j=`UIhvhRNqAR_49zmpc}+Bwr!L=OM;w+o9x9t zjZ0trT4+Vae?B=Z4!PTL^$h#rpS?oAg~-d zE*6ni*Zw`AIS_r(S4cqc@FsF$*hx~f9VJav9V9r!5ac!PO#0-Xv_(-&}+1^7O4&Kgs(oeeDFb|KbFkp#mGBnT;QaL~8q!q8qmwL7Q z{28sd=UutXD@52BKkKpYr7&4n4)#=2!?x3!+rafEr0n@FF5nO^)Wd|q{Adl^Ahi>V zb2*Z1s*0-DgU_Uug1fLhITwrD!wH>Zbj5Xer5ZDVPXm%oRMS-e8urwPlaCDrAQ4gJY_69b}umYBO~;>Cu*%-pitv-YHO?u)bLfcPiv<6{tv^X35j16MTHy8LOp zV#FmtCGk&Qt4|O7^JP>7k3V78|N8o^tK_pvh$vlcz>lDbdx3B1G}R#5eJ8p$Tw?`q zDsgsBV|}eqlUavb7{czZvRUEV2*?(GR}&Fkhru(88ezLQL9Zqk6vZc09aL#R&%YWQ z`7~Nyp(IvaZuO-QmxR4kHo_`B8h8ZkjE;UHLbunFX8Ib^RU5qnz2J zJbbnR_H;}`UpHd5&DEovAE`m?f76-Z-J(Yu`JOzHt&FMwE-+#4Z)Hb}_d|6{m_BKwIGTjXOmgp90TRFc`_ zrEDJ<6EuVTJEHU8}5SbK((Ea%7-4GO5~^R?Uqjsanu%@Q_>0 zjb1IkykxE-kr_h5{Ta~oE;wclEVB178)VF8-9|-XDSf*ReR(p9Tkf~%+c95J@AaZC z{}GzYWkC@BuY2F#CgNA5PIiTeK*qA%*p%usTYYG&-(^Dj?%yx+a8CI?GGVPfAkE`6 zm(Yc2=m71z0GOSH^<1a&LUJ4Nx!f*_B*Pp~#&oAz;JVO-@F#UIR#=JvNLIr+gLL|-u(=mI-;4>8G9DTw zwg$dO=!U|5JJ!J0jVhz}t`g%2ng z!U(X3-q zbOyt`jizR~yY$j!M$o*?1;GK7H6mT5(GSpZ24kbh?@ty1pWC@tl}GoPO`ZB1Gg`$4 z=j>k>o@KFUGIZtRzgu)Bts|#YpJa6~K*8ra^#7t-;NO`(7mfxHbs(JyPG~6GZU1nG z!?2n+$U*j6asZ?Nbk z!K|u3`({VN^UA!`S=F!XK}deykw9MAYs!i7)<}+_z7Y^LA6KLRnqgROwXB(}Og{fK zLatepUZP!<9A7e5nSAhRgjlmC4GAMl=0sLwOCjVgc&5~pr&d7=oD@VgDp7NlPUaQck`u~$=>&b=dGHphEhsnfq8 zCm>e;PN*i(!yC~ZH7^7`THA6_&1{HsC2n3V8=N3~?n|<%)VYDtrt>*VV_p{X^&5de zoF6l$DVl;c%IrBPF9+V;I{qP^=|?ZTlff=`o5yODU+FmXEQrr@4ec6>d!)E zKi-^tkICYDXd!b;33E4^LQ^5~7X;pJ3TT-d@yLA|Is5p?OU&TTi^7RlXWO>6-6H4Q zly?R`{529eVI&lrkNXMdc? zTxrQoY9;h>sH?E*{#~b>tjz%M8I?g+>>kZcvi#NxQ z>5)5TuW1+-(ROQ^%#W6rhsyZOm$%*8P4h;2Bgt%uEe7U2hL3ODGnm;+y}v_zLnd`! zQ+vunpZ-Alen+PKA2OyLa?obw?J&PgQSbieLUDfi z=|V|DCp`C{%^0CI;6$cpyiXtA?ggCw*~2E3#lXz_D!wb3^_WmrG7Fn<5Ce1btN8T; zl%%cDOa7GfJ3dJ-DJ-5$FR3%0>=RNTDMI(quuz_qWT>p2LpJVPvrL&{|!~4RH;g2Sr9onDb-qPOG-Pp7~V(QCl!9oU-&rG0_cBD_3Zrt`;C-628ZSo?-kRH)tOt* z^?1LxTn3i>4E<-T{2Csa)ur)m!WlMW9tQo_ zR@88&Pg9cLlPy&U*!HBpdrf2;R2Et%(dpF|J|*Uv$PPzl8U;xyOk~?jF`~aU5@SGD zHxWZa3I-&lM}KRA5R%`U>Ein0kI%oQTK|wI1X+VjKTB@3j9b??ay{pT&R+~RrryZt z>XAVQ-Lt}8VALC#4YMsFo`DDX{|gRC=i1XuXm@7v-RSJ@<2ehAO31U<3Wlt1v~g-( zSQ(21dg(5?&BZ_lJ)>W5jLBTm(Gf9Tu1xFSzr)CsVfw&J$$zekclmhDx-?1eYS)xR zit2d&7i+ZuUIuHmVBSrM6zB1LA0+&2t#%(C$wT)+iROI2_Hb5a&p5l)L_jQ}5!=xDy&g zVE;`wWJ_3d*XZv~0aS;qL~~-kbVfN~?#l2Nc6t0H&bJ0xvj|JHw}_anD{5B5+prl| zeJ;!AS=ax9wm}VlR?9r9hka#>Y9XS&hgL0=ILqM(r=eR{rCMI!`$$u0EdTExVsqkx zwtEe60C|3xQTW}=tj+fll5e&YS4#22Rjt}yb_VA`$p8^yD7h~l7339Eq)*{pYhOBN zEtw0LCckiBT>2xcMfZUrK>fuB+5kej4=6}Mi=+$zq3`$Y`2(KdyGS0zhOW@tJ*M$> z2+ik{dVEC-2&R=s0-KtgOBfaA4l2DNQDdBRYng^c}k}!=lXIg-= zEVRaJAX7D1UT!L5K48mK`qLUIaakFKOI(aITjeqIb6c@7f%8(eF@ZCrKvINGd8{wX zg8sz^rhvzT|1s>Dmmd4J+qWAOrV0*mF}_?`zTVd-bHTtoeCgXPBBWohuLk&>2u#d) z`A&61g>BGvP#XRMr9LXOvK)^vi^ZC6xh5x;NEsQKiOak@PlVJ!elZ z>GI~moRiznr50^^+RztEdfH?cOFEDONo{(BIYZ^aQPwAXUtFdh1&^S1n|D-tn#?{9 zRxnCjGFoLfNz_+0UZf)3LRzhc6m#9zP!w0|+7IF_gcF{6lG{#pU#Qy)cAim8%(dun zqohsxk1}W0K$-tJcU{dw34Sdl1nr~meA4iJ(wuGtP}@f{E4Wu65#1oNP7qlE5@X*8 zn05)w&`2I3eC)%tj*OU|iOE8y&%V_{KzRr>$rJqpHY#iQ`RpxF6P^7p-?ur*5Uyl16{h|MeJ9!SpP=GsZlOXu2&>D2W+ zj;%+v5=2bZn7K-F_?qToiVStH7ZgA02IwaTis%{EvF^w1iyVVav;c)yb<}6&@1b3~ z%&dddI|MR&I<_ucmBDwPx~XR>Gi+w7g41l?RR*tr>c*dOOhv*#n|CIy;}UVL+qd_#=*mK+vWkpP>*`PjJ}tNDM!3+U8#jObOwh%w65vR9`B96uB_Gy- zx&P8|ZAy|Gcej0UUS7cxTV+a+n;JIDqVT>sF8yS(pY{j=s=%8}D$?;s=(Pl>Tf+DV17F47lKv0CP=fyQ&E{l~O3KpGW z?jctLeA;0^52sN3Ych|KBiiP%vzLk7O=Rr*01)`PMCvYSI^y|a*MO{Iy1wpBtNT^< z!UWVUD^DBTD+oZgn4T*%30CExZrM2h2Y!OwAOLUN?yww*=~BmOrzlkpRz|_oxIs zZzNDpv;6rjjYN=;n`a#IExn9PX`3e5I2lHfSf^MY=6$I6qz+7*SX6k_Y3#ikKvmSfIfJrhxWPO9B7(dummel?V%?Tf{;^z!o(74*;7 zJ(RR&t`e^etAnp&Cp0`tvi0N>s#VB6S)sD1qrwuZBW>0K&p&^?-`+!*3yAC#%nwgH z1#`k9Pr>itI7op&oJbu%{4No0aSAUO{dU!->n6Ys!9REPu-pB0$TH^TyMzdhfLMF@ zS{O*bA4i^PJ}Lb7C6~g8_Wd`N`AZxILli>Oy{{yGX!_nfOaW3?o%x~sJ4%(2R-o+4RGfrUC8 zJ_GL%@#Cr5_we!AU7=C}ma%PcT?q=#oVPoK2rO?y{z7ZzLQEzvi29B-POBtzL zC6A43@PYrBbo&L%FR^Qq_xDyfw#J`dbsp%|kRK#ToxdJ|@+!kwb^`Bo*4@9NM3Rn& zqTrA!hoQuiD*Gcv7=j{n4-MBuPtWjFGjtKTeyRyW8NoU%3)vMv?^KGUrhcl;)JYrm z>*mMpS%;Mp1E>(gd*u2E2-i?QvMsVezr>~2Jz<**erzGwZO>{~#uy?;XL>k$P6PDJ zGE1}M%TBY@(z3azOSYc-Q3xUb`a4-u?XR)OXL)m#=}$(USmd8Xo|uIcMgN;7kze^( z`MAA?czA;9qJ zxxuA?d`iIf9sUAMvBg;bg+9#84;FRwPQ?YBN9|nBck_+==h477wD*tpRt@p4KzBzK z-bWSZA_aoKsqX8V_X^+LLY%HZ^j9FS$v)ACR8y!gv%@#7cbA9R_S#;T)9LKzW80$T z5rEg+CCEvZKa#tIyxqdJQg`{7(-6^yYxS0LdH_9lf-DZz_rv-qJlWo$ zQjoDg2=y7~*ZT>_+9z|->xbGXv;Q@_X6rIFyJjLq_QHS7IN2$rW*4UYDkWutlUj0l z3GTz6tm=E<5oD~wjBEN91D_5OIJ3$%Lp?(xrtkmORb)lcW5BXt#1$vGnGxM;`{f_5>j|YP4QBj-$#ICF7zx+u*jC1bTOE)@(MKjGM%d-8 zcA++EI`PV``&h+ehgg7DX2gJQ`l=w6UP$SAe7o}qH>VOP%hB(r=@o}r83s%sB`Vhgk%c(g;C{nt$=X&5-HL z-T20;zLW7(8X3*6#wect##7tT?qkF+G(=)pFmeZ(R6oDaU{ob~p}`+h{5aQHbhyF@ zRh5WN14R`Oj#Z(YvfFHzOzp$xFqg2pnfF%ChvUlL;G1a_6@V{(qnxvZ0Ry`wvM<(b z0n0Cv6wojL4KwDIt>AoGt%5rzcGmgn9XIi4Xb`vQ>hPy`^u(hPNEq>;MM7i4OH6+D zkko`11)Fh`kNDZ+CNcTTLQ-d56r4Z6xJj=gxSp{0Tlf^2x-}|OWr25=>bXhYUa#yl zR(vrDs|JT=u|c7F+ovM0D%ErGhlcO*#UPa;op8uFP0Qve#$CcAAcMrVTt4_m&ZzfL zYBY8lAK?$MYUb%^rXKYTJDIOmJ~)2Y{qvQ6(gR#||9pdl!4KLS{ibw;k3IZkbCuq^ z(cFVqGReHpBK^bDIg02pA+*5#$Pl;Cu_=LSKH`9-&@p79M~0nmrym-8a|QVLe(1L! z3Owjm>&OuA-ev`ujzqtKGRDW>@*0L=K*ugsr?3qSCN{V&?w3d=Hg`E%@l-#U{sFDQ zJL4uqUWbrzQ(HNojjH&e@w6}CvJ>KPwL;@)fBR%qIL+_Z$mLz_rwm8>Zi3CXs=1sr zYq&e8iiA%*x!I%y*rYHMx_Iug^9`rYu#$aMCONFV0`i%xy|R(w_fZxXpb-1%r<+3& z^?=85k~A!xA+j<5L9OjogYn{NQARTtDFEe3nDR6dA-JItjsIT@mAkYM6;Apn zd~#xc_ml%Bw5qgYPT2Z~ZbR@c48>1ef1Q=R#r2AS`-;Gq8`HpQ4*O3=Vw84tU&g`M zExt0buWXQ6yhOEZOsTW1roS1HtY(nev_!RaOsN+VYRD$Ys3RO4BeU2abep^F?>`!v zl-0qqCP|O&^7^C6V5`k}*L*&K2&du8V`i{pmoCkkNU8Q(GDEp`_BFd;eQla=K)Uy)+>ex_9Ngn6&f(GHt03!#Ou$>TKXG6 zM{#yFH{h8l40_0Yf3NrTVIPS$Qc0hzzrF!e>%;o_rL&Hov|DAIXtX!_PU(h9P2xdJR6Ot@ios3A+tl+&9 zwVK49f4f|_JITCJ!RKVV2u0fa(`Z*sG;H?9qLst^)xb3<2XSTYoNFkEUa|Kk1VITWSY@#`A*c5cq&U)u4PZ>8Q>R$WX#^`MOao@ae& z#%G@^FQ1_t=z(RD99`^J{Zi&fXA^SQ&hk}57hf=>Y*}EmL4Y6xxFnsrxWGUL>hjn{|9wWcVmNKH? zk%M(b%Zme&jRhQO-Z^RgtUtv?uu5{UdDkM~y^mO`5lOIy>!Owfqi8RN2Gm%O5$ATN zaC>L6eqU?xqeXjGgR#uh4r|brxp)z@?+>>4<__l#9H#aNauQJ4ws^Jy>yo>sGGb(*^#^bi9JD0I6;pI{XB$9aey`2)_{4>4$fF`PV}P0n7~7xtF*g%Zzu@i!4UK zwfVP23W$TVvJm2%E?Q68Eka#M7DuO=A}ipy79pfRsR=1;%*a~vO((h}AiDhdAW#37 zYLc~J&>wv@Zu~rh!_|jJIs6WX;ccjUp9kKL{}5e}1mQ z`0VpD6?FX1{~^UQBt__u4bFv9L+cQ0;_|H=(EhOw%yons`m->(DCefw%8MQztUQV= z-8=CMgs0qsWBq6|G`GTU9nk9vF%WrmS|^6T{cvvKVLh>MWTuDQieE!5zW6=sRmBD( z0ov=t&&0d`zV!FBPeUEOS$Cboad9x^H9^1`duQH#++(H;CY>oT`5fBQSN=cf^S;?; z=FIp>U9*M=kMsjJYoJPq&4$45Ae1&p$ntrn``uIvZX0B(1*MH5WH~a^ef-g;V|d3HlR`IqGkR;Bbsv(ZxNlh~j3a9BR(< zC!FW+O!xc~brAJk_-bSH`RTOz=@#fAtHX$qxG>x_lDZJlq>#GM)1;7y6iABD zJv2ZC)B~j3@7-!y$IHbJSf4pgtnd=#?~Uz(M`V241+E>1|wa4+iZ*>5tCU04Gdw`4$O|vOo=u1ZeYE2 z!Deba38-G`s|103+n;KqxuV$YeX!Gq{aC{Ya$1!8a5tYh5v%8f} zVEFsan~F%>Q-Sf$2bYI48SnL+F#&cCkS}&kV;uXd-f*{;6YwK3#2fwB2xWuMfl-p*iGwNckNx ziu1Dh_@#nE6==QyCQXXDu@T=Zvr>h!o0^F4RS3$qA&Ln<09N=;Dy(G|#hR|i{NX+) z8J&LUaDk){idXKS>T595sUzy9`Lo;83yPmj!xX%lQ^luDGtS4#*^i8x7)TkpxN86nB_5*Sr)z3{7US3%gqb)7l#*@n-(uqf;$5 zpyG0f+@1wS-BL`veyohBZrH`Bi}S55ck5V1RKMN4|L4xG)JG<9aQCO?H+<=(b573Z z@D-$YPBt*ADCaC_LbxJa&dGlyD72*&T@cmINt3y@rfG(JALUD~nN{`50wjy&a|b1hv5^9S#Qtx}q$(v0 z8K1vlABzbT0lo!PxCp*6va$1VaM4}s)*9&4a@3u+Dmhxt=fmghG|E;vxgsjYRWG zp!A5Sw6eHuDbAp>i=@mkfJiZfNU;;MWZpZ)_tUB*>;CjI-Zo94_A2X_p4Vwr-=pTo zgsZ7qc4F=$=ugXWs=n(`CUyOcnw6qyTOVjelq1`y)e=StxHUvgOr1b5D$Rr6bWMiy z)IfY&Z6a;9*in1KdAQ{X(s@e}`>n4;X4s}G%Xv<9qpTx%OY>shgI?&0RUO(LQ&82} zS@#53b|(|tdB|;HP6RvU#%f4XjAk-!hVn{_iKUWEEbsRiR4*!lXLt&*(n}nkr0B|x z)pfXNKxXB5w`;pxrV*i*?dEF$jW(RwHsk0Olki|zy!I@Vdb4A2<9)PqM-JsDGN`rU z`ZpQ=Dz4GY)Cv0h!lQDQHr6nQd4ZZX)~CMV0_*x%t*mvpX}{lFoD^}B3H&VLKGc_@ z!L0K?Re_szI`L=QCTH6?ZvYyp7%KrA*8?Y;xpBgNL_3>#jgUK3!2hUGqQV{|Qch6fhcd?X7JJ zZI1-TK|RT?@p`_7S?_o75_;u%yg#F?QtQl4H5z~D)SQ1X!YXu3pF=SK%z@24@a>#V z9O}8IrgszSxRx1%va0Bm5Y8~wO+->z`mhu@(Tv)|llmW5_C#T^#nqL9*M(ZEgB#Cc z9=|2U-&I|D_w8O>q5enn1-&5kYVjfIr&%{4=AxTYBkxb}9C~vvF=PZN_S11TE;QQaG&R}{vdJP4u<=T8Hv{K`luPuk&H>Ma7JV9O><|CLVIW_#dfg0-D7 zc&F3cmCjHd`1#R)l5zD5t_W|Vm$GtWh->dvKs-8T_;bEX&!-k%zwz`3iZ1G^zb7{M zshtS#O2M59I(Cg*28Yi=p_gFME3xU+*mcTm+cY-q>pOOZ{^N*Rf?ZMEykS?I8eE|X zQD%P-S1x;f_Cs~#-`}?m##z`M^nGtuk(>B<$az0^!$97}$g6a`K)bU@(xzqMD>vOVzKU=~dA5t#9}+GJOr1xQj|TM5mslSNV@a zL(>;GH?Ahn<`wu!B351D8dI9fO{%*_u zZRdzZ33)81#9=IL$G%(KrA3#YY?GZV&qJB#uEe)n?7b)XI+Sz=Nq&edKfxWO6s6oU zi+RCMgiYC_xkD=)63heAO+|aY6;OyH4^ZnZnkGzhx*pKEa0`;T4 z2^|Mh9!MMZgAEN#d2?dFYAajYnyHYK_BJMT^&_qWluomV{|w0gcW}DODt((uxiy2m zU39C)Yf=N2QCT{rI;K-H#X6?LZBhf8VO9DM7EQ5=$D5yjbh>d6&G?85ypjPY&gH_Z zpWntL$$iq_<@Z_2kdU-{qv`$W@@yRpn1fAm%S~(9@c{q!G12?bUMck9V!yJ>52S=K z>}~Xuj9F*rR%e%Mk&@71xNW=2ZmP9Z=%dW!La@MGpc#HLpZhP}XH@Ub)$j*YwqC+CN58wk+#2)Rr717g&uWUb zPN;VsxObgEpQj`hb}=$!onLv>7f!qvPOwjF;;s%R=;E%p#9mzA|M`o{;7TfBj^Iiv zV}|@^eoz7P&ssV2>mN)_s^`Er@?Ox+Zr><0Z%1AH!?-!HybZhDJ9F#Zq{_;g)j;{0 z^P&%~nw_NgX=UF8bZ^HWO$#D%hFuE^QhIq~5c$Ez*E<$49$1&=Bav7EN)MMDLh+q7 z@Bex!o8@SAa*!Ww|F=cOLao@iG@mLFV3vhD|6%^ib>fdTs|`D;aAS9+O?qFyf6N8ebY5}Qg5us`^L*RqG@@j9+aGki+OM{`w zCzd)mcK1)Hz%=$}x9ku@6Ox$vcnnHRjiUi*`^eb&VN-b+yV-JS(5|-MPF-y*=NhV4 zSNB$|x)rXs8?;wfvjCT-&rW@1KSryy^cv#JnbW7*3^KQ3vOEWiy|aY*z(^jS@reHO zbHJe9ypR7U`akcgZ3X!w1^YuTab2JPH<4lhy*lqF3S7jp7wrn=wuGB}<5_K-B$}HZ zGq6UH9TT`VmK`&-HkSU+{G0x){WwOggJDz$Xm8@gb4u^^cXTZ_;l`;18zv|I!5_0F2?wE+Z_czCW#$?WsmsdKkZebkLOTs6|j3 z;;2Pf`WU}}bI>xfy?&>Cf1`i-p~q}9Sbad5nXYEYa3@)q zGhN6O=14X%L%NDp6I0v#CK;SDS;u4?t8#vCGJ7rc4#E)=t3B=&ACKRO{@-U{XiXwJ zCitHj`rjwygS}(i#rJK@a+Q~`+>`SU z#wcAk-qL@6GkpL2rt*?%|2Ex!Y8U(b$i6c^%y06>f53mL8OQuy8NYg^mm9^OdcQxe zzk#^I@;jkSZB3k<9Zd~w{vkUfODHB54gv;(A4I^z14S=mYHRNNi-3uVk%8bpA1Hb; z3u|XnM*?~=YeQ#K5mRG36H_QYKB)it7WefOjJ3r5mRp}*A&;U7;?U=Ww8e{9bMFfd z%34d^a%(&Sq{R3F2vmV9_m9U@F?I^eX-#f=phfbIIdqI_xXNFTH)MN{mrv9B*9+dL zqlP)h!hn^W2>@K#OSuR5B7qap1_^T48dVe^JMbt5gT;*{+ z;SJs;`gA_*f??{8XYyu-E4^oNOe2b9Y}LyeV{cUyPh0RQ%~Jma3uF<+b4G4Y;wk=C zP?|6PG2dimNL5q==L*k56vx!LcdkRSd|$w;b7MY5^&rQ@7e(HYCeGkzDkK^-LblP6 z47p?HEQad<#T-0{JD=2Gsl;{oX%%G(0vV6ebrlOrEv+B}6)q$#A61Ul(FnG~DXzGO zhQOY_=nBdx=}5h_9r-rWFAgkTyx51)T+#i&aw(v4ftp)yzAtGw4-L)Vv-U&j+m(i7 zfLb~-X`rN7eX$6K@stY56w0>gC?{wQ2Q*Xpnf1schkAP8kqwpMbSu$2ITtK%-x*N& z2qZhfxfCUJ6Zh97{UX#eCb$5)U?_-$yWb~o!NiR+4kkUgD77&c8H#z}E=s+eX@K*n zL;%8sTyz=46i+t9UJxjs$4nIaFdgc>6Rrypz~p}C+?0Gxisv7k=H8)0g4}j2c37Qkb19{KqxqnL9Bbni< z_X|G$>@e9zD8*@9C`0_c_A;|?MptN*x-`8six3oM;h*0Y$6dkVZE;WQlr!*2CLsI^2$>yWq8P!N@C5ZZ83TAY3al&?-x2gulEF)kLJ8j}g7nR#fadAI`SZ@AlwREq*kS$Gz8UP>ZatxTc4 zY7P<-CCI%OyZ|U*PvkXy28`0e2Wa4B{|EzBg_T|thBYyfKhI;mR%Lk=Pytm*^sbCI zHb9g^QM%6?d5?)vXBl!4$^zTi(cwBsFFwv378oD{l`F;3f3^`vB>D%E`;YB4*^K!c z^Ryu-IQz|1;v{4bmSrTR&wLq(C`_=S5Kle9*iJ|fmZ)K>Y`42!lmDR=9*}-2y4ZCL z)SI)d)JhUR`yF$Hg6!exp<}t;8Bnl5y@)tAMUmwM>4OiMko79_s1SX z&>7!gulJl9(syJIdlmgDziy0DQw&`&SG5D6LEK`y5^MV3@$892(UbI^-6LyF&rYal z)+cEXV2;EazHIi>W*m55_6$SJMj zF0YbpbS_hZ9`>zsrmQx*PJNzVe)Y~@SCsViqqJFK{^`=0D!Q3ChP3un$1+$Dr2U-% zD6u&OAmB~}TY>*LX01;8YR7S^a|TnVSR{IzV+zT=Jg7V>^8`8aG5idVsn?Gz(cO|7I5YiS7q|9dhS@=<*JK4^wXqDt-)X1P{-0HHDIy=<_9!&!jHEhSfrti-`9Eb?$%knK z{>L<7R;f-RfH}Qn*+hkwP;oT-HvsFJ$IqsK>}d%wUuC}V)m3&HlriAUw-2)(^D~JI z&cy(^3*h%Bn6|`9)!P&xYKo;5FZ>xffy0a1TAwHUQ(KL)9iCNep(=@ zt0*d)ms9RR*gLtTP+|(pyS_1jxR{2SI*8C}%DMm)DB}v0y^nzOaodOmcA?_x?8C~2 zU&oF-qU5_n--a+_8ryP5vJ3TKd*O)2?H&BV%uh+^g&gP*LH)yt`C83K7q)i*IkgKT zH9N}MBi)pM8$K~l^wNVI{kFn2B69_w#T{Z8wu+z3%~^~0GgJ)8|n zTs`>sELVezS$CxcB)EzI7Ta9W#h`*?4gx+F2KOf1rVbjYpQc0sV}iLB;o*%t=*0@U zrNNcS9tU8bB}^MF6Z}3qsVA#quR?u$<982UDO z?6Y{69k;Mh4FR74Z=Ke}_EG3KHrJ3iiiL{_}E#I&ZckzoA0OJV(gP#GnW* zppL|#%mivmO4@}aB88g76n=zL6Mh$jh*|16TGpFchokGTD^%78mgJUXBw$LE7L)|! zhLo2C)|9s=+SabBYF9{?~kR1`EcL?nWPL&liEeQV7LAB2f~2qoNM`i?3H3=ULeXH#W3 z3oVQC2fli51NJWj$Pb25P!iL?ARwZl`D8~7NCqqm^f8PD&=u_S0l_(w9V!UCfe{$U z)>UAC|M-O13B3XEpPx_s=-mXA!c!oD0SX0n?x#R68=a0tsN?R#01OaR1pJ2T_n8F^ zxl2Ywy1Tze2Jv!-CW@cA zg#i1$gb5Wuz{@po2Y|VPu@7t)27Ei?3Z(Eu;Rk?m`w#``^dh$X=)o{E-`91kGS4WQr` z9`&adRtAXYM;Ld9{yrwupox3{dB>R;7z@TJaO(r1pu4|E0RZY07*_1tZfBdChyY;+ zA}AjKPQe@_`-FeaZc3rFcbWZBeBc9cd4T;A90cO~?c*M#mM)7;h_;Co9D-eKX70>HE1+qRg74u<1B=*M?%;5OZN>(Mvr z;rH72w-1pEzT5LQ$FqL$H!!$Y-v;m(gDuuNxC=8*M|c)uz&HC6&fAK}xe%@)AKrJ2 zWkDaia3P4B>o<7E?E~h3>>R~`=IY8Cjel6-Ho3iyD_*! zXS;frUBx4I;Fio%Z>vg>FhXqah`fjn5P%p_KcEQvaIa%1X0(OeCw5+>c zhFib7?bvUil43xiT#4W!c#uPg`zL2`@DFe#FbI!#clVDTKSc$9 zPJBD0+vm6EZs3qNVM3AnMu>3hn7Iy(H4FdZx1|Y!{@$Vj-RA+8z7fEe;aU1egl#T zi2))H$K*@b5;WSgU$9MGz2k`L@hO>rk*e^2ys>^{fmQJJL}ci)Zq7zRu=bL2?Lp6ec+5dF{*Iw# za`q!+i)6(79psNNiawrkCsTN49=1kaUr+a{UwpkzVr8WsZhd>I69Z{Z69cH(EU zbd;GR{k}Q7sbt^%%?MyFsTY2=5>&~Qq__DH9rza{j}>o9&VFF7_-KBQTrk^Jh;Yaz z9WMp8?Fj$pJvXYcNonOHOUzN@DOuyMO=orR@;k=QKkW#M5h-_`aL;kFt5WUCxdP(u zQO$q_Vwm#stMHsS+=aE{lL2B$y4X6zG&NFpCTwT!jiW_c0o$xad2ApX({$}oL!=fx z%=8qCC)ZqLq?yvOes>OjqI^sWUr%Dkw5QjeNgh2w_&u+wboV;x>B$v$Ox=s~kaX6M zM%FJnuXFw1-5<}&WcUp`GfiAGv>CU!oNj+$?yvSGgQxC~r|bWkTEZh+8RAnvRVk-f zH*V?WCXT>rnnQ1DsWW3G`S|>5N}Q8OuIA1Z;m9>ZuSt zx~p<&wA1}Wsc@k~Fy9CsRAG=u8V1sTzaxXtg)@wBg1V7KL;mURvkCZmHcEv?3F4N8tFR={bX+!Ya4U`?&&S1`|4VCiSMo6{0s5zPt6V z8))%uq&44m8F>5b-PdD|LDH6YvR$XNJtOLnR<4NJnYL2mWHcmJwg#8C7-YfTxI)-5 zK|4d2BsF`yZh2Ya^z5Q@ zM#40o&AN8&NpsrN-`+z}{poA6JEUkt)S8RV_n!W^HZ}gHAD^VhUUO3u<0ZmYIgj0q zXA8jEbk6f3fN^VCNAX6cUpo19sNv%WJRV}A!B|w(r7v=hkY9~@ffV5dHzuJT0s1jS zU1f*nAlqZov2VoOOs4ae89TCK;}VyS3p6wGv~H?f4CkFq9VpfSR_p;9|DX! zAU7lWB{w;W_$X<2&t#||sh9bA_aSH**KkibDj1K5K95yXq^18h6xTpm1QYYob9I^q z#tRJx$Wt43(}W-|JwNB8N8BihO3AzQauc@pDX=2ind%U;s2=gc^9N-kl7rRrRbA9$ zB;qRhYb6}sgE5iGqM0Io#$1OY(gjof8lwv*K`*^DD0w@TlqzV3PEEd1`@NG*J;#Re zZy(kYzV?O@hYUsCPm7x!l)Q}Ly2mqQ@Gns^_!}NOZ6Kew^kC-}RUzPC#TTaHIwlI; zy!T_;pqA?*$=3yMW)a&P97@6F_JI+kxgKi2WDQWYw_6o)y!;Er83`UNjDlGJ7H9Yz zVqSgk9@h|m`$@oH?Nd|l{<7G);iZm77KtR7FqBv;|9lECJa?4nm#~ur9#x4^)QN|U zV3NsFkJ~3O35%%0vSA-SWzgRV?iy_i9g1x80>3axezGt7K5m2;fpi}R-JAy?GIC8# zMzVYZT7$m0synL90+fY6 zJ%YT_BQEFLv=U=HAnT)H==TxzvMaw8fx6aZGc6Gg<2w=wju|estQM6|w@VS;`Rdl)Pwb5~Igkc7pb*;Q`p{SYhSi2k=CU(7Ca*VOb zfYWI-^Py)N>)+G&QD%n8C(Q%|%SDg9hKqm7>H7=Qr$m7mQ*k{XC)uYy=h4NJW1v=e zeDt`PXWc{qm1NDgo7sD(ts%Lm!I=n8l6px4|JTIfpk=OvRRx?el0mC@DFoDhO8l zN$1{I_;1p1zQ)(DUoxBkd*V+N@oah4_Cu%wa5fem&vN(OLhF5Krp$)FEyx5Rnva*U zn;}NDv#jKQfmm$_g*D+V(+Uq|Ur*b17i+(lb#3~ZH5)I)l*kO~;L=_pCB#|Bv=8U2 zX`zVj|B`0iQD4gPXN9-&xB{d|80JSLEHGEbSS15m`^!4d*9`P$UmBCac-=Y%|DAVY zAJRNJ`6!;QFrRzEC7LM}BFC&wLJcBTa!;G~4`xeM*Y`4;0HQlvgX9R%>aMF`7GI|i zBcRX7j$-#{E!{!eQ#hqzW`wNrU5ijHwPdcQ{g6c}#9SzMf^TCdaBD}&VmjFHtbB}@ z5o{oEv4SxZP_%jegjdY$d^s-4oL%T-vIYZa%)Ufe&Os7Ft(=S0&ttYB1g+QE`~gU6x&b6Dyz7CuOnOzIcEuA9M{o)#l4vK)33_Pq8>}qvY?#lNz(QRjDtp8p*O2 z#B!e{p*C&4?fWy*&=gWfsFnN_wsFv*J84;7U>^F37naEP8Dw`O#o`GRLy zIYzB5{5?aBjgz5`<7$U8?kk4=MjI2#hIx8@bb>t$`mlQ<$L!sb)9NYVY@?H{nT_FA zHkfh@(JikoC|WD*D)MrRz)rvr0^l?huI{ynGf9Fa?Ap4XT5Jhvs^d>{*bd5RG2y%r zq;ZN?ukhGQn$Y8s6+PEW0-v^IK94tn@)t3?zuJ3~Uc&%Wy_&zAB{+Oz-nUFebLG~3 zB(!D0NT;<+BfH7M$2d4YGR)_nicH+ED|M}%Yb$LE`$kC8Si4~G1d8lbsfv1CS*r~) z6BSXl5|&A^C@Nz?YE=^URX|E1*AkAPXynV#90_ylna*l49Z6$Z&Z6_E_=r5X$j2opa82x|hYp02xDy@vHg9rbwRK`6W)dnqm2adf`dP zjd4+h^wP>c66m0uU6n z_q-(|m*t7BKVFcP#5@`hE?g?5aatL;Cx1Vhqq%wY!BE?r9U}joz2{!t;6kk)5^$LF zP~TqdGfoSp9LbOBQYLjN8jz3|CCegcE3SgK?aF@lCWUWTXl{=_lZje6 zjXez;&cspdOQrV-C!Ow_W18MHx2-2>)3c*!>q)Jf;bU%49Vpb)@(35X!g3afe7GBW z6;$>{CE!48KrsrEHHPWf4L#_UD4|Qc`3SQBw7s;=P}=1;+@=Q`L9>*;-A6tjC@%X@ zV*|=(N5d)gYP_eTcc9-9MyrZ9f&F3h2xG%_X)-=vfx*`$a2P{N7Z{ukkaoJebDndY z)E_s5g-?1b4QHd_T#A)|;2v-)%s9PKvtaUA#K)Db++~9R+mTx6dcbstfwf*mWM3r{ z(1nwRAr5b4D-^z}%kkmN0e020R=_F_jnwY*jfl@0RLvvCL?0pvPLu1|n;5%Ts=b2n zv=o@wbIbiC+T?aRAM+sBl#6_o&mH6v9;9nsxmsxKV0BZk$PDTlLVsX2@-wvDSO;`p zM`xi~(M|HS;*puZ;wH9cV)L5C&DI7K&BFMuU7iuN{M|TE#2JW1ZZ`xMB^3AmIbk)& z(ay3^SgZWZ=y+KNNSu*~Tj{!e7|*=VPUs+l$eZ}`BEeUTIkZf$b<3J&=HN#&4KaFR z6@HG)SY8`k%sn&uS;p5b0|_q@lcRv%fUWIJZwTkY*JE|T(p+RgS_RU77}t> zBu-VuMbQ0LRaa}4@oVA+_fyV`wm$`h!@*R~ZS5|32&_^;V>t2sn?fDf8Y*RQNm9c$CPseH0j$tl(5u2d3%b{&Kc9TR(7aMVpo?IRfR1goZEjK0_=3O zE6xsP;2f`DYG)rY*&#l~fJ~LIEv|X%>qs*p2;ZkNEXzH}Scb-Qrae>aSx<_-Tw5)h z(eF=|8x^cl>jCkMst;Nx%7HYbvf(IynO>_0YPUg4AJzMG|C;_N0Z2f&i_Q3qTyN!t z4s0~fwa~3zNiVev!FzhL=C615= zw}Os~S1Upn?Q$_gFFlG785r_+FO>e+f$`)-TW3xc&{Bx|A~K0EDg*^$BHhVGi>7QI zcgJxK(dX~}>e0{uM>5?@=Q{;sDCmKffqnt_z>b(?ixI(X8?nkn?%`WC#v(#c(avL3 z;~wjKdqkQruo+a~NN8smcr{JE3PuVxChS>!w$}{f-)D2amCQL}zhXJL0G%E`jo09} z0~>-jTtj^a59vZ@NfuOPgYJr?2XW*m`{NCXi^O7$u$h#rl?ziaf?6KCwhFN*_jI!M zVU*+i=P2+8-&zlNKNIxQ=h&L@tu?*-qZ(N=c7@z)pf-XBMI6XyW&J0_r@40-qwGXl z$O#=BJo90n=xCDequ`nvFJ`Zm$`sg|sK9NLJH8&K)tSfX9a=YF#PB?$vRr9v66(bl zyKuT9en+0XGIj0>>wpa1UaAgPTyJ&FZM6hL1+4L^W4jzDsSlSu$`6j@ft^oq0_0B4 zuV6cmn#4t=R*`z+ok8?hF0U|(7$0zlpeS#C-~Nvo71!f5_oX>Wb>uUq``V{^_#rw| z@3Q3S9_m2M#}#JL31Fw4D&C=|T>2c@k3K~#=tOnQD92(r?SQ{q3&^H9rkbgdOXJo3 zs{@d~PN5HdB07oJ7Eqrxkd>aa)YHNam`u`$Ph*4$UiaUmtfJ8JEN59C^l@W(q1Xn? zf29@m+25z+NhH_e6@)~M&ozLncIbp=)0#&5Fb^~)Rpx2=36F7zjLLbt-(FqVbEdW_ zS+O@`?>Cdzc}##SCveq#3?_gqY6=?xTUe(=82j67E3(JHA zFSRUMD88!vMLY#%TLw!fh6nyd6{wU89_bg14NMJGq5JCfn0S|Y^hOU6nYnZ(L;|fC zl0?}0lV#4-`tTtA-4>n`1HYvZKIY|n2lq93&~abCd#Q22GCjwjr8PMPD;AYKMwL*F z)h|`*6;Os|dC_1VXkPF<(h!&7J-v70BS)yAQ>V$-QQafv5Sm3yD8Y{}mo@o#9#z)O zp^I9>0${zP`oxk}Ll>(7T7FD8W~FB_F@9_bq{Nx1cUI>-B7{N(Lp}7;)N>1osef&*zP~V*ftA z1w-EcvN#%rG1QtC+O`{&Z!+Y?g?tD)SRg!?NJpwMJ)7wfd(^L}pzKLNDdVVcr%7X( zPYxcOv2LzOcf2p%rc7KIXM(gDF8PGqPi{TDxs;}>;ZsT4e#vQECG>Q{UZGBDvri~M zCJI`CJo(DqtN-?O@TNeI&A~@1Tez7>9g>?Waes=5qV}^`jFZfvf6tB4kCi=H$Ag$Y z;@M6asobxdY%?I~Hc(cAb8sgdMMlSu?wdh#gg?<#z#DU7tHI!8aL zjx(@P^s?K50rlGW%E#f_Kq0G{y_9iNBF5E!$70^7xshvlaiAhe;AG(*Uaxik&5g5p z-$X6@EF14T#O}|{!JeZs11n@}pyBG>3K@<1mj!wND*0V3v!})I3Q03jYVyf!*lOqR z3CeKUn}HZe-o5rp&wwGS7J;BO!pDD6No zzgGhqiQ-0aHLTUuri>HGoi;O-k>T{^SM8;~EY)NF?)&V!MdD1q)T}{DlW%6ASq2=P z5)`A0Ku}Ux*w+tdV18_5YeSVx}00`X*0 z2IK-j(XkH5(FTCi6^P>0`j8qWe+Z~8k9qLL;&s&1z`r;;y3XNt^xR$;54B@`mtY#0YXb? zKMrVsfSa2eTYNV(_TrjUasucMT!1DpOFx}~IeQ)Gj@u-FYWz>jisjWmrvU5A2tN&{ zv=pS%xyLYJ+>urVr~2XO+kZwX#9KO!29|~Zr$2? zyZpcdIX-q_nApSCxdU-{2;tNKq{DGB^2sWv!0!F)0R-UCdSL}!>Hd)W#bZMlfirnA zy%aek2&f4G19+a@)PCtqv-h*OMIK&lL&o_n}LP`y05;zw!L@& z7?1<34sKw*a0j%M62HKcj@sQS!}n~(Dv0|ZDq|byhm*dX0&o5WJpcpi%hv7h+4@%d zU>7>x0niYbG6Z0*LmdMA%sY`csyobkvG|%nfcFP{UwCr>SoQ1u@@4W|XMipX$~opg z@{7hOEBj6SD3^nLmTU(N+_ zr|$9{S+-*U3Hl*-+Zk25|1M8%>sJjnsNZD>^5F)hda@uC1PJqe(M!k;-}$#oUcaV=hM$weuKHyr$a|4*X*ej>fla9WEFq^Gp1i&<^7t=1ZS!Mt(S9rd=MId zlRJoKE>CR_@)n?rGk44i@ae_)7*K!>oZ?~}^k%VdH8~81d|AZg0uPcDUC;kvTz}a^UNUpQpml%)yYc3s<*Pm^qSaLLg z{_j9}R*f%cK2*a``WF?@1O1zFm@L2k(ka&;&-lf6XtsR7rSA6}Up*ScC%U&1_ZPGy zpugOAUumCwCG@-cTDH88#|Jc@==}$}cjVC{_(!cnMkg0H|MWe4F7Nam|4ZCE3d|Eg zR?)1S@N`I^O+}D)4HfCwh9=Aa+fT!t*tlECl&(3+Wl!>_)he?dh zx+-Z-O+%`gTsOOAnI&&Ky+*l7YjxR_(QkbE9rFEd`tkBo2drJk$3zlJQ0N@5-9<_w z2kt*ZG*zC>C-&ZYs&3!mZl&ZjiHFKC7K%3KWi%5CWJKtHHuV>RSu>TGBXLx(c0gqv!R5N6SD}=O~)t|blxDo z({=u_p@-f6D-$c=JzMyE&tyEW+I$xAI5M6)Cmk9L$7i(wGD#8ZQ)>mqGYTp+j&hvc zRSgmKTE##$6zV(oB8|Rzr4sJFqO^t;Qf;IWo_M@r^1M2cQ>oMt*x%Y?0EU*rkq|Z? zbi_ zzJr5dyP(p9OI?5q|GOfTp1!-61HU(qja5={o>N7*bNEQyomRQ#jpXEPH|HLJZ#AoY zb!6h5W2=7mP5F%mtI}0#7}`s!NAv1EPSw;-cU&M8P+3Ey+h5|qqKLK3ZN;?d+UMXr z=pT^UBm*1;V z0R&u=cQ4XSoSM`634iqheO~mEDt$X5BJBG*V_u0B@4ry z`*{Yvssw~$0`ha(;1y|+sLf^95~7h+O_IRVX+?+9uiSRKt%RdzgmE#T&^ME+O0{e64Bgdyj%I-|9|U7z3QRu7h-^O~w9| zb~|?dD|qi*k~2VpMWd%U7`$_sgpySTZfJ#oVdlM^mq~|N@#wo2a{f0AzJ-%!MA6K_ zVpLC9wu~UU0Kpbn^59W7(EJ6u)u)IZM|{fI$sPHIx^OU$FF_AsnM;jTa9xuW21=(12)< z^yi-;G;RDx7U(-ucMuI#+ii&R>C`?3TIpy;Pj62+qWl#=+t8C}H$?izMr+;bC@INE*MK0!!El_{Tk@vkGagwMt#GXxL}4|!2gx42%6QvF@Yg2- z_=~eB8u%Ygj!qsLtu$0<0t~H+l{xpu0G?&1xoq`R;do*haJF1R;JNwTR$IRbu1U!5 zx_EyLJ;BaE2H8xX`oUQKKDy_32n4Ow*m`l@v5O&PPz${ywy=;pA@}U*L!YrPKWvgz zVYbzTwHzrq@B7G4TEl7BqvgVcouaI!NNotCvulW(PkB4yn(3{3Ikk};qQwfp4=}o* z`#jaasdD(yfDCGb4%FzvW7b2ot3?)e849+COi%}xcw&=O@VB$0e4m|RL>w)fOrCOU zk@+(>D{|elWg$E&a+fg%iPa0Y>3;M+JI{ecu<-jVIx&dvRsG%k?w5VfE)vO%H32q) zFD?7gw8P`Cno0qsh_Ok7y(%G}M>sU2-D~_NjlvG}2@4ZAz-m4FJibUA#b}OFUx)kb z+B!C~vt;$m>N`fB_uID|Zb97g2|YY?Xk}gbVC*=0ZOMSXQuLIy#jgBREgtKe^Bk6K z43RA(IsFoXCt>7GslqvWMT+~uKA|nR-U7D^@|Hx0T_1SYu)-?`>9@`StGn7F>i2k_ zjT>!9?@x9UO^b!{g=q+VrbUl6DXU+Z{lS)R^={U8*j`LFjBF~BbZwJl@$I$Bv#C~S zcs3;I^Rm?=gDg@N6>}JTpD0*RWs80D1wTT+EPwG3(L2sk1Car)|4d>rh!pyDLAS@Y zf03|B;atL?JH*e=TRW=Z1qQO)mWNifKHwU5Q*@3!X8PPRv8|(FsLSd1JH@`bbe(kA zo`Gu#pq@9}S#7eDn!RtlX@U)2)C{tT6fz~XEPXA}KYDQ|8?T?$I=&mbBvRAQuK-dR zy0Wj|9RS1a!{?sz8szl!jB=+TKo*BYL;Qk3Un+}3M9m+da50XWs-!efY|iFOU=g&H z3KQ<4ONOQJCs^eF4bb~8yG$MMq@2||1D}rsRJa*US{t??1qYf*?%CXFr<&izQx_U> zWwu2#$JVoV<&r|axbM|1`)b%AuGg$)1yxvJj$1ScU4KNgc_}dLi8NtlVpajjq^%$k z3z)DnP-iNY!tZ+*T>`XF7(f~U5eUVHxB^0~J6XHuxZz%!c<0F)YJM47Wv3^WpkQ`M z=~^_&oXBmZGqkAq>qh6Gdx?xq`3W>K_HK3W8d*Q`SDT-T*ADSsJ9H@_vP`z&Ynic7 zaTOh!_6q-tkZOguwDh47lp{+BD|u#k%*yj6lQ*){Jv#bAG;EBX+wTXuZ&#Ab@!(m> zx$@WcMy@DcF&9L_^`!lc#{G%U$TsHVqh$<11D3||D~H7hO~WSt{QEQHZlO}Tv{ zs5%m#qiRhr!vTjR_T6K+zLy4dnVR7{ndto>4Fsx@)21Pl>xNQX;hhd9?*;bNG#siS z;v9^R!B3kexWw6~y?q&xR>t*UAjW$pSqM;1OSLK|$%Pz6j+8s@SnZ)z0uK`@OBLbT zk9Rtqofi<(y6BiI=4+W)w^E!z!FAP$j)~`eo?K5UKE1E~()00AKBq^9WN&QAs2l{{ z1jkygCWdFCdFN^2D8Wnw3d41*IR4Fi zLnu3Z?kY`dDBra+BIDQ^lBsfj3kjr}xR-x?GN)TNcg#?O()Ke(og zSxOsE)2|=~AU5=YVx3IF1ujEB{pWo$!89h$vF)w_yFDE&e>8{mt(bL`Sq0I-oF1L& z0!LbHyK!%=#oJ=yOuB(qgSYduP(;%fzn!ATB$58s((3oV?7av$9~E>p8OF4)(mFsr zO$YJ%oZU&=#|ti4!}hD))Xk_x z_rbE|hfdYa&ed;ElxpHa*$hAN?N~2%nqW+&CJ@S5b()MR%eE|#rZbcWINVO_UfY=_ z$lK3w+f~q{v~^KVtghcOpoP-4wm>~Fg&x9vyyxlV;Uxp@s3ta@+gCmvt6fRc)ISf4 z)$QXDW)!69?i3+eLp~frJCZz~g_j)(==|>xXsV&|k`&5_q?EXpFk>Cx`sCTiDwLM0 zc1X$ABGc0Q|BJD6>dr)Ax@|hPZQHhO+qP}ncG59Bw)4ccZQK0z)wy~v&X1@uYE-Q` zSG}JXLmKrNL;d5TY3g%KU2VZb=G$z@0(}h;R}%i=?23RpmL1JP4x#0jIZA`Z0sRQW zKi(t!bz>1FrVzl_bV9Bs#e z>P!wjVsJP++Tstlsq1hoJkh2})E?Z|We7d16l*GDGPgOhLeBPVxplYDUmxx6)llKt zox`>4JUZQusGGm+TKY*wTx4t?xE)oVol>{!VJ2rsm2?lIh4X)+aH(~}wMf$7lCgMk zS#<|v!Y~g58yl!vhN!!S9d`M|#%7~qdpu2xfF-*v34kM}5YpEoY+HzN1)8OCNi;FI zy9`5{!*lpmaH9h1<7}<4(^DGqOLozH@KJ%sNHnP^SmdU3F)$*1vw+!9HR2(xC~&L> z8DE^bH)!;enBDX*Aj29bVw3E{heY};b86{YA8l1xn|E8B$(y76cQhUx4=(66->rdZ zN+@M^quy^=$~Z(YX7V{`8_7^;^yhQ?-G{8Y4|G)sGp7ZK7_^~x@>K}*YqC(Q+P~%n zQgE(p>M|MtAJy_^YQ{^G!%M?c9ON|CFTIA^(MVNn1&f=*J5VUChORwA#3m!wTgrk;;o3m4JP2uQB?!11~aqxH@gJx%Q4Hv%D5 zy}*hrCo7Zx{>}?}`*}}nH%mH@9KkdZA6KZ8WX>x@(L@uj{&$OOYc)DTX@ zC%v`{-7g<=eg>J7*7Q{rl8ws&5ktzwH+#uEx#e3J|^NJv?L=;EaF!B#rtcrOA6Y)%iP37V%VDSv2qk z_gLc>pUI9}1;pX%eLAp(W#)a7kd@l8a_$AO^|xK0K_@9}w{#1nOLpRd5?l8tnR8U! zPpBE9gju+42#UqMz2U$`80)6_P@&pa&C^4n_}B^%3x*+2@ddN5I$z}*LKjyh$&{9sD&mM_PZ6~tBp(InqLX$h{EDjC#0dN`77Ic z_Cc8j`e=P$n2n0BButm{mv`y7+6)a3Fj#w7@zl-BM)BQ*sy+${TT0S5;bDGhq01nq zYbMX;j-0H7^->ZRW^GID1CC>#Zh^*L$E62J#lOO^E4`#0HZhz~Vf`$T`RXLU!#2x# z*c3+p?@>;wha)|CN-J*bA1SJqYdjW<95>Nay$iL;9;>#kf*M$g8MPfn{i@3VD# zyshm;o1$%r>P!m{CDI37A)l-N2cOvWT9h8ep5K$%S~H? zg>#&U_8PzVsACDHbZ6VcaGYURnnxhrxgo?_@GhlM+=z^42D-Tg!O}DmX*zY!bkNi# z(EdgKCN-XO&v$YP)C`2Imr8%`2U zShtr6(7(P8*Q3hITgCFh9-BS3=x**zrEW_$`aT#>&xD<3kc+sV6usD1)5#vbYT|UN z&BY-QgB=-V@e(0rHWfBV4|U?eW3n<5|NUD+QvCJw`2`qa7PRP{k-QsEEr%b zv0AjJsnD(Q79T9VM{xpCqx7Z5*|2I9ll7AN%qQZF2{S^9eb|Io7Us7nfyvRMFgN8G zD6X?WiC|HIjxsDI8K3U+yBtoKEI+=IB+!=ooO$sz5%tAuxlxfOl^ho6ra1>Anl@xx zJ7qtfsxgjZMgu`9!yOS&AI|5+ym_=UZj*~kc3MCGB>!hi3`-|PheM<=RNPtE@v3!% zyON+luG2%DaNqtqHI8;@4V?2Axfd|h5sq1%Kf*~%j8CqVSKyZK_deH!=d5dsbiA()y0L!QAACb#s+7U*g zGv!nKOy|Axd~TB0?V;uXhlT`nKcna7iCLu5S$m-~U(J;1E99{PvL3oTFJDA`Q)A>z z14iS<`7b&iSC4eDh3k$@Jai0@s0gT|2pL@YD)WIR^E9#b>Uu%<2v&0>mkW|qgqyt5iw}~>Sgi4N&cq? zoPL1Fm?x=9FA>~v4lQMhiT@%~Djk+u3+{X`%|hgar~q!^^lR4ct(_*U+{Bx-L6@E} zhQRWpch$wtinz`2X1GEg*AW4hZ4tpVdsd{Vuc4AD?aAT&)mzV%JDfyX3km&T=k$$Z z={N2nR7QuYtSW)2RIq%qR!rxq&AaAAob=a@VnF1F87Aqr{#Qvwqg6smm1ox%)dr(Ru={y0CXpDy_=0(re^dYw zIyIr6E#4vxbxEFrbS1Z;bW9F%w&}AG`_n=txF4#`BBXB3OTKUaSSm|vr?Y~X&*yC~ z@xUdKYW~(rF<3)nZNmHHgHv{{*pW2PiJ!+AT4(n(7s|Mn!^{_Wz1eYc-fDCB5X(P{ zXK)*y^FKfo3jdkTUzC~>fN>IR$}7XYcaB{Ni_hy0OyS~wKJdbMQe|#D@ehWu4+jfN z_XLI0{wr+b1fx#CO{rXqEUS@5T9I!11uWGse|+kV!cTUXfkF&Hw6o{)!{f#*e3h+% zl;-pKf|$9^ic>UekH>p&*xzfA?uT^qFg(Ag&qo;ssTY4;niwVSf zm(7ObjQ}PoxP-G?@!h6tn_?rc&rUO3%(^hZaylKCA3Q9rz=;(Nq+!qp#100+=9q{J z5rZRF7u9$VZXrG@d=d>xo;Ql#ROK zQ=zlFtC&ntD?z*p3Lp0xQ@K-zK=D|gh=N7`Q6+Te|oMw zIWCu>OyH4g?`^J@sR_m)0?nNYK#^yQA@j4BZz5AcB6njdQy+2Of;a;H3|lfMG6U|H zzS7eF0{53^o0$(Wib~>8N9iSW?b4tp|EV%Fny+)TzF1A@8`CwcH|AtGu-%cy_(j|x- zDaiN=OeSYAptr>)KcAdy=(B}hV$@^;a8@}}OdE4tDNVUbZ748w`-Dum5PRNq?R%U5 zo4ESq))wEyjUfdGb9>HSn)!ATc7ZDY#_$VkTdc9@bkUd%)Hc(YK2vcr z!>q~?@{#juG+4|Hmpljsm+OOGN~p89p4q?0VdwJHMM(t#1HLwsnvaSPjK|)2i-tEy$;nWQi?JLVnFv#Sl1_UYEvx zYk~4k^fzoeB(i-eA=&b!7fLslbjG^j#TcrWwFPYI@?EkkCwJG*N=~Vv0K7QUhWl2E zkbYGz<&>tn7@Du_3Es9tA4riiJB;bnCZTmx4ZdmDukKZG>hcx+2zk>n8!Fa_X};|} zbxfWsLyrkVV&Z#?X$*V@&o7IB(E702(yOZ$iyTPx^|VX>A|h&`%5izElK2phOihf5N+t6cUpGcy}#Sjep5~MvZ2V2qpYfa9*-_~zMY>^>OAet)GW=t>Yj>RFr(lw{$BNBI%U7pc`k7u(+ z!PiuE_Cr`^X#sm%6>kmcp-7ANz zn0gnwuhh)qJ73a2u11020E-_ebg`=i!NwIL576A`6g9@uuJIjO*{kGJBO_JVa3-?& zDa9x1CL!7*9x|C2ey5HWB4jPJ^ao;?V^rwD76z14FRBMv$xMCoUdJM@)E=TRGgKxo zhRp)o7$Vv#;pMo3AJ0$ilf^W^RaWIY_ic%~uC9RtrQeZJ=274yt`qxYf^iCB4A z`1{}tRki<>948v!0-`x(tcfq%t~|JoS$DAtBNhEhnK4uWw0QVbN<7CxL!(uo zp{U5@Cb{AI2r6s$Ci**Y7V6;r42@rdEPNvp=v1~#?fjB1)ZBQd17(bwyNn$AroL&$ zhkRnAS(N3xHRk#oM%82w-{>71ihpAXmQ<+YAskXr;yUN1Uxs7I;l^vKrg)AQy6qmP zKDXh6xYh1Th?IWS9yErV2#aQ$+%K?ebU?mWZ3SZcid)M)pzn~o!5J<%>pqD$Z+f}o ztqO6H^s>m-S@TIt!X4gImDO)HTTP4Y8KEyj82)<4JgMjm?yXL?ly))<@(WC zG+|boYwa7TSDs(2Jp=>CN%eQYei=h4>c@pJ`&Cl{a%Y*H(@7R6w}CF==k4?s=#=uV zll)SdPee9!8O^aQ#?N68d`uSL4UTkXgnY?@n+O@Rhm4V5;h3_Pu)Dk=gg5&g22m${ zQ5&bzQ&}xP`DaN@c9*G}BT6e2CBfPbM=@qyB*}KarUzE;AHqj`7p6?`b z4sasLe#`Cj<$^47axlDwpabJR;iD%Tl>}&sGSpl{zi_(k0WFKKz5>Cc+HNzhRe-)@ zJyIjtU*BFf0m(nI1xBF(XdMBUZT_+y=Y_kb8bLYNuoAD9h3B6s>GOoaRpZ_!8T!sd z(HDAaB7r?yb4_01 zmS+oX@&@pal-X!B0u z-b$$xAZA;R)wunf3{>Bs&6x~4PK_%@dhWiCt>347?Lr+utVHUg_a*43Vf|jqa;iD~ zONh#MF6Wc05H`Tjm9)`b^`CPY*1bqrG~Pyi0kdrSij%&hG~O zpgH#aN25-fwh=e~r!Ibjhv|W}Z>RJQ3KJ4zn=d&n<6$0y+ za&U%cO6YTD4VOekW`*?XpBwgHj#i&N;R-ik)U=cr$_)cR# zN^UK2Y*y(dLq`A)vjjn^;9TqyX<0+cB5IB^(_WiN*hfwCBzLm@9bfAmg{)!R9Hjy)+KNqjmS=gAq{(9HgrNwwoS9K!sGdbyAaSyty0N`k*b>pXG{s`FJ3l zoyrDPVlOC;&4R^f5wp#eU64W)Ft(;7oBm?+#wpymj_-)r6qbfbl+wTv#Y`Rxv+T5K z+EyFreWRoMXp6u5IBFsV`O*9;@pH_Jg0{W>c4KRM3AZR5AO@Y|@3O)GxwPwpz4aTWC4b)8nUa>;q$CeiH@pcA)+lp@n&ev$MO%&+3Oh zq@D0;*)GNOgaGI5!pzZplu?8xwwnX+L`n(u(jSmZe!s=-SR!R*SZ*zyG*4wV5^aFX1-p z?9?2hEd+eRI;j2=3fsCUL?_tOQwnrM-`ZGI?S=;t`#5O@bRq!4N-pWF`12nazo@ij zuuk7zy<`?17;EBL$ZHEkd_)rd*7j0W0E@stTld=ISJ9C~2{W~J&PPJ&W}2jc^{uf= z00B>LFFQMqP4^t&;bhR#7=Tk~1{NF}tY7)6&?uhv=#=^zjzrE4B+`;NW-ZA5yvQJB zIMc(+Rd@6K>rYb6(HyPsd|3z@YS|lB_&d^T5sv|^NA^OYO`bKh@45i`BvtJ%t_F|p07~04}>0dn+`(9qQI7i zlZmLix0$%Evm%WNLiTmbmNyb>sfVe*R~N!MUh?xdV;-1X^2pmiH?6stynSo&4OSg~ z+psVPjkpLqc8WfPShB5TbIGy^h$Nk2kCNWVC37RUo0U(|FWSDLb)SGpv3-}7P6?l= zD#3lEaXU~8vfl(JH;&>@wIxF=ZI8y(si%68TG{#U6@=cc6+}$FkS(ciEcXn9#rnWN zgZhQ9qY06GVX}IpzL~9~C~HdXY;&%Mpajm2+Cw<&r2mbZVq5XM|BB}J_aZLb_Q**3 z;B9qaN+?>v3f#G|=ShtiXk-dJy!COl$@1w?;u}O5UF4t2@&m=6sjd6R>c@o#TQHIL zM^^>}eU(})7jc3LDh|jYG4x)#-aU2?5oVp+gn*cwQp}RnYJ<23mO00Hq!a%5|bZZl+1H7QDn#WJSw(}_4?@D$Jw2j#hFErtCKqYG|(fJLSC^bkD zUCm}5JO;byh2w$6V==ElxoJZJT=tde`j-U!V9JG++@g;SMpf!=C3S@UgVD>ar<%OWw;o6sDll(C~tI=K43RxxT+RM3?kmiU2craG2SL*AGu4GPA>TOJ#PR*j z{4YJ@CJk~D=1ZP29ZEp`?)^fhIic{%)sp3cl~On@C`Gfwpp{{&VYVEu8wE(MJ(YM! zIIZS9EE6qRMWudG(zRMMNv&+W1_94LO?YsLgSzvJxFkQW$S4BtXOuS5avL@vSW1AK z?MVg?T>P$cy9*ipKm-53V1MX4W}Fr561r)X1n)Cgo~@f`qZo7m(OL8$Z4@{^cPsHd zyoNTy0Our5uv3EFzQx0#w6dJv2vq>(U@bE>`vUrSr*Th)POKT%^F0A!Btfq*Iopo4Mm zd@H06>14&LW(yn+KXEljHjd>zr8}+2vFbuIWMW}ul6zFI8JmJT)Y?WhuyrteVc3Nt zBu_4QG6O)GW&3E+U@uEqo8u?rSg=2{o3oVJoq=l%h>T(tp0|a?z+R!GGC@jx&CkAg zP&)KLnjY%u*}E}?)DvVJbaj1qLu%S}o%+wrqqTA*V`CQg%n8KjuylU}Rj(;X{Lhnw zxe(v8-EymiZ(lYTb(vrwQIajbtIbDNyQu z?G;hm8KH`PB<#ZIuMA8&6oMqoMVXaryyvC zhR=L6`w|w^Rwggr1gymn2<4GB;hSw?OZHEAPESgTS;r9CPGL+&%_zc*Jl_yJJ(xRQ zo7<#Kov%+<5q3hrD%;wHjsjNY46OyO8Vs2;eB!a=vGBOmLfpb(LWr{T<8ETEoeJ<5 z%bL_7?5aFvHaA;XNpY_ia?>aRoHN+-Pn(k&V-bzTuOm7I<-}Em!#|C$PWcv}E#%kb z?wdH)(soGIbT1(aCFJNFYVUbnf8#5hF3!n|iqx8!C6@Gj(*HLyxV0lBU|vf^1N z&2B2>w}skgg82mg*`X?gPF2^s1Pd?re1UUMsVrlVvY1n?v$Lu%u0gW|JR4r970wBh zL6(9zPqGj2Kh`>|<5NA|L%h=_mMevmaVw|F#2!f1iGY8qWL4HoAq@`6ZvJ$n7lle* zOa=FXH=Qh@8He?hega3sHK<4p1s?bj9JC?GAd|$cL9Ly<$1EcSSj?e=&u)FbsD5ve z(U_nS`AD=B{BknZJ-=`&+4dv``Oxx9XK_~b@|^7Nce?)C0rRTeB_x|y)9EDOy~oh` z&^+5$XBv8h9;>ZdRlM4XhkVY@Mwun5>^!=82cHJvuf8N4JJs;kH=r&SZP`qRr<%?d zxIWmjL*+LHo=RKGK@7Aw!7b9kn{leXkB~;VEJ!Lu~+l)0%Qj+@! zz}Qu`2@UYX7+g{$jY zl7KcVih7^AQ1-~fB?N+O`5NTbKYaqO4Of9%gX%v)C8V>&SMO}&df09<9!_cG4;iO} zCaoCV><;2j<;LQe3S*$6j&jaHR5>sAg<@Pk_DF0z2Vwo6ViQ+&EQVBK5);xDPIS0$ zn7vUOZsV8>77!UcI}N3xq2nWbgZDo=3Xgv(9-eV;_HwB&4}1%Iy=XxP{wym%mjM)2 zIvZ!Cjwe^&|ik*%&gWckM3W6++*E`d+Sn1`iQb6R@>|B4{t2D3^`Mz z6@zUyEFgnDNj93D-^)g;N3DMl6eIBo{uk81^*=RxjQ`K3$4tn2YXACUZweVx>V6b73KN^80EMu@QmMP33d?QpML_lB~K0t{uKu2hx4^YmIK%88h zpg-`T+%Ui;Q(OJ%KxXWLz^K5^Ld9vJ+}_+FwRVOHn_oSkjGBzVfxy7Nw0(cg-=3vI!h{&4Z$SQ?ol%!O(P3Ng+Gr2R)U1pP-etgrvaY^+b=>aG>etPsc20(me_ zffxR9{=?N3MEj=?5=3^$g{sS7g{t!|CjR6M3zcsw*6eQ*xDDE=elY;8n zNS2TcpCy5hU|NCse*SuOWp)GsFv`0fRF_XoV12{;CGBhSdD* zjh^s?@BxA2CTxHJbNYY(G%L-URrepei8xbI>3S zkB|0&fP#Dlfp!lEUw74h0KX15eYMu+dwnw__XR*oY-`gNl-RtXsE-e4gUjcg- zi29yWgFgw%?qPiKVa!iXoP@tPRWKhc6BC3o_0@o1?_(qLghL|u2LDt}n#7#Akk16X zD`JorAg!t(BXstF&?k@objbA(B7)Y67+4e}*Gh;9kq~=uzPLIviK7lZAZzP{ifbm& zdrAMX4A2*`FV)k6@c2MHZyDDNV=#to-wb0AhHak^zyv+@0ffIKjeiEFei|H|f!6qb zV1WNz<@fFP!Q1U$Tz!pQw5{M{ea8j#Q4l6Vi~-v@!CModn(AOIIcbr|U(9qe5ykqZ zdRLB)b1NCfLgOUnvunkzPEF`4)23)$K}=w7x>rkb>X`@R2|Vi8m0R8&^%|BYuD6yk zCgl0F2Np=({YZ(kMQj6SROis%3)ioC0m;YlKCFM17p1R&WH+zzKe_qAK;5{$kum#1 z58zSj-P%Yqr$LT`y1uNk8rGhOXyfpn4n1+%z%x1YN??VTSCptwL3`-^9q!T)_+;l~ ze!?m*=%!#69H4VN%p?a5C!u2%B_EDcu6^V}xMVM1vtz(p-PA=_5RRWW%x3ya>P})J z=z%cK(Cj^A^mtun)2mq5cdfr}SN4`s2=1(JJ1VR4+<<@+@!VqZrvPn+3ST@D2_)Zj zNYx21#;k9RfivxLkFdJ+mSGgwvM#A-sXH79Y<96=M#a<0MO;OFDnYf_F195ZVG!fy z@XnvVh-a?2S(cU32XEaX@2=GRql%Gu*!y<5C!H+GGK2xesePz+yF8gl8|gP8xfp%G zq{isLYhnV%4(v-ocITk25eBk?$ij+MrEs%A^LVu}Uk4k^n6I{7r!sW~pRnhW<6ZJ; z;{rx(1%I*STH$M=nsdryzfNuw^Xfo%s1-|b(d79!yHy4U(An)FEwigbR<(;We` z8BAGiIL}Yy>bA#+A_Lxn9!O#uUqEe`f&Nw#MfHLoj3V?aD z+;pD$?V6X54)@_sX1)xRHCzH}m4sHJ65uqgT1DLJlJHadR!DFgZeZcuKSp7pFx7{W zMQ1gVdY1POW|GxkXB?t{QTa*lOu1HI50YTD-E1Ka@A;+qbSuVu$B+tD->9`h0sgQ2 zMjV}}S{NB`G}B~?EWRUKCvt@r(dk1=0^yM5h8+~?TAxh`%uWvvegVa_azLm=vendw z^vnq5%LTn`$E(xX+$;!@clo%CaT-18UP`y8yV#=ug>y`QppS9u*iyriX zynLGe(<~i)C<4%J3&%(9OqWSKbM|d@Z8Q_2|H(9?A(}?UU8V~Jj8p6TLT(}w((6GX zku)+V5;A50b6Aepiq##X(Kl{nbMk>DXT9p%9s38j=fzsIhvmvYFsRQI*K3{aGfG;|5sFX=<&0D&25Pc;#=Q?#Ti<++ z>FHP8zQ`OEVp&iaqe4^ftEtN1m!oHo{R!y=C;LStC(B*Ye|~Nr$s@rNDetsJr<-wp z&K^^te9bjtP()PM7~EQmGnz@I9i6i2l8MTiC$`5Ia?Cw95xXaGTx5*_&RmYay4F?WRqM#QiorDqU7aWL2vfY8_y&l)El?PGqC@u@s_TeT zIog9{lyqrOAKYkYr${bTIIJiCU?1}v^dYa1%psE?G6oTBuO)#Io+cKrMcAm2q^-i22GUNstrwRW%-Pzd@56ui1GPkb0K^B-f z9kN3jG4djm@Y^@H`UzC^9FDHjJTfbliLdq6)=|PdftZ1)IWgGpkS!s<9J9pZ#&W9 zAy+byd(5DNybtxV3ESi>3A=uEr;YvcYDX;qmndUu#om%5%}FY#9)gs2xafl~ZvpL} zm(eve;DyoJ7#jjv>D%YyuI@y|T&#E}&F&DmJUNPvza`n>-Mv_5uV|!F3z_|Isfjgk zc44C5#f~KWr1!IdVwH{ESiQTBvvPj+y&!d3fw&V9Ei@#0_d0FFU@!(%@HjA6rMmE3 zS8ck(3dS>^=>~t9YuFR=8Enl8zMeeUi>d*W!i`8MNyjpAwyt22gGYCWcJ<$>3=n`q z1qNgU*=c^{6$~)*q-%t>ykU8aq)hHtGw6!$$dNwjrgpay#^~-IdbaclZrkUhdtGZ@ zer;vbjJL zZmRmLvh}sLuAz;dxbA!Z$7x#nROV?mnEnOc!n?O;?ZCji`3> zQ%vw!f+BP+Ib=a})E-fam>}5MX1^dM8K!i>&Uzlz{o{?fM@j9V@qO!SU5mcHYHFN2 z`A-q0fz5Tx{xEiSHZi_Bf6yTI{VAi7oSWWr41WucDBYxQTKFENRAN24`Q}BNu=zg? z8DtOdj+s}R5Vw-TwsPtY^$sbON>+N!Z6cm+Y%c@)aJWYE9`h=?52>)Vn3ZTNV_o2* z{YT0X%X$~K#zAYImfPT&mBM&tJhfhi*x+rZADfNqzT2M%?GjGr!yjk}y~25xtLrw` z8aG1hJdYIjW>GhVPXQEs(ynzCgSp3i(?W@rM+0(E14z*B%@yWmHK z41Tf6C63Wm{%mb*{Jgsu{eE67hwPyO$iGYPeMfeK#Z`-U;_Q5o$6WlDgae+>s;rAL;+(o2=qDLkl*YlZ~=K0HW%qMLI(}ne~mni z4SBBHC=pvYo`ful{Nc%4ui;FCn&M3TyBa~)&eE~Ip_?#1W>9NsZ+g)&-~%^YGC-qF zNJ0wY#og<;0?PL9kCD~Z%#H1c5-kiDGjYj1d(q8*!FWh0qE=B|!yN7aRX2?&a5>A( zu5fj?#z~535jg%}KCxr=31{br6O?_om8}+xbg(k2dHda@*O; zN2M;YY_xxtU^g&e;Ja9cI*uQ{bl%Jay%G@)Sx|4%JOk~8PI|oi8~~c+IZj#Xy+EGt zAV!6!r=?LzYu18+ye*g*1(g`hjTXgF;n6iwH*+f633fkNZyINVm9)z0d+eVSDnqT(p(s2-979p6e$= z7(vZ8_4n2aFvi$O=4woss++u_{dn&VZZVl6_OUs>+@_V66I4kA*5_DrUjSl3xq4Yu zQ;;>_`l4XS&|i<49o8B3xmR8?)Dg-;Yt)-V;WoJY4~~4*igz5sC0#m;1PkjRi7%HE zHJ}FK>S@>ShjSOI8a4o8QZkb6qR@K;9>!P$Ua}$=fam65@Zl5&j!k}Q(ke>4Sn8Sg z3djxeaAuTsogXwEWWU9pw(L-`SUDlH(I*7dju$#)GRc zrNqsiVz9g_V1ONc$lnJ zwXiQibCDU1_VtTzhYs&lEj*liljWA;uJ!)A=38i8@wkB8;9QH2TDc;UvDf5U!5hVB z&E5vCc8|r2M7^LAr@?blhKqz$T@1BIg7N42hx&2zN(yI)Z4*I09YUqD2%;cPYh+Up zbV!267(l0cvN2cMF6#Z{TX1nq$15Pff`c)y=aX{}48Mv0x}-q7ICYv6m8^eXClFr8 zM--LWQKNZsA@)>;HL_^$9o~uigDD@$U*p$i@EZh9(|_Xh$HP;zgEX({GbSxuXM{ z%GCSfqaD*cQImECS@O7&d_v6S!5|wi#t+`A{)>@V?j+}4olZATDkRF>f28Q3)xru1 zrCfvG^-l;}s{r74Pxkr{6OB2xO2U($LhA1_i`6AaPJ=V`M%uaa^Lwo3l!ke|mk?i+ zicd*e9))bB_3oBf9Xd}2$y$kE{GMqf*M}G_leo4N%L^f0kn)j6!6k(vCx+i)eFTDp!D#V*HkpLu!wiZtVsnY#+##sVhNquC9ubcrty2GR<0BH zoYG$4)fH4Q2*pf;9p+qy&};DXZ{KjO9mUCKzo2ErDG@UR)kOz(15B{8SLK^&L_Wcu zMjXZ?N2QTxqKI}0`uG{im}q_W2cJ<>Mn9;Vm^nbrB=w+z)E4O<@WvX-r~LHrN_`tv z)!ZIC`m2gP%E2sTUNQhNKibfRHv}WynwK$59pIU-O=@>PbR(^kO?dptrHR_N!82=& zOA;~8S9j}1$SgGHtguqmEcY(6eR@WC`J6eLnmDnbIWu0#--<(@w)a3!l_(noFo_Ie zZ(nXMP_DtCE5XjWB)fKq9`h=iQK5^XjS!r}4HG(4gblQe(gc&kg*3jedeRL`J&(|v z&h5Gfv!I5oO|G5q{N;<@8b{YRmaLTLS+Oiu50;}SG`nOZ1InGXj^^{9Mf-X#y})n0 zE8@6Z_Mhs|gbBMwcO~s*n^?*ITQ`US%(9qm?F^e^bU>ozGcL6q9xN(@5!>FhXK|;Y z5-cI==14!&lkIhKJYZ8>LmWU7eqftl`=vkLxIcs%OaO%r69qF|o6@$9bKhmR29cuoH`cH~c}$I$_K z%?Wex_m!9rZ&X2FnH=e+UQ6s)4X}m+mF^t<;$pCCy%0k+S-NY*K*>q>S(HqCXsXhX ziq<;?W$Xdm49d`l%rAHA-%-x|JZTEx`a2@sOUPyVTM_?M(^V6n(~uov@~r$<&_$hZ zE9EK65$V}xbC(W$(+?Rh zhE~0G1JqKy^Xm0zx7cdHvUuYGDO?%eVbw$S+Kn_*12M4_sWadr+^*d*p-MgoY5U(e zF;~Js{iR4T`u;YOD&SIGNX=Zo)^X~qPPozFc01pnEndbmYcB}EF=5g&bWi;V!$U6qk5T`KP^eopEm>(vOqfx>2g;|evb$-;&fU{%SU`|n&@988 zu96ic^{U#yLn6y6F7pxKK-s2B{l=Zl^8v?ivuk2bPD2WOYx&Q^W6+%QK`C)Qk>kFEKTp>x6HK=RE?wwBwVOx$(hK+8P{+fTeRkLv6 z@1Uq%4FJB(KHCHNR}H~LoGq@EGJo~Hd%9a6qU^QYyPcDSZ3U!jrIl7G_iD;^8W0jF zB|-hWM^E2DL3x%8*h)d5qqs3JBIek@|Q}g;?e#m4GBBvL%DB?Y@@G* z!q$YcP5_L0sa5b|N$QN({AH}5?F$8*nm*6eZisN$nl(c<*8=*dLddg~B44`By|Q~$ zjrk?e$_JSix%iHoPJ4y^s!!=VOr1LiUrFbNe1YFs=3`>PLY>JMs}fP0>M+LGUYEWI zBE!J)jrscgV0qr1f0~mj@{QtSZ)cKpdenhXlG4p-kk@eFX{9)u_B>X?jtd{G))Q4S zgUgor!h=8#BhtLfk=HwBnRGVQU-@ZfXYw%2i)a3N3Lpd7&!%TfT6wPhI1kvQqD#ti zc>gb{e8jTLMD9%T_%aVfu$+s-;N~R;KbnWHX`6A~@)Y zQj1|6!#lkI}6|eZ4wYAzh4UJ1+5rXr)*=!yaPF-DC(7 z+nKk1t_Be`;B%+r`(xfb58X|VL2Ttcg_aBrS)Vte`a5(LjFU_zafsp!3M#e9#}IWp zMq>Zb$+}A1W{bIU6Gi1jhp~X*kLVAy<+5Oe85CzD4gp~A!3#MEj{;XGEAH##;&f{w z%ag}7nuvD&Zsn>Lt5JW@cg=nxoRwD8Mj>|Z#kB70*GtxNdG3*kb1N-o_};cV?(Dzt zPveC(07ctI3*9V(Cp<|Fb1UEdZH4&`63uufS0$8H+%_u{L^WVuYfN#;Pxy00D3|YP zgVP#`8VOdwe+D7NImVdZ$c_e0_EgC`Jl(6cp@9D~U)U_MTKBfRZdtF?UB;Wa3exTu zZeiEta=xSbX3+)vMOo)nA<3TEnGvPG;;xaeuP+!OY`tt|QKcFwi9E$-Qk?);g^ggd z)C5TKk|<9&s!rRb;qIl>7^CA$oq9&~mGiOyBUwSRF9jk? zyKUwIU6vM_5tU^VRa=3yw((S2XFgVfau9w~V81V8E6p;KP!^4}48=bZK9Gkv+rh+G z7Ccq}167Ym(99H^Sf@0#xS8END}E^#9JI$+rg}lW0I9+@N~h~KZXUvU;l}L`Ff@sW zJo6wYx#8#zkgb(oFs4j5i^onIZq7#wzp~%iG=-3KDu%^a202?B(7Xk`9eIlfN1oM{ zI_1P53X-5UWkctFKiWG9vu zKV70&6@d-*&9Mz?=pkTwcragDtdY!;zbncCpZk1zO|D3BDw-9aine(TDB#j+5h2s| zXb|LY;$K?Bq7(pUJCSF>Un>7`l9$TGMMa#aEJ>VR&4`+ETBbPMQE9N(qQ-?aS6?Zd z!AG|43@RzRNm0_Nb@BU!zRcu|3Wj-PP-k)z#Ib1muuzOpb7l_$I?COUPQ*A0oM-tF z#5U9MMct{wwx^MbOp#OZ*-UA63_FAv88LVT~@keX*~1 z2A0v8S5CZLBD8brATf=Jmx1+CGGQD>7x^|>T9*UfVyXB|@$LMsJ*~Khe+{zRCqUJ==K{ zEjn$!gTp=kuSo{x2fu(^5M+!0frViGe}jqtl^kSd{a^G013o(g7688U0H!)24Lu&SQoa*2?+8a7XCd7bPB}R#`}5n z-1S`TaGloZWj|fFpJ{w;goh2T0EX!@a`*n!314{4Dp%Z6ZOUy+?28wg72L@mVoUn%b2F=mrG_7@M7){1Rp3o5DQ; zX`u@QNSe}P!T&5pqMo_}z?6fggE+azBR>na(xU?h{Fi8CWmRGHG*u}}e8vJZ@x%Jp zv5*6256sfyPx0Fg0-P{;$>UA0FPH~lvhJJlJ;3}2LS&{RLEM3?`BU>DoR&hMg^`Rw z-Z`=H3CjG*I{*myIhoRrM)~IagZ>~|_g^5yPCv{6;Qs_6T=4xO zng}VUa7JMM3xsfCYIF?Y8P06a@V}m#%EkU^YscWzkb>2F5xS%Gm_e1%15abDWL&#p z6>ixz mStxxjX*bKy{Gi};^O$6cer^=bQ>3=ab-4)2QL8$FzQPB%4UbaO{p@Fl~ zK&UH(7L$3PO(li6)}6ux0k&&wYjq2OILjuO51up~c zy9fsv1GfV8_z-+_U~vQm)RUpX$E*Fdew)R?M1ZIR(d+{_!MCIXx!%2!r5n4L{Z@R; z?z;g1ej&XE1ib3?{jG}1IWmR}UUUDt{1NqCA3{M^Zdy+JG5U&?*22DkyEE7~0I##N zYXtV|6(0F)x_h5x`bFNeeelhz_(wv}y!J9o@K@yl{P41Kq1@Wy*7%MG{M5$l1N_5` zC+0}00|B0XC3fSoGq(@Ufxmun{dfg_Y&(9lkAF$Ne|zGZBD1&gOg?z8enZ!%aIH@7 zQwI~1wDn{S^Fh2Z;l_MBFZ_P6jY;B2)`ow2s~zYXOYac^)i%EsMd})v)^Lo_*CkA<@a>Ya-rTx zHx=s`$8fCxn>`P{;6ILF8ts9;GoQlgu%=)?Y&m!UGD*kIW%qa`^!5*)oS?4Y<9U`( zZ@=;2|3DnUHSlF-hG;;5ZK{B?>Utx39*;DzQ*rS(mM4z%9Wb9R9XLEbxHAYUtL#NA z2CF&fa;_Y7Ab+=?alLo1`Up-x){O`?muTK{Cb~V>PycONmk+p!AMmcH)h;TlRc8`z z?YhP3ZU){VWa;xwEgg4s+V?E~z-s7)vszEOV#%O`x$f;m|dMx|Q8iJ79P^B^v&Ic&V#+hW}l z(P6+(yHRGn5ji+r;NU_cl|cEb_?sxEwPrfgiocL;t8ySYjkaN}(o$Y~`aasr1@!md zsNm)MavfjxeU^#DNJddFzaTy9oWn2N?VK|8S zW<8gCNm$E)0Vk6&+51n3KW@wF7ig8}28xEX{T8SNG8T9|l^|y`VD|w(LG~9~3a2I7 z@$tdPTc_OhWg=9o-F;6QUPf2{`)yD8=V=Q^Wzl4qFd?#TjjVHCh9ZtdM5n^q>af9u z8PskSd^759JALZ7_`)2@G`TbR6;!bMEXK41sxyM`0~(2&tIp}H{C0tZF#Ibav?Y1S zUrS5C_=%$8TA9yN;P5v}*y+kwrJPDT9L7VzOJrcf%OxEbln}f&j!VFRE&1~>m-{AU z#>*cJQ_6uS`9JU~f1W2bYz&wmYk5s&Tmn_#Jiz0J%5z%n8VCi%qMx$%@+(4YqwOf)qVfxxx6BgF;$E73b$irM!Egj1vLZCA;Mp z{!u9|*RhrtHKvUzpH?y{j{&L_F5mJNmb~5*$mc{XDC~#Q>!f_F7*n1mabMR_v)amG z&}_mUe_^oN6M{2GhY*g$ZOdNm73=_S9Cl31#QV5`O%ayH1}G{<|9a7Ig^iWqc~Os< z!Kh-#e#2s6wYDj>X_3P)NYfl+?)q~4C^(1ib{qc@ALtR#@Tnm7txl>O{jsN8S&lRf zCNtl-s{r=fOS)W3gL9N(iMd46jEoti&nwx{Ck(v>T5QGxZlh^all= z?;AUYA4Iy;QUk3PJNK9pJFV4(XgKN7lsr&jbj~Sm$QSZ9*}v= z3NAQyJN}?N>$wG!%cQPQ)lz$Utj!dJdI@6b_9{DNe%^mRGmhnzHXVMg=kaRAo8)DS z$}`5H^pi;R{KK9JD3zM+W&cTJZY1EZu_u|djx3q9paY*X*|+j;3{cJ_B2E`i7^Hc) z6y1_!?0cZ7920e_4Ec*2Z%3;=0QSA--MEz<{UANvv>E~hw`YurAV0rsFoFAv(bm$I z+>)wrt~cAG*d$|0(G*ZtH{dg$72-{Ejd2)lKJw3Y@imkz#8UYfW7Ua@sZ1W@1^Caj z2nK5}+(Mnt5I|(J#So5NACNq0#n~@W>#ySEQ8A*vZHi!i1R{|n*2dJP$3y$9ZU*F{ zS^AgYJ0yGtGN64eFgJiz33406)q_wO-1B(f*$X;kG-P3hDAw0~$Mi5ol2HwgJ)#WC zjyIPYOXh>reL+U|V&5-(=i9^wKrLL;N7&=X-&L#a{SRRcMGLRJC#MtaSi8{wBOM7F_e4A(>&pt!_5w*8!e<0jG@W7H zJw8t>V2P&mpB=Co!ktarNL6WCYm_UzIpj{7=NN9^`7#xF9DS0-qrkqxAUVxr3g=4@ zv^!-2OdgnGi4D@FsTtJtF*9_4RL5XXsiLmps45^m^Zjk2bUXl#LqM>~F&H*jRhYb3 z)fTy^mg#ZYcJZLs9DHbPep6kw#d!ALa+46P{L*cbbg>jH`cGRg%b@}=q7UX1XwqXX zy9L^^FFF+vF&kDdx7V!|Mk1v9ImT|tLsx-br<~qLvq21Ly*$i|csi1Y(EMiuzN+!K zZM+0S*VmFm#2)yDP`&!4DlfhZ7w(<@Ls|U-MRTbDR9WU{g$j#Z<20^yREhtcsGUhecY=uVEU zdZN5@!d&Rfbm+zT5A5UVb*z3Q6W-aL40=o^GsR_z98LpT&kRTW7bjZ!7&y5N?;|q@ zQfE-TZ#_Ib?aP{LdmYYL?i6Wrq2qJOq>ujo=O$R9OeQ9tZ-bV~pk?u_UmRwhA|2TR z0U)s{>{PH(KF4K-WG$<>573*zDBwl3?%s?!u9qmOC_~;Hq)C$_~3%D z+;YlHGyN4l??po!>IA*a%!#D(55^Dhx0&e=og2sEGZaGiQ_+w5H zhl9LPWgeRPND+r5K@+x?4O_8G&Y9*?A~wfp+p>)$!8SO>*GVjBW)j74d)v1l2Ts%i zn~0>AyrIAaQR05hbI$Spc0Fb$P7RFYI6lpwPiQ!g1S#odTX zK3#dKEFL-=it*0#MYiic?ge{*SH{1?_K`<+XRkyn@%XpMtcIy0dGX!9F1R!vBp`Q* zTw;Z+?R<^p=FL2>FV)_zj4s_jVkn_f$qxx^OM2bf$(5-u_7XWe)al`r2yJq$%gpJs zaL(~AT~pM^FNHrI_7L$7az^$ow`Zj*#i<< z5}^z#LI!OTtnq#atF7a@&sJkO8bKKut$Evy=nJ@5_HCDaHH;gZm3Y6=IV(f(K^Ycx zEIw!^DC|~OqYwm;$1qt~eMk@e~tb)V)T?;;HqgJKu1{VKISC0Bxbp<~O z`#nr>z_A_`5LM^8;>Clsk`HaG!q+d#rEC_P(tsdhbj>1qj}3bq;i`zKEW0E)IQD8P zMkC-c+>E2-#YFc*j>ssq9MQyB^2ob=!T) z;mRBU&0w_XrsmO>ly%VCb~!7_taY-IiSYHi^AscQ?TrzMH$u z(MW(R?A2WIt9%htJMxA2GLq*IZA&IU(q75K=ckpOu^R>+%knj{QP+tT?pEB7B+qvu*_~ zsM2}zK<JXEwKjqsG>)ReRQT~MQ$KUw{X@iI#up6Q*aK465U$j#r&yG zh@Z>qJqUd1z1cdxi=qejT6!U7+m$)=O)lZ#)dvZtI$yW3)-qCNy#O@V5@E5M&V~(b z&5vN*w*_T;(2@2Rkyv<^W|5X{E37x~Bn&}uBk@Tkv1XqbT#`Vbgegr!7p)A4(`%g18v+ws@GR^2fn4J8yMNr} ziI>!(Tz(9b-`gV7>IH6M3##jm<24V$HY6r^-MA5AJt;!@-?x*3Ce@5O_f|W56Q@@q z?!F1Y5E+=1w)qFnVyP=wnCUEacxVZ0HD}*F;lt{}Un!_{CeFI`wzEnj)hcc;weA#fhX6 zJyokkb#nGt?p)&4<@t`+_Rg~E%GJxNXcm#z+^qb1oQwRpZx`%x!q2b;R%AgNhi_&D zJJKqTw7E_tUt?##c|sJ-=dDMEDNqhbtayMMr+huw0?&n#L4R3mUSTB4um*X? zDV~+L#=YXmclCdbwGDpfJW>a>|Cfu}AjG%5D(YXmKEN@=X~qpOFT zZxvoetCg+eT-magS3Eb8Zqbwq2~Jd87rIS)5%{#`byfFBvkYz5r1l#-=f{G8*50*S`oQqc>A}<7Dmx$Zu< z5~sU{vk`)r8B>r}m;ULz!ZCKfyciO+%>>G@siVhqcNKG+Tce(r0TePW^^k z)96~t#GgW!&-$B@nv`o?bNx}`>=HG{S$W{bq%>8GSH4)5idads??ehlC00usM-E{b zpwI%gj>m#+xId-EupDG!Mh!@^R1EwnJ=XM6V}GtCv2aSM4M)Kb**s*_I*Src(SYjb zA5)BGmm?8U0m2RFuFyWIjP0k~U@W6ejDx+SSuBaZz!LGaaOIg=!rxF3!vgC$nNcLB zoyu9asy-2WD?l)+2--w@9IhZK?)VZ4W!h7VM}Q&$X^~>3$94u+>*D4R5CB% zo~{(3O)ok8%IoUAxpg`g)lovfeK)Pl*upJ+RDka+9ZMkl4`H1j00>JQe=Q49lWi* z_-@=FbyJ6}J)J)|j&5X`GxL=2L#EZsfo#bCmgE-6QA# zjyg=gu@j&qXPjqF z!|bO8I}5m2C_3jeFL>jM-NmHal-sD~57MauQ8sG|&60nm=V85)?u$M0en>q={_4j; zyrfX-U>SEzr4WnZnfJ+*d5HaHSs@{WMs{+E^FP7-K?50qe$wkSprGr%dIuFT4S0Ti zkw8?c!>S~Ml6F`$uuJXI^5f-(d*j;g3w3YSO)W@ez(N)MQ1fW~r{>?Sb_4D5KzMSs z?kZ1SG7VAAe+#K-Om4a@Gneto`CU8iE>@j>{1Tizq%B0h0p(tlU!HJgZA{M8lHbG|I@QiVx zRHN4~BylV`;y!5htP48mcy)9y6TP2cQmBH%d-l3O_Kl2AZpfx1dg_f47V7D@H24J)Dq{BSwl97UsFdC!^4V*!_ETE%c^%gF95^`XZT>$Q^j*cn`=JjnL4bP zXLKC-T`NA&9cCCEqWS$9G##%7K{GtkyuKV;Sij#XVnx-9WHu%NuZM0#axvpFcj>Bd zPFt2S-#3kQi5vub^)akYV=_;q5d7RB(%>FW_hRmH3ejVs*->?^m;6hSVv$G(yhtK0Cd@K|Yb6DP>j6 z_eGN--nCL>HrW2m(Tuobb9xu}&&-ocVe?ww4L8`Z+{^Gx+TB9~st;c(0!0S86aIEu zO4%L(uCZ$FskxS{wJZvP_!wWR9RuIzby;#Y0=2Vp{c{|Qi8Z`9XlbEpY-pEg*hTjr zG{mW7*7R8x^}U1sfi8j0Se`8losf<^z}))ESLL_X-7B1QAmc3IZ0u3HHM?PQCMr=3$}Q~)m6isRL}rrQ%0BB=>QKO|RVQ+7IYM}?NkdvwEuTgx_p+YvP)w~MEP10}0Nn58;LHn*w}fm4o19-jksMs%XtLGZ!A!As&e zNyAB2KDH*RBII1!oI5uxPqC3?{UXS>OWg1G>;`Hr&@Vi*wNh@F`+O&E3SjEqEzWb{ z5MgkPUAQEhW&svn`6BqLhpFpOdr|%rU6EPNL4S3JvqG%cY()R#64#VBH*}0~?|9>% zB^nR=_riW5K$lEECssVI>*7ZsYJMrFahV<5*}5o265N?tEltjmk0_9E!}fD3pok`E z4A8Ax6T(!p6p`ISFWv5bBvn+=%V;+6ucGHM98HBTOncLWb;zGU=d5JzMNWq0*FaJp z_^t~e4~D9s?~gUM5Zo+#SKo}{{i1J8$H6@NG6>zfhbiFt8}Cmyww9TO+6=EKHlan_%t zdDY^*5@kH~0)o|XC!JFYeVa9@toGJ48;g{xT2oJppHI~1N2 zuw%bwg$s$lm7($7gICc25r(adJYOEFSK2a|>lZ*sqcT z0%nJFOlZ(;i_tGDrV=ID$CbsOJQB+_OP1BsAMGwTHSu;0=!=&dc0R*k)X5-qW$q?` z2pcUt*TV8S}8DZd7!VRK}tE}{7#~7Sa6R71f zd{m!A$WPF+YpszFRmh@>CxJM^Asu&SIVuk7P|Fe`QFqL1m~u>;GNN>yh&8iB8W25I zy=S12VCntgu{Mk~U1GfQu-d1D8z@(-TVQtdbg~Ne4aRJ5`a<{LYyvt{x~OU;sQU6$ za32RcU1{C+uCCse;BJ^R}mZy>Bpa+$0*_S6Q4?tX}2DV5RO zp?E1&VW8ZpAPynpqnba@cMDdaI9ebZWL*)Lo*NU^+~HJ%aGI?oB$mtC%6i}=(_lAl z<_1IfYIcoa;g-6r0Wl_)zp!MFi}gfR^jv+-#j38dh%G z-ZZ`zlOBU%ksgM;IsA~dBUY{xA1-bC@gCZXcy$|PHA~23?*A);a!&X)QkZ@j2Cvqy zW)LdeeRTC9v)$*I=}NB0Fb_ec;^HBO>FPVZ=2~&VaCJEGxZ>9{p)_U_)W!%-ui^>F zUfn_%)J{@2np?fOJv`KvH^LD6jd2q|)#^_dKiEYW4R8QY(_X~6BOqpEi3v{kUVQ@& zA@D(!5C`>2y63r$POC-y_|sx@;1rTQg(-Xhy%cr=delsQMl7;qpW_l*MuH~sEGMef z$HCU7DX6Q_oPq*b_dKaLamx6XvsvP*%&=sZ$^CcZ>2sg)^-hTRVQ=xq9rD=V>boCQ z(r4ID>QV;dovy;ca(~Djqi6!?$5fSjYu|%#(dYx+yXTg5LhUMtm60t;cd!0~DxSDQ ze_}x4V#%e^x}cdFffv;|pK#V?o{M@S!Ij#$oE!cnW5q}@LU~NYItNkOD>$COVELK zjWpJS8Ki8y7yoN*^a4}`A#WOe?wE3-w`Ht{ElDn3IpIo0HTGqAaGhi2p`ARNr_WF< zP25TUjuilg{s&mXk_H$mT?TLXRpy6`^|*j}(`yl?|@NFaDV^{_g~* zEYhCQ8_kSaHnsFiN8B-*cytQxc~J*Lm0&adB5c zci?P#ou%#p)l5VS4M@$E_}c9xv3FMSMQmRS{S79?6aA2^@||}5t7cvfM`Wkkk{0&| z@(+q)TU&k}m2<4gni=oQlsCDGBVKOM!s5!k)k5!|Tww*51_7^m%=XG1EwNSZps;>r z_pwj2*ZQ*Nw6!uDyf{IV;+T(ZS)c(&>`uSyq7VfSiVE4;4~go^);B&lMI-_%6;8Os z;YptL|F`3Ct!TNL!dzOjkBb#h#x`}=e)V3Fv}84`q0FGeWr0<)SmqA4N)QYZ z+=!ExwW&E&h8FFvvYb;^W6jbSpIEd+WwkAqwcN~_dTR@&NGqXQQm&YL_HkmUDJ?}b zcUM%Vn>nzeQ5*7!IUTA<b;>?<;vxWtTbTh96S!Mq%iHKhc!WsYKs$C=d|J#wFl7 z5Vcjg$HI|sJ!q&N9Hn$wX)B!&$L;+}MQFwQKi9cLm4z7FK2q1s?mX~?$%Pcrhja9K zvA%Z$%T$?bo?-cI`@n2t$jm-fuB>#}DjZus4iTztmt)V@9H1V#e5# zQSd(u+y2&yQOKvwhPvqouZlcKSPbbVeQLnPk+YAENAgv-oF;Q_kY#lDE{p?DaTlT; zDB~+Yjnb+=wSZ3yu@lwgQJA>}da-m_pE_lXIY{i&8jKUNg+kWCCJws@xl-H5SXB3uAWh zL=S#4&uP1mX1emy^0{^Aw3Sii-ISJTq$(g|jG(s1XRZIC3__rp*c8)_Q zAi9OrUT;W^JlFXxXTmUT7WK8C`PcIKg6z<(INK@Urt%<^JU+UxAbI6V%T;qP36C3W zUz6gHsO8<<+99BZtUQ%hg`3O|5xR{Bp3GAm>^xqryaJytlc)FvKmgOje|!El>9|}n zCbk*=JZbW$kRLi{HwYd=I20#nHGJ71$3pf-=_j5tkE2SI4oE&IxBAYlSN9p~tK zccS?`<@WKtLcVL~HTg#O-^K%CeHktG!cc))(QZZ4&Bh80>xF<8Om~A5u_mUNW$0LN z%LAJ3k{%)HTz4Uc=oNf#GfAGQ&^h#mPzB;+lU53@nu9i1CeW>lVf^3+4k`4s&k!X) z^^tc+dwbTu~h@#2;h^?CX zi|AEWg=GaeBp&;h+$(j}npP@g`(YE2Gb2R+&eE#_P~e{r1F?}w>(e-J$>k)@Hk9!L z(Vbbf3`f8D@Bqo@KKUn&uhWC5SD3-U%Z&*w))OFyA zgzKr;ok^?X{YN}g(wO8e%Q-j512*u5?MNjE)WIQAA1`bom+*VwYR8)*8yy@=fX!WA zr>+?p#FU^iv+XOJQr!WxK?&MQF1k>?^?dpke!;3BgUlsu+_vFWSqs9GaPcH)e73ES z+!l+X+G%Nmtye+!kHJeS+K0Eiq!NmWOO}GO%rr5YY6_W-&h(~UtF2Gg`l;jw(xPT3 z+I?daku?0jZQb6$@t<=<(NnF8*KwaK9%(jcoTr;{;gJcW1r!@%uG@n(;O2?fn00zf z1N2Z6FI96n_KoYLzVe05n-0q-^0x8X;P??eXLNxXmk`UZ_zFS%&JBLjDjE*%FRIvf zJ~gcFERfHMwgrbrKpD#q0R1C74*vT`Ij%&LkdkyF4gM>17>ZNph844;rm<$p?ngI} z2n8_04Z3&LyEyb+X^M?t2Z{MomC@Yv)#jJ$yj=%I&mUsV7oF5JOb~0eK7JJL(Mu5% zE%v+>uDjTC)1tQTFO&Hpz~V4Cs1jayjys1rbIv=ts#Ty>^w$~V(2LOIxFds@+S1ST zOfXV`mc;tJ#yoGs)&mh&V;a)P7D&>#gk3L-QI*h#+ve455E5?Nv3M=XVYfX4nAR<; zUfv^PoN5lCW)s-QKwfyly9KOWkB=f_1l!qp&UFZ3Cr@Lz7hFo7NCDnL~dLt=k z=}Q!E!#`T5NcPW=!2K@qqYWy!lH7m?rEiqzU-FuR05`t?Je1JI{|QfI_>Zb4dglLw zC$iEr{6{>Ijh^wp=|ueh4?NKYR0-*7lZS*JGbu)#6$|zsizpFIuQwzTWg{nn9ETj2 zBmxqjf(mF3X^uc#B+Qp#`>}HS{r!9DwY$!~`KaZ}z3Qm@>Nw(~Ivc0EgKG}1$WJKu zr3V;?EGNIohYbM)3GK%x0N~<6#5RHQ0uH6e>hJE+9}iLfTSw_JfKSF$0>Yoa-4qXz z7t%_JKm`L5Dega9%!i+c073koO0=K|RR(hJzX{w7>W3)?G6mgN6Xx{#8pO$wKd1bo z0o0zi#aCBU#I}2Dm)C_gg#;Ij@3(=Fgfs=K{Rhe(6q7LD4t?TRm%QzUGhgmTAt0cq zrw0gul@_q5v=D|BZw@WS0SL3NOD~6q&U25pgAXSR>xz{g5P)-T4D#j~+$zk8?_GdP zpO0w|Ds%ur=M2C$hL(c@<_!nN zUm)J*1|f(SdmqBduXDh!gF*v{j29UXA)xN}7{dNppx}^z2ceB}2=4msa}OaeqKgM1 z;N+E*leUa>3+I?*57hO0Snf_0^NEC#=n5s?#)b}L0{ZUKOTtbT9ohTxC!lxpB7pCM z5a?Hpv+vIfTrb(0XD2i!(H`y&opUiS_Z-3=-qfEEpojoIe0y;OgcHD^cm8Y;UlP^_ z*U)d40N?(zM{w{CqHTXTGpIVfHei@_cYSd44^e zy=HG;<&ZVJqrq5jw@@5nO)>g>HNHl+kcgoC^SXP#jc>l8U%yPhl#{=NpT9h@5v`S% zwv?;1kH3b&ZT;HczfFb8SJ48pK`e;eXkouD%)#IELmPCSZLOQWn#=MCPex-z*xJ86 zLT#x~Tks~e;G+E5KL~TW+!UY06CNg45Fc9}oL2tlw(W19P{{DJTb{m6VK9`teWPW@Fa|C=$-FkVz3rKgB zxq5kdh*Kz_@4-J{Lw*4vcA~Am0P^~IdBE7z&%J;IOny%L40f2O~yneoaf;>Du3POKc0p_oMH-3He_2_ufk?9zN zgLXX6zE1W#7cJa9bbp%l&+T8B7h!CE`Y>iyZXFT3lx|kn|48PLK9qlJ8$DJ|XpK5F zPO18DO55HSWF|gq(ge_0C%}xXXaFo0D&dLf*i5dz&>{YlgN#>$YrBJ_2X*SP>bF?d zow~b8#+{+a<$Uz0K386o=VC==Xe{dbQkRIkssDukhTC@;yN!c*_H0LrW1?yy^AhpE z5BuYt58aQm3EzytHi{t9;=7%O+sWq*H_RVEi8;?kxzl= z#F~1i8Jnal$C@ox+=xITGF~E8#+miPp4%fh85W$5hw`3G=(j`DUQU6Ug@h|iAUq@M zAg+-k0olLHm5zeNVqXv{x|Gx3qqQ@Y^v7CMfUlr z>s1fZB;h@eS}46g6gNr3jUV69AYXPe2<6-&DW6|)_kGx_v=&v-E_Dc|XGQe2t(-M2s05;ZK+>6QOtvT?j84TIhMVQo+y`reUvX)P=X&b>IyEux&$K<9Y#j6|?L zN&0Z6Mq~9=$6RFZ^v%YC&nfwBO0azyCQ;7v(BiHX56S*7+V> z%jEdHiynPoP1R4J>CM4uA9h7@Tu(xk#59o6|EyIpDb7AJtxOF8 zw=W*sP)CY)QRJD9Y~`!|eb9hdD1^^zgLX zS_!cDYpTck<`|mwU8fM%n{KLEp^#i7Y*6md+b4F=_2j~U*6D0snHMK6O2q7Hh_xMA zEz8}l+nxgFvi*{2j+0@2ZzE5K&V>RrzeY2{f^Oc918I=swOr~|@q9%j2x9Md(!^4z z3HvA~FD?Jlf6N3}``kK0j`zOd3Q+XW*Ia?;*bYB9Q==Z(k;|p>3%}UfPJ90`Lu&kG zg3>v$*(yA0N2nO{a{F--tLZEGm!p&WyT@#UG#L8ROe!e0mkwy<`Fq<l)>TNzIY$m84PWj}OXJ;PrQHHc^2lvK z;It3{;PAQL1R~bft?`Qaw>?>6E=y9o%%4cv}xbyxFYyFDTun8_4o%r3a`g4MCyI6oy@)eVB_vz(l$g4FJ z{Y*76*6l$DETa_?b+!1p4Fj!PWR=4jKDSAhN5l+yV};uTosM4-J683!u>1Gv{`^vu zH{!z9>?VxGWlSy(jd-Vf@#OgTtL=ciC2-)n%J@I=0Awx}cq}39!|?&64;Q|?cHINz z6;iTSqB98FD?;3++Hq9B0x)!xg0;a3b_m9qRS0}S#4sDj z)Z6(Bx2mCKh@z}k9d z!$T0B^9Mk~Lh5Z#brKM$$D##bS_ibqar)g!Rv<8UkaRT)-2|I1m7TWyLK>R>6FUK) zV#zHm3ldE4n1P#Omi|-^X~)2Zc z_qhqiAKdtj8|fR1>WiYqQLbo8*ZS_Me>SEw;j7R^2O1Yr_mF(B(HkvJj;zE0Q|R6t zq|UB3Q7h?}%MF$SZJt_kI?mD$c1GPvM>{FKln3#tn7$&D3ij#X(c_iV7RC@A%H$gZVaaEu^x!0!7@roZ%h)=vFAc!UbpFL&jB>jU0vx8rvX;z!rAz z57UBqI$mZ63IrRd4V99!=MoB)4iR?Cd6eF}X~2 z-zuES2jmNHYFEnD^E}6owmWpCZ-pC4aOWh3U8`hnRV8Km@g?Pna(K3PQpyoX#pSFm z>~ChYf+dl6CkrvUUgIy4ABV^0CS$2Ykj>wK!AG9%m}>}nesN2Nd&}R(bvJ`6Om$U6 z=qrfYD!HjUjR6!MI^}Q9qhi=Joj;JV560(ZC&p{Fvg@2*I3&I%S+te7dlXI%gz}@Q zx!>5#@>5X@TaUaPU_IwQ^+hSIc4Kp*e%8UGpBnA3iksrA(c z0n`K6q14(?SGzR^w!BQRxpFPdw02Yx@PfzKEFwRO^k9{|&}{tvi7TfaACF{yk`S}S zO_fFrsBCQmoonFvwpRpQrnF9%F`!qzI9b768|p9%XFxK)O^5}e{4Sr8-+d^3GxUdIqx33ZDxaYFtK%W zwyi{7f-$!rCK^4BjjS5vx{Pq)n%Ms|^sL5|N8N73Kte zz?2Fo2AyCx2o|M;@)oWb56+!hqKoKXMngM{P)0KNU#Z1Q@gFl>s?cG@Uis1A@$%tT z16=NvUk#24-kwS@0ggwh8Pc0u-m#Z$f-L)KCb(Aci^Pk+u;)#64*{zMS$;>Q$w5X7 z-ycG4@rCsbKVy1F&!{*UwTTMW{Pg|_PL92ziB?&?9T zc=9zJp~p%lwUDjkBF?0fX?F1;H}6^cM31+|m`CaGc-#PAkBg|t**BpLanDUr6(xD( zC?VQ;+Cqwr(o=owBz;SmG~J_?Eu1CBACdTK8P6$pu~Hz~fU02;`)UV~{htV@;KP;@ z8c4M}>;(_kSDPmxhSchjzRKCA1fcnDuwdZgA3ZM9u7lfuKeN>vxhIM=%B9FuFasW-i%(qRk~d<`M-xF!nqg9#!Cd!sVj(~*hKP;^V@K2T7?^=ShC{8 z2DJw+ykRM~wA4m6kJ@$lPC_=3q+&e>k+DDDe9DG5!RW+~=gljU-Ml|23?Ao|FFZKI znbOs+##xwx!k1rA;1o7nnET5dU3WIRCKIbM<~>XAQ)IZ+*8)n1nv zU(0Ouimn{;dJ{RRtzal;=FuE|LQbVy&^%jX*vipSI!tPYM=QFVuaVg4oR`T6utX?W zJ$|v?qcg46eO?Erl50jP?_D0doi5<+#VrlxoNisMH(M|md(wZ9h*kLP{{qfu#V9MC zKYxMJgct1d`*&_H^|^WOMjP*n=}oD_MBS3p!=Z(%ms!ILE}y<8bLdk8^dysMb{M!+{( z&Dy1Id$;0{lwkO@o?kjZm9Jn;;?J$xGg#O=zdjg(Ell0Z>PYPaP4}Li9!soh+HQOE zq$rfCP$b!9uiZc|-g!zw+1OprXNbh*2PyC6Y{8_UetJaM$^$$U)n)PQk91zU+FBgo zX=mMHZQ%r~e<4jSFSo+WT6TDuG0adT?YhA_ro%0Xa=7$PUKOF}ioA3J9DoE(MZmKVyC|B4WRY#Cv5zYX7|U7(3FQ z+=e@mFJ+l3Da>~goZVc5c8wbX0og%y+^}ZjiLkYTssW8Ih$~e3DjD#Hw_WH-T9$lu zl6lX8h#K*HcEa%5mo<#K2X~E9p`~Hl!rMc=C$Fb9meI2M*L#T072jodtMi;Q;RIGg z&3QU!i|$3kNNW+4MH+bU!s5Ai1nX$y7AibBcq2Ld%xc=}LnARL(#8kF3Qc8>onCC5 z*61IVaZG_$`m|cI!A6zg*mrxqv$#~>ov4f;A6sF3eS%Wh>Z`ilIUyVA;W~(JCf~#m zCryvH9llbcyxC%eBH;!}=vFOn=8iIxsdfOL=}=6d8h(wgxKE%Xj2uglN|@A+<|t0Mo?S91gBpNm0?&O+9rfXqTu zUfUe+JBdY1;t5B;>P1H8#KKNt?mQz{Cer?Pwsg}~JvHo^w>g1ArS!P06*xm+ zCH{#Q(x0E5&7RUKLr+4;HZIr5#c}GU=xCDGEz}>Odx)b`b17pf0Pe`fu#L$p4`f{u zT>MpmHC)K29)RI+p9fR4in;;DA6EG@KssSmf6D0r6U%i?7~*C&IwYwhMpk|U0`{sT zZG}Cxb37+RZtisau>eqXkyO;GNL6m3Ec$?AU# z&KHLh&O!$2#yGvj%Sa9sh+kG6IQ`Zy+om<#>)3O?;ofY6oAF-o`RU!n>t!fA;uyNa zj-CJXo4=50WKpePosV?fmboPp?WRt4GS_#ZAh7E1SbW%k0>$q|AVn}hz>2LG(4U+u)cRDR z$NINPHbw1s>@tG6YYHv#TIGPH)@Y-$-%iJ(t6+R*>^+Wq4N(v8W6xb!10hEkUuN@2C&&T?ukjNqouiPW6Do1U zena)HmBsBDvne*gAZO(5y^?H(^hizmKfVl=q5veFmjWDVcwi7Grn8#=ewmW^WvIYR zj7VZwbUb4pa)j$#6zx!7qodDU`8tu&<-!Pd#t4*r6 zhJRv8<_&Mt0m<^`>2RY3;2bk^UE(7Sgj&4$OG8^_Ef+zWJhsTq1oVNb%SrKStObSA z)jw5Jk!rhuVnQkz*bN#09P_JDY}I;SsJWfZwroySYaA1 zhgtu0e&N+_yr%=ofuv`FtKP#eo#+}VOEGi4BB_#dZzEhfD4Kpu`_1gO^<+Px`}u@seQpYhUnk?%RI%$=Y&K zwcDBhAgppV_HNyB51icAbKzN#fUCO&ytM}kUO$^ z{t`Ef>e#WN29B%F!XCQ6HkDH+2IOhWQ3uL9^WH>UJ(@3bq1jL{mGe`dbm1Hlb)MLC zb`uZVfngUfXh@88{ey6>5VL;Oug*ehcB0&%g?iTkX}yZz&$X{G8_{k0 zDM^cT;F;-W(QSWX;-?*N%?TuKw+xHnpIR-({N~GsK22+=gR<^A*Xow+R`03Jk7LZc zKRQ99u=Hy}TznH_$rQp}+Mz2$lh`Go4INWT?#)cp0c3TsYNB;1?YY08@l)kFBL zU^n`Q`(QXaS6EOnWD*kR9apVAOD5A}Ae7m0A@^qL&_DGlFzBivvtXX1<~>a%9>gbM z*4%Q}UFhz(61p=5swFj8_!6Z)^|$1a$&qhIA{P>Zgm>}hSd?o)YzvD3$l#NkHX2D! z!$d3usexriT`{Q>?L9Qmxrs?*{N(CB9V<8Zz9&kb^ndKiEALEqIH{_(8=?)^_pCo7 zk#!}ZGPalo23cak;+7VWiM$qfOJ0)HsT&^O!_Mp!-}+KP6uA~LM5U3JQ}R2phSFOf z*>22F&h7X%)szt3cTevVqxwAxEBxL)i03)W6wKdLGQ9;j`1US6#uN+cbBSuGo8iH0 z8tpQ{uTr%*tRGH%Mg%})l_)Hcvf`lKh(Y`0Z&DOR;0P`w;Qob8Rcr1@umosx#4~cQ z%7i8gR-3waweVPRe9BxvfFu7H$b};EjrltI*==2jM#?^V;r`69(h9l$22z(7eQbYC2 zptqGCkM!pB#1%z-WXtSmhnS1yT+O)YlIrczUczN3^)SV;+AkcMJ-PWh8n4u4)Nk#L zvK}=PVwKUggBv@1SpoBs7B4G4X;$)NBg?4;7f{G_H)Qi>mIzxh# ze)_+QwSK&HFI~<91X11=I!EuUmi|KNAh(iQnB3%C*=soq_Hk>#$l;?bBOCvw{)hYVdq1<`Gi{?jSDti+UfyB=9!% zsQT}SV>(1Mqcj6At<6)w2glPSYi|ZB*xI5aCd>BL(X+`|KT;18_2^195$F-jKg~~pvh3?L-t&E#^7w#%yx-pzd?CBTpCpM zBuKfyx@#&7j{~kW+%7{5d}R;oo{if%7)8(9Xv#^D+YQ$F;oiR-k??Sf8yN7=w8PI5 zE*$WOe*rcLQ{zpcffV7)4>;QXSj8dA@*yb9VCeBGQHBT+i%zRJlP4UXv`=Az@7uIm zNo_qLQ|um2J%&8^ZmDiXVA&Oe9*kuPjmA2X9OktlbCu%!de>te+t;J;fiO5bSgTU5 z-&j-r>Nl1#b~WcSXV^vbo;>Cj_!1hQzI$4g4*AEQXG*5D5j+B^Jx&e!5piUU~iV9JeMYpX&JS03k+Y~;a=Blb%xP81|q2A6t*I9AAlGto;3D4+JSam$isaA zWc+M#e=HYVvcXUNve~e(Miz&`VwYm&U6tE?prT47N^ixHZhy;{_)yXK-w=XdXA!=g zp(Q>y_kW;)|7SR2W%|$b+xEoB!v3G>e;bb289Dy%2tgaD@}dtGTP(A<8&~|yJjwPp z3D5vKJvtUcN3l?c6hg5OzaXXsAVmT#Bq-z=LWG;A*Us!0_s0FV9G`fPIbG`naf{w>W+ zukb9o+Nk~oz(ZejA%I(OdnQ+4VEBOKARwXbL^|C1E&6N#j9h*EGRXM{K%rkI)o*El zY`by}0H0l-KfxadUsMPn&ztL*Ac0(+>Vw|+^j`irAW&eZuX1moT9O zTMm9Xa)|q2U<4P}gD++6vh;0eQ#W?wa6nDXA0mS*gCVmJU=B|JRTSS10)lNn{g?d^ z{`B(N!oulz0Is0^-2!mly-4WqZT@~#euLt0fWEZ$X#O~fVC(>f;G({}@9kP%fq)Qf z@b>;Yy?=ga_U<2mtqJf!`oOH=1NOejIFZ0MzetEaZouxq(t#5WM&SXzJ-;4|1G4G0 z*kR5e@E&$(ju(Hmb_}T}??P{QC0*QGSi7S{_;9<3Xn;VkZ*L+1g};l6|4;0L9O$>{ z57u&X=qJZ^FJWc>*UYQ9UMBm2r^aeN@2cWnF z`tE4lmWo#W%MBvL>8e@|&N%0de#t&?_GTLf;8YfJfU8Fg`G+7e68b8gW%G z1A(zA8e1Fm)|Hw|_0KOSvn7CQYddza_YzMC{m}aPK?@Yr-H*TZhQTh*ICUqZ{$Wys zU4u58rZBbKJaa1C^i6I6a&ale2QE`>of21jFK1I#AkQ0`tXw)&kD7Hehi%D#BFA77m~IcnX=9S(MdOl0Ky!7WE8a+x@NS zym;30r0$Kj3q#I9W++`IGBkeVa$U&FW@M}@1e3)>5J~31H2X-e%!Ju1-~$)Y8*dj^ z^1at&fSbqC)%D5imd_`2+a_PsDq74Ln4CGKmcw92>=B>IO`-Nx!v$5ce|&=LMFy# zziLW9*|fA)m|;)~<^DzpkAo~~pFvs6h04=@<5 zEcQR8rA;aP%FVXA)d%1~#`%$}csYPgMWWt^hQUQe8&;QKdBS1~wmVO)f0stL1*cPz zJ)boS@qa8dc9Xn2+w$&yBTF&hZ>5e;3ULMV6*_o9tkt?c`8V#|2y$s}wuW`BK{Pg# zTFrOo*kAEWrs^Vw@f6kQn(N8B7KbEfrC zN3KQB0h6;(Y91m0kOZ6BZEd@v%_~f*4t&mCZP zHvyemsHC-jBMCHV(iKbvt4hdzn^{9lAs6wWWL#3Rp<>x%=%J&qxBNaYjRf*kR{dgsw;ZEYt=Qk-FeUd=RZG9Hx8^7guFTpt`8gO{+H3rq|7A z8&)&NA%$iMT{WZjY&pInnS5L-mVs}t+0yFRLDDG$&=AEtYR%bzZin+ zK!ADr&KN^rLg_N2w=S+ywL2+eP~|ZQ?T6>dHSl!4_&Fjgk$x zv`w`%7ls-y`lHk0{-j0}C6FtzxCJ}~D-9=FqRCkH)X8W?L7UBFP?!tSl&l!l@p%o1 zMHx)dD6%m=kQx?fF(0aTK76T31i;MeNs>@N!-;JG`>Mh}Ur~pr0Wsh(pnMxyoA~6T zmynyi=JODhT~Dm)tj_84SK~A-rI|L5wUG(g{>fIKcUGq_R%UO=%%pq8^7d)TN(1`W zbSH@uExMFKll*?c6H{(QK!!sx@wF+rjzPrlxQ>+UrGZxa=pAxjg?wH{EeoVzt;YNS zDmv92Rn=k@N~qht5U>wP#w|}__6VqqE8)3tSmv;>TdT3{+u_}HwXgI9JE#pg7v6zeq{y-{ zE{Zs2f9?_te>lN2kIzkTU!HHO(2`?xL`_5>G=gLZuS@%KxJ@UGmlBChvAV8v`t!*q zYDj04EVdxly(G+ObGXG?rCYDV+(R?-_8)Zq?ff&adh9+h;Yp{t(Mc-#UAEYO6|Uam z;~z_;@R(k%oH*c^Z06X(@neN5Lq}$nD86P(>YQBWBM0MLgZ5*GY1+Uk?}c}<&BzC* z>%Bxx3!m_Aj|n2JI8b7Sk*)$0u4$aQEOt6E^kmpSh#M2ss~L$!NsVEdA)zli>=s$f zncbUexn6&1@Z|Hprz?CL(5zJa@_YaKwtNTtsEBqt}0#ASwfouDQ3cW*nluJbAKg-x2%*Qo>JDa?hPaaV^!`tou zTB+E(4t3QE4zkHz-DpWu5(2uDc)jj4+&@rbzCj<7Bkv5CI=>;k2OTU zyy7iY5yz{=nqI#}f}xcoZ=gC8zH`(JFE(sbJ~}}drj_!iAC`Ii%@hKko!ACpQF_Ig z;Oh_*&-ajN83KQO>kKcnxW)2@t~>O1$BfJb=`pR8>qzmfQNbvY&v`|YqI=I5PXY(!wcxqc^JLOrs1JiYT;4tCAPpTyfsHy+Lh?=3 z$8b{yj+T9BkSmKb?G#cRylybb3On=!wiZeou#b4}&wpcd@o92v!t$X?ovz+4H0i}U zjUOGh5|cpeKpE$4OdA$ zR2l;4LqVmiyI99#ALE-3{f_!2YBW*sT{B{P|Afhc1Thc7q{zP9=niRN=|;N0sm zF-Z6>KO82RCzzk#s$W?DAu@zFe>o(?VP*azO)|sTS`5C~ zM8Ynn#(Z`qFLp5IHJqeTlY~Rke)=`G>7T%kjSTHL{@mS+na$N-ipf(RH6ml(^AIP; zJ2p>ezuVW77q?TF$7(G{ay>1ny@ahrBEQ4K{%u+TLD9)T$B}IB_h?w5kso#!ZaqwX zKfwo1@mPLy_pRvGus*iK#52J8-O-)CdA+_bRswSen5C!4 z?r_$AsdJd?uw>IyH|7dgptfL|asXV~GKXT1xcj zw5n+&?~!rZ)#nb!yrcutF{>NMW|plJ+gl|zfMslTv9cI+Qw`^K$O{IUT6>Y;cadmD z&kJkJi=swpT_WzBJm6zX09?N1yLS?zU?lR}*QZeZx$Rq7rF$CUz4B~2ldG*kGOihR zk##qSH~?OCqe>cr*`+HrX%nVjdIHE?XSTw*FhH`D2>qzUvUpjkv8UyGVZh_=<B{5mgw{{VjpVy-C(KuKbypZk z0e#2O$9Z)Dmyi39H8Qe^Gva75-n8}&+}D)~b*^C(oUbktVDNH?tI+)(^71~cLQ^sh zmMC#J$r`DFeA1wSIycj^hkDV>cy{Tj>R^i%M%hXC_kQ9Qt9WXt-+(mB#U{azSe4P2 z2nJdXOcL`)GqD@j!yoMm{J?WFnK&pQpSA3lEj$wpA81rJgTLp(G|N_c?3>0^^D_z- z?COJK$)x;ObXYzo=JWhOT!_pms&uz08ERX8q$NHWzIB6Op>lX9Cz2LMBec`ZbR+Fw zT~6jp6;oojNIket5se`3u1GZ<^Fev}r_KKyEfgMM>VjAkyjPz~@)Q~0>>X~L>UKTO zo2d5Lgs8?Io=7zYTI`!L(63Vw~2M0-474TcB39((!k}r zGt($M^_mLjZB{16-n3<}S#rCInWP=AlygypT03%5iDa(>uM*FF20EymSHfS6o>IJ- zw^PC}F1@=9;1Iv)W#{X&KF-5qlJ-ZIA2arN))@8?ubitF8Sq-9+x?kX#Qu%7ZCgl9 z`)+J_?v>06J;!90QA7Lw`72x!edP($?#-|IqH>d})JgLuSzBq*dIBz41%4bp4(f#i z+ri$gHl;RYS3G9U8#Z-3ak(}D704b=4MJtU0O?wKR;r-R-VCIC=4sK`^XEi@a;-;m zatPhg=`6qYh|H;LT#dAp;5-s2q;rvI;aO#kcI8iQachTtzM50E(Z6F&o-tC|!}2Us zyY>kR+pfBj<;YESywDrY-SG`&Chvm!cM*B45{ZWfukN&h+Auw&5HGI__p1`ye@?Wy zXv;^SqO(lr$+OY4E*TrlBZP!)l$(5+E`cHvCjKdx7AI>6TACZy(_j)_WYl-INUlsQ zxkKuwzpZaOBzdw)c0MUteX1$u?q816(kcH!`AQtRWnAX!)~TH3cNVM}voig$UPzi8 z*UOw$hTn{gFfr1MsPo37Q5m=Ypqf;)#OL+{zKKsgygdN@iQ&)*d*{CbdoXowHmJ%e zH-lOW3q|Rn!n?9>vB#AuDI3uR-|?ah{!~@n&r>k7>ebLP^~KDO3z9$&Y({u2zQnle zXz@?dDR_e164Ft=6+xJn9c(z+kX^NiA1RE`t6f=&%%8Fr)NWsC7>0*Lwv=EroCS~A z6V5;{y+}kixQ9=4D3p?sKz4UoT_QHQ$AFD01n7F%=}@{X$idRE?tzm@&18;g@AgZg z-nykd&e&w43H}?WECX^PS|0*eru> z*W(}4(6x9x{hdL<-MhF4kJ=xHyUogTx7Ei&h9}W$g7rGH32^V09+;OBeT?H#N(jBG zw)HwJgJ(oYKYiKosc@60IvMlJ$bPtAMN-9DHuB`;T0dQR|I+y>Euoa)9_v@dJR2t)|x}4rj z=h)pG<38Yl!CNv-0XlxBOC+b=V9tz(+i=*0Q4K*DOoiu!)1$9V5uPKh;Nr%H_E41y ze+$+NC(=|v*q<^_Ou#(o9Xo6s7|G*}XyAw$qg)@D!B&xFg zfqS?m#6`@OIkufMDRM{1aW7nql%9-bU6jS(O-|a5StJM~5y=A+p5hV?$volujMDYQ zC?|@D6&y=DLqoImk;u0vE$mUw)~?;C;vPPG;pA0TEID0ksRN0xEf^M{Me485=K!>= zkjF& z_M;o9 z{(_vi=9m}s@Mmn+d1^yRYq(B(+n(ktWz8!H?#wQ18N6LVvJIiRC*`HgxRVtTh2OfD z)Qd6H26K{%kZSKiv1H~M55rJVX}$uBy{7f_OP&=*RZ=`KsGS%GjtU<{dc?FADR^=} zX#C8!ODoPl!osX7|C&+RRfUru-+;~#KRW~VN>ZdsyBzEAm08if^vsbj;$WcXKg4qr2o_?}#_((EF>zpTM zpRIOjmXZoq#Me3$`H!5ad<Z_y-DI$Nxdz#Q0len!dx~`5rHjDuT{NIvN+C!9 zJgS3hfi`SgcV%**c8J}oc+{JW+@38}?`@O~OiGYLV3snw-z5ioHjc$v2Iz(R&fcf4 z2c5M}I|kq+ZQL3+_hgG{_U;KoF4t5P{6UR|QwG{>?R@fz$K(b+?MW(m;FclbnlpMM zxks{c{XXGq!*A8_uWQKH2VID+%D6zh-uoUAo(I;vBRNr(o8SdOsI|voSrD@|?k3RV zFkIYp4jDO5QMq0QV-W2ccMtqW5|bny)Hew0kiv6IZ)3J^j^r>y&hWvDDp^5^s@bum zzj$wTS-{-K*E8*N5P7%nr4pUTM?~?{GgeSmOBZ(OI+S_r^j>?Nv6N0}=IkSKiAMBw zLXJ6FDBai-y8y)B(V?p=eJVa1boe%Y6{|EM_H|={+8r8!MWqLUXCXYQ+ zO5gZEnzqkF^L0sF+`4)F__?O!EF+)Yy6{DH;Z z`*E2*c>}_0C1wlnjLIj+){GM2N~14kRCMKULx{f;$>R`z2|JcD{UW3vcDFP+z0}Rvq_qQD}W$1(R|QmxIFI*gUO! zngmcJ!4G_?1?SaYYLsh79ZR;;dV1We&nUK)c1I{BS)Q(^6-O`tGr{_)tp0Hn;__NL zCZ~hqB_c5Q!0llcI;?%>Tr|1V39Pofoby*NCEgIBf;t^6rcQUc@6i=$Jfz})$gP@; z)e9_IWy<9ui}Crkrg-Hg$lBOZ73@u0nZ$HAg_BKw64>!64r&CIn0k132ZE68r>4nd*T62AAS>5oVFaGVnqQ z8Si+A%`-bJ4H>@`fCtL!%I)Y82j;!swuszj)0H_uf}MCdhxG1s)S-*5`%Ao&JEKsE zgv)5bFROn@fxHAH1^(D34)G2MUXWJfm|IoRkyHALMcY0&6;!m`4{!E#BYccoaqSHp z!B2QcQurvv;f`zP+H}~ZpwUJ;tU5i$J^I=^7L0qc^-L5;o$WGgYN76;; zh%89r;MFGCzim+9#ytO^{Q^3Eb){SOzL2p4d4%z4tzmeq8Gg@`NeNzDl~pmFP8{>{ z!Rzb>N47m@0PmG(u+`@3Zm8_WU@zv>PV&)0&HCkAFkt19cTMI@Q`SQVUQ2q{d%ojY z07|SHPwfsb2XYR5aRi0X0xYrPsjsdLI??6_<4^-=NDZaO@D6)3sh|^0VC)rn+{^NN zTKgbJ!NsEjrT#Eh4ewf?L0@oyA|t~>+A*Nw=d;3Ydz4?+0(CT9%szl*dJ)zVFzaMe z%wtUK3SK%$fJzbcV#U_Yk~8Oq8ohR3mC?4h+Zu=+;&F6$a7{dtY(WMR4~AzK>-wk+ z+TS2iS;{EzQcsonvzY^&sJ<p;W&^r zAm@>Aff677-kMv`Gki<_Lj|Vhh!YtP0rWfU$b>-u%^yCf<#40LocEd5)?TRG=`4ZC zaq~;RUVWR%_?&_VAX!XTT*7XpiqK&Ff(z6mY z$l9|`kLpZM*w)E@Jo4~;9Y;Jz*-+uuKN%E_yjR(v?{cVl;Z_gsy6(ewk;63EgM3$Z z-Do{{KH0A8_rdkj4&q8&SP3y|!9@jJK!=%&0a?moFpb8^IGG*DDm>91o}_+@k4!9{ z>qJ}VKkt`9xU>91Wi=_B2$-mYQFpp*p876Nwb|4&d zcn3|1JHFqQOq}n0gVuFN`;i7W#ihR`hx1rWj&P$mU!SuV%D3$IUG%J4vqmx585yQ2 z%b9>g4He_$S!KMBY8^-2HIa|f+fFVshB&f1WN~sNqj|+T0VL<+RQdGXUl=tRPwudt zGiqHiil#57w>8qd$ijD8Q3m9g4>x(C>X3+%{gCVk z{MTey4LFumN(VQyM@pNSsC-vXhdU^jJSJ(aV-nn@K)+bSMpSwv2r1wko2=b<8c7Cg zl=b^J*Yq^m#9iJQ0AN{MM!q{TU)CPLMQW5M9|9UE3Xm=M6ev98A|IO=XARsZ5Tid$ z@aYhX&g)}kJg$ELkzFt${~O}K^4|~#R(jU|Kn;w)zym$={~!N1g_M)uP*V_*UK4|igUmyO#*b=lb9zZ`WJM%HW^82w^Lk+%LPUh@O3z>qw6PJ6 z&YocpxFj77NJuIQU}_40Oh!hAjlsXRGP4b6Zh8%pudJY4R9H~(MK{Yw0U-49gYo9I zfM{+CjQ{g-U}$J!WoBb|@QAkm^PZm=0ogac1)>l2mk|(Ra@>{1~A53COFKimveG4tLHJZ1#7>6~reN*jncIG;<4!<9At!-|+XqXACC> zfDJaFEUB&R&k`duAUZJ4RW;1k&&oHn=?TCm8myUEe$2WbLp~^bdO8L>x>g1|=Xc0k z)Yq)@ca>b<&q{YdPEN{4uk7YG)rFq}04GPLdd9*a1H(^^#o=RX3&tE+>|UNo!e54F zP%O}k6$7d|6eQn(*Xgd;vKp{KOqfQFiw6t2FtA(U8wm6bC)34o)YoQcODAHp9t z@y{K?TfeBTAG`hUGSQz+l5fB6*&j%nV`~!Prd+gPK-~Spx>X+qd-5y__+e%j0D`4jy?*I6+H$}08C%2rp*z5XAt2CV^C#PeM+LxP;sW=N34-kFpE>;UD}Sa# zFa2pWfyu`9w*{!_rD0S;$v5rVg3W&Me8GhG`^&1eKfrImV z`drod*}VPv`_sHnN@`0gYEKo_BDxiTT7h99+pNwZoi2OB=Tb@mFZ$6?Q{j;~OZ#}wD@p$8sK`3rt$q>vmFYAU zzci;p#8Y=#%1*$%k)aaz@>4;6iN-gKF#S^B!N1+J@SenB{6&P!=daK`gJeZq|LNxn zM4+aYy{Bld{pX`N13M@8W9JE2qa9uxDHm93^d`V0*;z9C{J74}UQhoi^8IqiHiku9 z2iMXH^t89h0wtyZ(%o0_GG^-N8lf)UbRThz7SwTL;H?Ph%3p2uzKb;t&blB_?T6G> zKu!m@SQ(rKDThF6+NcP8^P(+SSfB{FXcq%XZnX)w1n4hba>C$i&OTbeSMAB# z)6f;K`$kexhxvgoUk;+EUPbEn1{~S2O+Y0?ZF)d4PU^GK-F)Rv=rcU(_|M=1jTT_F zt8_}D?6;xQ7Bz1^YHj{WoU%Bu%NY5oMyjiX@v3`IJGr)$wJC5?IIv-?Cp9#_%?N`8ML5g}aVk#$wx*k^v*FlCUe&LfY?%QmR2lf zX(T#^CkRH8KmR9y=y=rmkIG4Om78oZ@2*@Dx;R{Cj9twPFBH&Zo9;^=JrWgFeWE8w zuJ_!86SS#hU{9buZX}`YMygl3NXq+ia*buGCntuc>QlkwoGx2uoipbUD{1Q)j(Y_D zv>70f)=Pdnc*66mOMu$GAU4dMCg_*#(oJ!60GOQ$~tE0a7{n|c;@D?}DXanYzy z6iduXFmOI!JNWH1`Wuku+%T9b+Gjoyr~65eW`yN^LMXJhvYM~mAl}>$RC5PoMqEQZ zg;an1I>z}4vE1T!kIJNgT13Z{kb*r}a~bT5!p@dcM8?Y#SEZ#}6i_5JJ#!mcjR@5WD>h)e1fIWCAq%Esa8(60t~W-d4?;ERqt% zplZm$9q4t_Ic*N4)M-6&mv)Z~*1HX=EB>0S+f(p9wF(lxsUQ;f^9UZq-FasT; zecmMdxX;a|6j~xT7?r*eNv3NJRrEzC3h0|duJ;%Bp(3H{xA?aAv*v-c=+|@#dV$By z-r!{_W;D-u8HF>d0b`p3E5>JL`ix;o`s+?R4!Ff*(n9`nAc>+HH5|h7cP&?|jAo z39ISWZ2$!W@hERQXU3BU(BwL7Ta0!9W3imCecM!C4765)j`5?d-PRM-e}w76kcVBS zoWyJd>GnR72s|Z$(a7H6- zX3xYA2poK>bZ{eS)7QozT3|v`+ETQAj)lg)2@gQQu_np*%&+Bwg- ztvG+{po7_H53|I9#Jckn5DlnizWm;89s@)%SX2kTOYp07jE+DRtohXT>Tv0*Q*$hX zr+hJxIBOfpePwl=`QRCAg_wH~0JP>(Dk0!gL6sM?s69cwpa^Orh9DZDxXtA3JiRPL zeJb`zL{+LD!@demXmq%h(eJ_b{a~UA@JA``Mrr{t>S)s)M_ozI4Fz1g^-*+2ioGz* zP-QJR^9ds7(|x^3$Qw+OF)YJWeUAaIuZ%vqFnn?3#AtU$kV1Wzrf{xr#IB^WkMQ@k zln_ux3F!VKtE*x@-}DP?-uCTW0bwK>a+yR4Bt-)dw~M35vpjBNA1PVmNA&}2?ndfN zlAsN%<*%MsPwUmR$^C^yHkYCc3`rpC=VFT(?@?U+gy|&}ao~p9v-WM}J`BnT zVmOm8zD^#eEzyGg#^}qjNB8*g2OBemAqk|A?T|E=_|nci;LGdrK4PD(%1ZpfYD{@( z|CO9bM~71|j2X+@xZSE{Pftu(0PHldY%`c!Z#-h3@1S!vLA{!PrBFmRs%~2#KVyQ! zgnT(V3|)>)Gq%QAgrL?|V=KG2eGe>S06L2wWXUXt`2cKOJQtFE03Crl0hR2!@{-Za z*M0p!KVf&dDlatmz^L&K+yz|Nm{5bp0koSdx|oXF_r_5J2L$*9N|I+@tv1HMDB|yd z+^@*;a^dJEgKDD{B8vHwJo+7Mk?qni5bvB|aLAbR3U^+EYAYiU&80r_tdQuMyV}uh z_W%lnlO6k~Qdqna77rJ@)Fgmx5)k&2I)uuQurkFB9x^YkXiVjweQLOR_9)M%uj_Bb z47YRIyFUiMaXgteV#7?yG@cz;H!eGSB#N*nK1zNsns{wLcR`_I$+IP!^=$TS+jP^u zNGhGuICxqTeoA~}alZbAQGAvfn9<9?K#0ItGYx)7bvuuIz!Uo2==)ZF!?+mf*S}oq zC4;N#lH_HdUPwUeU&pW3M2#9WRm~k{bCQj89WlmDmar}pTV0kD#44#|G^)v9N*KI~ z10sCvAX7s3kAq1rLHc3ZtZX-~u?^*4o~WWHs@Eyq@fC(A{3YIKk`1=Ll=BQ;l6a-JNVDBKsyn1|jcaaN zcduky5z}x^lSKu|zfzua1BQ9S^Nd*nnNhxj)XsP!Omu@;AyanG`p%Iyw-x{3zDLI* z^Jn1|(ALUIJt{sJfdR7bOQl`Gn?T2x36YA3x)LhXkhE5+7?jAl9PFE1O{-zM|@LiTV(~h1#lu<#Gb$z<5V}-9-sQ?!NU!- zwETM%%jDq^lL|_w-0xD0Y7*frnmW%T7U>*o7o z54J1mflnR7%?@#AH!HcU4{9slq0`O$-_3Uj73M^?7Afv?&5BujGlMkaV&=>QE>6u( zRsw9w+B%Fp zHpprw;9ZwhOuWn{k>#sr<`fw8jB4#3S|ESvRvo>OaAJhuBf1GwU5`lA?}Zo>laSw* zyej4?Ii<%~XC9X-md%!e#;IMuw9~Wk#quW&^zGX=O6(P^@^^PlQ#>@2-O_;@=Fv`Q ze!EZGZOTJE_O#L5tcofc#T!RXYljcuJ3wo*JU7pLpwzKgoiD6FJpiVgd-_GQjT$1) zlFLnX$T2m`Xe$n< z_ziOO49OcMGhnI+hri{Y^s68%91MGh()H%h0wr<$=gqt;-X=t!#Lk{!c-VtZj+QfB z@t4nJAY2~(ySf1{asuk|V__abrQb9uR^RhGSsu&aZ)lJ~5p@;+jT6-i;<-3)CB zEi0iP>0iKl4xT5WJ$e8yEEW-S%SzC;b6{$w_E0&A&pemrSz~Gf_daapdg7pFFX4Pm zxSD@+OX|2-X|zxtEj0v*7I5dSk(&g-hcVvv+ym@$d%X`5>X&=lWtFe7Bh{`-NA&4k zgZ`dqdYa(2xos)Y>JZJZ6y6K}MlNrzddhE(3ruFJ(9YfAtt`#oH{KX1HV6|r$javo zY>nMe8PW<7uK=2yB?xnH5DCGrgWql1GZ()4;1i$EI-MjYEIgi<_AF24VlB3^NfsDp z5FY6usB-?D&6MxFMDR40NNBhB5k#%=V(=21855pmO&{{C&HIS!WLT$fZtazBC4ZO7`t+WRdZ6W8i?lx1nizKF14}aS zL?+LLfbr>0zm7XMOMLwEZIaqJl(ElL@h8|2F0$HBU};8RpOj0sL)TW%G^-HEg{yc& z$%70PLrYN9WXaVyqBTFRU~+AF10KN6gmqq-oog6OqYJzW^@KN%+CXePHz0899dxE1&%M^H;A31nZM_ul{0FUafWu_BfiU(^>b9@Pn1RhAVV; zN$Y*dnOD1{<&e`Z9#)hqgwdJqjq0^9;P?!4_%cIG@qxX$mTg%f9m9t~>&eVBVD5TW zZSU~TPjXlT%cV!aaqHzNYUK^x$bsH*tXEav1WeohM7Xs7X|4!)aLBgOuIR&Sw$E-t zBvweQ)%Tj-iyYsQGESSa-y*p065#_Zc|Wb$X_Sw$!W7nz{QfMMY(QAZoN%xLXWTVb zm`~XvyYx_W0E&yw%N;#U4cS3Ea1`NnFJCm}O!I*&B-&}<23>7ml0?o$XWOn&*?+!i zsq=K}^l8;zf1`@O_xY#_sB8YAWnP^SS`a$&iLAiv5N6LP%1^u-iFbz<;~w6jIFd@Pf6g1FvA$cH_DMBlq;%V8vH2uo&+U89K$`ORVsWsuukuQq z<`_1Hb=wxpvivJjX_KEb0bwB#MyAneXA7pZmguURi>4(!tku_qU_Sm=pDv2W&;iA} zorbuL z`x<<>H8=Xw0u77OUt{T+E!2b_yT=(8v*&>D!n4>VYm;YT0wb@_N@C^vZ2OdColT`& z_$tzYmzfnQE(9&#QD&uJy1y04=2l9g)Pz#i`67>$aJ4Y}93$)HJB zjI+q7L{<&PMwhJ>o_`IQcsU1x@Wu(Xtd= zf%J#ly{h#aJKfTV(I5(M9e!#WqUs4%6mHylSLrt8Fe~SD8c1=ZczDN0;~VsvV_!Rb zy;pw7tCG0`zeH-*q-H6fA8Jkq#C{n?Z!OQp)XwN49fQ(-1qtuV-WdMXkKIc?xR

cS)S*yYCp#?j7sV86E|FROJ=j0iBe(6Qaqd? za!{88o@MW-y!f$PiL}|E!FZ_b5>aHNH!pxTGLT#;gSOuGr`#OO%)gN*v6mcW*si;V zLvH@YwRzm|vTHZ`fM!P3c+>WEUzqkJBjpxx+3>_&%saql@Y4hO=aXFW7){~R`i_M4 z_z*VX_0SHeY*hz6=DR1oP~NvvA~fj&Yw@EaISFOI zy*VG1LVK!U0jBQ?|J!r|^w0Ac2XmIM_@&HFAX7cDN&Da!s$FkZfQv}jx3*p5Erzdh zm&V09?a=KsgIe&9nZ~Q_FS6ms@skO|ldGie0=>L29ewOqL4s@%Ak^J%(es!)5&!0@ ze$wIx!LJPl7C_?y6hAx5bUFV#yObue&S491p|N9*3{tmTe5m3FNX915(OZt2Thrnd zol5GC!BeihSTWCQHgxR5MT=-Q2%_Qch^p4W(F0}JaHdV=m3ZMhJPuS2Y!C&-mcY)l zDSo8(uc$bLtvdjvSu(ylD5FIcPYu(lpNM6LSu+i?)$I$zwa5cxay-WV@QIw!5sqz- z;R#*wGHzrLQxnip8T_FYjCLag>&_<8_N)YQbS86{5QC};n&VC}XG_A(FwS~wHy~FY zJobMg4BbCgp`KhC!X0pihve7WYv2%xlb*a+Gw*CVf$4r{{;xd8FU(_Gld|CiP!&4Z zN1nFV1d4P*Etjct$4Vimh;w}u5?oXOoM`J;^WUh&Q>Ea9!|Ml?zl2zGZEWIduoWEe zUj2+u{x8gds_QT;LsP6rz??;MXJflWvY^q{R3leZby5t^UKaJ)@~69hkuKaojr8`8 zHo5t3Z3oRoU{H%S`P@<%ps*f3PwoiX!bhF*$b~&w0uY<(rK&y1S3TIeAMSE`{mIRS ztTlEdM@$VD+Qxl2M0Css#9-_~* zexDLlii+(&NX`(~J&iBy=2d9Xk2ekn9qoB#R$F}e$kK(6e)H}xjqx&Rq|CShC}F5>dPhR7|&5n zF-wms!_5Y<+Dl{vJqLFC`ag{tdEt9rMJUiu7{lXpM=)spM@D2m-}T>htNQdP6&f6% zeaU3TaaiP)T1@P2hR$#X&Fcy40hl{dn?Bzd&qhpVb6l7vx1LS#aEhJ)ZA1)Zx_V9* zhP@hLRR)iD%saybd^w9YmuW~O6uFNeUfsIu$~l{$t<&M^8-1b|bIAF~mlv~zq0Icy zjU*;eBC<)Za+dPVmUvoT{WxJ7NynBH0Va|#+bF2@Yv$W{SL`;2QfcLhA$)kHSRqFk zt{qhok)wfB*3`Lb=yfGxR!}@M(Ba`uKT=x*)jeIKpr*%Z}U#S8th)N`_toPVE#DW#gF19T7y_fe=-$#+ILtxW)qs?*)j zdsna$qMej@^<8i|&`nTMAz%r9+Bpano{R^*-cSd5d+iWL>DhhPbX*l^-HQ!fX}2I` z^rRUZ@CzTnB1#MOC2D0&PBY6zt?%Rv@Gb>@`~3-{0SfkK{%X|g4(0+s!>qw6Ab(@m zEEnWuvQ1iep_NBk1pn+4nr87-cQDKU8&A z!}4NUiV=e7{K(zoQ1vFtQsX-J2euqC;tn&7+ZraJT)uxjdBMXC2v&rLq8Vhy6K^fE z(hqyZDs+cLnc2wvc!t{QwMoR~ySjuVov-%pGxw=5GZ-I&So~Z6=$jyl1s!?J9L_u|@+rxiA}MXNbd>%%&4$3ytRTh-m{x&Fcy4#U&|R80HFPzu zX|-nsr_J2imT9BPJOz^UrqccM=RryDU-8M25p%TCQ_$A_!;A<)k6Dt53E>jB^CIt% zF>`7XgRjo8X7c{2N2ZO#8(i3h7qFyq5MgDUk8iYBk@MAtr6|@6?fxpD|7u@2*VPjB zfzyB2HuN8oDuyNGp^P)1x~(u*Kps6epWT9I42?W|DQGSp%F<`Sp*OtOOR4!h>rEXA zb!6hkeHam8_&k9DQJr5cH4~FR10n2Ng@tQ1H`tkmqcPC=GO+Pup8wUUr}ON}CaFN$ zSdb-wa-YLztI&iJ(|CTVoYb;+gV5nK%sKH4CRsGh)yg@&`C{lSk?&s(eefnZe~YQ! zgHcenQjJ}`tz$F-nx(69mC)i1>s(PNA2oH9*eF%C*xJVZzi?+a8tNr5f%OQ6$##K2 z=M}LG%neXi)t&T}?;9+Bi55v`Y7zVd16L5xzSlMThosG*}i4&sI(YQtpYF3yN2^46&}ycA&sizQej)997QpPsAnkEwVoI8t3I+Z*ltgq1vD0I1EpP3)W+xT>^qLnrelm&0{>ZFL^GktkPnk;RG- zar2G+gRrns(1QzaTOg?E_^3d1b3=)9at_PnVer{_6C)bz4FTSW;LR&uy%O@zt#M?B z2C%FrPiO`#P_{f--OX{KEmEd@oaDTCOnGEm@gMgF%$hxhXmpg}R>ivtl(_umX)5e+ zHS#HnMkO{E=i9lp0LU(La1Lsi>DWbzIb3@l0DyMBtCv0D!<-!{`#}jmS(ljM&mO}d ziG3N1^5s~Yv|q7TA;YT* zkk2XE64%P?XJVH0lTqZE9EMWTan0Wq>E@gXN`Q(lU6G=>XySiQh9gqfdd&B^2S)~> zvkVs(gV1;nt3(ZSsR;=K3V*hWB)He<-M%Ep2#p-W;_f)J2K0jxkcEgBSBUBYYj;ijnV5e}F#$VQb*y;Axu%@!=Y~{FbKaQ}$6A`V8){&LCl>m!a z1@;JeJ{7$}lW&#$hg%K`CPW1+#&-Olng)RD<0*xN+eHrLs#pGs@92YO)=Jx$@$i7) zpLlV2%SuEsnIWGg#)ztTW@q??)UCC1V?X9!QprfUeJ5a*n|Fa2kIQ|J#ee#PF_C zYyaP4-D>$|JVcx|Ja>tNWnj?qhcK%8LzI{vv>}xUDwEH?5Ist z%8a^0ARcMom9~I27DcIbJenFevXO2Ixh|?DX0oL;mD9!pw&33FD-;6bpn32ej9W?I z+RBy2Ad*!I)ZO}!+^V=fme4zstNc-puP8LWrm^HB-pl8xH@umL%}1{OWs}ku8>141 zkFfxyjL$`TY3d9n@}81zW#f6WG7j|&E8-bh)e^j|&3%DkPhHi2w4SNm-}4+vuL_$+DB&dJ^y?8^T+;v_dwBmEB3A%`Eh&4>W-ja0g& za@DL5(Rcqbd^KL9br_SAUCUSo@<~2dLx!sAJwLaIL?igaNcR53oG&=~rC(r0ZAW7g((erGH~Iu<@%0~)3jYlXO*vn+Vv;*F0vjO9o6dG2jSe~#VSiVV`?>KoSvM=&|X?}PNO>a z0p(j7c^IBf@=|1G_ZZ(@i$A(WQli!SL4B;N#TpNBC5&S)oCZCQIgPY_V9FcV8;CZ z)BXziDy)2e+wQEl%e+(Qx8=r8h!CwUuEs<4J4MMH_5`ce&+}jIhRUPz&nHu}@xU&D zArgSh%d!FYiO8b$J&@O3$NhuHjXr^KTbZ9g)w`yvs{J{Nt8@4-qvJkkap{Nh=@=Za zGV52gGllP^U7D66Zrq>noo@dx%h?aHg+$a+}s4=0HI+C8-^NZRyJRX2t@@X}#Zb%e6MO-(uAZ0A4L|)c4^GY`0o_=dJ%d#1o3Qx_ z`?klQ&r$$q9-byV7^&dCRm&IkUQ<@bA;PaoNtvK1Fk*nze1C8 zkG*dC3eoP1)VYCpMJFXL?Up6N8)Y0Sh`_LM>j4u%vRi2rS;Vj1TY3y&&4wyLN9;qx zHF#pug;(o&&VxLkc+-)k5P@3TMGBYPhSsAMBD3u>RQ^h!p+?_fcNA+PpQv9&uH2=t zJsT3~=EIz`-eaw2BXsTZ{u&x#mD+|J#LFe06%)x`-Fa3I<#ZXcbgQO;-ddEiAh~Hr z9LT2Y8g&z*+*&9p=06jG!dDT#OLG&u7k=YANtZd&L}Dp0`s5Cwo{th)FpBaRQ5q4A z1`cMr?*mpeJ?`m|5f*E)XZfcp;^s1||5q||nToem(uEOcXYU}-xwm!sB5UB$nguAmu^A00?j*YK;1y3pJ`KVmwb4I%_72>ielj z&D+2{(MAI`)->8k{g9Y_YdsXmCSUeB87QoN`!)X%K0*DMAo9%5Q_YzbD~4MUY0ZU1^8NP0==HP$mPtt9JwmF63-#nKex)GUpr4kxugnCyMPw zI>-S~3UVzrAof4K8|3yOg2BY0OFug#G;aE3k5cKlQkeJWFI)#Mg*~q9E5p!vd5gkz z?>S^7V!+^t)tm-r@nijdw)YtAe)rCHb$W)SNYY!ZIS2TIK=QYQizxi&1PFqb+RZj7 zWN~mRISV%=c(C!oA$>urQ>9Z8aRI0?F}rbY&SpqUBu9!@i->euX(p?-cjv_Q&T1C4 zJX=3qe$tF&=~PVY_(A;P~$zj zWm!Y?wrRN>P?_uM(n?zQl(~O`oP51tK^=EG8+T73A{_0o=;tD6 z6L%Sv08Sh;$-Pnq??q9DbJk}|!ZLC!GSKm^7Mo8f#s20TaEf#wQC1Q(3aGGVXh8W@a^qgkzVD+?KjpMh2=itvKE6w4I+2^QT0SDKx-~<`U-IAiGd9xQ&1Pcki6>xhOH5LtGK1H$^ z9w@e=xE7_4kgfi`>+qncv3FuwG8WYWa_i6R)Q>}!6k7;)ro zvqkMBU<>0p5GjXpx(_kNvzSXWb9-?k>gs3u_64@|SRGUQk`rJxaKo`!mM(7B3d0%9) zxLX$1{*z7OFh45{!EX$oXnX4Gx9O_u7#o?z$P+WMCSwmwKk&J=0jpG_UZY}4kxSon zM|__tjiL{54Ger{2f2VUkgMUspwJw1+@!)nla0*I+wx51SI0)c`@gt0HJWI{HIAdEopI& zefvQQ0g^x3zc4t12R?+gq-e_+s7^rt5J9SfKw_6y9U(D0yEFzx!673)1Ub``CEh94 zN&0^142@86c;G}exNUuN4cGxepP}OG8Mgt0ZS)e#ne19Swupd z331<%#&XSoh4sZEb@ClSSt6%^#_&*4oY)1ss`@^b9ij~MX?h#kU zSiJzh{3jJ;6w$~ixod6ISIq<6)c#9K2g-k9JwiyZlps)VB$suCDV76Q3CXv~4hUsg zrjzAceu*!-=wULbMdnSTulS%-bwNQoT0$I?NiDwg91;p8B(!nWiKJOvA%s7t&_`p_ zWkmWi4e?)_qZdm05jCVa_OT4Kh?==r-Wq57-LMe5M+vMM1QZqn@tT~F$6HR1<3gA< zgnA=!-o37d#O#>7t!a7p&i3qjf>b#1jvlz7>rNf<`Hc2Fm7J^DC&DkPu@Kzn4($62 zUR}<0_M6HGG)*u8LPYR6(NgO2(41-?KySZgxWPu7l>c(KlO^_UkxQ*gK7Mu?G9pIc zREvye(0X~tf@FAB`k>kwe-C#ojZiClX=4n=51o=*#N;1UMZVkP_F%Zky0Z=~WQk&_ z%V=1E2L0Yu^?K|MM#mc+e&~0CjcK5R51%NiRdSB;cg65O;FQwryr9{Q6T!%c8M#I! zv^1q)61~h^7*qS+DOZJ$j8gN!?p16^%Znm&%2I+)E!Jy~@0E`4ezOC9rilwxha`3& zZ%1(Y8WiwM3NH=?{2M8;ELT>@1;K;C{3B4Oq>%gRMBtGfbE@9YHEx`s$LfFc>?L*f z{~$vu373CIrwANqjes(NM@|b(o`Y8f-D@tfPcaP65#t3twlw+#JgL##2l-gD(5XLi zl%9{Mxt`-U$~(Wz8cs#SC28Z++#*x1-d4(LgVk2DRb^K$3LDkYhW&0|y{ zh1j`qMxpX_FOqs-+7j< z=$u{kwh$ihks?|yhgv)u=N~0jLQRGf>AbgC7?cqNy>*xi4RejlILaLJ2vJpz(B7R2QvFtxaaM4c(HNY-qY?gH89 zcI!Yg1ylI7jN;ubDC{IA1y=8S# z)laktOhcHb+#y5qwmq&LIhjE3VvO_*$Rl9}?;_@^03sPTS-r%3p|j|GTAJh6XK=g@LA+!-vV(^TuS{BtPJGgo~Cx6pp+CE z%|3{1Q~r7nFV?<^lc-4UR;MWne+1~e zHH$E$ayJwf)Kzy5p4$U0-s;~nt2|Vti0G4BdQ~j=!qvZu3PRmN(|)S*32OOzJwNb^8=MY_F;3NMV3j#Vjx*=_;!Nze@D%r%#85fPX39lc|qzOvZ>L> zMDGCW*owiyDlgmVsV~ffltPx4GSueV7kJNwkll$(>c&`9w$t9Wpq5CXAXit2AsF}- z+!T=i)q?+p)WINMyEX3JO`9rooBAkg@wh)*3XpKRW-BcLfN)xE@4)by!eL>aHQq9f zE|D4`uwOnzzBsZ?T0agdUECx$I{RJP!lb5p07#SS#T7!EzY%^l#{7oj@9E}uJEpj< znQc}X#zY{9usHnq4*p3|&5V9fzzi?)NcL29yO%zE$;}fyWT$ z!GCfw0euLL@us;T4+02&7mk=bO^J8moscUCWIY77XQt7Pe9VehtVvv0)@=FlU~;8% z+1@nmFckIm{kQi4b)WM@LPxj-hl?47_HCTf{7@L=0+WOECk8bG^i^n-x@d<5w{X%5 zICkDJkFkxaG+sL6enLcE0fr!NrLbq2&kwnD-n5_PXBakvbMLx9Q{CjNC_-#L=~EfJ zfUk9$Q;=x^I+SY>=!vCM!U-45?|bn~tc@JPZmA2tLzQJcH}5F4O?v*Bbt1QvrLW;N zx6!*P)@OKiq9Ufe;5}flk|F37Vs;Ov)z$$7oP1l%7SQs(gyF8KA5mh%k>VJKO#{8Y zGWu1YQrjXOm(19$f)G#^v4I9&usUu}Nb(Ta!NSGlo@-i= zy6*Jw!}912RNU3Q(HcFg-H%mXl~ipr>bhrq+6)mzmy3+7ge9-NTb-$N=1<4bavI8f z-A|Dw)l|%H$m{Q~l@5{pNH{|pp!z9KWsw6gfx{N?Gn=58aJhZ~NT2xIkQxlD9~TX+ z$0AzhqWZBs;fLgRhE;nJ*Ua2!@ zvx1qn$yg0ooq)N3s*hrKyK7;oC+;S{*?nz3=BYT_u;k%G$6aGG(~o7ZGKqTMwtL*j z=X;?T%a8{MZdhlWnr>`{Xy@$egUi`yu-Tq+mba$EMs`U!1uys~qTUicq#?vRra`!X&-AN;kVH?<9Kq@^Ded>VnC9Z&YqtqQ;BU_x@a5YeM?YS zqQ2=LXp!Ylx8`>srvBxT#kbQqI3~IMYOfoSuQ!aG+*gE#8_ zE}u$zho3)Zb-)Ks2Rj{FsTPr020g)~@J2=&lXA0a3@kf#+EIGD!Y2$I_G3f?7NYBG zWtfnu+)1!S+#6V=bx(wqX*ZY8jS>4)KPQ!uztazojG>I=g+dHLBYdaw@QdW!GgSF; zRq{iH9Vr*l?kDMlcPwA^1j?EQlz~4|zl3BYKf1mn%~rBxTqNLARc4Uv|qshinhFKM2z*7VfKL&+J)?_JZ{yP$8{%P)j-$7hll z?C!oEk_z2!CgSMa$A!sOyg%>f=jygsTp zqw-r3W(hDUknSB|gVWlOPC%@PSw5@P(r}vX5fdNK97MIsn+$V!zDQ5Q!mn{! ze6yh|euCgFQEe4->&#yE!nhD?qFsGrT+*=;i<6d|G|_5~P{hb>5qDC!s_uKcC-I>y z#4wkMAqd!I$KqNR(>7aK9EH8Fq4+ewpr%58*ezwk;Ke>8abDzZl6Y(dAFH~JX(-AeuAAVP890=-6Tr(Zd* zX|IFiuT?>x!p9i2$%x(}%sQf}2UTK>Z3*Eag;kTRa?nP1XUyES?*TruwvAz3^=$oI zy1l?9;*JZm?yE!urdi_Rt#Jdm=nIqA2$Muldf$pLaiuDtE_us|;7k|$2|K!h^nEy}yoQs9+|J(jw{5d-Z2PfhGENBLCD_a*c zCqf2sTO$`UQ8N>JQ!{9OerRVGCo>}ew8ututC?!ffBbn=7r3MYwEO?8GKads?I19B z$eSC)EvOs(tz1Ee9?#kHo4TvbnrKoP8S;00rxui3K0)74f3cv(`E#VDKKS~E;s7qlBlGKzyC4h4S>&aaMQQMinu%G+^!*MPkfs}-) zcX0w+`~CdG=Jxc%R{MOF&0Rgc8b(;Jy@zK@A6UX3w-7P~#6bd9PvwMppILME>T4KV- ze@*=@RB!nkgxP&|0m;X^k}wp`ZT{LH>9-711`KOUqe!5CK==m!1JFT$X>A2(UP|@- zZGOR=-CEu;;5ZUuiPtB|Hq$y zriWC7CKvZ$^aEQ)4p$$6{^%eJKKhq2FZ$|6U{i{{CjE*Ee(wBT>d89_9ud6|KNp{7cUzK zX=Z5t0GffM);)mfRBiiDR{qGSeD)=Or0Xrt|983V4s}1u82+1S{YcP6$)o>X-XVl# zWF%Achu`1AnVOoMf;)WEjSo#+y#8+jedU*%CM!q}zzg)@uVZfXt#SB!_-a5g^c#@q z!s_1mW}&e(P#TBszk2D9_2Zb`)zSH*_H4lMV?Xr!_*Ewc0n8V8B3UIPfAUq>dai}F z*U8W^go6C>-BUd`WHj?P7F!G~kWHQs=p1RYJC(ey#Yk38#pf2FA6+(M|LNocLDG|d zUE!@9nEoE(chu|)mVu*+xAg=uFeU!C9Lr*3*QXX8wbk&cU9%b9ja+p(Mp}PAqLh10 z52+U466D`D3~&S0P44{H^dk0w12BbcZ2{$g%l-`_i zv`i*b6?Os(B)!J$_Y}K!4uNDN>9Q=(^6sz`9~5J6r--d^$x+F+9l<eTzBR>@9B2 znrytq50U0btMwLZy5V$YyJrv&;nrcN0+oi-4!*2sK#g zYYX~_Frilb!k4fYbIhr+Q1dCXmEMwQjKlMVLk<8;AkET3@nWjH&s5aefH?M9n9+Z) zT4fKceCHF<9oP5b4W_HSasBy;bs(!>U^NXMNO(C2q=i9m?ONhE(UGC$iH0SL|MEpe ziyC(HASBhlf`Az)md)?c$OMgCgSDZ$zE+vtCBSLE;J3BoqMh{zU{DEYNvJF@d<^v8 zj#?0mJkj0O$Floezbvp($;bqM*`u%Y%tjMH_Sut`WNn0;N?XN_35hV0VUnm|H}V|` z&#&IJN^x5XXd32Jm(E+6UCxdC%h3HMYvd9|j~Q|aEJY1*vk`licxc*8758&j8Sa1Y9t z6ieBN^^@U@PHJ-Nyok^a5!qLYtk=}q+C_u)R19N4@d}UcB?1#_uLd2r%)f}tuR*t~ zL!13UcV8>=U-w{WN#L4TL;!Ai7iud5~l6I#*M~YZ; z5D0@(`x1Znad3-;%T_8~QWz^yWFo1_PlACj=&W$+Adffp!t+_k&*fp7aIX%QZd>UJ zCeSe)05(vZ0KNlx&7=Jvn41>5AZ)_TG$fS-63W9o$k-^ zV+VF4ZQj1>ME&GO7b^IOxnq0j-qO%f_q9F9G+JNs`z%7>YegZfHufN~W0Gi#=rL3M z4jh^_e_y&`^PkvskI_`hsR^Nk+|UqjM`eMh>9$@Oq#GUg5V}K3sRaB^ zg9+x26Nu^j9@$|9+~C|ND@bDoUZyEfi>2<)UEZp7vmMiC4N@FyqwI9kZHW^`M+W)i z6VXg#PD$*^ZOfbY;(Cx=Fe}Lf(OGkHTwQ3|6+n#w$wvB9;^r<_kX6sSyR`h;5&LnQJ8NHGh@n0_KVp`4IG8cX9+d@7QE5235b zS&>kY+&Grkw7KaZ=lBT_&VS7VQ;3?|38I)crPS=7fgFfbPFVXhMe5!%iJ7^q93CJW zPO@CiG1>7RCi^M;cslXW1%Kws6@p5ioo4B8?Mj zSd&n0tk&Wlb6m8^bA^nlNi}YdP8MEAM6LLd^Hq?PO>d;J_!d?_~E`JG!T4&rB#O z4?0tf034U3u7$0aisCPFk!{CDW<9E-IR?}NAUkGi^9XRndk z1vIBUyKbG}&>_}TfCR4qM^t@`vVbvjZj&Zg4D0d7jhL{W!Iw9za#!9qJaHUhvRfDz zOTrMF#BKM!p_~)Spm0N8CeVp2OCsE+50zmN%ZhGNPNoTZTGP05(&u`y?&K{T<-Z77P$*+}=X`#c>F=)W(H*1XaYB962iPnaf_ zova*;9w34RG$wddX$evMP%uBASI0%Ek%J8rW+%4u7V>YlSIGB_%=baMS>oU&-+YT? zXdYkOaI;P1cVw=&T^)*u<4W?LZag)Hu0*=6jP zUZ%bZij(T;1vVcFH#?ULJ&wEE8lOYi`dNObQzqe=BQ9Ksa zPg?bkUAeobNYG%YOp;dOT!f`_wtIJ66(>}sf*jAn;wb$>=N_(t*timMIt2s$w5DoU zcpN@qrFf5Q0i8^Jb0}X@Y=&m}UENbSq@66jYYU;hj$_CchJ<^%=+c~(=IyNgi^&~A zm1Xw4J@krlpV#e-POR7$QzxWzmHSm}tlSjId|)aR=U|`Y-`PP>&QKzpux0C z>=s*4t`yOKT|#v;j!Fvce>1;|+`2O-cg>>`y584PF7Div=EIm=<7&xmCT)OmpIL}J25#x@{ql=-aYPhT7Hf^x)rCMTLd6M_wWMgb={ zsC~bPvlyP0Hzl_xb{__Zi~b6kAaJ-xy;5nqpgiLgRiYEnjwB8pf8kS?3va@SP-$#L z``Q{H3jnmU9X02?Mim-}hQz(FUx{^nfi6)?XU_;kZxjkWX^9%a&st`?yBXty9aZhanY=Ss)N$#+x>~6XZyTq3v+Ka!sxd0elq=`1Ky6w#6aQ$+4$iSnVn_8MUST#chx; z9Z#c?=3v2>`8rL!V_DvzFd{6=kE%YSVCDI%s`027S1j1t44lAln@Ql7Q(`})Cohq| z;8Zr51V;>S6_3V%?x&`GJ1ck}U#gzEuVlKG(BP_hNPAn@*_h?ZC8ZMQH}ejz7-@HX zSFENlHTj@9qakAO!@4>bEa9nvmKU{;N*<}3?RW-(1^?!X3@;%X#|6s7OigWu_)1|z z0xhg(ZK+Q3$t$$;{4J;4-_2iobhApwi^-Xo1A8mxrlMHI2{Uy$o2D3lkkX>`+_B7D z0m-&0*nS~V_01~Y#UF4TH>@MYK(oh>Z1Dcg)V)mgkYK*P2Qd~Kq^lsUuqTshl?5{U z5(oObHV$1^M>MxC714a!B`x;}LYADN!}MSKZ)m9-1eM-ETc&P#oUshS?YsI(9!HZk z(jR_IxC*r()&S}~9F;JiP=t>-v@noruSn@1wvhjlE2+3pO(l$9(}ZG5eU*TO%>Ht? zzhPOtAu>(yCM2^FDGVxKZ9`0-t@);#GA1~+=CeUBQErac4MF;?pqHPUQPob@!V z(L<1p)nbbTqwm|Gz>Ls{8iHO&%(l1k*N9B(*VYF2Xu>XjhN+7j*rL$@fy5WXoM>Iv z1RJ(R6_@GNFmd|4^RT;_^yjk8p$|ghX1R^fBBer+V7kkJn?5X9r#{6vGf0l*dEb=o zyPpPi;XzuTxzgObG98Mb{Fq##>T-;oN2G|m8HIFBU53@pJkRjrWSGlsYs&)(zD_yU zkT-A(cmK5WdF1bYi0CXut2zIR*>#ZWyPC8+*G8yqM~LIg?q(+ zBo>s3QCDQC9(6q!9?c~Ue&L0*nUm*QCjf=vC-3$@tnU~bhq|Zx7u^;qHa4C-Wb~V! zk}O|R0P$>?f2LSCF`a%R2A9T@&-riD!veOa;(;CHrtAx06t1$ZE32@IT>l9K7tbBt ze_t>SPqt_8j+{Q8ljFDMCNCIb(`53(LrQOMdv+HQ;+c%W#bjLxBtO@=NC=AN1}exg zPsl4C18HD(L5zgP@2ybvqNk!Bq$W+w*YJ~3QmrZ(z#=&5pRtUHn`x=S&D9)%$RG5qUE%ZE zpDv%#LW{41MIE_d1pmCs4By{d&1Ngc%DjM=v8W zCjm%R@VPfmUtFg`TOazv>CqVp<$myXGHy{ok^<-why2k6zb23el{g|pB`ZSOrwt!7bQP=4 zciY5_I~T7Zxis@GkA-n=y~@7yB;?1+1$xEwVNyKEZIB4>>=o zq!cEuD}N{>rF-DMk1*8?YrLPp(54x_#L2`~Ytzce77UAQ-TcL75p+p#gW@5mISAJ zpeJAS^tBzqB|1oFtZto=O%u=^_A#?`57GZFu{f9rWP>r4{t3!90TnQdaasIC>@hG{ zI{ee~72fWScUkd?nm!CJ-t!q_N{cVO$ovTFxhxDTd1IJqaKbzP#!E4Wmz^t_;JO{d zwFbhNaqDZk%ss1R$frguj`Jjh-czLG4% zNN$Nm>4v12&-CfRsPh@=oc@XWgR$kRN>?o?ats&?jVJ-&#V*)3JP93*vS6X8UmLZNjT)axUi=lYPQ~D6Afg_Omr~V95TL>YQQI zqwFP(g!2#Tr_Mye_cg$swp{wwn{;+?4y~+0K{R=`668cxEsO$rqj0~nMLX#~Qg@M$1MTv=)3%iA%lFIB1V$r1|yu4Sk&q6BLoAmNWo`wC1s1JLqk%rLNLs6@c zD)p*WJD&%E?}6^Q^LmG4_fRBwGh5M;;yfwFrRKMt+oHUhIT{6rP)U# z@Q|kECUw+zR#P^Rfe+qu*PRd zrS;EXZj(s@#AhDO{Em{-3zsS_;q3$C*RD*CnCe#a|HarnEQ_K93j*D?ZQHhO+qP}n zwr$(CZR>2?cz4nr(GhRZ!}@{Bs>DjoD6(?-KDdX4w4Dv1RUkja&?IOG(c7&C4q0{-N~{)4Ktl+PN{_^;~YC+O1PK$GN-wsEkRE zjzX`IiRrZ$ZV&a~sMJ8F)P|s;?@wk~d6A)9alaNO#aLzblYLOz&o}2htzhY)N=I&R zAuLBLEpv&DEa$&a+PXaTTRb37@&-%3V&YX0&sVlr^)Qzod7q{`*%p_z0vXVe;s3z+ z%f376qQU2tBzL#tGOZx}C&jhGiSnGcJto)ri#n0ES27Qu>TB-zHX2VGMgt@?K6=rQ=yE1 zHh>mT8Gt#c`ZJ2K!8+cC`TOA(iEk(0?THM>8TkaIt={%;p^h2oijXKx^e7B<(;)Y& za`)jW6S)(4Pj~1Cuqo@Aa6F$G@*v>wn~wPs7zFoiQi@VkwrMFFo+OV0<)ZFe7!Q_SL#GBdbM${YY0Gl}<9?13vF zaZh#kN6WZ$US4FJIs6LInFp@R8F!EH!RbaD#krt9rR4!h=}E@iIiJ)h)7P*fXUj%D zV}EuoT@J_aRF4aUCwKpZwI%K}sx<9ip0OajQW@g66K@VT{eTp{*;PI&b>|y;S$oCv zDO*sOuQhcwKG={pPOkL>8Wr%j)HFPc42`Zj+6~t?dJoXVw4iyZa3%bcjcSB`OMBM1 z3?JlcM+gMviUE2#y$hL*?nCS|`(jQFRlpBAy9IH1&Znib(}uaY{1ZvxhfEL%LW51( z!Eu2n)6-xy8Z`-@8z=NAjon7E`|YDwTCJGUZMkWU{1qpi zvzdH9-mjOX;1*%K15+%!VZx$ju?-=cQx4i3)-ylq+(%Yga*=_{j6P9w7fLzUqt z`N8amhuBw(6H~A_J}Vd7trWB1h{hq600kz31z?-V{RqZK@w-P9TMpQ% z-Q%9!WY=4qB_#GF6r5Ek$|sgds@pCCAtCbNMU;jG8CQwa%CFh`Q8FQ!%xkTuB&AO3 zcy~BQYdxDpvVF@C)lj)<<){(a%|IRoDRSmx2bQ$*5fhBDH=;?E|H(-qlL20|LDB5c z16tWN-B@Jx&n~nQRJMnFjLax;N^dYSkd!E8mrqU1WRUD-+RxZ|Y%8CV&FtrpyB(Za^W<+rD+ch9U z9625|c_TdD^p+cne9Z4Y{wf?UoIrw3R%2Zjey2G0n$i8%BJzQ$>glndR-$P8z0Iog z{I}hwO}-25E~Zy5zdj6>oLC0rhnXWo)^`@(GKNJ_HrONNoD0ejD$rTlZ;T78?bX@tO z8*kmPZ7Kc>m#kcr_I0iaJv3lh4+k+sJw0B)MGnn;Fs-Teok!b%VX}kB>*+pRihzg2ZCPwL4#isQ>HGlb@|wN8bLDDv;`01DKK%iyc;(8VxQ8{o4Gu-!x zB1y_Hz+}et?<*TIF(1S*9m$9(XUd>HYKT>jL3K4QJoROFBW7(Aq@XAw=Uc*snzR$PPlU=lgm( z&BvZpS6Z7Sg98XFB)K4pLQF%nQ^N1>IU<%lJ!{0)m%DqtJtGl6Ik1={seE`M_bnillTbM{yG{wCJhxA)oD&plqC)^)l*|&wZIH#tiwN@h z#_c@TO`NY5ulVl|vZzGyX<*Q*kc#YCl_GAk8}3!(+LVD01C-%C3Uq=V*eK*1QHSB> zqYgstYzE=Y<}hJjM?rXM1wl=hAF|J*A{hM#GIP(9b8Q}f)zsK)a^yTorXa{!K=%O7 z($7=xfH?biM1`KORAkmf)GA!XltIy&)`92FR5 z8EZkj(VT4~#FJLh6fbsm-ss#jGX?F7j!y-*2CmbyY?*LT?gg=$17+iPv5#J@Uc!p@ zHg+QYd&RM|Zo=a7Yqd;PbBidL^PNH6Pc~r4rJy}qM@0!$>lXZ9w?wE>t`)My`I?i2 zj1f;;>zEQ8zfvpI#*UGa1i$Aab-ifvp4^i~8x$bhP}0W{D^N+H-ur($G+;Vr;Dsq8s^|d<&AnSLCdWVxWRqPhb~wS-TWpnW~n|gWaFXhl9;;(*E%9J z@z5R^^{U$at!4YZ_$X1y8vJQ2*H&W`w?sXk2M?>~>r&c^%0K6jiAi@c{MtgFEqcUc zl3FeqQ_O>Yj1em37Yy}VsbdCQKZO0{@Ttx1X+JzRGBOZ|CYqAjpu#PGf{=O;aBTr8 zqapwKZVBv|6pzy>!1cFTZd&nEA$(vDXp~1WrUfr(^WbUjFRV}qvA$8y|AM>Z&YL!p zWs`s`e}Y9f!G;=L+N++yMmg54Aqg3Pyu3xDuz)`6x#ia#+y`!t_fAXAyRBx7<{CuL zrUF7CJzw0&%I_SzRcE3lBV%bph|oH!Lq1cRIsNl}uBUzL!iEZVO^oLO>8ncph#Pjd6aDdPuN)c<_-%NoI z@ha`leKuFiIsF?h^vkgIJwVfB$zZ);VfWsSY)=|@3@K7KfxVU6trJM}Y|^eUt)eIt zzKQcz#PiRPy0DuqV9C?uXrT&j(cur)$=_c)EBym${p$>M{zcQV<z$9ChJjJn;!KwUbxirmiHY!toe(&3WL_ZEFR5s`S~Ege)m zx;W31>23uY)fN3B#a+V(r|<|%=&$ph0Z9-o?`abcA{4crFTOjR)Y%~Iw3R24d`pI^ zNmiZn=*g$nO}1WV)Pin^hDhW`5}lLsLw!Im*jGk5zx|yOVjj^^sLv!(7;iRq4K-18 z!CxfGAB22W&4MOL_pK9&>3slm(Trq{z1VW6^E-KqT}AQf#cpwU#D}Vu&*{9=q*Kk^l?7scT#GwV&PT+~Z<4-boTY)HmN8$W%Alw0YR>$qv?Sti*J=5IgO|3D<@psy#J?TC$n6o;*le2B%cqVq`q~|m*>z%jg{eh z9lQ#J?Z$(sB2BOMJr{?V zCO@VogLzvqVS@zBZ~^z7=?r7&YsH2bJTK>TRxkM3$MQatT6-LC^@dpl&p(TUn28A9 z-7-QU*B(-G%CHFNf}nJmcZABq*8i_69A8_jH_k9Wv?ON*HQ^{VA7kXt<0 z1xofqHf3179lMCa*`)#{>@v&ZU>yd__m7}JXL_P~E-72od+$RHjE3q;{%&EK3m zNRz|w3Ocq=>dp#D3a+N+Sohr7`X0%Yd|T2jR;}dxZVk_7A$GiPhwc{c67ZN> z0$)pZ;$G&L%Ub;dLs_y~`N0f%co>$KEaqnj)~dsOocB47H_Yb|VhMi4h>pr{$q(X# z-r0(;6s`Vi%Js5@=G|ufN&)8@Pu#cD#rvZ;{%$5(9^+yM9uCd@bh+=_VMPu+7^jPQ zTF@k6@y(lk{;@?;wnuwbr2&b)@4aMGA!@G{PFASK34a{jRTV{586|{tH^@+F}6O!Eq&E7H4yF0oIr)`^ z<41a6$Ay|=dNN?~9nxQ}MlTWJIC5h^+La3HmLI1ZG{&1Uj@z_?7PJ(~EU8;m9UbSN zE0^L$gDbPaz>|EOyD@U*qiZ*mE~;)Y+b=!oU(uSlw1#*wM${ne#b%QnnSg0@+;{_no7`4kLQ?VwIS?v2KSZxM z8_X)k3oH&cm?qR*pyYr-xP9goaZ@jsoqQWnLqjTcPGo#Ep&T03X9+UH^pX&dChizQ zGlHpl*6kFyHa)pCUkp3^{Tyv*(cRCbi>fcG<-vs6;~*q}%L#ejDxm+VZ%k>Zbq@ia zK&Z{^X`}jDQsU9XJ?e;Np^%ej`40ZUn&R}<>VTvaf>;sr{+Zz?qINyiC_G(D;n&6P z?#IU$kiMBD%vYFlHHwUKS~kp8>K8v+9<2_WKf|GX-NEH>h~d|k+3Q%h;h}haW4cYjZVAp`21LbOVAJyeT zL@?=x)AdI=ypg#4`X{fVxvZpUa!fdYn2E`2GrOB|+dP5dkj%^IpWnc~=pFU>G;lL$ zZq$~AGeEHlAUSGup6Y=kKjSdCb}#+Be8^_A6+orN129cyBVn}E-xJcAO8-3KAS!`; z{QcYZnN4~v%3AL{FGe^R@^1ihi`J-t%}-ZqrbjoG=~a}TESH(NZPaZ*66ellclD8a zM1)6tRjTOx7e1bAcvl6J9h?xHDGp7_h-oCGbwJ{%t1ntX5qC*w(Qx4_r#xi@69 zlZarFbtn_mIx}|dFq$8F!T%v~MnZOKi;_XtzO>JT?XkJKCY6dQ{S8d2P2kvB@ zfZHSIk<98#~-BL ztA2>+_JJOjd;#uP1j-JnY_5d23ANk|vIP#DCd^?_wWI<`OZ9klRH^hk&=O8P6|uat z)_1L1;8rwh*&sQTp(x03MeL;9J+WW^=+h(nd5M)C&eA2iJ1Wb4V3~o^m&k1Nr-Z0t z0Q8%)!s1-Qhg$~0kw(&7`ok*p-3#stoTxh^X=DEkZ0CKR_C4S2ZiTL~O2%Q(9lTo} z5hQj%1$n*=Zwm<6XFnbSc9IpN3JsR?n`{-4_XI6X(_LTvz2~oH3xU}Zh2!I$Ufc?Ht_>C4ZDG9 zPP>y=*>qt6Ng$+A1JrUlB0f2?VZ2S~36{4)emPA1M}8Vf!}(9Nb2}f{ibj$Al^;>^ zO{Q;fjI+yg{c6#SeAdSC?wp3)I1$xxQS_GkBX$jWGfs)mKdAvoy4J}JkP2U$TPi-- z|LrB@XUQeDn`Ibb+?l-EwA4N@h$NsXVft=^Lh>%!EPNxRyC5cmI^mu3CCC1Z;K$(3 z9QRE8i;^zgzr5N!S!4k_aNY)zzg<&T41?K3ODEPAyBzc{Fd!m9L!c))nbjQRdcM2u zZ!?@U z%e-w0HVC;1G(RZ@GfyT@QKL)RA2zQg?8>i%qCq-vlb$VebPAtI;fTN=;`2Ehq27Bd zy-Xn`TnX5l>{RzIN(#j{?PSd1&>?r%P}?b@B=#1r%}n!&Y62}7Kz_6T3VUJa=7Z+? zia#el%tWx+9BTp~&@#Iyt1-{<=&{myLZEGW$)Vk~V55cvvdjVs+>G5!?yiA}y{0Jo zxTI^L6Ih%`o;aR>`Mmqz`}$q|mhg~9juNUBl`m6LmNxgrfguckgP}Lj9Pl37riY^4 zsZMk*e%B|6ei7lY>!Z%3636t35e!{u@RKno!Q)ed$iE4++=iG@zUG&aRg3DSz5Tn;|;k?6IUyQ^2eF%ZMb2 zl}#zec8881*8VJGbx~F$m*33?kMAQ_U>x|_A2&YoxO8R?gbOt64oGYh6ezi@))#u> zqrp%H09lP40kT(wrjlqdSWPSY0Xh-d&G6yCnY$CJFCY2P815BX@FtIb<2e|rH&{D3;a*!zG-VPcGZ&vhf-?Q0fh7)kP)bxqdJ z@6yhMuEq8&!ge@AJ`?CD657v@aixwA)Rb$4QA?O1SCKopczTK`_mE@POP#gQy+WgC z;Ox~MoyV_{0*Y@n`r-i_8f{R#UXs^@j^HXLG+(_1^bPtd!c|B8id^K53(x+^)i|Wj zN1%fC3;S;yr<#Rg>BZtR4d?L+k}sVQ$v953^FNfh6Z1n&1!K>O>N>jc@+JOuUE415 zRLZ9aU&za)J%U3rt56}M6RtqNopG45LQy&$YdY{Drc3QQl=VZo8&7P)cokf{Qbrq& zQEoFLEnstYX%2kJr~x0s)Xhr+Y@C(vFwnLPGJ9sw3KiIOR!vQOO67P8`YVKLw>>ZR zUI&gTk|v!%9klp0DD#x-hGbHH^X%Aqeo@5#mH{s%lY8#p_-}FU>qLlNctV!HwOcjM3{ZFwb6UOG`0wIspzM46FB`l?n*`%skTDD_ z=3Pp8p(T>zAMc`v%XZZz_$Zqg9KI4#<_5$nE(?Jl)DPD@!LI#;NcET2mt3;^ukvn2O=>Oa+PJw|otbBb?*R$t z`YEWQerJ^ngK*jm$GAf^7)#?f4f%FrT4ihgG>_|2b!(+oUGmRq*|zo;pGM;-Tm2h} zDVX((AW+@J>zr^3m!`G_FC=ynR?_i&^cD^ zbIrGd4>y7T8_{*%jnPhhCQI{IIVDL)9rLjLq&*>nr9Nj5PfzWg2Z+c8%z$G!NW0Q{ z33Yjf>-E6HzmwvWX-lkHkkbMbyvrbDpS!}AS4Nx~3hq&2=_rPjp}VhnbzS4{R&&9! z5cR8;d4}%QHIwg^d{k5yniVGA#Q&pd@x{|5#Fq+|QS}8&tfgu4msOhRibLhN8CBM8 zlo+Zjk*_JeuJe3RsA*#k%mstDtq0-14C@M=<$e5_r3NVfyEzTC7R&*1q{5*2a=ri| z(~!5yJ^(m4qRJHe$%dhOOm?P*pZ1g2NibbD&uf+a9B*H4nxRp(`DG$x-$ACM$^XSoE~Urvhqp zZOQzC80+zyj%>*FY!65^+KGv#O-=TQTK7QDIK$dib+~#)4m>|Q89j?5a>U7M^@t^jvS4&+%`0j!>`1U+))&Po#PbSFcXmoC@;e zGvA81#;#3{c`ZD~{p=;kKK$rVW^l?tdCP|J9Rrlw<~}U0yx=O)jrbmG;1q8ToH`YK zkqP#zCV{1jO-Q>jHu1}RN&mvQ)z8bMZDfY!+`#MOSq~THN*;Ue>&U3L%6vn|yv7DR z3TeHJ@I)y6IAa?V*`ZB>y^hjJOL#4arQv1`xtqlDZo7Vls9CGQKiVzvNeZ@UY~=Ll z0y_koZfQcgC)p4zl+zX)w3d*IPa^puX@K|x(46?uSZqhQHS_}dnHB{ zrFolnGTH*9lS1>M5y_dF@x##D?4cp(Ub8HBm1i%_71MWfYu^Z)pV&G$^j4KCGG??t zVp4X`ENaD{a#M793+>BRD}62#g@&UPvDqIS~26-%$X{* z%>SgF{-O@xQ8*A|ZW-r^^l-cG9C20POMR%EU;{@;?bG8MlTC_IMBwR-Obz&l z@;{}QUEJQ9v(p5>a5yM+F#gS3yoc8Q_ZEe?+F8SXB6awJ8{mK*xy&(m^k7dtYtgad z1C^}yotCU=IW%-b@kHqem5;G-?1jb(<*$2 z3J*3OYkkHye4C1X7O6+#wJ&m~B7IS5;gYGCYJ#XQTUB+KXk$7aBHvBo$7e)2AoIXp z)RNk(ep)(Kl*93JZ{ezllcu{M*w^YSPGTOa|8OFS*HNB|^ZShwA7RL9U^EUC0(9g` zIby?b`6lIDl^0FADs)yW_7k6Crw*YI2PoWP4ae{Qumxm%`VO*9lQ)|}XQJGQzV;0u zBBh=;%k^L|hg1dvB6REIu0|g3-*3gXH4}}(sw|{^QL)c%R)Wo}} z+pZ4M_5NjFXtnKu)5BugyQZzaJUaG&a4M>dWdjL~ODEa3D+Pyo z^wP+PS?K($GmAK`RR{Fm$(0NK^6{HHg=P9>Jf^jZzh$RZv_wmHhOk0=86K;PYC&GX zif$9kmLpw1(|@T*1K;?5IH3u~Y4Z#biR6^<8IRFP=~`uZD#KxK$S$MS?cbMx!BdqW z*W_=$kS`fURDAeM0_D5WhMLlRXT}v7bq<~V&6|U3wh;kiQb$zhDE&3n>P{nJD91Pm z>82u1(Po~v?|377=H`J@qC-f@o(^dknsS=PHn2wX^GZ0UqgX-~cR*Kovou$~qS!Un zh(SbJMRc1KXgdrGu)1kdTxPp>p<_=+ z#6mng|H4N9=I`RX$C4Z!7(I?6IV5|I$Kz#GYsd3t3hUU|^P;dil!Mk;^Iq+RAodbU zuv)@T4d;<%-d(@rJOS|aHJ<{jpoTUJC-yquVs)g>Zj4pEs_%%sWR*cK2qnKOlVo6P z1y9T?S0XWmO(R*on}LxQh9~!UnV21RO_aPDg>TOQY@hwEkFEKlKF22v{&(wf5ZQ|d zdeKiDQ`pr1x`3B&Y140dG^XO`B|;YS;or9C+BUat*vXld%(G-`n-fCC&u50fhHXFo z5l-f1V2~g|A^4{Ov-ujqS8`w0QalLoS9lPM2$}mSVkArhmh`^@Qk`A~-MB#^n8n)v zXKy8K!1UjQs!)-x=;sRVcawuVX)Cu_jS*BUeg}SOf{1i9r^eg|hn!J8d^aYVB-LRp zC6xY&_%(UpO5BH~bLw)IApD`_I!C=pk`}J?so*dCs4xA4qZ); zmh@5yO|&qzB*%jB(@pOvev!hC4W#C?TX8Cdmt$|C4~IbvISfxk+Nht^+zsxQZa6^O+12ISdz;JUzVdsrHuH0-e_HXgO26i6T`MG0S2IRpZf6IT z+72d^v6-p)1|Utyt&DCi;?)S0M78+$xVeG`;sM-|P+3Wu6F`QLz^kzY0(1gy0XPeo zB)|;7%^eUM9}l02MPPV$a0}AZ5(IF;qSAVSiGlHF`f&v{u=0~XkzLL_fdo_F>Fofz zwZ**wIGDg5_19R8g#Zzt0SJgjpiLlf)Z7%8lLQkWCngC@01N`0D`NvVMQ2}{0f-`C zCeXl~fM;NM2h#8}4rpKo&j$XZn#KHtou0uw0CI2*zyjRc3Aj5G0Ov0l0{~u-j61RU zafA7v523-889->y8?XT^V8E=6{?w1;(X74kmzxlr{Id<)&3+v#v$=2Lku&d83 z{FfFI*~z=HhHC)VB4DQ26y6gGvhXvnV)omQ{P8Dn^oJbyCx7y@ANh5M^^>0d?*GO2 z$KBczU0a(Jxw{SUZ9ECE*A~Mo0C>Ni*U0J!^xbNWqZ{y-pB;%ivG&vN`27~GHQ-P3 zh41qRH!Uc$mqi5D=7Ss-8JnB=f^U}4%rXIMQ3n&0p$SMMW3%t|+O7+11Lx8N8W?E5 z^}D;qPOi4*KfF>aV8(XPFLLk+4g!+>=lyB#^pndIT~*c;RYNxH-){KVSNY8biQwuE zPH@0KWI?%={dayykLT#<%^pCG%#IxpnHvl~Fgy%-U~2sIYftnmJN#PTTm(4+c>=az zY-(m|3f%Ma_w-huJlMY|5jcB2`c^T+!t zP=LJv<7v3ICquBnb?Qx30>xkLFQQc6oebN?KT+7A#!Ek5Kh!tOPU;d{zw%zm6!CG6 z@h6@9H4`}ev{oL!9h~dY)`BZJkZfaQFZEf6GsDk9%LB9hOA{7qQ5mk4m{-0GRqfEV zQBphM4tK$4Hp$A^QH#M}*ihvJ4`+GwW@m5V z9S-*S#Wi=>-4=ntWSmd|Ds%6P1V4dHa62Za-fBjF4`0WlzXqxT#4u%$36G3L+zU=< zQqJXTPSujI0?$#$QR zyLeX4DMolKiq4uKi9E?IPZKdDXew0<<20-k8WjsZn$Z5L@x4^EyGQXQc5fsfVnKqS ze#vU!_NzxCy81EY{6^l#b2ceGBZ5HQKcF0I#s0>%G`gN&;(AB756CBHWz&JjJ48{} zdMIDr(WI%VqyWIO{7pO#fcLyT%?1CwqxpGhiRZFN68Ixsl;-rfe7)I4ifzm~9F%O% zem$Z9=Gp*%mCO6XP3-I%oIItF?`caGS)T1<|KqAIA%B3yWh`oC_>1zeuOYumq9&eD zNj|jbdLgyWsRdZ-<+7&TZQ%+rVR0d{a+OS(r@|d6OOURAr6W0rAu2AS1V0B_Dskw5 zAL9?GOv5_a5#l(*xSU_m{IEKTee38lms@{p0m-7E@{91kYV^aWjxiN*!>ax7?`ZWE z)q<;RCX{W=hiWny;6g;Q~MJK zO-b#QiFaYrM4gIXEX^is^dOWSuAHr3Z-E<|R{2Ro(!i|Ehs#s57)YOY2po5 zhHm}l>`aY$&|&=eH6eBM>z)JH$3=Gocc=dd=!FFYWqLA;9MViXD|V=PIS}f|S5)rU z>}HW&mRf`tNj{lqgeUeZcps{y)O9*HcNas06zzF|q|IF=vSEBJ*1hoQHq7r?yYHEw zD!Z(9$37)2vKCT*e+zP}$Jk6Gak|;YQ@9Y+(KY7C{+)HIVD|Jy)MKdeLcKa0o1YBk zH9x>;lwNEr3YHZ5Ur`}5X`6<~?w?<0UZNq-G)R9y%D~T7VJ#wk!c(uG+uk$f%t?Ws zoNM-yvkvd?Ejy7gpwv zxP>XlrmiG9E`xmV00jYOxVo&<%-sm5&AU%y=?Mg}5YcX9ziz3A1mn*w4U$e~6_TN@j}(O?}#gYHh>!o<&M) zxqT(p=(P3AnH4xWJfk) z8b95?4D2%d*+tJJy=yk6m^kg6q|o^Cv@yDWEX`s?ABJoG5Jz8{*4Bf8=_kcD4-P%P zhynV0cU@ts6V6%t1dAU{B84NdK>Ubgc6C&UZPGqvsQV$Cw^QQcjLX_wall`PGst^@ z;Z+7)%5K{Ms}LIO{F~puyg9*WYcqqX8F!RqD2_$A!(Z+hgwy&Jn&bgY_YSS4n6&Km zmUkgdHi|t8pjcD!v?Y_^IzT!D@A+>@`tr&8bOkxMb6A`?K8qy^R9np3m4yhk7Y0wO zrT*0m$QG4%7_h$`4d@rq@Q+fVq0)o~|7hF(oBIPcbt~{Au2VQl$ z5voS)I= znpDd~-c7Vh@g=5uqSRqfcaVCbVl0v~9vjXDBVLb|VX^S?MGv$9{%^3=E@*7e9=u&7)qzK*<&W%4b+N^X**0n z#9Ah44?~h=jf1ASX2=Gw)!xtn<>$^3T+}xmo@GFRa@@NP1;mCZp@%he*Feq^dju{* zML$57#25STKamiw&v+f7k(2rmpOcYaij{Ku-k;^ghyQYCQ7XqGLt?j{#+l>Jn>u&0 z(C>`NU}CHIS%}s(Ro8+sj^31~<)zr#-JZm`PD+wQ!61CUnyptmTfS+1)Ll0*9jDNA#JvXo#|ia^xG8U3SP}ot#^W~FY6t(ekmLxN4T{(% zQlPIM*KS`@wzYcPqzqf4`Dul&sa(rOsasOvO4+&;Z&Np4R6)nZGv=9@Z&>c0j*l@k z3f+cOa=bdS^#O^pLrx#T8X?2+YsE+bKrv5=&9r;+r7@wm@SN4wK-r;|9e)#t8hW$h83xa}L(SN97E)C7zk%n>Pd)=&ZM=PTZyh`eTHo*{hM zu{HG`ZF$kR7VT!tk`~&N=DaRDQ}yUKW@%|6)&qcS0*;xeH2Ro3ez+I;5k<<+l4%!W z@UtE_9VzE%@DW0=Qh11e)yUD0xTF!WdH`(qFcrK^(yl2%=m>+(PiiT(NTMR$^EIz z$)jJqmNML#3z1eKeF7Xg*2G7XBdy@!Ne8`l=?GxlpOx}7eE6G4Qnd8r=+Qqc{?J`C z$w)TEyFj2hvE*mMH%!aaZ=>QoGvV62XDP4a1!5vL*mY?@!x{_tqY#~up3h)f;r@o? z5eCY}3iz0o75%sa0zJhHCQ20B{fx|=hnchpmDC3Msscn91wt0yW& zfT?bLtocBaB~T;wmBW{fFd}cL7QX?r^JC&MicOr!txRFm=hC!1Wu!V;j00gsC%4X& zZ^sL+f~t&qR`EbM45IQZtSdbjMmltzk-_doDl4b^thLBh?InMs5MK1YH*a*aEe}x{ z_tJnBglOqt3gj(`#~Je7hlG52+lzFlnE;h{v=I@KY50i%2f9AL1bIXcs=atvKTI)9 z{`yg3u1L^#3BhIJ55!$cDvnsFb_f?b2H!2KfGsd zq7E`G2eu74tY5@GHgP=D&ns`4CW8DzNcpivGaUhHWRPfN7Tv=44^Jt~(KeonDyd)TGVUbC@npb-&RGVQWBi?h_b32AYl*gFG zCz3TCT*PUP zlpv!)S3A-W?T~EH^bSSVoa*_%xp@nWcG=6~IU2dZ>s7Rqu8BDNu6~UEJ zUAIsev;}V#C4q0={)i?NnM_H0KBtr$QORO(eb;Rz=(_Hd4IxI1T?1Uf1P9y9j5>>p zVMa(j<+1EEFupFTSN2Bk1s(#)wQF2TZ%PA|p8(4u?y@;CheGJ0g!JI`DsHNx-kd_= z;096izaQV*LgA=qi?S)&a><(d-T27$7^t}K$v_JQ#p){c?|sA>Xp{kKAIU%lha)g- zc)LS>)arD@L#>|4EOE&Qaj|wuoda_sp(e;r&vG$dw2WD^oYelWiyENP=mv%#E1>jVOJfWQ zNWuEU8Sz$t~Rpy zexT!(9M0pqA;(Uqdi#!DS2`wZrT#$opw6})CcVifo^b<+!y{9ga^7Pgm=n0)N;W?5 z9PdG#DvU3j|zAx!E(q&2YG;={o0;Qh>sf3zyW0an@iT^Td!@glu1%!O%oQrp+ zdG6pi)f&9=Dyo;5I{sI9x$3p3^8D~h88x09sPovH$&UChaHP8G{oK5~%@Wd^FWz8- zmHgwB#AsvcrREZTZ9Ue&vx21arB^2gTF9XT5WXdDvf0%-1fmsnQ zDXhI=t$ijuCyuq$vDb?D^M4-maQbR1PTJ~#Ilt#*X zNYFEO2rrLP#PZz(DTNqCN9GYJhkJ?HNlw!ar~fI$g;pXZ6HKOxNW{{bj~_ngM?g7A z!^?lqQ^(xO3obj6sA@TyFr3mF5+!KAusDSvz0+Vhr})(omIy5mI8es9OuWIuMS^;z zFv3Kgml@#khR6wg;6u2Nq6}q&!*AxKPZu(sV8r_Z~&NytFXrNEw(sf{G(g zD2hGuC!Bp{(wdYsa#mie!-(}{0`kB@U9-j!4~;JIpce-8O)WGsd2 zb+Fxu6T3^{SFUM2ywHG*$k2LO-!+1>M_ZQaJc!Vj&PzUTEs!!AljM&7*clOn#!j~} ziYZ5CcDqHea52voc3+;lOfQXNoAOFSU1fR3q#falT6Oz&d+~KTE-7nO`GLrZtknp( zlvBMsnI-c>=b_@R^4PFFLlCm$JJGUiYInCw6_y&QH>C zlZBQ`s0U#nq*5+0bfnZxmu2po)|?1_o}Ur;h4QhuhZ%lsjd*$?7vYxWkkbugcqt!9 zc>uE9CVsqnBEv;avfAqDWY0zOhu_8LTS#gC6}B=g*81A?)8nGNY_G`Q-4t#vuS1y+ zfS%%^qM};h-`HDq^v85XDu%rijtU~RrO+VgK+@tcxTJaKIpS=lpBrj%Blx7C|5P}j z1opDNZ;pdeQYN}B3q>xcx}q@MmKf2X=+;68Ds*LtF5gOWg+r?}9e)3}X;;zBVlZ8w zGf5@i%gNX?tgyx1gp*M4841RUqp2t8@vAi%MOX`FI;yy~P%J;&E}10;hG!w)n3(tX ze;7N5CSjOpNw;mAZ`-zQ+qP}nwr$(CZQFMD{WcRZi#rkX3o2?=b@F89vrph#B-DJ4 zFUWFP>X5yjrp13V#z-?BZS)(>>#lu?Xp^#y_T44pc*2gp)Ii|@dbP@4kDuVHbho3u z2vguR{v5=;%Cm)jWMcPcv!W(JwF<8aV&HO~8IhJ%<#H5$Lf3fQtz7A!gh>`5wnqs1 za#JBM`-D7tll;=MLZ>K*u+D*tHmSpQMY29Klk}l8WKt7TzHnY z)CO-(ZcWq}^B9yj*d|@5cV-b>M(8V~d~iQ0xrfK5yRhxmjyad8^W8htCO-6i(L@L< z2k#d_^-y6Z8^MpfJraK+1xNUXgNdBH$N?!us{Gw0OM%;xXeI2C@ zEyscay$(HtppAbwolha}vAbl8^=<5tnpl%3p@7m-XGMt z$GAIJd~w~@?($ZLPe6dHQo?&p4jRD zbxnr_>NY*#Uc&Wx%qs4aF}slv99EGVCGSAo)wqG z<>j-oQK!~J@E9GO?aZcxPq({qKm`MrhR9ogaZZJRZQ`Q$RMttbpjhR9D=+391W&#f zbVeSW_qE1NwT);Bjg^=KAp34CAXmS>NB47Cj{{5p&jVBW?h2T5qIsn z3d~7i2tRcUDXU9OY}8t#gSG0-Wb~U@$on@peR8xqDPpJ5iI&Jx8I2sPkPQyC(pljLTwz17$&rf)Rx?41eCS z*29F0*=|-KY3e#{=?O-w+cE!@N}C#RE)%2cPnTV7n;|m{w%P;kZpMGz>uL#yF^ZoU zI3ed+_f*!aQ@`m0QSBiL>)e7jp4yLu2XZ8R@R=H^LH)23Vv(iN56AL!HXt1CF$bfb z#wM^X37yKUx6Q9c5zOR_tO~E#yxUR#0@tRv%1w(|^$LZ)65q><1Iae?-P(W8_=D`) z3H%0Po(HCPXGcoN@T2ASalYrU1F}W@H#3ZQmBncT+;aS)?Sa~FTR&Gj@vo| zU2+)==fGz7l*8)T1nOqzv4=-$ZsR7$4aP}a${zhwR>U-9W$F?MtwT zx$Yzmm`DS=O6)~sw;dtPH+BEGbN!wJczQ+en3|OuaF_h_g&3;|L+|l5-963as>yXib8+?II;RLlA&joSeX033c$%_&{4k#Q- zOZl>LSbI*~)}2#E6oqA&wt9W&>&f=!V9(lh z7r~RmU&m?m2fpV`nrpaYF)32qvUb7U=@{XJ#Ne;d%d%GI8q~xIQ;lk)SuHWCSye}^ z^s48PhMcV3DMV4%Uyv#;x&6|xYk{9nAcpYpP?Q-4M%b}OMNQ_q647-jypSi4pc;Gy z{Y`yyS!zC(2y?5QC_N^hlK@%$_x5`4jWSb<>ctn-mP8DWYqA8(cWy4Iot84U=_}at z7<0z{n^Bft0jS%CG!^@}rMM=^p4XXVXIvx?#RhhFU}=Gx`6?#?jJ3s5w3LLHJn6d# ziQke{#4&Qms&_HM(x1mCyb|?Dwt7?rtC0x9FsemHA~dSCEd8x9uanQRIE8qKq?i5Y zCJr12;T8T%9X`+vA~lLZXnE$Cmwei65+ofB2CaDUq(!&g#gB3r5>(>O3d zL+6XKrqwb1lf&fhajw!j46SgV-0d7=zt+fTG7+vsErYm(O$E)K-(o>zvnFwXL%Q@axe>)3bzYJ9a@eYL72oFiH zgRf?+U8M?2ajB>B^W(&ukA7N0RH)8bgSGoPCs)M6xxu&^lZqhWeOPfL>Ahy(vpmWk znglWWBRZs%w4860bgQke&w*wmJO^T6F3YU-5Q?@PWpNn&%8gEBIAkU7Doc)nRzj`x zb9Drn%(MUe9IBc1wH0!2F38sZOr>M9@+ zV3vJ?2^%?0-3`1&Sv;b9_CH7gZOB{ZkwPTJnCWa+d<<@F=<-mE z@<82@vu*zMY4o1@aGa|%i3a>A&So*!Qcj1jx08)gSSO^PbMNkDE#!{dee;BO(<|Ur z`VJGz-LhIu=~I^FPE&SYqfMq1V!v}`1!UPKuV;n~8HBdcNYkz63%`zh!yXgn(m6|mnd;qD?7VJ6~clyzy1yN5INFOigxyccTSw7 zh<`Qcu)_xhW!mB4DREMxvpvZtIy(UiTWK-WBSb_dH=C6*$=q*?6oO-L5Xg6XymfM| z#*7Qw&@-6LyNc{WE`|AJdoDW`9Uvo-b3Z3WPQ+_9aK82D z4HXR+`ZJ!^VZer`$YGdH zh>pqfWyZ!0{&(4iyjxX^)uLlEl7XTFu6p6lZFs!{PqUKb#0DcD2I`UeoojEhM1G5s zmi!fu$2wg(svQrfj!x-YhjVAv0t7yt&yn-UTkUOQQZ|>OHq>Z~-jjyaBn# zTjs*$bcYxY>Mveq$@5Ti$-%8eCP?UQTnV;He=q+c6Km<>6wKJSty`!etTZ(}P&{=e z7j>6A0ZW?vI9;-I5>AC`OzW%z`fX^QP&{f&{RgOfJ72f*4vC;*ygWfYm+}>pfuEx5 z`lt+J(6B*Lqt{99#+c?)x)z$v>&Jz6VZFsHiKXFc>I7RDa!y-N3l7Qc)#7Ua!~PwM-0rmIVb%pQBHP16lXX2VC^en>W`Nzic`RwjJ8|4n4#D9+(5J2-^m@65 z{D>$T1|Jk*7l}TYg$=HsJgCri7Ba=`X1%(u&kg<@odcIR$&p_t$t|Rnn>5~dnwl|J z!=x%ijp9@fSoK||a0A+emdPT(a$N>%gB0+yAkL{B;A}+GLAB@V%}Ucz4;-kyMRXcU zu>OnFd`;YNUk=iNv8{?<2ERkoU6RL)t8t6udUDaQ)g_WNU`#u$;Yu2tWa-o5cr!}q4;t6Mn6XDk*G-xw_L$xFg zgncDfG;8{`HjAmVr$M!l%cs02HNK1CB>~Ke{>QYf55IMSp<3}G@_ufV7>qGN-hhD% zD!@43HEuKo586l%*Zl9LNQkhGu)g{vo`pO9CAiiMO$?aN*a9#tpm1R6o|}?rVn$pI zi|}HUIJ_lrN$2@bFEP|Ppbi*I@LgTs#S@m6ETp(YZ(7fG?&%%`ZG-N6XZL0^T#r^v zRlCAXwyIuK#eI&wsVnL6dUa^}$A=j7lD86O`S4iH5c_sraxmeQLP5$D_3V(Foy#t= z;U-MO(Z*E?E8&`Es-&NB0S3nSJB?NXr`#@fsN|0jeIh;}C@mti!EpS9$iDjDWBRKtv%RmU4w8>U6 zY#`xb*M8`t{@NmT5eL$MW5MA#Y+)lR>{%41`DLgOiv+U%dV&x7=o!~t0e}{HFqHbi zmWyd&=6yppQj#TqNvI0X`+hAoDo+!qRJ`Kkaft}?iT9Hpoi;jbIS6ah(Y=FOq|I52 z>66MmqmE?;rBM)^f@I2z!$h4BhkWc;yk0b33CwP*@D=spVstdc;rDa!&;}JGI-(or zfN?Nd#1$^D6`e5SEzmrI`FV-bm}P}vD~V^)=Q$mY=yJE1*cH$q`F>)kE@H8q)Bem> z5-3ZW(dC%8_LRxc^BD%6%+^UOf*&z`L8$oVzJt z$jL3Qji5SJ#Vse>C6@66Gw2FE^)upXDT4!Dzd{@09vYs!sxEpec~AIwM1j(;N9%A; zc24*nJvGT;o{vx-A1J8gRiTH*nRKNw=-OtKrs~@8>cYclweeTGh&d_i4NOKm`XD>0 z&;JbW0dj+BtTgKW*;BCc9u+mu6iSd;o`tY9Emlbs%>6A$`t@97TK38S(PNehf%<{8 zhGR6vLbbxrV1LIPi53i9$pY7oDTB`!%SV6KxXgv|!~9Rb*c7?2ILr`zXW@LC8a2d^ z4D%)|BUse+PZw?d1EmQz z2-VD4ErrpjF;1eOax3tFE9jorsM*D{xP44x3LwY`NAbRSHbl&Rij6%}+cW2IpPe&UDQ;;I}j1x;{Z=}UCc)v6r=6*f!A383w#;LU5f9cY z?Zc4Uk6a8glQdj&6y=dwmMe9Gf&#XZ`DH~{fmk-pUU|%M)Zkdo7ecOr7{SC5eCPT{ z#h#J6lO!y>D`dO@jUZB{;666cLPlb(-^p2C%EU4yJ=iX02lC~_mG*WskR&<~6&Xn9 zAY)+d=+Ru>oZ1#{m9kHrW|e900AA90E_aPQf()GgLI6uT1E)RI>n797_VXImAjLu% zxer@!M^8D>X!rZ+lt)X5u6WsnH&U7zCqmN$58{cOg8V{X(KLHcKc4_lpF%oq_O(vy z3Z$C4dqm!UOFdF}t)XGH0%WWIVCB$!C2`qbcQ)8Z2Xl7x;O-CdAOmj7b!=Q3^yQ|rS``Da=Y$z%6TEX zW4XoTIxqhZDT*f@X_=9{T$1iC# zVCYiXTCTLb{6Kk?D$j$=p!bHuTnXAl-N00s>^L=dkWpYRvj~0+}R2-G|yr7i?n0n;9*JOJ2nm&MNOOK-s+Sufr{OD%#S|5K3YoC;Q%unF)huw zeD8rfV^kIhNta>Ml5J>;{U$*mJNc?E?o%gS`059BC@u>EE`}u@fa9qN9g!^%`F}`k z~Ui@whkMN)eAzFp}U#u(--HM=w0euBm+H9kS2?60-BRzx$Jz&)t< z4`QI$V(L2X+2y6Bcskz5cBv*#*Y<1O|DYw31b$rEpgZ%h+t5II2+D(O8_?D%hbk@1 z67uc?5LRh-ZR%q4tL`EnM#39Qo~rIv#yYI7oX*(IjAdxxuHq>pJxA*N;zY%VuG3(I zZq&k#*?A@DvRYFJy{g)t4BD_&eX)VwB39ZUOyRlR25b`vcD3sB$_|2-lF zT#TdUaa=o}+$b&2vF(SS_A-4N2PwGvwkt0(D3r66- z@x|p|=`m}4LlA!n5y~adM$NHKF!5`jG)m8uuP|5DOn=$Fs<%Lo6u5N4KQtX$$K>ZX zkjBmS8`Fv^*KhrXtZ)I@*>%Lz)v`rcKCF6v8)LOpisz=_^p+};TrRJrA@btUp%|)q^E_^oe5Z_Mdq>KEK{>D#9btw=x(5v(#s2n1Tia!y&LPKdz4ZWow%D&t zB&4D7Rh!W30m_WcaIJFaQ0(@Jxl-s-d$;83VVd7ebfmf}_JKIP;Zqh*bPUp3$5PbF!&nd*=B~X6rcuf>-smjQ$Wo5ej9m8!D3k z6tzRCP>YW<0WY=Qsi6*%(5evfi8y_+4UMPI4|n$a;t!M6(5fHEL?K8CEv{)TCvwzc z{@3KcPGx~4P+wSQEw)MNH}+qiLY-epp{8(>YfzQ2KJC zNn|Jo00fu=_YrsnU&@V~%Dv{BO?!Al)~WHdcSnR4I?M|W0hAuwU^8y4jmHnd7`&4x zlnuwgY`&6rr`2aW63rSG064V^@E*%8t+FMs#7tgd_%iA@(u%13LjeiUtLUN67ymNl zNFjg-Wu5e@K>ffM#wYWzIoHvIv{Ihrvg?qWK)ilz8SW?nt7DOh`#Fj7%Mb3sA$*Ga zwpF)RuBKJJOkNGs#t{n21n%baxNcx|Gz8Wb1Q$@*53NRWd#f=hgb}YTIe24zK)2jk z--U1e*x%HI8W$Ds03lupudG$xJB5xhwHw}DVI70DkKjbvUzrh~E1i@A_WuI2*c zO_Z@Bo(qC#<9#P7u|eHg$4{dR{G-W~KX8V+z_b4)p}@}Yza|tIS^uwu0t+MK{{vD< z&-(uhsjO)?ayGGPCdJA^^%`r{X;5gOtk56ZZLsMwRI^sL-clWr7CXErfV9eakb5`rkO<{`J|_;lsQ|e(AghVSWH1 zfN?x?>xT<4XC|=Czam3`bzoc@YX1B=Gk;JB{ZsS*PTK$`;tCM3d|7@jZ1T#1CXbYGD7kPT$a>Pu*BCPfR<901)f$`fqBD`jUjD}j8`j4;~Kti(} zP$rosJ9-ANG;}rZ=ToiL)(XhExwRhD_wmzC3NX5wn)*+s%+%Jv+T;r!F#E3nXfyNM z?fpL-4|J}Ers`Q%I{VL`X~(Zs`8NlMtmW-%-ukZ?1(Yl4pT|2{ba{CWc7IYrN)&ki z`0T)^#~Ux;gJXmHpPk|_cKA!*EL5m$ESfFA&RnO4`d`hj-}mp;^G{z$LOn|>(}$V0 zat@4*3@_OYALw6sOb#wCALQ@bqo3*z-`w9UH^Mm>v#7d8Gt()2qx97Kg>q056FY6~ z*47LZ2Zr@um2M6FUfpEv6dR3oR@?WOl?%Pn(7!#esIS3@pRHW#onL#lRu&gEsC(|X z`K;_#GJKz)%9t!)K7Wlr^v5}+8S=R(j}IDhTw1i4pPUCf%FmHHdf_CS>sWhq_-5Z@ z+7I7!l($!M-q8w|2K5_rSbaT9C|TJGq&U3WiZ8KHF!0XWe6LrC^CqJMiVs)^??gHA zr0i`!_T5$NJ|Vs?`>mjgIQFfp@!D{Pku2ucQmS-S+xZVu`nLr&ONJY2Wwo8Xb@G2! zAl`9EEgf`df2Z0$%vw|@04v*jef%J*_-V45P(RgpYd;7(=OCz@j`nf%Gc$t|+Q2kZ zx(ZKOq}$cl#NQav2_TiivoXZB!$R>fOdgfkeB^FtcP>gI-`I zIkyeo7ktr{AWfRZDx?5zB1kj~^R36xTmm=PnW-~mc~f1N0!|$q*38LZ8DF5MS2TX! zKsVv4(kHEm__Ov4JQ@R6rf~R1E6)p+B;8ySNe9xx1%Sm_oxp!Vb zYw7Nf204d~{A4zz;`cqRI!A(3Ppx8fT5tM$doG5yN7y}#N0n{T9VG}qqpedJBhcW% zSB$ZBL^BtGu)8u{p&2(yRH8PEQFd2%y)3#m*-Z?UhkVhkiW@!l7;2t~)1V2pzy1uB zVooJ)Co9u8BN?NXE6F=ftlpIEIX9xF{;kd$^|W7Ew@$dnhKE~Ywsf{>ysxSS5pLW^ zaaj@pcUTqF@%R;|vW-c7uQv!%A)N+kKeRjfT*PsG+aakKH3*b1%Dn0s**!z_SXC0=|Cho@^i}$=7qyW9iWjYTu@`#Ju)C3pMMQ@DlZ~n zXq|Bh9-VP0n9@GmHRVnn);AJR{cN#iJtf5VP;$}{)_dhCFu$lnNYu-aKhDlO>m^*g z@rVYlr2D-ko>0Q2H z+!gg2AYlcM5I)IM6`miL#*&xDw10JnZ7RDaH-;b7cBs`_<`*-gAl7=#=HZj76A-8b zT2G-$2ZgK*lZ;Ee@4jC>@v z%`k4TT8eExALIKol{KkUG>vLu?MrESj-3t5KdLO4%=I*8C3}xz9|EX7O?3pm^#O;L zw9q>+4gZ2zJ>f}wO{*=1eoEY(a3QLjk4v>zMjg9pw3v-8@xT4p~7UTvXI|AOO z!zAsILrjtcE>Sat^WU0?5qdX>_U9l*D-qXXto23Sd+|hAkGL)-e{8$_pk{ZjC1m%^ z9D+cX%4cS5I#hEzr%9$5q)2kyQ%z!Drr@hB$P1LiayYpl+F>$J4iMe@lsO2Tv?UV& zm=vCv65c}c#R*ktLqRni>{7UFf-u(JnA|9pqIU_C=D+C~jj-Cr{SN9CF=6cS;LBDa z;a6&WF&t#t8^f-#eqL@o#;04Bxs-NzQEm34l3VfnIa>+D}sOHTi0PsT; zj$&=ph=k}daK12h{wx_?O}PpK$lcv+@6qhxwEPI)bV?f)rbEu!Rp5Eb@-%0$SeUgx zi-O-yos>h6ZbRFV@kkUT&%y}OBkNkBM!f>C(wis>K>`{jpgX0|H%Q8$ii8?+v)o_K<= z|6SzpDKDNsW>7krWse6$N)Q-yr;$Uhh1F^a3eAaA z77y@}9}#B-CtXTHsUANP&_)7OQN<7sMi5is>m;s@#j0{+%C7M+O(k>Np5JiU3XHoB*j^rjr3jR`LKwhXDcawn zOjJ5pfXlHqH+%U=@5_mJdXJ7)KVmJ&BP7xSk&5efR3p0&W!Qm3lrRK+F}SEi{Om}k z6Gr0RkUsOR7dd;G#yZNS4!^*vJfa<046c+Y6y$q|V!_@9uT{Lm`R)v8mv5+qL`oa7 zfIlVO->6-*&u=ab=awA3uohhR)RxEKEVM8TY*SZ1@n02QywxEk$2i4(pN61ZfvE5t zVZDwOfB82MuKfEVG|GW)>~6LbTe3XY@6u8$Y$ysT($Z&Sa!@&X5=s3u_3L(UsXGD-zN!b( z438E^LRgIGAHsx1!_xiIBU|^rm{&I%8?Uh@1%C#8_yUAj9EQ48LAkElAy+VBJ2yi~ z6TUbS1s*Qyd%q9>?FiVfel!SGqcMpa?1neZS?C;LLPzPdh3UW?emy(T9WErTu8+Mm zH<#2xFD^+N9H zXbB9U;gWJ9UZ4@;h7T`!A{5ID*Vy=JC4(I()pEb?K$C-j8cvuoElAi(_OQM)p)_Q?xbhRRk9O1@m> z9M_FeX{~6LtRo9KVwa=A$&&(@Tg(*JvA_dA==kU2YuBscJRPl{wZ7^#E@kk+A>pU! zq`sW|E^Q{5o_=^qEwohMcG{ld$aOm=^1C-Lx)L}{A zJ7os3};b>BQDZXgWs&b zFzTCZcG@X1rFH_uX8R4?wG~%LFFUY|>hOFdTb4GQ3u1!#(-`^dBNV*N`r?S`CE|wa zK+?sR5K&JmGtFmM@2ZFqQ%;*6uSjI#FDvYH(K+(URR$kPis>W7`2x^M*Fifrg%avS z!P3CN=_Np!mF&H)nV?`J5OnZEQ?~EvP4JI_M2`nE4RGc$jVv24UY(KBJ_w}$9_(J+^baCGCSJ^??qaaQuWR;=0S>S%AroSRfzW2eBf4HR`s zw(s@WB7;e;fj_P>D4OUTw7d33WLtS+p?Dt47uS@*%b%QBY{O4@>(LiJq zrNCn4jGl2a4-rnth_#?}DYkNe6LB zGE)yhS7(FDi6s00!z3HRdZ;` z%JndpX*thaSyV*u2)F=iGKY*h^aoS9Y&6&q!55xS(~@O%AK2e=vb4Yai}j6z-=Ejr zigwD)sm~By5NB#9K`(9{kqL<~+7v8oQ}fSpZtDXf9v|P-gOkv-s#&( z0I^*#-jglBDd-2E+%57jDMR@n+oCfIr#FPL(>z@oIT9fhF-yR%J7xE%OP|U?HC-W+ zT(v&AB?BqD?m*LF)-}CyDjkq)YX=53eAa2H@~U$@w;iLITJ73Rr}G(6KW&v}dncXI zGiFqBag=D6EOoDq&jACYZqK*fW1yF(gIppG6N|hiB@FPFfd3|XpMro+s4rH7nF17X^7eqJUi%r#5+#h3v7u4+Fs zVJ)0ejc=?Jm(DKZ5C=TT=0U@KII6}dWyflRZo2;(_Ol|etJ#*X5PJ}W>W9T$dene< z^*pHEk<{2YyS&6nlfE@`nq=q`AFEXkl1mP20x^2}_;=P>+S`oR63(t!Fn>~v8NjVn z@vLV?{2#-eH7_X0r56Q1A0eK(^%V*rPmZ|vvvQs%7@5bf)gt=!G)9L}ID*vGVXIB3 zM-P`$@337^@7Yh4QvF?(vK7{V7t%ICpt|~7Mt`^6Q%-Rz&aLJLVR;IiBJ%<@7FYXm zLpBb9kx0e(phcM>{TU)&sa?Bd5{luYoVM7Hx;^SU^0()j8GX%>?*h>$-N&EB>+R9f zYrbp0Qnm6#+JS4qNJTw*I-ds|5CAml5)TmWB$vSKgmxvqYe?p`OGB4}}IWch6vmnz%gGD%Ow2x?h4L4=|CZ zvKWms!-7Xx=u3B%bM3EC4$hnL*r`V2DhQ=2>TA6^XxLabH-pQl{xhmRv0CuUYvFXZ zTcs>8YsB<*R!AALvr1P4?69`!&7z+Wa3pWNS+dwcaisDl=I^XGjpRnFyy^j)^{^aT4h{d#0&BYum=OI3#W_5`?>){;RZBso{KyKLMQCY&cg`Hi z+9hWSJ1Yvhqe(vizQG9;-LkwcZeX;d6FhvxR^Yd=yu$#)%Yd=OM}`Syq{~XzQtW2e zmk{VEnQS=K?n1WyCWPNHe~sO%OHy+ZE5=Gg>Q!(sw%ID&0F%!$A1>c`PnV2}V;DUq z$=qY9z#NwUvI2~J5(_O_f2v6Az^CD1;WBZmfteIOhm4OKp7%w|h$aZ+ zdeX{}XH3=j^y3OoN8@M0^JJZx3ES1q-W+%ixhZfl@I}idBBPG{=4d5Pf{_w@6ohj`5|dCM0&di#gKZRdm4_6pO1ccP+>t9kF6}fo3a1AAgB}e0diziPWvY)SZ3R>#CQNVxCgo^xP z3GOoClE_~tb%*=j_ATFBV0Y+i$Q;&0*hH67H|VR`KORgXs}1+_wiR-19g9IF(req9 z!t06P2?3(k$M6wMslM#;piX1PfMd{GQa}8HPh6~i(*q*-$!9v%x??)%OJzxAJC2#Y zb!I3~*x^K_UCY!Qz}vd}6|EtV5Y3_Oi((f*8!J-vwkAbISKwq;G`!t@AaN)*Tor}3 z#mHQ+G&_4*c5?i4_*&C>hiosv++n*5_!^KAHNh1m;1#Q7xmQ8ZEg16iULQ^TdaWm; z)~`8YTNbvJ(gWOXyp5YWp>@`+(Yvbckjqv|RN_x} zN|UmYQ_8Usm!oA6$Ah!dy7I^Tu9(bqhGY%8&uF{Q_bTiQ9MTT0^C$B5EG;saXo8#U z-aSWcEpRISr1`krb{Yy3pWjI4ygrQEdeyofC*b z<`HA)r)T*=LwcpHVyuQ0Ylp8(03mo5?qV~L4G+k5T1v=tO_5*bIFIs^R#&#yuHTMuCzU-nNVmF>i`1D0*}5xp1Fp3G1Mk^C<} zS_3YLD+r!pxi1(N@QTq{0@Pq^U%r@6O_&(XOn1R4VB#1N1*neslOV>_y70iw#$4+R z`28Rqt?%4GPpDg30kT~$D$)q_&%|cNUg24^>tLo!d>h-gKUorq^@zn3#ZHWNZh-pF z_MZ$QjGOz^0+gFU0IapZO`0o(oL$59v8se}V+=2zx5yfWn8&`MEJQ6|rO`Wrn_l4x z_hm{lhfWW~g)hzQfp*;r$AISFmbS>yVjztJ%k}0yMynF!Te(r}P2Q}-VyYWx5Nd~X z`&4Ix(3gHGMB0Ca2-~*yyo)N1{Uq99jOB7FtpJ&us*v=y_fZH0$M_OHU-M^mjTKCA zKBcEwmZIq=EpI2r>=M^GU-ZsUAfgJ7O(K0F;=>o4YGq}ujTOdL;?)=<>>ZoiX6t4c zJHuD7)qEjrN+?S+>u5`kn#@W0UPZBZB?q>QW(u|zI$BA6ARmZX(cxH~w*0i6hLBY- z7n#!i>3Txrt1@b?xwvp?O)VA@?0RQgu<$UvhM=s8!7n{%R5(>Qyr$m|O+G8_u?eis z+9`BGs9xIL=5>5#qy22gP%BJlc4-xSzEfLpC~z=M*r7RoL9@XMe4n*Vk+K`^td=62 z>{0S2ksUpo+n>a!@RImpQ?i1lWKNA6 zdL?2^mOzeM7hN><;V=A}Y8YipE2M;{Y=FF0P!v!|p$;)LiQYn-ZAiFCt?>fdNB)Hb zIUcxagu)y}$ieBbjtJo&;;|m_<|~}v^LLxoYVXIOj`~V0<(CZ+Mc-*vI!mOx=&r~Z zz9^WtXAFswX--euq5;YX*TxKK-PyX@cq=MU=-YWUxkR`xlf9RA>1be;f_#sM*L58q ziIgoNHDz9#*h>EQMYcWC*Yn|g`Nbt9Y|ROv2RWi1X*BP!wm72dg+)K~>%+b;=un-q zOK8MswyKbR(>Ny7EZA0fjx05D zKU+MxZOl<`K2V>(IN!i^+^(Y+luLnUeDY4a_Vevki}`EcS-$Fl#MqPq*9D5HbpUxIPN4Xb?p0RYP_hycn;|l zajMKQ%yDHOBB0m9 zvDs985M(83pq&mk|+a-zvB?dp{#jSn@&91pTq%j?q_x z%s^J6-G@KVQf@8{`9M(ZXM zRumf;p-_FK5toe>46=2tAS|3+=(`OUSd|C9GM= z2v7g0nVcn_d z{*E$%aG{h&-}AOc$tx{1%B(Y;ovEu}`+bogcUiQeQKJBOY~qwuh#~{mcN`GP<%9qu zKYivJANPJi(3DVy( z&22a_UI%#Md)(WFbgmUa!^?-?3sUGtm{F6zmQXw(sUTxoJDdfR7P-tGNEOSAG42nI zG|mRzEfXeo5Gto;$MN5n=+c}k|Dd0 zc|^lwN#lz7G5d9cDq?K*adR<2g%FhvO?H|~M9Yk)2}~tllx)(&KTA1@Yg8?K_(Tcj zXJK>ZQUSw@$gD>y7QAMUvZv(u;&r>>TtnWNItek@uQ&0CwWYv=d731DYu^eZ0cenF zG}tuk6(u-`6{Nrn8_pbrxrf0U{)vJ_FyBvw%E#%pjv}5gfB}-aH-*u zg>^iw0J-U-0Gj8WQ6q_*9fWAqoPVf5R2}kcDQ#<6>0AzO4svjIK7B`BQ4b6(v8l;n8i92?;&|3g*=CLECD;sH~1Gp18Q0}A$Mf6ZIiy7N_ z*~cZ}n01WqYm0&wr(4h)q2GK5n1u**Wm(1}h4lq~19c^2kN|3v7|v2cG06a{FI7!8 zb2jjN3(fBQVx{@W(%~bAlIYut1HPFvS2B17U9+T0Y)Fznt6k9&rWk{5uB_5;Lzww# zVoD=nAsL#{d9rQ8sGl1T$U&P@I7p{p=A-kTmeqj#TsIL;U_#)^hX_$7< z;sZWpcwBOV)$Z8q6B1!{UW_f;fd1j$4s){&f+s|A=*vwGX!u20Ll`7 zaakqb&2sZz{pR|<}PgnXK@6uZpwP#j!Ba#Wt9`hlE-9IY; zEC%E!wZa+*^0oeQ69p7Qv)r%S0-1A$Z%&UE@+whdl*u2X77BKtmH~`DS5i~KT@368 z2`D4Rxd)Y^3e=?H2|n$T&Q5~SCyBtxz}X>FIT_i3s!as`tciS$!n^#N@>}zyX@>i( zH+8Shg->|A%%k-+lnDI-7mZ`5`@Dq__+!FVR&m4=u!~P;*~|_PdEFo|NP@#rD!v?T zxj7vo2{FezCyd_$^NMfQPXAz!@r@ES*1nG$b5_+T*|!=tDYO^gZ(vIut`4A3Z5`YG zZP(U*oOs;u&@#+GID^AksR3mePts68EjyIFBF2JZ%n^{ae+a9n-4mWplr=-A^u5Ff zDkCX;f8l0Ddv5Aag{Z>qw$0CAX4_pcZ7&kLaDmeqXl*er9>=H$*bNQxWcR}QAj#P- zYi%w&IKO>*{*nvw+ewi+4cLU3?1qMS40PfF(?6TyW`ujtGW1Cs>{0pRUco-rQw)g| zg7ph_JT#V;W{8*xyG_@eptsNx-cgG#Pmi=hS30MPr!r0*s=MRjI>J- z(`&*>8nN^1nQs|XRgeCvL>9Q`ryO}koI6x!sUj?Rw$mf)hUKU3kU~+iZ7c0M<}ES0 zGxD=zV}t|zV69z@v()!~nskuB(SX+uHz&MlE3G0Bv=ZJG@9;0CxO+@&8@RX6(`Ql!h`aY^x>rb(9>Q_S7q+A&q zQxW%77o8zxKxT|K9>9nMlSy-FcFo*VAfME5rIH6q3f=$);R2W1DHQ+BMYt>0O}@HA z+uU_5L&rh*6p2)vwt?jNgHMG0d+%Y+=`h1WgDqm{ptzn6TQU+)Nu}PiM^m_w{tb19=;+(Iu6f)netItGbs<)qu$#jF}Ugft428fQY~XcXV$a3 zSm^7%R`zbgzG(6M6i<1KAtEXE2klDjs^T2;#*5k}j>opGP%3`&rQC*t`4ha=trD4s zYy3-cZz2dcfhdaS68cuv4fv=rIq-Z-!#U^zbRsWZ51q74al&Hxlr#e-DcV4&J&%Qr z(5z0LqtMlr`dlmi`7yt&WBpP`H^O|{|0ZJs`2sGOBAs=F7ypka_$}A+8kdRuYjppj z16QT{f+Tll?lP&*YjW10E#V7E(B8R=*S2=}ETK%h793G!=FF#VdsuSudo#kq#!tLAm2>ODKGKb`!0Wut&^U5oKQl$}G6C@`Bv+qP}nwr#s#+qR9@ zwr$(CZQHhc-qh5;n5x;#E?H!oRDHSUo2R%;hkAn!7jG0C?c)+`WP* zvoxX>Y!?hD1^Q$Q)+tK0e*r)^3)_p@DuG_07JRq@5Gb38uj$ad&XT32u$VDDi zE%X@rmI4R%dj7>TN{moV6=>6~gE{r_u=4-fb3UwPkI)?sj<>%@Ywvh2hbYA&k}*L7 zN&9*8d0<@CMMmfJi{%>N+TGxJntPvfHFd)3lTXe7nS$MgcEG-p9x*967|w)8Y8LJc zDcxwpVBqVZhDG_$zhe$Pw4%E1r59;Cqrko^OhxfUMDL`Iq_&eN1^Z z7r6GI%%;pva*B4*Z!LV=+$)pke$M&{n}8Q2$BW_?;wTKa+=cUlWi=K2A{`1vR*|0$ zZLQNSNh+>2b)Qqwjm?1>kal;}l1hqB7>^^aHA>5?Ox?8ZmxX+{*KnA-YT5d~pg5Bc zOE{vijsp*M-g2WGs+Tm`PslpAI3T6n?M4Me2nXfUp8he@c-X?Hed$4##CWyDj#7Vr z)K}tmURAMch~4+rczFSrgMqFx?TzO~ijV8)2O%6x7|BHI6F# z6}gfBgUkG7dW-N}`9}h4LjO5IITft;jII2Bl^c9g7riDMF)tP8qj~XM+&iMzs+PE@ zh-f}6K%~x6-P!S4&FJHm!xAYJMP?7H)io|$m8L7EnbSDiK8c7-$D>>bt9Cu-nKsmu z@evU2xKNM(3p=9?9j#qZ%^vqieYCCWghFWhW#qFiz@qf?NSnQlcti;tQcddTlvBqz z7=E$W>RxbacOj`C9w*69g)U9=gj=feZ{NMubGw6-n0(Y}e>@FN9+c+vhFQ>NekRY^suF0}Vg)ykMPqQILxYp;NT^h{q%(!E zBz1y}pg2rVq3g3K{WO?cI69K9?GGRjvDCQPRCfNVgD(vTk71@Exi97}+kBxW^~NIn z4>od1B}lY@Nt?#W%;x;QJEh~19|BSQjkm_9tlnF#sjFHs!8S0q#bhGcg)Mlk>!5LS zC2xW-YxS~qCOFFYi#UPm#5P4k)-zOM?U5&9&O+kO`I%^ti3h!mw}Q6&7tE4TUgaoE zznA>G9^#+a-?7-Fe%U#(o-KS_sUTxlB&OUK6=bAR{#SK23ZtM#sz*%olprb%v797n z=P9;Z%wungK)jq)c$18`$Xzc2&mhEm&B$!^2O>!?m0RN*Tq<29b93NsaZPt0F-Yas z*dce@ZYj$tc0cyzl0nTC*G)2>Z;T5;R%wTndKSueMh~c~_G{}|R^+VHGD0|Tzt!0? zQ&UFm%IH)0cqLAF@OE2@Pmlv!&v?kS$>Uf290pk>!0p~iuVy*tjrM`JGxGR7%-R}k z(0dKgP%$ve<>Qoe=NU^kOKVOhl7dCNO&r95g)W*yY(+YDcg$Yvo8ANRo!zIGuMpXm zAKi_ewGnRC&_g?wczpk9j9wpshlHXz`2laEi8j^+h@XVN+g^Mk350ko8}jza5#sb;qLU+MeOD8jOHcMU z!>=)=;mLmk8T>3>IJs+NB;*tDw$ug;)O>%L#P<4w@ER5vZN}@n6&7v#vE#2yF`w9m z3{|rqNjq(W$xhhIuS)2jc6WS4jUz)0xvh#};i?*4lJnK7=3}n`F3gm4Gx%g-_*p{` zPoAv)_6NG@C(z6Ma&*8YJEUg8q8m9`ASr@>6!QA6(fHOoZ{O>EH#>sv^L?4}9Bn)$ zziN*#Uw!|8znOlA5{7lNq8=xOfAWB(vE8ghXW7~iF((Y^DK6T#7Q9a_p^~nAkEnu4 z+7jn>Gt=Bo=l=CiYlu0svMKQ&E6>=FM?2ctqHg8S*1v|%g0T=wnZ7kaqN6#*b;20*`h(L5VlnJ}Sqagh z%I(V?STseX>@A{M*`pO@-@=bu<8odrO3CPyn@-UIiOhXfY*e_GdSVNP?~(aPgxy^J zi4BPk&w3EG4lT<*{%Znm^2w!=v@n1TUe4XLq=JG4Qo|D9b51!m<6&wofc_SUz!F7! zTz_75<-#z&2haB|3`cXCT#TzCi^1L!8JYn+Ig#w7Y?5DoIdvFKj*XX2R{)_C+fi2- zs7TDG)Bf`Dmu{4)bzcYwuj0y@+ecn{ z8wo`MhA9NpnO5FfQ~rJ7kZ$?L%rK;-+?xSTFq8T)Cno>d3&@2Z9{D}Uo|`Agq@rna z2~!s0o#C_lDJg}bD&f>6VnFs8iRwaAGxpaXZ9@R!uJovTJ?yyzKqVXW&y6$Wa#pnD zk8HHM7iC9X@tN4PT#XYxM<_JCb@To%{H(uuvWDxW=;YzA-0I%~1Lu{_6=4svQ!U&b zOos#@QM!KN-O-uM#_WJ(=~>*GuS;*m!hFN|k207l8#aTv;n`_*$*#9~3EaXG^Qp(a zV|c$gTzr%$tlSF@wy>-ORkx4e3R};yD56gtDX<2~P{1+cL7xWBbAip=3oV4CeE1tb z_(ayOzw%{HRcAjqmO1l38O@!{5V3KI+%LRAggmk?>1;*bXrsNN z%1OhG5(nY)y-#S+3l7twcYGyO?ZTOU0bHW2G#0|lS=KK!{19&|4UKqXT%a_*()+{lv|9W@FNQl?~fpy-jCUD5bKe>t|T>F!+5Pr*jq!l>4XqME-HHYUF%DZcz1VCs6tbd zr_75jcRn|-B?adg+Q#e%UcQX_A_^LkQ1E9Z?oxeSloT2SHi)`W-%BK`Z+q=(iw9*M zYHXMonvAlba7jbY9GAR0CIO?hq5bH%lVpL0!=m$ALRnLA zi%D2B_uX+1Cre7XalnvdC*N_uKzD?A4*pG*5rUALrNL_74I;Lz2M*)}LuDZzAH@on zF0z&>)4L3ZR)bFoowPSS5M}Lkp&dvzj~g6C%$l-)4J@xDkhOF$M@>HBsq#kfg$0ef z{zepIEAWx0vGgo!Vt|NpJfjw^M$q;j8T>0u33VTYUgk_vy zw(5z9Uv{Bv!?PN{7G0ZBycpewNe*@7zH*7A8kf~s4u&OA7iZVr08+NoZf7Y){%2pd zUv2c8SZt)*uIw>>v}hh+pMZcD&lCWINvo3Wc^AJ9qm|{=gi$5|zhtL$RDcmw!UuVJ zl@rOoGm_GFzx3&;<`{|0d1!Se^o^oA^OpKTlhn+vkvm<;cT}Mr1cpD$V7U4^s(hX@g~UvDdS`k z4M5OiH$xRN>niP|VbMsFy_IdBhpkJJesexOo&aci`*!^9c)hBj{yOxDT>ULY(y2|1 z`KMixLMZK1a8#ZoDdnTHq1Dyt!yWiXI0%k-FiD3!mQr;k7e}R}O=!>hm5{7v-NV+g zU|567!}H^3K!5URFNW9Ul;qR5&nrb0xnO2I9zG+Z%IMN6)(@(`?8^{QTwvp$yQf_ka@kfGi|J;9-6(n z54N#Spy8-A{V59f6`^{1L%otn+wi9Ywqhu~KnnlLZfZQiJ9Ib3F`VPA?Ib%NC^gZx z;DOqct*(Eii(dit$Spp7xA| z__q#%Y1HQE`;6?Zzt+-a`2i!?-KHGU3JBiK4RUQSl9P$$f{da0XedI=m|Ry((P^DO z>!uqlX*>(xksoStw~NfTNb5;ZX}}+KLwpV5)3()7ZEJ6D%NJsM;ij$gWiT2Cd zxV$uyn6e_EB=JTdpVU4-8OqOFem-9_jm`Ey^KsCjYfGhUV9tdMh$gtrO!%heCE`+* z)&#~K%YhFx)QY;Es3isJ3UtNI3ZRBk1^zT0lnX(BaF&-KuoeeZI?y3k%7YH*%-$0TgOfMz+6gy^9uhB5Rkbb~5MZQaP)`!%ZKo`(m}C z5)sttW5v3Sn1F7=u%L^*7sx|n#&e7lj;Wznqq*z*Sm*8v{UUeHz&0YQ2H?NTFM6V& zVwy@cPe;ajK&c71Bnhmjj_u)H)Ab5bWnssr`K_W>GyXi;J**^sA^v$I z_9vj!4(6YNTcrP6+4@4yvD&_xw2`ub80fDVnpbLuH0`C%#Z%R`fmnIwytU-<9Va#Ljj z26u>lOBFPauAemds3Bprs?zY}U=8qDHL)lUya3n1_B$4hP(Yn&tHlJ zkYuzW2I1sw`^@9E)I~Kn9X93h`CdvY_1lEzOpkyL4BDm+FtN z4TQC8yq-SPuD0$J%gZ$Q-b$e2Qgy{f2bj-ZR6}C`BeGIAxizCF z4e0>W3;BhyiN~BKJ$Ev&7Z&bnG@9Eoq&{lL@v1uzm9fLC1IyHAf(ug3x*O4T-J8&EC z8E~2oo2rqF&U{@8<3qc&E>LovJR(Oz7unUfs-+3TKSo1jwrD66H4L?8^|?Q><+Ud=e7sy3a}hk5(W)o3V>FU!{Du*$Rt z@rlma0y}}hDYfU1*HFel!9k=Y%i$FS^wobqg6I~99xozF$;3{=FFdK{J-MqwLZT}P ze4VrLm!G-WhMD@UZBoSvo&;MSbo}@T-fZ5e{~8Yeu>_0rII1vz>~dasc6WFZEAf4x z$nwB)aIlR;Le2OR49EAZ=5c-6#u`&xY({0rDhUd-75Oe`Lpx?5+^{jDm16lu36V4( zCd|IyKQE8&7Y10I-?+=%f9h~4L(OF~L$~Uu-`{VI1#nHfo-^O0fN%)okdjLuYWDFI zjA?eH@>^_w>9yw`Oo1rf zXS`;{b@wfJFcq6mM*nnLFvd<*KK$R`hOx>I;{0j-y4zl7LzZ6mOb_ zJ*08m@b3(L`Z_?;hJI7mhaKY1rZzLd-ydDJ*Gy>0tVMcD?7PzQO&7@a{RkmQ2S9c9 z@)oBey>@ACD%-WbiVuYK0!AN+kj-fa;vxYnb4M74*{I*=9PO35DeoBnqfv;wu96B%1T+RV3l=}hNF`!CMEQy)i z8*Hfvlfgq+cZHMlA%jFbcx3GTl^V{_kx&Jtx?F&WNa6PN*0ZUT=eBhaLOoY~d~H%X0-GPp;^RY-vY2SXtO4nHX6wM^R1L!GHs3}Kadnj>U!cJ z2`V!G;;>;}%)h#a*eJkOy(gg5jg;~4aGI%$NG~j{pm|~@ytaAzu#3S2Fi^(5a<{o! z-gw{@U@_lss(Ie&8J&ipdtj>Fd*_=c)GuAT-6g);<7*sZ!v=y%&yXh#TuXR`e;4$s zZG4M3Jv3zC-3)(1nfO^vpG^tz;&4v*TlCtstR(?7ZtZ8C)Bp)DjxGy;10OV8p#ihR z+p|_ps-@7=MkhPYLYzK4C7$ZW+P=Lzs{Ijs`F8R~yM!@rlq6jfB{jG+LS#F#CbpWk zf5-VVkQ0G*EpKk<00WV?wzmn}I)eq`CSS9?PNukCXL8fu=eu`GU6*Sr z%vQC#Ga_XqlO=~>tbvk1Hn|w<85JF5i;N5mzEY3r z(fuPn`Qu+D#N$F}{Xf3@LCs-X8UZ)Bx|P3LfmH(p{1ZtL4B#5TfQC?#n~G730GgDb zE&wR=Xy^93AxX`Ut>P#J;EbV~TtF58r~2UlF8y!-N({7_=k%*NnR=ZfIDn!6V_XH4 z=e#iHrcuma(T5=FfVtNEad3BY0SUzYLxSq77e8@10sslLm95Mgd!gK0GlPEV#%2J& zZVVq|x)Uh_aIeq|tmtNwl zm+0;{vg?=G;a9it_X+7&e)rU`G{w24MUA1w1K;283bXICfUyO%>lVu&XRp@e&>Hy7 zYS&-pH&?<4JFfZD5B2kQC!@~~g%+xX?bGcF|BI*v?e>D9-ht8SYY@gU38WoxI!QpT zBn809=<@aN=jK0x9?ZE8Y#nG9^ykxdH%LSC7go6uBwcI$rx;|FpCGS#y_fy2W_|a# zv5a~=a(s;G3qAA2&aC(~!d}U#6&UEpj!f30Zru;(rvM2Rv=fjgeQj6T@W9{{?0J+66GUq&1ZP%SrX9+#dN+G*ZMJso*iQy^x)$A9 ziUGTB_NjJSYiRl*^G+@dPJ<-BR{xF9Z%^jHeE-AeYglFf;qyelh3ufZ@_-{?F4*vc zz5ss(DJ?(BO_NTKySC&paBbD1zpoukP=gZ8I1a|y;J||?!MXUMQi1rbC-hy-`AYub z^BmV_un1|aA>^e?5#sQ@<{$rq&l`HZgkw1VK`aM}y8nmIk0oSnMdRFD$m$#B>bT?J z-H3k0jmY`OTG@8@6*=zf70)VhYQanJMZl`!)+zBC#(z-9AJEE&A|-f!$QPoP?8t?R zT}2HKG#;mFkGY0G^P3}HlJ|xCFt@7~=CTGAE7mA1thf{EhGm0yTrNQ@@DKRu9%kTG z@!~8UP9IYiayj0nuQs0MdMV8!VXxgHk_a^ykT@?|fAFrB{Y-Yu=AOg8n_d%}xPKc5 z8Q7dv0@N|9KTLJ=e$=DJvjUY^;5?4Ocmm?CcXt;k6Bl?1m@WnjWFGE?^|qTncqYbl zo2Z|MwI$`*Ajm#1za|EZKMNpdbc2QCXUnmv7h$`krHW^YzPeulfJDA zm$PZBzE(@+CdX~LD5*afODOS=8CaH%Wk%|va+Gxhq0VG_YJNsvSr(j5U1tu~;SY6* zitQs=^<84*mM7On@D4*HuVmP&NQ`F#B}tp*NF=Hd_4Z_EOx{Jv<<-M<%iZu?6~z{` z6QF~GA41r%c`=Vntep+DmF-gP>=+>7AMlP{vjzvBDY{E#AfdIk^Tw5g~E3QfIcUjPvF29MB*SMrNS&r8$x4xSW;K zdUCF!iD+9V3WK2#tot{2CjoerlI5S727|FAk;nUE zmhw*;3L|UK8V9-e#Devx?7+_$M~)Q8~#fW+G%E{ypZ5MuUI8F7Mscf z1;fU=9x|l%wFxpPfDMeA}KF#3YZO6>f4^O z0Wl!pbCgW*XYM^*jBQF_5}TD`^&&8h4Jwx%Jk!iKFM%?4{ zA+6?gpu-Yj&tq;V5qNk(*;J_`i5{L!#T;=&VKGNI6WJ`&AcZH2DS7Q8 zlfBT)XTr?fJjcEbBI-IO0H`$DTEcoWorfFlDH73?*$V3%3qi}vm&pWF1uid}+#Je@L+W_$qwiU{lmPCXU-`zGMak!q%e(@}D)B zF(&Mx@&g2uZc}5WM_DS9)naZAyE2pf&h?_%>U51Q>9KAy=Dx$IzOpG2&o6#w`<-oB z^BblOaE2deVxy_Z-Dvr6e#T^7D#l;9Pr!J|tTX`8Z|R}fi0k;XO#59ZC@Z{{r>E;< zAZV@8H3H!sc1swc!HLcOlQBhWa-N=~+wbrwkt6)2qCrLsZjg`Q=zfnyljGCFq;-OVayzqsx&}o=o;!Kf(>WL)$b$Rr6X;`8bzuOr!dfle()+ zq9nEp6ZDDAV%cOPt&Xe2sX0zNXxIHCLV^f6y;2*ovOC>_VWuTpy1neFi~(h?c~*3C z3c1sNUtc0)RZ_bS(4Q0`QEx8{K0GZhPHSa`RI`>A25$`nBF{$+bw&t|vN;ZMA=yeR zno9l%GSY~5;QBUU(}mOS$7BFIfos{oChJ9#YJJ*zI_FULMgM9$iz>u4Sg{Wy zh;+7tAe{ZF*L!W|iHX}Ch zVB733LDwrP>>(cPCBak;|K>$*2epz1EKQEiv06fCb(LY-(V>>kcg33EP16)1@E+SN zIq3>ToT5Fh^%Wyb+R?ObtdEqCh^nHQNA92o!-sqVc}sc6=0c-e+0QQt0DL#Rlc%Q#IH!F+x)H^?M#uS`aR^OX)1zlIjb70V{8akN}e z5B$!D3kq@cM#fC87z{C;>)vXkm91t!j4qnZP1=O%mf1t&V+`lchJVRYAh4U@HnQSU zjB|oXU^O;GvSNcvl{h5cgvd@@re+)sd*^Z-8RAt{vejNOGHkXpJekNfpheF%Gs4w{mnwEo^(YbNzY((qr)DX7S zFM>b6Ctrfc=DoZ5e28fuDat(9Hv;o^7JX!}%O-5xGgYg%@b7nG?Rma<;367p+XPYy z#Wm+n2lf^KIGeOVfZ$$FpIS`kn14y;2<%qvmGKk2l9yhG6X(%}F>^N*aG`nKx3(Om zZ_In!F4C`xfh!NV_bvc*gUU_<3dl}qN9o+-Y)-a^#T#qt{Oll+V-EB&Axs{pKiup_ z?X$Xtf-3`}JK@I6&{@9>DJ!2vaxqPboh;5i+py8Z_p^B%-u3Z(;opb1@=uVCTnfpr z!$R#Z{sf6JxQZU0MR?AW5p$l;bWC9>(xol+$$(Cz46#0v%pn>l-^da zo}nf3uMo~vpe9w+6X+CYNqG*!;xV;qy3o~8Q1LffQTUeWC?ua1-4!*9DqXbzlzWu( znx?avcH>xC7Lx0Jq-K`#OqMaj3CA{h`gCWrIX_68oI3t45+}C>Kn{klss|v6y?r?j~e77OW!nf#q)6)g3%B&m?R5-Zk=M|?iIuZVI_;> zkMipuNLe9J+x3bv5yo0KP9*9F-mB97DHJZM%6$)8Su{ZG29|8xo(|JNCiYBAc3m*K z?eUC+x>49?3;SCwS3#v!Qn7Q5Wtm&NWYK8K{yJb~RS!(<%N_nwb^RfBL)C&tbf`03B6f^2R_hNGI?K`2gBTU|U}(vzfw3jsF?KKBU}V*c~xerQ9!oq(0fq(Efz*csNLEg3-?*JqSAK}qS)C!*Sm+k_=>>-IZ0CK1o zegyn-n|sD&Eau)QLTe>|N_rI97B5K8XzF<|7>NmM2Gd(;Mkcy8!A{;dH%|`9e*?18 z?X*~4Kk(DZgbY$+*a+eZd+Ym51J^%714~A@l{{Ja4pnQ1eHw4^j>`f6pgIJ?$7ZvdvAR3O_T8zzwzlcaz8s5h#SaUfTNpd) z>6Q<3Gk>)t#xSjt;T%g*RdIUpE=w{<@ku&hO!`x854yGV#ybtXuhNT4x+ z{$AL=0E|Av1Y%?btoH;k+1bz($wK)~(w&I*7T93I+*5Cfty^PO*Ja@gX$w|#uYc3yhGgVXE@O`W) zJijq0TZyAxjD8C2pmcj1pe_u4)=ZkelF&qq3L7?YGxW`kL{Ufjd3WC4SieW^V7z9h z6YvO0NthXh8FYl2-{ugf$x(vW*|*vZmLwEX$n2uC@_r?2uf;o5<@pe`aFw&{kls!K z^&WJs$8^I6vT{t$jS`ufM?j^(aqo$Q=4i=GA2E=Myv;AJcy|CWP*N?OH(l5iRh(zI z<3@*>=G)}t*lL>7PxuYs`0*!XF5864%Q^A@-HJ7t$9sXqqIPaK2)t_Abl|bO_DI9O zy{8{NyBSfu&xtrtCrBRdfAuxci!dQOYmkHL!u5-J!=pw%rOZ#HP-$*K1M3B>zMd`W zo5JRp9!;%!QU?XVEYWSV$~bel(odALRE-Yy#G5wk8ryjPDe5QA-M5f{EFWz9628-! zG6(zaNIk%*1Anze6hXZn>QOmE!}3@b5TK0o@!_I)0>qI1W@9+u)If{wy8RvWv`hWb z)ko2_?>&7wpW_CAilsm*q2oJcLEtoAH>(-BwUWAV%=dQIU6CS^g6nCSqcQ%gkk(>U zp!X%=SFKIEuCrta_lvYm2Xc+)C6%M4@p2=!l+N2v{Qp^2s^5h#?U(peWl01F#@uow09wW)(kIu z<)1gJ0tU1k$0~smZ;9v89W&Wq{>Q_{#sxDs7qFBYqEi%ctNSS?JsC@~42kXZ1KTQl z%eAg%OYcofU%O#E_lJX&lDq>ibb5JtOXEUx8tqCpjoRH){8MtW9$(r8+EmNj8AJt2 z)sTTQK~%kmOI$6WeFGwpxuEhqk#yn6Y^RMS#L-jVJ{Pn67&7PML#6yPNjW=}Z-sP0 ziffUV^#IIewsO`MVuzwQ{Lq|=7bxyisuS(7!zAX8(cU_#DNFolFUTj#2U?s$5b zg9_uK*?RKzfPYoUEYbjR03XxBFoMC9iu0rLu*FP$KWjBW{f!#J&`faF6P;lV zo39nt`nZ3_Akod1IQS*xc8Q)&)_!YHfJT#|uTAzv5RxD1aw$}2(F6~OyW*Figws{w z2=|&|&?RbRFXRZwBF1fQ$?}Y3bqozy^U^q{DTR+}v7@Sx@`|AT%rw6+;>4~rl^bYe zkU#atpUD91ox7`Db}qf#`5ze-ll6v6N6YZfs-1Wmp)MwLQ1P~cLDr=5#Vh2x6}2MO z6CWG>naB}A69O+2nJ^5Vo@lNZStb^lAww!~6MD)7V2vz@^}6p!=c?+_WLs>WS7R&! zlPqZ^w@Fpxcb`JVvu=Q5m+De*!X^UWp#QRuLGX%7zI7`VNOLcCz-R3x5Lwy0>`8^@ zYHvBTmX`|9Ji1WJbxL*)qgBnON0jtRo;F2(R!{#n1pbi9f)0yOq+Y##^%+j0mRmkV zg6R%)W8DgE5Fb!s_ByeAJzC-t&s%yqD`PM;MGge|;s`0)Tnz~Wt3WFeDNJ_hdo31( z$Y2vy*f18dNSDZ9Hj&(9_qe(6*t6L1t=O(OExqfIYXPDRHYI5YJGk$HO5Y#_z`$z^ zTGW(N)9@X@TM+$n{ue>yF1-LMw}U=ro!UqGY6>cS>?)7AgSMH~{>iah9Zj?oma$m? z${zOc^o$(zPN*r5eZ}#(TqKk`GX1_#8LAK3z_y2(3Ps@Us`7(|wc-)iyK?`co3~p5 zO79_^x3;FmpKORLjBFu-^Fpz}>ghWE2w9mvx0m&D_bJFfphKp|qiZ6!sr}eG26gl? z!+nr(AuUKk^hx%MhpzS&bp?BjG}8|W(=7dG9}V!1Gr=Bp&cLZ@!wZ=1#?$Ze5PTQn z4RX>f9p`Y{))d*UUy$AEcfytNkyR(xkciLeK`jal#A(ZJyqRcue$p{yb%a={F$P?j z4jD*xvFw#uK!{3NZRu^U{YEGzII$guUR^{%GjKWX+_{)6FYAc=67n-u(Go>B|0C_0 zoY`IS5>b;j9|X?SO5Q|eBZMvg9?(Um>}VaMzPyhfHSYk}Dr9UgD^vsKIL)zm(Qw4V zFxQ814F*MKT~DE>>})xtAuRMG6eDNW15uH<8M=0$mRV`^=CzKiz6%f!WaM3z_iR0F zjB9o>fdLC16mn(v+q^U_ToFKkq-m6Nd}iRX$@d!a#c4>qZV+zDUceh_SxW%FTkF~( z-yF*3j+ZN<`ZS)ScsGp>+<%ebCP*CvM6OcJ%)1TU%Zr-V_)``%++&A!|J{Bv`CBnF z?hWI*JE{MiiQLgrrp+*q7d^P}nN=xxQ5u%fD?1q6oF<>?GO{+$$V8~yt|Jppicy(e zVt7bbpJA>EFz4+OyhN;iHu$GX`kpncTEP$RdB=X~4q>UPQ%lsk^OHeFPrT7(5ieb? zM#6PA7;JWwO!rd$&1~7r{YG7V2fqqTj1$a!b7-^*YqIevu zm(WMuH-*8Doo2$ephJ4whTU_xFtPbK;!0dt%o?f&wP*bbEPQmawFfSO0!&If?zjf= zQnlhSRx<(1xl!t!3%>JS<-Yf?=E*106_LjpLU-~b?vPijnP}eNF|!5a`W>>m2SWR3 zYvn=V=%s68#VA8#_Wrb~2R%I9rMa@SPHx5KmJ{Zb=x7noz)i&*$aR=k-}<=Py^}Txh;r_Y;$-SNdn*&hMZoA> z2}UY4_J$d1212-yIQP#=C-V3c`Yka7^>9f8ch!l>QP?H!z4jY5U*Wc_UyPTvuBJRA zj4LeJa?coywW+tV(dVlB2l^9yR@W9TeBHYG@L3&P`)xX`l*aTT(XjIKai+HUR+gi5 z723^obJI+Pic1-{>Vowx7JG>iRG2rhE_=h!NOy6?-TL$W3)7x|)p?_+7SI%gpn|)hVHA7ui3b(>c48IcXwLRr{CfgdU5yxyTlN{pl;h~)3>Khdb8sk z9y{6;NDoHHPRPD}q?h$w4f}&tXGenwSE7qmBC|a#2T9ey=N5iH7&V1Z z;BrZ?7YFf2Ay|!KaV@3l#V*ZyNFSqme-@7v6twQ(GnHKD80jW#DA4~+*5LdZMw`H_`rwmHj^VaBBfc|x<0Qi1!W zz$4A+ zJ{|3tWKWZIpA2RU)Ke%#M|gCK{&^c7CE1T?NKAuWzHjuZv*dhi+gY~dx>Q;-_I&#Y zo&cihx8qp`TlV6(Vy?(zow&I5p^}L zxe~&cs*vEflsj|9k;`%lasKrp3nxiUSgJ*QE#L=!u>FBYJY|-W? zvmJ==FdhfY1~u4_i}mv;Ql89)u;L-nPl_rQ6V~VKu^}y2p~;b1?v zmvy~J;`N9DT2klR*>}C6VAF+ovR#OPT6Mr;|m zEh$`5PJu>$V%93{e)DDZh8I(jd|0JNy((R~g3#pSJB)|1d|u2q+YT@4NR}=-ud4Bm z!&1Hg)sAw8GN%KN%11(;}i>+r$p;(Od*$lSg^lxqgRJB=>$D7q`(P8160|eqd z(Sj@gh927%T`Rb+HD;E?onU)^K0R2g?ZB*n_^_Q7nB@|t>X~G8E|n?2l8ATLF5#~C*jdh^WN;^(2gIIe}07M<^3=rah@UrA;-gSE{XUbk80_w0=0 zeD$urgk1zwH`=WMkBZ_)AT+wRNY^{sx1TLa<|!4Q`^}c|d>!3mih$u;g+o(FOJosy z{`1Y%fvzoElLeZ`(|?KIL01;@b3s(ZY_N}+WZY{Z+q&@`@&(-z+v{U;zcx*kEKL1m zBsg-tecXI0RS^j=LRD77XAFO_^ETq?@K@)St77V}`8s|4< zm~i1g6zSGuT9!7V>jWOFW|CfCikf8d%TXkvaFXd8GS4Pz8g?p#TAB-G8Zsx^gCp!9 z1RtW%fJVE?^@G58+`ns+y z8e)F>iPe(pOKkaOzTtKZ!`>Lg<~xT;VqDYLRiz+Ex7I_UVPL=YW^5|)T&%=ItB5ZC z#SPA#Gc5n~Jq85|h*{b+gBPWTOLey@`i0G9aey1WF0xi-H?NAKZiu4H7ELLR9*j9W z_ybLRydc2VRR-PA=sV_MnxomdFnC`KdNeVvPP`ot6ys z_5RHs_WAIjOS)N&Zv-t4Gj-yb(b73rxVROa?<9lW$_8?b%s2%13c4mX+Lc@blt+20 z_9`M@m0wJVqgVJOKz53E++i4A^n9%ZB0AMRpHri?x~n!B?zoe_RHI~a5bvWs6=Jadk}WH1N!mY3J!&jW%FsNQgM=Chm{l7 z_OIb}0>6s^|MlG=tMf=y;vIJ?N8dk=b@p-Bulld9AJ=y<24cA5_-2PloK+gnd{d5j zU855OjZz47CSw3I>s8Rci4Tm2|7@-AhKywfCNN1-ay z!r39V$66xkj7uV#eBIPlGpuqK+!0Afz#zkxxQh!K_YryOfVpT z9)<&?`I`fIvcXa-5!C9%8j^I%uuTNtrPDMdt!#vfYI*u=j+bfxel4w*F=xpPZ_Ra2 z@nMn|R2v9X5o`6^0TO3$@+WKJOsF>JOWHFdqTsWZi_eig<7}vf8~bmtd?G<4jX3pv zUwz%KT3)hrS_6@rj1~lQjx!|jTVM)6$ntW_7I)C16@i?qXF^w&4i}rlgw*+<%H3J> zQ{dFug#}O&xL!UJfqOnz^+Rl@&)R1w>bHlw*jhkuAYFv$V`>IDzT1;(aE`&|=n})( zP4|lQ(4D}fOLm#LI18)pMkuhtzo*m5Z0Xg^e0F`2qevo`uyjsm%bAg-M{xN$uq-!M zmYi02J-}RX%Y8__t{$1zL`8rC4{G{-kANuGaZ8Ht0YJ>?1t6WX-Mkr_wRV_a`){2O zO^;nmF2xfU##i+hw%*~BAZF!kt^?n3+PWIgpHCWR}7rmEZZ5|t91b5uPcTatf8&I@3axCzZzIMuT@{G zm;ESfeMjgR%Jl}arOrJEePL)LM}C70(?^389YikXxvhvmop_X_lM~+Oed1G`&FaNy z*zPi#@OSbX1k(^q`{CW%^q4O4{PL20f6CVS*Qd7Yqn~4RvIb;TL#m3hutAuhipyT-kpj3O`Bu(3xy z{%{i%TXzUE8t6x$e8L?+-P@o$?U+itt?Q7i!_(%|b>Ft+y%}hSdoZCYHauQME(@4G zOn6*Clh9eLq!R`Fgz1%#RF7aJ>4KgYFHyy2{Bs@(BuWpX#R1&Z6e=Orq!p{GmAQQ| zYb^35ApMHE4&QuP4L)b20D z%pZMaBn_cZXRyJvc9rZy0{6`%%gm>2moQH+}F|yDv0jdnxDozpr+G$VZ zi~&t(C~8!(zWU={TaqvuftQi~CONd!sOhrJWy{m@_Rnj%43yf3B!jdDz2q)3YB(7% zKpA3gDsa9Xg}yb3=0WS!RNO56p%#fwRHQ_!$NCrseFwOEJ-W;4cqhB(LAi7(M)B(U zv8=Ttd^X$6xcFkGBg-vWYBBCY@WD>vT6@koQrIye$FdpS1x#~pbZ{*)7^>xD&Fpyu z@AKM%xX9Y|_}nFgcJI)V_|1_`E?tq(^jyMX-Tz|jo|=T=!SDdDZQHhOd-q-2wr$(C zZQHhO+h)IZrkx)2puZtAnLJ7E`}$Z1kaijcAc@&W6cR_3+y=GS7oT$?{y0>i@|eOd zy3JTs<_B>`>t6ptC!iAJ!?YjAWO83Rec_O1av34M=#}_o^611m#o5QSGUGcnYSXWS zBJk|ccHtPbK-QnWX9BXPHYEZ!sA=Hegb7 zvn5p5Da$Dqy@?<{Jfe>d+^y&Y0S1fEZ|y$~`>CEADIWyKKD=2hqvC*JZF~#SD2`*j z9)Yz#k1#2do_)y)M1$ADq#bA@-v4*(&l4tCq?JWkr}A!JR0nfv867Xwj>VO=1JpU zus&s;9WG#hQ=zx8A0WX>isL2UE$skb(F4m}fr)KmPzL4lvU~Q0+CYh$x(X*{kA%m~ zKQc-i&sVgqCe)BN#*Zy6k`uLw+A}sERj7WZGwSQf_uoZ2fJl9-Y5id-C97E7aa9 zz<_S|{#08kJBv2D%h05$=qiJg3Sr}2=Z?Zc0$IJ;zM?@ky}V-Gcjo(UZKpv3@HFl} zR$g&9iuz!tvd(EyP7T|-F01mD@f2kR$4bbVR0$L z0Q7stEr*GvuPXggNaBD=jpSnbiX+0t1U1w)bddf>qLEVPe)^luVFQ^d+?N?o(?kCA=a-A2-KzfRlpV=LyXPyR4vD%0IN{hb5z? z!b5u6R2O)W?eSh>L|@17)ZZl_DWXTo@vp=KZ;&-XfS{nTuli}56dZj&i+27ftf z2p$pj9g>HO->v?uM`6x#r{eg_BZP9xpT!VwIOTI^SD8H*w0b4V2O9O7yp=3s?%Y@p zK1y_@KrY{kKm4efJEM`RCF&-H&zvE@U^{sv(3qP2dW9Ea9Q<5RfJfV;&e&p!0Qesp zVqFL}lPR6DlS*@tvLg#8B-I>ut$W2>Uq)p~(aYvq>f!1&9oiIbljb|N^n!8;ah#=H zhl1PMF917AS|yZFes1;A(-dmW$u5tyyqyp_JhE5628BG<`y#_IC(_|`4U`yeu2%GB z!D|d+xhE{#v36K?&vzDOm>DU(;c$R`BupWCFDPln~*0ubdh z{pQi}rHT~2tDP097`q0~K5l!JQZ$}ld*WFZd!9>@Z@`uupB z*yzXX!((JUn`4CXIQUX6q%MrMQ#eFQGSG6S;`79H8Ave_dA>JR2J|YU$3xQykEd1Y zNn`;L)!)3GKHk#rW_QgQ%I~?ksI5xB3TB*_4($^;$2~kG4t0j`U}@7RS&SEdTjzy` z?z1`(?)%JTDTvN7m9Ic9R8%V9lP2{=j6jsKl&fo3yauO6E@B~2^4n%Y898PDE-<$U z3)5^#k(f@IyN)ai84$emFU@tORe1132puVnq$uzzDE7ns;|x7Mj;kQ+o>3w5XTIsw?XIm2U z9%0DJi|L(7abkMDUV&n5RqCw4jblpq* zuX4s#`nPss;s9KqNp%l(Fd-K=#+xYG%*j*V=Y4>5ytr6zEZv)af5f*)IpJNHVP5p2 z2X5%<>gc9D>yRCMIQ3sYYsnX_7*3cxkL({=?jzAYs?s2)qAaH19^;e;#4kEgh<|j4 zWIK=Dy=~l_oswWxv;}pg_EXcPYM7o-I4n>PAQQ~xJ-EmlQ)q}!T=VCXQEs-4xra{~ zKeW10n+@#+xYJM%y~32^q@#mYpJ!JhEMR(AR>#*rg7lA)4CBRB6bg7!h&F6iSXe90 zn7{As?M@pNZtj1^E4OkGVl_&4$h5kL=FAmgC>bY_LLbxS7SF6q^CCw?vR{~e*Hb

BgtqQ5q2vG9ZS`)P7f26Ot}_Pgf#e zpGc+T9cpD@P{F@^jwy$X|4Iv=c`BfTCB4XJOSbQyiL=|L9)0_uqTS(xjekFnZaXJ& zxbj^+yy60b{VC{jjmwzQS{-*TN-&Xt<620AO6Rt|0D-mr-kF9s& zfa?7(YrdDKi%VkC$DK^i^$TVo81WJ6P4(o{r_Bcz(fy^nx?O0kMv&q7I zWDTtmF4{v&vPxJ8S0_Hc%5Msr0*b7n>s8qBP>530kw=OWeJZ>JcX?*S7&X8L`fH$d0J1OfD#*G<-#jBEMS>=N(u2vugpLx^xcW z)s{!#zI!|0BZ+BHIHbeup5-`Rx~x-VYJJznk7*WmJ7FvetvU9 z?s`weZ2MUzww9%fL)aU%Q70ZU-S}Xx}X! znOD0(s%oY_&9c^XwFY`z7RqC8@G+sG*6!?0^?^5H6Mwbytv;&7AKw-kB1tmcV>Y>u zUX1ZY3Vqr>PrmvK-=)tNw5hrHvL?bs2jR3EqDKa#(-rYPjCV1qrD2W}$hh1*h_<+wjG`O&qz8Uc&(=iA5ZHU!|Ru2=C!Wfq7&n z>UftRg_CrzB&n35#OBG#L%^{(>Nw4Gb=1%{W10v8=9LySIVvNRuA;o5R4bzT5e(K@ z8XHJ;(7Pu=aMHSa=ahWuOmJL@LgJ1P-hT*e=0%zSm`-^xKJxmMEnOn!R%4WYFDO`j zR?=>sFFJp36Y~P+^4&>QC*a;MG8p|<%>a%ANlLCU{%W0N=@vQr%<_x ziqEMwGSxpMAIwje9c|z!y@ z2aHMNLu^&dstIF9@A#IlILf;6h!`9~zJ({%kgHNr8+RB?tO{hrqUs8n9Dn6fQ-!)y zS*MU`+h33yX^%p}$&I_aE!0U8PNL$aa<9qIEYBmUe?%At zmyvtsDJ%-w+StgfQ|&;?Tz?zsXEa@lpv1~6(jZoNml8Rb;gV{T&c(e3@@&u zE?Y=#(%B<;KFGlxx3F=iszxpmV)U;k+h4O4FIb# nS&>g260fS*vz@-+^_$cT%v zJbL#zqp718RM;eYe1x<222jntdYv|m?J!PCN?ROhCffQu(jqu@0e{L$_!~5AB(w7k zi9!w7qfLZBwEACF1Pbm5pNR!eGOLFDtRL=RN?ve^u?TNe2I?I5TZ#C4gpGlHc-au9 znk*l=1mOhV=@YAX3Sy&khD}Ta95WMgjD*R7S)J76gZw1sXxAq}9xL@Qj5rTrCdAur zH6JCEw780s!uF#qx_@F;s+#rB$^xwX@l$(`z!`Ov%W;+$uTM%ROgm7ECh2xU8GnKUK^Crd~zEI)ua!e-d=rWJAbi$4G!sB9%vj2=!|$d zxuldSnre-3D9; z!-yZI{d}3MZGZMK4_4x8Nb*@F_|T0w4{MPHJrK+^$=zd%l!U-0r@x>?#>7uWf2#UP z)u0vbcw!^bn9{B?(c$%xJSa}LCjO;H2$dB@H%x`HC=x+!7$zO!q*(Py)hTwo4 z<}_L1a7JwVK1ebyD2zzY3e0Rezs+TIE0WGctWX0$-F99^Ic}(IUSr@Yn%Tw?*EguI zX&HD_6Mt-oe5-tUgcsE_#B33_<*K)#*eGdeF|GQhvQ@mSFA_cXJq5Deq@;5cP+fHw zM?y3Zee)u`irR_a`ONJ5)c6;%P|r<7Sqzn}9s)JvS))Z|Thgb9oFQ=^+v$Btux|v) z4!Q(zx2$0B(6tTajYC?K$av^P#WkoVZ9lla8JtvgyM2)@jvzDVIj) zK$wEub2JzVGvVHuLcS6Mg&EAfdA9*#EW1qty4Eb$B_wW01as{|ei3u!f?r$Mdm15) zL4O6(3p?m_^I_7W*faL1%n_P8q3k_xqCZU{DFxHM!C|*%?Tx6Iz&f_)=xCDgeJ@`k z#6tY&#MmaH_`^l9bL9;&e0y&DkSM?Z9TIVG@52!z;qh>dVHux#dTr|T^dPGPOb?VX zw4uJAVn|2KGd?!yq6&B^2CaZIsgH3=fnpzRZ_BcvS#cX613^RqkA&tN!4lus`g_Kc<14bS0PO|I9ucB8}0`lqfF-F=vdACTb3A9QDEcj5bFJjp{jz=^SP+Bf_A$k(`^G63vDt2uEJYo|IG+&g|s3N$^AHxlY}1HY%w7K^Z8--FMSRw!!;3x_=tGa!Iw5 zU?A=C`@3hq5f=(;j|>=#v~O0pH!r*K}rAI=9?-0*%qU zoT-;d)jLiZ`;ZU)Og}}FIj-PuX?A)Y3veae`Ti4v;#c}Ng5I*T%(6jx0@%UD4o7{G z2gt4`Nd}8#`J`CHl$@*7-hdq1FT83pzA(qQqnZ<&lN{GpC46uFORdF+N=m%<9*?~FjXymIIn0w@0T;}R8||`T^OTp z5%tx?_%|P9_~$h7vlLDt^^*F$MSrlMufBfw9A_al;wK|+!hiALZEEe~#4iALfo_5_ zf>x%15g;d%SeYxLqmza2jqQE{nsq#6Fnz<)cP=a}V;@T6l>`DIg_JxHe`cncKJ38U zl=<*;Fk4F8_zZhvng8^&jzQJvThiC+kC=En^2VMY&(8SKFg^%`DkCNvKj~;KJx3n( z2>0XJQr%WNGk;%{deCasBbFK;n`ugmq!fh^hAgevS;bsJsbIj&aO8U11>2pvCu!o; zvA_|9-Ij#u%=mB+%0qgDuX@20X#Hz>P+l=g)b)%--|eEZOadm3j=$e??|O%abagIs zW-h|fTl)>tKduJhiquDYm9RCFYU;h}(5n|y2Xd)2Cx5e1Z!V0KlAbSgppGo87=SlD z;C6_)j$-_#acSe#)f4+MU{`2{g!F=>11U`3RR#P6@!7PS%c^wx=I(YtMWRez)rUT% zaZ^-isY45vU;fA0aVqerKXil9FrlU4R0?ti9?bikRae%G{?d&BGpn@L`i~-(gjyNl-Fqc|AEF#6ePx3SHXf9vL~kPX)BY1UP}B>Z}2}6#SnJ{QCLRH+se| zIqVhw&g)>nT39Q~O4s|_^G5jZTgGevre6nILVp$|SjLCGe$<+tQ|? zSd69fE4s-RG{Ao|LJ+eMq;zIWE+r5#zYKD4mB7?uO*+FSVgxjCu;gH9=P69+hJUt%GN!4-219DYTEg^hO3p ziZ8b;JIhUUuI|V`JYHaTv4(G|-GxiTj?B4jl|Z0P$68Lkhy`=g>!hCbs%=7+!3Nz! ztRUEuz<( z>%9kbV&04`J$TGPx5<97kUaNI!Gv!DW^um}rYd4s>Q0AMbYI*gaaB=v)*b5AjP*$U z@Z?l#6CU~EoHuRlp?LX&T5LW8F)*X+u6RJx-tEq*cbX?K?9U(1i$1lTc+1-2*an5m znGt4xjQM{)NgNDUu>Fvm=>Cp2FuD zXP=9$4R{geuYX~DtNF;@_Q6(f$!mb2O=lq^UA4-B7w}bPaLOZcWHoZ^x9&gX2`sj= zVhgUd?f{L;k+fvkVkp)^GkSCwRnaWv)OrrmnsLA3Qe6!58>LW9Y?FqgE0bTSCUP)W zyQ$+^Q*!uKhc9nT!XJ|Jh#6&6GcOyKS==vf*$R4v`hN?;axXsF?j;)u`z`E=aCP*` z0Q4JvP4ICpUz<(e>>Z@A$CHNdd;B%EPiy$~V{TZ}Pg>kOtdBh=Hf?Jwwk)WDP(y5) z6kXoo=RROIC!`?V9JLoeiy*PsjjzDgw(vkjnDnEmkDM<`0S(ug4rzMmHq-4(#hw|# zFcKajtA9#|uVB#I5J~iVJrx|aCS?Zi<}5=+bubFZzBBa7ByH)%;|ndZ`?R)&K7~j5 zv^~Mau>aZ2h=c;w`H%MwA`&}1m+Nd+eQm(v_;rviedQGm(MzIaenbAg*338?bAin8 zx)v><9(mzc;kGSE+6Dfw>iKC?&(_wRH!^f73V$BE@pMX4PYkITic!4>PEUR9FI+!| zKm&>^65D4GvW$|2-HN8I346d}mWrG1RVpZL{vx#kjR6Xs@B0Cl&h+TTE?7fKmtp2^ z#M|$wXfEmFvks!M*6bga&xM0f#K5GxA0@Axup{RsrdBA5i4< z<$opWVO8Jm(Y`f&aLp#*lxDqtMBQQi zl?`W$-b)d>z{yt(cD!AZ;jv~3x zw%5QphabeofL3akJCD;s8CVm~DxaJJLH64MzCT5lc~=ROHv?3*2HM4~s)V}l<$s-r zT+u{Vcf-k$6k}|C?Kw~m^KI$lx9scPqaLCSP;{uw3C8b}^||swa5=?jm>}%46H`>K z69$pke&2HqNeNZsgNj%&tVp?79Z7dikBak1j^JlAoAQYOF=+5SJ5A&?yg>4e6M8&I zTfYB$1CV2lCu!COr(kj5!ZUyFXn*3G@mb+(p1BQ$!ew8Qkg4Vc_b@68msUr0J-|qO z8sa#-*vL*p_3l!4wwMe5JXC1ZH>T2(K9olr-^v0u&^`to#R11OFfnR6ov8_l4orqP zGXQ39_0y5sc9+Xb821aAGSN1t5VDg(o7^RXbuyG*^SK@kLb$LtuNh?V4u7Wpd071z!M zVJ^m@31nHNH#3vv=mc%NBS>>_{{+OFN2TAoK zh4*-=z3t93@6*e-1_=ssvClEGf-0$t`J~L1#QDy`Zn35M_KSYZwZ7v1cs{>f6#asA z%H-xJc(u&MtxWg z2ytA+q4m*Fm!2#9vXl)%FQlV=<9K=pe#Vkk*MzuuL$W^oz<;uHeX5o|xDnyB-oL`m z56(F`speicp}$|oI1+)JKnz_s?shDl>}bybJAHG57SnkCvenqy)Z;=8>_fOsw#gNh z4&m(vQbZ;Rs%yi@@YFAoU}nI!vKo(R&CKjm!}f)MsC@oRwNzniPh>nrZi;d2>lk-p=2c5>c>8dHOi{L4mR|Pd%KpBfkkI z8J2Y{(5QdSHo56)M5!CUd7H`o?xH4`8j{3I{kfjEA5=1gY!s^}L;bE?cNz%izdpE7 zCNa={Ei80}tE^BhEJ0*os8%)H_hk%)5oa8kfE>1}Re$pGNHV`=gN~0S?kAXm4nc@} ztVBgyg#~;lCM~g}{bpk<4hV91sfXwfmEo$A>z{BMBx$+Ol!LXg#Edt&zUI}Z43NN= zoJKmlnvjOBT5Y%h4b5`t#n%Z)p7uMBYU)lnmD*zSre{Nl%Vcg6;=uNcEJimq>cg1c zHYCch1b^4cPR3MobY-7M14DVS2PX`!77KgIl{E|4R_lap;&xoyRZbK**|(QIsePPz z27YDQ5oE2o#97%6`+O#~klu%&x5}C~DH#X18&D_{WS_`dWE3ZOIvgP~gz+~}v!|do zPwnE8FVudN+4bWZfE-^N@ZF%qW~-S%g|+Idp?@j)kC+F<@#5?StvQzj-e$o#IzJp+ zSRwYdB&9VM7@Eeri9@@#vV}kZE%aU7Q`Y!zZaj1j6_>M5?LsVl;v~^pF`Wh0uz1gY zLh2sv^KRjyyFx!8VsfhUzKLrH;5vjKymRq-R7|z_(}xZ1U%&3uOUULgCa|={p0l<{ zV}BfAlh2A>PqfyPcg#zX6D&BgRF*)hah@^qYSr@yehv4~NRA!EqsJE<7=&Zplz!`CC!fi!LE}wREkMKXq2d8FQ>2}!IuYD#7S=*} z$t=7j}w`r*r9euiCgCeu#jElWwj!reE?f^YYzdWde=%#P;lD}U#W z0KcvZSwd&K0so3CKWMcINhvvj0Nu3Lc(HquIM1vLnrVzUlNQP*}8{=xTEOL6d6UP@C zbSYTgZ2}?SHz3=_eO$Q@Q_NO2@qfJ8?Kc@sl5sC?M$37i+leG)>dN(8(jV|qC4*OZ zu`z<|-M)B1@U+t_bESctB5;dHf==0vI9S3NGV=nK07*c$zs{ETA5S!F4UA*c(k7Ft zUeNa2ILgx}Gyr4FR>so$FP^4@Sz%kyCW~Ic+u=S~ETKtFP%< ze+lgdcn)2O((n$w_gaCRmeLhhHHP12VWv&{=s?V4xXE@_i;t+=9IV7W+G>C4o>P=M z$1qaMg7?RNN|p&xf0ls+EcsIj|KUcV=h8o0Tui|wWH_%;`n@Xu3D#Q^?n(7wJM{aJ zMK5g@Q%Zsb5z|V)SYG8J+LxXjqReIno_opS?85x5HX1GeqUHn#Mp_K)e#CP@EEjpo z8}iS~S@eFZaF7*Mpl6^S+U0);bprWBU&Pu#8NKPa1Cd-!8FSprHH(;>o;1w&D@5~w zS%}u+ox|5ZmFYzsu%ErNNibYs+eli$i3qpVI>8Tr!Z0KSNH^prC&9I$=>t(oxJphz zYL+)j0(5SlOjupQ!B^Z~n@ed%ouyJ1N!Mr5^3Y>+Tz5;D^qN}Qcl3WeiqDz$YryWyU>Nm8u)%izZ=?)z2Q37<4LpGcfM~A?O4nLd3N{0FEa%e3>=zZJkb5 zo>)5JWFpPbC73EOL1$2 z6hDxzzbDYh%j?LN{bA_h?KLJ-$tI}}X>xXR z)SOEH+o4S{s(00Buo_o7g_?dE29u?7Mk5=E?#a3HRZCIVbjW`^47z5*gcWj`kXLR) z*#hii+Ih+1=1v>BMUKxZ#XR{%V?;#}S*0z`in{1l)9`L;t|mM4i~trlqbpm~Gfeyi zT;H27f}Gu?$tMRjvSFC2xBPaZ_u0Oy{Z}DOt6G?8YQS>|W0TeHRNujK0YDKxov-+u zJL<=~8t}Ra+Pi-@TnDeNmZTarpI3W#e$ruPOCk|%dr10Sbp`{+0E~Om@}^wVm#*v2 z<`OZ0*Zp;)Zlgng0^dL!?P(s`%eZNioV+G}F}04_x6atgfIi2b6do6fgQ&K5We!L3 z6&ac{UaRwXov6&ObnP+RB75ljZ=>B4%HV4Pl2;ua`}2QR*OmceoaC(aL2wKRhQ%Cf zPGXFNY&aqyegm9!B=&M?)X(KoXA5*L%h-|n(z=Q&bAb@;{d3}CdJ z7e>~xkUcBCW1!=P$bOf1a!ThWo@HEq4e)WLT@X9^PZ7%H|Ri^$N80e|PtkhkE^ob|*jp}156n^twW@I-48+fklD zqij;F`D}|?(x+w73G4SOA611q3-Xp{bI=xh2iSj;gxA*+uwZ{~gvMrK;h0(VfHMQf zrKnuTr!BjyM_(e9VaTh&6CwhUyWo+bClUOULK?O9LEK0<4{oZ9lrq+PHU90|JT zt8C*nUz}NUB6lNqVr#3!fd#Ef&86?2_>u#zoCgRE0cP|piHu+AJmZtGAf@LUEot7R zeTjeQ%Xb=L3hSm(r|X9%!C^v+KPkc9RTS*Sh50N;IDX~hi?hPN>cc7(i{+vRzUU}} zQy#H3$O&R8S!ed8=rzavWt|8ANF;?5k)yh_lR-Y5Kcb>G5(?n?gX7 zi6#KPYHhqa_xE8MO4>L1xn)z=uT~5|c#zu7=uS|mKk2W?TI$K!UozxxrhjUu*DwlP z)9Sa}jXes=7(SvjW+*;@E_G+9B0iJ(`@f9r4Qa>tqt82|a89wwYp_y@Add#2#0`I4 z2(T^-c0~5NkJ6;^ihnFX$B&^b5Y|(x&Dzu6AT$!*nT*K@4&ZnYKRktcqm+3Ys(ar-+uHUGwk&c{Cp*3`Bt_A zLzgz39|hTy>Be}<8Ljc%Dx{5*(rACK-a~*%#Nj*{_8_L|o6n``i0B&1`gp3G%AX|UwCt(1K znc{n(#=?8k@R}yt>5}W*iKVuMEr>Z-q`hXY>R`2dU$Co8mnO!Qd7$5GB}%0)gk%X zYEWo8LDdyDhL-4|Ic-CD-B5qGQeO`Ks#~@wD^pV6#2ZDl6hpY%Uh@g2qbxxYV}4d= z5h91=i%{_uDK$?PRPVnj$-0lMd!vz$ctcsTD~I8r2{`5WQw?B`Bq;qk@O!wbo(WZz zBPwIu8DcvK_%L;!J1WBd&im0v*eM$mCe# zvwh}uH7C;<$^oTyJ^!iL>(@}}TqkKc56`v#jx}`+1H;+Xt`U~cwC6;^x|n+_Js=%{ zx+jR(lMjgJa`!FUXji`2xg?Df7h6>!Nkb)vwp{$Z97zD4jf+@s9=0+!PN3%Tzrbu*y!Z3Wb+1yc0g z`AK;hNg`kSsxb`8E86<1Eb@uE837i-2fCHa(GFY-OUesKV-Tx@)Lcc#oyS!){!W_} z7d4aw(4+9<|Kb(do(wP5ym+jvR-%O zWHtI$TZy`%(gB`xn$s!Hwe7xmPW{aTWBlzb{0AA0^J$aaM3*vowyWAsYXZjdCkyQ> zp`{tcwHMbf)0Nh}CXaao2ZIRpPq1s4FTzf*7vu+`Ln4O8!Rm15#bI28VZ<%yv zhg9T74aR!fDQe(J8*?GM^}8;{1c)2iq5C2TI{+zG+Dp&Fg_FSSL-)S?_a~7H$Ux9D zf%@Ww))@)$6NzUd!~<Yz5idDR%`@>ss_e4!MeLxK(=3M1-%w^EgGG2{(#}$IwHhJ zOivXqBhkl?$J}c$!3fk|LlV`y2v_xwJ7C_8f*;E7`={{L7QtGc9S!CupSiIDH`r9& zCBKIG`|SdB8*S7m=~+|B}wAb6e5xra=Mg-e*CD${;C zTC<>Yz#|8s#*lHhd4L>dpl(SBi!qH8NS3|$x=)~M{+8`bRX9uqSV4m+CTo#_`VANO zl*si^O)CoAM24NSIZ_C7dY?2{_c6 z_)7rzH>zg*FQH8{5p5wzcLIqMwybu5#C;uymOPyVFIklgv);^ zL9*rC*y!o~NnhmEBWm&CjMSUOI8ZGZ?4(}Mg%&Qr-6U50}c3vois<5HU| zsPP0(-?CKj$$h5-4PC9h;Wn^i*75ifs~baY$cP3kl2JrACQnfTLIVOGNY(24qLati z9_U_)KYOb&fvk~KYQjq7GK-nUE*O99>$(vza`oVsguG~BGvM}j3~w6pAnT%a_Kmk$ z7!#u2Izg>o)Gy4I0jUXbPj~5p=c1hX{iw4Js}NONf8sKI@Gtc-<<|Zn@5kBE*T|?!=((S5nmpgd$tA9Zeno#g>@hjEmLC1! z4y{acZohUV-Q|9`t|#C`xpK}ClvoLjr#=Xd*P;A;$YXW9=~ZDzhm{SR&YYfw04)4F zmhVF3ygKCJR-LW886-9~I$=|+bfSf8#+#(Z=P1^A?R$x;nLBZ8+J98YTBU;m1*$?6|NLII8x*NKZ8^eLO|N z@fhQto*7*$73lti6%Jvlb}qTzAQ?Ngh=M5GnWS zQL+$<^WIb{&N|-he*i`(4grNkk?gZw%>Vi$x}I!74Gjaov6_8wcK|XQN{#?_LYGSH z2twkCfN#%i+?aokQAipPy1I%7(q!yb9{$sP(W;h%y1jm|fXS|>mys>s-<)VmK}Vd! ztXkR`ro}IGUhcd72^L`W0DV1+MoBJztPJs;j}Fg@*L%xUC4A4T)=l{C0vUNp(1@)y z{N*r>*n4EW|MxhrL~BVvYaJZ`8m52TH(^&)2y~36@ymZk+iXvGk~<%b7L7mUp9u~W zcwigc_(fv(apl_X$#5KJg=iKf8ygaO(goeI-U*ZzE`kBX7jixj7{B`ci~ESNZgE87 z5f^l3W}@U$M&bh3$SDoQS5p`h;8A3+FyVX=m_2KhWP(Tv2a8hsR#lx+XIC7M(QwBr zIA~el-syjKti>hIltM&Bj+z=h1u0RBBYo|9`&!g_3KJz2=Ll({+PoKa7#4pBK=bcH zbWskSQf|pn=$9u0d4Z^s17sMK`H>T~{64_)bB(HI1)RGK^jn3&YqppErF>ohk}#@Q z>nVi8(nCK{3=zm}GvkdJBl>G{B;G~ch(7*^C$oQc^5J*M`WB#?DisC5M(*R3*&Zs= zB>sn*J-VZN$DY`nFG8Po39YdEAy}Y@HFb59ATRY`g4I@`UOVf?ypv{7*@$k8hE!dB zBN|Zmwxn>&uQ6y;#@cWM+Lj5Oc6E9zQNh8lf1Ef8*so{)6wDOuGxwV>7iI;{7yOIf zRSSQv3{8Q-W!P*sI)$OIT$_tpgl}e@&S?BP0gjKs!@2L(xf;_1yg3Znd5=^5wYv== z|NMm3O_~+Rce-V{`}9++wKW@~>Xm<(s&3rrRG4%rl&k5bMv`Zj!2da8W06=KJMAhJ zlFE4E9!Zn%LE>z&p~_gC3<>>T!-Yr0&9#3dCza5O9KAW`_gEO1Y39Atwg(_nxf44= z=vV_2tO`?C*Kb5PTK+8KiSDMoT)BhBzxMF1rU*tE?$i;>cqb^so{yyAbm2Zl&Hh`a zKvtD_!~aNTX0gNvOvL|$&to(yjjEMFRvwSZ8ib_lfipS5?p4P+Lo^+TvA-k04eWm` zec4;6ozTorxvk$9hvGx*>cd?tp(6#yK0pBfYGr$=)qq2j4g9(cko~5i? zlVWECq~oznSJOun3r&jBwW7W8MOI<2PCz#%Ji;S`0lQW^7!ALGV6LrE27>SMG;CR5 zmd$V-fv~TwY0J#Hutaa43UPE*HR^cRznBzKfNU5p?CY2@f|tK&JNGs0&Lw|I%7bZ; zNrJwcaiEN>_mH`AF0v*?PSRq_XK8q(YEg%9lw&-6iK@m^zu#my!#`z6T%B&GVPpuW zq<&6Wtef;F&hzRxzXfT>3a&yTqLzC5;*bjwnV$%KZkOD+WjV#NvN&*tJXT%~z_scQ zv~n+Oof05>UxS4!9u-{xugQN{oIvC>apZ5u>r-uwogHnQKmvVkhZ>~jdl^91nybTD z7yqu)TXrp~_g#hQNe-CwS{B?9VJiSci;6i*`7ef_`z}WgVFmRi#h<5R*9TDHahPGF zMjG}7k2sIbj1NU-)6k8TS1?Mttxx0FvO?|lM$zeMA#miIjb?lL*-kdybspxdidU*!lC$u)N(UVS zirj*B)__-u;7dPspP$dXn86>>X;FE0#yMlf{#2b|)SU-7`XRyOQN%qQ*fzX5{#pZr z3o$Fvt30`HaT<=>2&pCO6M&&31PX6G4eg+Df}>qS;j}WP)<=JejpX^qg=0|-KBw zGT~L46R!O2xQ&>M{@CJy=pC>l{HLkAlAok^6BHGqF-Hb9%(_1xCd!_iKM*z0FhD+A z;LQ58?*3i=hunXG26QMEXz2|0RkCBuBi#JWJV__gfBz2e&RTTV=AphZVCs1^et4P0 z5B3yT4(&Q9lIB2leHqdudQ7VT?`yM(t?hibi(w*8za;;CgtP-kvn*&#uOS~T)!PYk zH8SH*$;+piBilgVUl{;v>({AYM0*p1r+atObwd7GOgldRax>tW5D5Wxp+T-yAo9~71xA0t}xf;ULgwC4?HqAT(=;&uo~ahI_+0uz@r zJ`5xTFgZ3km%+IU6$CLjF*lO|yC{EjWmufuk}VQExO?Lk+}+*X3D!U(4KyynAxLm{ zhu|*3-623ou;A`)!7kr-=FFMr+&h2f&X4Zr-L;SRKS zbaDWKUEe7F$AOwaAi&iI2(SX#0|An%YWngjvH*Hn6>Wel5DbL8HKFEaZV$2mD1j`1 zU>6_*z{(KZ#aVBrY11pR;2nhVPtm$(bS4B+Afv;e(@0X;2%PJclk08T)N1IWeY z?Hd4c0a!!Kz^-q1;OYnffi3LaEdMIt&2HuRcR@}N$2Sj$H|&i}&C$ix#R39yas|9) zRg;qWN1d)VX0Ctbb^*P?07t7gPfJG&x4&BY8+)U9LtV{4U>ATZ(9?hQuUzIpfF;Pq z$==NCE%zIl69n{k8E!5hu=T$x_yB+at<4~o_CObxH<~x@zi#JWeFFYV_hwE`_FjKS zJO1tUpEZD7U4ZshEXeE}Z#gYo-*Q`nz{sqB&5JzP$`QcM_7A(Io6|orcOc~N3!?vP zW*FXzFtc<7+j{{lfmVOWtSXMKZz%!v|1*_Y{`W-wUy%5JMd1GxdH?^!{dbN2%On2( zeb4_+E#qcyuVUu#HUR(FGk~{6V+IDi?HYg*;ICz4Zw3MUwQxWd|5vD)1IXU%zYG3% zZ(ZO&s{Rkoe~15(LL6-UrVukbHw*Va%peyTkSEYm4diNJ1F(NGvwyq1zwO#!OCZD^ z1O~o|{P+F71+lUH8>VFgvakdHr3UvuARyTC-+Oq|?e7j)RixzP#r2u~n{E5Iv)bEK zxN3Ph0RjJ!Nmtp?@;?uMQAtQRdIEfy*?IT@%pAOIZ;$cqIr4LGefoc-{hNsWUuR`A zR|v=xV93V8#>RgRc>Dk7?_Ve5f1{BGTR2+&HAkARW?;*=(fd!sU$BK61oEc%-`n7= z^M9WIegr_EC(r_U@t328V2Ev6X1Z%Fe(unOlwn^FJM2)XQ)z=%Q9(epW4C`=_&R@u z=~GQ8OXHNl%Qvr|hfdGi3XD4=J$UwX-6_D+e3DO8484B^m@BmHyi7YmtR|(X=|{R> ze9q>S*4`QLu<7hz0&u8rozVO&QtM-JJ1`oduxbkr zk7yJ3?{4V^Mu&$6yD#8+w~3i@Vv%SB&G7w_4=Ivdy-Xq34HhqOf82T9P&`n5u+yL2 zr~<*1X^wxAb>6cN90Bz0rB}gIMiQwm4U0C7Y~E)>*EW*ERDjPUp-&mSzJW5eR52D| zm**JUeS$aWY$VC6ObXf=o$h)8Hw_CZsJ=3+^qd*T@}8GwdAeqLTsAF&GE4Lt%cPko znzs^e>dpK9L^uig+4HUwL;2I)(d0GtioFfRU}=B4`2EKO_=3?jJdb_35?|$Etw}^q zO#2WTEbsW-KL?bz#}EmPYE3Ivk;A&>0=AM0+r=-J-cR*5ymEe18aQ3p`Pj3cOa|mD zp?!xhSnpcco2v_?%&)rlBv(5L%5s)?rbDZEU``Wrgc!vhlhvtC`$*SLUn`ZTi)(~ zZ)a$8oQ-T$VOW&Noa(RPl&7f+ZLgiI8q9wJeOK~yDP#nh@9~6qOxnev!Ve4#XQ6hP zem3pPbYAz;K}TwpMol>kOAYi^_aJ_{cA96AAqnuh*e}NNQuaXQCxV%ye;O-S9hee1 z`;OJ5x$vZ~7nMK*tSIR9s?VO9DyC7M7v+okrr=j}VULza7k!vd&a~rD)mSUp?MZ*$ zgiEAM9p7Cr$B)SJtBZOa|jFl9rh75E80sz}WhJJbHrm@*scy{jpexO?AG zBqh*&f##mtV}95hRQEdQ?Ag8IDnn_l=fhZVBYrv=*%A)I+yY~n0?k8H&N!{RI_5ZJ zWAkDO)%fE4bDHAZoJJANu8v<$d}!0D((iD|40SGPeqNbMv*wd6R?atAl%IbY6)mAh zgdGu`;9vFG?8?SuZgH4f)&CU!BGoMgZ^^V#;WU1s@S7_NQ*BEH2Pv1fap|(w_}+!+ z?2vT@%n&Vd2lGq!PZvoOGHz=X)f#fpgdACwQ~4?yt^3%3CGy8O^;7)&Cw`#dr5rrv z&96VjC1mo&OQa)pLB6^Kzr=r@E2ZK$CRI7VNb#kz*)J_ZFffCP@bI8*eQo7#3cVLv zcrs2H4@$FKdtT8{-V^<3$~-=-8v^kfEASV6E0{7FoabL+59e}HMV`K#vV8L zFxJ~`1ybDRWZX1y*q$ULsW!mV8Ejk47i{x&nA6B+y_xW1QV^yJy@}D1jBxWjp}^1) z%sj^W)h3!)+W376eSjOEdz;NkyrwDAIrI6GvkciM?4wbs89SbaqmW`y8ALgS}GN>r?v(TO}c0jO)eQuX-^+~IBT1Doq zus_))kgj`Z!|&z^c?TF(k%{7==HPo3y(sn0$WJCAlASnsNh?uIv)Xgjvx`PZN)**B zp_C#@Qo!wc##zfeozF>VwwqTCg-{CTdG}Twk72BHCzO9M(CjOJRe5JqgWnc?fHCDk zX<0^y5fM2(wmXZr5)dYjJN4!lK=z4pzKQTZc z?Q|aF*VI5H{WqG*BfB08Z881*8`}o~>TKx(8T<>z8Cn!?{`Gr5@1IZS*bRqD{PSh8 z_bV;Vxz0;JIGB+Yi(DNg=a$CaKOZsI%7>Gp8ycq|YThAK3KNmsrZ8yu}gtu*oG!-zKR-fBA@mTZxkJ~Z}V*uzA($J}_P zlf?G8fGwA zCa-f0_exAaY1iP${20xT_r+qI#tdP=JKR7gb6aX+MaQIG%;@&J*0-f1lod#>Flcoa z{iP8_v8^s^8c(3`O?hst6JB2a+@-gf51?smZ@{bU2b05FcFemnBR3*<*s8<-UcP^{ z3eKx`7{7nteBwLa(h{Xp8#?a}(t~%VA&gW6C7C%oBX@befFv*m; zN?kuG9Kn5vvCor()6te^(o+Fy9-MzD+?IXpG~;^KY`~*mp<8>|wrhY&Q~Z5Mj{Cc$ z_B$xpHcfRaTo~cbO{ksS#aY#?mD~WBXx`CrG3$b8@qJ%5&T;M#d9&SciSPYr=2r=W zy;fEI1|d>rQk%?C7tGr#Lka8;La)M3zjG}yJ!_V#md8JrnV>a(l+|Eb6j*-|pY4s$ z2QPpT7Pdb&P(Gsw(}0+nlMpHxN0IN?zr(IS>A5k9u6HL(VNpuQk0VY-moS7B_k7&n z5?G1o?&X86kR-}>&jMv;t-d7YBpdX+cX+?_%xByvms6NYD9s5*ir7kors7)0mK5yi z1t5r|tSIa|!cdw%yuwC<=Xjm6jbS9%#?*L72Mxo3@n)xa?eYF5Cnh=kUB~p|yVrX2XE`A~al! zp#L>laA`?K0F|n4+cEC5I>)ol%LPTvQeZFd=X>M#*U1Swky*au$53TPYNi2xn(ylf z5hB}jFY+gJWahp+v#`l1s~wq(>;X}BW41*)BC;B=6GEzCm{~~8U968h+*$2pi~7^c zhYEhBOU;Tn4JNF&W0QYjW>Nr}7RPTjM%+kCpyMo!m102(sTx$**fg6|gvzU|jp5$U z9I6_~B=SAbsfAuO3=OoEjNraCAPPh`RNGvZ_-IDcogcmaJQYT|A4?js2VdNIX6;jT zDva=+w5+X%gR$&98G!6GnZjBzLjra50p-ZQ*M6RNQ}QXa;D~d%HV11x=NF z_oTUds?!3f%Q(_VW#enYl1G4dlBNg=>g?6rD9uC6h-A=+ksk0z z8npe%mnE{lwy%FDkAOs2%5_aUCp&q6_PckaJb??npC8$lpIbr}fb#&SDMdY*Hp0S~ zs}OH?lC);Aqn~fx1G6|pEYrZpBGR68wZE+GtMY{_PB@PQHsOcjm4}wRaPh_z@?=ck zoTWb{!qz#yCTVmHrej8e%!LFD9c8?ps}GgIJ!uxg0Q!G1HOtCZ95dLK>7*yp?yt}c zfGdLjn3*A^GG8|T7W3gtJYlCHLRCR}~39$^ya*3DtQSMLnXG^1QtP3^|H-2kh_=0`+Ls^To$DvS-s zowV@H?w`aP5#!7RUf$ukIkl`!7@RQUuyNF$y7br&)*GXLQOl#B0+XAa1U{wTjpG-3;S_@IkKBK5aDqOvttDq2$!M!vlAc1n#^QP6 z>R8C;rCtYyInnv;&NdDuG2EMaG`d@u;h=m6e9xl<~)QLcS&q%dcF zz!grNc9=R>N%k=m7#xNSr#m9;6^id54PfqW@g@Zy(53MTqSM= zHJOBN*UwZQ(W67Uh|(~anJ;%=IQKM3xR9!wo2NfITlO?o!A`-kMRt!|m?iZb7fnkh z?iC4sES=Dx>&Vwjey66qfizRzpP5=g{#wlJc3{$*^bUZqjL#R4-5*XX$_=U;Pndsf z{wx-Yz*-o8Mr7dvhgpAiXP26@r|QX9Km6;P7Z*jZqzTa^&-Ypw6wH~B*(Lol_`Ft- zoiuac3k|-TzOT9Rosf~Go{D6bxCMqTpH)ckAp-?rw7Op4>oK86dIn7zngV^2F~HL# zuI<+Xu9Mc_3U{FR0zdgys2j`;2z`Hf2bUUG-xWTZB=J_f&6VSYYIG7~|D<@pR+%P% z8X7y6%8V&3B}-W@>9+d>F|S;^hCHohN5~w2GEPqY!5Ne78Zg3cph6g&wQ~?-^4^Wm zne&C#`HA(jokw>6{$SyB)j`wsChF+SHW!yvA(f^mp(5yGBVT2rRp;7ZT{?fJ)tt`u z;0nZBOVsZ?K97zju60nu@yD5`UeRSzce7jG>EdXlkwGhy3_;CyS_RIeo4ryY<7#ZVPU7=YbyANg@T2U={{YPHo$I)v zMnr|pMipx*4ydE-wapC+(E332!_wMyXZ9>-YpSaLyH|gPZXH$VQrh^y zSMk)DJotx)cRecnwuY!AZBTPg?c2F9AzDyNS2Rv1En`_Pj~hwWv<&em+?L`&@9Z|z zukn4!RP~NowY7i zABvB88fKk;yQvVL+Q)xvOa5ZqEf_6|d1@h=B_5H{3CD_qc;_&f4h0hj!0vuB(`U=A ze%a|dToX-2h!oM#42VYjh*)wPx^&I?Q_6~Jjr$b-mKfEpXL5nVT;+i4ow&XtPR@w! zSA7J828kIjDkg=o3)?Me5i*lh3}no0=Nz2*F@qr4!;MCBVsL-@%~+}6NfDdy^PCSQ zs{gN4?5#vC40s*i4+f7_4)4$FJKbsuIIj6}CYfa2!jott%y>(_;kAb3bLh8$cUh-r zCy*l2gx$ZV_{Na`%7=Q~XgsMgfCs)(DiAd34&D)~eavfmfFJC7`4-pgH!JGX5>RGn zu|ThvOrUM4L2rLMUrtaR9*~^pM&H!In5TNie@Tm~08Vh(lnwPk6Z|xtnBWq>tmv#fZ!ef2WNq)+s^&4CB`Ig=o1n~*pwgPQoHh7vrNpvC#w7uL% zDMU>uQ*<<#R?z$CIH>P_lVDQLM3dp~{06J?w0fF)4l#eaL`>ah64=VMS?+a1FA&Jk z9BtF)8vCL_%U~K$_UPXKq`eI(`^;b{Dj}KZqY79e*4;YAxCkRH8_jlOB#J`dDzp5bHhwlsT<-Y8jcHX#Eo?Vr5JI&fJygHKw=exwQ9z-O-{}CLN}flR z##jH^W&;4+tG=B%P!%E>oo$U#huEU2I5lT1*$}h~__YKEcYk=5sPe z?1;6F$Y&-<591Cai%G!1`BN*pc9=G|fcs@y&W;=RI$zLg?rLjo)?-SVJfSKQcS1|u z2~H&vLXz@DFP33)Ug81g2E`b9iSq0SALL2 zftjA5R!$YD>aQ()s*&|_I;2W5h^WEQX|EjYvMLpv&`E1hmJBp>Y#Q0=$#CPWu3D02uOdxrcm*Cyjr2= zzV`Mj<$OJcf$MwTb_b49FO()PL0Y@u7c!GZQ%f|0SJ|);@O+)p5Y;l~f|pga3=DQJ z9!V4(CQyX#e0%B?Z3^$IS0h;kra9O=r43$Anz;f2Iilc8u@uNYk^wnl-IYQ{A3NB* zamb*RCSO=KQM6RJcw2ujm%la&&zJ~HRdiuTgqg4=>)JU)XquVFe^eA0EzF~=Bc`lK z{2bX=QH!p{BoZBiSxo<^j`2+F0isXh_sM)-Qr$KzGFkR!{3c$aFBD=&-l7Gg*!aaY zAp+j2Z5=)N0B&4zjIa3*=iUt3ouZ$4cIN3!49n*ICpJWxySsng5JeZWf`j812K8D0o%<4+ z8vTcs=+2LSPRw-yoSc2HGJHUNI9tA zldv7mE-z84`NMzlRy<N7gbfetqSb&3 zG6{d@s4`0D#Xlf;;T2&*Bqklep9AbYMz_|5;|}Ze4R>4pltN1q@zI@w*5&)*LJd(( z)iyUi+nJOfRAi@pR;mN*V|wQBLTonSb6??Zz5T{cx5%g#_eAH1Bs0 zK~u`u=No@51!<@Koru!TD-VA7rKDXl&`sp{_3*9QI(Uf0oq%_opx(8WGge(YG>teG5Wt0)Gj(P0Q zod;Z|YWzzS!`Lm$lgw3ErRy>CU}#DZiubL5K@WdHh5xyzyh?nD=P}nS`x8c0@wKS;G0ZgzvoioJ1k2y-> ziB2%MZ~3wDjKbbX-4t|Ij-1T@*`e zzrKH1>liexQI+De(;9VdUM=5v(I+-)1e%GX$&c?T1(k_iOnZCgiaYPU8@Yq^mmEFz zmp7WAo1fei#|z|gSuXAoG#nE9wC{({Zq8t0L>z6Hgk6_)nVUxV-K)F%wQn=anbdT$ z%jQITx9262Wb|f5T9A~Fubg;cvMlfN?4y5yv(uhjQx}Q`!^)`H4}F;Tl6i1W`o|8W z+(ERWznWYLdiLgK)5k)ntD z9vf?y2QufW!Bor8zmoE%20Cy~7^jeN8JlIVWES(3ebPEOGG?H=UvVDwYkkh5pHY8P z+?7k2a5zNw6S(fr+1`yTB#0=4+%AN@Bok_#6OABCG1`W15Gc{}f{1vg@raP_Nprz6 zxJZC?T!(cPM8&p|^hefuT-e#iy)VQFU)M7PUqqUUTTl!%wpU|~e+#yWPc@3j9Hg?e zTaA%ZaCVna!IRj^hAd(}>S=)L(JX(EJO_-~N3lzZ4wcsNEVjCOtgu4}a0uMoN>KqE zX7YO8FKoV^2w$Nis}c;%$CZ$8sKUFFu8_4*tf=EGXe=qb$-94l{|&&md=bK+Xt9G9 zHQip}Y1J1)Nc^-d3a0mv9FY;SCwH*zDYQeW99h^aCyxbWLz}A-6fbmq!V`az7<_5? z4D#_=ixPf^uu?9v*GL=`*AT3K3N0;oQU2pkixSg@i?wXKI)Z;0Eh+J*mLTqFAlJ}E zkiuc*(W)@;aBADx?PEmrc2+goC5FA~cs&xr&D!T6R9I%4g7O7D|F1R;z?TwLoCIZF zrgxW(U59NuDC$^WHk0i=TQ7f8dW<=N80)Ljg_Gl_Q7Wj<`LEQ}jcVhmu)?t`sjL?M zS9Mfj;%Q3<3)zh&PcM&)S^+}`cratgqDP zpEg%2A_pKG5TeF$O4xskY(Nha&XO+CpeBSKsi4HN@X80uX6^;{$#FcADQ)NSsoVfV zweZFEfsZomDJh!jf_(yvM?^iKLeq|$U!GrkR>Xf3M}l7NG|s*>cyLk>?YsK8MPI5q zo(^bZ%$4z!TCXl{RmHnhvU_=0nf1MsB*nQmw&5SH$&r0r4{U!-siv(M6J5nhtxl;4 zFrN4byDxw;-i7l*U}c*;?VVBbOfLAqozwaUi|}jUDi4YTw~w|aveolE0RuNVuNyui zT)~WTNnUAMF23Pt?kHJNP=r^Zr*i|>3OR*vJG`V0mQ{opg<)x4+kv%Rl8g5w<+qfm zFiz!ZD@Kg_2z!6Ux-Ys0e0_~4jtSh$h)M7r5-elvtjY$+6oiiNXEUkI2FU%|_JZe# zSB2Mp69~(ks{=}Vchud)XjkU_www|e^X9#fLv5bE<96utXlAY=a>L3E{bB3g)|#Cb zYYk0#B1WSo=|qC8{&QSZ{_4Y!2@ z#nU7ilbCrpHORB8 zD&3g{f0ez2ncwcb9R}|0p_*xpZ;_dNoQ2^vl&xJ>`We;J?U{bmLhHyWK9hhxh)%ID z^P(2vtGrN3fLRO2$!7~+G7iZBCEuBPXhkE$3vA6PR!gB73{qEpCSYxXn+ZN(DTlVC zXvKdsG7U=y(r5;czwAXY)+O5Q_F%vQy))nyi-|hd5jZ#CX424b_erpBYZ^oHeoFfH zUjSZB!b_z-T(?vrR|<8t^~RmCXZUR;(dYlTgrC?&r1$TXNua4ouH~hW3m45^3JByT zNm_Os;-Qy8dMLlWugHQ%XgfXt(?5_Yx=w#&oXrOuphTzPMvJ>P6ZPlyD&=K1{=>JGqA1KZ($B z_>Ll(SNkC16CZl(S(A=oM9eP{^}a2J&>%K(*F^D8@@KT@F}!Ou(d#N$P*L@ZIJJK< zlco%PFIaWkyFFy-GF_`Do29#*BrTT&5WjNqZAE$^#I&g-QCrMIyB=MrfZqA&AZ;C6 zvLxKR^enLP!#DB-hx0EmZqTsUSuqK4qGPR9wdyO?^sr>LVo)Q?RuNbXg`glTVGQ}C zB|l|{U+t1ahB`T+$Un-zT!m}q4}^ac&^EfO3Z{i)VSJ{T!}0xq{$VSXXAol6$Q_lt zU|=8ZDr^spO&feeEF4_7PijvYjVi>If?5!#AGr~x-qWDA=E+X*vU2${ZsaRJhZ^f^ zPH|x&bD4b3w}3J?)aE!mHT|hwk?g%IK`*TEG$8TYw@7Qp83{;ALEng=YG{88LUFY| zfA(_DV^v7qEA$8s|LHY`jNq}8D#u!j6so?Q4<{8}d)l(ULl>W|@_^9G6(?6Fow0KCk*Phk-B;>${2?PnwQZ~FS|ZJpROy1}u8Dr)H@8jhwCvYuCs zNCpNjrHO;YD>czri&ha33D|$g(Qh<3R%*ErmeP=cCJ|L?N5jKJQ~8_%pbGB!(fgg4 zL6LwCj(1R{^%?NfoFbgiF`iRnL=_8vG=?A% z^xw7%v_JNmzi+Mi<~=$v3RGE|FdA*qf)DxLPc%+y7ijPT_}t$S$eKMFSX0n zgs@Mhs#)PRAy>MiLm%c_WncE;7%e6R`|r%pzG`M+2E-?RmN$!iy+y2M;}T6>pffUi zztl{!@hj-LP0mehNvgD|qDO;zih$pmF88D~+iF#}%OrtgdZ*2p@!gR(Ep!ej|WhGiqg0n)T+^B8?rdqqZWU3s6!dpc;qFAyRuL z(D7@#E}YUP{^}Mn;ko1bl(A#I*zxxzrQ-J&GJ!t^^Xg)Y6ITnnSSpcv+f^T(dC=R& z+7&N?kU7k|V{wXql+59|@kMhji=m}ef3P}~BMm=4wKBH*q`*}Je1; zbMiDOSt^J}C&Q@XiOAOm-OrH+wMAFTk6ZtI{n|dHk+T*Vn?6h>;;*$CEooRAR40Wp z*tesn7h^7rbXm$tx%?!skv|F!&!GT3x~zXTDB?C{N{G{EF_BO9HNq^d8*-@onQL13 z`vm4^u*0-}D(o;!9~WK)%@2Es1s(V)Dk|N;J(Cn+W+x7p!-lsee#kEgf1YjiqU`ZZ zDgAy{@&F&cD!-}43D&J@tlVB_s&L@UXvnZ2Qs@;zZa_Xo;ZIw)5vv&pYr!4Z6JM9( z^l0x*@$11$t;5(U%kI0yomr%5+P-RKAa92_Fmk1TV@@Du13mQgLScjOUHe$niI*fs z_(}+NdNIVZ;C*92c~fh(c=lQ|IqR=5+#{|U<1>O5rs&KIM=c?aDHX>jg4Xk8xH;8C z6`?uWufr^xbFwBm?dfEzg;#yDP^s8EhMA?I*00_l7XUEy^Bk2`ZG`Lhx?8z%(^MIU ztiINNJP*H-vz7c#1pqEy+uzK;n}5_6@TLG(eKvf|;J@rF2ovb8@DC#ZSabXAN~6&t z6AqOmaLBo+kxI@&!tdv2%yJq5+T+E)Z`464RB|mI?~GmQtYQ~&Yk39>sZy&jtbQrA zsR*K?wDOhK#LLD2jNQH_ov!0V>%GkX`2&l8P8NA$cQ%9AYa(^Q<|B%Ug;!&~K+3A$ zcNl7Uz(sCM-ZGlKgz-`UH0co1i!$ga_bky3dRd(h-FY-m28Vi&?Cq9OJkXc-F_mBE!)+6{;%?Yh%a1`}U|ip2 zzNa8(CdS4)z^~qkw!Ou!jmNQH{XbO$(nn^K0TvUNPj(D712Q%sH>AF>p?Icd(*s+~-mQJ}SiMDwoiEfHY+x;-Vea-<$3ZzI|UNSRP zlS%}FSkLmEgT(-;}EL zHEe@%NMRr(26QXb3F8q&4AwG%QUbUDZj~0$1($&`0w@%qw=lwXOrR;W%79#rqGf^y zT2Q&cpn}#Evt(eXgx;a15q}&bpqP+K;81{uK|oLs3Q&kbdB6~*kpy9Z1}HU10+gk| z7{&lrOrcODs4hY(nN$!15(C5(zy=}_Mhx_YdgW0B0t8rC+yEI6fpo0KHHsa}Xeh&= ze+u%2)zhqa8e-wV@z9w8%P5gQYlarfKMt7NQNQqR0ObK2!A}KF-PK=e>@Gu036SDc6ptr=NAR4Q3OZvI32~4 zVD~x+jC>y7mBK1_gY2Yd zX9<7?QT8=rWPTZs5|UhvCh?T~xyXuSJe-i(VmeInd4GC7Bjao`iF0z905E3-iKh^o z$Fs33JcmXn3AscZPLi|2#ViI02q4MR`FC^hwPFU|jm z@8lEtOump|9*@2!h2?1oQAcW-TJbkZ(@~m_7E`jAjX^APcVlVqAXTuica^l!7QsBoPp=P7oTjL9?}Az|a>9083c0BwLB0LbSH zi~rn#y?%>Fiy|S@1=>)2j()MU6Xd|QIe&uD0IU&>rLG0!O#vT^NrS$U^cfmOj`jf2 zi+FP8x-1jtwUt;wZ8_v_IXbpHWNbODY}L})%2AeEyJWi}Y1dWWb(MF$%DZ)~Jy&MW zmD%&k?A2vp) z%#({O2Ye;@6mUPB%t>4tu*;6Uy0PmvuA7Lh7-Dcpl^7CNIdPQ}uX0k?N?n=Ml}Wua zXT;+a=GD+|=M#_5j~6PyqhuHwQ~TzC~1b&YG6Sy&-lSIOUgjUK;7 zk6)w5uhHYz=<#dxxc}(UTDik&Uw@ceSMJNj>sDT*XUSE20n2Y%z`{yc(4O^cl~*rc z_qR^oZax2JaB`6Z`*CscdzOEn|1;Q|jRwI-9Kfx1v_#6S2_zQ9q>U|y}e2DSu&{`bD7VAeTZ*e=0RWrYJZ+Z>=_lo z;m%2br2c1+XIb&=YPQ&<(wG601N~o=9PPf{-8$Yq{iNk7&~jxTgXLF<$TRWcfHyquae1+qyWFwT>E;f zPwCd9t##}=^ND~9V!d1+fPWY)zrzP_{QwSGwXdUao2qAD2jJ@V1MD02O&_$&qs_`L zk5+fux`#S;+$Tva=-QfuQyr1g` z*nsvs0-O0PI9VjY)&k6i2Q+%d%rnvH2pD*;0l0#@`++mXhhj7`r++FrW2fB2`gEwr z>{Lk_F`?qKa2!9PALzFFmKoy?F};f!-(tHBbT=SfA-%)8kqGt>yyKsQT6o8;@khWr z{td=9(*QUALB=&+BDzX|>R-v;_BJYK45^leZ)5_?#P1_E=-AON$gJvXCwO+vWg`73u!iSVVgL zX-LaG;o*RX|3$cgyp{vO9`wUtxjMjb`2bkniJSWnELQD^o1aGT%~XEHBN|Z@*`peG zf!G9l~kEnkk9@Algl&bzI#u{-2eMGQc!?HFVT(gFEn}=oLy{dzUF#LBc zSJlCvr5oF;=qTx`XylyN&pI92#5xtP_(YoQfe)WQ=nH?W%)>S;O;vju6!KMu_Ds*O z-_5^YlKP2~RbaXPkA|GX?6rI-LkFr1g^mVM8A=!xOn*nHL-08rA)cig=<1fVOhRxyY9pG=t3PKAC%e`uGj$PI>M6blBjTxo8CfO!GNSh*@SDg zFQnWSby5J?3wVXj83UO}sWF5c@LGls@BkU63u;_09t^aSV0gF@(;|kPYH;s?g2@MX zBJeZ{%725dA`GQAkY{kBXX|oE1wSb$DwtY@bv_~}7nPyV;!#4sO>K~Jm+r?UES*3z z!eA&PlqYb*0~2wpF^yPcC_?b%HXY>;D=CXe2Am?l3J|LBsE;iYas-7$wiHvgLlljc zAyic%g~p`f1M9{I%*G`i7UZ^ll&w@)2(x*>C4Yk^{IDrG?iz7A2pQB6z>~nUoS4E9 zWH3{-VN~jz1BuMyN8vF}l#-;_a!8R81?)jJ5C@70I}t2GwxbZ6w<_fkMc62TDGJrA z0U~(N6U|L1kOZ2#H9lv8E{?-dJGM?pLvO5GzuFp&+MqkN>Tj9i6<)skM&4PJfhTY! zdw*Puojh67cA+a_S!HPCW#|#bs?B7NfEvX1n9^50bxVw+5xjh zb5(dMEyN-Waid`J2Fw`iNvS0iREo!aEqNTlDw(h(ptmsEbrqH9imbid=2v}@aqIV2 z!{yAzdI%e`3OWET6Cv|j;UQjXeG!0=TYuk2MVZr%mEMk9Z)QWILJ+MBBY-)~lmxf% zHz=^4(Dft0c1)F0_vGHKEmrU9t{1F#7RDKDCn49<4C^Lo8LOVn~+(Pu`=4bzd&KJTUrnQ%=PYfQq8=YKFj8ksVq9>fmX# zv{1ld0ta=3h#eL=4zE(<*oH<#@qhe0w&Qq$;YS%e?g?9tMpl{#6RGWF!%Egz;Gjf6 zsrLS7{3+uicWvgektx&z&a+r==3Z-0Fx$OZUiYi@| zb$hod$~KTjd@i>sDoQF%Vthhb zyvncZlr~i5`8tREE?rXErAvFw4)fO4C0=f*tuoZNS|#>yUscu{aDS55Kcv$zy0T$d zS(0y+QMqB*-aM?Wu(f%Jzgp#GJztYtnp%^-HLh$P`n3C-hh0$htg=IsFy4jsPqz3J z_D?I7CaMyRHIr3QSfT}Av^EVLmKOi5b$Moa!NqM9zl*1kv$OSX@8jV=w)b~G(GW5w z@%cR9uEcY@|Gdd~uz$&nz3~PM0cCH{Y|Zh+Bfw*WY{!?c?7`mvUa%9)*o1*&gX|UY zBpq$x`D4sHE|Td-m^5sVPh|~Q>_P(IvNuz$b52kfsSux5=;fkg}i z=Jwxk@f0rQ1uwq9>}xGDCR!rfq`VTEV!oVq$*b~w^db2~zLW>I@f@=|#f)c|r;G9s zb8(Rru{*xpltRxXt8TUrj)nxjJe-dw^&7HKbP4wTH*ep(Le|uJQ1{Ardj?hM9Np<7NJ2Fvv6DjEj2cz?&am(%spjlQ!7-Jjg;g4iDa z_pTf)uN#y{>)m@`&ytkCWr~$Gdy~c$ZFxi}`*wd%O8On~Zym zAp(8k+)3m9KlQAhMZR2wV7^?K>_Gqx8%E#2!)=#DmRCf++;X|YVyM30u>{h>za>)N z`e=$$+<(b!zJBrH_=7LXqvU+i<3MrPz-#AtSDrRRDVm~Gz9?}#?H*`-Nut1)lJw=c z*OK5zklpeMQGG*b*t%o03Q7Muj(-VfR9*&hqZF#d-4iNZoM+nS_1&P0>bgb>IB0HkU#M7?0x0x;~>Kv>?k!dq6(jFy^n##HO(yRV(w6k~7s zIGd}4-ED6j(l&RI_N&)l-f!=e(mu+j?=tgt6Ax7M*d5G-Hu1X+c2*5u-k-WOox5oa zV}GIPb7BqOF6sT8*zdLUyQ~N8reQjsT2@_MX%~MkFWosisLq zo~n}fsv$U`-(!%`cN(wvUqAnF^0_7I8-K$ti{mX14zon{~J zc3$mmbpfN_1}UtaHti>H@Eb@?aM*Rq5*+yI&2*z)BScWu@Zb$^=%8@`5Qs}v_kT>$*412TBuM)A-cd-}Yb@XOkd`+V``ANcCOFE-CvzdmkIj{wLkX4vg@{ zzqFJGUBw0`FFfA>qp!NbKEHK+R;K+ynB^Uu_WoG&OEIkacFpp;G&r}aKTD%c{Z$(L zs8!ELZTfp}Z#H#*r^fpzPV<{MY=7Ciq<8PVwdd1fU4^&wPCee$-Ft6s#58*sD{}Y6 zF1@a0cn`5RHa@yPU*xgve-C9{M5=mDjtzd+)sq|27%2O-AF} zPz~S--uiYD6YL&P>{~~-DbsDrBHo}(c*tOnLD`KM?Fw3bl!2 zE3T~9nLLV4Z(AX>>07}*=e@#<9)rM}=GATDz z@r(>Bf89&NFc5#wUvcjuZ7ylrz!>PJI2=Q!AR<0=Yv~GZ8BP1(fA2LH#RorNKK*i+ z-0vfaffOuAlR}XKW(uUrKxt~(6f_}fglt5r4Q7NAjJ0Ai5y`{bv4-T@9eR=651T%e zV^fOcvh?-11IcQBv$%LVTebVm;MZ=ya&~#Xf3BNh(U-3xjL&Po?b>7SI>4eJOKa-4 zo$qJ6l3F5JmT@hSs>inKcOK9vK6-W7x~e@i6aYhKI{o7Bu54;Al9?OGjS*CLHLb=# zVfwbMJUoX%kTL*I5ILbGc-mwH843iG(}A>nc!&I;e*RSDube|wIj+BJO~Tm0hj}gvg+knG8g8_ zy8nrCJ}iZ1*{0Xx2fYM`;bkV;U?D8x*|Ut6z(bTf87+nu%598V;bF=hFale7whY>3 zV_$#A%U8g1+2Qr6Ia6B`r(TJPM_{Gwn4-lw$||gqootIGPe2E(hAwy%*1%)X36H~C z=$4(nAA5UXo$TFD(DC~p1va2`J0l%M2++aWaYZ`O?g-D4T&>;oJ{zQm*%H zQ?7O~X4_$ra@FZ5xey-lj!;LG3AGb+U!wftzhhmS@@p5G^4--a$(k=yzT<3^gwU76 z3gvssrozn&F|iWJxUT|I?5kC{^+kWol42*t-l@XuXgnkB-lf95l&iY>KNEEkWhcsB zRh^AQ52AJJpc}}&6I-vT_}f(MAiLhD;>?LCNrV$+C*w|(ohUm|_CX-y&V}$HAiGX> zo!I(j74LM$QCn21|Hf46eJ{%GDvf`X%F~01kN^KDyHvUoSKN22Y=6XPROMTtJ2Bd$ z@~dZJG^X{B_%~qMhfu@Fzx^V From 7c8e1f80ced90b8e5be66a4b7207eba3438f4e60 Mon Sep 17 00:00:00 2001 From: yao Date: Wed, 15 Jun 2016 13:18:23 -0400 Subject: [PATCH 004/197] Updated several codes. --- doc/Code/LocalizationExample2.cpp | 2 +- doc/Code/LocalizationFactor.cpp | 4 ++-- doc/Code/OdometryExample.cpp | 4 ++-- doc/Code/Pose2SLAMExample.cpp | 8 ++++---- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/doc/Code/LocalizationExample2.cpp b/doc/Code/LocalizationExample2.cpp index 42f19de9e..34b719e81 100644 --- a/doc/Code/LocalizationExample2.cpp +++ b/doc/Code/LocalizationExample2.cpp @@ -1,6 +1,6 @@ // add unary measurement factors, like GPS, on all three poses noiseModel::Diagonal::shared_ptr unaryNoise = - unaryNoise::Diagonal::Sigmas((Vector(2)<< 0.1, 0.1)); // 10cm std on x,y + unaryNoise::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); graph.add(boost::make_shared(3, 4.0, 0.0, unaryNoise)); diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index 9be7dce99..8b80f2b2a 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -8,7 +8,7 @@ public: Vector evaluateError(const Pose2& q, boost::optional H = boost::none) const { - if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0); - return (Vector(2) << q.x() - mx_, q.y() - my_); + if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0).finished(); + return (Vector(2) << q.x() - mx_, q.y() - my_).finished(); } }; diff --git a/doc/Code/OdometryExample.cpp b/doc/Code/OdometryExample.cpp index c2b6558a4..ef880384c 100644 --- a/doc/Code/OdometryExample.cpp +++ b/doc/Code/OdometryExample.cpp @@ -4,12 +4,12 @@ NonlinearFactorGraph graph; // Add a Gaussian prior on pose x_1 Pose2 priorMean(0.0, 0.0, 0.0); noiseModel::Diagonal::shared_ptr priorNoise = - noiseModel::Diagonal::Sigmas((Vector(3)<< 0.3, 0.3, 0.1)); + noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); graph.add(PriorFactor(1, priorMean, priorNoise)); // Add two odometry factors Pose2 odometry(2.0, 0.0, 0.0); noiseModel::Diagonal::shared_ptr odometryNoise = - noiseModel::Diagonal::Sigmas((Vector(3)<< 0.2, 0.2, 0.1)); + noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); diff --git a/doc/Code/Pose2SLAMExample.cpp b/doc/Code/Pose2SLAMExample.cpp index 470f13397..2e2b41704 100644 --- a/doc/Code/Pose2SLAMExample.cpp +++ b/doc/Code/Pose2SLAMExample.cpp @@ -1,16 +1,16 @@ NonlinearFactorGraph graph; noiseModel::Diagonal::shared_ptr priorNoise = - noiseModel::Diagonal::Sigmas((Vector(3)<< 0.3, 0.3, 0.1)); -graph.add(PriorFactor(1, Pose2(0,0,0), priorNoise)); + noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); +graph.add(PriorFactor(1, Pose2(0, 0, 0), priorNoise)); // Add odometry factors noiseModel::Diagonal::shared_ptr model = - noiseModel::Diagonal::Sigmas((Vector(3)<< 0.2, 0.2, 0.1)); + noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); graph.add(BetweenFactor(1, 2, Pose2(2, 0, 0 ), model)); graph.add(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model)); graph.add(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model)); graph.add(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model)); -// Add pose constraint +// Add the loop closure constraint graph.add(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model)); From ed7e9af2a46762d20cbf8c733a20530da21a5cf3 Mon Sep 17 00:00:00 2001 From: yao Date: Wed, 15 Jun 2016 14:26:10 -0400 Subject: [PATCH 005/197] Deleted irrelevant files. --- doc/Code/LocalizationOutput4.txt | 14 -------------- doc/Code/Pose2SLAMExample-graph2.m | 8 -------- 2 files changed, 22 deletions(-) delete mode 100644 doc/Code/LocalizationOutput4.txt delete mode 100644 doc/Code/Pose2SLAMExample-graph2.m diff --git a/doc/Code/LocalizationOutput4.txt b/doc/Code/LocalizationOutput4.txt deleted file mode 100644 index 902b79f79..000000000 --- a/doc/Code/LocalizationOutput4.txt +++ /dev/null @@ -1,14 +0,0 @@ -Factor graph: -size: 5 -factor 0: BetweenFactor(1,2) - measured(2, 0, 0) - noise model: diagonal sigmas [0.2; 0.2; 0.1]; -factor 1: BetweenFactor(2,3) - measured(2, 0, 0) - noise model: diagonal sigmas [0.2; 0.2; 0.1]; -factor 2: keys = { 1 } - noise model: diagonal sigmas [0.1; 0.1]; -factor 3: keys = { 2 } - noise model: diagonal sigmas [0.1; 0.1]; -factor 4: keys = { 3 } - noise model: diagonal sigmas [0.1; 0.1]; diff --git a/doc/Code/Pose2SLAMExample-graph2.m b/doc/Code/Pose2SLAMExample-graph2.m deleted file mode 100644 index 1cbd020d0..000000000 --- a/doc/Code/Pose2SLAMExample-graph2.m +++ /dev/null @@ -1,8 +0,0 @@ -%% Plot result, including covariance ellipses -figure(1);clf; plot(initial.xs(),initial.ys(),'g-*'); axis equal -hold on; plot(result.xs(),result.ys(),'b-*') -for i=1:result.size()-1 - pose_i = result.pose(i); - P{i}=marginals.marginalCovariance(i); - covarianceEllipse([pose_i.x;pose_i.y],P{i},'b') -end From 0472b14ebf5abd3497357865f685345432530748 Mon Sep 17 00:00:00 2001 From: yao Date: Wed, 15 Jun 2016 14:26:28 -0400 Subject: [PATCH 006/197] Updated two code files --- doc/Code/PlanarSLAMExample.m | 8 ++++---- doc/Code/Pose3SLAMExample-graph.m | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/doc/Code/PlanarSLAMExample.m b/doc/Code/PlanarSLAMExample.m index 0231d52d0..8f63853e7 100644 --- a/doc/Code/PlanarSLAMExample.m +++ b/doc/Code/PlanarSLAMExample.m @@ -19,7 +19,7 @@ graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); % Add bearing/range measurement factors degrees = pi/180; -noiseModel = noiseModel.Diagonal.Sigmas([0.1; 0.2]); -graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), noiseModel)); -graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, noiseModel)); -graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, noiseModel)); +brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), brNoise)); +graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise)); +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise)); diff --git a/doc/Code/Pose3SLAMExample-graph.m b/doc/Code/Pose3SLAMExample-graph.m index dde5ba85e..702928759 100644 --- a/doc/Code/Pose3SLAMExample-graph.m +++ b/doc/Code/Pose3SLAMExample-graph.m @@ -1,12 +1,12 @@ %% Initialize graph, initial estimate, and odometry noise datafile = findExampleDataFile('sphere2500.txt'); -model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 0.1; 0.1; 0.1]); +model = noiseModel.Diagonal.Sigmas([5*pi/180; 5*pi/180; 5*pi/180; 0.05; 0.05; 0.05]); [graph,initial] = load3D(datafile, model, true, 2500); -plot3DTrajectory(initial,'g-',false); % Plot Initial Estimate +plot3DTrajectory(initial, 'g-', false); % Plot Initial Estimate %% Read again, now with all constraints, and optimize -graph = load3D(datafile, model); -graph.add(NonlinearEqualityPose3(0, initial.at(0))); +graph = load3D(datafile, model, false, 2500); +graph.add(NonlinearEqualityPose3(0, initial.atPose3(0))); optimizer = LevenbergMarquardtOptimizer(graph, initial); result = optimizer.optimizeSafely(); plot3DTrajectory(result, 'r-', false); axis equal; From f933008b48b3b6e12a395e20d01348c09645a63e Mon Sep 17 00:00:00 2001 From: yao Date: Wed, 15 Jun 2016 15:00:24 -0400 Subject: [PATCH 007/197] Updated two code files. --- doc/Code/LocalizationExample2.cpp | 2 +- doc/Code/SFMExample.m | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/doc/Code/LocalizationExample2.cpp b/doc/Code/LocalizationExample2.cpp index 34b719e81..7fce69566 100644 --- a/doc/Code/LocalizationExample2.cpp +++ b/doc/Code/LocalizationExample2.cpp @@ -1,6 +1,6 @@ // add unary measurement factors, like GPS, on all three poses noiseModel::Diagonal::shared_ptr unaryNoise = - unaryNoise::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y + noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); graph.add(boost::make_shared(3, 4.0, 0.0, unaryNoise)); diff --git a/doc/Code/SFMExample.m b/doc/Code/SFMExample.m index cb6bdf00b..80d7cf279 100644 --- a/doc/Code/SFMExample.m +++ b/doc/Code/SFMExample.m @@ -1,9 +1,9 @@ %% Add factors for all measurements -noise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma); -for i=1:length(Z), - for k=1:length(Z{i}) +noise = noiseModel.Isotropic.Sigma(2, measurementNoiseSigma); +for i = 1:length(Z), + for k = 1:length(Z{i}) j = J{i}{k}; G.add(GenericProjectionFactorCal3_S2( - Z{i}{k}, noise, symbol('x',i), symbol('p',j), K)); + Z{i}{k}, noise, symbol('x', i), symbol('p', j), K)); end end From 66adb25886466a10ba07830369da6baaa70f269d Mon Sep 17 00:00:00 2001 From: yao Date: Wed, 15 Jun 2016 15:01:59 -0400 Subject: [PATCH 008/197] Updated the lyx and pdf files. --- doc/gtsam.lyx | 27 +++++++++++++++++---------- doc/gtsam.pdf | Bin 823965 -> 824145 bytes 2 files changed, 17 insertions(+), 10 deletions(-) diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 38c6d2b4d..29be8dbe4 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -1117,7 +1117,7 @@ The following C++ code will recover the posterior marginals: \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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={C++},numbers=left,caption={Excerpt from examples/OdometryExample.cpp},label={listing:OdometryMarginals}" \end_inset @@ -2239,11 +2239,11 @@ 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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={Matlab},numbers=left,caption={Excerpt from matlab/gtsam\\_examples/Pose2SLAMExample.m},label={listing:Pose2SLAMExample-MATLAB}" \end_inset @@ -2417,7 +2417,7 @@ noindent \end_layout \begin_layout Subsection -Reading and Optimizing Pose Graphs +Reading and Optimizing Pose Graphs \end_layout \begin_layout Standard @@ -2481,7 +2481,7 @@ load2D \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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={Matlab},numbers=left,caption={Excerpt from matlab/gtsam\\_examples/Pose2SLAMExample\\_graph.m},label={listing:Pose2SLAMExample-graph}" \end_inset @@ -2558,7 +2558,7 @@ name "fig:w100-1" \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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={Matlab},numbers=left,caption={Excerpt from matlab/gtsam\\_examples/Pose3SLAMExample\\_graph.m},label={listing:Pose3SLAMExample-graph-1}" \end_inset @@ -2717,7 +2717,7 @@ reference "listing:PlanarSLAMExample" . 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 + However, the code on lines 20-25 is new: it creates three \series bold measurement factors \series default @@ -2732,11 +2732,18 @@ bearing/range measurements from the pose to the landmark. \end_layout +\begin_layout Standard +\begin_inset Newpage pagebreak +\end_inset + + +\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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={Matlab},numbers=left,caption={Excerpt from matlab/gtsam\\_examples/PlanarSLAMExample.m},label={listing:PlanarSLAMExample}" \end_inset @@ -3237,7 +3244,7 @@ Cal3_S2 \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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={Matlab},numbers=left,caption={Excerpt from matlab/gtsam\\_examples/SFMExample.m},label={listing:SFMExample}" \end_inset @@ -3396,7 +3403,7 @@ The example involves eight 3D points that are seen from eight successive \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" +lstparams "aboveskip=10pt,basicstyle={\\ttfamily\\small},captionpos=b,frame=single,identifierstyle={\\bfseries},language={C++},numbers=left,caption={Excerpt from examples/VisualISAMExample.cpp},label={listing:iSAMExample}" \end_inset diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index ef4ec2df15acd3df8d65e97571ce0fc4e7865f65..240528179e0dc879c32e2bd2e7bfca6612f972c0 100644 GIT binary patch delta 64817 zcmYg$Q*@wB&}MAg=ESyb+sVYX^Trd~b|$uMd*X?08?)d4?_TU(Uvzg>*QwK|9^{s? zE|js>H;93;awU_N&;VC@dhwf_SONJ)g;My0u3p%gC6Gy+=x%LGWi!SvqzrJe4Dn%W zNpusLKY=eIL$`-<>{wg7CYs<#ny63dyocN&R|-7n7f_^aePh7i-PhTDMqHTNRDW^T zgD8|e!Kum}=kILr3psBdO3d9URrbgfMGvvk@BU(=#;$6&5g@x-zR~S-^Gb*SLqrz_ zJ}d+lQDwYTO0)#~f|M4!)=i+y6hmQ(-t)!r-l~U&pBWQ^C6i-xgYKr26PQ<@N$Y`>u0tgu1h3MqQ+7-%|B);uN2%&zsDwRaT%X8 zXgSMTkg661;U5wl$i5x%OD<>Bu%dHK>lQYdCbrdRF@UV&PEU73Rh`W1`*W}`C^Q90 z66pwd5afQr-?Q`mc=(b_F`z+1!_~;yy~lLGbA4p)whpW&OP>F*B?g|qJk$GA1PuruBML%@oErsl+Crx4xUJZbzVj4C5n8olbl^ z9KfRZMomkLS804hoG4_7^Wmr8<8BvY5z9ybN9}0)gblS#l>|AZZI9g|&A-cyxm;_3 zl@bs~)Tqj_&ju(Cc3&6dtlL}cMl=7xknG5BGQfAH^j zFazy`-<{a`-%ZxMEqozJ;RS)yb{c((!m8zKw1kgS1OmbAJw5nnx1IEIf%M{Y8 zpuSf9IClAyC4x7=&;SCF$Te(a5gd`-5auU~6)M!!E+K^qA&3kP2n>b(eKY*P(^x!; zsE@iMBA&9q7Eg)e?QSTn6RrKNXA(*^1}u!&!WRrgS=H0E48kah;M^CAdMU61OMf{I z*KDR=B?;z-Tx|R!tNBwHNOmGSjqbnd=jcP;XzS|+<*o&XqyiO5bB4fhR{7Ks(_;pFE z4Bd<}W8r^Hjk*W!_O`Ni?|yNhkY0zE7>>vE-jD_5KzC}Oy>*PwM(eT;zHIQ_+Y?GR z9O+>ANoWjw8v@H56XafJ$(hMsJUC`JOoenKf;)@QX6XCqv1*#^1P9}oVKDHpxAm<0 zJ!vDd72I}P!5+E9neTa?DsAaQ_%fg1FV&}zeN+sC9 zEt4I>5^k;5zY^nrEw;8@uTy~X&^L5UXu?)wpMwOO9jTzJXgV$&YVx^D(0r|wjTX?| z@-Nl&Sj+hhW$bMBw~kFo_6ie{#4dQS#T57k_N|9?kEP`qXE(o?H{Ki(0;br71}D z^c%0pl~G^0gq9wGb?5wY6Io_~fP?f~|Mfy?iQDJ{obiEQPk{GaMgQxt( z_V5O&25nsUbY)_Kf?<*-H;au=HzRptR%-qlnGFMTi_5_5DxS5c{j2O|7!#s2322E+ zVWGcbp*htAL!Mrk&+N)&EG}{ySyAHo6!Wbef7E$}#hMyd)|pai=*YH|dr-rPt3thW zR3T#O?>0_}MeqH3ztZm4#n<}FgJ6mDJZ_Pk>BK0xlRlDWozb1)3e{Ses9JerM(;KJ z4~$pwF%{0-;is#ci@AyY|EwI7QLrGI<`nGN!FgEO|92pq!MBdzY=8Rrge!yu^JO`{ z#mY1j!cg!?zQo$J&~5&2kczFrrMqb8PRfncd+d9;n-@X$r%{XwV5U*|bI^r+j!W$c ztJvGsAMiQ!G_p)LiWb{k!rIZRkRqP-AdVK-teAYEbN_JqtH=<0s_QQFhv2>iO0kb& zTm_E69|ulAuk*}Le)v?)qfhtnTBO6R*yvibMvjYTYR61Iy(2&O!?P^g$6&kbVv}W{ z*shb2uFa}*{M_er>M6TQEBN`g432ydR@q$T`+~KqwQf}R)$z_By1)mmA zD}e)44WYp7Ry_sKLk*EchTPdM>i5_yAg0I!dBs54PpIcv_TbzbKJq!piBNVGg&ilNl75mzPIwqZ4)GY0( zF;hyzZ+EwXmEhpp|8+Wm3gH5Wck^5dfsq4-&7*JgCyQnQddsEqD>kWQDvEUr9X z;>BOI!pT`DLaFYG5onPW`escHAc`GQZCzlsS^ zW$^>1gfmmi4$#3l5d2**vLS@Ru*j*%*CT1)ODKCI(LX5@23Hi z&_F?mWM)lInSakrP)fC)&j~XhT3Vnozd$pe=Af&EFe{gb`T&Ohb(iNB;eQ9Vpw}bY z^G_02DXtM&hx~km2xb|%E@33BdZ}h(uwe1ECj8L_1I*#5!w`di)P{w~ZzmXU{Uy0! z3Bbr1VG{@q z7ym}`dyRw*O?j^h%~E2C@*VyZ+HH?L$Oyn9=P>`uNi>P3SS~K@s@kd-j35l^Zix-P zIo3&?>lCLCX84oVF7`5Ux7Gu#Xyhx5J^|`Ff&fc4%eMMojp!QwtceB>!3;+Nj$HPuA&Xal^B;pJ zwXtN`+n8O$#LC-LWt5~17=R>k>ZX;i2#bK0@G0s{N~kF<#B&TEz(*@8wLG}mW?3;} zj5G8HtQGZ7`tCc5BWwvo$mTH!?edgl+* zyd)LzO%0`9fphA<_;Yt9LPLV3bnxo4iY>$AW~a0x*7zXO1at_QabQ)kx2V!yZt$UU zWsg}={R+c`6rGVqwHJrV>$%*@!bw;_<&sA}o{{Sd7+_1}r<}MG~xd zOeVD$q}qOYNqGsy^O1(Vejj2KfgU%dz|!=_8|_@qPJd+=HC!uLU#!= zWNjLHI6>mZcuQaV2mFocxNou`jp_iGNW4DJ*)-Mp^Wf+4MllDnx{?k=hI|KCuO2_?hJ&=}%Oc09jb^|H=OQl~Em92Y^xzvUDggGUH z&)5V9@L_1x^50;;Q`+MFf`!0?6rI33>ib$kosw4rsonD(Jay$Di0;Y{V9C86@0Zx? zG<(hVTN`Ug0H@^(hKjlXn)3CcS1pSl>FEw=3R+dd_Y)AU!GzQpm0VXX2OJdZ@(E=x z!wwGD_AimX%9v$ZN5$(%f5UU#?5Uk(?4_bJbur}rK?VH;`;8~?`k|qbK#2=_2 zbwPj0$4TbXW z&J{Z03y46E)TGxJ3q>Gft~at)8-)Jrh*yXZn{csNMvIdhrIH&*gQrxWif^D-xwp^^ z(O4Dh7!!>7|8{00|(DVa--d6Sj#0S=GW3}+X=hc-34~OFTVxVVCrCXkD-dlJ> z_TN}ZA}mxo=Lh4>*Y=eM^?)Czfg!#(QS=!Z;pj{35*ukTYtAO~(CN>VUS}X&S58hk zbHLQhpqb9mg+fcr>4130tstn>a8~O;xL?h)nE^a+31x#Z{)7PzB2f5=O@7t$s!XT$(m|54RY;MZW+`DVi12!+I zW5Gcvt(SULdM9K8`puS=4(U>ff`5=ENkfXdezA$r6h^oar@_Zt@0fXaH%7>Tto}$u zq4=rn6t}oD#V%IALaF}70AUMLFWD)}71Va}c4=@yy^BYn?reGDob0g{5=6wKO0w;5 z>t*(PyzEFJk->}>q6EjFPRbjf4N&dZsd|WgWaC!~tQ2ny*?Z3+{aGz=(>>T;pUiXP z_}b!8Y{`Ihcpgliir0;TOt}VC-@sy9RfAfonq8BhRk+?SMRKd-TOtSxe!5Ni>VHY@ z*vyRi?60=-f{5I`6o{LU0RFWhq}!$^-?U+at&s=G{8FX@-L*nh+B|`20t72sKx(UP z1++_3<&Z_`j28yDZ6Cq6`}bU|49%~pWsU{i4V4+b3>C#sAc?hWr@HUWfM3&tevN5( ztJN}@Wg#Hp*_y^+nJ9j@!6B-Mw1_xyC2Lq%O#lx2$fD)lo^6bX96b`QV zo%MO(^XO>=0JTYn0PRd}jimu&<@vwttgfEp!GG-RT-|(e>zs+eGf#<=QV(D3<#zDi=X0)&r8rZXDj67X-{)mFJ+(w~s^M4w_{v%zbA*Dfm zVXxWxn2HTqtw(LYqC6Ika#~z-yE?tdn;ngdvS6uNYsIhgCb_{94?higlR;bn^7Q5W zZn!$(&?L??XK0Z7^&%e_$d3{P#A;LgG#-o?Nkmw@THnm~t`Bag1D{nVfaHpEfd}e~ zRd6r{j@J9eU^IXCizh|ivVdgG3W0)*2$;DbOh!;y*j731wlUS!n4^+)TfzUO(jEF) zLL`OK??50lJ+gp9MiPT8vie@`iHsS@CtiThY>CcREEX6KDwn7LZ;6x($T>r~W+L6T z8A1=u5gUT%#DTAo*m4ZQPBg19&w=LV69+x=SMFX72456i<-_GlrNS$g11`xKRk1XRsb(sE%Kn zh=lIT`^kiZGn_gBK+zU|nQCA#xuBC%r>w~Bfs1&j04B9U*ZaRIp|tRjt97gI04z-IUr@eGr3sOAVccBJ`v0U8N2f* zxS_hjY!#Ebo4S1ZuYQ*rRu&*rGC#lTSLZD17WFDVW1cI`;L#0#)=G&HSk@>zzjkqc z{Hh7y)YI4&eX?xP7-839YL5|zm^yOoj`f?pq^>15>hA{zw&MPV-EF62zPDqXzT{lLj;iMQS072K^raFeb(L{HY@yBfay zj_t_`;`4o2P62@T@HR?^esuqeXh@8{cecSL7In!);M_QGA)gq=sr;gh%S$ zaC}E{^Vuo{&z*C>1aH26q)JtnZC^*m-b}twBP@%u#P7_sB2Rav0r07Pl)qSn(P1b^ z*uiIOj(@L)A0Tp8*~OQ^Q3bL6Itg-|c)b3oOl>Iu^yNA*VUvLoK?67}A4u-TsY@ba zz6IE6?+%}3Ua6`uiQw}%D{;fa{v*Th{meIF<5JCI)ehZ;#cLGkEpFrDQ(6DoM5Vg{1Sct$)HC zIo1wVFQR|rA)_HBdIbbC!Mvk2a<*>mUBTWgqD_dQ&~OuK6g z?6{rCYRWWaDBP$Jh1h4h!M}v@joU7;GPboOsxj!RPF-Z+-rJ9x%k%HB4B5eE*4LPN z$GCPSCyqvCr@-S8QAc3+MB4{gD__+!A}u!{9#K~FV!a8~l zJDKU8LlSRwg=iZ5DyfAy!taPJfYxBwK0j6i6qp09*XKtWYxK9Vj z^_=deUDy?8cje9UP&DS9*b7Ql&9@M z6K?&YQ?WHuP5_Iaj^UY3)+r%Uy6PN2$trN1ri#(v$ncYkgsKU>SkJb_`%$$5{sFVM zm@TLKVJg9%4e=yCD+ZC$;ELdtV))>}Mky6+k~4Q3|0r_OVxbnsji=v!$mB3{@ z11G{eGGM%|Uz4S*%moz+noiU40HmX@7mCS!1^gbzoiR}h>c_qbN zf&I}eSncD83wQX{_~ThnA0gLw{I{p)9L6`iaBf%s)rp&;`)~YtNLMX*Wv`;z7tfb1 zkJo(AsXIs=AT4N+JM{0A#0ecsbi39lWWz6s7i1l9PzRpU#{4AH_-V3CwJKZM_qS81 zbacLhGSo!vMW&UHgja>u|Kt(iBbfG;^&7ql?6q0DR%kp*XcLLK>!H>Z%+k|1QIFOS zDg!UjJ%`~EM{av831zottP@i_U6Z)S!&;7FRDfp#n|u2f#zSeL0(vBV0bIrpgQQ44 zm@2I>F3^XN?ZG3Y-6D3j3hFSasvUK7jEW)f6D_(;iT|Q|pcLcT(TwjzM-sy;% zV%J>=|MQ`M+Fpba3u#_@Z3vN?5UD{q|5KnB9P4fKb^B5-5e#)s5Pw-GX$bi;BD?3D zINv;~0TV_I=i}1?E&^NxN?^g78Jw&O*x?J)C;*9f?>C+7T!PW$m^Op~`oCguvR)M` z(C8q%#6Hs6I-X|idm1I$g83_h-aBcL{o{$RTe=mEho$PcPz(j4#OrO`b=GrSEQ?zk zg4?U-mw}I4ucy=C{}X>d$s(*s_Sj^KcKwLDk>7sGGLP<^h3?l^H#KoFZ7T}q{4@PP zO@T3a-!qma$8bLDB;DujrJY*-3CKbs86BJZYbZz)SkxBKpO?vMEc`)Af`pZ&NM#@s zQKiDV`$Y3$AsfVVFXO&Oj57L72Vb{I0JM%tv^oo2x~2ju;zjlEsmT@kCXDu!v+Wj!H+XnIKMf7x z@U#4MbkuG3%$kO!;Axdgm*RtLe?4KAwE1`|2?>7wNgIy2^FmxBBa6%x1A?%lZhZ>{ zceX@Py&N^XG>PMLMmrk@uuOC72)GW7j?T%Y$pCE?n-6D|PSxT`p!4cC_4_&;amWaq zULJ2Vzx|lHdtEruCcDx_^`d$<(ge7Tt`*ZT3k}keDU$sF1qm{x%9ODIJdzo85vG}} zaa?WfQs`Tjy;qZc2FGe9XX*FvI*X?2S}wcG+krM4u4=<@%&R zZ@6r>tX14Gx#XELAYY?qW3)m+Gq8rbm|)0V=OV~Fb;h8o*@b4KwFmXu3xB#mg7AbzdK%>1bQXmxeQykwwDZRm;h#F(&xH<%a9kR%DY(4Vq`GzuETf zctad51|}Me3QashZ7WjOsuU0Ou+Y%c$*ZVT(K7b9kkLpTI6GgoVA^O@YlC_&wNuML zjhr#|!A_V)dS}F8y@6^rV4rZe_Sdl~Ho$&X>u64f z%aXmdSYh=XtGEFv`iQQtj2e~uM&(FlQ#%i(q!C7HO zvED}6^g}KisCLjP)~_v(?QKmRT5RHFkAlLh$s{$yK*wX2M~y_ce|#Z!V*bUOL1QXI zpr4&4_qv*`jd3`DJ74~b1Qr}3D3JGsbnW{UNmShPJhy+A5ZUb{=`0EreOI+;O*m#D zc!fOHY#7}|2rTH0YGOs_)ePliAAq*MUY+#}vS!Hup#8A*HE(GOU?muf$OOjtxKX(y z29_zgY86qjt7FBsQzdGn=xY=aW(@U$W&XO%gtJUo0BHr>QM!S|tuFDB1QM`>|zox7~iiBEbVG$*pI5h4zb5Lo`YD(PpWPlVpU!`v@k_%qgc? zf6{3IJ1Jr<1@qYUN_Cx{r6$5gis~VGx4nz_O$J)nL0EiCng6bqlMNyvXiKX9pqIfd zI?UE}srkMuyVQ0r!vEutM0%ESF_zirq@4DPH@oHuPp+ z_iL2#P>eY*{}-cbH;ct%v!mT#x1A0(NSP>{h%%8YJYPJ8Ja|hX@iHF)d9nV={gNF_8YK-Ir2mkz}S}5&1=pb#aqc*wHHazhl}TW@rMu z%wAb2pwLmI5)VIOCgU!zj#k>`2Z7m6hp*2Q`#isvdxG0jcvo|HG_GYgKfbMPtJJInjKSqtmjemc&VV9yh#3WPv26O@T*>! z0R1tXk!xxNvOG@uctkmVhx?#+-@o-};W*~xL-!mA!anc zMzB2ug1ji6mY71jvf+GugFcY=ZC^~1L9x)Awi=mmz_>X7AL8F}-E2n4e%+YnwobCfKe@JfFrEr5&5yY6AVJ5S`@%sZMiWeKoJVLdvLwK zX%MKrqvzB6ay-~JhwX`-UPt@DEE&wQzs1m<;6(r}9WmdP?R!HFO16ai><`?>vreQf z;hKDx_$ZeF&aMKOb}lc^?_qBrOgg1eVKK{(Lt93mSw3K}itUomJ-7oAt|ozXCX%O0 znvEIzR*ioGN%K;&KU6i!=!`PTz46_8JGy#$S^5|_b@VB{skCICtbEKeGkbl_^H}3F zbSgW}YKfx!n*5jz^5HuSvxxw-Itm23nRQ#`uX9t}d$Z643e?vIC$ z3xz12wE%cjFv%m$en$3P`xqWZWQ2Fq3e8V>uM@kjajhypSsa-COQI9k&5E)Nh2G&x zZLQ;9C4Y^wB&FGo4yYEK@*e@0QdYhuPFLUKshi$Se}kmVlg*N9JnPrgm5cr5t&uT! z1kQUv;PMVeBEu^NdK}ty_-y0@xtHsgU_Dt8*}dQ@x!S7~YOJW^(U#%oABo)zFwqE@ zjB}Xa%$pn1(8KC=uyLFxd1UToLUITgZYdQ+mQlDCLR^IMeQq!)?=Wuq5o3f)+!(;O z_K6Gs$8Tr{l!1GYkW66&uUTynKWv6FuDv7Rp5vhhhGq_202CdA8BXA7p0a&6#2sM) zPXd;#(5d+Qr=**+ABGFpu0dW+lKjMeOH5U_mn#V72dOEUOH;4VwEiS2@-25X@+gkQ z9SA~y4B4SyNL@4q)Ao@}h0i7UyjS2d8=@=tp2_kr36*vZj`IQ2e(%+PC*q9m1UH~S zu=Kf_GvmB{qrACylFGlw%zs2!2OnoKVw$#Xx6r4oI^s#S2Oji zWXF8TK`Tbqh2K=rm)jrWy(^@Ve-0-SOWMnSRzqVx<0Eh_5`%#g z@?GBM>xj0OTSyT5ty;%@XpK>`@4{9BZ(yivjxj|W|CvYBLn<(EezryuRz6u{z(6gn z(Zq(EAuQ6MfH_-`(_L5{l4nE*j@;6x8Gg+5*{;G3|3~EvffNJ{%|X^!``PC_&=x#+ z=T%mE`Th8mAVip4B8X;=0uzig`=8Y5O`TR6^#TF{0u_-dHiI@xmm>8(sv)jWIRN|?qLQAF=~XuC^m zpeVa!{CI~@`H_$AQ83mWFp<1Bw|x~$?)r)1BvBpzvs~;qz_3`%IWBNX@Qk5CZ3assO`2Y2z0MI!VVnrbS@2b93t)k0TlB0~jBjE`ikt1fRnHIN#0 zO*(I&qgpoed+P7rlpD~adStG!vDvoDRX5E*%}CZp3}9+Axg_c{xA3B+-9Va1`X!7OeiLP;qUZsW+n ztEr$IoZk+;E*@^#!>UzjmscEE>+hwcW8 zDt}g>Oe3u*-aivwAcJ`wIeXJB`EIV#rj~rD ztAZm=^ku98lTc>Ld1gMKDT0cQw8?-wYdqNwDN^@CBK{l&kJjP$olDoY!BLP9JAc0L z=KHt+=M~i*_@-e*X~Jm8@1c;BxtV}XhQyxiOB~5^b^~WwK zeyF@CP@Xta>q$Y8ZeJ_Cn0LtrqJUx-eeBz#ipnw~6qmGW?=P zFVoS}`AKlaCoqzOL2I69-fjJ>Ak*Z*455Qv$+E(&%kF{@`gzF#`8w~d>_>9P#$6Zd z?5a&0{i;HcQ!|VDscY|S8TDa=Nl!zlHi6FlUJqWb5vW6SZtnkYNlHe3KQsEfs_B$B0`*u?()qB$l;ngSjU zRb>|XU;B@&E8E^akNBUPzXYx8l|1^542J+5S%KK*+b~c68=0MAebV4P>$9zC#-U{@ z_+#pn#>{u;fWeX+hS_5f&aMF0=SI7NCifJqRyiNXI&Zt8aZX10d*i4Nb@;s`-$Dw=3X@ ziG*W3hP{rmBOuU3aIA?LHhNzCnRGmwnNwmZWz+UMVb)*JS3V2%xpOj@MC6tQ#RNXR z7L@dpPkUpGj17SDl*sbWgcsy%WvWp=+A`3E`>YV>(y>bF!lR5RazZpEYU_I?-GE4C zH&Qv?_p$s66OHPhL?wo$olNcN7y-7?HiQu)Y>osp1z=VOS(9}iZO3wO9bkhJvzj1C7t3IJ+xdym(OZIJ8SUoFO^bo;ca&c zc~VKYr90})V#F|1ucOW(e;|XN$?mTZ^!(IN0mR2RbtA62B*3SWf$>``Qupxr;UcMT z=O(ehv)?S!kvmSL796RAP)enmXgvD-NaR~4xE)VQNDGGRSq4e$Drs@=FnY-xg^&dH ziB1i7vU@TDd(PN7s$|==5L}x8q1;*sdFF@0G${$xUM3P$C!AKp1mJ5<_XdD7M)qZB zeOsNRY0=gV7HC6yGwsI)1HUo+to(P?{7%%AF{F>LV)W;fB5vjedoXQgl*mb2vjiyN zcAlM*1WiFKF8;bnQq&q=#`e)b9V*9&_2risP3v$EXd zWR0}^or3^9Dli$!(e*~Q@N9;Ugisp?1!bhU#UGONU~(O^z-1+unlE(KA#x-*4)H3i zit80D($nz-%@dzldj+waxLZ$OF~RabTeb4*3nTLTe2d9*y}6VLwX$yC&E(RgPJW^x zWKRU@02Bq(C3ncWUk_&5SQ~9{qv3;Je%d611gxW;lv+#*9Xj7R6?8%M>b_+G+@<~- zey1)XSN2icfO_+0j_!4Ji8^wP-4WKkmh6jZF$Z%-^a=;Zn?ZOs>{FtbU(NxWRX@Ewc|*=m#_&z2l-ZdDmk?) zybQ7&Mw48pB|l90vdp!gRVYOP+cz?mx?cJn*KvEmu?#nas($)KiSJVP5nUE>MAIGa z-HK^zNx&wkB94?GHWF$FIp1k)rjoDHman?$8Wd8+3z{U$Ans5ssyb=p#TAn1FE%px zdj<8!>%FJN!f2f<@p7g@+l1O_e-wWn5NK~`%FS!SDb4iQ;C2NheK088c1mBUjmQNv%CSUdx`tHfq?*oAP)YQhr${T~<f!Vp)Ivive5!w^> zj2$QzM2JY`tkD5K+-_uY3_oj@OI1cx8LpDcn$d2_T>C)l zecXn)jW>2Nd_C!LzeX;H+a&~Boffrm%SXs114WP!Q#VKUh!~V&g zA$_t{&~lM8i|^&9N-dYpwSzFOe68Ik{n6M?EtAkUZ_v{}d$hgVF<4TH9HU;}hb1P* zT10S<6&D^M^7(#HSePN2V|ruZJDA$&r}c6+j8fQgNz*#(0Gp2v=o2m5;E?G1ORZPi zJ-tjF0A6rYtSxOrg%uIUB0|}Q!!@<0HT<3*Zs~@a4GG?Y2Jt1k`;YDkJ-y>qvX5)I zuC=YBOV7ks$PUZcR81F48QALT`o3c2-|g;{%36__{vue}nIhcJIXpQHqnb5;4J^9N z>8R?7l8f4ND)8^$XS0Jb;Em`yl|QnTuM5&VfEtG?7kj-UG`sE~E*K)kF8bd$vRik( zr=8^*rRqV|iF10IDfl>|&pTLs6^DI6+NDHqpyRR(g!6rqY0g|f+E{ly*BZyNem$+G zP_Y+~iOS@hhxz{lg_e6o{1d311@R*3g7^=ifdc7%7ms^U1SJ%5gS$Qg`G1&RSW$T? z;7M`7n_6IteBcpT3V{R-j1p=ehXF?b3{=JiC$QgX>G4hERTRZ?^dIcT%2cjh;cjmfKlS0Ug*sxK$g>%bi|dP%9NY3ge62pq8exQDp94?_9_vN_Pzf zY@kG+)V7Pp;^jU=l}Xured~%!9BC^-KrT$LdnAyw-r0YEG0z7bK=xTQZS&-H5OB_` z9a9uabi&uo@|hzgj-nLF;j@vs@P;`y_YMtXeN+?YW%sl7M!E<>;wN_I*O07RA;~jJ zO~1V+J(K-UC(r_|uL1})ahXpPM;AM2_z*C6ia~`A-+!tPFI`d;IG4r;SZf{)fTPmk zX5ri7tH+t**m>}$G10S2f@pny{Q>uB?B19NUNMEaug)MhQY|U}q;LCR;Ey{mFg(40 zFN8G3)I~z9^MQR7{^mZTpDr3$jmR{nFii`>tLrul7XuyEY+iE;fpQSRk9JTie=UXp zuB=Nv*yKpZv`n8LWAUgsu;QDew)eS01bfZUYk4NSf8T|nF%BtTQb{y&7ty7Vs z8+U#5?f3C7P&TN^eG1;$m>!nTX&e`;q)q}}-jdu}+&<#^FoVEnn6SZWB6(Ndz(#Cc z0Zv*uB5s@N-A&K^scNwCh&wf>xDJV2kd2Hd6zuDxT`CW0C_e052&Tg z??06?j!C~F6nE804&dkiyzuQ>rG=#cdW@elhm|ntW9`+=tAI7k=D zrhO$LLb-Odt$`?*Gpa)&KPD|Ir8zAs#;rO00&No{xc?-LasS~ zK>hVEZ>qd9qn;Qi$f9DLz5kjH#y)iI${;kxQoQusej8z9j)V}2 zrRu}Pe7r=j#MZm&zIQ_$VX;Il8%JAEjf$r+=^%Em&5v6YtV5Q^LB+Cuy!$czj4e5%R(uqp7>OmUAx8I2f94kgXv?)&^vm0j%wefh}3?yq@% zKP9S>eS9ZV+hXV9?b>T&)A8Nz2~#7;1sX5Na4skau=7#sz7W;3!lH+e&XDX=I^(kr z$Gf)t1GUHkbLL5Ro(IKf)8hd>N&shN<@jIp=C3*7a=?kwb3x}tQ6-NDGGOoELa9h~ z#8XnFmjo^$iiXArC$nDc=ij-YkePIpf&_x!FUC|yOwrv#-JP!)JXSt)e#fK8Us0@G zKDl|>E$>b1hb3`rZ*$`*1S?7#dTTUU>oB!<`YB}+oMSC4DOyBi+~Bj%!mMc%xY`e zyX#0@{3tZ~g6qR|-$rM(Xa^}RFsqA*QZGHNlTVhmK06baDl)Fizxrm!fm4rS62Xz% z6M|;Fo3c5F)?GtBx)Wa7va|iBR>Ot{P8Q&!*R}{p!E6dnuj{rbYv7s8OPVkgI~dy9 zh8wk44u0^H7R&1^3eF#Mi4_kd^b+Iityl0Q+vC&h<=Y)Nx%N@m>Jh#D&P8I+Mv7T{ z)Zkg~Ev^d~JMds1qBAtcvGMTr6P79zWR3e-YYdjNl*RAIw+6?gyx6wI{`gb@u#yMB zpTK2EsXZAeJe>Klv%9VimaPhlq(bRA;Ij?g8lEuOtwSm+Fj6o&kveyB6xW;yo*{p= z=AVu?5YOO1niQqtS65> zC>%51;pKdIRWw9A47(nxJmAOyHjY#zT`HWD9~LytU73iaeJm>{_B*uravSKxlAo*C?yHVzPBIWtZ7!Lmhhw$4fLYZV}UszmP?^QNIs`=|2 zSkwGtm7aXyJ2$p@hK+Z7dWs(I_W&{iPv9+oOwV*&jwg2AV7w>;zwc=@A;S)%P{;0d z70ldK)bs}h-9|g|tRxgf^}>7t!)r{2jAg0utoUPV2^R!swEXp;Rb_#P#sD(0Bh;ZOih2_O<#-LnK^=K$Zn;3e=X zO^o6qo z8(h>WjQrml7;+=i{{dA+1ACJJ78AFg&jH*G12s4{lOd!if9+e}lbbjaexJXBm#xLO zV~u_zE_Dyd?k2UHWG|PQw_IwAv9X851_y8^zQ6ujNMJL;Hd@B1Og0ZLK!{eW`|D5L zGGK4+Vei=)w#N@=1diAvo>WK?>Pf;;7zW;CdG_Wl_NH*}cMl^LD(|-Hxr84>Oa=E-x#0(mlCN;#1Jb~cEkix=zdTF z0e!=8zZT9ih-YNH_v*9fXHTxqE}k;x!Hg8R=W6DO5D6ZDc!4-p-qqB5@Ei|if9nlz5Zo-wB=wF$hyNHS-OCDi1Mcu1fK1Y zN^pQgf2iuG9#wjFT03AU#AKMgon^RLJWvP|VrIgQ<40mdF&#D|XBloYk{mHmwVDzC zo39`5FnbBK#Pk ziH7ou&GI^1>|w@+!TyT{HhRJMFmomC?Aq7Qf5AQek9T~2^np*V541;shI0Z6l1Ckr zgb0%5VNv5O!!2qkLzGBk?%;U3VK*lR&B$4X zf7^^O9EsgOQD1%j`}lN){3=iGq^Mmk<+kP=;!<}RPA=u4099>S9QLR7$^b9pDD5B` z!B7zPC#+Xl5qI$(1p|aFz5*Ydk1G4O&bCb9ghDVZ7wY6F{2VIxxmQ)5N^+Jb^CUeE zaa-gMg1EDco)8ZZ77~_Nit3`B;DZo{e`h&wLHv&_DdH}S!_skl`)8ZRq*~6)Y#J|) z1`O&DCJ<|o`b!ecvoz`w#2Lb@x1h^pzKn`qnZg@z$D=ynwrAw+;Z>U34U<9WaF*eQ z4p5cT8XiOb6lj6xhX=SjJx%g>QZ6i0ks=Ce}wiY zt9{$l?M3t$BUo@9s@Uqf;eeD^nmElq_rA4VNrVICAhUbNYB!BIKgz*}a+Y=-c77~p zIlMNs=v*`85tg*&^&nh2%W%UbCkRt+ad~_*pWE7J(3G5IxJ`)$h*4Xf5&qQ^{|T#^ zY?>|OGT$6`t1SQrxz$;Qn_Kmxe>AXe75y1>*9Zs6;T{VbdaR)7assm@+Yl$X%W!f6 z3qurATU8S2?u32R8o-)BRBul_{H&Wcxi;;cbu&}&48n)22se1Z^4}ym!NW{)p2X#C z9H)oVoDdXa_mbv_{<%r_e^q@_CE14yTVOw)bRCOm2~5Epk|k#AwL$21f0p3}?|>q~ z?28XXeaH6>zUe*Sn|;&xwiVzYd^^ic;bPSOWQ)|V7;X7luKk=E*&Y7s4Y>40K#2{8z3+T zOWD8MDSN1SWVM{U){JkGN&3s)7oUSKvLh@Hzn|o`sr))CJNJ4Be-dG6@y=A1c&&GMR2u-(Js~7n}qim zNp{a-P$)UeaEqltee5gl%tMa~4q;(I@FFQny-_iy0{aC2b2MfI`@epg z#QCZ;t+PB^nzLn8E~4v;d09luKjRS*{-k+y( z4Fw<=bQyD5=`!XRg@Ju>NFWLs69%CDdu9fFKBB_cpGZ|#`g7Il)7q)IJ%Mt~+)j%60dv&f8y4mkA4_c>O#GWT zx7}~8{E7KWf6RzT%W8;uoSU2PM_|&bX=A19PqV7NWv$>UE9!B~H1*hUwv6)k)kO8w zEF)J_TNlP{$_O!WNq0=aH1c(Drf6-QYKl7M&KCi|CX8oo?Tr&etB-r zs~M~66{mFa9aWT4g@kHee~L9ex0;Gw{9>dU`rC9&1uFlB z?90t6t~3t(+nZ!^V-!fNPVd%5m6dydc7-VBZQDlRX38rW(|BetvJTY+K>=%YDw6-j zf0m765|FJ6Pd!5vP!3@#>+e5kmnUGY7NF6#7q~$%YEZ0oXak8+=1((oC(TN8aubcH zb_3Bif2~jOi#L6tyO!KXL{I=$u#Z?%x;hqfw1fo zjDb>jqY;J;HLYmuhW^XPBSMIO_2Ti9b92WKMz}A&2!*9TZ1Stiy@NBv1=$Ut_P{^? z^pi%1c?Yq&a}zIC=H4b-o2G^c;asOEizpuv1ze~X`&!R;i){{R|gc)jH6#$`S)hX#>?f0GE+%F0y58 zTk`9q%%gl`@R=E47jdbhLn!}h1XP!qf4+@h^mFyWU_iCFm>~WcP^<3NLa;z}aWAar zI~X%2)5<203~bE#ZrtqZF}aCy2;2C;ry!6agg}q-U|B>2ls4O3s!o6e&~Q-cs3=m9 zfvNxz65i$E0J>pfc$h;rHHOahN5PRvI~X;`ieTU%{3D9fIDIy`?_xIud0m*yDX_EmK6PE($0Tlu= zFq2W#DSveqYj4{&@OyrRzEuVyh7VDe@}WSAHAS}s*ifUuunq++v9=IBJc+L3{rVkw zC&Bg{7%=aS$9q4-qfNx4PdA*-538HIN2Q{I6`9PU)sJW?qfDf%D3;NxivEgCS1l4* zXaM|~#dYWGLg;v72fV1eDiB`TB1zLM{&OJ&kAM3;-j?`I$NSMDur>%~F-JmAg2e42 zQG7Y$^9wVqYd4tTI9X8Dr5*1<9p`cFkg4kJi1%Gjq}DhGR%#uSX`jg!x3!DESHD6C z67Or8qOWCNd5xOKX5D+2e)>Oqi?oA1KhZn@-o3s<;770=fL%Y@k)B}yJ=+4p(p<7O zaDU&L;bmmOA~NU9tku>l${k-d!+b^V!4;_)|e5^P7f%FNVKAGj@u;+5K5bs)Y%{Q>5 zsvB>@GL6k{X9n9j#N5`*kk_%)6s(1ahkq9@^6pWHlhPF_XDTZot3h;wEXyck#Zu*- zLwX1dU}-`61u~tt0FzuqCrpRhZOM{@k7|!dYt0Dmw_x#zl$y@94TXm`_oZok(x3)a zF0lrI=lKEpM8vD7hYv_NSPGNoOsDFiG(#Kta%#pNA#6I+)*aO$hDnF4?@fbnw|{T# zP?r<>)2Goi`~R0`)noPnoHRgc<VNm$0ITVW zH&QYMbAq^9>$W|K4`b|2@j7Fv$Ap5T}v`DVnkF~dUS zkR{^YcZb?G)p4?B-tDxH_hQ)KOIC4{GvP8PXl6fwC?6*G+vCIo~#8hgv%1c z0mvtF4MVO^)2d;bi+S4r=0}x1UdfFpn1Zhv;&aCxiJd%wJzlX{fe@_liS$X8OJ6$B z2ud=}DFje+3uqANq6d8cq_Gm7= zTOOY)Wk7sdH{P{Cz!9wAvkJbJ_Ku`*jzIVXLNMgo^C`OPNu=L1sEWRU{0CrGgktsl zyP>c4rLB<54+DR0TsJb8W=IzLGMe`LiH+mk?;zF;U!ESGDI?#*ClG6|E~n{)a^cYT z1tdL(UL;Gl99!|GSS$t^k|KG? zbIx~elCd}Uuy=lfUHkR*$>|vjJi-y79{XK7AOCLe+~I&&9ost?NGO@F;5{SsBoNdtdPKtv$J%*Dh(^d zC;a_n$_Vj4pMpl+cu6CNf}jk z5S3+=&l}3=g!t~v$SqFGI7{BSd)!n>`IzQ&Em+_dctt7*EC=-++=VgjOWiR4aY6z= zDeE*&Dmzi!+L=giKRuIOafFCb1tbkAitP%*J4*;fp<>OFA2FueWC%uqd>bk~?Gc8k z6wQ)&b>n|nkCVJkN-a&pXIZTBnVoUcVSZ7j^E5}3X&{Jy-N?-9#I8u4xXL7-t%(^u zYOzlV17Qi`q%YhZimWIn6#LV-m>G4dz>l7c4k}O|!veSs@b~9m+qqj*m2MEtA+-ml^8YcH4g_E1H!pjb%}#b*jl&P}rxRr_obd zfh0H&{0~`G456yJE6nk^MRQa-bGNji!#>(JDNDl^hUCH4bZy3x=c!JPP2 z_ciL(&y3A#>UZw)Nj~8iP*E27)Zr0Jgax$Vs5!TnU4S826kE?^FkX~pQZ0*oX0W6m zJ*L$v%G|;v(*DeWKh13$HG8wHL7j6YR$zZ!yQQ3Ty~rvD4YSY(Bhn2R#kPzN@S zZb!O^=GIz*z^@W#n~iJMec(}BF7?03E%Q_cNGQ_h{`~st!=<)4ZTCh^*qJpvnH70r zd#lO{0=kJ-%TpBB*|S}3Q&lK^qQi4&^&7Z z#;SC&Y$$e40~k%KWfG^_|HZA@_4F52z_e3ipgMq<#DM`&QZdY|Hev_CkROYdv*+7rD#EQKm0cC+=J; zOt_cNECVHf2zj&S$t}R1Kq>@Q3=N?;+y`;xd|*0AhLOl65rgLrDw_b2apkTf=YBLPPtQ?EmOk3$9K zb&%A5phvHY8%_GT~#5fw4; zs9(&=1^j`>mZ6tDL5* z2=*cfM9`LVuRHu+R|;Ht62J|i%GRMgXzS3wj36{}`JqIo0%QNfZ1z^9Z4y_#8F`zq zy#?tg%ifA~C;U{KFRQk#12BW>amF#0#5mg^Iv;nhO?vD=B)~htpBHJ9gR!oOFpB8f z|NqTJlpY<3C!$B@vX~{=0Ih(bP_?vw&;YFftt*Lds-iB7Wf~7q;u4(P!IZAj`63#i z0>N9VZfwK!-2f>{P|(&J9kBdU^SX;R0r9FZ>;}%Sc7`s<`XSCAhpO>3#=!~$To|$3 zupX|4=$QJlBMsKgLjQE9Z%9lV&fdk$uG93~$z%S?k)R;7}X~F?FgK9E=B<;;I zeI=$}+YrX}OISUc+orb7-NtqM)LLPH27}GLz1{O(}QcMndLG*>SiTO=A>p zh?J0SI)B8+;)Vr?@K@uewZ4ZPxDo$nuvt6m-}Vql_u%gLrpO=0U5Jqadp-(xqiKx8 zT?mylbLCC&5>$c!3c}XE-|vTi%AOGT?VIc7w|!T5*hk@oP!xoSQgNJWN7ERmS^+gL z6V1oSgH?OJM=JZ$h-fw&0*6kw)Ck)>Px7QpoZUF^K9tc%P3a6z0_(B)6f88jq_HK9@yP7C9Kp2zn>F)wTtf7n zg2#or!o6Fgo5=nHxAyvVm$5bi6NgAL1Gh*r1c<}|G?TGIEPq>%+qe~epI@Q3+Sr)k zRiw7*0^3EB&1Snuo9VtxgFvx4Vp^STEMekB8*s~q7Sy`8h#8hC8JgJ z^5U;;gqScuP=AOhaSFkW$9E7UJ!^DAP^>zJ^O%_j0~WyJ7%2-egbS9Bm>>$>Pa+Ul zZ;~8eMKA`59LBq-xqE)`=gW(SPZ*1UA_d~PypBYI1eX9W5XUOITtrtBGJSRV%T_JA zZ~#O^3MFyO4G7GuKwj7l&!#gX)Fd~TWKy@l9zGFxZ+{@gh+xtTEcGhOby{Yh^|QRz z<@`1Ksu}kWEU@d;0vBl4&1OZ zw$q?^j0EPx3@R8S%%B9eagDVD(N7VhNMSLIqJLnFFp5}=5+WQ$@qfRI__ZiDquIcF zU51|YJn8^29mE!5>kJM_+?xjV zu%OMnnV+2ve69G&0DRA=Deb_;$Vt-x0J%lPhE=CKduhV&5l%wq<*TraYkWS~z zv9MQZzF4Q_yL;He`>oCw69!pbFvgiyClMAgY#|gi#Q}m(mgxjoKfhCWdSbQkX_;=8 z&aK|q+m0=UB}mC_rRaE-i2H)YAg%>tgmDd)%4x&4;8H1UlWMo!hK3L_poq60L4UkG zH-f-NA_$did%peB7$V+<5LsS##Src7d_WXIzdVR|`xSx+?#l#&)HoO;OpOIclKM&p zIazjQF#?-v=s#xTZ6)cGUF!D6Lp6#KxQas^?`E;DTMS}xFh&@QIYF3m&ti6p#atpv zw;{<>o$E52zbK2hdTw?b=V-ea27j@P+;R0$Usmw~f_K&vyg%qO-xtPwS+Du_;{24Z z*z1?H3rM1PmvQ`XTnT(OH%JMBF~XF9O2nv7I0--H;bBCgSb&HB+~caQddBzVORuha zv%x-Z`KnV3z|6P)Brmc`_xh6uJ*2$+w0={pdUbN^QXsg4JRTIlOS1j{xqm5P{ox>t z>>cnibU=HCBUBm!R7i$cpu{N$)eZzspZ7AK(hs3L93zNwmLw>lzUn~Ylfic@0s8lGs$EJoi0Dv=Fq&12 zwo#w#&0?8Pb_Nj?j1fkWq<=^-e`-(E=*6R!CVZ2{qck7+sCq2;n_FFdi#4wiPnG7k z<=7{G{Z7KCl7pN?Fh-b@5U^C%_`T%(TG#LC3Y2cTuicNUI$Ni8SIkO?LQI@d=VCTB z9G1O?V}!Ac3kZXJ_DTcFgZ*q$7#5|@Efr*WrOW#4(Ek5P!jUAQMSmda&C9$PUw`Z^ z9S%-2dm>4nK@YN(V2m(ZVFYpJlYC10J*JPj2ayzv5k?Y`NHU)mQ2M_TR{edm@IL8Y z-jeu=*dMZb`3(jrx&CmUhoD{7Mtz<)#M;6!!mJH*gqc6mrz~Kz?SA9C{U$}<4tu*b zilIB~iNk^O>%yS{#DD4SgSw1&knlqxf@Dt8_rKBnu>kmpT_1>joWl(zJJ_!?3&Sh(|)ftnnBJY zVE!3pDDm};OK{W{u+-}`%NM$Ie~W8(t()ibV&U(y)#|pYOE9F$HKe}lr%g78T-|lD zpOBclRZ(odKUfGw92PL66xPukXQ6|zbSA(f|5R#Yu&`n|xt;<$yoZJcWfN@sB-c|a zCLdhuTBp@5P=5nSY=wY_SWJG_rG5ZUxk<}>cHS1Td8G*8 z81Q(RPJbzesR2ow7Cw2Sb?%g_p;!QPCzi)wNE z$-FvCwx`Z8!c>Wj1Y`mZs_EKX7e%gJH*3t$(tj8;+)`|m$qoIjsC~x|ev-7RZkx5F zUDVtZg}1Yvav5*iL=NuJ*6&%-875{c$3)xQyojP&4xb>Y;ybzURradGZn!yw7st$o zfHz5`Xqye|G@B<`4m$a18ViV$W{f&kFsvr?t&3}|Q%a;1-46zl3+9^lUOH9_z68f? z7k`bpd6t=xznQ8|-x>F0L}dRi{SsPE%QQG8hMO((&7X$(l|^Rzz2?@>J42fhh-U1z zvM2(z^!$?EEXM%r6Peyp%rGMhO!g9 zjR_)RkF|DT-nTDwm6dvNM?C~bBB6G>R}RgmMF(*p1bP1fsF-QUm$5bi6NP03g=GeX zWe0_22!&+{g=Gr0WeeX*0ya38@jnU`1u-%;Gc%I`yC{EnRaBhamMsJc?i#FccXtTx z1a~i-0t$C`4H7K41r4qtxVyVcaCg1@|LN1G$GQE~-49jc+iUJMm&~qGV!g1$YNI5hy9ez(8YXD|?W*u``el zpb0bshy#C30c>mlR$g9S1WJIIy@LnX%EHnaK%=grNlQ=9@Gr|>TL2~=|3uzBovbWC z0IK%~SD>xEgB=j${7&&dc2ord0nU~{fVq_|5FnGK?-EMCGcR~(e`}ZAo@7Oz;vb~eD zlPTEB!5Q!#Raso}A9*@k8aw|L+sW!32H2aw?=-VFb@{8Lzp;0kchuR~3giTE2D&@{ z70Z7F2r#p9au*O_g~%lSDk?W zQoXT*gRRHk-u8d*`p+D!oSlHS=1d5zZ0|8mo!?_ySb-3j{~8tZ_o3;Q%kzo+A12`y$`@YE*Zf4En^Rm2mE!<*cyWYf88~XF2MiK&DhS$ z*5ki%{P&HTz<(tBAAJ7~%QzdqH$@a=@h%J_D;pEbKg?E6l2-0OGi57hQ%iukvF(3* z&;GWngUoxr9FCw4HhAt5koj-1NJF z%m&5CX-AsTUS~7%>(Dw}EE>C;BVSYuik@MK##-6IaA$Y4{^YKC{#X>Z4k*5+DK&A} zztHL+FskwokEjy&?{2Ak2K)PZ+b>``cL?aS;@~Oyjd6XG4@r}pJ&eHDwWhBykFMNq zoBUsb(8{5hj*^<9eFmIK&a{7fMeDtwMf<`7x$_#V@hHbY2p1g>i6i~h zZ9c3?y}MQZ75~+q0M3vrWl79Qx^N+(ZZmAOC-IjY=2SCj4bU z9dZ4~tB(M>DfKPap7f$IXuJzP*w8`hh8B2qhkyDZ-g%zq>%4HR4m~ z#*TR5+7GKg_-?JIYm$Gfqe#?}p=sK6Bk1?HzGZudPa_7;=ZYzJkj>1Pk!mfYd@f{JV zobEedATaWqXU+wd22~gGaV!A2wY>awroV&Hu1s!>B*i3~-Wz8eT6JNwsAn!#s^;k@ zzNzWT+0<3d7ntgS4lhPd@Qc<`b%RD16O*nnS|ARSr?fOOs=+M6afXlwX<*c))$t&F zJ_m7vIEZ&=E(U+c?h8Z+&l_es7e}j_NqRBTv0S>uC-l3BRhVD!5~9N%Y$!s&D%HHh zX3_oU4%mIxYCz7Hud}$@Uk{l2RNOUep(j%tCp5(--F_3add1DNA(Um>^MyMXCD_w{ zMm^9hhcuJY5#fzQquu=3)I^s$(06DRFLFKBT5KR$GE9F(V?t=YgmjQ`wV9b|G{*?D z2%p6D)~= z**!on&0h{bMH3A4Xm20V^9_vJvk2x#bo8ygH~Fgj3|o74BOyl;^m!a~Q#OtTg?H`++V2wN0>V|=PkDbk zOL@J7aB?_rVh8&nOCVPM&iYLW0cS}ARj4L8`Gpo=Q*F<1Am`Gazc(?&`)V|QujnUq zeEnMR<;A&{_nNU-v<%q*{VjGUfF1VUVE;zrRCeTo?OeytJ!HH)l5&}X^RUf%B(J%> zn*6Mxhq6IFQ3jKX9HWuf*R1U4QvH85y)Tk+16G3qHjQUr0L}2S7}@BLeWT{KU$e+3 zR0SbpTb*x8SzoYi4hU5=oW+h#Ij;&BPdACAEEoGJ5O}rBc^5W&EH{nKnk=kY4ZE98 zj8NeU;UQT1{Kw$S5sssbr@M{y zc~fQ3OeFOrsf}L4zL2Rxm~zbJMJYoK{PVQtPSRB-1h^!cWq3s8-X&`W^6p9AKa8lp z%jiY5?3-2S_v^RH^8(nvCm(;8sjN z?~kQQc=(<5a)m?L-(!phJ)69k+p!Kg>%d6$!-+qO8ENKclW}JP9d2(>ayh?q=wKvL zx46wR#qZ3UQ0Aodk1>KtZqt}N=ZZT0wPKlVLt!ISCg0o}OEpy4FEM{GBWxZu@1XMK z{q3*@M25?UT0W4;C-|@x2W`O;zcxnPV@zlm%Jqv>UV>i5eHl!u?5sTfOQ1$X6D*B# z^5W{s)X6Jwhnu^Vj{EjB(#?hkkzwd-)<1BNHez)s`5@GcsO@@ySb+YKAWpQ+}sM#KC$nbB)u9 z8&zxh#j4-1MHcXU;#)#+wY94$V#T`_;qYaB zzyP>~x1Z3h{9I9g3u2e6Bl4zpz6pOtI-cLa(N3N$rs7cT zmHx`)J!^FUp4~rxNEQm_*9uTL>Zj|lYb7VE4vJHL%HaPH(*H=`TS)cztsqT#dhpGl z56%MvuTQ43Z$#SbWH5$q--i1kq{id%0YWS>X{$KOmcYvIt=&C?*hH&(Olqc)IJZFc zGIzSwCasGIsUd%@R^o}x^+g!bMTgr^FH;F>f@kTOG5mAU&NsSp56 zB;|H2{e%d`@O$_D*U(){ftAHX`(}qe6Ue`gmcok?6nbCy4!QiGVQgJ9t`+p0HFqM<4o*t)+;w^c}^|a>;I-+M<}- zV*aLu=}W@uC^ePLh$moz^p-IelV@)ux9ENcMutTOa9Rdf?w{dfOYs> zS)4j07;E2@m6EFSCyQ7zdPQ4Ay!WONNAEze@fVuKsd2F+dgz~TEi?LOjf_dGwq!xp z7F>U1Je*Xdg$DXe1Sd_g%Kk!RlxQp)CckzQ!sn#Sg8YU!o57{(5a}1w3#rb@6v4Qy z^%&h2!6<(GEqIuGth|J1rQ5UFYh&0lew0FEnnGon{j7+J9==yHIY+LGDhi1b`(&V? zX&?O=ePfsh)!~D=qZYdOOYE91K?aL;eAdO3s7r-M7fHAYn6<$%7X!;YF9bg z=g2>JB}q>!|LnR8(pK17PBva&2)J_)*eb0}xH)mR?QIzrk)S`F8k_ib;jVSPY@2^k ze+hTylT<<=MDmRXSkd*lsf69{;o+`|^u(~R>x>V$&7igAKAX~(;}k92YcIDOS8#VmfpgnG(c^I%FB`cBKiYFoXit!% zXm?MVh4mr!YR5uA7}~mx8RQ|rdUSs?kOthQot0ohr32f@2pEz>2kcOAPDS@B-)BM% z8VdAzP-u53i$j*@a^uN$A@e-v?JACk7fKxSCRU?Gv_W_|xt=U))!3db?h;TkKv4De ztg{{Q(I>RWZr*}Um}=^ ziLdKojP3n0e)qW|&9?zKs99P{Iffz>IAW$_TH35aZvp0}{kW>uBcgDQgDU+&Sn_HB zkzNj6@#k+70aTBm>oUFmIe3M6bdN!94aM>?*D$PkF~rS4z4(QgYZP$Nw?rIrli)(f z!hBeP(#%DMcqv_QYPN}#v_$9=%<^PGn=MB;h|{z+fzPVV&RAEeaj5!=yn4{-x^67! zWcYZA%Fu7mak`(fSb?;zvgZABmHR1kpa;EqBw(ty5j8DJnO?Qno0&3g} z`R{<2$FkJ61qFSa^lW`ka@O0~HwtNnpXOE5@oZnvN8)iQK5zQ()UY`F4hHkmPC}*9 zCdPi%tpODFsUBsoU8=^j$BxK+hZf?nR%kJAJUL){TcV0@N|AqRXfHm5@zJur`5}s+ z_Dt7p&WDTsZTm9?oDpGyjh3r!XzE*Q>wPH#i+pgy+zqsWG$g*1sfnZ++MogtH?h6} zb9CX>#M9aO+eUYE1eKX_EA1CEWar(~udA&RR3Dfi>ct}aEXWJ!Oc6aMUjOnO$cKrzW+$21vJQWohx979-9x@lgDS|;SkeF;OrgtCJ7{Q-fn z?9`Jl@SgRuLR;)3Xl0iO~YgUKH0Cb#aa@5uz#0B+nvdnY)g=Ar$C02!t7$qh{z z)jswj;kcKrr})S!QzDJ40j`KOTQ&_;i|$4M4nQn-Ms z6fnG|Pm(j8>+CkHTobX?2a<;BQ)q+VvYZ>gS9$F$@j0mtQ-4ipo$0T+2=A;j?Iuk_ zI4JMHE$0u%p{BelE=18uLp56CLwXh`b1Dd=o+NKWtN{B);wSk0Y_hDYwrNv&Z<4H& ze20G=?p_0zjD-dy#%x*fX2!Lr9KEpoqg2T^?qq47>h-p+qqqAT$4xay@~Vr-rb*m| zxAk>SismFw5P?xdOr5_=apM%1VWbr^=+FP5IR@F>gcb5Wch4*cKNt}?p1%YSIa<=E@7?&?!Zp#nS0T(GgZ58B3S($ zTZkv5wA_s?yKxrDEDe64gIV2?6Gr}}bj~A!%HNK550XvLh_(faulcrQgx{whhv6bs zi?7ua0|IBc=$vicE36`kU$=|ni>Brje@O z1{5FW_$v!1e|jjv@Z3&oVh(!-(V1%&vDV2#nEmu*LNGtmy|y&o zf5b1*jZ~kWaYcTMng4K7A@(JXvQUc6*G6Qz#L=zUJ3UU;ZLxC&X7z%s9o<57AgP_B z07kf&P`U!bN-*n%$=nKwxSaYN`2&CWo>%n@TR8X@F;;kc8dhQ=boVyrE;$#K(OZsB zfL=hrQBXkejr9$$FMyZGP3mO!+6H6<9_{ zccpPiSzLpD%cTD;L#Dzr1!I+c0TyAvbFV)dHlXY1xK!K*xj5WdtP!mChg5%g%vp2V zRcPGYn0L?iZpy8!u=G&9)B_@%{*MUpqI-pW)~92qtMsI^Y^vqyo71$QI<`|A(BWCD zg}~6pW*NK(q8Fu7t~R^=bH$H%WlGo&$?-Qh} zp;=$*u4X{~XUMcUXN+*Ad2f*AZ8Lli^%v^)yJa4X|NYe*2etuO@Zf~SbtOc>* z*21t!x4aoftSzY~m6UY(8%nOS-aLqL0%5KY$73}S#X2+bV3Q;{zrp|Mx96+MjBFE4 zNerHyJN{8t2zxz@#UUbi1Em#wuKX>FAFX?LI^$k+wUXfB4`ZDW&*FbGI$F8h6X$It zkvv?lSZsx-f|cs!DO2(TL|rEh?m_bIhMiM<_?5F^t=qjOO7Zcq=5Fg=&{;xerwxgVg` z!I7Q>j)_7+X7i|*%EWjUH-!a8@Of6^@~Uc9ZzEU?D*Tv=Wj1ZJjc&^SZHF%CH^S9u z#BoSdZS}DC>pPxS3w%D3ClS|^xyu|~)#1+C!P)jl{{ogvlKrKWSzS?LI+@yWW2ui# zpQbr%bXm*?r`>-(s&r0;nlX*{x*FAo?XT`|zS3fwsjQm~8D+)|!2MB;4IC1V!{J~i zVJQSnd})XmNA)77!v^`6xw;7Kp{R@<6Lfg&bFUM*I3Vm+MBsCSpdhm4tef?D@^?`@ zzRsMsRA^Nt+1l19P<<*dyvC=U*XJjO*pAd!=NT?9dwYMqLe(PCONAM$v)LquN&gKU zA1azDzf%e`Dcb?H+73@EQ6!^xH5%%D=^042kSQuuH0w!?H2upSsvDEzd3r0SDHIC< zk&DE06D~*P3iiA$xCVh^A5tjOFCGq|8lyF5AW%@7UO)T?c9Kil)V6EHXt^X4p8oS= zyy@t6yy<_589#21nW2m;_&(cdlZi`8u?HsV42C>vQk>>j_@HFuc!Yp^OKxgsTVPk_ zaCkOKvcq1Z6&6qJoT!G6ZR{&=s&#t(_rMyysc9phVYBk5T}-<&3QkL99H}^^icg{a z<8D(6;%s0Gh?`^!{cxVi(e`J}YCq%NW2mW#szrZmI5F|-sp)+fCyhYSOiSLk0WjT5 zdR$+oW`ed6)y4q3xX&+sezdwZmxEf+{f~%&1cM=t0alTW#c?%xdWq-NBx05DW<2l% z;nDMzb8vZVP%5b2+KgmOp*D2WhK=qgbac&qiy7ZGOl?pUOWTwM;n#+`s^?!;z& zEGB=bgTe*ZBpRrTngYl#y4qC5rNM;#tq_CW6%59bHAYlrKO#)Hpd*N~MRY3;+ zxlh3cL3S1d97w!GL<*i6_5`Uf4%F+MpjW=!y?!PV_QLNVpAERI&W8L$P<|ezI=YWHNe4G#i>fs~RvCZN zegXohCZd=@$uS=@DpW<4SqTPQjyUv(dx?MnehfwEEaH-VvktgX|y~@cGam1TT zD}%V{t9RJfq0>H!^%fM{OcQ<4c^Fr8rPZD36lD;NAgU{uGDRk7R2RWThnao&Hh^06 zbO+3VBZ&WGEk*nX(2DY80_;oW6Bh%!O)bj0@wFP#7OX#;b$9wHEBA1_mpp&B4AaI# zIRH&SvcDZj=7uRl+3LDi?K-s5oG_?qRW4{6lFO@-EHL#^4RQg}nY#Lnu~krXvrK;} zP>o4L;PKOu1!QBSqcMh9Wr3B}nEjKX>-?AwF3Lj!u>NH)}|l$*>M-%MxZe}pIIpnYCm?sQomRCEh@ z+#4Qh59afBJlR!eKatxHAy9`AY3d7|4x2-!6G+?@|77L4qF3QrVkS)Kad1ZT^#&~_ zxqN+rCHa;n>}wUVao#G;Nv@oK;l;^N3#F#0R>hyUqstL@8EWfKrH0t4$DZk$d>$jy z6ZA9sD0ZB#BZ{HtuTJDh5%AU8-oX?J8H9%Tl9C^jH|lA1gY?@kmbt=lLeQ1cHd*5b zDg4Enr*i$xv)@4&9^bWzyuB5(u#Uly$b&f>F@^?} zWjj}q@TQ+Z^Z0HI8300=MopHJn5MXK)Ok1$?0$dpz`nsaXKy8zT#4yrcvmCOgCO`3V znSdC6toibY6HyD15D?*R+y}v2%uEf=$`Op_{>o$C&)`9H9cfZfnf1lo_A3sg(1I!F zY?GBrruOfVV=8xll}`Bq+j;Mc%9EDWp;`apy{z5FONuShK^s(mz6b!Q9U?0tyqW=38`jwlV_8-L?ceYo3$?{A6sCtn}B zufAh&A1#lZYzv})j80t!h_`{hmFe{xZk>`Hbw!Y9adw#Ds!WTTmAJ9qWEh=rMn6a4 zG|OtnDCj1CSyvO<^)r-8oyTD$c!R+i2@Yxgl~b%eBJ7=+E6Ds5-ke)cd0^W*CL2p57L%aV z{5O+mGp@=c{N~Mm@asyt7!x-C z%m@>rrXP9Ac9NQGQs1#?l3kzX)8f>pSHGu|2VM3y4dxjE$-^GePK`+uQkQtS2KTo`GZB5qrw1Shy##Z%-RIxPs;Q?(tUwD?LZG`Mf zzxd?+rAoJ2zHKoMlI9t`R8CoHGX_ctJA&AHJ?$dPvEik-L8uj4+|4G8cS*>ds}0pH~r;l&T~POK$eI@ka%z%$p>;nWALCtqOIs<>DFNj?pl?I8O5DFC~PjvXH8+Da@tk=#0;)~ ze6DYn15D5DOoVpuyyoL22$V1}ohe8beTtw>MrP#nwfVr9;(m(*#hK2LQS%k1~ICpJGY2lF%Jvf%I0ZPNt{0%k62aP zEIRB|Q?Yabu~?PIBW4>!5;t$82+C>}ijJLr*Exw()L89(EmU*KZ=O3bZpA z)T(Zq!R0GDmg^l?a`E5Rt>UA9$9*5jG#}LS(Hj#o6wA72G8FUv!p^S1j6Gt5i|5T6T;6 zB6Gx8DkqSj4u+EY&rwJlbe4;Q;ERsDcz1O3m+mQ(U zNv;R~kt&;pg5V3){9k{OL7(P-^mYGIu`vY|OFAo?KZiwgaY6{M-(N-NH*T$1*8n}d zj4|oP8)6>A+el%PS`z&_q$QyZ42H3Az?Gl7imyeMRY9tyJ>3Nl@q6`=kIKpwhoO;^ z0It!HiG0jJ{dFquNo|T>r_3s6;$NI;ExhAv@D6?$%dkv-&1k%qRNQ8N6}D5stCWTd z2cTv?M`qy?1&Om`ChwSJ40{QT5}j!$qRBn?HtW=@WbcXvo~f35~cB z6i1In);7MPrs+Wt8R8>cvkWVikLKSj6h@*X*f^x~<3)UnMOs6EgUDn!YKsNI6`3*& zcd6e%Yal9ZeDJ_?0(47%=dG*qohiktm*y|eNd&2!pSVjp7===Px+-W1@8@z!Op`1_{iyerGKtWCJxiGVVF-gIU%r@x zUN!@0{jK<{^@DH`Jo+H%Fiu6&=Er>#emF)h#bQ`E7LxTn4~6kB?Y`Lf`(Gnwi!*}V zj9$1}0{e!}ET7NW?z(ZlMn-TNh)5XV2`{#C;-M@cEpiu{m*>15{+R^%I4oy(0S&v5 zZt;0W1_>d}!O-!4xfI1eTZ6Uq8B&zH=r&-->YWLeH# z?<0;7dBP!VB3LF=OHW7{iof4xuz<9+RTGtN$9r>;-hAxQZg5%?zTk-L{zhM?s{gOvV4Gu%g%)a zQW7UwS`&phZ~79L8^-G9&MwJmlQUW#r9<(j)o2k)L8 zN@c1LM<<=>mu$qj$s z!a{O8$d^YGCw8jI?oT*bLUge!NJ`%fko81n+tJlZ#~EBzn$LRXWS z?E{H_5hSY~xC#v4ka*Edl6wad&Xx;#FdlV>D^O#Xel}TF6OyC^; z*Nwq+Yb1;FF)@0T93R9T8b{9^)1*8AGl4wU&hU!;hE^A~aurObJJWquaswn>7(TaI ztEqmVoMaNQSRCLaXJnueVOD|io>}=!xGEiiElz1>WX13`YqoFUGCtWz9{5OqHt9|z zV|?K{V~}(iuaUE#!f4QU8}!rcX--oWJ~$&a!)1J(%F`Om5ow#h_-{nng| z4oE-(^~z#-AM_mDFA+E#`{%2F7GI1!WYTcP7FJA4ad?zDex{+HuQP4txjz(@6tn`c{=^w7+1c!b= zKoeE;$oy!ICcOM^h@4aL0Jdxjd?~+9p|lxFc7lM6S`80pOIbuxOvcoIbgN>}=E=XX z=DEUbA-D69{}ff8h9tO3$F@=5zt=eu*cZ1|pj3L+!JlK_k$oVa$9AVe9tYu+VJ+W` z+meGa&bmxD3FE^@nYJ<>7d+Q@z$6%V|AgH=nHzV(i{=EmCZoy9sV;ctdMG}BY2Ky( z>+K|$Tuy|0qs?3``xtS5DTrray^S$v1w9RRXppQ)s%UYDD19L+p|Klf>UkPfMnaLXPd|`co%#xkDC&7+m(yFe( zV1E+c-YrvQ5e0y0E8Wd3kB-0K(UolI*(|5TU53{AMvcA2Vd;Q>w2TvtAq+c#*ibWnHtS|?6};s+q>9q3ahku*;%=swyPp*9{9qFMGjjJkq9Q&T6)R#+ z?8LAp&aPtH!h#%pcgV%lhr1a~z!Gv}sSR0~)dm^P$L`;MXjFPGUTgP?1d-Y1oz;0R zY$T<)OT|bx>1gRG9ZcKw71{<`^cWp7GEmC|E%eM+He1DIFuf^7oMPA;Z9JH_ z9Mo0>g)Y2`sI3m)2fT27{ymv>69u_K@WxbYjA2n9mM=c=@M~3QhJR^hr%{@$u6y_R z;7edn?>Ot&(9qZ`Bos0Tb)I6z9O`;zO6PB6& ztHlUJVk{Rd9-m3v>+Y|r9@T=zZ~e&RuNpRSZKT5hQZ7yHDqeAj_zH5SVNSO78@3du zgj8f=Y0BCx5WQnZ&cu}bx52u?P}+fZCTQC#`Zf|yR+{wc-Yi;=(=her?vW9sBwBBb z!f*nA6jw5WPNJ{Kr=s-1stqdcYMIFb@-zz@#grL%I&Y20MNsiV8DBh_6a#}xUp^|v zZj9)4E><-cFvH;+R|;~X#aO+duKZXa?z zxdY~;@H9J8PCwPN5~ph_Mt^{kFQxm9=X++7TO(m2Av-Ab!3Ra!R{a6yn0021-#Ln$ zPf5RRmi}HfkdXET2$(r(7ZE?-YQ0l{VQ*%_-?=Ypi8EK`4~WI6>`yiNWhSBv>wJY& zZI=2;2`MdxRF`sW%hsWaW*eVZaLo`oO8w`TVd)Cq#`e1RH`AX6GDbv1 z*?u@DYMOUEupLAFE1%lUb_=xD(M_^!0C@io!~FE{m$5bi6Su*83)6A}Gc}j-KMEBD zGB7eQmjQeWD1WT9W0Yp?mL(dtZQHhO+j_&cZ99V*wv7xc!?u}W+c&>+y1IJQ?f%nU zKlT`VX)et5EOKHcReE7F2NQsVgS{&~GXoP3k%E<-iJOaxgPno{w;a6+z`~8_ubv%- zoLtlyVC-t;U@vCu3g98q1eg(t0ZfTlScsUpxw&D;iGM^L9KD>aEG%7#sMJ+7scC8H z{!{ah3z3P}e^~xTx>#A*6H)yAaR=BsINAa1UH?M-Uk9oJ07R~q03vfMTL6)$qLQ|> zf+P`@q=Gt;B)}fvY-~%UyQ>(vW08dkZ<3A=kB1eF;ot2Br-+v-27a|L1V|&-XGjMevva&a|bu;^? zfWLZkhkq61=r&Nvz4PO(ci2}ViNzZ)78@0^`G1>R)5Vz4(5M7 z%^XbK{%Pr7w!bict**va_AW%O08iI{a+v^#%zvz09Bqxg{^tG*=ICtouQJ?Rtn4lR zvjRFIXMlyVvzaZx#pN%|U+jOT^PhbZ{V&}cJ388W{VUqxUta&S1}j$=fUP+L3^U8$ zoTjdSb6Z&1!!Z7{E7JDn4n)jM|JIwiIsS*u9pL=00a5+4Gt_^JFgA0rxAh`21DL}w zDh4>X{!K|lm)h_PB7fm#YpY;v_jdvQePf9J9vNeMqQ7^BNRH^ALt|^~{QrwFwzIPJ z`aebeS8q+gzsvnUfJwU={~e34y~ST@m>8J;t+aBHu<`_$DOtIiS`wKX+y0%|zx3+% zW&mefD|^6SZvQn_B6?;frvGA7v$Qg`vHynz_J5lI_GbUJgMYtt{i}XPZ5=6bB`Mnf z&4K-wqtf3+a8>hi{9D`q=tkbb?0*XXz=()AcoO;0Gjnhe(X((d|9yXd3*u&B^ZVbV z{1*`Of6DU4uFh7TM7n?bW@7$V_y6PjPf7p3z=+$MI+*>lI;yV5_GW*#?SCr%F`K$M zJO3s5UkBiC*MI*Z|7-6708fA^%-XVpDQ~ECMs}uaJ!am>q?qnNA2aAkm}6O!T5(}u ztwV1>M&vGcmC;9C7(??k&sT@n(wXDup$yH@Xdi|xWp6s*ssPWAl)AqVd5hu~C+$%% zqd^&b=DB99&-J3*4ww!Hlg82Bq_T=Z=?4V<^eOfNW!ay{#Cr1Q-(;tlq z=v_$7Kq&P^XXg|tC(lomLu0>3hI?PUav}x8Nr>J{)Xo1J-auWV?UJ_Kbz?3nhj&0!d+0k zAb))vKHM|f24Nw7xE@7j4EWKI(SphLRHjx7x{-+Ymre|pu6g52LA1CXNP@}gUVz-k z)F!0pJBUUANNSbGW`2ib3B-$Q#1W18u~3Os7)XhzmHR;p zNeuB`__A2@rG^9*Jet)C*h~e>F!blXvJeD_S-!%$KUjO+tbm64UqIVt;|Sy+92(F7TLw{?AjnFui-+_9L-B z5qJ9)d8^?%iwYgoq6iCFeHjKadRz<`mGt(5yxb0_X3S)pS^?Y83#%5V*W1zqAzNaf zto5?RXH%C!O~(t*eYqMsW+>H6AAj*dJ(0u}pjb+p*&x$j#(MF-B*ta_E{|LcTD2HJ zq9xlOWs(S`w28YEh?S2O-p*?ENipF(d5 zZyu88*)8}}z|^>XF0AOx8=Gf-jdEF_AY)P1cyzPaIIA(Nv-Rw>?6xTx{(o!6oJ2FU z2MuN;#YG&j4|sW)k<2FVF15XYlcqdokD`D7n_n=YQ zq8!1EyvW^xIcK|hldIFM8VWXV^KQZwLn~5xeecZiak+!uhYvpoOMlv6SF)$sM?OAa zbjE=oM0xxAi68~iw`5KnKuC-}zL4`40eZYQu!pgdu<+r>#C79nh<|#SL+msY)(>-? zENnf__h%C^_Nts#MuJBBH1xi+T~;!Q2==${ZtVbO&L*!$!CQJ_Z`>&h-S|iYm}eSo zyj&u&?tW`+=uE>mxPSZe#(1x0a#Z(^jH_sertEQ!+ddi#UtNb1D+2by)4m_=mKC};5Vk15Ldy*42e z4+;THP%@igNF0(*eg{1JpM)%pTMII*NmJ)HMZK91J%S8oj z$;sn4{L$xRZ*6>wjN!r-n2a&9GM8l<1O*}&|y|{QfYXg0FL0dK!J6wqK=<%^RGNQJe4<#uHh-9O)-_|pPvX>C zK#>J20Ns!dyYBU29&jk_E4D1wIO4Rg2_mjxS#%RqXIQ+NpYkmeUx2c_ffbe})xu)t z;(sr52%Eo3VzeewuFiISn3Lp(Z=4cm9F34$<-+z>Z136;smsa-YY9UU#TLrDK@XiV z9TN;G0xQO@`NW^!vM??+U;w3ss%Po4MI3T}30V@AV{M?<2O*v2k8o z1aP)UhvAL=GU}7-Ia!5uKogk?cdtM0l7FR>3YkYi)tx&0K)-&P2eB%Bkl;lbKwJB1 zd5bzc;!97?B_HqevkBj8f5^y{m@9*F|7|p4<0e|PWUEW_hnF|u9I$BdsrO3uYA}T@ovBJ|x0*0dwoPYMYMC8MP0DxXtEhm$NPlOO z?M#s6OskwMdWMVFBubvGFQ)O1zTc2Nbo!B2a7Gh#Jt?@|Ql9K}Tk_DMV1C*%|3kJt z`3rGJW{dT%HZ}&Eg~x#A&ne87@&I)32TPm6$^|gJX0%Db)M-reZwI1^9vP7~e@LGk zptGVRN$9~391Kr?(=57xwIcYR34d?+I*IUOGfRWm7i^kvZCafNMIvh)MbPLQOBm23 zm3P9feP|)}4bEhxLH#S^$6xRel-)Wv!QsO{DTKy%ezI&<;Ys`Wmj?_cFtB6W!+x0s-A*CC6Kygx5Tu2AC z)S%cGwTCbmQp02rqj?)mF@LJ3wQ{Ci5uPg6VlndVGOqVKxhIRPXHoQYLlFP0mFHC9 z;##y8-%?zQVuD9%NMq%+T)HBd&O=E+HxDH57}zp|poF1sU`P^!^4*XgwEM-`W^zv^ z8iRK27X_-bYG;fVw(zlb*|-3ok5xYfdd-BM{81 zbmvUtn*ceR4}UPS@7}ps5+zO4rOJF#1eR_TCVAiu7(Z!9xU=z5{@0lV1C~7mX5)P_ zAx;th6dj(yWY?hIFn{boF5)}rp{jH37q8f=mJs`Wug;p7cBx^3qp~d}t}_iIR5ux} zCq`|gr^eT#b24UTM59gb!wi1u6m5O-4x{w}guHRbanIbGfU0aJ22x?4ML|F0g$+#H zn}e+!Irpfm_X3mVW5sMpY1DySY+;(Ssi!TW=gbY8PcbEvntv3a$E$6~*uNJ@F!q8# z*7{i^>dnD!lG!)F%56uSpr(Y2JfvW5L>aCWan(S5WY2yfD}1}ibNK-esOJ*=n=ucE z1p7}&Y|zg%_rq&qOOT-o)NLRL2FIPa5I14-LJufb|B?25X0T$4fbP^5>nDi8=X^hd=uAHALa?09 zV4e-WKqNN0(9I`)cJC@8ibb{1Vb!c$NDZ>(^g$}8pB>_E>ocAfMS zjHNzA>tkw+s+|IpowR)bkOW>5t9T%* zCujXUJNhcp)vzLuBOrS=#+h3O=5|_D7jS4{oqslENa2HKK_nSTrBU5@@)oBAI?F3M zCtyV5Ls8g~#3a5rW729kfvq>dw>7VQxZ38rMjoSroy`(UTRezKaZaI9V7yXD7bYtPGJ+jO++tT=C)M zQD2Aq@)hv0M#x!A(28y_A4lvyg>~XF^2^$68=n>7U!Wi|&ZK z5%fqz9-9GlvZ@tG`>N72+*-s;!>h1YE-F5wvVxtRKGkw|Cgp~hS!U{;Kh4g^+*)&J z7B!dCE5W%t_MTpwmmJ(U_0_VWV|g(YsI0 z0z=Npqk+V}Fthv-dy^#HL6}z%2d1gzZwAie^})J>bunko8pkhH#~+X0TnBMat?-`w z8i_jk9;u0Pa2*CT4Q%f4*MI1NvNi3CwZbxJ zNRjs6aVnwpB5C0p=13m|zKoB8*boRdqC54gy>V*_pUU7@M76M6Yg(AL=5};bodrep zX=G^VfG8qk$6bAGXok!^ZHZh%5~ZR~n3bVnCEwCHx-25@8x3sMDZe&`)B>+9 z>3%>K)^596%4KF?@?oxxs?W0xtH`5ygd38gcZis*2u)j zP04R(;KeC+@_*1;$GP^y8hRDaV&{3LOkZEnIop;q_*wazu9@G39{Cq(7<<5M72hdM ze<*wnwiR?kW47CDB2>tJipLnyVd|YY`A4mTPq!=0tH!b+JfShd>OCepWDYpB9(DXd zTbA*4=A>f3kjebTT~<3Wgb#v@wWTqSN->Jn`>@SQmwy9vYN39N5{c}Keb7NPz-fLb z-B9&#-rypb%XRBPOf|l!EGGx?b(qyFM0j?`5x=9W==qMyY8<5`)S)_mp%G#Gn{mhL z%sqJ>xCCn8+cAC5&vX9?2dqU1K8MN}rhGBR3t>ZcX$H#7inM;In6j4U<-jY!0+hqF zw*~GDU4KjFP*#I7>T+EyJf{UYV`epG0T-d4v+e=$P?~pQL~>v9zNOXiwsah-f)QG$ zYKE%wRPivUP`FQF?L(q8aNBxe_SfUJnG6pN+gdaJ*RafP*$?t{Q}tu46~?oYQO9_- zjngK7lpE6!m9vwIVN;39nHnMKd9r)$U#u)nq<@VPk!_j}HDbt+j4!0eBI=xiGP((v z(_f5m$0JIv6?wT_2y{?pHpl$W=KB~QW4j9t+(`vIH+u#THjn{8`IO(%M?o%mTxhs4 zqEQDU-cCGlAT)NkAoV*XBCIWCSM)*Odakd@Wf7oIn9dDGNlou`PzL=8xxvLK07Rw3 zfPY5AaDD#E;|YHgs>%Ln5r>iX$%8Bjx_oD--aIx^-#677&hnMmsPrPmL+~2g)CC!O zdna+vi5(T#@@4lBHTr(v{VOJjU5%jL{I2T*u200wgie7jq>SK}zRS&%lF@GQQi@(3 zNFIJJI(X>~kKrK_iT=mCN4}7%CCSvaXgOxi0`N#s7 z9#@})_dLEAH)S=yz0LDFMusUf@oS|m?j#?ao zt}yD=M@)6LrL&`S5FM5@&ubtFC;)GpR>YA&hq1ee9;E?c9=PH**)1m1hBrd#qkjTQ z)unjh2a;}cQnmDM^x6)Hvm3cu@s+BXz%0Vy_fuL*rE7JOWek)AmeaPw+^=m>8s|r* z5SETOE7kASQPgIKq~scE943|r?3k-%zS023@4R_)H$0iJP{?f3EvrYa^I5g5k#-SN zTHNps)m=vEw$dFPNY-=hayTD%pY4 zNFbsu!0J<%;EFS}+-JyL7v^|$+(ktg$@Qdy8M181uSD9oGC(1@Es$pEu*|39ShvB~ z;kt)xtcc6)nq;DT(530!`ZDJ~iK-ZG)1tCczXXFyB1O4N_%G&;`vB7fSa?zVRs zuheI>TpqXg0jo9u%wqVfBSpX>vEJgEOLnDn;$&gxslYIv!Q2%j>|S)WShVv7N;LbnZwnbR?O^8cCqz41WaPNOfAYplFzjHnq&+~EiQ~QZA~2b+bh~)U34fP!2E0ZOeGk~j?A_coWpfA8 z-8s!Ki?#7aFf+Xq1dsa$L4p{wnCtpsK&R`Xp1ah;R<4*tRufg@)i=3#S5+9t80guh zD;qGmvZCkcOlF zM#0e8Z}`!6P{hP}Q=R=X3D+SkbQCK=SwOjH1m7&RKzny8t$*o1HnTMuZ_#Mw-*CE; z-!3qh+9&Tu`s2_1#W!Oro~p%WPbGb6`}Rd$)~TY?Kph zJTcAm5{O3-=(}&QwYeNKx6!Yh0$&rst+gcar6K@-CvV}-=)JWt-C=m|A0gDqRyL#e zxKVmHBV}^>xPKo#Ib}Wsu2s)E6))?vl^)jC`OPUSOA@aNy^8O?Si!m_#rrlPp?Pe9-zMn*T;{F-LA$B12EfikZ;A4)#?Bowv~2g*fy;rJ4{*jRBbHlUqQOfPPXy(~PUVV?!466x-=~9$>eAklDw11^h&YwrPQ+vzQ%Cwj2XYfTR ztSih4Sf+;T0czyd3Q$4F=}zc9OFbP>lP)JLtE@U|uCVPKHo?(Mg4EBH_QS!=8-*n__=jg|w}ak%nhhl|m7Rc1i)t3n`n z<8A!~seg;&(;E_fcDE;KQksKnUVAG#0eoe6*{k&6zMjwzNS?JLaD;vYVzI6g0dYnYM+IkA9m8Fy*Twnl<6Gte(If5 zEa9kOJ}K;ch?zEo$7N&i$1~bwT}lhmg`;(rZ5fLVw+6kSA-J&dGSmQ}OYNkM! zr@+NXD!1JWJ1ESc1R}@Br7#WlOps%?wSR^$MU+AESZ|b`P=7gD zVpDy9StTY4UA5`bc$X?B#?r@X-F2Oue2s>lOIU7GhsneP#TG{4n&APxN!bBauG`L@ zU>h#!DGJVt#x@qTv&oyo)+7-xxsMH945;9GwabJr$`CG)Z}l||hZT1!J45lgi)lP$ z3OdKU881Yz6~&@zh<=ORo0>krTgRB-+S(U`1u2 zYi(RdKu<0G@kjzBo&HQs&#~Cb>FGevC>fNjTn`NPn0IQCSS9|H?CUF#Vt*B&q;}UH z3o%CJS?>%#+mFDypiLmdB%Q*>YO>P}tDjhwI>)gg4m-MI1hi7(w9BL&5w6+kTQscM z*Q^w`^-)h$t*U|XBPFlRf{=d#jd1%2%@OYY7_th=TfQZMm^09@gf@KYJ@NG(-G1BC zdAoysc&*25k|%%`rBlYpDt~)#7nAG+&6&}=+bOMVawtX9V%fDOv9WITIe_-AjqSkv zmoE-WQ8Fpy5BTh=V!fX?*lB`qm;FdXuk${t?8 znzO>%mUJH&jhp=z?vo;ZO5(3m+21*Z7r@9TPeYJ`QedeuO2Tj#EDL&`42VWvYKqu!v}$3 zpf}Lv+HmT)H_?zh^nZ!Rr2u}8_Npd-z#a`By)%#hG-B#-wErN*IEi3CZzS$VeK|xc zL>vy>e)MC#V-pc~9KH?ulV_AQhdvR8`Pg&9@k0#vu+YIx3GdV+DwjMl{EtaG;zZK2 z>QFT5Mqai8dO{5SWL8}#Vm#SR;DJ1Lh(nbg8KWPX(tDd7N`G#-vTzyzxa|gaiWGG= zuw2AJl~6`7N6{DY5Zce(e>+T91!jk4PI@$dL9pw}vNi9wx5Rr%nfJW;qmT4bp%sK= zD(`c-tZz_msrgeiy!lW<%?6jH{ewZ)t^N-s$@{NFXwQ^@<=g5+0*YEssj3HV!64Rh zN#YIFu8^3dHh;GU2wgAm_b3*(#HYw@PE2mJ2_j8h#i?IZ68fw}35P18ZI3uP2c^_H zI1qc$!Uu>F9BtjRc)opUgyv(op6k6?(ExOEz%qe3LCvrj01nEqy?9&G2!}v6Uh9^` z9g0DUIf8yL+!6x3C&H}uR9)V-3j`+W=(>)Yr)vT+TYsPEr@|sIFjC?Sa;Cvd@h^SD zw&965FW#frA7WduzkPeFMOt}8G0sRlOAR=j@J?VvjaI1-5)EF7O)gZN45S?#l?tqF zO_p!TwozzH*_v3(EDxDxzOM*km>+|T>R*tYTAh^XK(p}oFZQgUYoG65oADz1hBV8W zF_Ygo(SIF3*(y4F_=DusM}TqdyS3(HlM;bzCs zm@vG5s21$q(gjM##7d^d+K^f_x9geN)Z|ju{9*x9+3ruZNd5|(H4a?=QumJ$nFJ2v zb?d%WE*AeP&|PbwM$0a5O6Mdubwxh3@7zAhtv(?fm_RP>gSVc_m+v!SI!b;6s>oqP&P9m&s z!GB#})CNol$So?j6fC1yCoSR{4(fawsi(RCTQ$;qMw5W(7Z#%Nt6i{)* z591>uTkqwOcS`w(?S)#|Xt>j+BvAce{)4W2{1f|{Hy3m{if_J|uW;A;#f0hxI#-P$ z_qWC_=DHds>_;c#;{b#N6_^HQ{UY1wMSlq1^Q^_V-(H#TH3cU&?+9YYe3cu@J&RO@ zn119MAUmkw^=quXYM&hR=&O6~%WdbxR_)?GkU)=Ic2ybkB7RtRUDECRkxv2IN@iKg zX!Gkm8Yr1})4Uv|!C8#?e4W9w&W=@*2wCukmhK*Z$P_;?jbwiatgGg=ha!~4jDHAE zx=r<+72Y2=NH^V@F?jyXRr7GcMq_@fU+w7$f%d>6h!}sXAqmJeAHGo)hcx+2T4^C^ zv`;!Gmz#oAe}<+aa zlOe4%bdRE}M_sCWI};!;`F#GH(kka44x^}rJ92*;oWva0wh zRIFybm*Ad}DPV-5cO&bf3Z=;BlN&~t=<7@;=3&`4cN_`&pXt0W-z8>@Nq@OXx$05F zw7~Ha=YKd_iG|&k2gBgg$?mWBC{L|XTOVd<cjIo?H;F)#Ajt39)U6zKms!oV zHT2Qz&8d&8H#2leKYo6c_i(9Y9SJ(O>o|b6L?7694a5urO02oWvf6Zi7ZQ>fh76fo z6@Uq?bV#@TAWLFMTC+eLN`E(NH6N?Bqbc29gxoBqqwXAlk+crP{(0HLg8TkWdl#OS z^@BSej_C0Qb3C`Lv#GNIeqP@)f{AGJPo@o7*!bxtu_|B0v z6PGZ8Tj8Txc5l5`^5sS!;@W3-IU$R4baQ{c^ldG@6G>47UVTTOB!8R+w@Wy^HSG+w z2o;QS(qeKAq(D=Rw&n2fX?8y8kIRBEH}Mo=q7Q7y ziB23qAzDlzmw=kwCcId`HkLH)mmk+eF^ze6&sM+JN=g6m34aRf3EU{+Ept+w*WY

<8FR&X&0}$Glz2lQmCOK3vVKO+cp;F)LRPYOdq4972;_P@3a^A$z^(VVEE?F z#PQn@zt4j37=J@dVr@sXwL@N;O_zPu@hk}SB0n6BsYlcPjcFu4a;jS63gj41cKD08 zrUAY~DZC0D80xY09>p>8i)V8n>v<`f%_Wfa&BvHM$< z*pFcV`9yd%;3YmSIGuuVT#5yLyHg6PV8TX0I@(t+X?t~Y1k>QA^uZD^TK(&gL@iq$ zMD_kro;t6^lAtfK7fntU$7V#6rVnA~4m9*8J_&C{beIx6;_gthi@R7^?^g9?U-OWV zYF)9;;(tSpc#eNhD93RnVkO+CKkbL7@j)z^57ZfE+7QZjI^7<5+n&l^=W2f;>Bi`yu4Fk|R|JlcJO*xm7q- z27g}IP99d*=}c7p3Z&7=V-$*Lc3$9-F3~Zias+gdG;E9|>(egr82?>i90{}Zu!eM13G1#%2K zL1)_aL!0drjAtWue24>GbB*gm=IrceWF_Jg!3uv3YEuDpmPE}*-fRx*J)(5ZDf@m&?Ow8(MHnHnOrs()Nlpe$_J4c0Hlm~HJCk}xcMSdT${q*Q-I;T6bYD&38 zAVq)Sg4eMVmX_autfI`^*n)*re8L-%&9)FpMHlw;27rNTmB{&Fqnsekg3~Q*{@Xms z(0AxoT=+@=#YOm}fuMz|IHB8(F}V5|ktl4oOC6Nn0@Sv4pl2^Y7p!-)D*+`1NuTRj zCfgnKM?tk`iHun`rD$D6h_EdTV|=O1;PCS_ z{cJ+vp+}ceq1Ng3(CNB}!_R;?Dr9Fbz;9j1P+~F%IAX~Len&YVi|xb~{v^}w2y%Ay zx>v`k=>z+>8d0~j+OLzlNQGHI*Y=7gcVX`O61Jm3-(WHMi;(AOfO{2lUbS8bXe57R z|4fEeRkdk0q(d61ew&46?WTryy*mCK8B!Kt5$LC#D4Ep^*suM_#|RBVOKcIQgeW=b zd?t+d^f)1^`P<_W(+olVful~2O|kTwMdN|@I6LsdJba3vxk1KXsa%cn*uS`CsX`MN zVqrXv-<9W}ok>0K8s$#I4T(%5;z55pt=fBhYn$`)V2|_`u6H&1rKGEiv;ayCFq>)d zI42(BSSQ1I$G9M|HGI&( zGjK5Wg3XQ0IcU#>v*feGW~iyyoZO^K)D7;vMXRWDzefs_wtZ#mNiMrV-?womfHb=LDXh8(JKgOrS~3=F*av zvy&{|ig1>IJy4H5|47n%rn7$shx^BkUs#d`!Y5|9iy1qk{SK{eHEiH@4~lC(aKCF4 zbP^;R-U9erJwWW3uMq5G5W$)2->C7U3S3@uT(afvCKznb22#}Bes0P9v4k`|c;~^5 zVAVU2BTJBbM^a?Z^Q#(`&mm4OfFOGK{cZJ)1&8%86|*CRwfvbqIX8cC0Jz>V2ns%B z1J=}RiqU_`AD};}`8R}ing~*jgC_2UTO=Rf;GGTnwmaF5<0sv~MsEt%L zJ>zIZks3+V4GR=ZMN?ksI141w3Wk3pOb>UseAtY=XJhLe zwXgf9*PxOvbcqW|{u=_~1R+n&7|rr7AniWy6^6n%3`5wd)tVirz;OS!;H~}G2=G+& z$`>Q8)w{i~iHvQGGS&<#M4oTBpf)RzUbk!DFe6B5lWS-lBiS*ZvmjjCP6}R7Z>b}g zHixPDB~p(SW_o`Q1fi(B-$FQ{T8X6%ciIn!)e@(MWr3O}Q5o*S&Y1>kY`wbrDFh$b z_t`c9O{6-b zS7h65S#6mnq#8g@NTk2=}FOJUiJl5_lJyeL1 z_-si6<8zZC${OjF&|@q;)3xBn@*E=eS=he}cx_<^!W)Ym;g~lv5i0g2kxj^{@e=TV z$pN|cS8)~q>>j%B2Y(=!lMQqRZc!c51F@pNU2lJVp4@c$BAkv^xJ;8-gI|IowO5e# za*im%618;1QeC>(&Y`31`h}VZYw!>56v7v~erqS+!S-GIl_UzssKc`!#B0UpuMST! zzw=aVEGS7*6%BA8l~Ovw9?Zt#DiWGRoj^*xt9d^8{DDH{?sq_h7iQ*tmUTyk%Gu&K zkNAHR`7kRA?{cDY9-E6*B<#%y??CG9-$&@?a)c@hE9X}mb5X~>uZo#TzK920eKRx9 z%-|}r;Umjpi<#SciQ-U|P)1%7f6m)e@DDkiQszMkp0%KL42&R`{ys=WTDR<^cXm?O|(L_^E+rSZNe z)uErcdRjn02LBMOkjlh|u>=n5lC7uBG906NzuW2r9U3Yv)m`#5uq@wS!oR%W2S0xy za*_|Hcv2Qt^yKgcp(z7OF^a=$8o2tMHP<*@n@b70@4n9a?v`24pc7UYK{!88?amfd zsgSOQbS%=FcKlOT$8IWI2B$*r#ybAN1XId&Q$84z4NhEd_RXL0vbh7S7!*(WC%R4$ zU0lk1KW$;J8PaTmTmIRyt5t`EDrbM-jKhvGQtK*(Tk7MBinX@|ne44w0I;aqxE{5>6$DnT0y#Hn zzEc@94YNP@7*TVM=l~puJ?SIppSI=85)pEs{L$C$pW zo=cu5F5OkUh0N%S>-3V-vjKmHbzShDWJm8%fq%y|oxebi(mvI)$_Nj*Vj=vFh%H_c zOh$NQAOL7)Ki_QF@R*@mWNi$H4EGnRA8X%vy{tM9CE=}OI{~-0KmxSN@oM3lCDDXN zHj>)BmeNJk%8uIz*`);u#-a&}uy=1kCCg70b)lL*G>w@wRCy)g+F5^=?iv^BZZi}` zN^x${f&NxJ2|Kvd0uXIgpbHj@hZ3NWcmCVsVQg8l79Oe+U#vu1GKG)(L z*GA@#+=;U4{wO_eYAy0EzIONNL7qD|jHXhGoe4M@p7s-266EC9F-)d(o4=L5jDpzK z%_;B|nKC8s=ofmt5<`DU-%-X$@3JUhKaTr^=6Y%rg`7ibXRA_T7JEHF&uJq@SQIBUV7+L!Kf>3O>3=k$xHD zPv-x5@cFZY&`jgE_Nkg*XR*yOTt`Q=Y+iOOIe0ZKGno(>1EhaoyjPE7naj-uMzawc zZre-b*=)u#@ctG25dn<8-R@${Az2|<`&%O`$}}9*5U-md^rXg`bW2z*VtjnVEKoi0 z;ru(IBO=OP6`M;5eAsI~b9wI*nWM9Vt}9TGPp!D5oV2{$#ClJ$V(opih~QvTtbQ1!S~R=dixliNln_)1Z#m*%@2JjhfFU9l*+q3J zC0DyceSI=Bk;7~};!1hN>|+rUb-&)jX{h(&`1v(!wCktL{jI^0XUDh{1a{rR@C+PN zKfJCHMTi%v=ghvQUiacDmj6xz5Sn6HdfAC+zR{><)nI>P6j8h|2O7mhH0Sst5fIP*@#N0W`8(QJ6?af#;7^DB;n=F9?^`<92iG`4fRP)B9*u=^-@JjN zQJdd+15AI^xMEhvcOVl2`l`q%>7L-8Z-cieeW4=5RZa&G8AQiI#Abe(A^uZCufST( z=<%4_27FdWR_CkV1DZJ=P60T(r zSI~Y^!B`${F#EXop{j19w|uYhKqfkV$&;*Iv^fxEKw6=Rko-u0e)PCfcfx%5+@JmuMJVUw70NArKx%H3BD`bxU&Ap=!<9yC))5mfeTvj%}N z9l_lt-!&s9Bp%@?4L9?*r@F2dJ*oIGMnLc2To&}{N}?DOeE7Vfs{e67xp06yB(-A9 zz6QJmpg5TNsS*_4rFjes-fdEw=B^Mg?`Mq6iBw_&t&VlYl>umZ?8*ahsj}>PoE3j` zL`n-uJDPXsr0eI2HH5!_14hc_d+ZLk3DU@q~Ew*IHeg1kdb)8Q{| z7gNpoUZpV}jn|tyiP>4YH%Li)`K5mJp(7@hCRD^|Mh>uHW6g}#3){+FANOCOk~)m)As@vG73)s-HF)D!rkewP=S zLwVRzz{gz%^fgt&O(}sGuQ_$JjS6XZj2p)WCU#$Wge72`R##A2sZi0xB-=)Fz648F ziVveU{&AYfn$%The9`@7v!5}yNws%=Uzs59d82eNj*#>{dELTDXq#zTaC?8;bR!bv zAc$uiA>O8Y9!mL#(tj#R zS?Qd9(eAUI3e+E!my3?&_Dp|VijwZPBpSkMMbTMZ3QQ~ZQVT;4BSBH!%ep~sp;yCV zu*kkUoo_x5OogS=Ij195bIzA2GdV~ z7ADTA9vrdx3ivZ9vF|AqcxcxPV#QwAMWrFdZL5)-MuJUwbCHzC6% zt&EpZE-O)N9ZkbfGrE6ly%rWE=TT2CjK{)hL-N}M#7iqhP=08H1tTApBWIi-L4LjH zLr>VxzT;CW;(ESsDI2Kpydb~Y;g0w$I{6-}lOxXlVE~d!S1>7YQ&9hP;%(74jKx2c z?ErhXK)c<0*>5m%@yihzb6GIAeOow25(CL*1fEe8XAraX0@HtN0z#&ts#{<`*q^Ok z*I8>bZ;XNT6)YVR*KJ#f0ExYnS#i<-d1+7YZHsY@EyQC|R=EAXlpLcOFE|L1lI`|f z5)35Oeyf7d|3ih>`(~8-1Ib=ULB=?HOnIwE5GuG@+o+@{ir&`L4&-5@IL)v_@6ueq z$e=*(tPU!Ri9~;erBrSYalLK8Dj7gKyNQ(HkTLSj;5YHCh*UBwmFkliABVY*KMfknhP;`dc-K5C| zM0|`ud}8-1X=U{~?ukS=jsB`X!$>fX`phY-N|h@mJ)wVW?#b|2SOpjloM91Bf-9fW zN}X@2DDI4R*eMg%lUy4VT--U9P+X9r$#>9bmo@s}5hBEkKN%95{}O~A^>qarK&aNn zu}HkwIfkS$-vF=qM1xYj!;U`n0>#3%&#t51Ron$sD1OXI%7J&4L_=f6SMI<+NWU{3 zW5eDg5R;HqrO~oQ8Y70jSC&_bS@Y~>Z(*0NPIwBlA4>i2!IPj zXnfB(y7gn=c` zXDq_5uo3w&9xB4?*)m@~EK+6w@t<1pScH=Gr`=JHTZtXMg9RQ*d8N8a41__*bb#s! z5Du^T^dKkF6YKoG3{<0@)f54DyuX7HE#`mC^|hs__*os4m((c6{IKWb-m%zx$rJ?L+j_xgKHiiS@4un5QV+#D>>T{3@? zzVAP;VDJALiaAdq&V~HMO^tc0j*r(@68^vk`cZF%qlVlkjE~SbLFMw9-4HI3AiG~3 zV4>C@iV9b6il73df^Gnn@vt2|+p_12M~i70WjLas#LCx~_8ts5Ev@1}g9D76gVxH4 zZzcqZJ2mm}5@Ucc<~=YnyoJ{-(g=TetmTqx#eGP=A_0vseTS;e*Oca!a6GY839FEU zJe9_%f0U_MNKPGC$;B*HNWPcA^4JTsWDMqEVq~JIueYkFx+nz2*1G0WW7dIP;w#owCilEce;DfC7(Wzr#ts?fSP9E4Ab1%MrZpSUhy$dOhyM))nKUGxcPrQCH9iHR>$-$ zJo!1J^_YOXDm>RjCRv-@^NXc}-0EFvM-Jxj($wKIp-{C4|Lv{es`CK|zyuAiaAT}P zrb43+)iE?`cyMYJ>XY^Qc&5|PYr_-_)MjQDyEdrQc=5%cv!?F9fnNIZC)t_0_Wls`1-FneStLcU;LeMcgiG7d$FA)3>$bYX#wp0_<2htc zuP3{d;Oc@T5k`N5`^`52<32hDwlP-?HoknS91T@iV&1Buov^iHS5`pP19b7`aY;i$2tD4l+x9V5^iLgG-X{4;41^Z1 zY%TdI<$37i^(<@o=ad4B(a0F0)-(#wCRf(hgAQR~;`4tt%03O_twC`fW+~a=t_=fz z{AT$;LE*$(M|P5x%XTV}h|J$Q6v4BA(lPSBmLZ$;#NG1V_M-w z&U)+6?Vws)cs8D0>Z?jqWhk>{?{7vAPPv$t26%8wxvAX>@ro=cofZD4Ithis9CWcV zEO<^YThxC*2IeXCMMWl7GKlP&=(C|E1S3w3rouoWCX9hVOsu`TCgN0IyD~Vu1_pV%Wxq69D`B~E-T zgx!C3mU)(K4Z&2qSS#@QT!J2RtN$BewSUe&VyTxyYE>r4Ys7DTzfy(43L?szFHCfC z;G&Vu|CKual;y#R49$?C>7eD5dOG`rqFqk6sxPRd?1ZKi6#dlUVBZi5x%mDIyD%sI ztIR;IH1uRW%^P>7dOFQcqqt4#x}=J8*V}*2)9gk>RAcZT)BgQN=(#iJx2Zkw&3sBS z4yvqKb3EhSMPgLV1iy26Zski(@u2QZv#s3&98q~w^rC^?6>38G_xdHC^0zRvR>@4g zO+if&^NN{Kn!Q}~dn!v!Qm_F_N|~&40ulKi=VXGW1Jzxan-`;}B1oZ{jt+k}Ygm7X zUyLj?dtQ6F+~ZvpVqAI*S%n>d5T!6&rwVaXlZ#)6B@iB>&XU_Ve(2zkY@zYKP^C}B z6zTIA%o{U)y|H3T$JF}c0C9!ck-WW%(~5@TApou>JtfL)aiaP9afC_Y3*S^6tKR%f zcPj|WwqWYwZTHl8;sP4D0m9fX8Pk7Fnc&id>aD&zucp=0r3NFpI_UuI;&f3Ij!XL6 z2!6Yhg>it=?vBRfv9XaXZ)DH`0nb@|yah`%)66j1hj%o|L)Ngj>E=`GG}9Sj0#{~n zeg7&CrwHp;pL8ISA{Mh6YM-|N%;ON(zMIu<71$1=yEAIdUaZZv2&0F_zz2VLX}mU5 zE5U%lNajbuNA&ghzV9M&#D~OhwAaK z@~T802B-{}~Um4B})z z;|KYmnYR7-H<$hcqEmBcMI{5|rhoyiAm#PSSk1ZEd^sO&OmT|GhcZgSzS08E!hC}I z(aj3;yL^jAyGQ0c?Wt1&Tj^Z+SZ#e>ZC^4{ufC~~NJLKxgH3;QW!BL98`j(63m?F0 z4@=MrlQJwta9VLndNZr$*d(ruNVasW{yn_s`c%rtF;~uL2#+OHn_S^5)o=|s)(ViH zB&U5mtvG|(m+|hA%9}BMQ=C-Mi~df1%fldSZ@)byD^dsw?#3xgrZ=e1lj9~`qk16E zNqUa+Y{nyUdFX$)CKb1z3*wjxt9-x-J*oNF+i8+^og_gGv{e%P1s^%HC{( zUJ@$m3iOIrtJ6U?M?c~GlEeWmjW9c9a`Q?-7h7g;=zM>m>ygSfI3WDzl>~&!q;hEZ zcwK;}riT4~?2ZqxIc}?tZEdF=2yFIG&67eyt^RiAWw+Th#F)1dAs3rozCFrD-SaG?}|MNAe(CxANO$gczw zAV%=xPGf%$LKwFFTaqaBfkc&A^k60@%Iy-I3PBa&;}{A`a3x{a%QD%>g;*$6Uz^VY z4jSe}5%Ddc_&omMt*2q?Bj&SglZz0IG714B6DD703VI~+I9?y6XZ9`ycnEOGNm?Cc z#C4txFXhYs1N~;VXWA*XsEICeuC5iY^?-J+#HxQc`5Wmgx>w&Fue(7*HZr0_($4JD zP$(H75rXmUH7ONv&FzMMNBs*= zrlAMOS35@CeEdNQ`%&b(ZJdUKpsUtqG6myPWJ<4mlkjl)mKa4~EkiB#c6+4Y2pwa@0=H5W?+ydBhVLO7w=fYR-zh# zVJ8-tI|CT?Sqf`j<@SpvEnv2cCV)LExp`arwfC+m5K@F4Bti&gP(fRhj(?0N|AC$wN>z0G8(6V)0=x!h?Yb(Nkt@!3fKSAvFNu`+`Iwku}Hi2@p6p{I* zrvB0ai>z5E!j&a70?iyr$R!bWv?;CXolqiB02)jnTPXjz2vIVg>Wq8$qH=E9ot$gA zy=NUa$Y@JMXVbpYm$5bi6Sp%y3{yA(Hj^QwD1Yr-TT|P}wtnYV=TZ}9xFc0UqpS8Lrxg|?rE>rtdofKGV^>tmowfdrNQOSca zppph63aE+#7IL`DAPObiRlp72O&}QDH4UWHa1R3=K{2HR#u-E?5%7@74XPsuKz6Em zz$rP_sUeAL49I{Bfwi!J%MhExfQ``sR~iG*poS-EcpyRwO&ApjO4$aNS9c6Bf3v|T za20X^F%bk5g**ZS5&|rclo?1;fn*G7W>6|(P&0#45zx!vL2`-#D1|ID5S8Q#YKDd- z2fi4{ND3f|fz+gcmKik|z(ygn0HLx7+ENnpK+W35K!pZm%_1JC5X8oK7%0%t2ICNe zDq=vll9-1_fl^p=WFR1c4B!@oe+qkgJguCU~Gl1T+f~ zXdOW*P>ex+GNA$^utEWf2~m$sfQCWMP)>sUX$V?kfFVjF15|5y$O395@Q4+GjLr$9Jjit`8p5e7K$j(X+NfCK;*+)%&+<~Arv2na+Gf3__s!ehJ9le-zOVJcq%D;9vjRAV+yNI!=nWCR?I=pmZ}Z%A(>~3e3ZjFhKc;e*vIE8aV*b{sFDU zIaC42u?$qL01e~CD9M9ouaEYF*O%G6n2+-GstEKzsOQjhp2S6(&357<37+k|04;#L zLlFuQQS}9K9AxAEL|Z(A>c`*HtNHKGzWx3@5Cc&4c6N1>rx%w6s1Llwhj^Th;z_W3 zlLW`vdGQ0Nh2ke^e=&iYU&SM+;yUKg*A3m{>G93CA6w3&+P1tq8X zyx6{sbMVI-WIrw+1l=INrQ_mq4q5=zS3i)~@nTrm3a}dLV6u}q;Q&K2bW(pA&l8Iv zsa(YFY?O`D*@boPo}{~}p`rH30qJ@4FoP9z{Rzd^pfGAvf2i9O>Ts39Ds_YGr03@e zfCf?aHDY9b6^{~E8Kiex;TklA87O!9epF(cz_GKq6?l>jhj1&OB+n#Z%T z%RGllCkeSi98Qw+!i6jb2nZm_)A=`YHCfEbD4R}Wa(Q!gnar@ZG#iuoB%WWAzmhy7 z*(@Q&kBk(Te|eISbFc$)o_OzxbJ}1eai+DmV z5SvL3)FpF-IEf3gMP8C^vO{*sEApDWA$#O4c}Moi0eMdj$r1ULd?3fiP71Oh-^mYhO>W3vw)UiKF?Ua1OGP>vCuF#oOp=1^EqBb?_!Zo zY|WOcf5Y9X$uBOseDdkA8EwdsUXihkhX$Kzxg=ikV@MTje! z)q?oTrGFl$fNJE>2lP1mF(VeX2*nAMC!^V4eL`z-GsB&c_ z%g5({Gz&Z=W0FiWhl@#ef&Oil6&0@Y$boLnHF(FC9lumb@3d|~mQ zJFwSJ@n}&bWV%2biZ9SFmUe<1*g8kh8-O*UvDBr2yeZ&gF=^0Ol0HMD$k84kco|R5 zU6WKDt;>9Ni6@s? z4){v)Dd2uMnUlCQV3!>^*+= z9zT1JpS{P=-s9oDM{DLzVWMpAoVhP2uUmPMo+sDs2`s;D0t+)?L3`$}Ra!lLJ=i+g z-+KAa;N&t14&vhSw=DlQ|7Wl_8x4Yw*nwrUKn-X#2nRy);P+=Ape{Q6{rMm`e+2sh z3ShoP(68`57Ov^RpqB!!t(Xe_?#i!t?0d46f#DPP*&aCV7)gz9$9vt>)aMhwV1d-GFq3^bYGrBG_Z_j<1ATc*hqbPk?uP2V<*g zfE!=PxXMdJR}oPBE7{xLe@5kuA=c9H$J$G&Uh45d5Dr3y>CX=0QE+%1d}<=s=0I_>|%)Fc*M88zf*dThcoF2dp2aHzwxvDP9POEwmf zUVli^a#grd;PG#Ve;deaITLI_KMt0woeh_dfaSfoc?iK`)sDFN&lCI=cWy*cWOs1j z#s&d{i*gJhp~sn}&JexhjKudi-b1 zSCzq^r5o$3=qTx`XylyN_c~rkTc+X_??@BIH~53L@W;wDf2_mORMn?JH(zCFxBC42 z-TwP2slQRO3M|+E(U5Z()Rs48=s=ZMp`$@mUL|x8rsJwZa6cVa%9I-D>ZYNqqt#Uj z`;$@*)E!r?Z5wM`%lu{CbsM%tchwQ{L8*PHg6yyh8MR=9kK$^ippDoKF7W|~3s9(mA*ckzB$!i)+u zBMe?;gz^M#cwi!KHKq}Z3`GdO+{UB)VS;55$$(Sje^&uQ7487CSwfDWkjR!|$~K6i z(K3XhDx^@ERD59F_<-54#65)E){nB43Nv9c54dDdg@0{Ij=M^n4nhVc1n?wqizmi# z1Q`q(?KLWO&VfW`@uP5eCrU|DtU08}hywPY7>EPKgpCLmA=^=i)mxSFh$3v1z!-(< z)c_IPfB%W*CKN~lP2C!wGeH-|?x-DF=SoAbuUo&^8kO2hcWl+(GRDiieD;mJGb;m6 z;Bxl37CVlzrtPjShh>$ak(XDGNY|P&8qp-sIMGBAG^h)~Y)*>sMIb;s)(;4Km98Ez zYcyAdo7Fhd@a{O~d#=d!+*EiCKMs8YYCHLhrm ze?E*>!ewvk!O-tXoa7^if{yVu_T)>w`L*M-37It+D-+)<)Cw(|S%&;vJ_LkkRyNHe zZ{5j&8%VdQP-Q2{rLi!u{!htTG!mGAfwcj(L}(Ir2v1e%|1b`6@({T&)E?Y{Q>inffw+!VYX}eZuv15f*lv+y_bN5^ZD>T$X@(Kj<9LGZM;Y7i37d~bR+{J+i2uOEqVBF? z+H0rJ<#wHl*urC%DX@;} zXB{XD>t%#`nWB8ImLe>D)wEw&fA`(UTivT=h3eVn!+2a$DCNS+We=Dt+`3HR^HwcW zRPm}T+q+Cr)`2wQeYs3gQBrBro=I8Jq_7(Us?uv|5-BV-16^EmfTuk**6czPPrc$~ zqOe{es#lT9RU%cc?o=yI7{)Y%Cuqvms5&2t7gwCTdfcGXtF*D?q-j%^f8{b!b#E^@ z`8K4>aFt${DQ&1q^K}mCUAn|q9;>>vr|&RrU0vdthuSJbeWz7o3lCLgy#Ob9{X;qp zqbm!Bl_mLB8I=o$?Zv~|3R{bZ_^VZ3mh&~qrKvUPTjR>&p-;QNc-RG1&ni1K3H@DY z-{j(5*taZ|CaN5bIg?dUe^{agAG9_N9o7~vJR8J}c+Rham9j6#!t(C3RkP={rzEl{ zYjsy~4kBe7=Jkxg9#bq~VdLp?JX`&^r;7Hky~gXW_4>cQ@>a~Uzy8XwDsi=czVoyO z*F2)MJVxY};NQnnNZHwXzxVOzAKM4JpJ)gPllWpDaF^qyUD@Ace>~V^2G138m{%!# zPHAh7`$|ES8)Q4adSka&2k?N6V8SN!!y9C;h$rc23wL>A;&G8oKf)MngM2DW@Q6YM zmvN3u{Lhwqn1|`bg|~;fek?atzx1AM1{-l@-_I4}bbd97Z^(Qxo!VD%?zOn(=v4}o zFe$6o5#;UR>Gqd>e_;P$57=KvV9gSp0*e?3%q?f)Tr^zD3m$xd*~eOBOteI{NqHqS z#e6yKk~ifp^ds_#d?~lb<8E=cR~&bWPZ#A@@!~QmVz)`WDTSV+Y~5@h9&i8pW!ti? zy1Aw$)3{Nt!L&5oXIkpWW13=O57V0VBE{{9FP6+TSu?eQe_y`aKm7PB(EVXe{Wc18 zGRnhBy`g!GdTWc2#%Jv~y+CE!0}1vh1D*<)M!90E0UfP;X!d4|tX3==0)9 zQy$TM+$a1Ki;R);bMM}&Gt86W|MJ`F+`wG9ExguokBgUXOS-#A($^0CVLP- z!-ml}@Nm~roaI5BFLxZFu^6h4(JXFfaI$dIUHq82mKbJ?+yfa0p z@}=W+f2YIjIWfyw6Aa7KRjVFG-3JE0?Y(<>@~RDk!{H?DhJvIH3QFP+)VmF@L+s{0V&B_;yR%(6 zvJctxeP;GIanDMR0m6`IGvei|8*umj7^dmve@&x53r(LlYdCpHALh+|tCi4YMrc3{ z8}hWX>hqe?uhHLw`-bc_y^riqkKS#+eb*s-6jVyu!aIyzXJ9^_$d0LTI@YScPB+XPgRL|)eM}hAJEC@d-d0!zr5K!deaj1E&U9_ ze;l>xV9tCwtEQasTN+C_)4ony3s1;)JhV2-yN=KL{m-zwv+2-Fd1}seE#?B!!vOrv2;?es`(~6+3HL zLIoeaac|UXk_fRHES$D`qMfoYdRz8Ie-0iWJ3w*kV8eA)p!b#Dsyak{+xVf`Ijw87 zYV9wtFpJ1Z5Jm0N^FgHgj?0%6{$D#S4_@MLIwT($;YmF(>Tw6-p)(Mk4}s2E-D0@` z6=CT|@Bl#RU;gO&^iTVvJzB;`pZH1;jx|%e-HJy z-d?Ke{+5vU;iBeui`cStN$=l!YsIL=x(e@ToqD{h`?ua&#%Z=LR^;xBU3yK+@Bw0P zESq$HV#;IN|8!O4F>UVOa(f}8Epy&(JoH5#Dz9~Y|JHk#4ccVLHW`iYcQt?~c8Ha0{I) zK{GWqGdMvvK3xhgOl59obZ8(rF*K7g;3=0!j|>ohQjp5CP+Ek71#b)GA<|M56zl_9 z5EQG0KnNiuOq@uJ8U~Pv&VU4&sFP(wf;up%I?=>I9Y}(qF$StQU?2o^;K-!z|6=mX zUgzvb&${2Pnb~yCEEAZ_>Mf1@2#n@T%~8G~eK%;7F)t4}S+*dpX#5A}B-Wfvw11fB zzn18Kn_z7=7Yee1pI(nC+n`H!@!cq&g$=L~Ho<1- zfi3VHY=v&wSCeV0FaM6U(Xd|GSbLPTB-;+p!!CFMqIEkUdbLyb!(iIw`xCKj2>N7y zlet-cOggvkihGjpM(gwd@N=$tbySxJXWxsSs$&Z{Jko_7-%!pn_95eEl zk;&|kwE3(_o318qoJ#zBE>aS?PuHM28D(rha!Nq}v10l7jT$lXTGiZ(?T>>$9bM<54yO zx5Bv}K3BO7Uz>7Wx8rRy%u}xVSCm``k9bF@Bg%x@3A#5a-_#cKmMGuZZ_0NZkCLqU zGUZqP7$qU}7HCy|eXpr76}k82K*oIqkYaCB;qK$ZNwJe+Z&%^L<7Sg~U#r4@zrUGk z>iQD3qw#_$dsQ_y7Cng8t%D9A_fBlROT{~PVg=dtjVj)|6(xyqqU>bciLw)AC(7Op zWZbzB-V0>c$*vPy-=X58&tt2dD%Ec>m3kVY+@;d!;#8jhHsRCpY(S-nyD=J6xp+86 zdsNK65ihLn@Dt#b{Vd<%jRZXrC%u delta 64597 zcmV)~KzhH?rZSzSGO)2j0y8m}VK)LOf9+dskJ~m9{=UCLA8mBa<-5ovEs(U?pm*Ii zZ5DSQ(xTAXvMt1xTuII*_v>%?B1^L67p-etb0~^bltexxXPz0($g?<@1vq$fh5hx_ z{ngDa69M6faY=*wX%Nyt!mZX}a6bv&59n}2Fvf$sY!WY$bT%AOfd{{24_WD&e|K4# zWa;p?`+qnng0v783I`(^qL53Egh(gWV^Ypt>vl-RAR3oh?(W~@(Q00JXclOsC6yI2 zK~idm{3@Pic?@GP8B7ub^3kEgeUg@$Yenwz?uVCmt`!f77<`JBt3`YbPY4+-VzVh& z;ks~L##ve-scSsM?mEfRcw1VL7mR8MMu&)L4!{-=R$nIRI$L+ikV`~~th(Ms`G+CF zgUra}qhG~5O44gTSvqkI*sbjXQYor+*vl+V%Y|Pg2tCgx>#=2qePWehe^h$^?&Y1` z{f30E@2?0na6keg8B#nDSRf9{9WSr`xI)Ul^cVZ6>h2%h+%8%0U3T>|{8xciT}B>q z)WCGCZ_0v%3Nb|ju0ljWpjITe$!wkb4Y6m#5hI47q{YygVW?|Pt7my_8;filEt3C4 z8% z4vmPXfj|jnSv2he;N^`+qP=#VRsz_ z=%dwXEAc?AV87)JFV1y5N3f8`ivgYQ%KtaP4`HHka~hi%r$_~6kGokv58{chY7<0h+ zl-%fLoksa**MI6vYgdy3yhSLg5z}2wa->4l(j<1BR41i;pI@=SUA6*Xyccaq=Vam5 zTwV4g5fNcESGEzj7ogE`UX)Jwz$qj3E`t*Y1M1-wv#u3yf2}1HthwfL9+hq(aXL1{ z@J!+qES$Hgl&y{bqY93sB=gM=sdI0Ocrr773V@=AY+ZKQDnu%bk*7#~kK5pt+ko{d zcVe0~m5=UV-Q^`GD5M+5^^iDTnlX--UB|ZM2-hdPlb0Eh$BU?pUAtJ1$8k}(NXT1< z5ry>;c6lN6e=k-s9ME;2#pezwfiB=!B3q(A$sWl6z#dvC+XnF*!cQ4?;Sumul(Ycp zaRYnaJtwWLt5ZzuDN^dT9ws*~YR`crL6YGSHx~BY_@AaV+AYEM?vJRAb{(hcFkrXd z)M33*{RBC6>8&LvA74M(V5>u>1Svv#Ev%a=S~gd9e}FCWDN;B%SuK;Q-B}=agk3ZtHku%d`Q$Fh8Vj_D5C?}2~WDmU{tLjSE? zqnc$ae?>6~24qupf+Q8NhX#zn@u^Je^Zqv+OyCvdo{%W2;L&zm!aoK*!e9}+gCwd2 zAPEBifrLw*_93|Ocn2Y*Cymyi0o5^_L;40U&R77K(guHL3BgK{fG`w2j6h(yTJK*( zZw%t|+z&z3`sXHrg%eqUc8qJ)NPzEQ6ih{ve}*5Z6HWwU5x5<==Ch!A`^y`E<2q1a z5)fn=M?eu5oAB=DrU%k#y@K~6X>HdK|5E5tdMV_1xhg+j3OvoyMUuu*eyIuSq~{Xo zv&zjjKk)1t6E@^!=NVIPjDE(1HH6x%an5aabaN~4UUT`e(%-F>vpaU$qJarp=Eih0 ze@uJ6*O60jlN64^bEMWEqnFgE7WNZl9gQ920S!Yq)a7|Q>W$HFM+(j+?LW-%zrIs_ zIhkC{qh1R5O|*u5^>Pl|eImFJcy_sEL&AP3>`%Xwm6|10^4uMX9==5Mn6Fcj;QuY zkUU+GX_geR{Y9@se1btds;jQgp1Ceqz;^SdOPWogs}#TmlvIF#6QDdtfgPkvvO zc|*-Vn$>n4!4Q};u~GEb`!&fVWVYuivM)qGJ#wI|+eLUtiWc=m3Irj)uBvne}I>{c!(^>ks}%;FvM#7cVLcXV<$eV!9l$e4CP;mo@gs=*Ji; zk;Xo2RHs}1zHk=cR81Gup%P&-@#@3nWYT4i5)t0i#u1da#<*{zJ<5fRl3KYhy0PjG z?riAX*rv}nW>Mt21FF6KLx&4je~1%Ze+fLo-GdISZKEgf(q}hk@v=8YKVHI6ihTm6 zj|MBmXCCM5s6WPuI|>mN65wHHxcW|u&&Va*k1=0zE>S*a7YoR%FU%MHfKnW1q|Y4B zVq|ZOevDKCDO{Cbkb};@#kofO+!XhgR|>(LNGp7%PYIui5Ax3vWN(aqe}W7tBG~64 zgq|+QFD8Dj)Vw!@W*oxW@OTJKe5P@hHhW|A)24u<8T(|2u!C{5Kq2OT$I++8(e!$^ zbwV6XY+7>`WqKm?BMj$217D9y`03{VR|=wE#pPohr+dR_sgbUGzc?0>_lTk`4`^2e z+~)a#qo&>Q`lxLkb7yw5e?0FN4y+o^WTu`JbYz$K2sygn6q^OHgh_4)f{b?NM zD_;UL&9miBF-URqlh^iZ_W+GotCo!hBZcj3BT6CE@?ZI0J~WDYe@%5?CTNN5RS z{(gfAT9=rZXQmRxT;0#uw%MvPhkI-BrVyO4!M}$J4?J8skNsd{&DEnFjNRHIYD(*6 z`2Sc@8zL6cW<{+LhS7i*w-_levReMGtd&4YLbqxwle8$KbZn}6v@o^Y&PUMppKd5B z+Mm9L+7~;$xc{cBexXH!Fn=t=aW#YeYn9y%m@kg9cEa~xza0wLYwe0#<#MLEm~|A1ufAwcV$saQgPg(|GjSx z9wUzqMoG~R!jQw^n|B|>C!E|QIQi}j`|%H#XBV#+OEl7w%H;AoQ4(p+6G=GII!!JY z$xo9Xin=LQH`5tae8SBjCiQJOrDAelyV-wi<)-r~5tC2Z-Flh32j$9*ez{xKlx}j7 zf54coazA_P-U#R~<(rFFf)4Pe3M0Y^P-Rj6>nf`r zUQM;|@7fmvLWMvg747=_+hTs}b}a5@W_dDW0wXDtnPCO6#I6In?($V*s1|^i8$N$f z%D#K|ezq)rHQ45G&)t)|JgYaAeZ@_*OP0lLSuUQMjm}DwSmxvJM^ov-HXw5SQ2Y`q~ff`G0fWW?*r>z>#r!ykc$CHKkYa4Ial@4x4BiYZ(A~}VA}oIqmmR`? zDvLV*v0UU!hc$_y4eH8;YTtP7eaH}|08MJ2zbosUMxap83EdI@?Q|wFp8R{a9SemR z)~D&;Xc*)4Pg2B*b_CI}`bRk;l(zg>faEZllxCn-xNvvn?w0N@KOoiKC*OVgXG8!5 ztfkYU^N17)sIurJboX!&$TNS35d!)UOu|^*B*WXk7(BV&+C#SQUt9zv?FVGmKOeFF zSg2MH|NgZAXRF260{xG#1$Yp9L)RCzQ_dl3lGE&TG>ma}$`yjhY*mgOCI~#bhVdkV zM#C6K5EBSfPZ9r&z$g2__Zi_Na0rYb+{eE?c^OF&1=n#BTSvnf$5wwz5TnddBKCP( z$^Z{GBItL~@dFn4KmdK4Ke*udOFW9|z=t21KuD>-N~rl1qj*5f{{xN>aU9dnVx*>Q zm@_hLk)(REa(A^Gn!VT&$XmN8`2IGl@BTu9zV~ z#A)U_8pb$t#VL|hIBI|7UVcNWpRzBW^7azhlk@f&?+()sGNL_#8zj%?hrs-Dz$%UG zqd*|LV|qjyd4xOr^kr~)_!7809D$23O#ZXeG`P|*%9BiEJd9DM!8K^SIju27r3X_U z?hEOYC>jl897PHvO8v2#IzBf4Eq5niMyC14Y`Mvr{AE=|BQ<{khaz;ktxv}U1_?-h zp}3HaE2N(s@&&&g6``YQ;p^Lz)M7M@acTkE2MYLP>57gnsA${4ynt|HwWKIWX zRj%?F7y>y#kc5AH?c^(}+O{M-t!f<)<4Dy`5f(Dxf+FRM5rX%XVAP!Tc42V$ks9}9 z<4Hu1hB1z42GtVtl`R>4rppuriH;MdeARMty^nW<5A(PqQi$)5P9a)gK1-Q_;`{jZ z&CYzXUvvCEFT(A%!{NZA?e#Jt7w9=NJ3N2xfJ2dgj{Sen&6q1cYZgA+t#!VtK1u6F z!x*P^U_qRA7)0eKLVr!b`8itOFS-T7y$y$321Ni0Taq)%~^fega2ZE6KPTo@eY!BHO38qi@ zxNRV$Onv6Z?PK0P@NxSD1bV@ZQK*Zw*N)eazA{1Dt`57o zxwm~C?m<O(P2E`CJ~G1o}K_VCnO=oPEF$yW0Sve6D4P(tGg9)-DpouKo)3uFGX;uawL zc_b2BSh$7=8N^FqztW~S4!Ga87#SKNi?)C5NH97TqdJ{XG@U^WG`X}?!=rf#WLF#C zas(@e@6_&6%%r=h3sAcUcfAHhb_@D6#s42XR4%Svr*9xdYrbn!#m#TW*#f z%PMa+)heO~Gv&hj3>*<_8}eSdg(`ng22CTM=R%!AD&<=aMeXt@?U}~Kt2B}3!-I0$ zP!NGYlB;$ZCXXS_Fl7G_9tI0vL=b|UR`g$xZXd$|e)A)U5(kLlkBNe0yI&&_R)a(p z$M&&Tol}a48)6|tLh(>kt-J|#K9@ikEUoW>8S5oT8}Q5wG49AXkk_p(fOmh9!fFph zw5xocZR*^;b?@J~w`y#yhIm_s3BL@3m9`rP`VN=Z?t+*@E`vhm=goQGozDPb#%Cl^ z=O*}JJ;~7xGEtiH$shCOGRv#RJ+LmrT)fS48{y%SVl2&-a(kPpMc!n^vUcB3EEou3 ztD&{JbuQAwMR!{1c6k)(L+yW{95N`nee4m05{gLw$+qyA4n3B~D~q@UaIF#vK|%%v zCltfIOq&7gTtby!L$HPbYox1m8+Zqv&)#)@0} z&C9DITg6fcNHO{@it;*Uq=2(lryJ>Kc%A@NiDVDMbr3_yXgu${!nl91lR58i_|>@4 zvla((b-|HJ4PJL<&1dFf&p&=@$E(mUCvdRoynf<$Xs7$pH0Y+HTU|)g<0h)vHn?w)FG7+3# zg;@o7MP{HeSgyxFdw5KNMhc=H1wV*APk$c|j|4Gpk^+o4@hgAti{`c!b-m8#&6X@# zpp32bW5p8T0x3%N$OO`{zJ20_6UYwnn)CGS1H?y+Q3u&95GEoSEPCczv11SwXq1ey zngn{4Dm?1G5z7Bob1tfmIFEY_#i-1mv-i^7iZFI zuf5uBACgXorf7*1iqw%*Y~NqsT`WkE4sA*CXxy9WgCh`F{IHAt1Q6~mJ?_0Zt# zS7+xJN_#@ENNed`-FSiYjPO|$1>V)ddpA)`O=p60KKZ%Misf`BHJ^O5t($U9f9;E@ z)RQ=A%Br6JcJ(dbDKBD?kp|(oH5wF z4|X&RyxhAy`_B-;2<7QeG7&rlK-2jr0HC-7CP$!*aAdY`6b^j;^1d-FM1*H;f!#!- znGDs_2m;uRqQ|*78bf%5@xg0b|8nl3JaC5)bOYwBBc}ZT;3L3NWYfZ$e?#k1oWWe? zd-z)|z5eGAs)-ctle}E1-^lFc2$GUeE3{Paf4S!Pw-@f0)Ru(@ zz)AQ=yn03U!%7%;VHwO#YX&30@u43!$urg!||gXcct;eKyH}u`#!t} z<+?2EW-l-M1PbY7x5!e%3^i2U!#n>z{LBlPge;! z=sNt2fIp0PqxK5h;fK-l?Dc4jWkT`au({psI4mIbM=hdNklMQe&+S$A+z_~e@{Mxft|Y@xeLR~^8V$v z@S$=6xdPZcT%NvB@Tqm$~Ekv zo5t7n=xuvTe}|W6g`<-*W#Q!Hc9kWoc5-|94%6#Rnq==em-cEN*SN)-^O8R5CN36n zwIJF>iW5I(R?@m#6Xe9#0vqXEawSHM-`)dG#RRVc-5E}Zo+<*L`BHSQ?kKotSQLQU zqGPcD!r@FXKXMy)H}YN)Fylj1-4WsY!Kcf?k(Yx--1vOX}(yAbjb?J=!trx#eGyrDJe^2>G= zR(-emJ&h0-ixD}+bVUm@o1Xpr^hb4XfK1(9Nyxcb`_YRL1t+pe0{k7?Ni z9LwiUu|<}`MmqksMS}iEU-s1t$m?vq&0)LKe{x%sf&+x8n`)ahEwGhc1f1zkc&FPW zkL#L38$G*0qYFIPIU;o+SR|rDjWq~5!>~L9Xx1O{=VB=52unC&G!<(da`eplhxB52-=ac_uXRg5NfVubR*iTZwRcigLSLxtXP- z2Da|0NxG(;!)caZXl#oQF5J5jy00c8t7*V)vW_Km$o>*B{k)e_E%Wj^&Y|UZ5nr%S z2@=b?owHKNUN=>|PHpNj;8{t&T~LC9e@sMLRlCpxeM2^3tgOJ~8%i{2CETC9y`iC^ zY#gwQ5H`Kpq_xc#M6-%fPvksAKp8v3fJf;yYgS`Ci;1YgXzd0bIYU&l?A-O&gE zCFurv1J;ZXq*EMR$JP>-SrO+obtQ2@AlHtjN|O>XT+Fu7Y*$hw4XPCBV+W8GfAo8q zI={yc$*@jPfpKBgc}rg)=a*%^b>X7#+r}hC0bMY&wE%@D z>bkyv=(hd;Dli{jkacGnD2xNhyqSgAoJ~)Fx0TBQY6njiTNlt+L;l=nLq}zaglK~bJvw@bx6ah7t zVK)LOlWwaKf4XcyZz;C5MYjaoLst~4tvJMF$&=)!*{|Q>MY7e%u~{__9fBYr#mmQY z`3`R;4i*6pULIkWKD{_PIb$Lq95F6waB&$#G?4I_BvEiN58j1*G9?(}@a=@+u&lH5 zS5IC~-e3G;`w^4~Vfx`AE4}I=(8))nrNqe-5AJWxcK@Bn~rIP!@GlrK)IZ z2g!m2C6dY(ksv7(i+FJby%>>Ut(L1is~h{J03t0KH6dZzsIsu7<)uwin;4-@ZdH{Z z^K7XajYzmq6Dq)1V1ul%e?_X8l}l@;h=z4m)MaIBmRSm1%5?AA zmi&bUe!i|MAj9;}tBDA2n#|T%u^{s_Rk^Y8&9N<@7)$6!w4ov%KFw-1&*~wGudlL9 z+b)j6a$YX8rn;F(p*_wi4a*{Pb(c1^9)ZlVG(?5ms$8w}w6Y&omD+w>maf#8vTi$S ze?dQ4P5SvI1-^jB*UuWo-nORW^66(#oM|-}Xkh z6>T7CH?_XFI3ke20SO2YEam}=BE-1}X3L|0j!^7le|y=M zy>)Y7U&}THiAZb))2o1FZm=iNm+|m&0)w>pOmz5AWeuL{8QrzDjd(Yp?V?GpOY5sr zJMFr#pUS13R?t*JG_!Wvvygdidzom`Mb92RvYA;q&ouj3tS6g%JvV;0$OFWCd2wze z(kyD(RBThnXmV^zW>uCpS>3Wmf4N-G8hvXkhoz-@Yzz%F+Au@LC?+&um?9D<+Uf7! z<6sVTAShx<99)~0OZeA|SQO;JInbwvAPEBmfq*)9A=v)-7D7Z1>Yc#K9S?NplIe;O z0&po&Y#_#1LEDkWG2#ii8-aklNwQN4e+=S6{O_R6{o2JYFf9i6KdB4y$Gfs)#kpE6(|Q1iQADE-NN;8J|30`sGP8;t0>|_=_w>{f z2t0IrJ4bXA{eMUF!*PctVjO3@G5k0KJ0pR4dw4xK`ghHY6r|qJe+3P=1Xi*x+|v1c zC?+L>?bnt!_Mp7g0dD8+Ap*m0ZsXk3VXRF9y^o^9igj&%(n68r0jR$EhhS+ad<=h@ zN<)wwR!q`0zjHD(u^Mk7@8c)aypiMh>5bvXPZpsVyER>Wd1Sb)5rO?Y3_VICZwx<; zC`Sal>mu1d9w6w8e}MXsR*PW!^LHJOJlPqKCnp|AhqVgcnVIg1jnVsn?heHFgnwz~ zgnB<~utYRT#<9j5!;dwvl5yeZL06hAltDG50noY_R2KiFp0t?av?RArtW+=X+NEW|TK))N#jX ze+)m$3xQ<&f13dz50v+ye0!zBA1J?}ygT-eqP#bTALThg32ATJ=>z3GD9;@`#RKIx zly~z-|=j{V0!U+mQ^eFQ0uZPm$%;J z)F+04`bE(TTY_e*RWI6M?GT7ZQa`IgxI6FDFDJPF03N8;HT#Bz+GS5U0lAV+`|}2&WU$7_d?-$nywkx08t9=@DzPY=-zOnb_>nyI4 zJX6c0dbGW<%52}gwpSI$x-9j~c2^HYzFs`ouFr*9t!z)=$4dpnN;_;`d;{j_>BqQ!kJEIUhmNNgY))pG` ze7Vdggo7Zp-QiZ8&s?XTVD5j3b+IzWqSQ}H+fg;syF%J2AJ>V2`(*y9rOqmQzczDs z=F9KC>pu?AGkfQ4QdX@r;_6>Uv5S9KcNZToFc>NDuqPrEVd8PYPyqIb(~I{X0&fO= zU`9k`HvbBAM7B6u)YrP!Iedg5?1UbBQ<$0iJ&$#$<=; zZG5?W%>yq2&I@KHV1gK@&{GdxfDb-6&ybx_lpqqyX4IeTh(1n$LeUI(muJf))2eu_ z;wmrR>_Nprh`5ZJS>NwxE)_^He4fQeV~n#n0|RiY2sz#0t0KvZcX?9k0s8HubxjBz#~)( zBqFfkIE!kdF~(61rcz*#-6!^_Hlz`g9H#NJG#ZaFN+TvE65K^r-qR>RFc$%f;aV)b z?$5s)*J5(7YyDva(8%GZg4Q&?w$Aw!(D^J+byYk*75=;q2IX;%MHod)oX4@z7~?n= zaX4(bJ-;|TK&N|>?Z|)a((%MC|Hl(IY11`1IdL<%Viujpi_sY4coBlK+?~3^|Iftz zLRX))&JL$;34+n>)LpM58OpIVgphnn3h!uZK*@FzpG1VuJmg?-+(^PD4T zoVml%S;QNSF^+gVLY%wvTl7s4ui*%NBH|fa4y{G~(yjBP2#$Yqn`0Ufl@LGKT8X|Y zNQgG1Uy^;C?rv=VYmBys&$9?U7GfNq8H1--b>ufiXX=>8ey8*4bav&%v5)^w>C-9g&gExOdNjs3O5+eQ;a(kJeDqvL-NF1E zmBwR?Qz?MMlW>1uh%hSs?Or@+)*LM<8Z&>}sQx zDG-rVH1vPQ+pocTYhhZgBmQvzi;k;uOYXSPs?tuj`$uJ6KfNZoQ>eO zR&HipAyFG@na8T?mch7X&9ki)c+hHv4rx5K;!g=2LJ9v0jo+zMmn#*U!WGJ;RhkO0 zd!A`~Yi%obOmmi3wl~WwWeR6t?P(zS69tz->WP8-u9&{ zpV_T(!GfSoxVqQVx|jy!VUW#mzosV6(*~m_2pp{>^%msky52_D9NHCz0DM5&Oq$Jxj1KWC44W}Gsw$E%L#0Cj3Q3!B zH`RYjHEr$Hmhg04;g@ye{+~<;s>Q4$P?5yjvpc0jhmB^w!a{EQdJCwmWU#@ai~V)Dn^ZCOBB_K3LLK~ z^P7W>Y(bq}H_N`Yi=vzIKAW`+X2|`=d<_jDH${CWYCDOdt~L-$WGm6JSfj=}noj{w?$Q?FqC-FTSUWlcT##z+k z!Sm;Kr`;@(`zqNpj7e#x*p$Gy+vI;g&<;)W#bae+0XFSc%i0&s+^BoPnM(5v`~^eH z)U0Am+{8sysub-j7HiSuPASJ!9EKc7Nkj74E&Vb1j)BQ0@FZ2Dmakyn2@%}p{X?)n ztL0jkLrD1wAi&gxv-N(AxB8RL?sc)aQN_nKgv{!PcJAJzHF#ZwkG*xlTp)k3*}ylu zZa7JYp$$6(!iqGJus#m=OKM?%5C+(m)UwC~pUtSIV7T79mHB2DSMOt;2iRECaRuW6 zZI{~*+8HiC#*j<%begJWm+ib`&wjeugE!ZFU6sj9Z~0vr=PTXcZ*HbSI9gjO3^`wK z(-R8BvDsKcERG!c@J@BkuZ9Dmo2Zik78J8V)GGx6H>+0OBEGHIhZISQwe{L9`IZF(6Dy83S#l-0Y4_`Q5+%oS9Z8%fAQ*~NFC-uF?w&i| z(Zt@;!`_=Cymuw=KlX@62thf9?PA*p3J4=p! zg@60dvl@H01O9*d3dS(zX`}@e-qpP)smHiN1jEz9yPjNx%S{?gXN>t1_2YErOF5aJ zP62Fk_5SpA(ZD9_D9LS?nO0@ zAH)2?HW7^N%{s|~%(niHIbLk4`Q(Xxd0t_Ch_WPx9t3|)Z?4{g)F3m`yprVV0fteI zCt)1sp^5B6kmcdZLil&Eu#b6a{tWK& zB>g%Sd~$4GTA_-&yQC2KbAfKs(8PBYN)Sci8pJ$qe(^Ti1f?|JQ0Dw<$NoYgMZj`| zA|XX#+3SBB>@A=T)PR^)-ecKw1%C`NCB4YI1d=om1Yv-{krI9zf*p^)K`5BhW3(nn zr~|`&!HR|f6YzzAp=zKO3O!P-ke0F?fxvvVes&h_7^HIKzr6bH-PS>Uq!pM49F%Ja z0uUiELl`6|sZE*;K`<8iUU5yA-tOaXZvf8M9!!5tfRX_Ybmemf<4U0K9Dp3V_XV8^ zj3+-^7X_~x>kG@&tRLK@JsxW=bwC;kejDOmhO{PLj0K%6l2wpH=9?gu)1- za@Bv~K8zRVcHKV%(2K*M1XDzbtOpgVznv^h3e=%QC35rmUBTb)_ejt=;IYUz9LFHn z0f)klqbODn3dApaymTn(e2D})>SB!{8aq^v*rR>>lW4v>V=(pCC0uXN)1GgzD< zskd0@02T+wsoT#&vrJ-h2*`)!ne_&`43~c^lXc2g@c$Y@5`Q%<HHL9q(* zUc_q!|4=IUkbU4&eCJb86iDCO8M&U$2&I#7&q9s)X(Yr}vnNF1n+|SriIgJ4$mxvX z#!dl6gC^Z*gucEe?4D1sl`4UzC5C z1wHG`> z!+hBp!_Ai|B%zvH7nJ?8w2~3?z*2v%HM{D})INfhXrFZe6tQl%9M9+JF-+#mB&N);f~?N526|JbydOZ z{`}~dg?3rN*rjkk9~OxC4jJRef~yy%*erj})s;Y4sy$afoYFpRKD33P<~DytXDZt6 zPK|I@P^yDgw(cFoDp!b}q>@lc3P9JTM0QiTdl@5DsWeC;XAC!y;4=hQ)f^eJQ4Y|) z|I%{O57m!PW8rVIFkX%Y{yz8|#J54ZbW`Tct^3@hpEf34x$b|C;TB0aETp(9*Gc=Pc_UWTKM<$GGvcksY)Sp01)TUC zQ7#--j5~(I~dt^Z!ud{HV!hIGlrYlC`TAql`Zl6o2`El&W1ViyalRh zx#zw1soELhwxXMq`;}Fj*Aj_1Rs&9;6bKT_e|Z9>&*+X5C<7+2C9ta&YWjV99*a;4 zp;eT>glfU6WgyJ*A}=eC2ojY#%92--H@p4yXDCvR zl~pYB7zVa2f`>MZ|kAKqy9Y(jYWsnJEMQ~RVTtpt3iy za^*l4s&cKYw(kn9zX05J*6V+= zYFc<4-jvOqGXvi-L&6bFD4?{xKWyN0mC>&-Ul=eOXDAk1c~zuVM(&7^7%?F`5oQHQ zv?CEC&XZ2yH;m~32u6&?k3f1OkD(QH0x)J7I>T7)SE{M9g&xu&7D(Xj_l>Phhf1$2 zUF)K;_A=&fA3vCT7I7KQ?{sVT85MsLNlE(VuXU~$ZV=qgt+}pLs%`6Irfj3Rb59oK zYMtfo28_Yf(ze^F{QcMK%in*Q!2JI@iE#M+gb)(WFWGiAYmH}IDxtyO7XyAYZ zgkcnO7BHZA1lPst?86y~63J;RvD0i{b^Y9f^Q#rX!9{uY3;cEPoy@EQpY4C3TTks7 znFb6qL@2eExyqKCmhwCblW!+84inZ=8t&J5X{^p!Sl-$v_4-bC($?S9YMr|WzhREk zjk{@G1+Fi%#huc*y?L&5U4s~bNfVT|lh)#YG+4U&Y{l-YvRK+?R%A`4Tz6eJ8SqC> zw;t98Agf5Kt87BKgG%jO-By3)%C^cBe7u1#2p&%REU52F)A7FOho@zwb%Cst&pTF> zYZyZISBKwJ>JK1RX-2*WveKyo`myX7ccXJF^KFkUJFIz_e?w_P11cgUg;+8DcUH^57ac(nAo01;#nBi1#7b{`d=om>$$Sf#82F2f9asnHNV4 zAQA$}7UCEyv~~mn61g9Mz;Kh~=|T8H5a-5!23_m<);l3kNthfH#uLP&7|>1lx4b5O zdLZbEAil!2S_ZqfZ=V5Llmrrd9U`y^*0hZSE}(wn0puxuDCkT;1pmppG&s?zzOby+ z`p!?=>8Zxj1+WvrcOifAE78^^9;blb2JjQ%7iCuK#|!tDp@YRJlJvOP;f>)JJR*X4 zLafu%o<`?a96uQ!Af;8eCgZW0*=`_-B#Ov3GyAWV=tDv7Av%HEtVl0yW^e(ZSHqwL zQ$$JpkZ*Eq2MdD&b4cM-?%zK*{Qb`(5{!1Rc?&GN*taM0?a+UGYJ9u&)v>l9-?a}1 zIY=Sdm+UwWdSm!;kj6+RY-g8n7zbC79_0gEVL+Ama00fz{PGDbvsFsASZDx?L-NqQ zzsS_GEYuKC#1Li&16^m!m8wT|Gj8w>A`|~^(uSp8lMJ=qkFW(SgJpCaTf8y+*aBNM zlDMr}^oT9&>5PBo-H6GzdB7tS3R*odU^;@bvw}aKxfqFu4fA_DBSYkb4H@5V&ht{G z+tSB=B8-e|U&QWlb2{cQPx;-rrFt+;wHX>rPyMMilZnOqiAxdzx{9NS>yP0_Tny1X zaT`#6c$hOAYj!bz*gSq|Gbs>`r3V=frRnr!i|o?3!|Z?Pg>s0IeK)#Qd98<;z3Xa@ zhkn~Dfyjf8oov7K##CWWyB9kZ{N>Q@WYE_oMMB2M`MNiTm#-7>$ha$Si*b$Mn#klh zjl41ZG>T!70IXJ{_@7p0c&pXP_M&R3vf?Y*au?#!vRdxAcqw=izY<{<9L%>8L#(PCCJRRFH z9-7*Z>e>vJ;dUt3j>j;n``^PXSK>K}S>6~2GAn;Zm<#Ah5ytL^PJ;JR%l=sG%+LkZ zYP5Vb8dzTFkGiV0IO9C69J{@Se3qlv@Qj*`TPV0pwT3;$8I1q` z^PQXfTA+V$aQ8S8p%m635lDupbaDAbRyRah;Z9qbGfC#)%;l$ruGY=tV?8^Ekm~c5 zYI1dR-sWEB(4hMba@MYqXf=4w1_A{JWmqtSESJPxvJgMsPyG)mv;)(V0TvUto;d;L zkOMO@G?!sF0w{l-S4(r-HW0r1SKvs^m^1)_uiWfu-KOIlI?*l3fg)iEEgvdL*-?Le zcd<*EvgJ(M$z%X7c0cU%gDk~XNb$>+=yGI%Jvx-Ex4!%aEbdKKzK2A>~pKdrv4e^Wh%;zFqw{w&P3H-{dE=P{*V_hn$=lwbKfc@e(JA&hkrBbtP?V3 zxB#V~V^Ks!s#Ek=rAefX5+*T`EZFONw>=D&0#)+EDvXs3?pG=a%4+HdI@k{7en;EK zS=Rg@Qzw51=T(G7?C%a^2{q7k_s8y()`gcUGFb{%Ugh;Iu_~7JI15jzD3d44Yf^r; zv|0@5`@V6No0=oZHY+WIgKIo)9+V_)%RQUAX-B(h$0$u-m6Pi``syEf-Hdj4!V4@z z&2Ep^=qS`j#gWQ2Y@p|iArGH-uEGnn3S2i0eSLqZ?1-`0l#}!nQ3yB9@NZfAh=xVx81w+5-Cox#v{)IS>B=(^U^M6ZWn_Q=_I+(HHPZxcguUcz>TzyyB>pm?pVz0OY<6NUYI_t zI$nRnsa={fl247_9QUp&n@jOP(mPvC4(*=Ybi}EUF=Ymf;}o)PX~U{M6!`Rx;kjS4 zps)MZPQ#I;pCE8dRgYmlF~F{L9eN!XV8t+}_IY*Nd847^ap>DiA+(2Pa-2r4={4my-cDuCQ43&_?cT*Sekv9^yK;PW|6x2p1<94c&CJxZ*KUg5<=`}pvO=f==u)N3 z!6qXT=Jh=m*6*`0p@s|Cw=4`VkII06^W+r)r_jR+TMhbVy<pA1d5KR zLqU!m8lD=@zlq#<+_sSa6At!SbFc`*jdk0MJsq4)w&Ye{)_5AqKP)!o@db6THT#4n zU48x{F|gb2Cg}5pGZp6MSa#&d#dm*-XDHNp6zhUQ^2LZ_b2f!1zE zesMUEB`Ity6yD+xo0O)+03*B3l0=i>+0sfr(w?dTI%iZ52R;RiNQD6513-U{B+EmU zzYCYp)ZQ#u(l8^QyMkSDf#f=B9neu3d)B(fmFOEh!Z;O>6gl&z*60GdE$zxa+X=-Xd9 zvBcj(GflR(91p_^Ol)gAhI%AAzCezDc^(0SoPO*0n#Xw&sp33G^8ije$CFUO%gZyN zb-b~_6W#V^D7&o%fuSSv#(TnM)ZuUGpG5tuqj?r-%z$}cs5Ax7fkc4=Qyn8me)%Rv z4M$MlC@ymG>=j%1A4hSXiAH<|wmkz#RV=a$aMX_g$Xvbw01EyW#)XQ~{DQSANn^=e*_q@SOwRn=R)^pNXBt64_+PpdqV`55`QVF{)P+^SQ+nv=IrUwqqC#a$BYFW z#fq@t>>>~`5 z3kJ^_K|gp1+OJpe`b1(J{!*q%ogPa1Wtl9m4kdhAdGlAP5Y$-kZ5jeikGh^Tl}{QJxBi+@ZI1z9F+X~&||#{zGS@HSLH>?RK| zif9x!z5Z!?bmd?a$)>}fMLvg^NXo|s22Zv~B{)I?v~*8BFnadRxMGNpoN!+eUh^$f zgrv2C4dX|~D2mBAbG&8v*%L7oV`44h-+%b}@h)8-jL0sEgDo5%k}^xq=V>(zNFfo9 z**HLY%kTrF#E4>QaU}L9w2buejzokHk(p@eu39h7i}@B-Y}xC-SYWFcj1QJ8>8$Hs zKLz)MKi=~B-~%6hALxz%4aWo&BoBIw!6wWC!?9SUkT03?~`WwqlPL# zvm6&S-ZK261}0o#VW&G9PB+}<#3+lrW%yY{Vg%KRwMc#T`R~KS74pk6yOpB$y42O1 zqg?7O!_TEyAdX#09Pdx zFy|e7|5;>J+6Qo;!Qp+Mn;a(Ba-J8nbUqj@s7IJUtcB^XS#nwANuMCj5PxQS3wo7Z zE|O}mG~qS)<3ST`H)rI{?j@SL-I7t@@Rs2Rk4Pa*+=dPr^G2Wpo*%xzt?5}-rqg=9 z{_^&w@4m?BMWfp)8HGk~8GdM#95Lc{a|qp^thVh>cURCMMsVQTRjxHf!wxAgG;!Ju z?rjUZk_bo2LuUVW)n*QHJb%c+yAqae5q3P3u2-pu*G4(PTZW$#FqD?Wm6SyKJ7F8OMt`s-5Vf}_zWl74 zwz)RlJL_hy;u!-Fe;Hl?VX**Jo1!fGGV`2AX?>lh`R+_72F2LDWIAI1^rZh?)jrvh z+=mW3cpuKYhJsqgC}tk{5_2WnD13X%@WZ#Fs7>S5cX)5Wo8AMw*;fs3R|AfMx3>&G zc!R2(Hu#PQ^G0UMhktPuj=u~)lLSW*brlZ9-*P!{o+f3MUwViKLr?v>mq~tkuFpH ziJSfR$qAt}%x)>vU4D?1EvKIng?G@ZD-1_@!dr%)CuoEib$_)h_1OK}UFUpruPVq* z(KJ*lxk7amD7)V8q{<`(M=jfB{3(MV~DEVzIzbxwB z9Up=O-L!_A4JkK$CvaD~8u%amb^^3FI&CLh7NHv+)Q~^kn{$D3glNAU0?uVJe6J58 zEbUdji-9R19e;PApxW_o+0zA{2h9xU%+&2CjEQ4^8D4QrW2ghD^Cacp<9NTa@bir0 z7=N-jHY*wJQ@y+P-ETbE{fklIc2@&1v>6jp?dLHMJ>3Za4szPpOL| zfEhT8gG;F7h$#1(=~-6Qde`EF3LFyr^W=mP9RBuknwHDjwqBIQ!k(oQBEpZ!VmVK% z(?wFxlk?LT^CVBoSI-_k|IOY(i`$8h&?Rat0KT9FV9984!ZC`Y<_{c1A!)*ZvVUFJ zp`K2t2!HjDQszqkv}#UXnQyck*lt>fgA)i5DV<$sS1CNfNLb|awLZh)D!2MC=lTcR znY}#)wA$NQ)jVL2`j5lP-r^@xPYfpERa(04*G~S_{wroh

%GA-@RcN5}fZSAD% zAGA#0x>0ahRLwZnOg%Q7Et2w`F;tu8=-8OHs(-A*loeuwl5R`|ixK0b_p|oR8DlVA zZ9HDA@@btFIhufDaQJ&}2Y7P!>f!Tadu}XN=3A;Vt+dKf947O*ZT+Af*8U=9ng$i6 zR3V|-Ph+jmou*YQS_)T2!v&;Q47s70~Xp$jBNSvV`~oxG^+$yG9;+6_d{VWYS?p1bROwKxa-&g_-`(>%*p#j1h; zkpfnx6UJ$HuBEJ;Ozk#3roC#0+&Pk&TYn%e4hZbRHqYL#G=wA#ue16p%k6n$50{zt zz7^{3Txg@s3a_u3%|eh?Q-+UqM|}nEfCp0%5sNFh)wFp$tUHajNHdPXx#0+qyZNwi0HzDu3)PXIl)&&wtd$I4!yXU^FZmO|$%+Q|i1}Ii;!^ z^s`*(RO>;{vdAnfr3+O109+=nxhfW^YbnpOx=hNo#b;rGU8S{-4xz%c2~b^O`?h}3 z&ou{&0oCDRg7_Vvn(l6fV1er6UM@E=W~WRmn?W+Lw&$C1v#H1QDk&jsTYogj2&r3q zYyl1tY5Xd0EwOMT%V&03*DDtg!+#(~!1k5BJGIXVSc_77a-P^T8DiT|I6=ffJZi7o zCpIVBXfVsBY4x*RD6`sjniYmf;JzVb-2@4eHcg1osrI|m#Q~uI4G5$}3es1+bGw`f ziR4Y%*yMTw)}6>W1*%8|C0>OBR+0Sn!V^I^{WHE^csL}EC(yb1N-?o{7NhoPCIgO= z+v9oWlEO_taI6;(-8xH`DNIk3PZ|P)BY?umf!wQx6sVgbZlsExd^M6tfL6z^+Vw($|Hm_M5xNq(7G_v`R<)29~C(o0N&S=(h6BHSp_FG@K^)FW;I=FGyc!W`& z$x}ZuKL&Mn%nd}2(AWa{Uqh#fahI3`np@A6v2^Lk9dxoelB&o?}$w2ZN1(N zq)&+8uqnvlz~zrZf@|3&-@uZpZi0Uai#)a4tsPwF5%U{+go2KRreMuQIy?oDSGPi( zq*LUaDN{nSqv!@%7KvfyLKT5S1_%sbc}e;OGM$$NlUyVxO#9kz$dY}CYL7_k>yGLW!=z)@ceX*e+qG_}R}=ai(rBCA@8wzbn0){z4Uk$nH38_IE?ZL5 z_5(qmmtSx0iD=jL>N{hJ6 z3lUQ$XBwWLH*I6bkwS)jroz;QNDfncCKEQh)^=H#hW4RxNQ0T)BJ^EK^&;RuCuxDu z$RlBqI=`YT2>vF{p6Gv=CHZ#5v$4Zm6p$t2-gW!hHPvCV#>Zr?-9Y<@zg|W4c+%&m zgUEwlbm#kNK#ZQ&-EkR>uf|SK)&dyA<%nSqM1S>-#LsI1;lnyk4l8keW0-)yR&>(-%MK}2VE`*eam?8cN zX7aXiXCv^_auzC(C$O(z1{9!2nkaMC&iLtpJyu0pOb4Z^wh*|9cbw$PW+wm(m7 z9IyTcv3B@+cXLlE`5C`~SbK3hO()a~hsH0HOv6;=28B!hI-maokPDZWlK~bJhrH|o zx4i5EAv^*%IG15J0w{moT1#`=MiRd3SKyLbu*w|G3o{s}_Ta>pDp8cmMmp>|No_$O zL_r1t1^{I#DgXEFc>n}RP$a}Chb@;p@1E)IuOBlY_U0b;&QGu_zqvj+J!64KIAUB- z@A}r0)DzHDN_y8b?-yT8rUYZ`U)AL*u23mfhR)|md+sTv>;=jvnN3pEaMfyiFv&~;AWsL;f zlH1a9P8{bjgeF`1C@X)OnJtZFQKfaN$yiX>-jCDhF|9xnoCp59tSW|3RoxY4``n^ADxJAo+E8Kd zZJCs%;Rvd6p?7)E>!LD^^4LvHvMgOzN#z_yGySHp7J|E$ft@IzvMkcPhI4kENmCk! zwZ;WQp$I$>He!TX1~yz33&W19(yg_t+5{Qqh^T*Hjnx2Oon2a8>4gR-P)4?>llU&z z2K@U9yrkVr`gLJPL1#`X#wvR&wFsLzd1cOP)T{f9&1&j*?(j)I;TTX+7WvfS5r+s1 zD8W&4ZV$TvL$D~ep2=XmD9fZ;7WvFzNq0S@)hf!|#3a)G%z;16Z5cIdv#dd#b0t<_ zUAup!oOHd&DhCZS>4OpJ0*qo?#vEb|gc`RZT|{$hEkWQ{iL=edHS0R?s4bWJ-{qEh z8U{!x(&zsC`s&@KwmEJ0Mork6HT2AiJh8P^Wd#A%M62a7itFsj&bIP~kqR(rYqt{u zsElikTiu?Q(elpDzAg1EZ6|t8QGU`q0LE#mbg^tGc6I|8O{--Rr`rF;t=aYT7gfNt zQ)8eyn`?^|EYuP(Bg;tp_*E8_8W?XJ?BMvsH&PSWvJO+722*vfe33ob$u7P!^Tmj4^$^^Un@*Fm+LG8C4Z2-ne*r-U{4?=ffYkTC=TaA zTsa?@4w7L+dYwsMgV77=F9#?p#QOyAw@(X!Jphb z>C!m@-9g{mj;^2EmKg~+l1#k}@jVU|nAbs4gMS*4TSB9U2u&yHv`OKB$4~h>bt1+o zrZ;8eGB+4+wgQO2vJBVm?XGZVs3iB{D!?5j6p<23_R**Gjjod;ITvLW!@EB8haE3SRLgQ{G51> zf?bcdD8NnfkkyJH5e_Wpg6V-H4!|LVhML4tQZRC)0g^;LPeDfnrFNfUG!5cz_Mg0_ zcF|tg0jQzQl&;eGA{w9q!8=sl*oNtwAqGL9ZD!j6%a5AZU9<^^ zS4r6ooL}z@U6A!doIeg#<7te86$ZF4V!2^GTn*7N_sfnnST~c0423Y_7q%#$11SX# zc&o^C2vmr5@JVcbaLAD)V(ZK)(|>1S`n`rQu3ukuYi^6$7Iz!x?3)RJI|kprb?(IE z$6;1Ba><>52_faB>^Q)TrZEaIBn%f;g#=DxAY=hPQUBqe!epZ8aq z)vkPTjgMW4H6)+yoHskp5r4EZs;9+Gk?qLO!!4k|B?m$k3WZZrzkQ*vum9M%PVHUr zICepQhaGJ8bMW-gtmwHE{aIN_^|uIX`8Npb{;v?$#Q{Y2TwdH`%ux<#G>vf%h%xgc z5W`V8Iv3^O92J5k_Yr_ANPVULU`Co>Y5mZBgD2#zeYOAa7$@bj zZho!R{8Gz(`Ccruq&i(hbr#*6UY%Wjuw7`;cTQ6&&301?X62p)^oM8~($2QfAm(#O zsQjp^R*SaVej~QE#7kCsZ~f4ApVetd?ALVjdl2Z4vNDNgPqtyd8qD+_3j3cODV?;L z%3?zN?icj_K8|48|9zVI5*|X_okFmH8-;sEqnnuiA7$(Hl9$1J3loQFG6T11G6aak z12Z`@mti*oD1Yr*Ta(+i6@K4e!M9426^tthrfFunONPieekcdceNrD}ZA4rJkq|q@! zp&S^_L#7|hSO5=0B#nqUC>R_uK@_@Qlt5s;aeRIi-ZDsFWqb(QyXRMby}5eygs}iL zl3<>j+d#xf@Cd{U#IX!+(%{vCEMMRJ)Y0P66M+MX;xOcT0HKHr22V`atZ0_25aUIq z@~luvm4AI!&x%G>ACp{5f!X5T;204SwWI%H$Fe`02_N4)gigo^g|mS3mEZ-N0QyBZ zw%X9?u>D#V7OrP6fB40Mkk!d{0I?XfV6q+ePb{$Q)Dteyq02-=V2bF$5FnRaFhayo zjLAGRc+2oJL?jU=#A?HOh8WZ+#E4=#Pa|&`et#N;95Gm`(TJZ=>ts_MQ|r+q%O`}; z08k#5>y)Om;m z=JQbZmf?rGz$S1RUBoz#7)26`c^Y}k@Y9HeC?>*c6ngRKA$>@Q2yc7*T$Ve>j*qIc zcYn>sktoe>Z&jt*@USauRS&U8gs^Wr_FNCmiBZ&bNYXSb-kr=EXqta1X zyVtXHBoK^nG|zb6GW?838Mx`t>K^rsHzWsyh-2hnUMjlHzFZMT7NxyZmzY3713n?> zM4cz8A>6!iw$29Z%q8L^K8gD_LRf_0wkT?IFoG|_0(c(w zc9-8jF;;n6B|8VxJ99hW)>w>W)FtHSlX33y!da+!%kV=Dmda@h8}SWW;F{&Z#ruY> z$fH&|j#}@hMlF0MYRS0k`Tk4eR)2U1TTodK#jSos@QPgF|1NU9{|b?dyVQIZ@x5jE z5npf=QCB^Xi{}B5mBTJ<^*`qo`m{nLbcW=3heh_nlFy#(n zb_rr0AxgVg`cxIF%GNKc^1WK?xMW@P;2{-**eEaU)n4xV0#Zyil46b)Hh(YlhG(N2 zepJqnNzUH9q(g#wrT_QmN#JUZStRh5;YR`*Ax2$UL@pkVz=&8fkC^az#8tf-89$b! zzkW4Zvy6Gm*VkjEc~NGy8ucgFBdWZ--@YyLQBHO)1tSjC5fH#xvj6}274-d6&sGx# zeDWR8pW%#_S^?=(R$Y%K;(r&xlK&N~^8XlCevy0}tmjkmfwK(cE8#m*y;vQA}N_OD>)__DiNe&TDOpuvtp`ity7}hN#Q> zqR|5j=E|d43VF-$(>w(nE}{QtS?r z*ZZn}WPP5KF4Lc7LvI;=HWaW_*3vSbet7X)l7kU?ws~AP**0m0QVK#OVq(I<1v8oZ zyyC)Nh96{H08?FYK|RiU#$l3Bc*b&SC6^Vos+!4}*Z*_4GdWyOK{A>)J2SrdGsOM6mSt@zU@KcFIQ24v7jnc0g_5QI-wPQHE zl{9yES+hBLnOUg2hX?vYfKr!f%>mS3h997qBh1{J9LhZW>F~!elt9ux`8aHEA^!?a z^uqDn^phFi7;)J{P@8kkGQO_}FWb{t=UC44eC*hsPN)MYB!BUevl*WwQpphJ^b0>n zoHBakbHo`7I9SaSg%fQ#c%0k&IRk#`FD$6Q3qrqLt{B0K z$Dh`!+BLTIwko&wPA!R8d`h;vT-A?$TZZ~8wtbT8kJ=vFX0+bz`oVk!X{mtuSCpaH zRTwwg`DuZb+J7clk?OBW^xyK6!aCXmWpt8xtOR)CA1h^iH)RnN832d#%+Megw`FCY6lzJu;?A~i zRZ{Ok8>l8~1Q=qm_?xQKH9X}ytG2!LJHpzIj#oswr+c)o*3kyv?fLm zn`8Uk@6>=MMCf!oJbyypY4qKTr4S2!&VFqr+W-2<+%>p!@9ziHrWhD^@WUr2Ua<%Q zbr|-EKz}b2A!Md{)z_|ir6FG^?cA4S;d*h$4&6P^?Tte$zi)>(RhjPB25b2LQ9n(p zEO`riN;3y^d*-HUHd$@&EH}*U(H_)LgwbIt{YrjijBGyb;(ZhAm-Qfy0mhqTNij?f zl9X=Yi?>P@_L+T?Zyu%gS>~R&PX=`pu`Mv46Mv|RwR>c!VgwahXWi71MmHZT+>S^Z z`>aqZtzBbjo8B5Cfl+$8be}957$bnYu~++j0*&Yb45MsY-Kd?tGjK-C(K%vAbcPZ7 z06<$Hiorp(UE6C~7Rq)rn;BZ#%?!5`YckoPzm|>bc;_Zb>U!U|jU&zMewnB^8k)7-v1mOY10P$a_#<<6_@^}xR2`Zbt1w`~Y`lQIvEV71^&aL5kXn4M>nY5VJ` zn&g9aPufK0@5U{m=d^T#B{AG|;Ojpv_-VC~%#M4lji0w0ZABoPF=6G{pp8-A*v0Bm zpSaPw%=g;kIcMgUJ;BV)rYiUEHYeh?s@at30I*cVkSX-iY}9IY0o#xq9kaPLX3n># zs?I8vKA?x-NW|2Hd)a(HCx5MXWmH`4k~JPYIKdl-;O_20g1bWljWpH}9D+Lp zhakb-gS$(x;1=B7T|VCT&Ye5!e)DT)esr(%)P8E0>^im9p(a;WV-hpBHw8-DgCR_8 z%&hzXC6Jw|i?gCVSb<3uXzB9V)D{GI1Gtc>sU@6%CJ>N4SkeRn=OMo9x80|Wz|Ol$$lE^non0Te)HK(I5A z9$;bb1hDI*D-cX1M2T|T^#<2xdNU3ZV=sHGeiHD zgo(L5*w!6j4zxgKQGc?ByoChN{m)cp{=XCX|3KpZ6M_Fv5WwzM5dz>{oZZ%X>E9Lzs7Eq^==+x{$ug=ndVT9KZo(+aC_ zy4$eG(7I6Cm!!PFJ;NFYphpJYUuYR01%{V3`jS8Y8_2 zA!MgIeSczgo^WFQq5eEM_0}J#Q-7=YX7)mg)w1x|hw`)i$Y!PM=*PN$vYwApbl+Jv z@Q|I+=BGJEA>&0CHIPXY$vaOhh{8c-N}~*N!%~HcjR(b$xAs{4(xTnoDEmh6Vo!u< zBoJ5XHDGrBUL-};`O0(mC%!!9$xF;c5GTLDQ-6(WH}^Wy#n+#tb?+|U0X|M@Y`7jh z!YHn_;ZLi$vRPSDPyjU3{3FKz9`xJGIuG>RS^DZ}9(2(pf&ELOmU8mb?Af{{8)G%Y zf|F-A?8Hz8b+8ZXojv_KBXf0wlgdz^d2J?%r<;6l{dHGJPv9ClV?}CV{uJ@wSWnd? zR)0s3sVBnGb?8dhIa&dwdUV!XyJ&R?$Y|(9)a#Qeo>V)DO(2(F>s(2}7)3`!QV-4r zrAXm$AB=wiQ!F*fxP)=cG1H%*v+>o%8}4y*&YiFBXbCh>RQ?e7)nffVR~X8G?KNBJ z|Kip56=*u9%!M|_d@9M5pQLi@-oRn2uz!lqPejIHufYwr0_A))t$z)e5KSq{pn#JISHx8#Zzh2Ng8!c1wSV>@JwtPByS)&49J=p2V z#O3s?y;xnZ+0D$XXM*96$Lt|1i}v1d2Knf_usgYb#0BVR2q~A7G)@xCw>2AuXMd*x z6~z0BoyN`CqHda2hy7v=fH71KWA4{LoRQjn%T-+a&k#38fFiqJ4%eV*6 z@Z4bg8kzk^Xk|FrT}c-mFi(TPC?Gk9S50!v@5DK5_h)+tgG83-=Ze*44?c!lP%9K~|s)X_77w=-$yW ztncF=v11u1fa2&=duRGh?+Kyy^wPHqdsa;E#Ny7`cgxU@8Y!)(s|Y}(EP-?id*?6m zzW>C6=oj6WcRq|2MJv`Qw|MzULZfGgc#XA5SfeUH>$*Mxyy))_(}%`&nyi z!GV|LqipeTynPXXUw_{3x`tKAbDG~E(fP7Op~Q^>KM^Kwt|}3>OMIpk--Oxj%11{r z(_1=@1N-636W#%bs$e=(cH4l}2v|2i+5G-JoP!qD%)ynI?IcGo9^>qsx?+K?~qT)JegN)=fbyQQH*7s7^E5yrTb5mk9 z@cEdRRxZ|EF@N}=n$+XeE8^05^na!MwIo3?TC``})YdwKc1)8OG`7+8`Z-et*Jhts zRTCm{c*1p=$8@qzB4f2MK!wbwZNWFc-fOjPV%}(J&1Tfocx?P0F&_zvbwELDGUz%A zc0{LinRPswdfUIA*dsvXlnTUp~+& z!r1aGWd+H@^#XJB7S6I&rbPH;TBRRI%DjqK3>DlGyo!uz(&h9cn)l4h4F(Ka6!-uf z>4`@rs()^r8SUxhXhqf9z<`W?N%ET}Mk=!FoeAZd0XzR{0zVuz;)8Uyi)Bt_Kld>@ z%q+@69>X8q`Xw+si9ZHenfYy5B+i#{UfrT$3syc z_iT9XgKFF#?x7^&6E+GXY>7a=uN`jRNlmq@$7H4(NVD_QF0!XuY*M>PQ0r4`rGFmT zU7tlzTy%Mi^fNxgPVg>1F@=g3Y$Zv@tBJMo5-GS&Ul3~$m~s2mVo(54o>DetyUF#j zkiDVjHEm#1aIH5V*%La>2E|p{xF7`h#pgaW&3O288s?IbWMy`&1H{OMNIQ1}S8&~n z{uPBJd*%n;6KJi6%z0F;FTHM~7k>d(#B#Wy=p3ZkN~c@Y*76S{w)_o!UHcLRWCkw= zaT1lyVNe$R`;UJjC#=-ZFo)A|wUzJ|)6spc7VXAqEem-p=dPQXRpS1P($dI{cmO8I z4l^R9i{m?w!@U#o6iR++GTjKl`mY_A5}e|}@(4kxL&87RVsU;Wq_GjR-+$>yZZ$%W zpwl9ZEp#sS4%3{2rGOIovB+p02P)P`U+5`ZZt?Am2^FWt!3ufIe9-W0P98`7QFf@; z?9~(9%*W_LqUyQu;^McDr10f*<+mHc9(o@PU>p7ct3wA5dY;2>U6m@+98ZQq!goT9s%Nh%$= ztRpJfcin)ezc19#ieY(TQYeiXyqnZKZE)Jal)z?75nye}O~K1WLw}xcXuwQ#+!(Fw zCrm+&!MbMJx*ZofD`OtuJIvMORH6Zuc0M(q0!gF_#BZs?>ah$&_Z4XVfX&awM~qRj zIg_TSY+bB%R6Mj*>w>JE|qzNPW&|M0LOc}fo8*V`oT``(x^M4fzNK>{GPKS}nL8bnq zcVj^e@ov*YcHcR+Q*)|Oll@)2vaR(}MQ}{C;BBy+HTxs|Y>qt3^wjs6WI;bd5}%Et z%(#G7r}syg{F}b4+qZ_vXFlGFx$v0|5|LS!vgs{QR2~z)Re!S#Nr?EJH=Ve`gj2>dN63>|aCIl^>9Ff9D#-R++XHMon|E1$_E^i# zi?~weyf43NIi5mU4)Dhehm~JQ3sXz>xtvuATe6AlO|8Y#PDgn-{Tot$9?fq@ef&{e z2m`xjL~~Yq$;oIX69pnne8sGbnZ0XSElU$7%AU@!Qhz=ikB8)4hAR71_kF`jTsE{Y zT!zk;Lu0niiTZWfyf=_ven@;+6jZ~aQ4pjP6^Qto0FG+&lZ7dv^)>tz5eg3f1OJ(mG5+IyJgU<_Lt@ zSsq?Q%Xi5L9mdt-3WgKGHU7wHi)XoPs{SqSW5o4>K%#V_|3h~yk!kuCwlhsp44CA| zf`2QJzGF!4buRcv<<7z8tqY;x_Bd&O`Kl>dTOghwc7Y0Asv=}~l8hlYh*q7XQDDKC zRJ1a7#`1(+yM&l!%0IO-#Z0^2g# zmsup3LeVc!rdp^H+cD#bk;g(&bL@Vgz_}qqQxv&>Fg>Ig9zP%=E~6<;fNV;@R@Dhj z9|}u&7jIY-(r_wstwl z&j#{0YihV~@gV(yB~D7Si}qw3iJ!`s6b%61DDIP~DuZk+c>>eI*VRyo=(sLn=H*>z zp6ikusAps)TzYCgowm2`urp1LH-DR!KBCjb|H+i+FAY#2wEcoHtcZ#H$o`cUrhvc4 zfo=H2^wLNDZHFxs3SR;Yu}19ztV`!Jq{$@jt%x#W2E06v|)2jBO zspsMAQx%UV0=eURGHxUPfyAq-_~&P*wrL4_K96A7H7EJyBx2ag^{na--qjs)|^Y_=JM=8-zVPQi#*<@g*omD7cy8 zB{+AaX5^f*+&O>c2~hc(O>KY!7JPM$SHv?gPRmYn85x39_`yFn^q$Q@nH3$)&3$|%JcNd6y! zwr_3_znf5LpZ1N*k@vy!^3H^NsVZy-omOuDaG&NTG@;k74ZD%Z-O`8ab(Xw63jr|` z3tpQ1tU=A<+G$rj5ew>b(tP){2~1eYCvoXFF%g2s<=YseDSyPw-Md5@9U11(-SzXj zW$I&%vYw@dbxl0ROK}gPwOzj5y&qh->M5;NKLRHrYgQmSQ7lhS(XD-Kzb_pW_1n}>@9m-4)7J`Tzy;+V6%`d|AMI~yxWA0L ziBX35A;m!wwv;RoTnQ~4Fm#rCo^c%6m*-(xI}m)77k~Yza1?>PHTc=b1}Q0#cGE(M z)0K4;GVY{eEEHX>34u_$m_^g>NjirMRI=gx$oqCtc4)zuUpbOgpL%j*d4{31cVsys zLG%&~YB;jIg7W*dlN3W*49kk6t)WJrn{Jadj0`-`pJO9E{@@^fqeHalA3`#X$A2;{$c$tDj6Qf=>Je>~+!p-1O>*Tp7t^sRc?Ij%IItg)epBz=T+$4obIA0A zJk~wi7vp7b|83P*Nh{V5Rs>;n=$eU_o2zx>h~+P`fRh;~iAUcd1@-NzP)mMx z9cKotKNdoW&DH5^6oZ%+CmchgXM9mi47_W7%=J3KhM`HvEHa#hQ?( z>8=4TrJF7kOuhqgrDcRzx6R8V%S>XkJu2Q?Jx%$q)oh^8`u(PbiYIiU=aAzZSNOd`w*c7)GooOi- zuNRphw?N*QKT)6ZyrtVV_s8-qBU(L?p(<)w=VSR}Kijo(s||(DOuHx;R0~H8Ul8Izw&tKPI=*KfcoKPP`s&gwtrdWnHCXE{|u0J-*&c( zC@ODf)PQ(<_@72VJW2>ASw*l6N@K?^S-Mx)@s213>%Z2mt&yk9TNs7H<;8ehuc;Zz zLTFuB{g9gVWIzs`)Lee8-~z zO@dpQiDmd6D~9XC3O#rJ$<=x=I=XXuit}wc7Sqp*7QA_Tuhm1XZo&Imr5tV^X1|$9 zaq>19S>^|Cx)(VOlo)ewI%J9Lbt$ucJKnoEQguuq#)r`LTRDJQGe$cfIi2z z;*sgjyfy+%EU#Ql$uev1$AHzUZLJ48Wn=96b>3WU!)F*buHihqG9PpqwDx0(G$=AQQGfOuKHQ5Wg4fGCsAi-#U!p_%lK7~kf+yObcewuNK!b0% zAb-J)P&Nvv<0hhsPs(tm+j8IVAFPFj^_xnAS*PJbL%mH6Q_NwOo+ zVRZMvMy7}DM6cPH2ju{P*`-ZvH8x$*%yo_I8Xmc-iIps4C3TlTpV#)|Q0e^CS>(66 zf_0uTV$TN7-&BXNH$kt?&>O_Xt?rM?$YIDOb*S>f@j7shUAjDA4a0BvUUvojxNxN! zBRlU&;WH+JyQOeNPJi5T32540|2&?5^npFTM(;DUQ?VV>e_%s0tRaT*A6j^NXirec ze!AQCMcTb>&09q$b0WkR+rEKU>U^$kernChviePP*E}(>v2b=M*qyqaMv_to%Pt(e zKMA9w+}wjo>Qh1`^^SHH_qb~B`_F^fAPKJ%7Xz_=0_F}vTz@j?LLCmyYaI(HqmudI zDRHKzKbxI4z2$ezI`yTC*b}}mqq7J!4%8khOb~c)EZi+tRX*+X_%NO z!U;}WmmYE+;dc~*&?acx)xX?n`0FT|>xcX6oAQ?M@$0^Oy3jNdr4;mgChGK3ICjMi z=eSdj87Y-_o8AX_FES28M-S{5r<>N#u~$eTmSe7rHfk9x zHde-KU#!p)!*gtSDMl68^%AM-Jb#xPt^@St2*Vy86jU+6#W)+rMrF^tk{4bndlSmz z3bB4dfM$N4HLdy6A)c&rDtXHElL0n>-`~FQW15zuuzyI=SJOpdvPTG8dYx#c`fb^s`}f6MCQ4W6BB?bz{B9Eu zsw|olYFHC3aWM-Ephh;AuQMc189cpot6SoRsd&oXy2m)|S(&qCM5-012SqZ2RV2HUqo(RbrS@SyglcbTA6?4opREvpdb|75dUF<{Jcu)FyQT13rfkX#2oT-bqVKV{VYe1Z>Ih=q}F53Dk-)+>XRb+9Xce>xt}jPuhGQLLTU4R8JEC{h|6?HKFFONk{u z@zr-FzU+TE-)iHW!^#9>|03clN@~!uN_VcXu$>DxA?N}zG^d)bc|(kD#x-%q`<{%F zG2%8TyQh?k3sV)Ue|B;N%Aauh`opcxer`i}w4t0}`j#&@Yk#IBn749;i?IvyN|5OD zzDt*d;j1~mvc_+9?ljvJt;P@bu=xub(~Eshz&U^NZ(5$no<@c~l!W$Y72I{o9N9Q` zX8ZK+f-m$T*q*~SfX68-3W zywqD0x$fX-k@#lo1J*FPWoq81u3AjyHPpIhIDTW=GnFHM=u}Y?OowmiAhX%Ln;ka3 zS5c1rbtA&VEjRGqAp1aNe{zDo)xSJ)6SO2UIPl1H3FGC1D7?j*(#$VX9a%g{BVkDG z@q_YXx~8Ux{d8RUhnQi*nGw{HN5$Unl?PxicC!1BjN7qm6Lj9l2gb}{FR7TBorHgt zr%{6I%>8JI&xM@sODQP;!gigHnC4zw@97X`NpyeB5vlk(T6j_y>J*O})!p7>sYF8U z{(!Nt2%SueQg3j=?{hjP5&x|h4aDK0r(B4Lm5)ot&b^f7UEP7v+n0?j#UdhQ?b@nM zlsxy+DMH5%2ovw$KCe%6<5rm?Ym*1{m9KiunWx@wBAxULv^B{r{8tm zX}JW&iqHM!V{;?dtqy*$=&`A>>0r%zj7|q#ZQ)q68ECWz3G3sLQDXBv#D<+GM?j0P zj9PfmkG`$(l2VZZZw+pnwVI>mcmtbIt4bIFnk!4EmP^lTjUw;6cS95IM@D}NS7H02 zl3y)Xqxa^)BYcMgV&)Tv8FLYGlu)N+WU+wnoMJxPtJ17S$4yFtM!|Mph;+9ezQOa( zN+=^?#ra`aieS3e_f8^z(n@MTsq*AqyPa0K@#b=KnA_sd=WIbBeY*6D&=cFZx5rCu z>PBrW7SjCMBU6?4AkY;22C)|*>}88b}iR@0X)dH&xlW6!!hBo>GjSipB0`c2Wv&iB`|GvAls(?>i>$8 zt}l;KXE@w!wJZp0T3UG&dR@xWUevk)rL%uJb(>w0=0mM!uWW(9Z7qNE6nUh9%&exv zXY#$QW|(0m&WOc#{Uv|dEF~6x3+RofI|VP7;jLft>>12P+$FQv+b@}2kiMfWO-*wv zz#|X*g2vD~5`qy$DZc`b#$u*L-3uOaIdyJ8pM@y7j#ghf><_R1(}OjNU3_dT<;8P>v85W`AmRJT?L6wjF9tW(Na}?63oswRUgL%S5%;Yv z1U(IyB?Mo4af*MJ27-tc-ab~&3udrUB4Q@QWkMY4D@_>w1Z(|?cerN;59{pQYY7I+ zZ?cO~sHiL`^liMrrM33jGFr(QCx)4_u7tQDR)^+cUWrHRu} z#`ONMi0*R?E7f}o_&9twV%UsQmRIW?lxwWgRvq+??XRW1d-id&BtH>@^`F&; zYVq={F^>1_rQykYl_@4Oi}Z1xoSryE*>^-OIk!8i4M}#FW>a99=>`Te{>&Do4pg{D z;$3l6T3oy~e-+hK6{4)7r0s#<@n-p`8bPJ^JtKdm>Kll63w%5A=O(!UO(TA%sJg_N zqj~&}PD5@G}o_#{h_8l=H1(Vu0sl;JPd2hJlby)VbN9m6Qu^eeRa>QwEMnrm} zhg$n$QH~M>*!JZg1@d~2yr}>dis8eS`8S>!X=i-xC&i_kQ0gI84?g(pOU6(wk5i=8 zb9sO25e)hs{g{lG#>8sE4Q;u+-4&x;I<6UgmORZ^8fOYwp@fwZWJ+k@YY=Wq z9%a9J%!mm2hKQ8bSVrbb@FDW!DHOn8E^+WD=pp!w%gQ-upb)5#f+dU_kT-c?9hlWK+g?`n{pm_=}6sGln3V zsGAVe%txvsggpF0Cj0cGW~cTs2)$>P2o?Df*BoQZH7nIXF>voRiWYkkyDW2y# z8cpBDwQ7XmrjQKq*n%V%9TQpRao`+SGORL)Vn%<`b&J8q%M=UXwqcxol-iY6X)TB5 zL}?ja|M62at4__IOU!K1e)8hlRg20Cu7@H$8ul*n!*~5pjT19W4z!CZ<7b<8EU{5h z8&hcNsk@;^oGss|jpU2M$DM!s5S~#-Aj#toy4d-t-(y&FN(~Qo36NneLK2!n;2Q$b znUb!5<>#N3$w*N*4kvCj`2}GJ>wga{2YB&Ng>*BxBV_8WAfk%4;%akhi0PCgWMBBC^Vt}esYuw@ z^fXjJv~6peYsA9x>6L%uN-^yOnx=4MfKT3duT-Cf-p8J#C|!=l80FNwnB-^_Jo@f) z&>CV5ohd+{2j6gA)Zlfr6`p@)bvtA|gdf5`CFJ#&Ee01$Tw8W7K0pGWs#WyDGzIWt z#5<8(BD@1D88{rR?+J?rbP0C5_cdoz3otv!$81)nZPYYGtI_gWw7OLD6eu{tmI6}byLsp>+E@j z`0Kzo7((tZ^ugYJ#%Qa@;^YsSo48l{nGxEaM`M=C&4*h8Uf+4hBs3HnHYP|w83{;B z_T5F3QbNF@q4a-~SqE^&2TIh4a&w?fa!2j@W~u(;>_dLBLhWO4&I-#~=nUYaT#b(p z4JHq{+2JxqX0%WDuT<&+q<1}NY;(@#7Xf3kSrl`6KN4Z{Uv{Hj~7Y(DU?D*>=)k^qx|Pm zMU}qa{B|!f$1%@pTD+RK{e#FVS^5NvaO_(<)kc}K2YD>u;f)G6jjy@zI8aPWJ-PQM z-Yd!G*Wj*r{|iZzLH%|&3%Z{hw-yAwAgF_Gu@=}W!>Va#k)QB^5Y{fvQKgXJkz+4(pIAih9Mbe~(5;!|ay~L+w|GXXS?x>(R28Qyd)ffWily{?37)n2%eIFxOth zW!OYjjZ?At;C(sQyr;H`@-Dk{Y^Pb8&5u#(P;6f8Y9m64ANN0xpzB{WTl@$k`$Hj5 zkuHCW&o;?3KwRarOwFj(G^?%5`)>AFwF||eb-EAnv*K)xprElPkIukkE=E+a+x~^s zI|6TSxsWfeH;HQT)_VD$)wAf^5J4n6tC}~RVtxL2li2}lHgj7fC4roqj(dLZ9kb6) z)!oUhroR@}7;xc%CoO~Zk_2t*yQO!fPzryVF~5>z3h&B_!Wk4@@?2NxpE`SPPNH); zn&2CWrcqCL5J1qhHJ!o6qZZ{+pGpzs_Vm`4&jL_k+H<&Bd|9<2gtsjfPn*?We`>Io zjHZ`P#9h?vN1O#}WbzFeI^W2?nyYneytE?9^F7D!Ni|;{9_!!IMZ?r%2m3tDlw5z4 zMwRd&qY^bfsSbJhMqLhENLOFU?-eJj#hQ|O6V!fcUaZY7RhPFW^X=i` zDBY(u+}%rIF;s%47ZA-gOuZH#6mWm;^;}$a;4g8Vf7rI+56+~2w?&1qvi4jdd+`cq zH)7YS!{SHo^E9eM>RjHX>+#G$XGX=WtB&y_n6dg!8BsMZE&*Qp<$}3&laiD;pw5sI z2?PzdR{QnpCD1ZxCmG7KvE0q{_f6aMi3mPc_NOr75K;;h-@FQ%AO#he)&iv{B88%{Tzyf7agHsldv)7%9#%a+0WkOS2L6Zf3 z4Rl*K%1rk-{ym~y{z^mJ#lI^RmwPVAM!f`P$6f!l3VCMFb~^di z4^e(9*`2E2wC&n(4`MdU$d`ZkauBsI8RZxMKc)C{ z*7R>BTCFtz4p-?1y=vQAr_%5z-Jc~hVkIA1QzEx7K&|JG0hb znm$=(vc)MXkvz1RkGum|77#YI5OoDk`CGCmaBIg35XF1jPY+~Z0e7Cxe$o73j{cUB zt#ws=fkQq?dz;oi-&(vy#U6?<_rZo|RZ9IeS(H8@GvUYj>Cc6#JG7x>+7!p5J?S8f zWZ-j4N5Wpta{6QGAL9thmH!7ZuY%{d!F&tmavU@@F$ynCWo~D5Xfq%%3NK7$ZfA68 zATlsAIXRc{F##ukth8fvrERw*96ObyV(+kGI~Ciuv19JIV%xTD+pM5sTNT@= z`}FB?zV1KW=f^$9y)+l*x)ueAq6)o`sl72!+}_Tao|%D(2Ow{0YwY5rY;P-X&n-)@ z3^aEE{MEA~P*8|~fJV-i_I9F1&Ojc32GA5B3N!(*umG5Uxw*L!C;%e%4jv#&a|>qx zm71~!H7zaOe`@}50T_Gyhvjdilcl*Gfb#E;E6~Q?!4_!e{1@W?I#2}&1UOp&0cMsq zK!AvXqL!4r1b|9HUJW1tv;%^SYygTb#x|BF09i{Dpq&$t8enD*0@(ap0GQa@nOgqS zniIocEFmXCasb)?^|1YG`wOOM@8s-c0#cC@TK%I-MisB4uZ04`62cx8Bsn;XiDyK+wMiMD@?kQ2#B$$kg7>#sgpq zG(%tql(%>On-V~m?C}dCf9_&qBX4B;cLDx=V*r1TjFBDS@0|h20{%HPHb$WTUyPBh zrH#k`DeAv^YXJXU?*9Qy%Gv1eScL4%|5C%m!1QmWrIWa&JJ3|o(%HlUU}j|VcV_?6 ztJ#?XK{l3lz`xx7YpeizW+tZpVpFxSG_kh(hXnS2n}Bwv|Fwg^e{}t;env%cad`=C z+W*ag{gFxG+yCfB&ffHY3je?e3){N`Jn5M^xB&DlT+Dyp-`|3`S=hY) zH!1%G#QdMKoRKrg(jB1lw{Irqe|7&qzW1l z1~BTEBB!5eM0s8<$ZkVvb1zBO45dP|91;JfCe^L99xfb|gkUu(n@i9ql zh{fzeZ36pRS9p3xnRxv4_-*Lt=*V#I4RrqjK5b4cJO!^2womdYNs_aNA?Uu*<3pj3wglrpP6UG_oT0tq(MHDnZGig-q>`cvDGr zCN9);B`x(xzG+UjdOQING5#-+f^~jBE0T5vi=*{BoxO?R_7$u{yG7hPerFOC)UpbpIg5IPeN`@JixJrSjt7ylf7yg3Trp);H8-*f4J(k=9Mg?f z>n3x#Pr>?%8;T~mY1>516D5^Pap!fHtl!$J)7_IM#vXt?FJL%*G|(hdvJ2Hv z4vpy!8`G{ZS?eir7DdL^VxvuW2)?1IVSxOW3Kv@cn zC|(&a+TLmjQ?g3UVPDCHV%cobYIa*xTmO(UgJAc1Cw0_ESNA{%4CaRdMOGm&ML-Mp zy(X$C%AL?fk;Zd1DLQlnt0lOpGLAt|&YqGW41{T({F)C`TkXYTf&zVB^^54iC7T_q zf0KcoyCoLeZj_M6ZS1-^f4>ziJpZ{;kr67>=k7v(zL*_PkFtZ6WL(hJN&jo z(chuBd*!(+A=(S_?bIS)<}>=z^rdyV7_chn?FMv zMgOqY$rPPVUHCU1%|G>Jt81HntzvqQfAQ}LBPoZ(QPjwU`1N6=8{ME=4qAYKF_NmImY8EwSP7dCJ>y3^- zg0Hc!ZW3pi&4g3n)cAc)teDK}8>ik4vKf#NKf|pE=w@*7Rw7wv>ey-7Z4%Rbe^!k+ z0n@bm^`;|5g&c_Y1i9E@%*Jm{HA-?>8s=)C+(AV)Yf6B8PiSBj65!kS;5y$@Y+2|>{q6l%7l<#Hw;i9mz ziUj^57Ai0cH>{Apr=pq21WlE^zrvvk(O!h$gO*hb6?2tVGUT5GUVU?UCs&Xw5ZHEh z;lH+qJ3t$HP`Cte&UEu8RHazf=WpEPUWX_Il_&Ok-I@{NbNjyyAN(0Ce{Mxw&iutb z^8SvXJq`vV!rRvmfaOowls>kHAT@mdK+9bK>hfMA9z;nXB8ME2)Q)4I{O)BAwAF}R zJIHo4w{bh$n~B5Pt#n)-@gM6`*Zs_NT22QL?QPxO*aA&K#xI5eo4TT}+==tugs219 zr|PY|T*6VV-m9&cOvBgse|vLA1TUttRCf=ID;NhR?9mQeo+BL}Q=FcXCVb$qb=q?h zG)q7lym=(<>R*;;TRheE!|!V)DX*E|`AtfP)_%h7H&6WFL|4?+Ui==t;)pQS=x!CC z+o(QCnLI)2B3OLOUV~paa;NHhD-HuB(hU6w%UX%&+sfsI0?*o6ej&Ldo3;#-Ns&Lpk z&gP+&;o}fJ#aqZ@O>c@4!!1PtOws4{a_)+fygSV>lsq;{#jxrUH4iHs;|zF8o%$BD z+bU@6M#+y2Np3xCfApGXxRp3Ze!*Ygs~VQjW$I@mA0JZC;5zfMz{5n+Tr9@41z7jD zSdhn+m^^wV9D7Rmp+#t(HeAq*7Cd+)(^BP5^LQOz1duWDpbo(vd-UOoLl|H-LTL98 zM1H+>_=)8)j5P;Co0Jh9->n;khj4Qwh!I|G=MUbF`n~x9e|ea1f|S%^r`kDCiA2oq4k^lm_w$q;G_4CrJ{||S=E?f{X_eS)K7mAzJ+C2tYlb0HyWc3Vs z+S;u7y%zH1AgYzNNQhLDv3nr42NzFAjh`nkWb^t$yAw$+Js~bfTKFdDK>R#;mlNE# zH~1b#!T;84T_GO3hdd%$8%V0ZQNR$$_Yz&Co>oM4e^FZ|7(7VEoopPUT@es+rZ>V@ zZNc4~%4G+wIfvFIwq*Cku*@bU7`Lqvda=W&i?Q0P8B9z|RfNeb3eVGRBh|R0wh0$` z60gP_jyymf?3!%YdAARHpF?p^p?RU&0k3UU0A&@&yqknN&HTmekVS3oJQEErS=@c~6A8=1z~=)WufuG6H37wu;M`YqovDL&%&W&a2+NXtao(>3 z7^^uJH|WD7Ui1`PaxtDcjf5V1Lx#>ITxs9-UdKY$uOmc?H@h@aJ$?|+f{PTL{8-MM z>Gl=)3XKkCRHBI|$ArW0_~EzcAPmPvwtv2EYogrJtt!NmY28toRBHRRI`K38MTDP! zf25<)X4>Ckxx!Zt7&J=cYnJ*^vy@ho_#XOX56UHQP>LfB@)E-dYBQ4zO z1M8Uuc3K!O0YCVThvn{Ll0oOYT8NwzfBQ-?6p5Jfqafa`bL} zsmJlc$E=1igCx*}H}0sXCwF~JNsMP2Zq7YIG-CN8hT22Dqkv9k(={3qo7jyupfD*T zCa8^GqF>~N-a{M!t8P4q)wG47e-Pf&QZe18fJ_x-z7Y0$5#9Tl(33&lvmkP^EvXd$LaIl&`2q`rJoCRH9l=cdT7lM9i11a1*XRLsyfFeHKX?ahE5vilii zJ-I6#fknI8Nr?_p>4?%VW@2f6KqBTTyB{ z!0EF3Lc$Eni*!k;|C3m8gLdoY2eYPXlfNFexSl3`0*oSLu6{h9$3epNAPCOeoK^K* z_k;2%**;bOBtpylPB<9WcLyqx_?j%@RB1LTj7T?zkTCEHP8dHV)Y0%D*Lf<=fMW-P z-Efycj917vMMt1N*)`}re~dVgjq(P0paQD-;1ylb6lA~a)m|0VDly1+P_p@k529g& z>n6u{$Epc)SO0hbC19tAHdy!GPZO3*(bgqwGg|G#$QiXC^~}!ltH`8dp%(O+=l8>& zTO&lj+S|xdaF03vm}k;>D4z)|3E!8EDo6&IxZ4oBPhYcn7JXw^;|%I zGUnou;{Fbd^3O?jJ-8yVfEX%A-vWbSaM+FxbP+NuaD!v@8EMO7hAN`WA4GRNeTE%d z;+nMsVqU={0`Uj7f5#m1OZNpAp?XkGd&!%-LUUaF2yw#Hdq^qD7;5556W-*J&Bl?W zO^adV39=Y_f|{2!qG%rMuhpRsGgTjb5ljWeK>~Y z9$AVtqLgRJMtRN;Ax%~&;P&n83{8d^;ZS#vv&t?dnUF>?e+KS~J5scseb4cyGyYQ> zh~s#Q@TC7C>rX2GiD}<}e^cN{HUsEs-z{3Eq};sUUT|&?Njmnqw#0WVtB_-}g*;Q= zany@7l6)7I9RdmZf^~i(HDyEBH79V9yiX6fTb3DI)DTS>HsTY+grSC}!Jorq6~c*$ zqi>^_^QvKKf5kSpkp>Fv@AUn_=LmW#vA=#nr$36ujcwT!%Mu1eZ=#>yvo8FM!$+u< zjViU!K-+4{&Y*i0hR>VPtO$xrVKxQQc7K1?JmhvkxNShLi>x-Ra`a1Z)ba$v5_yQP z5J0RPpZ4=?>nTfBAqqc?KMC)1cf zFdTsie_+rJB2r4_W1pP5ZP>qT+*{J|nv1WNH{~Ol9ntynCq!$tx`RMMiZi+BP2BlV zmQV}x=X^AA)5i{-FFL3JS&8%P&Mfj;#>qEVUrF#rB|iWCrXmF`C{vY^xIw@0Au ze{4Ey@7AQu(V2#O!4oCxgO4frr79v_iOB8h&#&5u$6wcMt!c)m6%}CJ5D#WQ`t!bn zht1?3%)a;4&9lpfAySL9n;DanMK_RY6o&G0^khV+?VthgkLSnE*hwxlDgvby!rFZq zmpysEbJxi9gk+ExIf}YA&Zk^GdIWSJf5c`C$~-klBoiQ!5xD8R{6i;1RMYB{0lAWH{f0ug0Ogttddrn`>4f0FUQ z9m_{pD@q|4{<~>iLPDE(fNBSmm|O-zUl&7&AdF4YPLf}?Nzh!`J+?fNW7V&;H_F zEy(VC>T%k7Zb@;nNbUMGW$YM=#yh0-TCX69S|QCiv>$XC>E@F0^=z)le^;1(GSzJh zHA2!Ds9|=W(aJ$}!pR})W~lE(UW^X{xG-O=MYii!dZSn6|0qFU0%{O9S2eM1%xvkV zI`Rwa%BJ#~lm)Y*9`SSF^fKa2TTlCJtDoJkVjuRcyG=1FLUxz=NYGp=p%@lFL6C@| zm4&pai1DC+{H0tb=(>E=e;0V+Q~Ruj)iaGECa|H%cbeN~(BL!Ij|PIc*Qs4^H-^;! zza~K=bE2Zvm^fnAwz6K7)WQ{SBsu@3z3gxU#eOx$i7WaS9+&+(C>sws0BN>Q4Y)5E zn99(=y$J*|3}UeI^pZFePE#L?%T`{MaH=O?Pb#0!JL%8OUa4Ffe=^NSsvlA5;(xGy zpQLTL@@jXKgari+h@ddG-`3RxrAgn>7R%Phe^c-bwlpxP_`Z0CDT9LlN`shj!l#8L zInQfDw&$CHv(u&;d2_F%+2MtaKZ|ZNBX+X+?ckQL_pl+u%u=1I%tLAlSq^gw#uDpt zb7W%Vx_A@>zA(j3e-TvUFxz%eO|R@;1e#+?_ws_AwP`*@o{_umnjS51%R5iT+68AT z|4eNBP3fh-C9e|{xz%bNs!X0E7HLR_t$Xa~6TSxht4(oEC5r9KBL*X)?n9h?`ha80 zVf$~4C221ZCl&j-bb2RuY0bnCAp{!ErurN@&%J2=&RYzKfUmZCTCFbUs{}O7qaLtu_&U3`_5nrc$h#s2$-fGoBWY zImD>0pEUY>y*3F{K0PiUHW9Cwt`?M%KcVf&G`$^8s*x;zkEZ!Q~|*Q-i3XW4R8cuJwd0d%!Z z(!4aiouioh#I`bG*^+CZDt*7#-X#;vj=FzuUf0z=*B_Mh*be?K)U<%+zKf0H;<0YA z63Sj}SROtuI%KJJx1(&{c!%C4W1m{gdRy-!e|FmYs|}ThY_*3HH$seyMiTD+{pDMJ zxv+ev9%s+kx7_c~F4TfV$QFK#KYqEE^g4vh>a@}h)6&GDRQ=+k24dZD2B?u`MH^_u zY^z3p(Gfzwe2=Wkv;a9s`P1P@@x1tvLIMf4XoVe!v>Ce#>A%*0nFBAsNpOiwx8@C1 ze|#^8Q*kPqPes*fim#H|iCEo+0J%`87G0{C^3QxZ_w1|Wg$8p@UpY7Zd zp#eQG1+uh9TdI7njG;H#$0t-%<1w+^<3?UCeJ}B4{LGy*b0Lrp4uZ`j+q8V(I-60= z7-L$rXNe;=gfBwhWzqA}Ra3YVcl+%j2^sCJl*cvh96 zubk=k3l&178C-4Z0$O33mirW~>)echj=QiBE1`}|AWeo1?FFEPFAWx$-3)7*g2;R_ zj&l=m6{2&%#)`7kra>;U3ty7bttXwguV&6;^+P&nY^5S=?-XniUy=IZj7A%@e_rA)sduMKz4iesxhAuq$ zUB)ZHZM*0YAFb7q4IQ^)-8?vnp8Ap@AW}Bnh7Fk2m|0+PIH(Kaqy(Jf-kAAkIPz@# z@wsv|o716uI(Myd;cO_U;$Uz6e|gvmdwJZ>dhrG!FGez|HZLOulr60SKZjO?QxN%u z=s}lAxm|wo^*S9P@Hq!b#y@9@{es7jKS}+9T$te~|rUUIC2U2WBSGG|u!`le1}U%&?aIEi4wZx!XLMf2~;Y z9_H5{L{PWrDx~P)aD&PqEVuGBxJ#FWDBHSqc+qlWjF;~gqpc8T7X>&YbB0zjF8ZrzP6pI@=G_v%wy_Y0Xgud6bjCz0BP1P`OczvX{hFhp*WoTt4#f05Gg`8mBg8DrjH z=~I8QoY%%bo75-gLYDe_?);N6i9p4Cqo;ztq;2cGHsi$0#uNG0ZDHtmpx@WELv4aw z7%|)tF@}WZ*CK?QKjfQNfR&jnGq+)9R=$_9z~*Ya*kU1&uYd+g3ii0&Yy_qQPW zWDA?&Tl5&ci=h$)e|>anPgbcXk#psfcKP$#Oof}3RbEr#@}l^Qe6PZr7fygqanYW2 zV32n&Ql)FdFtbU?!6O*7u%Y2~CZC3>%@Il$l%MpA_Pe5I9x0^_%)U~gZU~`xHZD#< z72*7fi~XI;+U)SmT)0wOHilVdp-10?6vIlaL5k!z-S1ZtfAF*=;h;Z<_*1(})Jn7$ zYNyDBUs;!#<#9|5*nL$gtmNVR(NY{Sdlq}z;U=Aqp?E%nv#jxWR3G?#R~urDa20Vr zn5~!&M-bk1kqG!GW{_=)Q-YyjKV92yUY7|U_cB&lmvIL>FASG_*YLRVqK1nwca*0g z@+t#icw=mQe*~xtV^ZqlJa@JxX%d?Ps$Y7`JAmIy2{Kpcp}pMU?@`@rMv#cTiA1BE z#eJh4Czui2=Xf5#<#O0q1o8tJe{F{pfR!$!cWM=daRvgoD)3SY^IN%q@A+?KGWQ>N zq0t}lFXhajX!nc<{N18rfA@71b<8%G=Q5~W*IZ&ZGe^wH zi}al@#s0pRvYRU$`WHb(zAnBf2Dhf?Q%?F(VKa43>Idd|<>J)~5d6l9&IutT1|3!! zxgJV-mHVUe_U^*kBBXxn{FcHI z)#S(%Z?3u{^9VOkG_^9+J^3k*wd6(k6RKZxSMQhqZ{f)knND9AUbGHb~Pn_}i z9#s>tixco7ROOrQ`R%XFkVL{qMRBM7xN_-pH z%lYEEa`Q{BID?G-f<1UPV;1a>tp^M_ftWL_C3pzld;*|qS-(d%>_R{9DBTMUnClj% zDCQfr-!iBcFycBL_JM>@ax<9!EA4S|Q@}b=gj#}Nd1SOI?~Wn;SlVR3B;wCZ3Bo-& zf0{o!Creb4CpfG4M1ivwT{7=t`NYqZpEa&Jj*ec2Lr=vlH%Y_fVt%6YV@OTNz~1;w z-%95#kUP}6Q%a&dNWsY3oOUK*W7vu`^f~*XzKa1JTDNA2_*n_Y3HG(Fy8fX2R(X3U zCVL^7hg@F!h&SySz)N!k<0|#GPiQmJeLXvNPf)1VBmg+xWb3YY8nYX|p^iyfA4bFDg6Ng81TpsEz-RmH}Wr z_nsAIqg)I;uxd0eH~V}h3#e}AH- zucGR0TNKPsD)%}N@=X61)_E-=X(p*eHdf>9ZbZGf(xh3Abuq-TZ9}l-V#ggOt1P1ZeA%+9e-4Sdh+z+|tSQ1V@gJRl{skgY7 zJ50MRchFWl`|xUy=_HRY?bi-ze?!a6-5qT5V+;`Ek8a20(#fGj4f7@E>bQp5l_y`? z+g7%HvraEOmcj%w*i_`q$|BvIYusdk*NcACp%;4Pnk{Px2M~XpxLx1}8xstAwLpme z2P~}|qn=7tNtEi=NM@Jzl4}nGq97vC`g@h>4Ks~S{dcaAAl>mi?!^R#e;J$=7>~2x zt)=(RP)!-Zt&2MMj7Ck~^LO!~ITD0xRCc$HAq3uxnAUDt7FIU>$(b%#j7fw93r)$v ziic@WKL=?oqxGEy!!iv;m@r6pC(^*VY;`a+-z*i8ySxd=Ggpr08KOm|l6{66@mYw`{^<4#PM8zjF;UW-%v%u^)PlIZ{RO4+`vE6bVk;!m}yjLVg>k zpiIOssSHJ+ujgjUW5!0(PiEA1pu~`0`|Zo&2HIEZk~4Z^D89AYe}2s_QxZxBg127d zPm!U|_>~FUs}M^IWGQ%|9Kd_K`fLU3C?jms%u0>r%?os0TD0Vj{t$mFF8wiQ_TVYC zSYQbwk;MB{CgbIwU1IiFg={tyTfNR@VRx^eaif>2C~@}@2k)NfyL3|(M?_iUE?Ifc zE#S{uCPA{U(iIpPf8Xj-52ND&{T9yR689Lk#fi<0F#*ufQJCta64zq|#2zS%v_9Zv z?Uzt%&uJ)x#GCu(vwT@VQ2hgY@KJY5qgf0=rK9Qg%saMZYIv~>OH zqE0=7*5Qe058lJ5RMAbuQLo-A;T9edtW#3=5`7Lwf@1^`!xifNIQlj?76(kzpO-|D%n$yCbO$AYrR%;{MR16~hceD=1S| zLYn!B!G!fARV9D-hR#naGD;#T%9_l)sZH0^x;pz?btemy@>YM6dBTU^jFI2khni2M z@FciDuS@rhQjyq4zRqe}RTQ5K>@fdvtUT%O7FD%yf3X+H1}OxP8FYK#$g+=+b?h43 z1BYf^F`VA}>wvpl9KAKUoh3Lt;)lzAII!UFQX9&Y9E+`Qc2B18 zKd{$8x;!`UEqps&NL-?l2ocxvuiJVGasI&iU>i;CBKI`)FDodq-rHR%ia1HRtG!0~ z3Gu{Lf6e%73tGSle%S@3=KLj$3=@n-wfiN{#4}TDOwGGXm|;Q`G^^cQiVjJi;N2igYjs!J#8|3S=HHk)M>)7xyxEXT;os+)z8CCRJsVS9 z!)L29WRI%vV6UluLwxUGd>DWcr-D+)u3KOme>)E(c$zUE_ueh_x}xO7?R=Gz3dHB&i`{A;EY@>R9=SQSVA+w@{eI7HcvnJtk_V8UE z-cou=(s1MBEdnfocf+jgYduJm`D~5Bz1Egh0)QrPO-px2IAlWTmrS}h1l3jj(nA@< ze_{$CkZM(VV@3AC_t#0WVhosjb=EkTw^pCq>{oq!{6f2L?oUFvSsxGPoQK??f=8Bc zDy29dKh`IemCa2_rZ-Jf9yVEU?2k09{Vw)7b{Iu&Whz$F-V12=utX^0pxco(5&06dv&nVC3(Pg9W3%AQ>syXky+0|u&!5Gne~j_j z@!4wO!?fTr;%C1(T1bRkmIi~7Q^@bGcE6oip|{*m)5^}I)^+1=)inyklYWugv94V{ z>@KyOZLRO4*PT@xS8HPEl6v^_Ue?2wEs>l%n01QuIyiDtCwj1~}+ z8UzlRS>{6tF1Jgyrjo}q#IKs8e+;FVwwV2_v85^5T7casqNDB@K#;KV!_B#9X2E~^ zq`eKv$VlamK>|EnV~=OIb~JX>BhTqsgfam(jxUZbaB-*wjWy}tVj6ycBLmi6C>>?j zif$cP)A5Nzx#i!hWOmnjC7!SKV6HrOmSQtF$2RunN?un}I#3mak=3^Ke@H`U@VkUk zT9QxE3(=vzOl1i)z+R zjJ4xEZ1w|!M7A5il4=w;e~jyOFw#k<*(bno)J)s;sLkp5{bC3a^4e@W;k~?8X&Pld zMIu&7ocgdpS7A$O0v9G0hfmcj+{Q(Ei(u|#0^3LqArYQxtTl`0yGF;O-na||b0bdy zHs-*(tjNSZ9E$k_S}~;YP3*JPOG9zvUfEG~IMYwJA2U^NHIh=le?9$!d;Hc5c}pD? z=JdATRL#C8)+6UitS5x#GrHAaeo@%02^62QeUh-iV&d>T-i@5#PA40$CN6`dGWt&Z zY^&|h@Fv7k{mR|+?9?V!d25E`1SVfiMIO>f{<>u(#HqU&!kO~(8?7KuOGt+ue-4+) z<-WnID-*}40b!pxfAJBPsQBu(NK3n%7Ml+Hio>Zt`gvXm22+oQ-7C{bOxRSF`X$5> zfz0p+Z*@I#yJAQsCOF(f%iULpun(S%fsCic2sXn$b|o4N{v^i4hq z>IRGkq69)Vs(8E`rKk9Mxxkz4WQ~+=%oVm_c4JqqA2asje~y+6n_$B6ylWTHrORXB zwkX}7DkR(~%ObmP40AJo}SV-HrC6$UWgsv6F|sex}gvQncmr;at=s#oA-46-ldYAH*VGk z^;%-{E|d&;dYgKn*&ak2T_L8-%PjFFK}9x%yIk%Kf3ox0M9K%fx4kmaS^Tn4PMmJ4 zBfCRfBdLsvSiX6B6w{aOmc3kbH}L))0t9D)2JNd z8%*$~S;8r9BTsFBD*x)(&p27sUz5^?w(Qj8(#O+W^vW%X4(7lo+|&;vx0w*8OdKDs zB*CrBf2ln1%yxXgvPNgD;+-#rNf9YuNVENnjCz5IEt$oygR0I$#%NmQk}}^_=o^vh zm6Q@=)Re(}DAvi?d+Ur>=KY$NDbOZ{O=2zbEs&OB=eD5luIT}y?04wK)iotF6~qzZ z1f5A&sutTHD4zAG@gWXOja9C9>C@AkunLq%f1+g?^u~Pn4Dsss+?g!aI~1v`hxJ2H zb4;&OKR6|gBew7$qkuL6#nV#Rs?kyA&%F{)FTN_VgO$6^vl_Bke&b`MG=l;UYXdr) znA3x-{0J_XbnL1pHqom%rihr?uRSQ6whr>WU+=|i969)_75F^K_fjIR=p1j!tG>y` ze}O3o<-hzqW@#P;W)!ApN9E5a5fWbuZ?pzVC^)gF)C2WZDuvGu8e|1%<{fVk^Iqpj zhdzTgqeGT`DbGVD^##mT#E4z4jiA+j0z?oqooeB9=i#=r{M>tiI#9hEU9n#iQT4cv zq%&P1Q}e6bi=|C7zlqeA2MXCBz|Qdoe^kg{co8`tF3RhC7w7G3oY9%iVvH$~9vp?8 zQ*fYNltp8^ub~Dk*W3G)ZddfqOhS%W;JLVI(V6OA({KqP$NS@E~F zhDMgz;09&NS<5fmCA)Il_nGxO zDn*bLe;wi_J_tW}tZ)x6zyWa52T2au`hLAJ30Jp(O|24=0-L=3+ ze(Ybi|8$sh+>qzJdYU`L9q&i#t6ZRCr0>ZsM#CZhsfs8T7gGrbA*%MpKCI6Cr!~W{ zaEmyPFhVJ}u>WmA$M*Y3iw-;ommBd9$v%_KBI&}7vO)X4ogrTU zg5qjB|7A><5weSQ)M-E5Q;_t1Pm%JTrba&N`%(~1LdDofIEDMo{*YXMv8gd>4lv*TL3g|Wp~ zN#8QIRFks@|4lIqW|tBnAmJ^N^t<_8KyA*VZN08mXqqNi@k^v?~jM%O2e z^$GC&n?eZG!h|lT$?J2Bu>%8adI5;gnE%4XQw+XSk*DF|xbMde&GHDk^sBFgMpkIo zw2loe?PMF6tA*QDjLR!mwW>@SWBskYd5ig7T5@CH-@f7LWm&hv{LV2t`WhIojlGY0 zp|zw#>L3W&0F=@DE_UYMYUiw9(?p|!hX)d#q(23hyy$6L?95_Phswcg)>qvPOKncf zV}tuW1(nxS5X(}SFgtZ>-N~|6!oQvVzR7u#j5e&$uxUs)pHkxF=iYkGh4UXHx(~gG zP_kC1Q{kuA-ifG%6pUk2{FhP|v{)_82BkXttVw(G0(AY6#bp-yhLm`@lU{NBHg40oG+^ zzIioT!4hq-!ecN6_8+-dT6-jgMh*G2{?y8R8LgFTB@TP|h8*}T^+@Mp0mc@7p+ zhw%?7Jq7L^dLzOSnlSk^?@F`^(V?PLJsHO$K);6^lKgyN^n>_2AM$Sp8j*ap1Rr7Y zcXaz8^zEh&wm1BsjM4HT%z(-eK9-OkE;%>TFKHA!IyS7lcTOiMwcQ`+uwrM@bw@B6 z>W9q;d)sl=5}fJ={*a4@&zSs${Anp5o5dLj;AZu;9X9(Q9txAfT zr-3*ws`dcZgYD4m3Hj8!V736HL{cHw?2%O2M|(B8VM#JV>ZY>Qrsi>q@m2+IQzci@ z<@~$a&m&}5dlRs1Nrv04gQfM=BYb=`01=7_mh;!{`@H>%2t0d69ymhmi6SoH&dcJK z1sbMVl}q)y=GAl`H;G#_gT2YcA$9AcBAdR+s!j{WJRWgaaM2J$viZ9`@=m%Jf+@y! zeEA|Syj1cU*nSJfd-{3w2~QXkVyb17g1eD6esT>1%umHE&u^+&-BadrEHY*Tz^udZ z!*t!qwkDsv;vFW$}mq(c*X=3w%)}eMG?Zi7QOgn6QeSIuP0?+EYJFk zN7zc|k*@WR(D#*TWZ(C{ZllQ;7>MzS32Cqckc5watlq%1xwxT?r@;*Az>a@dJriBj zo@_a_;ktvxq2A?uXroHB{1;6`HSm?6RLCp@fNo{$Ew+p^`531fQ&rUa85=4(SYyg!}*kd03Up7aNaH z|J~2mB)*vs^kOzOHUzetun`x-fb(kyqBGT~cBO?fM8%&>XrcPqlk za)ET2gulPQ-@}0MM4;%I80BHOa_e<{Q0_V$H z$CM^A3$uzMolXjDQ3ff~0xRID!AoqjB43!S?83UHo|aDG#N)Pf#B>m=BuE%uw-o;s zu9~R^=WQi+wKOau=~_ozs*qqzTkl`M7n#~yH#$mMIRv95G=NzP{vDEFOCfn@wMm?9 zN8A9Kn?wW?Y&$2VC~>=9yn!>qQOmc>mBF{l;uo1GPp*jjqA2TOpgMB+S|D!oa)2>O zt}08rNDW&N6Ib{7AmkiWe=AHTH{m6Qgi7WppJL7^@m_u8M}MDr{MTtDz8q7M*F!oIG{qk5Qh)ol8SJo zHNYh-RYlYhakDHP-eC~e)|%YT9nn6Q{Z6}qLy}iG2gKe+PLY`}bcAtz{7&H>satP2 z!(l8o3O{-0aia$Ap+}60FJ@1VTdQf`g%tVxF7ixLE2#UblM;f{Q^omfQZ+D}PCY?) zigK%CLsQ92l>9)D*Nt+B7tfl1aj`PncTw$Kq!7Y4Mrd%29;MhKX0MN7rff99*=E%y za+pk&Mi@Sh7o$(+2A3%zW3^wR<7$2vS2N`W+`$D_1%&jz7#2Q?hd%o$ zI_`Xxz0!@R7;z3BZAUHS?{?>ULsU}zJH>mQ2Y&iLkfil0b<(~#Fb1wQe1*tz%t%y2VEFWm@R2J)<_6r&H~64ihlMAb z0qq|+SRGL%SrJJOupDp>h9k(Yssa`bvKLw9=(LJ;EO=Jxj2D8>1vZ$Y1J%a%`ubIP zrkSCECsFU#$_V@|An-`^O|%@9vB~4irS?bIZT`7hp6rbm!Yc_x0_|6)uS-5c(w60= zjB;TvcG~Z3=kqutct)Pi0lz=S)*Ok1fu5lLoGe&|RcGh<8ELX*tQl-k;>JW~l)R@Y zI97Mfi;DVW3^pFu=AunqA6N0!WfHq{9hQ2)Vpgu;b!=SR-#5N0b_s$2BKjib8)M~A zinhaSlF#l~fS13F9<(B}(SPp+sSkX?#1reaEjN>sOS)eazDtg-DIDk7My=og_{7G1 zJ1vj0)4=$sp%N)36~xYii_Tbmoh`L{l^`5M zyKtB1$Y{R7q1e%Wh+zmJV=ciq_tMRjHLqoHC zg{e_yJ3q-IvY%W@bN-2nWPaXFd)i^*{w#Sa?~3=jz^2uQZ~m}yc3OQ)ni|4{u|vV>9V(FH+j^Enl|Bru>)=Rdce(uc z%{W7blp7lxKltibvTPm(0GBk(An4HL(-9h5M0yNHe<2@3;P0Q>h|IpQCl@2gZHG2y zjY@hdr3g~@AtNU^bn5;}`%AxQJ-0; zxN@z^CapfNSiLvAK~>~jYkn0h@Y`8LjC<>Oto+3H7xSOaNlab)MFz&O0@mF4+#XcP zWsD_%wGRC{NN-N*C@|XI>-x_w=aEz-N{@5SE^=c9E`Au>>Qfg)V_1TC z(O+D`cYNUjJmO6xenL%=g9fBxZXACvS*@9_RiA@J`zUH`Sb(^_s)Lq|$m>%r&5qqwQr-h4J3zadwl^d;tCxI^6JCsuTL5b&dB_qBRiNX&loj#A zCAzF&llqq~&MfNIeZX-{@Uf{)4j zuW_Y(ZJprv!$jeCere*)UFMA+-4VS{kFFrA$TBiGNGz_~OLcAY)w_D$}i% zm3o^z*QD|;r%@$yz>R|X6^2Npc3;C{^B*>tZD-m`&TjprjVWPF7?WmDnlRK29G+KAh9DJ0_feY#s6oq_##PJtp^?pIM}8J&_&E$VWUdtg zt^>#reVj?L+3_<;F3HH`w3>d0i@^hBoiLCL6A zF+SX>)Xwe)@_UHKwl-Dac9*%WJrR?ZzbRu6C6+tP+le5eX*~KSTt$PPOVuM!Fghfb~dx zcPR$%Rvdq%I)zPA-DQIP5fdSqqz~@yhxIXkV=n`-4lGdG=BpiQ$ae&(W0-67DZ6n|896-MMAz;ar36m?n|4;jWrp ziDsWxe99?B?k`i4!hY6@BQYx}KvHb1)r=q$p%4m%CpO{GPlaN97ILiC-6O551X7IS z=!$|*BjWQSQ9BnQrsxE0>Ksg%_}St`AIj>v1PDH^_ZNJ*c%iOO08|;N_U=bh;77R}YC2=K zm>qruX^1*j$i>u-wINV#R@FPk($`|LJ#CPWvDyE$=-Ev(rM7po8IN8#2xrjzIN_qr zOrhwK`sq-41ih9IWFd*PzIhm zSrQD;&ernR9d8;Xj-N8n80|bbW^MTCiYvs0H2fj@P+L)lS!Z(&pi~G39Dzj#isv_+jsrfAeN=^u2}{XicAk-_cm1y!2*)07+iI@fIu@vD%X15KUY*wg}UCx zaHloa_EvB7#m|EoX?UDH3*z;O1=I2XdmgX0rSS=Zi%u{H-4a63o{Ch(;bTVaK2+rA z>(UJ31Z26uue=3l{)nB$aLgfCtOuovtG}6sQU_Z}lf$npu*SfyV_+|_8u3znMb$A{_FP@<*C`mNtjH?1!M~kOb4J($ zSk`$k`XPc=}+V4$~_i433O9T}4{7MmsB09b%q zb^7Vol_Q)%Tpa8p6<1r^O5d!dcw@rK+1_2Wm6Bi9DCqgk@we9X z0JRN|<{Xsj)Foil3Wcn+lLYRfzBY2x_*jcBN(=`E^o0U#qRz}X(%Ev9!uWRNFJ2V| zC~4LUAVw7mb``#IpCp$thBVi1%9wvb+y$#D-IDBO@qw$GpSa!A}niFcc)D%*g9tqY!NSUHnNB^DCvcELHR0ft7v)@uz3hGZvP|Ro6sURlTb-%H+f+x9l1b z<)#5XgmkR*7)>EF>tUao`Zp`e>caeFNPaPUMp6Zrq$gN-7_q}uRLrbryr=VOv)@1e zVz_lqteQIp9^2CWYX^AV^uI?+-3o_MKvSZ@Qy_UxX28-GqpmT|#aRyrk|I>H{S^t& z?OKn!0oUqaS0mg?1NI%v3R*z;{r#Ukyd+s^C}792>-E0ZZZRVF)|~)Q+mAzPWWTiC9y^vE`BG}it}#}Rx&GFF~Y;> zpBoyk&}*o@X!S zY*Z*}OkC!-nUx%Nrb4ER%E(2W7Fs9|P7Hm=+tf*;CQEQ#p?Md&eh7J1p0c2$r?qnob|Wv9Oc*)49TDG_qmT3t`ix*K-hm; z47t^^-Q_}EQCh9O%;H6-0EVF>ZvC_Rz!rK$}g*`g_kr1bTDNf48ZXn0%#V$4B0UUp+{p! zA^G|i-zaJOHwxk!*LIYggI&zJ-gc%f2Du+U#d@~76SwZ{12paw-1L|@tYJ;c3TL})vMmm3KOug;vdfvpUKjb1Q={1xmv(E()!96ta zwlyt77~7v`Y~#?zCEX`Bbq8wrer@-|=Tg8ISINWrO1G;>9N93g{zs23>7JBGSFwm2 zFWgf}W$+{xhP-vU1mNA)a@h^$^EzU4p16|P3)&|brU-)N0o(h~#f%51%6mrx0!qJ9 zs~!IHCh-9bI%R|SWP0wP1^m@#vF5W5RDZP$Rwwvx^ZGh;kx7hYhVT5L%@F~4;-bN| zYtt9t*$I)&+s)sp_Q=n5a>1J}CSQF{=F4pD5$vF5O)ox0$@Pp4OM{enHTXxS0ut7r zmXSI)DAz!EV6v_&eIr7{$;)W64Fwc&PjqjYlQKHQ0HJqNb~ouFL($8nyd~yIfqQJ5 zNlfkcA5wNmsO#$7*=ZR0BPS5C-0O=P^3PA6F9CQBxtEy>jqP%k>2NjME~#XSgoa;A z*;QuCbEKCgx2=j$zOft|I{K4&Hc!Qnh!UCwBq@p)z?>V?+>T&b3P-Ugxft2M>kIaH z;EAI3<{r}jFxr+;Z(@X)i4d18R9l%2MJ*NMGJ#L^H?z%Qm#Op5zffNuFW8@KS$8m< z*fap9Aa^dTSq-@;!ltcGiUoArt!-khljKo=s~C=z8Wm979+Mrd$R{G0wlz zt-`Q@)hq%q>WLeoI>3_8_}89&?iflU`=~AM`;9k+5k^D? zwlvJqm5Fsuh9fA-w9(xXCCzLl{N5d5#2OY)9G{!&3!At zAa1lER*B1qt0V^tH(NYa1L5fPGBf`Urr9C<37?qU54WQ(={5T|A2MW(JTige7xtB= zD;Ip{rU&w1u7xFS8AeWX%rRV)z?r(CCtQ6LwoX_?; zwxe@C>8Tp-6-d#ppy-kuu1dSz+|df~rWQ$7&-Yr!@CgNvBhvZRPZ&6A$M*=uS=IJh zA_~Ixiw2KIy1UAo!>i?Lm*+s_Jw)fIH02+eYE6iDg9ds-Vbj9S9#}Ff%q#l+$i1rb zJ4@S%p#zP1a{c6G!o~&+cjc{oT;-UxKrmv%V5xoJPv+2)#WIp2A4!G>%M-7Krb&kp6o4!U`hfpR#>BcxUUU)>h*1p36Q zFsH5E#a^N6zdr_zw>q?GJOq;0dEByA)r?|{3o!^z1knrKfwpb+)reGVqCQsJ4}a*E zIJHa^h*Vj@Y|G2;1kAr(EJA$tau@4CBC<+lwgfmAsJhzfsiY zFf}37ZCVZ#nGblf#3$s)=bvylfI8adY0Ea}B6RC5QsLEe@~SmQv$n~9dqh?>@>}0M zYAnyMgvO@JcqG&agWhXYD6Wm=9MFBV#=XdM$7j4JzNCMk1*!=itzMmOj5GbqGceAF z*jnNGmH{9(tt7jVmY<=ew70<3v-c$QxV#b7jQx%WFX#Y8)7Rd*Eu^JH;n&tYu#L8P z0R#)K6lNHjjQSo>NT4-fwQg@y-ewdG)MUm@KJAd)*<>s}w`5V;vx6$Cl{-nSMXdBH zAahsX1cVGyrG%c*|3qUul^$)_C;bMG4nm3?c`#50H6bsDO7&L>JBLehi zF?cN-RDm#};?k{9DEcoZ8kE#Vf(#fh1SVk76ulj;BQO&NELwyh2ox3+Q)&`{tU`zd zik+1TgSk9QxB}+X{FaD&1SC}?{XaFJ3naVfP%^k7f*Bbk%7~DSiqKRnE`m{UqIRH? zHiSKOly`xJy=j36c%ua>vKowuDIWqld-WLCFcS(Icqhhr=p76glx&s|HK-m)n+yPN z6+9(`1Bwner;BaOPcesXV=h!Hk;F6rPM>+sOjW>MKPbc;Uc^>Vf~r*rG7_q0%sl5* zE;K6_{Ams2V;o2>bn~!ut6~-G+ zlmTZl#x?#^Pj{dooro&BXB~?01K|#i2?SB)2d)u;2||BCgohDHA_oYP5sfgEQW|Kg zF!L}ise-lv*$I_{7h(V*hKQsHMrBD46$%1G znE{~_BswNJFt1WRzrbHI@tP#kPpb9-Lz~dS0+wtzLptFSBx-`q5F!$vYKQdq1c~mS zh>1ZS(4X$9u?w%}9{7HU#3F!L5psE=#Ita7pRny6UM0wp7SyChVEDXC=5&ZENbIl7HakVFv)=f*%6=&6sHU z(K272{!?Mmi961f{z=^*7otMRc*S@y9Yyh{;N-s}p1Lv}1t6U#G~G+8G0)*K`;&fV=K0L4SB*<$DsUJ`lz*5HvRK4ki7sT!GA!oa4037`Dg8#{J{){r$F)M*xkLg}o~Iw9LA>M=pE zPFXi@>msz1*mjhNm*jbrnUnZ(l$w)-d_?*t7C@0d!FU9ZGkv(o8#5CMHxmoQa*?i;lKB?zO=8YUq@Ea${Z#mCChXEk zwmU(1^lK|o(Edt#{$PvWoBsIBD>ZSzg-^kyu?->%V?T`qDiF?v`On|8=7rKY*-_K_ zB{yM-yJK>xv2CTr`0p5JmpGY;y2euV>vg8QkXwd~vo&DFu7YQWHv97+IfgPHDSJK~ z?~EL$%FD}1TD-xGM`WJjhp(&N-v_T$xq~;(Mk|zqXp1zWZ@06)SQR05ms4<`)Guao z%vP8Y=2Xg|W4w7l)B!{##QT{(tEe7pZw{4SoqcE_Ey+%x6Qo3Yj~M6BESXy`wn_HU zagmPEnIBMOP_?7MNs{Ih8SFTs{xiJr&_>PI)m{tmbB+X~&a85+i5V<(&6tl=En9{Y+Bxv6%LKp7y8e+H}bYTyZ*U( za5FIAwuUTV44p0yzWiHR@DhF^#4tZsL?3Xwy?6+4LU;y8@Atd7gp%{PCs~U-0ZJAF z7X)r1ju$u01ms86%^B{*ogntF*7;!Mgl1wQdkRRn*1rO)h%X5T_@?f$Ru_*k(?%b& zE-wI8mrl?2Hvd-7Z|y19g5!;y_o{WateM3dW*So#(l@$fo>;5$KWW(dIS<5LTmYdH zHjx`zmpG54vT%EvvMZ>$fbCo8cV&;-xKy!M#BTzjBjx5Fn zhb|bCa3mkq_A~1g^^<=K)k>%r6%aYal-&FM)e;~0WZgzuAH^7qJVmx<5WIdHD8ZQN zO{{|t3VyQ;t?2{^Iu*VOAw>MuBgeYT$=1q8evHhejjEcV>4lNJ`|%#+QRSG)T#K^! zk$H#Tsw?V=xIn(3Tm3W2C}DuN7tQ9sJX$Ot=*}H}Y)u)IgCFrB4I_%a1R!)*cVuJ< zoyHohB|GH!ld;sN!ctOr4H>6QkT*JF;7K^2IV@+s=}s!Wpuxw43ecH+vpM zxUD2u)XyOG49B$*8K$|~fpH~|O2plQJiAXr(^D)&!p0x{~7b3 z!Pmy(-n#O$>~mx7@A)y!?Y~LcCdHEdjFNH`K(KD7+`_wkRYM7T9hw*vo5>?a%N3`gx z3*unP95Po&Lo!xw?G~9B`7+F%2owIrzD=^cHo2MlljB3`lgH&eoEwb5TTi8SAK+UL zzTyINnBQ7S;qF?$fXR2Z)4x>+SI>EbeVc$F*%OwGM$qxQAg&7%`1(N^!d2A)joVT} zbX6$QV6&b(%=PbMnJg85{T((p_vUUIV?brHxAU;F#ojc;HmR??%Vwzcw3bIifT{&q zuR#F8HH-}V5%*zm(g>nIo@huH$Dy7p9_z&kQ<~S`gDv{e`4uWIk6q*<* zsGR@E5=x~Lu$nM~<^mBW){3s$DvTbNPK>Tj95z{U;D0gtF&$2R{qv|bAhkv<6E?-W zpFD)-(^lVQOZ~tNrBUFzGUSff;bIs&o+w1PxJM%F4|n1?T>$#^sTj3%GvQ*{hp5Hq6 zT*2xrfU&fYqj9q>4b2>ewr|H&-8;$Q%1xc2Ch5-$;>)zOIZ&r8n5$ests3H*!#qw?)JU7jf^XP*Pz3BSKw8a49ZBKefz?(4x zW70Ak`OsOqFcF?Mo!_X^>4GI}R<}b=d9TDn4dx}jFum=ip; zlyiYhMav4Rv;7@J(buMWEsP@1XJkUmxJ5**h6JNZtWs;6S~G_!)_OG0&ZSCOT>zc2 zmdpF8UHG@Awf%(jVkbk4dC~n2pyzULFNL+w(nF)Vrj+&f0&ii{Evk-t#obzQ%Xp)# zbJ!IrO+EZwp=ubDpmNd%RN?+S!VOnq6%#>L_P&ON1`{DWCL#@k0~7g9v!a{o#1?H< zGws)7jkEpT-0y8eKD&@g%QX65q2CP6j*fQ>m%8aHKg{DdawaON=;nfv0iEn$NVG9n zd59(we4CnsGV53-#?CM6m1_?hs%YA&X`NGC&`Bgn4?Yq`2^5(1^>=RUdGx@Rs`$gI z-r>`#&zGU5H?76GK47g?+Wt#$*IOr~icnSuAKyjx_T~V#YZtu!QBFu1e+4Ztm&tDIuC9SdX%-yGlO?A*e@{TMG_omqfbv z%0X&#w&bM9JDxcD5j)^>Q#BiiTb3eWK3!TbXCB2SxJo_+#*AOY_s~Fq}0Dc55%QnN&nGi9x zj$7WBuAwFH4sU-uZQ%=OV{Q&T zRFNfYkKT5o^TgM+H2M3rK73Ebo9ni?%EOmAyXwVRTer_PFC~q!jSM4|v0sTrZ$jqR zWmYv=&_MS2`FecYw@`>*Lm;~bCc+dd@DkCSEeycUCVFvZ0;pf-lLU%cj2>= zy8SWk;LcUWSO5 z6Bj}3q6d}Kc|id>fPfC7f`MJ6z+?xG{Y*nt{ik97jong$c81%u((Pep^^bmZ!^!WQ znY2NNwl+-b><_7rz1x{~mD%WPOk||@q?ufWQR(4*{u$Ycvbvys_RU&sZ%Bad{$hwJkgPy0DQ{3_>@V)|o zBxsB0&~t=@(YmOgOj&G0Bs$+-D*Ic-@x2Atw1x+*yu`;sC{}q9>nFVbuZ8q}kMX-G zfuAMvPs>D~r&?o@5uLh#BZGDeAUXbFrTmpGZnxZ7^5WRj;Id?-ALiMt zz`wKnrRzv{vZRY;>+&+f&{Jmq3evEeuDBt{c-(LWw9?#Xa=bWpbQH{|ayxPmyptfO zt#?wDH)ES=%2q?gP^_oc`pPew= z4kjFANw*z_6@0U}kXQjlVu2Vm&p^_sSaBdJJ17(c1$-ve58_Ph%uFN*v|wgsW?XP^ z=25Y-&VLsQ0qYl+O)njm+m3{+P5)dhvii+dtgMd?otP|bV(!(?vZIwp{k_L08viyI zoe^f{X}$XtJ(!uCP7MQlFV!;^BElLtaW&8VQ}xIOK|S@^A2dqgJmnEk+EXQKG$BQH z&rYf2nV^ftXma5a+D|X-=5TUp?qj}Yi$)A=6CAnmgl-_uL&Ow+`+qRS*luFC45p-t z#^wcEOk&~8gkw(DFu^c7*%LHRNPI^|Fb2LgenqIb?)bAhe~JNee2DPok~~Et+>{)2rGR-u{tO- z&ealqhuD!uRBRws-xq~Gs{bnV6+GOS_cD+fJ5ByGo8$Fqari5yVM?}M)}xJ6=KIL5 z?Q*P;D#}0tkM%wyX~HhQ*{4Uk#}}?W`HC5wt zE~8yj)|d3CBx*z%GbrN@EYXtkbO)ql8@4{h?gX0)dJvFqRSctEn5`3+g z!{SZR%BSF0OO@}haQYK5tLAX5ty+6xG2J>qcU-8YBqC1z3a>^BXas+9CT0nUk}yC?&z=x(cunK$r@J0?SC4KWE0Afor=NY zA?LW}4;BD}z>syBeTnj%R9+#qr;?}YiAbjnuQPCqx8aEZ19;=pNYpnhJqS@%PKKeJ zR2a>r;#Kx2y7U(s%?0288Fb0B?rw7NMf1&1po>_}#tm7!r0JVLPlMl{F`2NV@Ve@3 zuT>hgA!*SyIg*ZjrQ~gE8|zW&*S%7RnpPKpT1={(_Kyd%m|1 Date: Wed, 3 Aug 2016 15:27:17 -0400 Subject: [PATCH 009/197] Fix CCOLAMD base cases for 0 and 1 variables In both cases there's no need to find out any ordering at all: - For 0 variables, an empty Ordering is returned. - For 1 variable, an Ordering with that 1 variable is returned. --- gtsam/inference/Ordering.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index e12c32df3..b94f01689 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -53,8 +53,19 @@ Ordering Ordering::ColamdConstrained(const VariableIndex& variableIndex, gttic(Ordering_COLAMDConstrained); gttic(Prepare); + const size_t nVars = variableIndex.size(); + if (nVars == 0) + { + return Ordering(); + } + + if (nVars == 1) + { + return Ordering(std::vector(1, variableIndex.begin()->first)); + } + const size_t nEntries = variableIndex.nEntries(), nFactors = - variableIndex.nFactors(), nVars = variableIndex.size(); + variableIndex.nFactors(); // Convert to compressed column major format colamd wants it in (== MATLAB format!) const size_t Alen = ccolamd_recommended((int) nEntries, (int) nFactors, (int) nVars); /* colamd arg 3: size of the array A */ From 2fdb6ce48f02fabfd4138aa0e3006fe088988dd1 Mon Sep 17 00:00:00 2001 From: Enrique Fernandez Date: Wed, 3 Aug 2016 15:41:27 -0400 Subject: [PATCH 010/197] Remove unused indices in batch step In the batch step (in recalculate) we need to remove the unused indices from the variable index, otherwise the elimination would throw an exception saying: "Requested to eliminate a key that is not in the factors" --- gtsam/nonlinear/ISAM2.cpp | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 18296b393..122bf8aeb 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -334,13 +334,23 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke gttic(add_keys); br::copy(variableIndex_ | br::map_keys, std::inserter(*affectedKeysSet, affectedKeysSet->end())); + + // Removed unused keys: + VariableIndex affectedFactorsVarIndex = variableIndex_; + + affectedFactorsVarIndex.removeUnusedVariables(unusedIndices.begin(), unusedIndices.end()); + + for (const Key key: unusedIndices) + { + affectedKeysSet->erase(key); + } gttoc(add_keys); gttic(ordering); Ordering order; if(constrainKeys) { - order = Ordering::ColamdConstrained(variableIndex_, *constrainKeys); + order = Ordering::ColamdConstrained(affectedFactorsVarIndex, *constrainKeys); } else { @@ -350,11 +360,11 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke FastMap constraintGroups; for(Key var: observedKeys) constraintGroups[var] = 1; - order = Ordering::ColamdConstrained(variableIndex_, constraintGroups); + order = Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups); } else { - order = Ordering::Colamd(variableIndex_); + order = Ordering::Colamd(affectedFactorsVarIndex); } } gttoc(ordering); @@ -366,7 +376,7 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke gttoc(linearize); gttic(eliminate); - ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree(linearized, variableIndex_, order)) + ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree(linearized, affectedFactorsVarIndex, order)) .eliminate(params_.getEliminationFunction()).first; gttoc(eliminate); From 9f30d225fe65c63136e3f6d17e82714cb59fe259 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Tue, 16 May 2017 14:15:01 -0700 Subject: [PATCH 011/197] fixing compile issues on vc++14 --- CMakeLists.txt | 2 +- gtsam/discrete/DiscreteConditional.cpp | 24 +++++++++++++----------- 2 files changed, 14 insertions(+), 12 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 77434d135..9aa8b701a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -116,7 +116,7 @@ if(MSVC) endif() endif() -find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono) +find_package(Boost 1.43 COMPONENTS serialization system filesystem thread program_options date_time timer chrono regex) # Required components if(NOT Boost_SERIALIZATION_LIBRARY OR NOT Boost_SYSTEM_LIBRARY OR NOT Boost_FILESYSTEM_LIBRARY OR diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 4a918ef02..f12cd2567 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -87,17 +87,19 @@ bool DiscreteConditional::equals(const DiscreteFactor& other, Potentials::ADT DiscreteConditional::choose(const Values& parentsValues) const { ADT pFS(*this); Key j; size_t value; - for(Key key: parents()) - try { - j = (key); - value = parentsValues.at(j); - pFS = pFS.choose(j, value); - } catch (exception&) { - cout << "Key: " << j << " Value: " << value << endl; - parentsValues.print("parentsValues: "); -// pFS.print("pFS: "); - throw runtime_error("DiscreteConditional::choose: parent value missing"); - }; + for(Key key: parents()) { + try { + j = (key); + value = parentsValues.at(j); + pFS = pFS.choose(j, value); + } catch (exception&) { + cout << "Key: " << j << " Value: " << value << endl; + parentsValues.print("parentsValues: "); + // pFS.print("pFS: "); + throw runtime_error("DiscreteConditional::choose: parent value missing"); + }; + } + return pFS; } From 6a5beab4d48f3bf479dfab5291433d100033ae1a Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Tue, 16 May 2017 17:42:30 -0700 Subject: [PATCH 012/197] fixing compile issue on vc++14 --- gtsam/base/GenericValue.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 5b59f4872..bf186470e 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -167,10 +167,10 @@ public: // implicit assignment operator for (const GenericValue& rhs) works fine here /// Assignment operator, protected because only the Value or DERIVED /// assignment operators should be used. - // DerivedValue& operator=(const DerivedValue& rhs) { - // // Nothing to do, do not call base class assignment operator - // return *this; - // } + GenericValue& operator=(const GenericValue& rhs) { + // Nothing to do, do not call base class assignment operator + return *this; + } private: From 3f98942e9a5cf4dbefd358dd6ee7191d79e92f6c Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Wed, 17 May 2017 14:30:17 -0700 Subject: [PATCH 013/197] a few tmp fix to bypass eigen errors, should not be permanent solutions --- CMakeLists.txt | 3 +++ gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9aa8b701a..6db1f6681 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -251,6 +251,9 @@ else() endif() +# tmp mute eigen static assert to avoid errors in shared lib +add_definitions(-DEIGEN_NO_STATIC_ASSERT) + ############################################################################### # Global compile options diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index 9f71956ff..be2c67c5f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -380,7 +380,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type */ EIGEN_STRONG_INLINE void conservativeResize(Index size) { - internal::conservative_resize_like_impl::run(*this, size); + internal::conservative_resize_like_impl::run(*this, size, 1); } /** Resizes the matrix to \a rows x \a cols of \c other, while leaving old values untouched. From 89ca6fb92542a92e1d50d4ac5cb5b1b159c8fba8 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 11:39:51 -0700 Subject: [PATCH 014/197] fixing windows compile issues --- gtsam/geometry/SimpleCamera.h | 2 +- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/ImuFactor.h | 6 +++--- gtsam/navigation/ManifoldPreintegration.h | 2 +- gtsam/navigation/NavState.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 4 ++-- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- 9 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/geometry/SimpleCamera.h b/gtsam/geometry/SimpleCamera.h index fe493c075..a7e021394 100644 --- a/gtsam/geometry/SimpleCamera.h +++ b/gtsam/geometry/SimpleCamera.h @@ -31,7 +31,7 @@ typedef gtsam::PinholeCamera PinholeCameraCal3_S2; * @deprecated: SimpleCamera for backwards compatability with GTSAM 3.x * Use PinholeCameraCal3_S2 instead */ -class SimpleCamera : public PinholeCameraCal3_S2 { +class GTSAM_EXPORT SimpleCamera : public PinholeCameraCal3_S2 { typedef PinholeCamera Base; typedef boost::shared_ptr shared_ptr; diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 2ad3c17dd..84458f521 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -27,7 +27,7 @@ namespace gtsam { /// All bias models live in the imuBias namespace namespace imuBias { -class ConstantBias { +class GTSAM_EXPORT ConstantBias { private: Vector3 biasAcc_; Vector3 biasGyro_; diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 532abdac0..e713fcb99 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -68,7 +68,7 @@ typedef ManifoldPreintegration PreintegrationType; * * @addtogroup SLAM */ -class PreintegratedImuMeasurements: public PreintegrationType { +class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType { friend class ImuFactor; friend class ImuFactor2; @@ -176,7 +176,7 @@ private: * * @addtogroup SLAM */ -class ImuFactor: public NoiseModelFactor5 { private: @@ -285,7 +285,7 @@ private: * ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity. * @addtogroup SLAM */ -class ImuFactor2 : public NoiseModelFactor3 { +class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3 { private: typedef ImuFactor2 This; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 92d3f4814..22897b9d4 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -30,7 +30,7 @@ namespace gtsam { * IMU pre-integration on NavSatet manifold. * This corresponds to the original RSS paper (with one difference: V is rotated) */ -class ManifoldPreintegration : public PreintegrationBase { +class GTSAM_EXPORT ManifoldPreintegration : public PreintegrationBase { protected: /** diff --git a/gtsam/navigation/NavState.h b/gtsam/navigation/NavState.h index a1544735d..e9afcd3ac 100644 --- a/gtsam/navigation/NavState.h +++ b/gtsam/navigation/NavState.h @@ -31,7 +31,7 @@ typedef Vector3 Velocity3; * Navigation state: Pose (rotation, translation) + velocity * NOTE(frank): it does not make sense to make this a Lie group, but it is a 9D manifold */ -class NavState { +class GTSAM_EXPORT NavState { private: // TODO(frank): diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 88d9c6437..c03cab88a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -28,7 +28,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegratedRotationParams { Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements boost::optional omegaCoriolis; ///< Coriolis constant boost::optional body_P_sensor; ///< The pose of the sensor in the body frame @@ -63,7 +63,7 @@ struct PreintegratedRotationParams { * classes (in AHRSFactor, ImuFactor, and CombinedImuFactor). * It includes the definitions of the preintegrated rotation. */ -class PreintegratedRotation { +class GTSAM_EXPORT PreintegratedRotation { public: typedef PreintegratedRotationParams Params; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 06be4642d..cf5465c05 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -55,7 +55,7 @@ struct PoseVelocityBias { * It includes the definitions of the preintegrated variables and the methods * to access, print, and compare them. */ -class PreintegrationBase { +class GTSAM_EXPORT PreintegrationBase { public: typedef imuBias::ConstantBias Bias; typedef PreintegrationParams Params; diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index f2b2c0fef..831da0a12 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -23,7 +23,7 @@ namespace gtsam { /// Parameters for pre-integration: /// Usage: Create just a single Params and pass a shared pointer to the constructor -struct PreintegrationParams: PreintegratedRotationParams { +struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { Matrix3 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index dddafad7a..f5e3f7960 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -25,7 +25,7 @@ namespace gtsam { * Integrate on the 9D tangent space of the NavState manifold. * See extensive discussion in ImuFactor.lyx */ -class TangentPreintegration : public PreintegrationBase { +class GTSAM_EXPORT TangentPreintegration : public PreintegrationBase { protected: /** From ed4a99f6209efe58accd8ba2139cc9145ceb1143 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 11:56:52 -0700 Subject: [PATCH 015/197] fixing vc++14 compile issues --- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index a5707ce89..e36630104 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -30,7 +30,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeCamera: public PinholeBaseK { +class PinholeCamera: public PinholeBaseK { public: diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 43ba78ea2..4db1ee8c3 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -31,7 +31,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeBaseK: public PinholeBase { +class PinholeBaseK: public PinholeBase { private: @@ -222,7 +222,7 @@ private: * \nosubgrouping */ template -class GTSAM_EXPORT PinholePose: public PinholeBaseK { +class PinholePose: public PinholeBaseK { private: From 6b3608cf9ae954d71c2af349bc080239a674b5a7 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 12:32:29 -0700 Subject: [PATCH 016/197] fixing vc++14 compile issues --- gtsam/geometry/CameraSet.h | 12 ++++++------ gtsam/geometry/Point3.h | 24 ++++++++++++------------ gtsam/geometry/triangulation.h | 8 ++++---- gtsam/slam/SmartFactorParams.h | 2 +- 4 files changed, 23 insertions(+), 23 deletions(-) diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 18f311a23..026bcdd9e 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -209,11 +209,11 @@ public: bool diagonalDamping = false) { if (E.cols() == 2) { Matrix2 P2; - ComputePointCovariance(P2, E, lambda, diagonalDamping); + ComputePointCovariance<2>(P2, E, lambda, diagonalDamping); return P2; } else { Matrix3 P3; - ComputePointCovariance(P3, E, lambda, diagonalDamping); + ComputePointCovariance<3>(P3, E, lambda, diagonalDamping); return P3; } } @@ -227,12 +227,12 @@ public: bool diagonalDamping = false) { if (E.cols() == 2) { Matrix2 P; - ComputePointCovariance(P, E, lambda, diagonalDamping); - return SchurComplement(Fblocks, E, P, b); + ComputePointCovariance<2>(P, E, lambda, diagonalDamping); + return SchurComplement<2>(Fblocks, E, P, b); } else { Matrix3 P; - ComputePointCovariance(P, E, lambda, diagonalDamping); - return SchurComplement(Fblocks, E, P, b); + ComputePointCovariance<3>(P, E, lambda, diagonalDamping); + return SchurComplement<3>(Fblocks, E, P, b); } } diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index 99cb6c2e7..215161b3a 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -157,28 +157,28 @@ struct traits : public internal::VectorSpace {}; // Convenience typedef typedef std::pair Point3Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point3Pair &p); /// distance between two points -double distance3(const Point3& p1, const Point3& q, - OptionalJacobian<1, 3> H1 = boost::none, - OptionalJacobian<1, 3> H2 = boost::none); +GTSAM_EXPORT double distance3(const Point3& p1, const Point3& q, + OptionalJacobian<1, 3> H1 = boost::none, + OptionalJacobian<1, 3> H2 = boost::none); /// Distance of the point from the origin, with Jacobian -double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); +GTSAM_EXPORT double norm3(const Point3& p, OptionalJacobian<1, 3> H = boost::none); /// normalize, with optional Jacobian -Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); +GTSAM_EXPORT Point3 normalize(const Point3& p, OptionalJacobian<3, 3> H = boost::none); /// cross product @return this x q -Point3 cross(const Point3& p, const Point3& q, - OptionalJacobian<3, 3> H_p = boost::none, - OptionalJacobian<3, 3> H_q = boost::none); +GTSAM_EXPORT Point3 cross(const Point3& p, const Point3& q, + OptionalJacobian<3, 3> H_p = boost::none, + OptionalJacobian<3, 3> H_q = boost::none); /// dot product -double dot(const Point3& p, const Point3& q, - OptionalJacobian<1, 3> H_p = boost::none, - OptionalJacobian<1, 3> H_q = boost::none); +GTSAM_EXPORT double dot(const Point3& p, const Point3& q, + OptionalJacobian<1, 3> H_p = boost::none, + OptionalJacobian<1, 3> H_q = boost::none); template struct Range; diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index fdfe32e8b..e49e93d5a 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -28,7 +28,7 @@ namespace gtsam { /// Exception thrown by triangulateDLT when SVD returns rank < 3 -class TriangulationUnderconstrainedException: public std::runtime_error { +class GTSAM_EXPORT TriangulationUnderconstrainedException: public std::runtime_error { public: TriangulationUnderconstrainedException() : std::runtime_error("Triangulation Underconstrained Exception.") { @@ -36,7 +36,7 @@ public: }; /// Exception thrown by triangulateDLT when landmark is behind one or more of the cameras -class TriangulationCheiralityException: public std::runtime_error { +class GTSAM_EXPORT TriangulationCheiralityException: public std::runtime_error { public: TriangulationCheiralityException() : std::runtime_error( @@ -319,7 +319,7 @@ Point3 triangulatePoint3( (cameras, measurements, rank_tol, optimize); } -struct TriangulationParameters { +struct GTSAM_EXPORT TriangulationParameters { double rankTolerance; ///< threshold to decide whether triangulation is result.degenerate ///< (the rank is the number of singular values of the triangulation matrix which are larger than rankTolerance) @@ -382,7 +382,7 @@ private: /** * TriangulationResult is an optional point, along with the reasons why it is invalid. */ -class TriangulationResult: public boost::optional { +class GTSAM_EXPORT TriangulationResult: public boost::optional { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; diff --git a/gtsam/slam/SmartFactorParams.h b/gtsam/slam/SmartFactorParams.h index 761703f8b..e8a1fa7ab 100644 --- a/gtsam/slam/SmartFactorParams.h +++ b/gtsam/slam/SmartFactorParams.h @@ -39,7 +39,7 @@ enum DegeneracyMode { /* * Parameters for the smart (stereo) projection factors */ -struct GTSAM_EXPORT SmartProjectionParams { +struct SmartProjectionParams { LinearizationMode linearizationMode; ///< How to linearize the factor DegeneracyMode degeneracyMode; ///< How to linearize the factor From eb1e75fd27c72cc2ed42ae64c8fa1e05194ac20a Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Thu, 18 May 2017 14:46:46 -0700 Subject: [PATCH 017/197] fixing vc++14 compile issues --- gtsam/base/deprecated/LieMatrix.h | 4 ++-- gtsam/base/deprecated/LieVector.h | 6 +++--- gtsam/geometry/Cal3_S2Stereo.h | 2 +- gtsam/geometry/Point2.h | 14 +++++++------- gtsam/geometry/SO3.h | 4 ++-- gtsam/geometry/tests/testCameraSet.cpp | 6 +++--- gtsam/geometry/tests/testOrientedPlane3.cpp | 2 -- 7 files changed, 18 insertions(+), 20 deletions(-) diff --git a/gtsam/base/deprecated/LieMatrix.h b/gtsam/base/deprecated/LieMatrix.h index e26f45511..9ee20a596 100644 --- a/gtsam/base/deprecated/LieMatrix.h +++ b/gtsam/base/deprecated/LieMatrix.h @@ -29,7 +29,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieMatrix : public Matrix { +struct GTSAM_EXPORT LieMatrix : public Matrix { /// @name Constructors /// @{ @@ -60,7 +60,7 @@ struct LieMatrix : public Matrix { /// @{ /** print @param s optional string naming the object */ - GTSAM_EXPORT void print(const std::string& name = "") const { + void print(const std::string& name = "") const { gtsam::print(matrix(), name); } /** equality up to tolerance */ diff --git a/gtsam/base/deprecated/LieVector.h b/gtsam/base/deprecated/LieVector.h index 4a85036e0..b271275c3 100644 --- a/gtsam/base/deprecated/LieVector.h +++ b/gtsam/base/deprecated/LieVector.h @@ -27,7 +27,7 @@ namespace gtsam { * we can directly add double, Vector, and Matrix into values now, because of * gtsam::traits. */ -struct LieVector : public Vector { +struct GTSAM_EXPORT LieVector : public Vector { enum { dimension = Eigen::Dynamic }; @@ -51,13 +51,13 @@ struct LieVector : public Vector { LieVector(double d) : Vector((Vector(1) << d).finished()) {} /** constructor with size and initial data, row order ! */ - GTSAM_EXPORT LieVector(size_t m, const double* const data) : Vector(m) { + LieVector(size_t m, const double* const data) : Vector(m) { for (size_t i = 0; i < m; i++) (*this)(i) = data[i]; } /// @name Testable /// @{ - GTSAM_EXPORT void print(const std::string& name="") const { + void print(const std::string& name="") const { gtsam::print(vector(), name); } bool equals(const LieVector& expected, double tol=1e-5) const { diff --git a/gtsam/geometry/Cal3_S2Stereo.h b/gtsam/geometry/Cal3_S2Stereo.h index db49448ec..3a0f56c30 100644 --- a/gtsam/geometry/Cal3_S2Stereo.h +++ b/gtsam/geometry/Cal3_S2Stereo.h @@ -27,7 +27,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class Cal3_S2Stereo { + class GTSAM_EXPORT Cal3_S2Stereo { private: Cal3_S2 K_; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index fb250df6d..cfd7b4500 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -152,23 +152,23 @@ struct traits : public internal::VectorSpace { #endif // GTSAM_TYPEDEF_POINTS_TO_VECTORS /// Distance of the point from the origin, with Jacobian -double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); +GTSAM_EXPORT double norm2(const Point2& p, OptionalJacobian<1, 2> H = boost::none); /// distance between two points -double distance2(const Point2& p1, const Point2& q, +GTSAM_EXPORT double distance2(const Point2& p1, const Point2& q, OptionalJacobian<1, 2> H1 = boost::none, OptionalJacobian<1, 2> H2 = boost::none); // Convenience typedef typedef std::pair Point2Pair; -std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); +GTSAM_EXPORT std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); // For MATLAB wrapper typedef std::vector Point2Vector; /// multiply with scalar inline Point2 operator*(double s, const Point2& p) { -return p * s; + return p * s; } /* @@ -185,7 +185,7 @@ return p * s; * @param tol: absolute tolerance below which we consider touching circles * @return optional Point2 with f and h, boost::none if no solution. */ -boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); +GTSAM_EXPORT boost::optional circleCircleIntersection(double R_d, double r_d, double tol = 1e-9); /* * @brief Circle-circle intersection, from the normalized radii solution. @@ -193,7 +193,7 @@ boost::optional circleCircleIntersection(double R_d, double r_d, double * @param c2 center of second circle * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional fh); /** * @brief Intersect 2 circles @@ -204,7 +204,7 @@ std::list circleCircleIntersection(Point2 c1, Point2 c2, boost::optional * @param tol: absolute tolerance below which we consider touching circles * @return list of solutions (0,1, or 2). Identical circles will return empty list, as well. */ -std::list circleCircleIntersection(Point2 c1, double r1, +GTSAM_EXPORT std::list circleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9); } // \ namespace gtsam diff --git a/gtsam/geometry/SO3.h b/gtsam/geometry/SO3.h index 53f2c2130..e9d257acb 100644 --- a/gtsam/geometry/SO3.h +++ b/gtsam/geometry/SO3.h @@ -135,7 +135,7 @@ public: namespace so3 { /// Functor implementing Exponential map -class ExpmapFunctor { +class GTSAM_EXPORT ExpmapFunctor { protected: const double theta2; Matrix3 W, K, KK; @@ -156,7 +156,7 @@ class ExpmapFunctor { }; /// Functor that implements Exponential map *and* its derivatives -class DexpFunctor : public ExpmapFunctor { +class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor { const Vector3 omega; double a, b; Matrix3 dexp_; diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 01f784ae0..de7fe4625 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -89,7 +89,7 @@ TEST(CameraSet, Pinhole) { Vector4 b = actualV; Vector v = Ft * (b - E * P * Et * b); schur << Ft * F - Ft * E * P * Et * F, v, v.transpose(), 30; - SymmetricBlockMatrix actualReduced = Set::SchurComplement(Fs, E, P, b); + SymmetricBlockMatrix actualReduced = Set::SchurComplement<3>(Fs, E, P, b); EXPECT(assert_equal(schur, actualReduced.selfadjointView())); // Check Schur complement update, same order, should just double @@ -98,14 +98,14 @@ TEST(CameraSet, Pinhole) { allKeys.push_back(2); keys.push_back(1); keys.push_back(2); - Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys, actualReduced); + Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys, actualReduced); EXPECT(assert_equal((Matrix )(2.0 * schur), actualReduced.selfadjointView())); // Check Schur complement update, keys reversed FastVector keys2; keys2.push_back(2); keys2.push_back(1); - Set::UpdateSchurComplement(Fs, E, P, b, allKeys, keys2, actualReduced); + Set::UpdateSchurComplement<3>(Fs, E, P, b, allKeys, keys2, actualReduced); Vector4 reverse_b; reverse_b << b.tail<2>(), b.head<2>(); Vector reverse_v = Ft * (reverse_b - E * P * Et * reverse_b); diff --git a/gtsam/geometry/tests/testOrientedPlane3.cpp b/gtsam/geometry/tests/testOrientedPlane3.cpp index b3d87f18c..a1531e07c 100644 --- a/gtsam/geometry/tests/testOrientedPlane3.cpp +++ b/gtsam/geometry/tests/testOrientedPlane3.cpp @@ -120,8 +120,6 @@ TEST(OrientedPlane3, localCoordinates_retract) { maxXiLimit << M_PI, M_PI, 10.0; for (size_t i = 0; i < numIterations; i++) { - sleep(0); - // Create a Plane OrientedPlane3 p1(randomVector(minPlaneLimit, maxPlaneLimit)); Vector v12 = randomVector(minXiLimit, maxXiLimit); From 0f80f9bf41e30103907b012374305915eaedbce4 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Fri, 19 May 2017 18:51:14 -0700 Subject: [PATCH 018/197] static lib and examples compiles --- CMakeLists.txt | 2 +- cmake/dllexport.h.in | 29 ++++++++++++++++++----------- gtsam/CMakeLists.txt | 4 ++-- 3 files changed, 21 insertions(+), 14 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6db1f6681..115c8bb49 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -128,7 +128,7 @@ option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF) # Allow for not using the timer libraries on boost < 1.48 (GTSAM timing code falls back to old timer library) set(GTSAM_BOOST_LIBRARIES ${Boost_SERIALIZATION_LIBRARY} ${Boost_SYSTEM_LIBRARY} ${Boost_FILESYSTEM_LIBRARY} - ${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY}) + ${Boost_THREAD_LIBRARY} ${Boost_DATE_TIME_LIBRARY} ${Boost_REGEX_LIBRARY}) if (GTSAM_DISABLE_NEW_TIMERS) message("WARNING: GTSAM timing instrumentation manually disabled") add_definitions(-DGTSAM_DISABLE_NEW_TIMERS) diff --git a/cmake/dllexport.h.in b/cmake/dllexport.h.in index 023f06f57..6539e869e 100644 --- a/cmake/dllexport.h.in +++ b/cmake/dllexport.h.in @@ -26,21 +26,28 @@ // class __declspec(dllexport) MyClass { ... }; // When included while compiling other code against GTSAM: // class __declspec(dllimport) MyClass { ... }; + +#pragma once + +// Whether GTSAM is compiled as static or DLL in windows. +// This will be used to decide whether include __declspec(dllimport) or not in headers +// TODO: replace GTSAM by @library_name@ +#cmakedefine GTSAM_BUILD_STATIC_LIBRARY + #ifdef _WIN32 -# ifdef @library_name@_EXPORTS -# define @library_name@_EXPORT __declspec(dllexport) -# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern -# else -# ifndef @library_name@_IMPORT_STATIC +# ifdef @library_name@_BUILD_STATIC_LIBRARY +# define @library_name@_EXPORT +# define @library_name@_EXTERN_EXPORT extern +# else /* @library_name@_BUILD_STATIC_LIBRARY */ +# ifdef @library_name@_EXPORTS +# define @library_name@_EXPORT __declspec(dllexport) +# define @library_name@_EXTERN_EXPORT __declspec(dllexport) extern +# else /* @library_name@_EXPORTS */ # define @library_name@_EXPORT __declspec(dllimport) # define @library_name@_EXTERN_EXPORT __declspec(dllimport) -# else /* @library_name@_IMPORT_STATIC */ -# define @library_name@_EXPORT -# define @library_name@_EXTERN_EXPORT extern -# endif /* @library_name@_IMPORT_STATIC */ -# endif /* @library_name@_EXPORTS */ +# endif /* @library_name@_EXPORTS */ +# endif /* @library_name@_BUILD_STATIC_LIBRARY */ #else /* _WIN32 */ # define @library_name@_EXPORT # define @library_name@_EXTERN_EXPORT extern #endif - diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 8c1d8bb43..7cf801e74 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -110,8 +110,8 @@ if (GTSAM_BUILD_STATIC_LIBRARY) SOVERSION ${gtsam_soversion}) if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library set_target_properties(gtsam PROPERTIES - PREFIX "lib" - COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) + PREFIX "lib") + #COMPILE_DEFINITIONS GTSAM_IMPORT_STATIC) endif() install(TARGETS gtsam EXPORT GTSAM-exports ARCHIVE DESTINATION lib) list(APPEND GTSAM_EXPORTED_TARGETS gtsam) From 3635380be42d0f79c3dc013230f87e97bf578710 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 7 Aug 2017 21:35:24 -0700 Subject: [PATCH 019/197] Re-factored and re-formatted, incorporated Duy's fix (don't de-reference bayesTree) --- gtsam/inference/ISAM-inst.h | 75 ++++++++++++++++++++----------------- 1 file changed, 40 insertions(+), 35 deletions(-) diff --git a/gtsam/inference/ISAM-inst.h b/gtsam/inference/ISAM-inst.h index bf2cacc84..4471567fc 100644 --- a/gtsam/inference/ISAM-inst.h +++ b/gtsam/inference/ISAM-inst.h @@ -22,43 +22,48 @@ namespace gtsam { - /* ************************************************************************* */ - template - void ISAM::update_internal(const FactorGraphType& newFactors, Cliques& orphans, const Eliminate& function) - { - // Remove the contaminated part of the Bayes tree - BayesNetType bn; - if (!this->empty()) { - const KeySet newFactorKeys = newFactors.keys(); - this->removeTop(std::vector(newFactorKeys.begin(), newFactorKeys.end()), bn, orphans); - } - - // Add the removed top and the new factors - FactorGraphType factors; - factors += bn; - factors += newFactors; - - // Add the orphaned subtrees - for(const sharedClique& orphan: orphans) - factors += boost::make_shared >(orphan); - - // eliminate into a Bayes net - const VariableIndex varIndex(factors); - const KeySet newFactorKeys = newFactors.keys(); - const Ordering constrainedOrdering = - Ordering::ColamdConstrainedLast(varIndex, std::vector(newFactorKeys.begin(), newFactorKeys.end())); - Base bayesTree = *factors.eliminateMultifrontal(constrainedOrdering, function, varIndex); - this->roots_.insert(this->roots_.end(), bayesTree.roots().begin(), bayesTree.roots().end()); - this->nodes_.insert(bayesTree.nodes().begin(), bayesTree.nodes().end()); +/* ************************************************************************* */ +template +void ISAM::update_internal(const FactorGraphType& newFactors, + Cliques& orphans, const Eliminate& function) { + // Remove the contaminated part of the Bayes tree + BayesNetType bn; + const KeySet newFactorKeys = newFactors.keys(); + if (!this->empty()) { + std::vector keyVector(newFactorKeys.begin(), newFactorKeys.end()); + this->removeTop(keyVector, bn, orphans); } - /* ************************************************************************* */ - template - void ISAM::update(const FactorGraphType& newFactors, const Eliminate& function) - { - Cliques orphans; - this->update_internal(newFactors, orphans, function); - } + // Add the removed top and the new factors + FactorGraphType factors; + factors += bn; + factors += newFactors; + + // Add the orphaned subtrees + for (const sharedClique& orphan : orphans) + factors += boost::make_shared >(orphan); + + // Get an ordering where the new keys are eliminated last + const VariableIndex index(factors); + const Ordering ordering = Ordering::ColamdConstrainedLast(index, + std::vector(newFactorKeys.begin(), newFactorKeys.end())); + + // eliminate all factors (top, added, orphans) into a new Bayes tree + auto bayesTree = factors.eliminateMultifrontal(ordering, function, index); + + // Re-add into Bayes tree data structures + this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), + bayesTree->roots().end()); + this->nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end()); +} + +/* ************************************************************************* */ +template +void ISAM::update(const FactorGraphType& newFactors, + const Eliminate& function) { + Cliques orphans; + this->update_internal(newFactors, orphans, function); +} } /// namespace gtsam From 45a7b5ba68323cecf7a365457fab42f39cd639a9 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 8 Aug 2017 00:39:22 -0700 Subject: [PATCH 020/197] Add edge/vertex parsing from any input stream --- gtsam/slam/dataset.cpp | 47 ++++++++++++++++++++++++-------- gtsam/slam/dataset.h | 17 ++++++++++++ gtsam/slam/tests/testDataset.cpp | 34 +++++++++++++++++++++++ 3 files changed, 86 insertions(+), 12 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index dc25026d2..40a2573b3 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -195,6 +195,33 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } } +/* ************************************************************************* */ +boost::optional > parseVertex(istream& is, const string& tag) { + if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { + Key id; + double x, y, yaw; + is >> id >> x >> y >> yaw; + return pair(id, Pose2(x, y, yaw)); + } else { + return boost::none; + } +} + +/* ************************************************************************* */ +boost::optional, Pose2> > parseEdge(istream& is, const string& tag) { + if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") + || (tag == "ODOMETRY")) { + + Key id1, id2; + double x, y, yaw; + is >> id1 >> id2 >> x >> y >> yaw; + return pair, Pose2>(pair(id1, id2), + Pose2(x, y, yaw)); + } else { + return boost::none; + } +} + /* ************************************************************************* */ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, bool addNoise, bool smart, NoiseFormat noiseFormat, @@ -214,16 +241,15 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, if (!(is >> tag)) break; - if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { - Key id; - double x, y, yaw; - is >> id >> x >> y >> yaw; + const auto indexed_pose = parseVertex(is, tag); + if (indexed_pose) { + Key id = indexed_pose->first; // optional filter if (maxID && id >= maxID) continue; - initial->insert(id, Pose2(x, y, yaw)); + initial->insert(id, indexed_pose->second); } is.ignore(LINESIZE, '\n'); } @@ -251,13 +277,10 @@ GraphAndValues load2D(const string& filename, SharedNoiseModel model, Key maxID, if (!(is >> tag)) break; - if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") - || (tag == "ODOMETRY")) { - - // Read transform - double x, y, yaw; - is >> id1 >> id2 >> x >> y >> yaw; - Pose2 l1Xl2(x, y, yaw); + auto between_pose = parseEdge(is, tag); + if (between_pose) { + std::tie(id1, id2) = between_pose->first; + Pose2& l1Xl2 = between_pose->second; // read noise model SharedNoiseModel modelInFile = readNoiseModel(is, smart, noiseFormat, diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index dc7804c2d..76dd398a0 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -33,6 +33,7 @@ #include #include // for pair #include +#include namespace gtsam { @@ -88,6 +89,22 @@ GTSAM_EXPORT GraphAndValues load2D( NoiseFormat noiseFormat = NoiseFormatAUTO, KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); +/** + * Parse TORO/G2O vertex "id x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if vertex type + */ +boost::optional > parseVertex(std::istream& is, + const std::string& tag); + +/** + * Parse TORO/G2O edge "id1 id2 x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if edge type + */ +boost::optional, Pose2> > parseEdge( + std::istream& is, const std::string& tag); + /** * Load TORO/G2O style graph files * @param filename diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index b3e208b91..39c2d3722 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -26,6 +26,9 @@ #include +#include +#include + using namespace gtsam::symbol_shorthand; using namespace std; using namespace gtsam; @@ -39,6 +42,37 @@ TEST(dataSet, findExampleDataFile) { EXPECT(assert_equal(expected_end, actual_end)); } +/* ************************************************************************* */ +TEST( dataSet, parseVertex) +{ + const string str = "VERTEX2 1 2.000000 3.000000 4.000000"; + istringstream is(str); + string tag; + EXPECT(is >> tag); + const auto actual = parseVertex(is, tag); + EXPECT(actual); + if (actual) { + EXPECT_LONGS_EQUAL(1, actual->first); + EXPECT(assert_equal(Pose2(2, 3, 4), actual->second)); + } +} + +/* ************************************************************************* */ +TEST( dataSet, parseEdge) +{ + const string str = "EDGE2 0 1 2.000000 3.000000 4.000000"; + istringstream is(str); + string tag; + EXPECT(is >> tag); + const auto actual = parseEdge(is, tag); + EXPECT(actual); + if (actual) { + pair expected(0, 1); + EXPECT(expected == actual->first); + EXPECT(assert_equal(Pose2(2, 3, 4), actual->second)); + } +} + /* ************************************************************************* */ TEST( dataSet, load2D) { From 16057a2c8ec67c9dfe6e32d9c5e238d6b1b0a044 Mon Sep 17 00:00:00 2001 From: dellaert Date: Tue, 8 Aug 2017 00:59:33 -0700 Subject: [PATCH 021/197] Unit test, succeeds... --- tests/testNonlinearISAM.cpp | 91 +++++++++++++++++++++++++++++++++++++ 1 file changed, 91 insertions(+) diff --git a/tests/testNonlinearISAM.cpp b/tests/testNonlinearISAM.cpp index 617a8cc1c..c06d10beb 100644 --- a/tests/testNonlinearISAM.cpp +++ b/tests/testNonlinearISAM.cpp @@ -7,6 +7,7 @@ #include #include +#include #include #include #include @@ -16,7 +17,10 @@ #include #include +#include +#include +using namespace std; using namespace gtsam; const double tol=1e-5; @@ -228,6 +232,93 @@ TEST(testNonlinearISAM, markov_chain_with_reconnect ) { EXPECT(assert_equal(expected.at(lm3), actualQR.at(lm3), tol)); } +/* ************************************************************************* */ +TEST(testNonlinearISAM, loop_closures ) { + int relinearizeInterval = 100; + NonlinearISAM isam(relinearizeInterval); + + // Create a Factor Graph and Values to hold the new data + NonlinearFactorGraph graph; + Values initialEstimate; + + vector lines; + lines.emplace_back("VERTEX2 0 0.000000 0.000000 0.000000"); + lines.emplace_back("EDGE2 1 0 1.030390 0.011350 -0.012958"); + lines.emplace_back("VERTEX2 1 1.030390 0.011350 -0.012958"); + lines.emplace_back("EDGE2 2 1 1.013900 -0.058639 -0.013225"); + lines.emplace_back("VERTEX2 2 2.043445 -0.060422 -0.026183"); + lines.emplace_back("EDGE2 3 2 1.027650 -0.007456 0.004833"); + lines.emplace_back("VERTEX2 3 3.070548 -0.094779 -0.021350"); + lines.emplace_back("EDGE2 4 3 -0.012016 1.004360 1.566790"); + lines.emplace_back("VERTEX2 4 3.079976 0.909609 1.545440"); + lines.emplace_back("EDGE2 5 4 1.016030 0.014565 -0.016304"); + lines.emplace_back("VERTEX2 5 3.091176 1.925681 1.529136"); + lines.emplace_back("EDGE2 6 5 1.023890 0.006808 0.010981"); + lines.emplace_back("VERTEX2 6 3.127018 2.948966 1.540117"); + lines.emplace_back("EDGE2 7 6 0.957734 0.003159 0.010901"); + lines.emplace_back("VERTEX2 7 3.153237 3.906347 1.551018"); + lines.emplace_back("EDGE2 8 7 -1.023820 -0.013668 -3.093240"); + lines.emplace_back("VERTEX2 8 3.146655 2.882457 -1.542222"); + lines.emplace_back("EDGE2 9 8 1.023440 0.013984 -0.007802"); + lines.emplace_back("EDGE2 9 5 0.033943 0.032439 -3.127400"); + lines.emplace_back("VERTEX2 9 3.189873 1.859834 -1.550024"); + lines.emplace_back("EDGE2 10 9 1.003350 0.022250 0.023491"); + lines.emplace_back("EDGE2 10 3 0.044020 0.988477 -1.563530"); + lines.emplace_back("VERTEX2 10 3.232959 0.857162 -1.526533"); + lines.emplace_back("EDGE2 11 10 0.977245 0.019042 -0.028623"); + lines.emplace_back("VERTEX2 11 3.295225 -0.118283 -1.555156"); + lines.emplace_back("EDGE2 12 11 -0.996880 -0.025512 -3.126915"); + lines.emplace_back("VERTEX2 12 3.254125 0.878076 1.601114"); + lines.emplace_back("EDGE2 13 12 0.990646 0.018396 -0.016519"); + lines.emplace_back("VERTEX2 13 3.205708 1.867709 1.584594"); + lines.emplace_back("EDGE2 14 13 0.945873 0.008893 -0.002602"); + lines.emplace_back("EDGE2 14 8 0.015808 0.021059 3.128310"); + lines.emplace_back("VERTEX2 14 3.183765 2.813370 1.581993"); + lines.emplace_back("EDGE2 15 14 1.000010 0.006428 0.028234"); + lines.emplace_back("EDGE2 15 7 -0.014728 -0.001595 -0.019579"); + lines.emplace_back("VERTEX2 15 3.166141 3.813245 1.610227"); + + auto model = noiseModel::Diagonal::Sigmas(Vector3(3.0, 3.0, 0.5)); + + // Loop over the different poses, adding the observations to iSAM incrementally + for (const string& str : lines) { + // scan the tag + string tag; + istringstream is(str); + if (!(is >> tag)) + break; + + // Check if vertex + const auto indexedPose = parseVertex(is, tag); + if (indexedPose) { + Key id = indexedPose->first; + initialEstimate.insert(Symbol('x', id), indexedPose->second); + if (id == 0) { + noiseModel::Diagonal::shared_ptr priorNoise = + noiseModel::Diagonal::Sigmas(Vector3(0.001, 0.001, 0.001)); + graph.emplace_shared >(Symbol('x', id), + Pose2(0, 0, 0), priorNoise); + } else { + isam.update(graph, initialEstimate); + + // Clear the factor graph and values for the next iteration + graph.resize(0); + initialEstimate.clear(); + } + } + + // check if edge + const auto betweenPose = parseEdge(is, tag); + if (betweenPose) { + Key id1, id2; + tie(id1, id2) = betweenPose->first; + graph.emplace_shared >(Symbol('x', id2), + Symbol('x', id1), betweenPose->second, model); + } + } + EXPECT_LONGS_EQUAL(16, isam.estimate().size()) +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ From 8f20c0c9af2eee1f367faf44ced077b4147f55b8 Mon Sep 17 00:00:00 2001 From: aparikh Date: Tue, 9 Jan 2018 12:02:19 -0700 Subject: [PATCH 022/197] Update FindMKL.cmake and FindTBB.cmake - Find more recent versions of MKL - Work with Visual Studio 2015 (MSVC14) --- cmake/FindMKL.cmake | 18 ++++++++++++++---- cmake/FindTBB.cmake | 4 ++++ 2 files changed, 18 insertions(+), 4 deletions(-) diff --git a/cmake/FindMKL.cmake b/cmake/FindMKL.cmake index 8fb3be25d..d64e779af 100644 --- a/cmake/FindMKL.cmake +++ b/cmake/FindMKL.cmake @@ -83,10 +83,20 @@ FIND_PATH(MKL_FFTW_INCLUDE_DIR NO_DEFAULT_PATH ) -IF(WIN32) +IF(WIN32 AND MKL_ROOT_DIR) SET(MKL_LIB_SEARCHPATH $ENV{ICC_LIB_DIR} $ENV{MKL_LIB_DIR} "${MKL_ROOT_DIR}/lib/${MKL_ARCH_DIR}" "${MKL_ROOT_DIR}/../compiler" "${MKL_ROOT_DIR}/../compiler/lib/${MKL_ARCH_DIR}") - - IF (MKL_INCLUDE_DIR MATCHES "10.") + IF(MKL_INCLUDE_DIR MATCHES "2017" OR MKL_INCLUDE_DIR MATCHES "2018") + IF(CMAKE_CL_64) + SET(MKL_LIBS mkl_core mkl_intel_lp64 mkl_lapack95_lp64 mkl_blas95_lp64) + ELSE() + SET(MKL_LIBS mkl_core mkl_intel_s mkl_lapack95 mkl_blas95) + ENDIF() + IF(TBB_FOUND) + SET(MKL_LIBS ${MKL_LIBS} mkl_tbb_thread) + ELSE() + SET(MKL_LIBS ${MKL_LIBS} mkl_intel_thread libiomp5md) + ENDIF() + ELSEIF(MKL_INCLUDE_DIR MATCHES "10.") IF(CMAKE_CL_64) SET(MKL_LIBS mkl_solver_lp64 mkl_core mkl_intel_lp64 mkl_intel_thread libguide mkl_lapack95_lp64 mkl_blas95_lp64) ELSE() @@ -115,7 +125,7 @@ IF(WIN32) ENDIF() ENDFOREACH() SET(MKL_FOUND ON) -ELSE() # UNIX and macOS +ELSEIF(MKL_ROOT_DIR) # UNIX and macOS FIND_LIBRARY(MKL_CORE_LIBRARY mkl_core PATHS diff --git a/cmake/FindTBB.cmake b/cmake/FindTBB.cmake index 45b33e3aa..f39d64601 100644 --- a/cmake/FindTBB.cmake +++ b/cmake/FindTBB.cmake @@ -82,6 +82,10 @@ if (WIN32) set(_TBB_COMPILER "vc11") set(TBB_COMPILER "vc11") endif(MSVC11) + if(MSVC14) + set(_TBB_COMPILER "vc14") + set(TBB_COMPILER "vc14") + endif(MSVC14) # Todo: add other Windows compilers such as ICL. if(TBB_ARCHITECTURE) set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) From 0a5fd70f21b02be283efab4e37a6440ab96c44b5 Mon Sep 17 00:00:00 2001 From: anuppari Date: Fri, 12 Jan 2018 16:08:02 -0700 Subject: [PATCH 023/197] Minor fix to select mkl libs based on tbb use --- cmake/FindMKL.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/FindMKL.cmake b/cmake/FindMKL.cmake index d64e779af..cbe46a908 100644 --- a/cmake/FindMKL.cmake +++ b/cmake/FindMKL.cmake @@ -91,7 +91,7 @@ IF(WIN32 AND MKL_ROOT_DIR) ELSE() SET(MKL_LIBS mkl_core mkl_intel_s mkl_lapack95 mkl_blas95) ENDIF() - IF(TBB_FOUND) + IF(TBB_FOUND AND GTSAM_WITH_TBB) SET(MKL_LIBS ${MKL_LIBS} mkl_tbb_thread) ELSE() SET(MKL_LIBS ${MKL_LIBS} mkl_intel_thread libiomp5md) From 73efaf7e3469cb627ddfaefbd0a075f2c4d1cfb5 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Sun, 21 Jan 2018 18:40:49 -0800 Subject: [PATCH 024/197] Typo. The second argument of between is mentioned, but the first argument was typed. (was \xi_{1}, should have been \{xi_2} --- doc/math.lyx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/math.lyx b/doc/math.lyx index 88e243a01..b579d3ea4 100644 --- a/doc/math.lyx +++ b/doc/math.lyx @@ -5189,7 +5189,7 @@ R_{2}^{T}\left[t_{2}-t_{1}\right]_{\times}R_{1} & -R_{2}^{T}R_{1} and in its second argument, \begin_inset Formula \begin{eqnarray*} -\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{1}} & = & I_{6} +\frac{\partial\left(T_{1}^{^{-1}}T_{2}\right)}{\partial\xi_{2}} & = & I_{6} \end{eqnarray*} \end_inset From d9937ea07f5df945ae5b4a6e58068a39c1f51671 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Tue, 23 Jan 2018 10:15:19 -0500 Subject: [PATCH 025/197] small doc improvement --- gtsam/geometry/Cal3DS2.h | 13 +++---------- gtsam/geometry/Cal3DS2_Base.h | 6 +++--- 2 files changed, 6 insertions(+), 13 deletions(-) diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 81463ac06..4009a1921 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -23,18 +23,11 @@ namespace gtsam { /** - * @brief Calibration of a camera with radial distortion + * @brief Calibration of a camera with radial distortion that also supports + * Lie-group behaviors for optimization. + * \sa Cal3DS2_Base * @addtogroup geometry * \nosubgrouping - * - * Uses same distortionmodel as OpenCV, with - * http://docs.opencv.org/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html - * but using only k1,k2,p1, and p2 coefficients. - * K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] - * rr = Pn.x^2 + Pn.y^2 - * \hat{pn} = (1 + k1*rr + k2*rr^2 ) pn + [ 2*k3 pn.x pn.y + k4 (rr + 2 Pn.x^2) ; - * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] - * pi = K*pn */ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index cfbdde07c..4da5d1360 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -32,9 +32,9 @@ namespace gtsam { * but using only k1,k2,p1, and p2 coefficients. * K = [ fx s u0 ; 0 fy v0 ; 0 0 1 ] * rr = Pn.x^2 + Pn.y^2 - * \hat{pn} = (1 + k1*rr + k2*rr^2 ) pn + [ 2*k3 pn.x pn.y + k4 (rr + 2 Pn.x^2) ; - * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] - * pi = K*pn + * \hat{Pn} = (1 + k1*rr + k2*rr^2 ) Pn + [ 2*p1 Pn.x Pn.y + p2 (rr + 2 Pn.x^2) ; + * p1 (rr + 2 Pn.y^2) + 2*p2 Pn.x Pn.y ] + * pi = K*Pn */ class GTSAM_EXPORT Cal3DS2_Base { From f9d6d2dbc1eec41ec5a2668bb704ad609b845e16 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Tue, 23 Jan 2018 10:16:00 -0500 Subject: [PATCH 026/197] wrap more functions for Cal3DS2 --- gtsam.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/gtsam.h b/gtsam.h index ac4e80020..a5e24715a 100644 --- a/gtsam.h +++ b/gtsam.h @@ -745,6 +745,9 @@ virtual class Cal3DS2_Base { double py() const; double k1() const; double k2() const; + Matrix K() const; + Vector k() const; + Vector vector() const; // Action on Point2 gtsam::Point2 uncalibrate(const gtsam::Point2& p) const; From 108da4957ad2335db3a423933be1999b5f684ba8 Mon Sep 17 00:00:00 2001 From: Simon Julier Date: Fri, 16 Feb 2018 10:53:58 +0000 Subject: [PATCH 027/197] Set the INSTALL_NAME on the shared libraries. --- gtsam/3rdparty/metis/libmetis/CMakeLists.txt | 6 ++++++ gtsam/CMakeLists.txt | 5 +++++ 2 files changed, 11 insertions(+) diff --git a/gtsam/3rdparty/metis/libmetis/CMakeLists.txt b/gtsam/3rdparty/metis/libmetis/CMakeLists.txt index cc02a6ed2..fdf5e7511 100644 --- a/gtsam/3rdparty/metis/libmetis/CMakeLists.txt +++ b/gtsam/3rdparty/metis/libmetis/CMakeLists.txt @@ -15,6 +15,12 @@ if(WIN32) RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/../../../bin") endif() +if (APPLE) + set_target_properties(metis PROPERTIES + INSTALL_NAME_DIR + "${CMAKE_INSTALL_PREFIX}/lib") + endif() + install(TARGETS metis EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) list(APPEND GTSAM_EXPORTED_TARGETS metis) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index c159db250..3875b6a19 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -130,6 +130,11 @@ else() DEFINE_SYMBOL GTSAM_EXPORTS RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/bin") endif() + if (APPLE) + set_target_properties(gtsam PROPERTIES + INSTALL_NAME_DIR + "${CMAKE_INSTALL_PREFIX}/lib") + endif() install(TARGETS gtsam EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin) list(APPEND GTSAM_EXPORTED_TARGETS gtsam) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) From 530f6e99fd1048b72591742b8c5cf9c6d85671ba Mon Sep 17 00:00:00 2001 From: Dominic Pattison Date: Sun, 1 Apr 2018 15:32:27 +0000 Subject: [PATCH 028/197] Fix quaternion component error in Rot3 constructor --- gtsam/geometry/Rot3.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index bb0278953..58c150670 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -118,7 +118,7 @@ namespace gtsam { * @param q The quaternion */ Rot3(const Quaternion& q); - Rot3(double x, double y, double z, double w) : Rot3(Quaternion(x, y, z, w)) {} + Rot3(double w, double x, double y, double z) : Rot3(Quaternion(w, x, y, z)) {} /// Random, generates a random axis, then random angle \in [-p,pi] static Rot3 Random(boost::mt19937 & rng); From ae86bf0271c501bf83c3fb6405a49487551d7951 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 11 May 2018 15:13:14 -0700 Subject: [PATCH 029/197] BackprojectFromCamera and some small fixes from Skydio --- gtsam/base/cholesky.cpp | 5 +- gtsam/base/numericalDerivative.h | 172 +++++++++++++++++- gtsam/base/serializationTestHelpers.h | 4 +- gtsam/base/tests/testSerializationBase.cpp | 4 +- gtsam/geometry/CalibratedCamera.cpp | 15 +- gtsam/geometry/CalibratedCamera.h | 29 ++- gtsam/geometry/PinholePose.h | 59 +++--- gtsam/geometry/tests/testCalibratedCamera.cpp | 48 ++++- gtsam/geometry/tests/testPinholePose.cpp | 28 ++- python/handwritten/geometry/PinholeBaseK.cpp | 47 +++-- 10 files changed, 348 insertions(+), 63 deletions(-) diff --git a/gtsam/base/cholesky.cpp b/gtsam/base/cholesky.cpp index 7bc5949cc..bc5279c7b 100644 --- a/gtsam/base/cholesky.cpp +++ b/gtsam/base/cholesky.cpp @@ -144,8 +144,9 @@ bool choleskyPartial(Matrix& ABC, size_t nFrontal, size_t topleft) { // Check last diagonal element - Eigen does not check it if (nFrontal >= 2) { int exp2, exp1; - (void)frexp(R(topleft + nFrontal - 2, topleft + nFrontal - 2), &exp2); - (void)frexp(R(topleft + nFrontal - 1, topleft + nFrontal - 1), &exp1); + // NOTE(gareth): R is already the size of A, so we don't need to add topleft here. + (void)frexp(R(nFrontal - 2, nFrontal - 2), &exp2); + (void)frexp(R(nFrontal - 1, nFrontal - 1), &exp1); return (exp2 - exp1 < underconstrainedExponentDifference); } else if (nFrontal == 1) { int exp1; diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index dcb0425b7..2fa6e33c6 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -298,7 +298,7 @@ inline typename internal::FixedSizeMatrix::type numericalDerivative33(Y (* /** * Compute numerical derivative in argument 1 of 4-argument function - * @param h ternary function yielding m-vector + * @param h quartic function yielding m-vector * @param x1 n-dimensional first argument value * @param x2 second argument value * @param x3 third argument value @@ -317,9 +317,15 @@ typename internal::FixedSizeMatrix::type numericalDerivative41( return numericalDerivative11(boost::bind(h, _1, x2, x3, x4), x1, delta); } +template +inline typename internal::FixedSizeMatrix::type numericalDerivative41(Y (*h)(const X1&, const X2&, const X3&, const X4&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { + return numericalDerivative41(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4); +} + /** * Compute numerical derivative in argument 2 of 4-argument function - * @param h ternary function yielding m-vector + * @param h quartic function yielding m-vector * @param x1 first argument value * @param x2 n-dimensional second argument value * @param x3 third argument value @@ -338,9 +344,15 @@ typename internal::FixedSizeMatrix::type numericalDerivative42( return numericalDerivative11(boost::bind(h, x1, _1, x3, x4), x2, delta); } +template +inline typename internal::FixedSizeMatrix::type numericalDerivative42(Y (*h)(const X1&, const X2&, const X3&, const X4&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { + return numericalDerivative42(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4); +} + /** * Compute numerical derivative in argument 3 of 4-argument function - * @param h ternary function yielding m-vector + * @param h quartic function yielding m-vector * @param x1 first argument value * @param x2 second argument value * @param x3 n-dimensional third argument value @@ -359,9 +371,15 @@ typename internal::FixedSizeMatrix::type numericalDerivative43( return numericalDerivative11(boost::bind(h, x1, x2, _1, x4), x3, delta); } +template +inline typename internal::FixedSizeMatrix::type numericalDerivative43(Y (*h)(const X1&, const X2&, const X3&, const X4&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { + return numericalDerivative43(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4); +} + /** * Compute numerical derivative in argument 4 of 4-argument function - * @param h ternary function yielding m-vector + * @param h quartic function yielding m-vector * @param x1 first argument value * @param x2 second argument value * @param x3 third argument value @@ -380,6 +398,152 @@ typename internal::FixedSizeMatrix::type numericalDerivative44( return numericalDerivative11(boost::bind(h, x1, x2, x3, _1), x4, delta); } +template +inline typename internal::FixedSizeMatrix::type numericalDerivative44(Y (*h)(const X1&, const X2&, const X3&, const X4&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, double delta = 1e-5) { + return numericalDerivative44(boost::bind(h, _1, _2, _3, _4), x1, x2, x3, x4); +} + +/** + * Compute numerical derivative in argument 1 of 5-argument function + * @param h quintic function yielding m-vector + * @param x1 n-dimensional first argument value + * @param x2 second argument value + * @param x3 third argument value + * @param x4 fourth argument value + * @param x5 fifth argument value + * @param delta increment for numerical derivative + * @return m*n Jacobian computed via central differencing + */ +template +typename internal::FixedSizeMatrix::type numericalDerivative51( + boost::function h, const X1& x1, + const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument Y must be a manifold type."); + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument X1 must be a manifold type."); + return numericalDerivative11(boost::bind(h, _1, x2, x3, x4, x5), x1, delta); +} + +template +inline typename internal::FixedSizeMatrix::type numericalDerivative51(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + return numericalDerivative51(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5); +} + +/** + * Compute numerical derivative in argument 2 of 5-argument function + * @param h quintic function yielding m-vector + * @param x1 n-dimensional first argument value + * @param x2 second argument value + * @param x3 third argument value + * @param x4 fourth argument value + * @param x5 fifth argument value + * @param delta increment for numerical derivative + * @return m*n Jacobian computed via central differencing + */ +template +typename internal::FixedSizeMatrix::type numericalDerivative52( + boost::function h, const X1& x1, + const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument Y must be a manifold type."); + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument X1 must be a manifold type."); + return numericalDerivative11(boost::bind(h, x1, _1, x3, x4, x5), x2, delta); +} + +template +inline typename internal::FixedSizeMatrix::type numericalDerivative51(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + return numericalDerivative52(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5); +} + +/** + * Compute numerical derivative in argument 3 of 5-argument function + * @param h quintic function yielding m-vector + * @param x1 n-dimensional first argument value + * @param x2 second argument value + * @param x3 third argument value + * @param x4 fourth argument value + * @param x5 fifth argument value + * @param delta increment for numerical derivative + * @return m*n Jacobian computed via central differencing + */ +template +typename internal::FixedSizeMatrix::type numericalDerivative53( + boost::function h, const X1& x1, + const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument Y must be a manifold type."); + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument X1 must be a manifold type."); + return numericalDerivative11(boost::bind(h, x1, x2, _1, x4, x5), x3, delta); +} + +template +inline typename internal::FixedSizeMatrix::type numericalDerivative53(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + return numericalDerivative53(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5); +} + +/** + * Compute numerical derivative in argument 4 of 5-argument function + * @param h quintic function yielding m-vector + * @param x1 n-dimensional first argument value + * @param x2 second argument value + * @param x3 third argument value + * @param x4 fourth argument value + * @param x5 fifth argument value + * @param delta increment for numerical derivative + * @return m*n Jacobian computed via central differencing + */ +template +typename internal::FixedSizeMatrix::type numericalDerivative54( + boost::function h, const X1& x1, + const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument Y must be a manifold type."); + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument X1 must be a manifold type."); + return numericalDerivative11(boost::bind(h, x1, x2, x3, _1, x5), x4, delta); +} + +template +inline typename internal::FixedSizeMatrix::type numericalDerivative53(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + return numericalDerivative54(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5); +} + +/** + * Compute numerical derivative in argument 5 of 5-argument function + * @param h quintic function yielding m-vector + * @param x1 n-dimensional first argument value + * @param x2 second argument value + * @param x3 third argument value + * @param x4 fourth argument value + * @param x5 fifth argument value + * @param delta increment for numerical derivative + * @return m*n Jacobian computed via central differencing + */ +template +typename internal::FixedSizeMatrix::type numericalDerivative55( + boost::function h, const X1& x1, + const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument Y must be a manifold type."); + BOOST_STATIC_ASSERT_MSG( (boost::is_base_of::structure_category>::value), + "Template argument X1 must be a manifold type."); + return numericalDerivative11(boost::bind(h, x1, x2, x3, x4, _1), x5, delta); +} + +template +inline typename internal::FixedSizeMatrix::type numericalDerivative53(Y (*h)(const X1&, const X2&, const X3&, const X4&, const X5&), + const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, double delta = 1e-5) { + return numericalDerivative55(boost::bind(h, _1, _2, _3, _4, _5), x1, x2, x3, x4, x5); +} + /** * Compute numerical Hessian matrix. Requires a single-argument Lie->scalar * function. This is implemented simply as the derivative of the gradient. diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index c55e5067b..4ef09beb1 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -24,6 +24,9 @@ #include +#include + + // whether to print the serialized text to stdout const bool verbose = false; @@ -142,4 +145,3 @@ bool equalsDereferencedBinary(const T& input = T()) { } // \namespace serializationTestHelpers } // \namespace gtsam - diff --git a/gtsam/base/tests/testSerializationBase.cpp b/gtsam/base/tests/testSerializationBase.cpp index 1db28bcc8..d863eaba3 100644 --- a/gtsam/base/tests/testSerializationBase.cpp +++ b/gtsam/base/tests/testSerializationBase.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -11,7 +11,7 @@ /** * @file testSerializationBase.cpp - * @brief + * @brief * @author Richard Roberts * @date Feb 7, 2012 */ diff --git a/gtsam/geometry/CalibratedCamera.cpp b/gtsam/geometry/CalibratedCamera.cpp index 026becebe..3c9fb1563 100644 --- a/gtsam/geometry/CalibratedCamera.cpp +++ b/gtsam/geometry/CalibratedCamera.cpp @@ -142,8 +142,11 @@ Point2 PinholeBase::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, Matrix23 Dpc_rot; Matrix2 Dpc_point; const Unit3 pc = pose().rotation().unrotate(pw, Dpose ? &Dpc_rot : 0, - Dpose ? &Dpc_point : 0); - + Dpoint ? &Dpc_point : 0); +#ifdef GTSAM_THROW_CHEIRALITY_EXCEPTION + if (pc.unitVector().z() <= 0) + throw CheiralityException(); +#endif // camera to normalized image coordinate Matrix2 Dpn_pc; const Point2 pn = Project(pc, Dpose || Dpoint ? &Dpn_pc : 0); @@ -161,8 +164,12 @@ Point2 PinholeBase::project2(const Unit3& pw, OptionalJacobian<2, 6> Dpose, return pn; } /* ************************************************************************* */ -Point3 PinholeBase::backproject_from_camera(const Point2& p, - const double depth) { +Point3 PinholeBase::BackprojectFromCamera(const Point2& p, + const double depth, OptionalJacobian<3, 2> Dpoint, OptionalJacobian<3, 1> Ddepth) { + if (Dpoint) + *Dpoint << depth, 0, 0, depth, 0, 0; + if (Ddepth) + *Ddepth << p.x(), p.y(), 1; return Point3(p.x() * depth, p.y() * depth, depth); } diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index f1fa509c1..f2bed032f 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -201,7 +201,9 @@ public: OptionalJacobian<2, 2> Dpoint = boost::none) const; /// backproject a 2-dimensional point to a 3-dimensional point at given depth - static Point3 backproject_from_camera(const Point2& p, const double depth); + static Point3 BackprojectFromCamera(const Point2& p, const double depth, + OptionalJacobian<3, 2> Dpoint = boost::none, + OptionalJacobian<3, 1> Ddepth = boost::none); /// @} /// @name Advanced interface @@ -337,8 +339,28 @@ public: boost::none, OptionalJacobian<2, 3> Dpoint = boost::none) const; /// backproject a 2-dimensional point to a 3-dimensional point at given depth - Point3 backproject(const Point2& pn, double depth) const { - return pose().transform_from(backproject_from_camera(pn, depth)); + Point3 backproject(const Point2& pn, double depth, + OptionalJacobian<3, 6> Dresult_dpose = boost::none, + OptionalJacobian<3, 2> Dresult_dp = boost::none, + OptionalJacobian<3, 1> Dresult_ddepth = boost::none) const { + + Matrix32 Dpoint_dpn; + Matrix31 Dpoint_ddepth; + const Point3 point = BackprojectFromCamera(pn, depth, + Dresult_dp ? &Dpoint_dpn : 0, + Dresult_ddepth ? &Dpoint_ddepth : 0); + + Matrix33 Dresult_dpoint; + const Point3 result = pose().transform_from(point, Dresult_dpose, + (Dresult_ddepth || + Dresult_dp) ? &Dresult_dpoint : 0); + + if (Dresult_dp) + *Dresult_dp = Dresult_dpoint * Dpoint_dpn; + if (Dresult_ddepth) + *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth; + + return result; } /** @@ -404,4 +426,3 @@ template struct Range : HasRange {}; } // namespace gtsam - diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 43ba78ea2..937eb0785 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -85,25 +85,9 @@ public: return pn; } - /** project a point from world coordinate to the image - * @param pw is a point in the world coordinates - */ - Point2 project(const Point3& pw) const { - const Point2 pn = PinholeBase::project2(pw); // project to normalized coordinates - return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates - } - - /** project a point from world coordinate to the image - * @param pw is a point at infinity in the world coordinates - */ - Point2 project(const Unit3& pw) const { - const Unit3 pc = pose().rotation().unrotate(pw); // convert to camera frame - const Point2 pn = PinholeBase::Project(pc); // project to normalized coordinates - return calibration().uncalibrate(pn); // uncalibrate to pixel coordinates - } /** Templated projection of a point (possibly at infinity) from world coordinate to the image - * @param pw is a 3D point or aUnit3 (point at infinity) in world coordinates + * @param pw is a 3D point or a Unit3 (point at infinity) in world coordinates * @param Dpose is the Jacobian w.r.t. pose3 * @param Dpoint is the Jacobian w.r.t. point3 * @param Dcal is the Jacobian w.r.t. calibration @@ -131,25 +115,51 @@ public: } /// project a 3D point from world coordinates into the image - Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose, + Point2 project(const Point3& pw, OptionalJacobian<2, 6> Dpose = boost::none, OptionalJacobian<2, 3> Dpoint = boost::none, OptionalJacobian<2, DimK> Dcal = boost::none) const { return _project(pw, Dpose, Dpoint, Dcal); } /// project a point at infinity from world coordinates into the image - Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose, + Point2 project(const Unit3& pw, OptionalJacobian<2, 6> Dpose = boost::none, OptionalJacobian<2, 2> Dpoint = boost::none, OptionalJacobian<2, DimK> Dcal = boost::none) const { return _project(pw, Dpose, Dpoint, Dcal); } /// backproject a 2-dimensional point to a 3-dimensional point at given depth - Point3 backproject(const Point2& p, double depth) const { - const Point2 pn = calibration().calibrate(p); - return pose().transform_from(backproject_from_camera(pn, depth)); + Point3 backproject(const Point2& p, double depth, + OptionalJacobian<3, 6> Dresult_dpose = boost::none, + OptionalJacobian<3, 2> Dresult_dp = boost::none, + OptionalJacobian<3, 1> Dresult_ddepth = boost::none, + OptionalJacobian<3, DimK> Dresult_dcal = boost::none) const { + typedef Eigen::Matrix Matrix2K; + Matrix2K Dpn_dcal; + Matrix22 Dpn_dp; + const Point2 pn = calibration().calibrate(p, Dresult_dcal ? &Dpn_dcal : 0, + Dresult_dp ? &Dpn_dp : 0); + Matrix32 Dpoint_dpn; + Matrix31 Dpoint_ddepth; + const Point3 point = BackprojectFromCamera(pn, depth, + (Dresult_dp || Dresult_dcal) ? &Dpoint_dpn : 0, + Dresult_ddepth ? &Dpoint_ddepth : 0); + Matrix33 Dresult_dpoint; + const Point3 result = pose().transform_from(point, Dresult_dpose, + (Dresult_ddepth || + Dresult_dp || + Dresult_dcal) ? &Dresult_dpoint : 0); + if (Dresult_dcal) + *Dresult_dcal = Dresult_dpoint * Dpoint_dpn * Dpn_dcal; // (3x3)*(3x2)*(2xDimK) + if (Dresult_dp) + *Dresult_dp = Dresult_dpoint * Dpoint_dpn * Dpn_dp; // (3x3)*(3x2)*(2x2) + if (Dresult_ddepth) + *Dresult_ddepth = Dresult_dpoint * Dpoint_ddepth; // (3x3)*(3x1) + + return result; } + /// backproject a 2-dimensional point to a 3-dimensional point at infinity Unit3 backprojectPointAtInfinity(const Point2& p) const { const Point2 pn = calibration().calibrate(p); @@ -302,6 +312,11 @@ public: Base(v), K_(new CALIBRATION(K)) { } + // Init from Pose3 and calibration + PinholePose(const Pose3 &pose, const Vector &K) : + Base(pose), K_(new CALIBRATION(K)) { + } + /// @} /// @name Testable /// @{ diff --git a/gtsam/geometry/tests/testCalibratedCamera.cpp b/gtsam/geometry/tests/testCalibratedCamera.cpp index e629eb3c6..33a88db1f 100644 --- a/gtsam/geometry/tests/testCalibratedCamera.cpp +++ b/gtsam/geometry/tests/testCalibratedCamera.cpp @@ -113,7 +113,7 @@ static Point2 Project2(const Unit3& point) { return PinholeBase::Project(point); } -Unit3 pointAtInfinity(0, 0, 1000); +Unit3 pointAtInfinity(0, 0, -1000); TEST( CalibratedCamera, DProjectInfinity) { Matrix test1; CalibratedCamera::Project(pointAtInfinity, test1); @@ -127,6 +127,7 @@ static Point2 project2(const CalibratedCamera& camera, const Point3& point) { return camera.project(point); } + TEST( CalibratedCamera, Dproject_point_pose) { Matrix Dpose, Dpoint; @@ -173,7 +174,7 @@ TEST( CalibratedCamera, Dproject_point_pose_infinity) // Add a test with more arbitrary rotation TEST( CalibratedCamera, Dproject_point_pose2_infinity) { - static const Pose3 pose(Rot3::Ypr(0.1, -0.1, 0.4), Point3(0, 0, -10)); + static const Pose3 pose(Rot3::Ypr(-M_PI/4.0, M_PI + M_PI/9.5, M_PI/8.0), Point3(0, 0, -10)); static const CalibratedCamera camera(pose); Matrix Dpose, Dpoint; camera.project2(pointAtInfinity, Dpose, Dpoint); @@ -183,7 +184,48 @@ TEST( CalibratedCamera, Dproject_point_pose2_infinity) CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); } +static Point3 BackprojectFromCamera(const CalibratedCamera& camera, const Point2& point, + const double& depth) { + return camera.BackprojectFromCamera(point, depth); +} +TEST( CalibratedCamera, DBackprojectFromCamera) +{ + static const Pose3 pose(Rot3::Ypr(-M_PI/4.0, M_PI + M_PI/9.5, M_PI/8.0), Point3(0, 0, -10)); + static const CalibratedCamera camera(pose); + static const double depth = 5.4; + static const Point2 point(10.1, 50.3); + Matrix Dpoint, Ddepth; + camera.BackprojectFromCamera(point, depth, Dpoint, Ddepth); + Matrix numerical_point = numericalDerivative32(BackprojectFromCamera, camera, point, depth); + Matrix numerical_depth = numericalDerivative33(BackprojectFromCamera, camera, point, depth); + CHECK(assert_equal(numerical_point, Dpoint, 1e-7)); + CHECK(assert_equal(numerical_depth, Ddepth, 1e-7)); +} + + +static Point3 backproject(const Pose3& pose, const Point2& point, const double& depth) { + return CalibratedCamera(pose).backproject(point, depth); +} +TEST( PinholePose, Dbackproject) +{ + Matrix36 Dpose; + Matrix31 Ddepth; + Matrix32 Dpoint; + const Point2 point(-100, 100); + const double depth(10); + static const Pose3 pose(Rot3::Ypr(-M_PI/4.0, M_PI + M_PI/9.5, M_PI/8.0), Point3(0, 0, -10)); + static const CalibratedCamera camera(pose); + camera.backproject(point, depth, Dpose, Dpoint, Ddepth); + Matrix expectedDpose = numericalDerivative31(backproject, pose, point, depth); + Matrix expectedDpoint = numericalDerivative32(backproject, pose, point, depth); + Matrix expectedDdepth = numericalDerivative33(backproject, pose,point, depth); + + EXPECT(assert_equal(expectedDpose, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDdepth, Ddepth, 1e-7)); +} + + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - diff --git a/gtsam/geometry/tests/testPinholePose.cpp b/gtsam/geometry/tests/testPinholePose.cpp index ecbb92061..05d48f4cc 100644 --- a/gtsam/geometry/tests/testPinholePose.cpp +++ b/gtsam/geometry/tests/testPinholePose.cpp @@ -191,7 +191,7 @@ static Point2 project(const Pose3& pose, const Unit3& pointAtInfinity, /* ************************************************************************* */ TEST( PinholePose, DprojectAtInfinity2) { - Unit3 pointAtInfinity(0,0,1000); + Unit3 pointAtInfinity(0,0,-1000); Matrix Dpose, Dpoint; Point2 result = camera.project2(pointAtInfinity, Dpose, Dpoint); Matrix expectedDcamera = numericalDerivative31(project, pose, pointAtInfinity, K); @@ -201,6 +201,32 @@ TEST( PinholePose, DprojectAtInfinity2) EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); } + +static Point3 backproject(const Pose3& pose, const Cal3_S2& cal, + const Point2& p, const double& depth) { + return Camera(pose, cal.vector()).backproject(p, depth); +} + +TEST( PinholePose, Dbackproject) +{ + Matrix36 Dpose; + Matrix31 Ddepth; + Matrix32 Dpoint; + Matrix Dcal; + const Point2 point(-100, 100); + const double depth(10); + camera.backproject(point, depth, Dpose, Dpoint, Ddepth, Dcal); + Matrix expectedDpose = numericalDerivative41(backproject, pose, *K, point, depth); + Matrix expectedDcal = numericalDerivative42(backproject, pose, *K, point, depth); + Matrix expectedDpoint = numericalDerivative43(backproject, pose, *K, point, depth); + Matrix expectedDdepth = numericalDerivative44(backproject, pose, *K, point, depth); + + EXPECT(assert_equal(expectedDpose, Dpose, 1e-7)); + EXPECT(assert_equal(expectedDcal, Dcal, 1e-7)); + EXPECT(assert_equal(expectedDpoint, Dpoint, 1e-7)); + EXPECT(assert_equal(expectedDdepth, Ddepth, 1e-7)); +} + /* ************************************************************************* */ static double range0(const Camera& camera, const Point3& point) { return camera.range(point); diff --git a/python/handwritten/geometry/PinholeBaseK.cpp b/python/handwritten/geometry/PinholeBaseK.cpp index da98783e2..4153ecf06 100644 --- a/python/handwritten/geometry/PinholeBaseK.cpp +++ b/python/handwritten/geometry/PinholeBaseK.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -36,31 +36,38 @@ struct PinholeBaseKCal3_S2Callback : PinholeBaseKCal3_S2, wrapper Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; -Point2 (PinholeBaseKCal3_S2::*project3) (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 2 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; +// Function pointers to disambiguate project() calls +Point2 (PinholeBaseKCal3_S2::*project1) (const Point3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 3 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; +Point2 (PinholeBaseKCal3_S2::*project2) (const Unit3 &pw, OptionalJacobian< 2, 6 > Dpose, OptionalJacobian< 2, 2 > Dpoint, OptionalJacobian< 2, FixedDimension::value > Dcal) const = &PinholeBaseKCal3_S2::project; -// function pointers to desambiguate range() calls +// function pointers to disambiguate range() calls double (PinholeBaseKCal3_S2::*range1) (const Point3 &point, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 3 > Dpoint) const = &PinholeBaseKCal3_S2::range; double (PinholeBaseKCal3_S2::*range2) (const Pose3 &pose, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dpose) const = &PinholeBaseKCal3_S2::range; double (PinholeBaseKCal3_S2::*range3) (const CalibratedCamera &camera, OptionalJacobian< 1, 6 > Dcamera, OptionalJacobian< 1, 6 > Dother) const = &PinholeBaseKCal3_S2::range; -void exportPinholeBaseK(){ +// wrap projectSafe in a function that returns None or a tuple +// TODO(frank): find out how to return an ndarray instead +object project_safe(const PinholeBaseKCal3_S2& camera, const gtsam::Point3& p) { + auto result = camera.projectSafe(p); + if (result.second) + return make_tuple(result.first.x(), result.first.y()); + else + return object(); +} +void exportPinholeBaseK() { class_("PinholeBaseKCal3_S2", no_init) - .def("calibration", pure_virtual(&PinholeBaseKCal3_S2::calibration), return_value_policy()) - .def("project", project1) - .def("project", project2, project_overloads()) - .def("project", project3, project_overloads()) - .def("backproject", &PinholeBaseKCal3_S2::backproject) - .def("backproject_point_at_infinity", &PinholeBaseKCal3_S2::backprojectPointAtInfinity) - .def("range", range1, range_overloads()) - .def("range", range2, range_overloads()) - .def("range", range3, range_overloads()) - ; - -} \ No newline at end of file + .def("calibration", pure_virtual(&PinholeBaseKCal3_S2::calibration), + return_value_policy()) + .def("project_safe", make_function(project_safe)) + .def("project", project1, project_overloads()) + .def("project", project2, project_overloads()) + .def("backproject", &PinholeBaseKCal3_S2::backproject) + .def("backproject_point_at_infinity", &PinholeBaseKCal3_S2::backprojectPointAtInfinity) + .def("range", range1, range_overloads()) + .def("range", range2, range_overloads()) + .def("range", range3, range_overloads()); +} From ebf047b4aa15bbb880413da849651ff5ab7f5051 Mon Sep 17 00:00:00 2001 From: dellaert Date: Mon, 14 May 2018 00:39:36 -0700 Subject: [PATCH 030/197] Added return types --- gtsam/slam/dataset.cpp | 60 ++++++++++++++++++++---------------------- gtsam/slam/dataset.h | 36 ++++++++++++++----------- 2 files changed, 49 insertions(+), 47 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 40a2573b3..ba51864f1 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -11,7 +11,7 @@ /** * @file dataset.cpp * @date Jan 22, 2010 - * @author nikai, Luca Carlone + * @author Kai Ni, Luca Carlone, Frank Dellaert * @brief utility functions for loading datasets */ @@ -56,8 +56,10 @@ namespace gtsam { string findExampleDataFile(const string& name) { // Search source tree and installed location vector rootsToSearch; - rootsToSearch.push_back(GTSAM_SOURCE_TREE_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt - rootsToSearch.push_back(GTSAM_INSTALLED_DATASET_DIR); // Defined by CMake, see gtsam/gtsam/CMakeLists.txt + + // Constants below are defined by CMake, see gtsam/gtsam/CMakeLists.txt + rootsToSearch.push_back(GTSAM_SOURCE_TREE_DATASET_DIR); + rootsToSearch.push_back(GTSAM_INSTALLED_DATASET_DIR); // Search for filename as given, and with .graph and .txt extensions vector namesToSearch; @@ -75,12 +77,11 @@ string findExampleDataFile(const string& name) { } // If we did not return already, then we did not find the file - throw -invalid_argument( - "gtsam::findExampleDataFile could not find a matching file in\n" - GTSAM_SOURCE_TREE_DATASET_DIR " or\n" - GTSAM_INSTALLED_DATASET_DIR " named\n" + - name + ", " + name + ".graph, or " + name + ".txt"); + throw invalid_argument( + "gtsam::findExampleDataFile could not find a matching file in\n" + GTSAM_SOURCE_TREE_DATASET_DIR " or\n" + GTSAM_INSTALLED_DATASET_DIR " named\n" + name + ", " + name + + ".graph, or " + name + ".txt"); } /* ************************************************************************* */ @@ -98,6 +99,7 @@ string createRewrittenFileName(const string& name) { return newpath.string(); } + /* ************************************************************************* */ #endif @@ -116,23 +118,20 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, double v1, v2, v3, v4, v5, v6; is >> v1 >> v2 >> v3 >> v4 >> v5 >> v6; - if (noiseFormat == NoiseFormatAUTO) - { - // Try to guess covariance matrix layout - if(v1 != 0.0 && v2 == 0.0 && v3 != 0.0 && v4 != 0.0 && v5 == 0.0 && v6 == 0.0) - { - // NoiseFormatGRAPH - noiseFormat = NoiseFormatGRAPH; - } - else if(v1 != 0.0 && v2 == 0.0 && v3 == 0.0 && v4 != 0.0 && v5 == 0.0 && v6 != 0.0) - { - // NoiseFormatCOV - noiseFormat = NoiseFormatCOV; - } - else - { - throw std::invalid_argument("load2D: unrecognized covariance matrix format in dataset file. Please specify the noise format."); - } + if (noiseFormat == NoiseFormatAUTO) { + // Try to guess covariance matrix layout + if (v1 != 0.0 && v2 == 0.0 && v3 != 0.0 && v4 != 0.0 && v5 == 0.0 + && v6 == 0.0) { + // NoiseFormatGRAPH + noiseFormat = NoiseFormatGRAPH; + } else if (v1 != 0.0 && v2 == 0.0 && v3 == 0.0 && v4 != 0.0 && v5 == 0.0 + && v6 != 0.0) { + // NoiseFormatCOV + noiseFormat = NoiseFormatCOV; + } else { + throw std::invalid_argument( + "load2D: unrecognized covariance matrix format in dataset file. Please specify the noise format."); + } } // Read matrix and check that diagonal entries are non-zero @@ -196,27 +195,26 @@ static SharedNoiseModel readNoiseModel(ifstream& is, bool smart, } /* ************************************************************************* */ -boost::optional > parseVertex(istream& is, const string& tag) { +boost::optional parseVertex(istream& is, const string& tag) { if ((tag == "VERTEX2") || (tag == "VERTEX_SE2") || (tag == "VERTEX")) { Key id; double x, y, yaw; is >> id >> x >> y >> yaw; - return pair(id, Pose2(x, y, yaw)); + return IndexedPose(id, Pose2(x, y, yaw)); } else { return boost::none; } } /* ************************************************************************* */ -boost::optional, Pose2> > parseEdge(istream& is, const string& tag) { +boost::optional parseEdge(istream& is, const string& tag) { if ((tag == "EDGE2") || (tag == "EDGE") || (tag == "EDGE_SE2") || (tag == "ODOMETRY")) { Key id1, id2; double x, y, yaw; is >> id1 >> id2 >> x >> y >> yaw; - return pair, Pose2>(pair(id1, id2), - Pose2(x, y, yaw)); + return IndexedEdge(pair(id1, id2), Pose2(x, y, yaw)); } else { return boost::none; } diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 76dd398a0..929ada2c1 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -72,6 +72,26 @@ enum KernelFunctionType { KernelFunctionTypeNONE, KernelFunctionTypeHUBER, KernelFunctionTypeTUKEY }; +/// Return type for auxiliary functions +typedef std::pair IndexedPose; +typedef std::pair, Pose2> IndexedEdge; + +/** + * Parse TORO/G2O vertex "id x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if vertex type + */ +GTSAM_EXPORT boost::optional parseVertex(std::istream& is, + const std::string& tag); + +/** + * Parse TORO/G2O edge "id1 id2 x y yaw" + * @param is input stream + * @param tag string parsed from input stream, will only parse if edge type + */ +GTSAM_EXPORT boost::optional parseEdge(std::istream& is, + const std::string& tag); + /// Return type for load functions typedef std::pair GraphAndValues; @@ -89,22 +109,6 @@ GTSAM_EXPORT GraphAndValues load2D( NoiseFormat noiseFormat = NoiseFormatAUTO, KernelFunctionType kernelFunctionType = KernelFunctionTypeNONE); -/** - * Parse TORO/G2O vertex "id x y yaw" - * @param is input stream - * @param tag string parsed from input stream, will only parse if vertex type - */ -boost::optional > parseVertex(std::istream& is, - const std::string& tag); - -/** - * Parse TORO/G2O edge "id1 id2 x y yaw" - * @param is input stream - * @param tag string parsed from input stream, will only parse if edge type - */ -boost::optional, Pose2> > parseEdge( - std::istream& is, const std::string& tag); - /** * Load TORO/G2O style graph files * @param filename From 646f56413f0ec5f79000d46b3a567de7b30236be Mon Sep 17 00:00:00 2001 From: AltNav NUC Date: Mon, 14 May 2018 17:40:48 -0700 Subject: [PATCH 031/197] Update calling convention for pre-integrated IMU measurements in IMUKittiExampleGps, fix scope problem in plot3DTrajectory and make sure that all accessed values are of type Pose3 --- matlab/+gtsam/plot3DTrajectory.m | 87 +++++++++++----------- matlab/gtsam_examples/IMUKittiExampleGPS.m | 33 +++++--- 2 files changed, 65 insertions(+), 55 deletions(-) mode change 100644 => 100755 matlab/+gtsam/plot3DTrajectory.m mode change 100644 => 100755 matlab/gtsam_examples/IMUKittiExampleGPS.m diff --git a/matlab/+gtsam/plot3DTrajectory.m b/matlab/+gtsam/plot3DTrajectory.m old mode 100644 new mode 100755 index 2900aed99..ad8d71c4c --- a/matlab/+gtsam/plot3DTrajectory.m +++ b/matlab/+gtsam/plot3DTrajectory.m @@ -7,8 +7,10 @@ if ~exist('frames','var'), scale=[]; end import gtsam.* +Pose3Values = gtsam.utilities.allPose3s(values); + haveMarginals = exist('marginals', 'var'); -keys = KeyVector(values.keys); +keys = KeyVector(Pose3Values.keys); holdstate = ishold; hold on @@ -16,49 +18,48 @@ hold on % Plot poses and covariance matrices lastIndex = []; for i = 0:keys.size-1 - key = keys.at(i); - try - x = values.atPose3(key); - if ~isempty(lastIndex) - % Draw line from last pose then covariance ellipse on top of - % last pose. - lastKey = keys.at(lastIndex); - try - lastPose = values.atPose3(lastKey); - plot3([ x.x; lastPose.x ], [ x.y; lastPose.y ], [ x.z; lastPose.z ], linespec); - if haveMarginals - P = marginals.marginalCovariance(lastKey); - else - P = []; - end - gtsam.plotPose3(lastPose, P, scale); - catch err - % warning(['no Pose3 at ' lastKey]); - end - end - lastIndex = i; - catch - % warning(['no Pose3 at ' key]); - end - - % Draw final pose + key = keys.at(i); + try + x = Pose3Values.atPose3(key); if ~isempty(lastIndex) - lastKey = keys.at(lastIndex); - try - lastPose = values.atPose3(lastKey); - if haveMarginals - P = marginals.marginalCovariance(lastKey); - else - P = []; - end - gtsam.plotPose3(lastPose, P, scale); - catch - % warning(['no Pose3 at ' lastIndex]); + % Draw line from last pose then covariance ellipse on top of + % last pose. + lastKey = keys.at(lastIndex); + try + lastPose = Pose3Values.atPose3(lastKey); + plot3([ x.x; lastPose.x ], [ x.y; lastPose.y ], [ x.z; lastPose.z ], linespec); + if haveMarginals + P = marginals.marginalCovariance(lastKey); + else + P = []; end + gtsam.plotPose3(lastPose, P, scale); + catch err + % warning(['no Pose3 at ' lastKey]); + end end - - if ~holdstate - hold off + lastIndex = i; + catch + warning(['no Pose3 at ' key]); + end +end + +% Draw final pose +if ~isempty(lastIndex) + lastKey = keys.at(lastIndex); + try + lastPose = Pose3Values.atPose3(lastKey); + if haveMarginals + P = marginals.marginalCovariance(lastKey); + else + P = []; end - -end \ No newline at end of file + gtsam.plotPose3(lastPose, P, scale); + catch + % warning(['no Pose3 at ' lastIndex]); + end +end + +if ~holdstate + hold off +end diff --git a/matlab/gtsam_examples/IMUKittiExampleGPS.m b/matlab/gtsam_examples/IMUKittiExampleGPS.m old mode 100644 new mode 100755 index 32f61e47f..c80b6ec3e --- a/matlab/gtsam_examples/IMUKittiExampleGPS.m +++ b/matlab/gtsam_examples/IMUKittiExampleGPS.m @@ -42,6 +42,13 @@ sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadat g = [0;0;-9.8]; w_coriolis = [0;0;0]; +IMU_params = PreintegrationParams(g); + +IMU_params.setAccelerometerCovariance(IMU_metadata.AccelerometerSigma.^2 * eye(3)); +IMU_params.setGyroscopeCovariance(IMU_metadata.GyroscopeSigma.^2 * eye(3)); +IMU_params.setIntegrationCovariance(IMU_metadata.IntegrationSigma.^2 * eye(3)); +IMU_params.setOmegaCoriolis(w_coriolis); + %% Solver object isamParams = ISAM2Params; isamParams.setFactorization('CHOLESKY'); @@ -65,7 +72,7 @@ for measurementIndex = firstGPSPose:length(GPS_data) currentVelKey = symbol('v',measurementIndex); currentBiasKey = symbol('b',measurementIndex); t = GPS_data(measurementIndex, 1).Time; - + if measurementIndex == firstGPSPose %% Create initial estimate and prior on initial pose, velocity, and biases newValues.insert(currentPoseKey, currentPoseGlobal); @@ -78,10 +85,8 @@ for measurementIndex = firstGPSPose:length(GPS_data) t_previous = GPS_data(measurementIndex-1, 1).Time; %% Summarize IMU data between the previous GPS measurement and now IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t); - - currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ... - currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ... - IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3)); + + currentSummarizedMeasurement = PreintegratedImuMeasurements(IMU_params,currentBias); for imuIndex = IMUindices accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ]; @@ -94,8 +99,8 @@ for measurementIndex = firstGPSPose:length(GPS_data) newFactors.add(ImuFactor( ... currentPoseKey-1, currentVelKey-1, ... currentPoseKey, currentVelKey, ... - currentBiasKey, currentSummarizedMeasurement, g, w_coriolis)); - + currentBiasKey, currentSummarizedMeasurement)); + % Bias evolution as given in the IMU metadata newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ... noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b))); @@ -119,10 +124,13 @@ for measurementIndex = firstGPSPose:length(GPS_data) isam.update(newFactors, newValues); newFactors = NonlinearFactorGraph; newValues = Values; + + result = isam.calculateEstimate(); if rem(measurementIndex,10)==0 % plot every 10 time steps cla; - plot3DTrajectory(isam.calculateEstimate, 'g-'); + + plot3DTrajectory(result, 'g-'); title('Estimated trajectory using ISAM2 (IMU+GPS)') xlabel('[m]') ylabel('[m]') @@ -131,12 +139,13 @@ for measurementIndex = firstGPSPose:length(GPS_data) drawnow; end % ======================================================================= - currentPoseGlobal = isam.calculateEstimate(currentPoseKey); - currentVelocityGlobal = isam.calculateEstimate(currentVelKey); - currentBias = isam.calculateEstimate(currentBiasKey); + + currentPoseGlobal = result.atPose3(currentPoseKey); + currentVelocityGlobal = result.atVector(currentVelKey); + currentBias = result.atConstantBias(currentBiasKey); end end - + end % end main loop disp('-- Reached end of sensor data') From 1a3a9383361cb7d895e453bc006b1f1ffb9d3421 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 11 Jun 2018 22:29:02 +0000 Subject: [PATCH 032/197] Added Google groups link. --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 2632fbe2e..02ed5149c 100644 --- a/README.md +++ b/README.md @@ -62,10 +62,11 @@ If you are using the factor in academic work, please cite the publications above In GTSAM 4 a new and more efficient implementation, based on integrating on the NavState tangent space and detailed in docs/ImuFactor.pdf, is enabled by default. To switch to the RSS 2015 version, set the flag **GTSAM_TANGENT_PREINTEGRATION** to OFF. - Additional Information ---------------------- +There is a [`GTSAM users Google group`](https://groups.google.com/forum/#!forum/gtsam-users) for general discussion. + Read about important [`GTSAM-Concepts`](GTSAM-Concepts.md) here. A primer on GTSAM Expressions, which support (superfast) automatic differentiation, can be found on the [GTSAM wiki on BitBucket](https://bitbucket.org/gtborg/gtsam/wiki/Home). From bbe30c31bb84f1a9f0f4707b1944382ce16639a3 Mon Sep 17 00:00:00 2001 From: Jing Dong Date: Tue, 19 Jun 2018 01:00:20 -0400 Subject: [PATCH 033/197] remove some wrapping terms to fix toolbox compile --- gtsam.h | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/gtsam.h b/gtsam.h index a5e24715a..d0be06652 100644 --- a/gtsam.h +++ b/gtsam.h @@ -969,9 +969,10 @@ virtual class SimpleCamera { // Some typedefs for common camera types // PinholeCameraCal3_S2 is the same as SimpleCamera above typedef gtsam::PinholeCamera PinholeCameraCal3_S2; -typedef gtsam::PinholeCamera PinholeCameraCal3DS2; -typedef gtsam::PinholeCamera PinholeCameraCal3Unified; -typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; +// due to lack of jacobians of Cal3DS2_Base::calibrate, PinholeCamera does not apply to Cal3DS2/Unified +//typedef gtsam::PinholeCamera PinholeCameraCal3DS2; +//typedef gtsam::PinholeCamera PinholeCameraCal3Unified; +//typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; #include class StereoCamera { @@ -2337,7 +2338,8 @@ virtual class GeneralSFMFactor : gtsam::NoiseModelFactor { gtsam::Point2 measured() const; }; typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3_S2; -typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; +// due to lack of jacobians of Cal3DS2_Base::calibrate, GeneralSFMFactor does not apply to Cal3DS2 +//typedef gtsam::GeneralSFMFactor GeneralSFMFactorCal3DS2; template virtual class GeneralSFMFactor2 : gtsam::NoiseModelFactor { From b04c0bb15d88e36ca5e1c268bf8930166b473f4a Mon Sep 17 00:00:00 2001 From: Sean Bowman Date: Sat, 13 May 2017 19:35:05 -0400 Subject: [PATCH 034/197] Fix memory alignment issues --- gtsam/geometry/CalibratedCamera.h | 1 + gtsam/geometry/CameraSet.h | 18 ++++--- gtsam/geometry/PinholeCamera.h | 1 + gtsam/geometry/PinholeSet.h | 2 +- gtsam/geometry/Point2.h | 2 +- gtsam/geometry/Pose3.h | 3 ++ gtsam/geometry/Rot3.h | 3 ++ gtsam/geometry/StereoCamera.h | 1 + gtsam/geometry/StereoPoint2.h | 2 + gtsam/geometry/tests/testCameraSet.cpp | 4 +- gtsam/geometry/tests/testPinholeSet.cpp | 4 +- gtsam/geometry/tests/testPose2.cpp | 4 +- gtsam/geometry/tests/testTriangulation.cpp | 20 ++++---- gtsam/geometry/triangulation.cpp | 4 +- gtsam/geometry/triangulation.h | 40 ++++++++------- gtsam/navigation/CombinedImuFactor.h | 10 +++- gtsam/navigation/ImuBias.h | 3 ++ gtsam/navigation/PreintegratedRotation.h | 6 +++ gtsam/navigation/PreintegrationParams.h | 7 ++- gtsam/slam/JacobianFactorQ.h | 2 +- gtsam/slam/JacobianFactorQR.h | 2 +- gtsam/slam/JacobianFactorSVD.h | 2 +- gtsam/slam/RegularImplicitSchurFactor.h | 6 +-- gtsam/slam/SmartFactorBase.h | 42 ++++++++-------- gtsam/slam/SmartProjectionFactor.h | 10 ++-- gtsam/slam/tests/smartFactorScenarios.h | 2 +- .../tests/testRegularImplicitSchurFactor.cpp | 2 +- .../tests/testSmartProjectionCameraFactor.cpp | 16 +++--- .../tests/testSmartProjectionPoseFactor.cpp | 50 +++++++++---------- .../slam/SmartStereoProjectionFactor.h | 25 +++++----- .../testSmartStereoProjectionPoseFactor.cpp | 2 +- 31 files changed, 167 insertions(+), 129 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index f2bed032f..cd2277965 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -55,6 +55,7 @@ public: * and this typedef informs those classes what "project" returns. */ typedef Point2 Measurement; + typedef Point2Vector MeasurementVector; private: diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index 18f311a23..709172c5b 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -31,7 +31,7 @@ namespace gtsam { * @brief A set of cameras, all with their own calibration */ template -class CameraSet: public std::vector { +class CameraSet : public std::vector > { protected: @@ -40,13 +40,14 @@ protected: * The order is kept the same as the keys that we use to create the factor. */ typedef typename CAMERA::Measurement Z; + typedef typename CAMERA::MeasurementVector ZVector; static const int D = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension /// Make a vector of re-projection errors - static Vector ErrorVector(const std::vector& predicted, - const std::vector& measured) { + static Vector ErrorVector(const ZVector& predicted, + const ZVector& measured) { // Check size size_t m = predicted.size(); @@ -69,7 +70,7 @@ public: /// Definitions for blocks of F typedef Eigen::Matrix MatrixZD; - typedef std::vector FBlocks; + typedef std::vector > FBlocks; /** * print @@ -102,7 +103,7 @@ public: * throws CheiralityException */ template - std::vector project2(const POINT& point, // + ZVector project2(const POINT& point, // boost::optional Fs = boost::none, // boost::optional E = boost::none) const { @@ -110,7 +111,7 @@ public: // Allocate result size_t m = this->size(); - std::vector z; + ZVector z; z.reserve(m); // Allocate derivatives @@ -131,7 +132,7 @@ public: /// Calculate vector [project2(point)-z] of re-projection errors template - Vector reprojectionError(const POINT& point, const std::vector& measured, + Vector reprojectionError(const POINT& point, const ZVector& measured, boost::optional Fs = boost::none, // boost::optional E = boost::none) const { return ErrorVector(project2(point, Fs, E), measured); @@ -315,6 +316,9 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { ar & (*this); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; template diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index a5707ce89..4c7fdf94d 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -39,6 +39,7 @@ public: * and this typedef informs those classes what "project" returns. */ typedef Point2 Measurement; + typedef Point2Vector MeasurementVector; private: diff --git a/gtsam/geometry/PinholeSet.h b/gtsam/geometry/PinholeSet.h index 65047df41..7869704ca 100644 --- a/gtsam/geometry/PinholeSet.h +++ b/gtsam/geometry/PinholeSet.h @@ -58,7 +58,7 @@ public: /// triangulateSafe TriangulationResult triangulateSafe( - const std::vector& measured, + const typename CAMERA::MeasurementVector& measured, const TriangulationParameters& params) const { return gtsam::triangulateSafe(*this, measured, params); } diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index fb250df6d..3657ebf05 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -164,7 +164,7 @@ typedef std::pair Point2Pair; std::ostream &operator<<(std::ostream &os, const gtsam::Point2Pair &p); // For MATLAB wrapper -typedef std::vector Point2Vector; +typedef std::vector > Point2Vector; /// multiply with scalar inline Point2 operator*(double s, const Point2& p) { diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 6df62485b..3229cbbbe 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -327,6 +327,9 @@ public: } /// @} + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; // Pose3 class diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 58c150670..263301122 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -508,6 +508,9 @@ namespace gtsam { #endif } + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; /** diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index ac32be7ae..db4f74026 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -43,6 +43,7 @@ public: * and this typedef informs those classes what "project" returns. */ typedef StereoPoint2 Measurement; + typedef StereoPoint2Vector MeasurementVector; private: Pose3 leftCamPose_; diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 961cc041b..dd9bc9dbd 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -159,6 +159,8 @@ private: }; +typedef std::vector StereoPoint2Vector; + template<> struct traits : public internal::VectorSpace {}; diff --git a/gtsam/geometry/tests/testCameraSet.cpp b/gtsam/geometry/tests/testCameraSet.cpp index 01f784ae0..560206b9f 100644 --- a/gtsam/geometry/tests/testCameraSet.cpp +++ b/gtsam/geometry/tests/testCameraSet.cpp @@ -32,7 +32,7 @@ using namespace gtsam; TEST(CameraSet, Pinhole) { typedef PinholeCamera Camera; typedef CameraSet Set; - typedef vector ZZ; + typedef Point2Vector ZZ; Set set; Camera camera; set.push_back(camera); @@ -135,8 +135,8 @@ TEST(CameraSet, Pinhole) { /* ************************************************************************* */ #include TEST(CameraSet, Stereo) { - typedef vector ZZ; CameraSet set; + typedef StereoCamera::MeasurementVector ZZ; StereoCamera camera; set.push_back(camera); set.push_back(camera); diff --git a/gtsam/geometry/tests/testPinholeSet.cpp b/gtsam/geometry/tests/testPinholeSet.cpp index 28b7ddac6..f32fe60ed 100644 --- a/gtsam/geometry/tests/testPinholeSet.cpp +++ b/gtsam/geometry/tests/testPinholeSet.cpp @@ -28,7 +28,7 @@ using namespace gtsam; /* ************************************************************************* */ #include TEST(PinholeSet, Stereo) { - typedef vector ZZ; + typedef Point2Vector ZZ; PinholeSet set; CalibratedCamera camera; set.push_back(camera); @@ -72,7 +72,7 @@ TEST(PinholeSet, Stereo) { #include TEST(PinholeSet, Pinhole) { typedef PinholeCamera Camera; - typedef vector ZZ; + typedef Point2Vector ZZ; PinholeSet set; Camera camera; set.push_back(camera); diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index 10fd431bc..ca550cdc7 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -743,7 +743,7 @@ namespace { /* ************************************************************************* */ struct Triangle { size_t i_,j_,k_;}; - boost::optional align2(const vector& ps, const vector& qs, + boost::optional align2(const Point2Vector& ps, const Point2Vector& qs, const pair& trianglePair) { const Triangle& t1 = trianglePair.first, t2 = trianglePair.second; vector correspondences; @@ -755,7 +755,7 @@ namespace { TEST(Pose2, align_4) { using namespace align_3; - vector ps,qs; + Point2Vector ps,qs; ps += p1, p2, p3; qs += q3, q1, q2; // note in 3,1,2 order ! diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index 9e599f3f5..97412f94d 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -60,7 +60,7 @@ Point2 z2 = camera2.project(landmark); TEST( triangulation, twoPoses) { vector poses; - vector measurements; + Point2Vector measurements; poses += pose1, pose2; measurements += z1, z2; @@ -108,7 +108,7 @@ TEST( triangulation, twoPosesBundler) { Point2 z2 = camera2.project(landmark); vector poses; - vector measurements; + Point2Vector measurements; poses += pose1, pose2; measurements += z1, z2; @@ -132,7 +132,7 @@ TEST( triangulation, twoPosesBundler) { //****************************************************************************** TEST( triangulation, fourPoses) { vector poses; - vector measurements; + Point2Vector measurements; poses += pose1, pose2; measurements += z1, z2; @@ -195,8 +195,8 @@ TEST( triangulation, fourPoses_distinct_Ks) { Point2 z1 = camera1.project(landmark); Point2 z2 = camera2.project(landmark); - vector cameras; - vector measurements; + CameraSet cameras; + Point2Vector measurements; cameras += camera1, camera2; measurements += z1, z2; @@ -260,8 +260,8 @@ TEST( triangulation, outliersAndFarLandmarks) { Point2 z1 = camera1.project(landmark); Point2 z2 = camera2.project(landmark); - vector cameras; - vector measurements; + CameraSet cameras; + Point2Vector measurements; cameras += camera1, camera2; measurements += z1, z2; @@ -308,7 +308,7 @@ TEST( triangulation, twoIdenticalPoses) { Point2 z1 = camera1.project(landmark); vector poses; - vector measurements; + Point2Vector measurements; poses += pose1, pose1; measurements += z1, z1; @@ -323,7 +323,7 @@ TEST( triangulation, onePose) { // because there's only one camera observation vector poses; - vector measurements; + Point2Vector measurements; poses += Pose3(); measurements += Point2(0,0); @@ -354,7 +354,7 @@ TEST( triangulation, StereotriangulateNonlinear ) { cameras.push_back(StereoCamera(Pose3(m1), stereoK)); cameras.push_back(StereoCamera(Pose3(m2), stereoK)); - vector measurements; + StereoPoint2Vector measurements; measurements += StereoPoint2(226.936, 175.212, 424.469); measurements += StereoPoint2(339.571, 285.547, 669.973); diff --git a/gtsam/geometry/triangulation.cpp b/gtsam/geometry/triangulation.cpp index a1dc3269a..8e9c140c2 100644 --- a/gtsam/geometry/triangulation.cpp +++ b/gtsam/geometry/triangulation.cpp @@ -25,7 +25,7 @@ namespace gtsam { Vector4 triangulateHomogeneousDLT( const std::vector& projection_matrices, - const std::vector& measurements, double rank_tol) { + const Point2Vector& measurements, double rank_tol) { // number of cameras size_t m = projection_matrices.size(); @@ -54,7 +54,7 @@ Vector4 triangulateHomogeneousDLT( } Point3 triangulateDLT(const std::vector& projection_matrices, - const std::vector& measurements, double rank_tol) { + const Point2Vector& measurements, double rank_tol) { Vector4 v = triangulateHomogeneousDLT(projection_matrices, measurements, rank_tol); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index fdfe32e8b..0f53705ad 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -19,6 +19,7 @@ #pragma once #include +#include #include #include #include @@ -53,7 +54,7 @@ public: */ GTSAM_EXPORT Vector4 triangulateHomogeneousDLT( const std::vector& projection_matrices, - const std::vector& measurements, double rank_tol = 1e-9); + const Point2Vector& measurements, double rank_tol = 1e-9); /** * DLT triangulation: See Hartley and Zisserman, 2nd Ed., page 312 @@ -64,7 +65,8 @@ GTSAM_EXPORT Vector4 triangulateHomogeneousDLT( */ GTSAM_EXPORT Point3 triangulateDLT( const std::vector& projection_matrices, - const std::vector& measurements, double rank_tol = 1e-9); + const Point2Vector& measurements, + double rank_tol = 1e-9); /** * Create a factor graph with projection factors from poses and one calibration @@ -78,7 +80,7 @@ GTSAM_EXPORT Point3 triangulateDLT( template std::pair triangulationGraph( const std::vector& poses, boost::shared_ptr sharedCal, - const std::vector& measurements, Key landmarkKey, + const Point2Vector& measurements, Key landmarkKey, const Point3& initialEstimate) { Values values; values.insert(landmarkKey, initialEstimate); // Initial landmark value @@ -106,8 +108,8 @@ std::pair triangulationGraph( */ template std::pair triangulationGraph( - const std::vector& cameras, - const std::vector& measurements, Key landmarkKey, + const CameraSet& cameras, + const typename CAMERA::MeasurementVector& measurements, Key landmarkKey, const Point3& initialEstimate) { Values values; values.insert(landmarkKey, initialEstimate); // Initial landmark value @@ -125,8 +127,8 @@ std::pair triangulationGraph( /// PinholeCamera specific version // TODO: (chris) why does this exist? template std::pair triangulationGraph( - const std::vector >& cameras, - const std::vector& measurements, Key landmarkKey, + const CameraSet >& cameras, + const Point2Vector& measurements, Key landmarkKey, const Point3& initialEstimate) { return triangulationGraph > // (cameras, measurements, landmarkKey, initialEstimate); @@ -153,7 +155,7 @@ GTSAM_EXPORT Point3 optimize(const NonlinearFactorGraph& graph, template Point3 triangulateNonlinear(const std::vector& poses, boost::shared_ptr sharedCal, - const std::vector& measurements, const Point3& initialEstimate) { + const Point2Vector& measurements, const Point3& initialEstimate) { // Create a factor graph and initial values Values values; @@ -173,8 +175,8 @@ Point3 triangulateNonlinear(const std::vector& poses, */ template Point3 triangulateNonlinear( - const std::vector& cameras, - const std::vector& measurements, const Point3& initialEstimate) { + const CameraSet& cameras, + const typename CAMERA::MeasurementVector& measurements, const Point3& initialEstimate) { // Create a factor graph and initial values Values values; @@ -188,8 +190,8 @@ Point3 triangulateNonlinear( /// PinholeCamera specific version // TODO: (chris) why does this exist? template Point3 triangulateNonlinear( - const std::vector >& cameras, - const std::vector& measurements, const Point3& initialEstimate) { + const CameraSet >& cameras, + const Point2Vector& measurements, const Point3& initialEstimate) { return triangulateNonlinear > // (cameras, measurements, initialEstimate); } @@ -228,7 +230,7 @@ private: template Point3 triangulatePoint3(const std::vector& poses, boost::shared_ptr sharedCal, - const std::vector& measurements, double rank_tol = 1e-9, + const Point2Vector& measurements, double rank_tol = 1e-9, bool optimize = false) { assert(poses.size() == measurements.size()); @@ -275,8 +277,8 @@ Point3 triangulatePoint3(const std::vector& poses, */ template Point3 triangulatePoint3( - const std::vector& cameras, - const std::vector& measurements, double rank_tol = 1e-9, + const CameraSet& cameras, + const typename CAMERA::MeasurementVector& measurements, double rank_tol = 1e-9, bool optimize = false) { size_t m = cameras.size(); @@ -312,8 +314,8 @@ Point3 triangulatePoint3( /// Pinhole-specific version template Point3 triangulatePoint3( - const std::vector >& cameras, - const std::vector& measurements, double rank_tol = 1e-9, + const CameraSet >& cameras, + const Point2Vector& measurements, double rank_tol = 1e-9, bool optimize = false) { return triangulatePoint3 > // (cameras, measurements, rank_tol, optimize); @@ -453,8 +455,8 @@ private: /// triangulateSafe: extensive checking of the outcome template -TriangulationResult triangulateSafe(const std::vector& cameras, - const std::vector& measured, +TriangulationResult triangulateSafe(const CameraSet& cameras, + const typename CAMERA::MeasurementVector& measured, const TriangulationParameters& params) { size_t m = cameras.size(); diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 99c45ff34..6fd98bfcb 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -83,12 +83,12 @@ public: // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis static boost::shared_ptr MakeSharedD(double g = 9.81) { - return boost::make_shared(Vector3(0, 0, g)); + return boost::shared_ptr(new Params(Vector3(0, 0, g))); } // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis static boost::shared_ptr MakeSharedU(double g = 9.81) { - return boost::make_shared(Vector3(0, 0, -g)); + return boost::shared_ptr(new Params(Vector3(0, 0, -g))); } private: @@ -104,6 +104,9 @@ public: ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance); ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; protected: @@ -195,6 +198,9 @@ public: ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /** diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 2ad3c17dd..5fc82f0a3 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -169,6 +169,9 @@ private: ar & BOOST_SERIALIZATION_NVP(biasGyro_); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW /// @} }; // ConstantBias class diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index cb40774f4..025278c81 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -58,6 +58,9 @@ struct PreintegratedRotationParams { ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -165,6 +168,9 @@ class PreintegratedRotation { ar& BOOST_SERIALIZATION_NVP(deltaRij_); ar& BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; template <> diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index f2b2c0fef..1c673bff5 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -39,12 +39,12 @@ struct PreintegrationParams: PreintegratedRotationParams { // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis static boost::shared_ptr MakeSharedD(double g = 9.81) { - return boost::make_shared(Vector3(0, 0, g)); + return boost::shared_ptr(new PreintegrationParams(Vector3(0, 0, g))); } // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis static boost::shared_ptr MakeSharedU(double g = 9.81) { - return boost::make_shared(Vector3(0, 0, -g)); + return boost::shared_ptr(new PreintegrationParams(Vector3(0, 0, -g))); } void print(const std::string& s) const; @@ -74,6 +74,9 @@ protected: ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace gtsam diff --git a/gtsam/slam/JacobianFactorQ.h b/gtsam/slam/JacobianFactorQ.h index d09627b77..3f5290c58 100644 --- a/gtsam/slam/JacobianFactorQ.h +++ b/gtsam/slam/JacobianFactorQ.h @@ -51,7 +51,7 @@ public: /// Constructor JacobianFactorQ(const FastVector& keys, - const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const std::vector >& FBlocks, const Matrix& E, const Matrix3& P, const Vector& b, const SharedDiagonal& model = SharedDiagonal()) : Base() { size_t j = 0, m2 = E.rows(), m = m2 / ZDim; diff --git a/gtsam/slam/JacobianFactorQR.h b/gtsam/slam/JacobianFactorQR.h index 77102c24b..9e61f5324 100644 --- a/gtsam/slam/JacobianFactorQR.h +++ b/gtsam/slam/JacobianFactorQR.h @@ -29,7 +29,7 @@ public: * Constructor */ JacobianFactorQR(const FastVector& keys, - const std::vector& FBlocks, const Matrix& E, const Matrix3& P, + const std::vector >& FBlocks, const Matrix& E, const Matrix3& P, const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { diff --git a/gtsam/slam/JacobianFactorSVD.h b/gtsam/slam/JacobianFactorSVD.h index 8afe0bcbf..e7bc5864d 100644 --- a/gtsam/slam/JacobianFactorSVD.h +++ b/gtsam/slam/JacobianFactorSVD.h @@ -59,7 +59,7 @@ public: * @Fblocks: */ JacobianFactorSVD(const FastVector& keys, - const std::vector& Fblocks, const Matrix& Enull, + const std::vector >& Fblocks, const Matrix& Enull, const Vector& b, // const SharedDiagonal& model = SharedDiagonal()) : Base() { diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 7c481d0c8..2c0614cd6 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -36,7 +36,7 @@ protected: typedef Eigen::Matrix MatrixZD; ///< type of an F block typedef Eigen::Matrix MatrixDD; ///< camera hessian - const std::vector FBlocks_; ///< All ZDim*D F blocks (one for each camera) + const std::vector > FBlocks_; ///< All ZDim*D F blocks (one for each camera) const Matrix PointCovariance_; ///< the 3*3 matrix P = inv(E'E) (2*2 if degenerate) const Matrix E_; ///< The 2m*3 E Jacobian with respect to the point const Vector b_; ///< 2m-dimensional RHS vector @@ -49,7 +49,7 @@ public: /// Construct from blocks of F, E, inv(E'*E), and RHS vector b RegularImplicitSchurFactor(const FastVector& keys, - const std::vector& FBlocks, const Matrix& E, const Matrix& P, + const std::vector >& FBlocks, const Matrix& E, const Matrix& P, const Vector& b) : GaussianFactor(keys), FBlocks_(FBlocks), PointCovariance_(P), E_(E), b_(b) { } @@ -58,7 +58,7 @@ public: virtual ~RegularImplicitSchurFactor() { } - std::vector& FBlocks() const { + std::vector >& FBlocks() const { return FBlocks_; } diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 1453d80a7..497ebbc5b 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -50,12 +50,14 @@ private: typedef NonlinearFactor Base; typedef SmartFactorBase This; typedef typename CAMERA::Measurement Z; + typedef typename CAMERA::MeasurementVector ZVector; public: static const int Dim = traits::dimension; ///< Camera dimension static const int ZDim = traits::dimension; ///< Measurement dimension typedef Eigen::Matrix MatrixZD; // F blocks (derivatives wrpt camera) + typedef std::vector > FBlocks; // vector of F blocks protected: /** @@ -71,14 +73,14 @@ protected: * We keep a copy of measurements for I/O and computing the error. * The order is kept the same as the keys that we use to create the factor. */ - std::vector measured_; + ZVector measured_; /// @name Pose of the camera in the body frame boost::optional body_P_sensor_; ///< Pose of the camera in the body frame /// @} // Cache for Fblocks, to avoid a malloc ever time we re-linearize - mutable std::vector Fblocks; + mutable FBlocks Fs; public: @@ -97,7 +99,7 @@ public: SmartFactorBase(const SharedNoiseModel& sharedNoiseModel, boost::optional body_P_sensor = boost::none, size_t expectedNumberCameras = 10) - : body_P_sensor_(body_P_sensor), Fblocks(expectedNumberCameras) { + : body_P_sensor_(body_P_sensor), Fs(expectedNumberCameras) { if (!sharedNoiseModel) throw std::runtime_error("SmartFactorBase: sharedNoiseModel is required"); @@ -129,7 +131,7 @@ public: /** * Add a bunch of measurements, together with the camera keys */ - void add(std::vector& measurements, std::vector& cameraKeys) { + void add(ZVector& measurements, std::vector& cameraKeys) { for (size_t i = 0; i < measurements.size(); i++) { this->measured_.push_back(measurements.at(i)); this->keys_.push_back(cameraKeys.at(i)); @@ -154,7 +156,7 @@ public: } /** return the measurements */ - const std::vector& measured() const { + const ZVector& measured() const { return measured_; } @@ -258,22 +260,22 @@ public: * TODO: Kill this obsolete method */ template - void computeJacobians(std::vector& Fblocks, Matrix& E, Vector& b, + void computeJacobians(FBlocks& Fs, Matrix& E, Vector& b, const Cameras& cameras, const POINT& point) const { // Project into Camera set and calculate derivatives // As in expressionFactor, RHS vector b = - (h(x_bar) - z) = z-h(x_bar) // Indeed, nonlinear error |h(x_bar+dx)-z| ~ |h(x_bar) + A*dx - z| // = |A*dx - (z-h(x_bar))| - b = -unwhitenedError(cameras, point, Fblocks, E); + b = -unwhitenedError(cameras, point, Fs, E); } /// SVD version template - void computeJacobiansSVD(std::vector& Fblocks, Matrix& Enull, + void computeJacobiansSVD(FBlocks& Fs, Matrix& Enull, Vector& b, const Cameras& cameras, const POINT& point) const { Matrix E; - computeJacobians(Fblocks, E, b, cameras, point); + computeJacobians(Fs, E, b, cameras, point); static const int N = FixedDimension::value; // 2 (Unit3) or 3 (Point3) @@ -291,10 +293,10 @@ public: Matrix E; Vector b; - computeJacobians(Fblocks, E, b, cameras, point); + computeJacobians(Fs, E, b, cameras, point); // build augmented hessian - SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fblocks, E, b); + SymmetricBlockMatrix augmentedHessian = Cameras::SchurComplement(Fs, E, b); return boost::make_shared >(keys_, augmentedHessian); @@ -311,12 +313,12 @@ public: const FastVector allKeys) const { Matrix E; Vector b; - computeJacobians(Fblocks, E, b, cameras, point); - Cameras::UpdateSchurComplement(Fblocks, E, b, allKeys, keys_, augmentedHessian); + computeJacobians(Fs, E, b, cameras, point); + Cameras::UpdateSchurComplement(Fs, E, b, allKeys, keys_, augmentedHessian); } /// Whiten the Jacobians computed by computeJacobians using noiseModel_ - void whitenJacobians(std::vector& F, Matrix& E, Vector& b) const { + void whitenJacobians(FBlocks& F, Matrix& E, Vector& b) const { noiseModel_->WhitenSystem(E, b); // TODO make WhitenInPlace work with any dense matrix type for (size_t i = 0; i < F.size(); i++) @@ -329,7 +331,7 @@ public: double lambda = 0.0, bool diagonalDamping = false) const { Matrix E; Vector b; - std::vector F; + FBlocks F; computeJacobians(F, E, b, cameras, point); whitenJacobians(F, E, b); Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); @@ -345,7 +347,7 @@ public: bool diagonalDamping = false) const { Matrix E; Vector b; - std::vector F; + FBlocks F; computeJacobians(F, E, b, cameras, point); const size_t M = b.size(); Matrix P = Cameras::PointCov(E, lambda, diagonalDamping); @@ -360,7 +362,7 @@ public: boost::shared_ptr createJacobianSVDFactor( const Cameras& cameras, const Point3& point, double lambda = 0.0) const { size_t m = this->keys_.size(); - std::vector F; + FBlocks F; Vector b; const size_t M = ZDim * m; Matrix E0(M, M - 3); @@ -371,12 +373,12 @@ public: } /// Create BIG block-diagonal matrix F from Fblocks - static void FillDiagonalF(const std::vector& Fblocks, Matrix& F) { - size_t m = Fblocks.size(); + static void FillDiagonalF(const FBlocks& Fs, Matrix& F) { + size_t m = Fs.size(); F.resize(ZDim * m, Dim * m); F.setZero(); for (size_t i = 0; i < m; ++i) - F.block(ZDim * i, Dim * i) = Fblocks.at(i); + F.block(ZDim * i, Dim * i) = Fs.at(i); } diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index 840ecbc4d..0d9f90d22 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -61,7 +61,7 @@ protected: /// @name Caching triangulation /// @{ mutable TriangulationResult result_; ///< result from triangulateSafe - mutable std::vector cameraPosesTriangulation_; ///< current triangulation poses + mutable std::vector > cameraPosesTriangulation_; ///< current triangulation poses /// @} public: @@ -203,7 +203,7 @@ public: } // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols(). - std::vector Fblocks; + std::vector > Fblocks; Matrix E; Vector b; computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); @@ -337,7 +337,7 @@ public: /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate void computeJacobiansWithTriangulatedPoint( - std::vector& Fblocks, Matrix& E, Vector& b, + std::vector >& Fblocks, Matrix& E, Vector& b, const Cameras& cameras) const { if (!result_) { @@ -354,7 +354,7 @@ public: /// Version that takes values, and creates the point bool triangulateAndComputeJacobians( - std::vector& Fblocks, Matrix& E, Vector& b, + std::vector >& Fblocks, Matrix& E, Vector& b, const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); @@ -365,7 +365,7 @@ public: /// takes values bool triangulateAndComputeJacobiansSVD( - std::vector& Fblocks, Matrix& Enull, Vector& b, + std::vector >& Fblocks, Matrix& Enull, Vector& b, const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index ccad83f01..4abc59305 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -132,7 +132,7 @@ CAMERA perturbCameraPose(const CAMERA& camera) { template void projectToMultipleCameras(const CAMERA& cam1, const CAMERA& cam2, - const CAMERA& cam3, Point3 landmark, vector& measurements_cam) { + const CAMERA& cam3, Point3 landmark, typename CAMERA::MeasurementVector& measurements_cam) { Point2 cam1_uv1 = cam1.project(landmark); Point2 cam2_uv1 = cam2.project(landmark); Point2 cam3_uv1 = cam3.project(landmark); diff --git a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp index 4184d6769..6f9371e68 100644 --- a/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp +++ b/gtsam/slam/tests/testRegularImplicitSchurFactor.cpp @@ -41,7 +41,7 @@ using namespace gtsam; const Matrix26 F0 = Matrix26::Ones(); const Matrix26 F1 = 2 * Matrix26::Ones(); const Matrix26 F3 = 3 * Matrix26::Ones(); -const vector FBlocks = list_of(F0)(F1)(F3); +const vector > FBlocks = list_of(F0)(F1)(F3); const FastVector keys = list_of(0)(1)(3); // RHS and sigmas const Vector b = (Vector(6) << 1., 2., 3., 4., 5., 6.).finished(); diff --git a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp index 4feeadc86..17fec7b9f 100644 --- a/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionCameraFactor.cpp @@ -166,7 +166,7 @@ TEST( SmartProjectionCameraFactor, noisy ) { EXPECT(assert_equal(expected, actual, 1)); SmartFactor::shared_ptr factor2(new SmartFactor(unit2)); - vector measurements; + Point2Vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); @@ -186,7 +186,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimize ) { using namespace vanilla; // Project three landmarks into three cameras - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -288,7 +288,7 @@ TEST( SmartProjectionCameraFactor, perturbPoseAndOptimizeFromSfM_tracks ) { using namespace vanilla; // Project three landmarks into three cameras - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); projectToMultipleCameras(cam1, cam2, cam3, landmark2, measurements_cam2); projectToMultipleCameras(cam1, cam2, cam3, landmark3, measurements_cam3); @@ -360,7 +360,7 @@ TEST( SmartProjectionCameraFactor, perturbCamerasAndOptimize ) { using namespace vanilla; - vector measurements_cam1, measurements_cam2, measurements_cam3, + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate @@ -440,7 +440,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler ) { using namespace bundler; - vector measurements_cam1, measurements_cam2, measurements_cam3, + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate @@ -516,7 +516,7 @@ TEST( SmartProjectionCameraFactor, Cal3Bundler2 ) { using namespace bundler; - vector measurements_cam1, measurements_cam2, measurements_cam3, + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4, measurements_cam5; // 1. Project three landmarks into three cameras and triangulate @@ -768,8 +768,8 @@ TEST( SmartProjectionCameraFactor, computeImplicitJacobian ) { Point3 point(0,0,0); if (factor1->point()) point = *(factor1->point()); - vector Fblocks; - factor1->computeJacobians(Fblocks, expectedE, expectedb, cameras, point); + SmartFactor::FBlocks Fs; + factor1->computeJacobians(Fs, expectedE, expectedb, cameras, point); NonlinearFactorGraph generalGraph; SFMFactor sfm1(level_uv, unit2, c1, l1); diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index 71ee79d86..7d3d9c63c 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -155,8 +155,8 @@ TEST( SmartProjectionPoseFactor, noiseless ) { // Calculate using computeJacobians Vector b; - vector Fblocks; - factor.computeJacobians(Fblocks, E, b, cameras, *point); + SmartFactor::FBlocks Fs; + factor.computeJacobians(Fs, E, b, cameras, *point); double actualError3 = b.squaredNorm(); EXPECT(assert_equal(expectedE, E, 1e-7)); EXPECT_DOUBLES_EQUAL(expectedError, actualError3, 1e-8); @@ -185,7 +185,7 @@ TEST( SmartProjectionPoseFactor, noisy ) { double actualError1 = factor->error(values); SmartFactor::shared_ptr factor2(new SmartFactor(model, sharedK)); - vector measurements; + Point2Vector measurements; measurements.push_back(level_uv); measurements.push_back(level_uv_right); @@ -228,7 +228,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(5, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -292,7 +292,7 @@ TEST( SmartProjectionPoseFactor, smartFactorWithSensorBodyTransform ){ TEST( SmartProjectionPoseFactor, 3poses_smart_projection_factor ) { using namespace vanillaPose2; - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -363,7 +363,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { // one landmarks 1m in front of camera Point3 landmark1(0, 0, 10); - vector measurements_cam1; + Point2Vector measurements_cam1; // Project 2 landmarks into 2 cameras measurements_cam1.push_back(cam1.project(landmark1)); @@ -454,7 +454,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { E(2, 0) = 10; E(2, 2) = 1; E(3, 1) = 10; - vector Fblocks = list_of(F1)(F2); + SmartFactor::FBlocks Fs = list_of(F1)(F2); Vector b(4); b.setZero(); @@ -466,7 +466,7 @@ TEST( SmartProjectionPoseFactor, Factors ) { // createJacobianQFactor SharedIsotropic n = noiseModel::Isotropic::Sigma(4, sigma); Matrix3 P = (E.transpose() * E).inverse(); - JacobianFactorQ<6, 2> expectedQ(keys, Fblocks, E, P, b, n); + JacobianFactorQ<6, 2> expectedQ(keys, Fs, E, P, b, n); EXPECT(assert_equal(expectedInformation, expectedQ.information(), 1e-8)); boost::shared_ptr > actualQ = @@ -480,11 +480,11 @@ TEST( SmartProjectionPoseFactor, Factors ) { // Whiten for RegularImplicitSchurFactor (does not have noise model) model->WhitenSystem(E, b); Matrix3 whiteP = (E.transpose() * E).inverse(); - Fblocks[0] = model->Whiten(Fblocks[0]); - Fblocks[1] = model->Whiten(Fblocks[1]); + Fs[0] = model->Whiten(Fs[0]); + Fs[1] = model->Whiten(Fs[1]); // createRegularImplicitSchurFactor - RegularImplicitSchurFactor expected(keys, Fblocks, E, whiteP, b); + RegularImplicitSchurFactor expected(keys, Fs, E, whiteP, b); boost::shared_ptr > actual = smartFactor1->createRegularImplicitSchurFactor(cameras, 0.0); @@ -525,7 +525,7 @@ TEST( SmartProjectionPoseFactor, 3poses_iterative_smart_projection_factor ) { views.push_back(x2); views.push_back(x3); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -582,7 +582,7 @@ TEST( SmartProjectionPoseFactor, jacobianSVD ) { views.push_back(x2); views.push_back(x3); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -643,7 +643,7 @@ TEST( SmartProjectionPoseFactor, landmarkDistance ) { views.push_back(x2); views.push_back(x3); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -709,7 +709,7 @@ TEST( SmartProjectionPoseFactor, dynamicOutlierRejection ) { // add fourth landmark Point3 landmark4(5, -0.5, 1); - vector measurements_cam1, measurements_cam2, measurements_cam3, + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3, measurements_cam4; // Project 4 landmarks into three cameras @@ -772,7 +772,7 @@ TEST( SmartProjectionPoseFactor, jacobianQ ) { views.push_back(x2); views.push_back(x3); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -883,7 +883,7 @@ TEST( SmartProjectionPoseFactor, CheckHessian) { Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -966,7 +966,7 @@ TEST( SmartProjectionPoseFactor, 3poses_2land_rotation_only_smart_projection_fac Camera cam2(pose2, sharedK2); Camera cam3(pose3, sharedK2); - vector measurements_cam1, measurements_cam2; + Point2Vector measurements_cam1, measurements_cam2; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1026,7 +1026,7 @@ TEST( SmartProjectionPoseFactor, 3poses_rotation_only_smart_projection_factor ) Camera cam2(pose2, sharedK); Camera cam3(pose3, sharedK); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1106,7 +1106,7 @@ TEST( SmartProjectionPoseFactor, Hessian ) { // Project three landmarks into 2 cameras Point2 cam1_uv1 = cam1.project(landmark1); Point2 cam2_uv1 = cam2.project(landmark1); - vector measurements_cam1; + Point2Vector measurements_cam1; measurements_cam1.push_back(cam1_uv1); measurements_cam1.push_back(cam2_uv1); @@ -1138,7 +1138,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotation ) { views.push_back(x2); views.push_back(x3); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1195,7 +1195,7 @@ TEST( SmartProjectionPoseFactor, HessianWithRotationDegenerate ) { Camera cam2(level_pose, sharedK2); Camera cam3(level_pose, sharedK2); - vector measurements_cam1; + Point2Vector measurements_cam1; projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); SmartFactor::shared_ptr smartFactor(new SmartFactor(model, sharedK2)); @@ -1253,7 +1253,7 @@ TEST( SmartProjectionPoseFactor, Cal3Bundler ) { // three landmarks ~5 meters in front of camera Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1324,7 +1324,7 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { // landmark3 at 3 meters now Point3 landmark3(3, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); @@ -1422,7 +1422,7 @@ TEST(SmartProjectionPoseFactor, serialize2) { // insert some measurments vector key_view; - vector meas_view; + Point2Vector meas_view; key_view.push_back(Symbol('x', 1)); meas_view.push_back(Point2(10, 10)); factor.add(meas_view, key_view); diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 29ae6233b..b7d06b268 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -78,7 +78,7 @@ public: /// Vector of monocular cameras (stereo treated as 2 monocular) typedef PinholeCamera MonoCamera; typedef CameraSet MonoCameras; - typedef std::vector MonoMeasurements; + typedef MonoCamera::MeasurementVector MonoMeasurements; /** * Constructor @@ -226,17 +226,17 @@ public: } // Jacobian could be 3D Point3 OR 2D Unit3, difference is E.cols(). - std::vector Fblocks; + Base::FBlocks Fs; Matrix F, E; Vector b; - computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + computeJacobiansWithTriangulatedPoint(Fs, E, b, cameras); // Whiten using noise model - Base::whitenJacobians(Fblocks, E, b); + Base::whitenJacobians(Fs, E, b); // build augmented hessian SymmetricBlockMatrix augmentedHessian = // - Cameras::SchurComplement(Fblocks, E, b, lambda, diagonalDamping); + Cameras::SchurComplement(Fs, E, b, lambda, diagonalDamping); return boost::make_shared >(this->keys_, augmentedHessian); @@ -360,7 +360,8 @@ public: /// Assumes the point has been computed /// Note E can be 2m*3 or 2m*2, in case point is degenerate void computeJacobiansWithTriangulatedPoint( - std::vector& Fblocks, Matrix& E, Vector& b, + FBlocks& Fs, + Matrix& E, Vector& b, const Cameras& cameras) const { if (!result_) { @@ -370,32 +371,32 @@ public: // Unit3 backProjected; /* = cameras[0].backprojectPointAtInfinity( // this->measured_.at(0)); */ // -// Base::computeJacobians(Fblocks, E, b, cameras, backProjected); +// Base::computeJacobians(Fs, E, b, cameras, backProjected); } else { // valid result: just return Base version - Base::computeJacobians(Fblocks, E, b, cameras, *result_); + Base::computeJacobians(Fs, E, b, cameras, *result_); } } /// Version that takes values, and creates the point bool triangulateAndComputeJacobians( - std::vector& Fblocks, Matrix& E, Vector& b, + FBlocks& Fs, Matrix& E, Vector& b, const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - computeJacobiansWithTriangulatedPoint(Fblocks, E, b, cameras); + computeJacobiansWithTriangulatedPoint(Fs, E, b, cameras); return nonDegenerate; } /// takes values bool triangulateAndComputeJacobiansSVD( - std::vector& Fblocks, Matrix& Enull, Vector& b, + FBlocks& Fs, Matrix& Enull, Vector& b, const Values& values) const { Cameras cameras = this->cameras(values); bool nonDegenerate = triangulateForLinearize(cameras); if (nonDegenerate) - Base::computeJacobiansSVD(Fblocks, Enull, b, cameras, *result_); + Base::computeJacobiansSVD(Fs, Enull, b, cameras, *result_); return nonDegenerate; } diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index a018ec7ee..229a49e3f 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -540,7 +540,7 @@ TEST( SmartStereoProjectionPoseFactor, body_P_sensor_monocular ){ Point3 landmark2(5, -0.5, 1.2); Point3 landmark3(5, 0, 3.0); - vector measurements_cam1, measurements_cam2, measurements_cam3; + Point2Vector measurements_cam1, measurements_cam2, measurements_cam3; // Project three landmarks into three cameras projectToMultipleCameras(cam1, cam2, cam3, landmark1, measurements_cam1); From 3b8985fb6e5e31ada5778e467445caf4f9bccf4b Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Tue, 11 Sep 2018 00:22:20 -0700 Subject: [PATCH 035/197] Test of AutoDiff wrapper in an expression modified so that the upAligned size of the relevant binary expression is tested against the size of the expression in the AutoDiff wrapper. When the traceSize() of the expression containing the AutoDiff wrapper is computed, that value (the traceSize) will be computed such that an alignment (currently 16-bit) will be forced. It is thus necessary for the test to also upAlign the relevant binary expression. On x86_64 architectures, this test was accidentally passing because the relevant struct was already aligned on a 16-bit boundary. On AArch64 ('ARM64'), the alignment was *not* on a 16-bit boundary, and this test failed. Modifying the first argument to EXPECT_LONGS_EQUAL in this test to include upAlignment of the relevant binary expression makes the test pass in 'debug' and 'release' builds on both x86_64 and AArch64 architectures --- gtsam/nonlinear/tests/testAdaptAutoDiff.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp index aa50ce73f..a85118c00 100644 --- a/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam/nonlinear/tests/testAdaptAutoDiff.cpp @@ -231,14 +231,22 @@ TEST(AdaptAutoDiff, AdaptAutoDiff) { /* ************************************************************************* */ // Test AutoDiff wrapper in an expression TEST(AdaptAutoDiff, SnavelyExpression) { + typedef AdaptAutoDiff Adaptor; + Expression P(1); Expression X(2); - typedef AdaptAutoDiff Adaptor; + Expression expression(Adaptor(), P, X); + + std::size_t RecordSize = + sizeof(internal::BinaryExpression::Record); + EXPECT_LONGS_EQUAL( - sizeof(internal::BinaryExpression::Record), - expression.traceSize()); + internal::upAligned(RecordSize) + P.traceSize() + X.traceSize(), + expression.traceSize()); + set expected = list_of(1)(2); + EXPECT(expected == expression.keys()); } From c1b14f08f8d20fe9819580fed8eb86cf675c3379 Mon Sep 17 00:00:00 2001 From: Sean Bowman Date: Tue, 18 Sep 2018 17:29:02 -0400 Subject: [PATCH 036/197] Fix more memory alignment issues --- gtsam/geometry/CalibratedCamera.h | 6 ++++++ gtsam/geometry/PinholeCamera.h | 2 ++ gtsam/geometry/PinholePose.h | 6 +++++- gtsam/geometry/Unit3.h | 2 ++ gtsam/geometry/triangulation.cpp | 4 ++-- gtsam/geometry/triangulation.h | 10 ++++++---- gtsam/navigation/TangentPreintegration.h | 3 +++ gtsam/slam/EssentialMatrixFactor.h | 6 ++++++ gtsam/slam/RegularImplicitSchurFactor.h | 2 +- 9 files changed, 33 insertions(+), 8 deletions(-) diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index cd2277965..db9caf13b 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -230,6 +230,9 @@ private: ar & BOOST_SERIALIZATION_NVP(pose_); } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; // end of class PinholeBase @@ -413,6 +416,9 @@ private: } /// @} + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 4c7fdf94d..beadba929 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -324,6 +324,8 @@ private: ar & BOOST_SERIALIZATION_NVP(K_); } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 937eb0785..f3b99b2fb 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -220,7 +220,9 @@ private: & boost::serialization::make_nvp("PinholeBase", boost::serialization::base_object(*this)); } - + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholeBaseK @@ -422,6 +424,8 @@ private: ar & BOOST_SERIALIZATION_NVP(K_); } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholePose diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index cd05af519..493c7d00a 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -208,6 +208,8 @@ private: /// @} +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // Define GTSAM traits diff --git a/gtsam/geometry/triangulation.cpp b/gtsam/geometry/triangulation.cpp index 8e9c140c2..a5d2e04cd 100644 --- a/gtsam/geometry/triangulation.cpp +++ b/gtsam/geometry/triangulation.cpp @@ -24,7 +24,7 @@ namespace gtsam { Vector4 triangulateHomogeneousDLT( - const std::vector& projection_matrices, + const std::vector>& projection_matrices, const Point2Vector& measurements, double rank_tol) { // number of cameras @@ -53,7 +53,7 @@ Vector4 triangulateHomogeneousDLT( return v; } -Point3 triangulateDLT(const std::vector& projection_matrices, +Point3 triangulateDLT(const std::vector>& projection_matrices, const Point2Vector& measurements, double rank_tol) { Vector4 v = triangulateHomogeneousDLT(projection_matrices, measurements, rank_tol); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 0f53705ad..535572fe1 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -53,7 +53,7 @@ public: * @return Triangulated point, in homogeneous coordinates */ GTSAM_EXPORT Vector4 triangulateHomogeneousDLT( - const std::vector& projection_matrices, + const std::vector>& projection_matrices, const Point2Vector& measurements, double rank_tol = 1e-9); /** @@ -64,7 +64,7 @@ GTSAM_EXPORT Vector4 triangulateHomogeneousDLT( * @return Triangulated Point3 */ GTSAM_EXPORT Point3 triangulateDLT( - const std::vector& projection_matrices, + const std::vector>& projection_matrices, const Point2Vector& measurements, double rank_tol = 1e-9); @@ -213,6 +213,8 @@ struct CameraProjectionMatrix { } private: const Matrix3 K_; +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -238,7 +240,7 @@ Point3 triangulatePoint3(const std::vector& poses, throw(TriangulationUnderconstrainedException()); // construct projection matrices from poses & calibration - std::vector projection_matrices; + std::vector> projection_matrices; CameraProjectionMatrix createP(*sharedCal); // partially apply for(const Pose3& pose: poses) projection_matrices.push_back(createP(pose)); @@ -288,7 +290,7 @@ Point3 triangulatePoint3( throw(TriangulationUnderconstrainedException()); // construct projection matrices from poses & calibration - std::vector projection_matrices; + std::vector> projection_matrices; for(const CAMERA& camera: cameras) projection_matrices.push_back( CameraProjectionMatrix(camera.calibration())( diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index dddafad7a..34c38e22b 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -135,6 +135,9 @@ private: ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index e6b312b95..2e921bfef 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -80,6 +80,8 @@ public: return error; } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -198,6 +200,8 @@ public: return f_ * reprojectionError; } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor2 @@ -281,6 +285,8 @@ public: } } +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor3 diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 2c0614cd6..47c9a4c7b 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -252,7 +252,7 @@ public: y += F.transpose() * e3; } - typedef std::vector Error2s; + typedef std::vector> Error2s; /** * @brief Calculate corrected error Q*(e-ZDim*b) = (I - E*P*E')*(e-ZDim*b) From 4ed362dfd41ebb84711c00b522a20debdd23f4bb Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 00:23:00 -0400 Subject: [PATCH 037/197] Ignore Visual Studio Code files --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 32f124c43..b62617d21 100644 --- a/.gitignore +++ b/.gitignore @@ -15,3 +15,4 @@ cython/gtsam.cpython-35m-darwin.so cython/gtsam.pyx cython/gtsam.so cython/gtsam_wrapper.pxd +.vscode From 9c3949f738febd1ab84d28114b523a3bf7de3ec0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 00:23:17 -0400 Subject: [PATCH 038/197] Added virtual destructors --- wrap/Qualified.h | 18 +++++++++++++----- wrap/ReturnValue.h | 9 ++++++--- 2 files changed, 19 insertions(+), 8 deletions(-) diff --git a/wrap/Qualified.h b/wrap/Qualified.h index 899ac3541..4dc15dda1 100644 --- a/wrap/Qualified.h +++ b/wrap/Qualified.h @@ -48,14 +48,23 @@ public: } Category; Category category; + /// Default constructor Qualified() : category(VOID) { } + /// Construct from name and optional category Qualified(const std::string& n, Category c = CLASS) : name_(n), category(c) { } + /// Construct from scoped name and optional category + Qualified(const std::string& ns1, const std::string& n, Category c = CLASS) : + name_(n), category(c) { + namespaces_.push_back(ns1); + } + + /// Construct from doubly scoped name and optional category Qualified(const std::string& ns1, const std::string& ns2, const std::string& n, Category c = CLASS) : name_(n), category(c) { @@ -63,15 +72,14 @@ public: namespaces_.push_back(ns2); } - Qualified(const std::string& ns1, const std::string& n, Category c = CLASS) : - name_(n), category(c) { - namespaces_.push_back(ns1); - } - + /// Construct from arbitrarily scoped name Qualified(std::vector ns, const std::string& name) : namespaces_(ns), name_(name), category(CLASS) { } + // Destructor + virtual ~Qualified() {} + std::string name() const { return name_; } diff --git a/wrap/ReturnValue.h b/wrap/ReturnValue.h index 8b6b199a2..589db5bd6 100644 --- a/wrap/ReturnValue.h +++ b/wrap/ReturnValue.h @@ -27,21 +27,24 @@ struct ReturnValue { friend struct ReturnValueGrammar; - /// Constructor + /// Default constructor ReturnValue() : isPair(false) { } - /// Constructor + /// Construct from type ReturnValue(const ReturnType& type) : isPair(false), type1(type) { } - /// Constructor + /// Construct from pair type arguments ReturnValue(const ReturnType& t1, const ReturnType& t2) : isPair(true), type1(t1), type2(t2) { } + /// Destructor + virtual ~ReturnValue() {} + virtual void clear() { type1.clear(); type2.clear(); From 4abb7dae6dd4b043c08d2c821498d614d017d832 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 10:40:44 -0400 Subject: [PATCH 039/197] Used aligned container --- gtsam_unstable/geometry/SimPolygon2D.cpp | 12 ++++++------ gtsam_unstable/geometry/SimPolygon2D.h | 12 ++++++------ 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam_unstable/geometry/SimPolygon2D.cpp b/gtsam_unstable/geometry/SimPolygon2D.cpp index ba1445b20..00bd28ec7 100644 --- a/gtsam_unstable/geometry/SimPolygon2D.cpp +++ b/gtsam_unstable/geometry/SimPolygon2D.cpp @@ -126,7 +126,7 @@ SimPolygon2D SimPolygon2D::randomTriangle( double side_len, double mean_side_len, double sigma_side_len, double min_vertex_dist, double min_side_len, const vector& existing_polys) { // get the current set of landmarks - std::vector lms; + Point2Vector lms; double d2 = side_len/2.0; lms.push_back(Point2( d2, d2)); lms.push_back(Point2(-d2, d2)); @@ -181,7 +181,7 @@ SimPolygon2D SimPolygon2D::randomRectangle( double side_len, double mean_side_len, double sigma_side_len, double min_vertex_dist, double min_side_len, const vector& existing_polys) { // get the current set of landmarks - std::vector lms; + Point2Vector lms; double d2 = side_len/2.0; lms.push_back(Point2( d2, d2)); lms.push_back(Point2(-d2, d2)); @@ -265,7 +265,7 @@ Point2 SimPolygon2D::randomBoundedPoint2(double boundary_size, /* ***************************************************************** */ Point2 SimPolygon2D::randomBoundedPoint2(double boundary_size, - const std::vector& landmarks, double min_landmark_dist) { + const Point2Vector& landmarks, double min_landmark_dist) { for (size_t i=0; i& landmarks, + const Point2Vector& landmarks, const vector& obstacles, double min_landmark_dist) { for (size_t i=0; i& landmarks, + const Point2Vector& landmarks, const std::vector& obstacles, double min_landmark_dist) { boost::uniform_real<> gen_x(0.0, UR_corner.x() - LL_corner.x()); @@ -317,7 +317,7 @@ bool SimPolygon2D::insideBox(double s, const Point2& p) { } /* ***************************************************************** */ -bool SimPolygon2D::nearExisting(const std::vector& S, +bool SimPolygon2D::nearExisting(const Point2Vector& S, const Point2& p, double threshold) { for(const Point2& Sp: S) if (distance2(Sp, p) < threshold) diff --git a/gtsam_unstable/geometry/SimPolygon2D.h b/gtsam_unstable/geometry/SimPolygon2D.h index 835bb4083..0a0e0da7f 100644 --- a/gtsam_unstable/geometry/SimPolygon2D.h +++ b/gtsam_unstable/geometry/SimPolygon2D.h @@ -18,7 +18,7 @@ namespace gtsam { */ class GTSAM_UNSTABLE_EXPORT SimPolygon2D { protected: - std::vector landmarks_; + Point2Vector landmarks_; static boost::minstd_rand rng; public: @@ -57,7 +57,7 @@ public: // access to underlying points const Point2& landmark(size_t i) const { return landmarks_[i]; } size_t size() const { return landmarks_.size(); } - const std::vector& vertices() const { return landmarks_; } + const Point2Vector& vertices() const { return landmarks_; } // testable requirements bool equals(const SimPolygon2D& p, double tol=1e-5) const; @@ -91,7 +91,7 @@ public: static bool insideBox(double s, const Point2& p); /** returns true iff p is within threshold of any point in S */ - static bool nearExisting(const std::vector& S, + static bool nearExisting(const Point2Vector& S, const Point2& p, double threshold); /** pick a random point uniformly over a box of side s */ @@ -105,11 +105,11 @@ public: /** pick a random point within a box that is further than dist d away from existing landmarks */ static Point2 randomBoundedPoint2(double boundary_size, - const std::vector& landmarks, double min_landmark_dist); + const Point2Vector& landmarks, double min_landmark_dist); /** pick a random point within a box that meets above requirements, as well as staying out of obstacles */ static Point2 randomBoundedPoint2(double boundary_size, - const std::vector& landmarks, + const Point2Vector& landmarks, const std::vector& obstacles, double min_landmark_dist); /** pick a random point that only avoid obstacles */ @@ -119,7 +119,7 @@ public: /** pick a random point in box defined by lower left and upper right corners */ static Point2 randomBoundedPoint2( const Point2& LL_corner, const Point2& UR_corner, - const std::vector& landmarks, + const Point2Vector& landmarks, const std::vector& obstacles, double min_landmark_dist); /** pick a random pose in a bounded area that is not in an obstacle */ From bd4ab1598e307d85c0953fc2e1a086040b08cf6d Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Thu, 27 Sep 2018 18:19:44 -0700 Subject: [PATCH 040/197] Expanded shortcut_overlapping_separator test in testGaussianBayesTreeB to allow for sign reversal in a row of the augmented Jacobian. The joint density does not appear to be affected in the case where the augmented Jacobian row sign is changed, so we should not fail the test if that happens. --- tests/testGaussianBayesTreeB.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/tests/testGaussianBayesTreeB.cpp b/tests/testGaussianBayesTreeB.cpp index 8b2aa3ae7..88b1aede2 100644 --- a/tests/testGaussianBayesTreeB.cpp +++ b/tests/testGaussianBayesTreeB.cpp @@ -317,8 +317,25 @@ TEST(GaussianBayesTree, shortcut_overlapping_separator) 5, 0, 6, 0, -11, -12 ).finished(); + Matrix actualJointJ = joint.augmentedJacobian(); + bool Row0RhsSignsEqual = + signbit(expectedJointJ(0, 2)) == signbit(actualJointJ(0, 2)); + + if (!Row0RhsSignsEqual) + { + expectedJointJ.row(0) = -expectedJointJ.row(0); + } + + bool Row1RhsSignsEqual = + signbit(expectedJointJ(1, 2)) == signbit(actualJointJ(1, 2)); + + if (!Row1RhsSignsEqual) + { + expectedJointJ.row(1) = -expectedJointJ.row(1); + } + EXPECT(assert_equal(expectedJointJ, actualJointJ)); } From 4ba7c59330cda33ec496ebcf1bdf6e7f97e13ffe Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 22:45:14 -0400 Subject: [PATCH 041/197] Plotting utilities --- cython/gtsam/utils/plot.py | 76 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 76 insertions(+) create mode 100644 cython/gtsam/utils/plot.py diff --git a/cython/gtsam/utils/plot.py b/cython/gtsam/utils/plot.py new file mode 100644 index 000000000..556e9d8d5 --- /dev/null +++ b/cython/gtsam/utils/plot.py @@ -0,0 +1,76 @@ +"""Various plotting utlities.""" + +import numpy as np +import matplotlib.pyplot as plt + + +def plot_point3_on_axes(axes, point, linespec): + """Plot a 3D point on given axis 'axes' with given 'linespec'.""" + axes.plot([point.x()], [point.y()], [point.z()], linespec) + + +def plot_point3(fignum, point, linespec): + """Plot a 3D point on given figure with given 'linespec'.""" + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plot_point3_on_axes(axes, point, linespec) + + +def plot_3d_points(fignum, values, linespec, marginals=None): + """ + Plots the Point3s in 'values', with optional covariances. + Finds all the Point3 objects in the given Values object and plots them. + If a Marginals object is given, this function will also plot marginal + covariance ellipses for each point. + """ + + keys = values.keys() + + # Plot points and covariance matrices + for i in range(keys.size()): + try: + p = values.atPoint3(keys.at(i)) + # if haveMarginals + # P = marginals.marginalCovariance(key); + # gtsam.plot_point3(p, linespec, P); + # else + plot_point3(fignum, p, linespec) + except RuntimeError: + continue + # I guess it's not a Point3 + + +def plot_pose3_on_axes(axes, pose, axis_length=0.1): + """Plot a 3D pose on given axis 'axes' with given 'axis_length'.""" + # get rotation and translation (center) + gRp = pose.rotation().matrix() # rotation from pose to global + t = pose.translation() + origin = np.array([t.x(), t.y(), t.z()]) + + # draw the camera axes + x_axis = origin + gRp[:, 0] * axis_length + line = np.append(origin[np.newaxis], x_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'r-') + + y_axis = origin + gRp[:, 1] * axis_length + line = np.append(origin[np.newaxis], y_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'g-') + + z_axis = origin + gRp[:, 2] * axis_length + line = np.append(origin[np.newaxis], z_axis[np.newaxis], axis=0) + axes.plot(line[:, 0], line[:, 1], line[:, 2], 'b-') + + # # plot the covariance + # if (nargin>2) && (~isempty(P)) + # pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame + # gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame + # gtsam.covarianceEllipse3D(origin,gPp); + # end + + +def plot_pose3(fignum, pose, axis_length=0.1): + """Plot a 3D pose on given figure with given 'axis_length'.""" + # get figure object + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plot_pose3_on_axes(axes, pose, axis_length) From 7097880d490f67166e16db5f5a655577a67b3b95 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 22:46:24 -0400 Subject: [PATCH 042/197] GTSAM examples, cython versions --- cython/gtsam/examples/OdometryExample.py | 38 +++++ cython/gtsam/examples/Pose2SLAMExample.py | 75 ++++++++++ cython/gtsam/examples/README.md | 4 + cython/gtsam/examples/SFMdata.py | 37 +++++ cython/gtsam/examples/VisualISAM2Example.py | 153 ++++++++++++++++++++ cython/gtsam/examples/__init__.py | 1 + 6 files changed, 308 insertions(+) create mode 100644 cython/gtsam/examples/OdometryExample.py create mode 100644 cython/gtsam/examples/Pose2SLAMExample.py create mode 100644 cython/gtsam/examples/README.md create mode 100644 cython/gtsam/examples/SFMdata.py create mode 100644 cython/gtsam/examples/VisualISAM2Example.py create mode 100644 cython/gtsam/examples/__init__.py diff --git a/cython/gtsam/examples/OdometryExample.py b/cython/gtsam/examples/OdometryExample.py new file mode 100644 index 000000000..3bdf6eda5 --- /dev/null +++ b/cython/gtsam/examples/OdometryExample.py @@ -0,0 +1,38 @@ +#!/usr/bin/env python +from __future__ import print_function + +import numpy as np + +import gtsam + +# Create an empty nonlinear factor graph +graph = gtsam.NonlinearFactorGraph() + +# Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin +priorNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) +graph.add(gtsam.PriorFactorPose2(1, priorMean, priorNoise)) + +# Add odometry factors +odometry = gtsam.Pose2(2.0, 0.0, 0.0) +# For simplicity, we will use the same noise model for each odometry factor +odometryNoise = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, odometryNoise)) +graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, odometryNoise)) +graph.print_("\nFactor Graph:\n") + +# Create the data structure to hold the initialEstimate estimate to the solution +# For illustrative purposes, these have been deliberately set to incorrect values +initial = gtsam.Values() +initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1)) +initial.print_("\nInitial Estimate:\n") + +# optimize using Levenberg-Marquardt optimization +params = gtsam.LevenbergMarquardtParams() +optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params) +result = optimizer.optimize() +result.print_("\nFinal Result:\n") diff --git a/cython/gtsam/examples/Pose2SLAMExample.py b/cython/gtsam/examples/Pose2SLAMExample.py new file mode 100644 index 000000000..fe71788d8 --- /dev/null +++ b/cython/gtsam/examples/Pose2SLAMExample.py @@ -0,0 +1,75 @@ +from __future__ import print_function + +import math + +import numpy as np + +import gtsam + + +def Vector3(x, y, z): return np.array([x, y, z]) + + +# 1. Create a factor graph container and add factors to it +graph = gtsam.NonlinearFactorGraph() + +# 2a. Add a prior on the first pose, setting it to the origin +# A prior factor consists of a mean and a noise model (covariance matrix) +priorNoise = gtsam.noiseModel_Diagonal.Sigmas(Vector3(0.3, 0.3, 0.1)) +graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), priorNoise)) + +# For simplicity, we will use the same noise model for odometry and loop closures +model = gtsam.noiseModel_Diagonal.Sigmas(Vector3(0.2, 0.2, 0.1)) + +# 2b. Add odometry factors +# Create odometry (Between) factors between consecutive poses +graph.add(gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), model)) +graph.add(gtsam.BetweenFactorPose2( + 2, 3, gtsam.Pose2(2, 0, math.pi / 2), model)) +graph.add(gtsam.BetweenFactorPose2( + 3, 4, gtsam.Pose2(2, 0, math.pi / 2), model)) +graph.add(gtsam.BetweenFactorPose2( + 4, 5, gtsam.Pose2(2, 0, math.pi / 2), model)) + +# 2c. Add the loop closure constraint +# This factor encodes the fact that we have returned to the same pose. In real +# systems, these constraints may be identified in many ways, such as appearance-based +# techniques with camera images. We will use another Between Factor to enforce this constraint: +graph.add(gtsam.BetweenFactorPose2( + 5, 2, gtsam.Pose2(2, 0, math.pi / 2), model)) +graph.print_("\nFactor Graph:\n") # print + +# 3. Create the data structure to hold the initial_estimate estimate to the +# solution. For illustrative purposes, these have been deliberately set to incorrect values +initial_estimate = gtsam.Values() +initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2)) +initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2)) +initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2)) +initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi)) +initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2)) +initial_estimate.print_("\nInitial Estimate:\n") # print + +# 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer +# The optimizer accepts an optional set of configuration parameters, +# controlling things like convergence criteria, the type of linear +# system solver to use, and the amount of information displayed during +# optimization. We will set a few parameters as a demonstration. +parameters = gtsam.GaussNewtonParams() + +# Stop iterating once the change in error between steps is less than this value +parameters.setRelativeErrorTol(1e-5) +# Do not perform more than N iteration steps +parameters.setMaxIterations(100) +# Create the optimizer ... +optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters) +# ... and optimize +result = optimizer.optimize() +result.print_("Final Result:\n") + +# 5. Calculate and print marginal covariances for all variables +marginals = gtsam.Marginals(graph, result) +print("x1 covariance:\n", marginals.marginalCovariance(1)) +print("x2 covariance:\n", marginals.marginalCovariance(2)) +print("x3 covariance:\n", marginals.marginalCovariance(3)) +print("x4 covariance:\n", marginals.marginalCovariance(4)) +print("x5 covariance:\n", marginals.marginalCovariance(5)) diff --git a/cython/gtsam/examples/README.md b/cython/gtsam/examples/README.md new file mode 100644 index 000000000..4474da488 --- /dev/null +++ b/cython/gtsam/examples/README.md @@ -0,0 +1,4 @@ +These examples are almost identical to the old handwritten python wrapper +examples. However, there are just some slight name changes, for example .print +becomes .print_, and noiseModel.Diagonal becomes noiseModel_Diagonal etc... +Also, annoyingly, instead of gtsam.Symbol('b',0) we now need to say gtsam.symbol(ord('b'), 0)) diff --git a/cython/gtsam/examples/SFMdata.py b/cython/gtsam/examples/SFMdata.py new file mode 100644 index 000000000..742518c2c --- /dev/null +++ b/cython/gtsam/examples/SFMdata.py @@ -0,0 +1,37 @@ +""" +A structure-from-motion example with landmarks + - The landmarks form a 10 meter cube + - The robot rotates around the landmarks, always facing towards the cube +""" + +import numpy as np + +import gtsam + + +def createPoints(): + # Create the set of ground-truth landmarks + points = [gtsam.Point3(10.0, 10.0, 10.0), + gtsam.Point3(-10.0, 10.0, 10.0), + gtsam.Point3(-10.0, -10.0, 10.0), + gtsam.Point3(10.0, -10.0, 10.0), + gtsam.Point3(10.0, 10.0, -10.0), + gtsam.Point3(-10.0, 10.0, -10.0), + gtsam.Point3(-10.0, -10.0, -10.0), + gtsam.Point3(10.0, -10.0, -10.0)] + return points + + +def createPoses(K): + # Create the set of ground-truth poses + radius = 30.0 + angles = np.linspace(0, 2*np.pi, 8, endpoint=False) + up = gtsam.Point3(0, 0, 1) + target = gtsam.Point3(0, 0, 0) + poses = [] + for theta in angles: + position = gtsam.Point3(radius*np.cos(theta), + radius*np.sin(theta), 0.0) + camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up, K) + poses.append(camera.pose()) + return poses diff --git a/cython/gtsam/examples/VisualISAM2Example.py b/cython/gtsam/examples/VisualISAM2Example.py new file mode 100644 index 000000000..29383612d --- /dev/null +++ b/cython/gtsam/examples/VisualISAM2Example.py @@ -0,0 +1,153 @@ +"""An example of running visual SLAM using iSAM2.""" +# pylint: disable=invalid-name + +from __future__ import print_function + +import matplotlib.pyplot as plt +import numpy as np +from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611 + +import gtsam +import gtsam.utils.plot as gtsam_plot +from gtsam.examples import SFMdata + + +def X(i): + """Create key for pose i.""" + return int(gtsam.symbol(ord('x'), i)) + + +def L(j): + """Create key for landmark j.""" + return int(gtsam.symbol(ord('l'), j)) + + +def visual_ISAM2_plot(result): + """ + VisualISAMPlot plots current state of ISAM2 object + Author: Ellon Paiva + Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert + """ + + # Declare an id for the figure + fignum = 0 + + fig = plt.figure(fignum) + axes = fig.gca(projection='3d') + plt.cla() + + # Plot points + # Can't use data because current frame might not see all points + # marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()) + # gtsam.plot_3d_points(result, [], marginals) + gtsam_plot.plot_3d_points(fignum, result, 'rx') + + # Plot cameras + i = 0 + while result.exists(X(i)): + pose_i = result.atPose3(X(i)) + gtsam_plot.plot_pose3(fignum, pose_i, 10) + i += 1 + + # draw + axes.set_xlim3d(-40, 40) + axes.set_ylim3d(-40, 40) + axes.set_zlim3d(-40, 40) + plt.pause(1) + + +def visual_ISAM2_example(): + plt.ion() + + # Define the camera calibration parameters + K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0) + + # Define the camera observation noise model + measurement_noise = gtsam.noiseModel_Isotropic.Sigma( + 2, 1.0) # one pixel in u and v + + # Create the set of ground-truth landmarks + points = SFMdata.createPoints() + + # Create the set of ground-truth poses + poses = SFMdata.createPoses(K) + + # Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps + # to maintain proper linearization and efficient variable ordering, iSAM2 + # performs partial relinearization/reordering at each step. A parameter + # structure is available that allows the user to set various properties, such + # as the relinearization threshold and type of linear solver. For this + # example, we we set the relinearization threshold small so the iSAM2 result + # will approach the batch result. + parameters = gtsam.ISAM2Params() + parameters.setRelinearizeThreshold(0.01) + parameters.setRelinearizeSkip(1) + isam = gtsam.ISAM2(parameters) + + # Create a Factor Graph and Values to hold the new data + graph = gtsam.NonlinearFactorGraph() + initial_estimate = gtsam.Values() + + # Loop over the different poses, adding the observations to iSAM incrementally + for i, pose in enumerate(poses): + + # Add factors for each landmark observation + for j, point in enumerate(points): + camera = gtsam.PinholeCameraCal3_S2(pose, K) + measurement = camera.project(point) + graph.push_back(gtsam.GenericProjectionFactorCal3_S2( + measurement, measurement_noise, X(i), L(j), K)) + + # Add an initial guess for the current pose + # Intentionally initialize the variables off from the ground truth + initial_estimate.insert(X(i), pose.compose(gtsam.Pose3( + gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20)))) + + # If this is the first iteration, add a prior on the first pose to set the + # coordinate frame and a prior on the first landmark to set the scale. + # Also, as iSAM solves incrementally, we must wait until each is observed + # at least twice before adding it to iSAM. + if i == 0: + # Add a prior on pose x0 + pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array( + [0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw + graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], pose_noise)) + + # Add a prior on landmark l0 + point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1) + graph.push_back(gtsam.PriorFactorPoint3( + L(0), points[0], point_noise)) # add directly to graph + + # Add initial guesses to all observed landmarks + # Intentionally initialize the variables off from the ground truth + for j, point in enumerate(points): + initial_estimate.insert(L(j), gtsam.Point3( + point.x()-0.25, point.y()+0.20, point.z()+0.15)) + else: + # Update iSAM with the new factors + isam.update(graph, initial_estimate) + # Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. + # If accuracy is desired at the expense of time, update(*) can be called additional + # times to perform multiple optimizer iterations every step. + isam.update() + current_estimate = isam.calculateEstimate() + print("****************************************************") + print("Frame", i, ":") + for j in range(i + 1): + print(X(j), ":", current_estimate.atPose3(X(j))) + + for j in range(len(points)): + print(L(j), ":", current_estimate.atPoint3(L(j))) + + visual_ISAM2_plot(current_estimate) + + # Clear the factor graph and values for the next iteration + graph.resize(0) + initial_estimate.clear() + + plt.ioff() + plt.show() + + +if __name__ == '__main__': + visual_ISAM2_example() diff --git a/cython/gtsam/examples/__init__.py b/cython/gtsam/examples/__init__.py new file mode 100644 index 000000000..ccdd2d6d2 --- /dev/null +++ b/cython/gtsam/examples/__init__.py @@ -0,0 +1 @@ +from . import SFMdata From 3de391e895e651019d7f8c5f74b3c2afe1fd12ff Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 27 Sep 2018 22:47:15 -0400 Subject: [PATCH 043/197] Ignore .env file for VS code --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index b62617d21..e9ac11c72 100644 --- a/.gitignore +++ b/.gitignore @@ -16,3 +16,4 @@ cython/gtsam.pyx cython/gtsam.so cython/gtsam_wrapper.pxd .vscode +/.env From 1ec15a734505495d3158a91b98699e4e16cc4351 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Fri, 28 Sep 2018 00:47:17 -0700 Subject: [PATCH 044/197] Incorporate Frank's suggestions for PR #315 --- tests/testGaussianBayesTreeB.cpp | 15 +++------------ 1 file changed, 3 insertions(+), 12 deletions(-) diff --git a/tests/testGaussianBayesTreeB.cpp b/tests/testGaussianBayesTreeB.cpp index 88b1aede2..984728ebf 100644 --- a/tests/testGaussianBayesTreeB.cpp +++ b/tests/testGaussianBayesTreeB.cpp @@ -320,21 +320,12 @@ TEST(GaussianBayesTree, shortcut_overlapping_separator) Matrix actualJointJ = joint.augmentedJacobian(); - bool Row0RhsSignsEqual = - signbit(expectedJointJ(0, 2)) == signbit(actualJointJ(0, 2)); - - if (!Row0RhsSignsEqual) - { + // PR 315: sign of rows in joint are immaterial + if (signbit(expectedJointJ(0, 2)) != signbit(actualJointJ(0, 2))) expectedJointJ.row(0) = -expectedJointJ.row(0); - } - bool Row1RhsSignsEqual = - signbit(expectedJointJ(1, 2)) == signbit(actualJointJ(1, 2)); - - if (!Row1RhsSignsEqual) - { + if (signbit(expectedJointJ(1, 2)) != signbit(actualJointJ(1, 2))) expectedJointJ.row(1) = -expectedJointJ.row(1); - } EXPECT(assert_equal(expectedJointJ, actualJointJ)); } From 4a8c2f666c619427ffc180abf17bddc916133176 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 28 Sep 2018 11:20:26 -0400 Subject: [PATCH 045/197] Fixed warning --- gtsam/3rdparty/metis/libmetis/balance.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/metis/libmetis/balance.c b/gtsam/3rdparty/metis/libmetis/balance.c index 3fb0e6e56..f71df9c0e 100644 --- a/gtsam/3rdparty/metis/libmetis/balance.c +++ b/gtsam/3rdparty/metis/libmetis/balance.c @@ -20,7 +20,7 @@ void Balance2Way(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts) if (graph->ncon == 1) { /* return right away if the balance is OK */ - if (iabs(ntpwgts[0]*graph->tvwgt[0]-graph->pwgts[0]) < 3*graph->tvwgt[0]/graph->nvtxs) + if (fabs(ntpwgts[0]*graph->tvwgt[0]-graph->pwgts[0]) < 3*graph->tvwgt[0]/graph->nvtxs) return; if (graph->nbnd > 0) From ce65b5d0439af811846360195ad712aac93408f3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 28 Sep 2018 11:20:38 -0400 Subject: [PATCH 046/197] virtual destructors --- gtsam/navigation/ImuFactor.h | 4 ++++ gtsam/navigation/TangentPreintegration.h | 6 +++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 55f043dd3..ccf5db5c3 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -106,6 +106,10 @@ public: preintMeasCov_(preintMeasCov) { } + /// Virtual destructor + virtual ~PreintegratedImuMeasurements() { + } + /// print void print(const std::string& s = "Preintegrated Measurements:") const override; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 34c38e22b..da49e4ddd 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -42,7 +42,7 @@ class TangentPreintegration : public PreintegrationBase { } public: - /// @name Constructors + /// @name Constructors/destructors /// @{ /** @@ -53,6 +53,10 @@ public: TangentPreintegration(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); + /// Virtual destructor + virtual ~TangentPreintegration() { + } + /// @} /// @name Basic utilities From a87ce9bac423adf45e7d69fb08cbc14ed188773e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 28 Sep 2018 11:20:55 -0400 Subject: [PATCH 047/197] Fixed consistency checks --- gtsam/linear/JacobianFactor.cpp | 2 +- gtsam/nonlinear/ISAM2-impl.cpp | 7 ++++--- gtsam/nonlinear/ISAM2-inl.h | 4 ++-- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index 4597759e3..56a5dc085 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -188,7 +188,7 @@ boost::tuple, DenseIndex, DenseIndex> _countDims( m += factor->rows(); } -#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) for(DenseIndex d: varDims) { assert(d != numeric_limits::max()); } diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index a0fc117d9..3b5156535 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -291,9 +291,10 @@ size_t ISAM2::Impl::UpdateGaussNewtonDelta(const FastVector lastBacksubVariableCount += optimizeWildfireNonRecursive( root, wildfireThreshold, replacedKeys, delta); // modifies delta -#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS - for(size_t j=0; j)).all()); +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) + for (VectorValues::const_iterator key_delta = delta.begin(); key_delta != delta.end(); ++key_delta) { + assert(delta[key_delta->first].allFinite()); + } #endif } diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h index f04e16b7d..fecefd2a5 100644 --- a/gtsam/nonlinear/ISAM2-inl.h +++ b/gtsam/nonlinear/ISAM2-inl.h @@ -44,7 +44,7 @@ void optimizeWildfire(const boost::shared_ptr& clique, double threshold, // Are any clique variables part of the tree that has been redone? bool cliqueReplaced = replaced.exists((*clique)->frontals().front()); -#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) for(Key frontal: clique->conditional()->frontals()) { assert(cliqueReplaced == replaced.exists(frontal)); } @@ -121,7 +121,7 @@ bool optimizeWildfireNode(const boost::shared_ptr& clique, double thresh // Are any clique variables part of the tree that has been redone? bool cliqueReplaced = replaced.exists(clique->conditional()->frontals().front()); -#ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) for(Key frontal: clique->conditional()->frontals()) { assert(cliqueReplaced == replaced.exists(frontal)); } From 67ffd65838b774ad7acd89bf18711423af6a2bcb Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 00:04:13 -0400 Subject: [PATCH 048/197] Added Alexander's example file --- examples/ISAM2Example_SmartFactor.cpp | 106 ++++++++++++++++++++++++++ 1 file changed, 106 insertions(+) create mode 100644 examples/ISAM2Example_SmartFactor.cpp diff --git a/examples/ISAM2Example_SmartFactor.cpp b/examples/ISAM2Example_SmartFactor.cpp new file mode 100644 index 000000000..8435cc86e --- /dev/null +++ b/examples/ISAM2Example_SmartFactor.cpp @@ -0,0 +1,106 @@ +#include +#include + +#include +#include +#include + +#include + +using namespace gtsam; + +// Make the typename short so it looks much cleaner +typedef SmartProjectionPoseFactor SmartFactor; + +int main(int argc, char* argv[]) { + Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); + + noiseModel::Isotropic::shared_ptr measurement_noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + + noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas( + (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished()); + noiseModel::Isotropic::shared_ptr large_noise = noiseModel::Isotropic::Sigma(6, 100); + + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.01; + parameters.relinearizeSkip = 1; + parameters.cacheLinearizedFactors = false; + parameters.enableDetailedResults = true; + parameters.print(); + ISAM2 isam(parameters); + + // Create a factor graph + NonlinearFactorGraph graph; + Values initial_estimate; + + Point3 point(0.0, 0.0, 1.0); + + // Intentionally initialize the variables off from the ground truth + Pose3 delta(Rot3::Rodrigues(0.0, 0.0, 0.0), Point3(0.05, -0.10, 0.20)); + + Pose3 pose1(Rot3(), Point3(0.0, 0.0, 0.0)); + Pose3 pose2(Rot3(), Point3(0.0, 0.2, 0.0)); + Pose3 pose3(Rot3(), Point3(0.0, 0.4, 0.0)); + Pose3 pose4(Rot3(), Point3(0.0, 0.5, 0.0)); + Pose3 pose5(Rot3(), Point3(0.0, 0.6, 0.0)); + + std::vector pose_list = { pose1, pose2, pose3, pose4, pose5 }; + + SmartFactor::shared_ptr smart_factor(new SmartFactor(measurement_noise, K)); + graph.push_back(smart_factor); + + graph.emplace_shared>(0, pose_list[0], noise); + initial_estimate.insert(0, pose_list[0].compose(delta)); + smart_factor->add(PinholePose(pose_list[0], K).project(point), 0); + + for (int i = 1; i < 5; i++) { + PinholePose camera(pose_list[i], K); + Point2 measurement = camera.project(point); + + std::cout << "****************************************************" << std::endl; + std::cout << "i = " << i << std::endl; + std::cout << "Measurement " << i << " is " << measurement << std::endl; + + graph.emplace_shared>(i, pose_list[i], noise); + //graph.emplace_shared>(i - 1, i, Pose3(), large_noise); + initial_estimate.insert(i, pose_list[i].compose(delta)); + smart_factor->add(measurement, i); + + ISAM2Result result = isam.update(graph, initial_estimate); + graph.resize(0); + initial_estimate.clear(); + + result.print(); + + const auto& var_map = (*(result.detail)).variableStatus; + + std::cout << "Detailed results:" << std::endl; + for (int j = 0; j < 3; j++) { + if (var_map.exists(j)) { + std::cout << j << " is reeliminated: " << var_map.at(j).isReeliminated << std::endl; + std::cout << j << " is relinearized above thresh: " << var_map.at(j).isAboveRelinThreshold << std::endl; + std::cout << j << " is relinearized involved: " << var_map.at(j).isRelinearizeInvolved << std::endl; + std::cout << j << " is relinearized: " << var_map.at(j).isRelinearized << std::endl; + std::cout << j << " is observed: " << var_map.at(j).isObserved << std::endl; + std::cout << j << " is new: " << var_map.at(j).isNew << std::endl; + std::cout << j << " is in the root clique: " << var_map.at(j).inRootClique << std::endl; + } + else { + std::cout << j << " does not exist in the detailed results map." << std::endl; + } + } + + Values current_estimate = isam.calculateEstimate(); + current_estimate.print("Current estimate: "); + + boost::optional point_res = smart_factor->point(current_estimate); + if (point_res) { + std::cout << *point_res << std::endl; + } + else { + std::cout << "Point is degenerate." << std::endl; + } + } + + return 0; +} From 224299ccb90d0205d4926cb5ea2b92395e497e2f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 00:05:39 -0400 Subject: [PATCH 049/197] Cleaned up/naming conventions/docs --- examples/ISAM2Example_SmartFactor.cpp | 111 ++++++++++++++------------ 1 file changed, 60 insertions(+), 51 deletions(-) diff --git a/examples/ISAM2Example_SmartFactor.cpp b/examples/ISAM2Example_SmartFactor.cpp index 8435cc86e..77e29b8ff 100644 --- a/examples/ISAM2Example_SmartFactor.cpp +++ b/examples/ISAM2Example_SmartFactor.cpp @@ -1,5 +1,8 @@ -#include -#include +/** + * @file ISAM2Example_SmartFactor.cpp + * @brief test of iSAM with smart factors, led to bitbucket issue #367 + * @author Alexander (pumaking on BitBucket) + */ #include #include @@ -7,7 +10,13 @@ #include +#include +#include + +using namespace std; using namespace gtsam; +using symbol_shorthand::P; +using symbol_shorthand::X; // Make the typename short so it looks much cleaner typedef SmartProjectionPoseFactor SmartFactor; @@ -15,11 +24,12 @@ typedef SmartProjectionPoseFactor SmartFactor; int main(int argc, char* argv[]) { Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); - noiseModel::Isotropic::shared_ptr measurement_noise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + auto measurementNoise = + noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v - noiseModel::Diagonal::shared_ptr noise = noiseModel::Diagonal::Sigmas( - (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)).finished()); - noiseModel::Isotropic::shared_ptr large_noise = noiseModel::Isotropic::Sigma(6, 100); + Vector6 sigmas; + sigmas << Vector3::Constant(0.3), Vector3::Constant(0.1); + auto noise = noiseModel::Diagonal::Sigmas(sigmas); ISAM2Params parameters; parameters.relinearizeThreshold = 0.01; @@ -31,7 +41,7 @@ int main(int argc, char* argv[]) { // Create a factor graph NonlinearFactorGraph graph; - Values initial_estimate; + Values initialEstimate; Point3 point(0.0, 0.0, 1.0); @@ -44,62 +54,61 @@ int main(int argc, char* argv[]) { Pose3 pose4(Rot3(), Point3(0.0, 0.5, 0.0)); Pose3 pose5(Rot3(), Point3(0.0, 0.6, 0.0)); - std::vector pose_list = { pose1, pose2, pose3, pose4, pose5 }; + vector poses = {pose1, pose2, pose3, pose4, pose5}; - SmartFactor::shared_ptr smart_factor(new SmartFactor(measurement_noise, K)); - graph.push_back(smart_factor); + SmartFactor::shared_ptr smartFactor(new SmartFactor(measurementNoise, K)); + graph.push_back(smartFactor); - graph.emplace_shared>(0, pose_list[0], noise); - initial_estimate.insert(0, pose_list[0].compose(delta)); - smart_factor->add(PinholePose(pose_list[0], K).project(point), 0); + graph.emplace_shared>(X(0), poses[0], noise); + initialEstimate.insert(X(0), poses[0].compose(delta)); + smartFactor->add(PinholePose(poses[0], K).project(point), X(0)); - for (int i = 1; i < 5; i++) { - PinholePose camera(pose_list[i], K); + for (size_t i = 1; i < 5; i++) { + cout << "****************************************************" << endl; + cout << "i = " << i << endl; + + // Add measurement to smart factor + PinholePose camera(poses[i], K); Point2 measurement = camera.project(point); + smartFactor->add(measurement, X(i)); + cout << "Measurement " << i << "" << measurement << endl; - std::cout << "****************************************************" << std::endl; - std::cout << "i = " << i << std::endl; - std::cout << "Measurement " << i << " is " << measurement << std::endl; - - graph.emplace_shared>(i, pose_list[i], noise); - //graph.emplace_shared>(i - 1, i, Pose3(), large_noise); - initial_estimate.insert(i, pose_list[i].compose(delta)); - smart_factor->add(measurement, i); - - ISAM2Result result = isam.update(graph, initial_estimate); - graph.resize(0); - initial_estimate.clear(); + // Add prior on new pose + graph.emplace_shared>(X(i), poses[i], noise); + initialEstimate.insert(X(i), poses[i].compose(delta)); + // Update iSAM2 + ISAM2Result result = isam.update(graph, initialEstimate); result.print(); - const auto& var_map = (*(result.detail)).variableStatus; - - std::cout << "Detailed results:" << std::endl; - for (int j = 0; j < 3; j++) { - if (var_map.exists(j)) { - std::cout << j << " is reeliminated: " << var_map.at(j).isReeliminated << std::endl; - std::cout << j << " is relinearized above thresh: " << var_map.at(j).isAboveRelinThreshold << std::endl; - std::cout << j << " is relinearized involved: " << var_map.at(j).isRelinearizeInvolved << std::endl; - std::cout << j << " is relinearized: " << var_map.at(j).isRelinearized << std::endl; - std::cout << j << " is observed: " << var_map.at(j).isObserved << std::endl; - std::cout << j << " is new: " << var_map.at(j).isNew << std::endl; - std::cout << j << " is in the root clique: " << var_map.at(j).inRootClique << std::endl; - } - else { - std::cout << j << " does not exist in the detailed results map." << std::endl; - } + cout << "Detailed results:" << endl; + for (auto keyedStatus : result.detail->variableStatus) { + const auto& status = keyedStatus.second; + cout << keyedStatus.first << " {" << endl; + cout << "reeliminated: " << status.isReeliminated << endl; + cout << "relinearized above thresh: " << status.isAboveRelinThreshold + << endl; + cout << "relinearized involved: " << status.isRelinearizeInvolved << endl; + cout << "relinearized: " << status.isRelinearized << endl; + cout << "observed: " << status.isObserved << endl; + cout << "new: " << status.isNew << endl; + cout << "in the root clique: " << status.inRootClique << endl; + cout << "}" << endl; } - Values current_estimate = isam.calculateEstimate(); - current_estimate.print("Current estimate: "); + Values currentEstimate = isam.calculateEstimate(); + currentEstimate.print("Current estimate: "); - boost::optional point_res = smart_factor->point(current_estimate); - if (point_res) { - std::cout << *point_res << std::endl; - } - else { - std::cout << "Point is degenerate." << std::endl; + boost::optional pointEstimate = smartFactor->point(currentEstimate); + if (pointEstimate) { + cout << *pointEstimate << endl; + } else { + cout << "Point degenerate." << endl; } + + // Reset graph and initial estimate for next iteration + graph.resize(0); + initialEstimate.clear(); } return 0; From e6c0d7334fba6eac1ef6208fb7f949fe171ed0ec Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 00:06:19 -0400 Subject: [PATCH 050/197] Cleaned up cpplint errors - no functionality change --- gtsam/nonlinear/ISAM2.cpp | 2 +- gtsam/nonlinear/ISAM2.h | 642 ++++++++++++++++++++++++-------------- 2 files changed, 401 insertions(+), 243 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 122bf8aeb..d4df01a68 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -247,7 +247,7 @@ ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const KeySe /* ************************************************************************* */ // find intermediate (linearized) factors from cache that are passed into the affected area -GaussianFactorGraph ISAM2::getCachedBoundaryFactors(Cliques& orphans) { +GaussianFactorGraph ISAM2::getCachedBoundaryFactors(const Cliques& orphans) { GaussianFactorGraph cachedBoundary; for(sharedClique orphan: orphans) { diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 114c04018..235cb65a5 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -11,7 +11,8 @@ /** * @file ISAM2.h - * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization. + * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid + * relinearization. * @author Michael Kaess, Richard Roberts */ @@ -19,9 +20,12 @@ #pragma once -#include -#include +#include +#include + #include +#include +#include #include @@ -34,21 +38,29 @@ namespace gtsam { * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). */ struct GTSAM_EXPORT ISAM2GaussNewtonParams { - double wildfireThreshold; ///< Continue updating the linear delta only when changes are above this threshold (default: 0.001) + double + wildfireThreshold; ///< Continue updating the linear delta only when + ///< changes are above this threshold (default: 0.001) /** Specify parameters as constructor arguments */ ISAM2GaussNewtonParams( - double _wildfireThreshold = 0.001 ///< see ISAM2GaussNewtonParams public variables, ISAM2GaussNewtonParams::wildfireThreshold - ) : wildfireThreshold(_wildfireThreshold) {} + double _wildfireThreshold = + 0.001 ///< see ISAM2GaussNewtonParams public variables, + ///< ISAM2GaussNewtonParams::wildfireThreshold + ) + : wildfireThreshold(_wildfireThreshold) {} void print(const std::string str = "") const { - std::cout << str << "type: ISAM2GaussNewtonParams\n"; - std::cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; - std::cout.flush(); + using std::cout; + cout << str << "type: ISAM2GaussNewtonParams\n"; + cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + cout.flush(); } double getWildfireThreshold() const { return wildfireThreshold; } - void setWildfireThreshold(double wildfireThreshold) { this->wildfireThreshold = wildfireThreshold; } + void setWildfireThreshold(double wildfireThreshold) { + this->wildfireThreshold = wildfireThreshold; + } }; /** @@ -58,51 +70,81 @@ struct GTSAM_EXPORT ISAM2GaussNewtonParams { * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). */ struct GTSAM_EXPORT ISAM2DoglegParams { - double initialDelta; ///< The initial trust region radius for Dogleg - double wildfireThreshold; ///< Continue updating the linear delta only when changes are above this threshold (default: 1e-5) - DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode; ///< See description in DoglegOptimizerImpl::TrustRegionAdaptationMode - bool verbose; ///< Whether Dogleg prints iteration and convergence information + double initialDelta; ///< The initial trust region radius for Dogleg + double + wildfireThreshold; ///< Continue updating the linear delta only when + ///< changes are above this threshold (default: 1e-5) + DoglegOptimizerImpl::TrustRegionAdaptationMode + adaptationMode; ///< See description in + ///< DoglegOptimizerImpl::TrustRegionAdaptationMode + bool + verbose; ///< Whether Dogleg prints iteration and convergence information /** Specify parameters as constructor arguments */ ISAM2DoglegParams( - double _initialDelta = 1.0, ///< see ISAM2DoglegParams::initialDelta - double _wildfireThreshold = 1e-5, ///< see ISAM2DoglegParams::wildfireThreshold - DoglegOptimizerImpl::TrustRegionAdaptationMode _adaptationMode = DoglegOptimizerImpl::SEARCH_EACH_ITERATION, ///< see ISAM2DoglegParams::adaptationMode - bool _verbose = false ///< see ISAM2DoglegParams::verbose - ) : initialDelta(_initialDelta), wildfireThreshold(_wildfireThreshold), - adaptationMode(_adaptationMode), verbose(_verbose) {} + double _initialDelta = 1.0, ///< see ISAM2DoglegParams::initialDelta + double _wildfireThreshold = + 1e-5, ///< see ISAM2DoglegParams::wildfireThreshold + DoglegOptimizerImpl::TrustRegionAdaptationMode _adaptationMode = + DoglegOptimizerImpl:: + SEARCH_EACH_ITERATION, ///< see ISAM2DoglegParams::adaptationMode + bool _verbose = false ///< see ISAM2DoglegParams::verbose + ) + : initialDelta(_initialDelta), + wildfireThreshold(_wildfireThreshold), + adaptationMode(_adaptationMode), + verbose(_verbose) {} void print(const std::string str = "") const { - std::cout << str << "type: ISAM2DoglegParams\n"; - std::cout << str << "initialDelta: " << initialDelta << "\n"; - std::cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; - std::cout << str << "adaptationMode: " << adaptationModeTranslator(adaptationMode) << "\n"; - std::cout.flush(); + using std::cout; + cout << str << "type: ISAM2DoglegParams\n"; + cout << str << "initialDelta: " << initialDelta << "\n"; + cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + cout << str + << "adaptationMode: " << adaptationModeTranslator(adaptationMode) + << "\n"; + cout.flush(); } double getInitialDelta() const { return initialDelta; } double getWildfireThreshold() const { return wildfireThreshold; } - std::string getAdaptationMode() const { return adaptationModeTranslator(adaptationMode); }; - bool isVerbose() const { return verbose; }; + std::string getAdaptationMode() const { + return adaptationModeTranslator(adaptationMode); + } + bool isVerbose() const { return verbose; } + void setInitialDelta(double initialDelta) { + this->initialDelta = initialDelta; + } + void setWildfireThreshold(double wildfireThreshold) { + this->wildfireThreshold = wildfireThreshold; + } + void setAdaptationMode(const std::string& adaptationMode) { + this->adaptationMode = adaptationModeTranslator(adaptationMode); + } + void setVerbose(bool verbose) { this->verbose = verbose; } - void setInitialDelta(double initialDelta) { this->initialDelta = initialDelta; } - void setWildfireThreshold(double wildfireThreshold) { this->wildfireThreshold = wildfireThreshold; } - void setAdaptationMode(const std::string& adaptationMode) { this->adaptationMode = adaptationModeTranslator(adaptationMode); } - void setVerbose(bool verbose) { this->verbose = verbose; }; - - std::string adaptationModeTranslator(const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) const; - DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator(const std::string& adaptationMode) const; + std::string adaptationModeTranslator( + const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) + const; + DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator( + const std::string& adaptationMode) const; }; /** * @addtogroup ISAM2 - * Parameters for the ISAM2 algorithm. Default parameter values are listed below. + * Parameters for the ISAM2 algorithm. Default parameter values are listed + * below. */ -typedef FastMap ISAM2ThresholdMap; +typedef FastMap ISAM2ThresholdMap; typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue; struct GTSAM_EXPORT ISAM2Params { - typedef boost::variant OptimizationParams; ///< Either ISAM2GaussNewtonParams or ISAM2DoglegParams - typedef boost::variant > RelinearizationThreshold; ///< Either a constant relinearization threshold or a per-variable-type set of thresholds + typedef boost::variant + OptimizationParams; ///< Either ISAM2GaussNewtonParams or + ///< ISAM2DoglegParams + typedef boost::variant > + RelinearizationThreshold; ///< Either a constant relinearization + ///< threshold or a per-variable-type set of + ///< thresholds /** Optimization parameters, this both selects the nonlinear optimization * method and specifies its parameters, either ISAM2GaussNewtonParams or @@ -122,27 +164,36 @@ struct GTSAM_EXPORT ISAM2Params { * entries would be added with: * \code FastMap thresholds; - thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5).finished(); // 0.1 rad rotation threshold, 0.5 m translation threshold - thresholds['l'] = Vector3(1.0, 1.0, 1.0); // 1.0 m landmark position threshold + thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5).finished(); + // 0.1 rad rotation threshold, 0.5 m translation threshold thresholds['l'] = + Vector3(1.0, 1.0, 1.0); // 1.0 m landmark position threshold params.relinearizeThreshold = thresholds; \endcode */ RelinearizationThreshold relinearizeThreshold; - int relinearizeSkip; ///< Only relinearize any variables every relinearizeSkip calls to ISAM2::update (default: 10) + int relinearizeSkip; ///< Only relinearize any variables every + ///< relinearizeSkip calls to ISAM2::update (default: + ///< 10) - bool enableRelinearization; ///< Controls whether ISAM2 will ever relinearize any variables (default: true) + bool enableRelinearization; ///< Controls whether ISAM2 will ever relinearize + ///< any variables (default: true) - bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error before and after the update, to return in ISAM2Result from update() + bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error + ///< before and after the update, to return in + ///< ISAM2Result from update() enum Factorization { CHOLESKY, QR }; - /** Specifies whether to use QR or CHOESKY numerical factorization (default: CHOLESKY). - * Cholesky is faster but potentially numerically unstable for poorly-conditioned problems, which can occur when - * uncertainty is very low in some variables (or dimensions of variables) and very high in others. QR is - * slower but more numerically stable in poorly-conditioned problems. We suggest using the default of Cholesky - * unless gtsam sometimes throws IndefiniteLinearSystemException when your problem's Hessian is actually positive - * definite. For positive definite problems, numerical error accumulation can cause the problem to become - * numerically negative or indefinite as solving proceeds, especially when using Cholesky. + /** Specifies whether to use QR or CHOESKY numerical factorization (default: + * CHOLESKY). Cholesky is faster but potentially numerically unstable for + * poorly-conditioned problems, which can occur when uncertainty is very low + * in some variables (or dimensions of variables) and very high in others. QR + * is slower but more numerically stable in poorly-conditioned problems. We + * suggest using the default of Cholesky unless gtsam sometimes throws + * IndefiniteLinearSystemException when your problem's Hessian is actually + * positive definite. For positive definite problems, numerical error + * accumulation can cause the problem to become numerically negative or + * indefinite as solving proceeds, especially when using Cholesky. */ Factorization factorization; @@ -153,97 +204,156 @@ struct GTSAM_EXPORT ISAM2Params { */ bool cacheLinearizedFactors; - KeyFormatter keyFormatter; ///< A KeyFormatter for when keys are printed during debugging (default: DefaultKeyFormatter) + KeyFormatter + keyFormatter; ///< A KeyFormatter for when keys are printed during + ///< debugging (default: DefaultKeyFormatter) - bool enableDetailedResults; ///< Whether to compute and return ISAM2Result::detailedResults, this can increase running time (default: false) + bool enableDetailedResults; ///< Whether to compute and return + ///< ISAM2Result::detailedResults, this can + ///< increase running time (default: false) - /** Check variables for relinearization in tree-order, stopping the check once a variable does not need to be relinearized (default: false). - * This can improve speed by only checking a small part of the top of the tree. However, variables below the check cut-off can accumulate - * significant deltas without triggering relinearization. This is particularly useful in exploration scenarios where real-time performance - * is desired over correctness. Use with caution. + /** Check variables for relinearization in tree-order, stopping the check once + * a variable does not need to be relinearized (default: false). This can + * improve speed by only checking a small part of the top of the tree. + * However, variables below the check cut-off can accumulate significant + * deltas without triggering relinearization. This is particularly useful in + * exploration scenarios where real-time performance is desired over + * correctness. Use with caution. */ bool enablePartialRelinearizationCheck; - /// When you will be removing many factors, e.g. when using ISAM2 as a fixed-lag smoother, enable this option to - /// add factors in the first available factor slots, to avoid accumulating NULL factor slots, at the cost of - /// having to search for slots every time a factor is added. + /// When you will be removing many factors, e.g. when using ISAM2 as a + /// fixed-lag smoother, enable this option to add factors in the first + /// available factor slots, to avoid accumulating NULL factor slots, at the + /// cost of having to search for slots every time a factor is added. bool findUnusedFactorSlots; - /** Specify parameters as constructor arguments */ - ISAM2Params( - OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), ///< see ISAM2Params::optimizationParams - RelinearizationThreshold _relinearizeThreshold = 0.1, ///< see ISAM2Params::relinearizeThreshold - int _relinearizeSkip = 10, ///< see ISAM2Params::relinearizeSkip - bool _enableRelinearization = true, ///< see ISAM2Params::enableRelinearization - bool _evaluateNonlinearError = false, ///< see ISAM2Params::evaluateNonlinearError - Factorization _factorization = ISAM2Params::CHOLESKY, ///< see ISAM2Params::factorization - bool _cacheLinearizedFactors = true, ///< see ISAM2Params::cacheLinearizedFactors - const KeyFormatter& _keyFormatter = DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter - ) : optimizationParams(_optimizationParams), relinearizeThreshold(_relinearizeThreshold), - relinearizeSkip(_relinearizeSkip), enableRelinearization(_enableRelinearization), - evaluateNonlinearError(_evaluateNonlinearError), factorization(_factorization), - cacheLinearizedFactors(_cacheLinearizedFactors), keyFormatter(_keyFormatter), - enableDetailedResults(false), enablePartialRelinearizationCheck(false), - findUnusedFactorSlots(false) {} + /** + * Specify parameters as constructor arguments + * See the documentation of member variables above. + */ + ISAM2Params(OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), + RelinearizationThreshold _relinearizeThreshold = 0.1, + int _relinearizeSkip = 10, bool _enableRelinearization = true, + bool _evaluateNonlinearError = false, + Factorization _factorization = ISAM2Params::CHOLESKY, + bool _cacheLinearizedFactors = true, + const KeyFormatter& _keyFormatter = + DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter + ) + : optimizationParams(_optimizationParams), + relinearizeThreshold(_relinearizeThreshold), + relinearizeSkip(_relinearizeSkip), + enableRelinearization(_enableRelinearization), + evaluateNonlinearError(_evaluateNonlinearError), + factorization(_factorization), + cacheLinearizedFactors(_cacheLinearizedFactors), + keyFormatter(_keyFormatter), + enableDetailedResults(false), + enablePartialRelinearizationCheck(false), + findUnusedFactorSlots(false) {} /// print iSAM2 parameters void print(const std::string& str = "") const { - std::cout << str << "\n"; - if(optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) - boost::get(optimizationParams).print("optimizationParams: "); - else if(optimizationParams.type() == typeid(ISAM2DoglegParams)) - boost::get(optimizationParams).print("optimizationParams: "); + using std::cout; + cout << str << "\n"; + + static const std::string kStr("optimizationParams: "); + if (optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) + boost::get(optimizationParams).print(); + else if (optimizationParams.type() == typeid(ISAM2DoglegParams)) + boost::get(optimizationParams).print(kStr); else - std::cout << "optimizationParams: " << "{unknown type}" << "\n"; - if(relinearizeThreshold.type() == typeid(double)) - std::cout << "relinearizeThreshold: " << boost::get(relinearizeThreshold) << "\n"; - else - { - std::cout << "relinearizeThreshold: " << "{mapped}" << "\n"; - for(const ISAM2ThresholdMapValue& value: boost::get(relinearizeThreshold)) { - std::cout << " '" << value.first << "' -> [" << value.second.transpose() << " ]\n"; + cout << kStr << "{unknown type}\n"; + + cout << "relinearizeThreshold: "; + if (relinearizeThreshold.type() == typeid(double)) { + cout << boost::get(relinearizeThreshold) << "\n"; + } else { + cout << "{mapped}\n"; + for (const ISAM2ThresholdMapValue& value : + boost::get(relinearizeThreshold)) { + cout << " '" << value.first + << "' -> [" << value.second.transpose() << " ]\n"; } } - std::cout << "relinearizeSkip: " << relinearizeSkip << "\n"; - std::cout << "enableRelinearization: " << enableRelinearization << "\n"; - std::cout << "evaluateNonlinearError: " << evaluateNonlinearError << "\n"; - std::cout << "factorization: " << factorizationTranslator(factorization) << "\n"; - std::cout << "cacheLinearizedFactors: " << cacheLinearizedFactors << "\n"; - std::cout << "enableDetailedResults: " << enableDetailedResults << "\n"; - std::cout << "enablePartialRelinearizationCheck: " << enablePartialRelinearizationCheck << "\n"; - std::cout << "findUnusedFactorSlots: " << findUnusedFactorSlots << "\n"; - std::cout.flush(); + + cout << "relinearizeSkip: " << relinearizeSkip << "\n"; + cout << "enableRelinearization: " << enableRelinearization + << "\n"; + cout << "evaluateNonlinearError: " << evaluateNonlinearError + << "\n"; + cout << "factorization: " + << factorizationTranslator(factorization) << "\n"; + cout << "cacheLinearizedFactors: " << cacheLinearizedFactors + << "\n"; + cout << "enableDetailedResults: " << enableDetailedResults + << "\n"; + cout << "enablePartialRelinearizationCheck: " + << enablePartialRelinearizationCheck << "\n"; + cout << "findUnusedFactorSlots: " << findUnusedFactorSlots + << "\n"; + cout.flush(); } /// @name Getters and Setters for all properties /// @{ - OptimizationParams getOptimizationParams() const { return this->optimizationParams; } - RelinearizationThreshold getRelinearizeThreshold() const { return relinearizeThreshold; } + OptimizationParams getOptimizationParams() const { + return this->optimizationParams; + } + RelinearizationThreshold getRelinearizeThreshold() const { + return relinearizeThreshold; + } int getRelinearizeSkip() const { return relinearizeSkip; } bool isEnableRelinearization() const { return enableRelinearization; } bool isEvaluateNonlinearError() const { return evaluateNonlinearError; } - std::string getFactorization() const { return factorizationTranslator(factorization); } + std::string getFactorization() const { + return factorizationTranslator(factorization); + } bool isCacheLinearizedFactors() const { return cacheLinearizedFactors; } KeyFormatter getKeyFormatter() const { return keyFormatter; } bool isEnableDetailedResults() const { return enableDetailedResults; } - bool isEnablePartialRelinearizationCheck() const { return enablePartialRelinearizationCheck; } + bool isEnablePartialRelinearizationCheck() const { + return enablePartialRelinearizationCheck; + } - void setOptimizationParams(OptimizationParams optimizationParams) { this->optimizationParams = optimizationParams; } - void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) { this->relinearizeThreshold = relinearizeThreshold; } - void setRelinearizeSkip(int relinearizeSkip) { this->relinearizeSkip = relinearizeSkip; } - void setEnableRelinearization(bool enableRelinearization) { this->enableRelinearization = enableRelinearization; } - void setEvaluateNonlinearError(bool evaluateNonlinearError) { this->evaluateNonlinearError = evaluateNonlinearError; } - void setFactorization(const std::string& factorization) { this->factorization = factorizationTranslator(factorization); } - void setCacheLinearizedFactors(bool cacheLinearizedFactors) { this->cacheLinearizedFactors = cacheLinearizedFactors; } - void setKeyFormatter(KeyFormatter keyFormatter) { this->keyFormatter = keyFormatter; } - void setEnableDetailedResults(bool enableDetailedResults) { this->enableDetailedResults = enableDetailedResults; } - void setEnablePartialRelinearizationCheck(bool enablePartialRelinearizationCheck) { this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; } + void setOptimizationParams(OptimizationParams optimizationParams) { + this->optimizationParams = optimizationParams; + } + void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) { + this->relinearizeThreshold = relinearizeThreshold; + } + void setRelinearizeSkip(int relinearizeSkip) { + this->relinearizeSkip = relinearizeSkip; + } + void setEnableRelinearization(bool enableRelinearization) { + this->enableRelinearization = enableRelinearization; + } + void setEvaluateNonlinearError(bool evaluateNonlinearError) { + this->evaluateNonlinearError = evaluateNonlinearError; + } + void setFactorization(const std::string& factorization) { + this->factorization = factorizationTranslator(factorization); + } + void setCacheLinearizedFactors(bool cacheLinearizedFactors) { + this->cacheLinearizedFactors = cacheLinearizedFactors; + } + void setKeyFormatter(KeyFormatter keyFormatter) { + this->keyFormatter = keyFormatter; + } + void setEnableDetailedResults(bool enableDetailedResults) { + this->enableDetailedResults = enableDetailedResults; + } + void setEnablePartialRelinearizationCheck( + bool enablePartialRelinearizationCheck) { + this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; + } GaussianFactorGraph::Eliminate getEliminationFunction() const { return factorization == CHOLESKY - ? (GaussianFactorGraph::Eliminate)EliminatePreferCholesky - : (GaussianFactorGraph::Eliminate)EliminateQR; + ? (GaussianFactorGraph::Eliminate)EliminatePreferCholesky + : (GaussianFactorGraph::Eliminate)EliminateQR; } /// @} @@ -275,8 +385,9 @@ struct GTSAM_EXPORT ISAM2Result { * delta, as computed by ISAM2::calculateEstimate(). * \li New variables will be evaluated at their initialization points passed * into the current call to update. - * \par Note: This will only be computed if ISAM2Params::evaluateNonlinearError - * is set to \c true, because there is some cost to this computation. + * \par Note: This will only be computed if + * ISAM2Params::evaluateNonlinearError is set to \c true, because there is + * some cost to this computation. */ boost::optional errorBefore; @@ -286,8 +397,9 @@ struct GTSAM_EXPORT ISAM2Result { * variables have undergone one linear update. Variable values are * again computed by combining their linearization points with their * partial linear deltas, by ISAM2::calculateEstimate(). - * \par Note: This will only be computed if ISAM2Params::evaluateNonlinearError - * is set to \c true, because there is some cost to this computation. + * \par Note: This will only be computed if + * ISAM2Params::evaluateNonlinearError is set to \c true, because there is + * some cost to this computation. */ boost::optional errorAfter; @@ -309,7 +421,8 @@ struct GTSAM_EXPORT ISAM2Result { */ size_t variablesReeliminated; - /** The number of factors that were included in reelimination of the Bayes' tree. */ + /** The number of factors that were included in reelimination of the Bayes' + * tree. */ size_t factorsRecalculated; /** The number of cliques in the Bayes' Tree */ @@ -332,14 +445,29 @@ struct GTSAM_EXPORT ISAM2Result { * observed, new, or on the path up to the root clique from another * reeliminated variable. */ bool isReeliminated; - bool isAboveRelinThreshold; ///< Whether the variable was just relinearized due to being above the relinearization threshold - bool isRelinearizeInvolved; ///< Whether the variable was below the relinearization threshold but was relinearized by being involved in a factor with a variable above the relinearization threshold - bool isRelinearized; /// Whether the variable was relinearized, either by being above the relinearization threshold or by involvement. - bool isObserved; ///< Whether the variable was just involved in new factors - bool isNew; ///< Whether the variable itself was just added - bool inRootClique; ///< Whether the variable is in the root clique - VariableStatus(): isReeliminated(false), isAboveRelinThreshold(false), isRelinearizeInvolved(false), - isRelinearized(false), isObserved(false), isNew(false), inRootClique(false) {} + bool isAboveRelinThreshold; ///< Whether the variable was just + ///< relinearized due to being above the + ///< relinearization threshold + bool isRelinearizeInvolved; ///< Whether the variable was below the + ///< relinearization threshold but was + ///< relinearized by being involved in a + ///< factor with a variable above the + ///< relinearization threshold + bool isRelinearized; /// Whether the variable was relinearized, either by + /// being above the relinearization threshold or by + /// involvement. + bool isObserved; ///< Whether the variable was just involved in new + ///< factors + bool isNew; ///< Whether the variable itself was just added + bool inRootClique; ///< Whether the variable is in the root clique + VariableStatus() + : isReeliminated(false), + isAboveRelinThreshold(false), + isRelinearizeInvolved(false), + isRelinearized(false), + isObserved(false), + isNew(false), + inRootClique(false) {} }; /** The status of each variable during this update, see VariableStatus. @@ -351,24 +479,27 @@ struct GTSAM_EXPORT ISAM2Result { * Detail for information about the results data stored here. */ boost::optional detail; - void print(const std::string str = "") const { - std::cout << str << " Reelimintated: " << variablesReeliminated << " Relinearized: " << variablesRelinearized << " Cliques: " << cliques << std::endl; + using std::cout; + cout << str << " Reelimintated: " << variablesReeliminated + << " Relinearized: " << variablesRelinearized + << " Cliques: " << cliques << std::endl; } /** Getters and Setters */ - size_t getVariablesRelinearized() const { return variablesRelinearized; }; - size_t getVariablesReeliminated() const { return variablesReeliminated; }; - size_t getCliques() const { return cliques; }; + size_t getVariablesRelinearized() const { return variablesRelinearized; } + size_t getVariablesReeliminated() const { return variablesReeliminated; } + size_t getCliques() const { return cliques; } }; /** - * Specialized Clique structure for ISAM2, incorporating caching and gradient contribution + * Specialized Clique structure for ISAM2, incorporating caching and gradient + * contribution * TODO: more documentation */ -class GTSAM_EXPORT ISAM2Clique : public BayesTreeCliqueBase -{ -public: +class GTSAM_EXPORT ISAM2Clique + : public BayesTreeCliqueBase { + public: typedef ISAM2Clique This; typedef BayesTreeCliqueBase Base; typedef boost::shared_ptr shared_ptr; @@ -383,13 +514,16 @@ public: /// Default constructor ISAM2Clique() : Base() {} - /// Copy constructor, does *not* copy solution pointers as these are invalid in different trees. - ISAM2Clique(const ISAM2Clique& other) : - Base(other), cachedFactor_(other.cachedFactor_), gradientContribution_(other.gradientContribution_) {} + /// Copy constructor, does *not* copy solution pointers as these are invalid + /// in different trees. + ISAM2Clique(const ISAM2Clique& other) + : Base(other), + cachedFactor_(other.cachedFactor_), + gradientContribution_(other.gradientContribution_) {} - /// Assignment operator, does *not* copy solution pointers as these are invalid in different trees. - ISAM2Clique& operator=(const ISAM2Clique& other) - { + /// Assignment operator, does *not* copy solution pointers as these are + /// invalid in different trees. + ISAM2Clique& operator=(const ISAM2Clique& other) { Base::operator=(other); cachedFactor_ = other.cachedFactor_; gradientContribution_ = other.gradientContribution_; @@ -397,7 +531,8 @@ public: } /// Overridden to also store the remaining factor and gradient contribution - void setEliminationResult(const FactorGraphType::EliminationResult& eliminationResult); + void setEliminationResult( + const FactorGraphType::EliminationResult& eliminationResult); /** Access the cached factor */ Base::FactorType::shared_ptr& cachedFactor() { return cachedFactor_; } @@ -405,44 +540,45 @@ public: /** Access the gradient contribution */ const Vector& gradientContribution() const { return gradientContribution_; } - bool equals(const This& other, double tol=1e-9) const; + bool equals(const This& other, double tol = 1e-9) const; /** print this node */ - void print(const std::string& s = "", const KeyFormatter& formatter = DefaultKeyFormatter) const; - -private: + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const; + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar & BOOST_SERIALIZATION_NVP(cachedFactor_); - ar & BOOST_SERIALIZATION_NVP(gradientContribution_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar& BOOST_SERIALIZATION_NVP(cachedFactor_); + ar& BOOST_SERIALIZATION_NVP(gradientContribution_); } -}; // \struct ISAM2Clique +}; // \struct ISAM2Clique /** * @addtogroup ISAM2 - * Implementation of the full ISAM2 algorithm for incremental nonlinear optimization. + * Implementation of the full ISAM2 algorithm for incremental nonlinear + * optimization. * - * The typical cycle of using this class to create an instance by providing ISAM2Params - * to the constructor, then add measurements and variables as they arrive using the update() - * method. At any time, calculateEstimate() may be called to obtain the current - * estimate of all variables. + * The typical cycle of using this class to create an instance by providing + * ISAM2Params to the constructor, then add measurements and variables as they + * arrive using the update() method. At any time, calculateEstimate() may be + * called to obtain the current estimate of all variables. * */ -class GTSAM_EXPORT ISAM2: public BayesTree { - -protected: - +class GTSAM_EXPORT ISAM2 : public BayesTree { + protected: /** The current linearization point */ Values theta_; - /** VariableIndex lets us look up factors by involved variable and keeps track of dimensions */ + /** VariableIndex lets us look up factors by involved variable and keeps track + * of dimensions */ VariableIndex variableIndex_; - /** The linear delta from the last linear solution, an update to the estimate in theta + /** The linear delta from the last linear solution, an update to the estimate + * in theta * * This is \c mutable because it is a "cached" variable - it is not updated * until either requested with getDelta() or calculateEstimate(), or needed @@ -450,8 +586,10 @@ protected: */ mutable VectorValues delta_; - mutable VectorValues deltaNewton_; // Only used when using Dogleg - stores the Gauss-Newton update - mutable VectorValues RgProd_; // Only used when using Dogleg - stores R*g and is updated incrementally + mutable VectorValues deltaNewton_; // Only used when using Dogleg - stores + // the Gauss-Newton update + mutable VectorValues RgProd_; // Only used when using Dogleg - stores R*g and + // is updated incrementally /** A cumulative mask for the variables that were replaced and have not yet * been updated in the linear solution delta_, this is only used internally, @@ -461,9 +599,11 @@ protected: * This is \c mutable because it is used internally to not update delta_ * until it is needed. */ - mutable KeySet deltaReplacedMask_; // TODO: Make sure accessed in the right way + mutable KeySet + deltaReplacedMask_; // TODO: Make sure accessed in the right way - /** All original nonlinear factors are stored here to use during relinearization */ + /** All original nonlinear factors are stored here to use during + * relinearization */ NonlinearFactorGraph nonlinearFactors_; /** The current linear factors, which are only updated as needed */ @@ -479,20 +619,21 @@ protected: * variables and thus cannot have their linearization points changed. */ KeySet fixedVariables_; - int update_count_; ///< Counter incremented every update(), used to determine periodic relinearization + int update_count_; ///< Counter incremented every update(), used to determine + ///< periodic relinearization -public: - - typedef ISAM2 This; ///< This class - typedef BayesTree Base; ///< The BayesTree base class - typedef Base::Clique Clique; ///< A clique - typedef Base::sharedClique sharedClique; ///< Shared pointer to a clique - typedef Base::Cliques Cliques; ///< List of Clique typedef from base class + public: + typedef ISAM2 This; ///< This class + typedef BayesTree Base; ///< The BayesTree base class + typedef Base::Clique Clique; ///< A clique + typedef Base::sharedClique sharedClique; ///< Shared pointer to a clique + typedef Base::Cliques Cliques; ///< List of Clique typedef from base class /** Create an empty ISAM2 instance */ - ISAM2(const ISAM2Params& params); + explicit ISAM2(const ISAM2Params& params); - /** Create an empty ISAM2 instance using the default set of parameters (see ISAM2Params) */ + /** Create an empty ISAM2 instance using the default set of parameters (see + * ISAM2Params) */ ISAM2(); /** default virtual destructor */ @@ -513,26 +654,31 @@ public: * thresholds. * * @param newFactors The new factors to be added to the system - * @param newTheta Initialization points for new variables to be added to the system. - * You must include here all new variables occuring in newFactors (which were not already - * in the system). There must not be any variables here that do not occur in newFactors, - * and additionally, variables that were already in the system must not be included here. + * @param newTheta Initialization points for new variables to be added to the + * system. You must include here all new variables occuring in newFactors + * (which were not already in the system). There must not be any variables + * here that do not occur in newFactors, and additionally, variables that were + * already in the system must not be included here. * @param removeFactorIndices Indices of factors to remove from system - * @param force_relinearize Relinearize any variables whose delta magnitude is sufficiently - * large (Params::relinearizeThreshold), regardless of the relinearization interval - * (Params::relinearizeSkip). - * @param constrainedKeys is an optional map of keys to group labels, such that a variable can - * be constrained to a particular grouping in the BayesTree - * @param noRelinKeys is an optional set of nonlinear keys that iSAM2 will hold at a constant linearization - * point, regardless of the size of the linear delta - * @param extraReelimKeys is an optional set of nonlinear keys that iSAM2 will re-eliminate, regardless - * of the size of the linear delta. This allows the provided keys to be reordered. + * @param force_relinearize Relinearize any variables whose delta magnitude is + * sufficiently large (Params::relinearizeThreshold), regardless of the + * relinearization interval (Params::relinearizeSkip). + * @param constrainedKeys is an optional map of keys to group labels, such + * that a variable can be constrained to a particular grouping in the + * BayesTree + * @param noRelinKeys is an optional set of nonlinear keys that iSAM2 will + * hold at a constant linearization point, regardless of the size of the + * linear delta + * @param extraReelimKeys is an optional set of nonlinear keys that iSAM2 will + * re-eliminate, regardless of the size of the linear delta. This allows the + * provided keys to be reordered. * @return An ISAM2Result struct containing information about the update */ - virtual ISAM2Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), + virtual ISAM2Result update( + const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(), const FactorIndices& removeFactorIndices = FactorIndices(), - const boost::optional >& constrainedKeys = boost::none, + const boost::optional >& constrainedKeys = boost::none, const boost::optional >& noRelinKeys = boost::none, const boost::optional >& extraReelimKeys = boost::none, bool force_relinearize = false); @@ -542,48 +688,50 @@ public: * requested to be marginalized. Marginalization leaves a linear * approximation of the marginal in the system, and the linearization points * of any variables involved in this linear marginal become fixed. The set - * fixed variables will include any key involved with the marginalized variables - * in the original factors, and possibly additional ones due to fill-in. + * fixed variables will include any key involved with the marginalized + * variables in the original factors, and possibly additional ones due to + * fill-in. * - * If provided, 'marginalFactorsIndices' will be augmented with the factor graph - * indices of the marginal factors added during the 'marginalizeLeaves' call + * If provided, 'marginalFactorsIndices' will be augmented with the factor + * graph indices of the marginal factors added during the 'marginalizeLeaves' + * call * - * If provided, 'deletedFactorsIndices' will be augmented with the factor graph - * indices of any factor that was removed during the 'marginalizeLeaves' call + * If provided, 'deletedFactorsIndices' will be augmented with the factor + * graph indices of any factor that was removed during the 'marginalizeLeaves' + * call */ - void marginalizeLeaves(const FastList& leafKeys, - boost::optional marginalFactorsIndices = boost::none, - boost::optional deletedFactorsIndices = boost::none); + void marginalizeLeaves( + const FastList& leafKeys, + boost::optional marginalFactorsIndices = boost::none, + boost::optional deletedFactorsIndices = boost::none); /// Access the current linearization point - const Values& getLinearizationPoint() const { - return theta_; - } + const Values& getLinearizationPoint() const { return theta_; } /// Check whether variable with given key exists in linearization point - bool valueExists(Key key) const { - return theta_.exists(key); - } + bool valueExists(Key key) const { return theta_.exists(key); } - /** Compute an estimate from the incomplete linear delta computed during the last update. - * This delta is incomplete because it was not updated below wildfire_threshold. If only - * a single variable is needed, it is faster to call calculateEstimate(const KEY&). + /** Compute an estimate from the incomplete linear delta computed during the + * last update. This delta is incomplete because it was not updated below + * wildfire_threshold. If only a single variable is needed, it is faster to + * call calculateEstimate(const KEY&). */ Values calculateEstimate() const; - /** Compute an estimate for a single variable using its incomplete linear delta computed - * during the last update. This is faster than calling the no-argument version of - * calculateEstimate, which operates on all variables. + /** Compute an estimate for a single variable using its incomplete linear + * delta computed during the last update. This is faster than calling the + * no-argument version of calculateEstimate, which operates on all variables. * @param key * @return */ - template + template VALUE calculateEstimate(Key key) const; - /** Compute an estimate for a single variable using its incomplete linear delta computed - * during the last update. This is faster than calling the no-argument version of - * calculateEstimate, which operates on all variables. This is a non-templated version - * that returns a Value base class for use with the MATLAB wrapper. + /** Compute an estimate for a single variable using its incomplete linear + * delta computed during the last update. This is faster than calling the + * no-argument version of calculateEstimate, which operates on all variables. + * This is a non-templated version that returns a Value base class for use + * with the MATLAB wrapper. * @param key * @return */ @@ -598,7 +746,8 @@ public: /** Internal implementation functions */ struct Impl; - /** Compute an estimate using a complete delta computed by a full back-substitution. + /** Compute an estimate using a complete delta computed by a full + * back-substitution. */ Values calculateBestEstimate() const; @@ -609,7 +758,9 @@ public: double error(const VectorValues& x) const; /** Access the set of nonlinear factors */ - const NonlinearFactorGraph& getFactorsUnsafe() const { return nonlinearFactors_; } + const NonlinearFactorGraph& getFactorsUnsafe() const { + return nonlinearFactors_; + } /** Access the nonlinear variable index */ const VariableIndex& getVariableIndex() const { return variableIndex_; } @@ -628,31 +779,36 @@ public: /** prints out clique statistics */ void printStats() const { getCliqueData().getStats().print(); } - - /** Compute the gradient of the energy function, \f$ \nabla_{x=0} \left\Vert \Sigma^{-1} R x - d - * \right\Vert^2 \f$, centered around zero. The gradient about zero is \f$ -R^T d \f$. See also - * gradient(const GaussianBayesNet&, const VectorValues&). + + /** Compute the gradient of the energy function, \f$ \nabla_{x=0} \left\Vert + * \Sigma^{-1} R x - d \right\Vert^2 \f$, centered around zero. The gradient + * about zero is \f$ -R^T d \f$. See also gradient(const GaussianBayesNet&, + * const VectorValues&). * * @return A VectorValues storing the gradient. */ VectorValues gradientAtZero() const; - + /// @} -protected: - + protected: FastSet getAffectedFactors(const FastList& keys) const; - GaussianFactorGraph::shared_ptr relinearizeAffectedFactors(const FastList& affectedKeys, const KeySet& relinKeys) const; - GaussianFactorGraph getCachedBoundaryFactors(Cliques& orphans); + GaussianFactorGraph::shared_ptr relinearizeAffectedFactors( + const FastList& affectedKeys, const KeySet& relinKeys) const; + GaussianFactorGraph getCachedBoundaryFactors(const Cliques& orphans); - virtual boost::shared_ptr recalculate(const KeySet& markedKeys, const KeySet& relinKeys, - const std::vector& observedKeys, const KeySet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result); + virtual boost::shared_ptr recalculate( + const KeySet& markedKeys, const KeySet& relinKeys, + const std::vector& observedKeys, const KeySet& unusedIndices, + const boost::optional >& constrainKeys, + ISAM2Result& result); void updateDelta(bool forceFullSolve = false) const; -}; // ISAM2 +}; // ISAM2 /// traits -template<> struct traits : public Testable {}; +template <> +struct traits : public Testable {}; /// Optimize the BayesTree, starting from the root. /// @param replaced Needs to contain @@ -665,19 +821,21 @@ template<> struct traits : public Testable {}; /// and recursive backsubstitution might eventually stop if none of the changed /// variables are contained in the subtree. /// @return The number of variables that were solved for -template -size_t optimizeWildfire(const boost::shared_ptr& root, - double threshold, const KeySet& replaced, VectorValues& delta); +template +size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, + const KeySet& replaced, VectorValues& delta); -template +template size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, - double threshold, const KeySet& replaced, VectorValues& delta); + double threshold, const KeySet& replaced, + VectorValues& delta); -/// calculate the number of non-zero entries for the tree starting at clique (use root for complete matrix) -template +/// calculate the number of non-zero entries for the tree starting at clique +/// (use root for complete matrix) +template int calculate_nnz(const boost::shared_ptr& clique); -} /// namespace gtsam +} // namespace gtsam -#include #include +#include From 315ea79e2119c913c0ab773807dfd17375a2c0d2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 00:06:31 -0400 Subject: [PATCH 051/197] Ignore VS code .env file --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index b62617d21..2682a6748 100644 --- a/.gitignore +++ b/.gitignore @@ -16,3 +16,4 @@ cython/gtsam.pyx cython/gtsam.so cython/gtsam_wrapper.pxd .vscode +.env From 05d5179bc399ab86eaa40b0fe1c8b2d0f0bbc3f4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 17:31:46 -0400 Subject: [PATCH 052/197] Some more cleanup --- examples/ISAM2Example_SmartFactor.cpp | 31 ++++++++++++++++----------- 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/examples/ISAM2Example_SmartFactor.cpp b/examples/ISAM2Example_SmartFactor.cpp index 77e29b8ff..8331ade04 100644 --- a/examples/ISAM2Example_SmartFactor.cpp +++ b/examples/ISAM2Example_SmartFactor.cpp @@ -5,11 +5,10 @@ */ #include +#include #include #include -#include - #include #include @@ -56,27 +55,32 @@ int main(int argc, char* argv[]) { vector poses = {pose1, pose2, pose3, pose4, pose5}; - SmartFactor::shared_ptr smartFactor(new SmartFactor(measurementNoise, K)); - graph.push_back(smartFactor); - + // Add first pose graph.emplace_shared>(X(0), poses[0], noise); initialEstimate.insert(X(0), poses[0].compose(delta)); - smartFactor->add(PinholePose(poses[0], K).project(point), X(0)); + // Create smart factor with measurement from first pose only + SmartFactor::shared_ptr smartFactor(new SmartFactor(measurementNoise, K)); + smartFactor->add(PinholePose(poses[0], K).project(point), X(0)); + graph.push_back(smartFactor); + + // loop over remaining poses for (size_t i = 1; i < 5; i++) { cout << "****************************************************" << endl; cout << "i = " << i << endl; - // Add measurement to smart factor - PinholePose camera(poses[i], K); - Point2 measurement = camera.project(point); - smartFactor->add(measurement, X(i)); - cout << "Measurement " << i << "" << measurement << endl; - // Add prior on new pose graph.emplace_shared>(X(i), poses[i], noise); initialEstimate.insert(X(i), poses[i].compose(delta)); + // "Simulate" measurement from this pose + PinholePose camera(poses[i], K); + Point2 measurement = camera.project(point); + cout << "Measurement " << i << "" << measurement << endl; + + // Add measurement to smart factor + smartFactor->add(measurement, X(i)); + // Update iSAM2 ISAM2Result result = isam.update(graph, initialEstimate); result.print(); @@ -84,7 +88,8 @@ int main(int argc, char* argv[]) { cout << "Detailed results:" << endl; for (auto keyedStatus : result.detail->variableStatus) { const auto& status = keyedStatus.second; - cout << keyedStatus.first << " {" << endl; + PrintKey(keyedStatus.first); + cout << " {" << endl; cout << "reeliminated: " << status.isReeliminated << endl; cout << "relinearized above thresh: " << status.isAboveRelinThreshold << endl; From a31294d7778934d51f6e5ff1e389edf210e57236 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 29 Sep 2018 17:52:20 -0400 Subject: [PATCH 053/197] Modernized, cleaned up, and turned off non-recursive version (fow now) because it has a bug. --- gtsam/nonlinear/ISAM2-impl.cpp | 317 +++++---- gtsam/nonlinear/ISAM2-impl.h | 11 +- gtsam/nonlinear/ISAM2-inl.h | 287 +------- gtsam/nonlinear/ISAM2.cpp | 1149 +++++++++++++++++++++----------- gtsam/nonlinear/ISAM2.h | 78 ++- tests/testGaussianISAM2.cpp | 2 +- 6 files changed, 1011 insertions(+), 833 deletions(-) diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index 3b5156535..aa201138c 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -11,33 +11,35 @@ /** * @file ISAM2-impl.cpp - * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization. + * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid + * relinearization. * @author Michael Kaess * @author Richard Roberts */ -#include -#include // for selective linearization thresholds #include -#include // for GTSAM_USE_TBB +#include // for GTSAM_USE_TBB +#include // for selective linearization thresholds +#include -#include #include +#include +#include +#include using namespace std; namespace gtsam { /* ************************************************************************* */ -void ISAM2::Impl::AddVariables( - const Values& newTheta, Values& theta, VectorValues& delta, - VectorValues& deltaNewton, VectorValues& RgProd, - const KeyFormatter& keyFormatter) -{ +void ISAM2::Impl::AddVariables(const Values& newTheta, Values& theta, + VectorValues& delta, VectorValues& deltaNewton, + VectorValues& RgProd, + const KeyFormatter& keyFormatter) { const bool debug = ISDEBUG("ISAM2 AddVariables"); theta.insert(newTheta); - if(debug) newTheta.print("The new variables are: "); + if (debug) newTheta.print("The new variables are: "); // Add zeros into the VectorValues delta.insert(newTheta.zeroVectors()); deltaNewton.insert(newTheta.zeroVectors()); @@ -45,55 +47,55 @@ void ISAM2::Impl::AddVariables( } /* ************************************************************************* */ -void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors, bool useUnusedSlots, - NonlinearFactorGraph& nonlinearFactors, FactorIndices& newFactorIndices) -{ +void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors, + bool useUnusedSlots, + NonlinearFactorGraph& nonlinearFactors, + FactorIndices& newFactorIndices) { newFactorIndices.resize(newFactors.size()); - if(useUnusedSlots) - { + if (useUnusedSlots) { size_t globalFactorIndex = 0; - for(size_t newFactorIndex = 0; newFactorIndex < newFactors.size(); ++newFactorIndex) - { + for (size_t newFactorIndex = 0; newFactorIndex < newFactors.size(); + ++newFactorIndex) { // Loop to find the next available factor slot - do - { - // If we need to add more factors than we have room for, resize nonlinearFactors, - // filling the new slots with NULL factors. Otherwise, check if the current - // factor in nonlinearFactors is already used, and if so, increase - // globalFactorIndex. If the current factor in nonlinearFactors is unused, break - // out of the loop and use the current slot. - if(globalFactorIndex >= nonlinearFactors.size()) - nonlinearFactors.resize(nonlinearFactors.size() + newFactors.size() - newFactorIndex); - else if(nonlinearFactors[globalFactorIndex]) - ++ globalFactorIndex; + do { + // If we need to add more factors than we have room for, resize + // nonlinearFactors, filling the new slots with NULL factors. Otherwise, + // check if the current factor in nonlinearFactors is already used, and + // if so, increase globalFactorIndex. If the current factor in + // nonlinearFactors is unused, break out of the loop and use the current + // slot. + if (globalFactorIndex >= nonlinearFactors.size()) + nonlinearFactors.resize(nonlinearFactors.size() + newFactors.size() - + newFactorIndex); + else if (nonlinearFactors[globalFactorIndex]) + ++globalFactorIndex; else break; - } while(true); + } while (true); // Use the current slot, updating nonlinearFactors and newFactorSlots. nonlinearFactors[globalFactorIndex] = newFactors[newFactorIndex]; newFactorIndices[newFactorIndex] = globalFactorIndex; } - } - else - { + } else { // We're not looking for unused slots, so just add the factors at the end. - for(size_t i = 0; i < newFactors.size(); ++i) + for (size_t i = 0; i < newFactors.size(); ++i) newFactorIndices[i] = i + nonlinearFactors.size(); nonlinearFactors.push_back(newFactors); } } /* ************************************************************************* */ -void ISAM2::Impl::RemoveVariables(const KeySet& unusedKeys, const FastVector& roots, +void ISAM2::Impl::RemoveVariables(const KeySet& unusedKeys, + const FastVector& roots, Values& theta, VariableIndex& variableIndex, - VectorValues& delta, VectorValues& deltaNewton, VectorValues& RgProd, - KeySet& replacedKeys, Base::Nodes& nodes, - KeySet& fixedVariables) -{ + VectorValues& delta, + VectorValues& deltaNewton, + VectorValues& RgProd, KeySet& replacedKeys, + Base::Nodes& nodes, KeySet& fixedVariables) { variableIndex.removeUnusedVariables(unusedKeys.begin(), unusedKeys.end()); - for(Key key: unusedKeys) { + for (Key key : unusedKeys) { delta.erase(key); deltaNewton.erase(key); RgProd.erase(key); @@ -105,26 +107,28 @@ void ISAM2::Impl::RemoveVariables(const KeySet& unusedKeys, const FastVector(&relinearizeThreshold)) - { - for(const VectorValues::KeyValuePair& key_delta: delta) { + if (const double* threshold = boost::get(&relinearizeThreshold)) { + for (const VectorValues::KeyValuePair& key_delta : delta) { double maxDelta = key_delta.second.lpNorm(); - if(maxDelta >= *threshold) - relinKeys.insert(key_delta.first); + if (maxDelta >= *threshold) relinKeys.insert(key_delta.first); } - } - else if(const FastMap* thresholds = boost::get >(&relinearizeThreshold)) - { - for(const VectorValues::KeyValuePair& key_delta: delta) { - const Vector& threshold = thresholds->find(Symbol(key_delta.first).chr())->second; - if(threshold.rows() != key_delta.second.rows()) - throw std::invalid_argument("Relinearization threshold vector dimensionality for '" + std::string(1, Symbol(key_delta.first).chr()) + "' passed into iSAM2 parameters does not match actual variable dimensionality."); - if((key_delta.second.array().abs() > threshold.array()).any()) + } else if (const FastMap* thresholds = + boost::get >(&relinearizeThreshold)) { + for (const VectorValues::KeyValuePair& key_delta : delta) { + const Vector& threshold = + thresholds->find(Symbol(key_delta.first).chr())->second; + if (threshold.rows() != key_delta.second.rows()) + throw std::invalid_argument( + "Relinearization threshold vector dimensionality for '" + + std::string(1, Symbol(key_delta.first).chr()) + + "' passed into iSAM2 parameters does not match actual variable " + "dimensionality."); + if ((key_delta.second.array().abs() > threshold.array()).any()) relinKeys.insert(key_delta.first); } } @@ -133,81 +137,86 @@ KeySet ISAM2::Impl::CheckRelinearizationFull(const VectorValues& delta, } /* ************************************************************************* */ -void CheckRelinearizationRecursiveDouble(KeySet& relinKeys, double threshold, - const VectorValues& delta, const ISAM2Clique::shared_ptr& clique) -{ +static void CheckRelinearizationRecursiveDouble( + double threshold, const VectorValues& delta, + const ISAM2::sharedClique& clique, KeySet* relinKeys) { // Check the current clique for relinearization bool relinearize = false; - for(Key var: *clique->conditional()) { + for (Key var : *clique->conditional()) { double maxDelta = delta[var].lpNorm(); - if(maxDelta >= threshold) { - relinKeys.insert(var); + if (maxDelta >= threshold) { + relinKeys->insert(var); relinearize = true; } } // If this node was relinearized, also check its children - if(relinearize) { - for(const ISAM2Clique::shared_ptr& child: clique->children) { - CheckRelinearizationRecursiveDouble(relinKeys, threshold, delta, child); + if (relinearize) { + for (const ISAM2::sharedClique& child : clique->children) { + CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys); } } } /* ************************************************************************* */ -void CheckRelinearizationRecursiveMap(KeySet& relinKeys, const FastMap& thresholds, - const VectorValues& delta, - const ISAM2Clique::shared_ptr& clique) -{ +static void CheckRelinearizationRecursiveMap( + const FastMap& thresholds, const VectorValues& delta, + const ISAM2::sharedClique& clique, KeySet* relinKeys) { // Check the current clique for relinearization bool relinearize = false; - for(Key var: *clique->conditional()) { + for (Key var : *clique->conditional()) { // Find the threshold for this variable type const Vector& threshold = thresholds.find(Symbol(var).chr())->second; const Vector& deltaVar = delta[var]; // Verify the threshold vector matches the actual variable size - if(threshold.rows() != deltaVar.rows()) - throw std::invalid_argument("Relinearization threshold vector dimensionality for '" + std::string(1, Symbol(var).chr()) + "' passed into iSAM2 parameters does not match actual variable dimensionality."); + if (threshold.rows() != deltaVar.rows()) + throw std::invalid_argument( + "Relinearization threshold vector dimensionality for '" + + std::string(1, Symbol(var).chr()) + + "' passed into iSAM2 parameters does not match actual variable " + "dimensionality."); // Check for relinearization - if((deltaVar.array().abs() > threshold.array()).any()) { - relinKeys.insert(var); + if ((deltaVar.array().abs() > threshold.array()).any()) { + relinKeys->insert(var); relinearize = true; } } // If this node was relinearized, also check its children - if(relinearize) { - for(const ISAM2Clique::shared_ptr& child: clique->children) { - CheckRelinearizationRecursiveMap(relinKeys, thresholds, delta, child); + if (relinearize) { + for (const ISAM2::sharedClique& child : clique->children) { + CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys); } } } /* ************************************************************************* */ -KeySet ISAM2::Impl::CheckRelinearizationPartial(const FastVector& roots, - const VectorValues& delta, - const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) -{ +KeySet ISAM2::Impl::CheckRelinearizationPartial( + const FastVector& roots, const VectorValues& delta, + const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) { KeySet relinKeys; - for(const ISAM2::sharedClique& root: roots) { - if(relinearizeThreshold.type() == typeid(double)) - CheckRelinearizationRecursiveDouble(relinKeys, boost::get(relinearizeThreshold), delta, root); - else if(relinearizeThreshold.type() == typeid(FastMap)) - CheckRelinearizationRecursiveMap(relinKeys, boost::get >(relinearizeThreshold), delta, root); + for (const ISAM2::sharedClique& root : roots) { + if (relinearizeThreshold.type() == typeid(double)) + CheckRelinearizationRecursiveDouble( + boost::get(relinearizeThreshold), delta, root, &relinKeys); + else if (relinearizeThreshold.type() == typeid(FastMap)) + CheckRelinearizationRecursiveMap( + boost::get >(relinearizeThreshold), delta, root, + &relinKeys); } return relinKeys; } /* ************************************************************************* */ -void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, KeySet& keys, const KeySet& markedMask) -{ +void ISAM2::Impl::FindAll(ISAM2::sharedClique clique, KeySet& keys, + const KeySet& markedMask) { static const bool debug = false; // does the separator contain any of the variables? bool found = false; - for(Key key: clique->conditional()->parents()) { + for (Key key : clique->conditional()->parents()) { if (markedMask.exists(key)) { found = true; break; @@ -215,19 +224,22 @@ void ISAM2::Impl::FindAll(ISAM2Clique::shared_ptr clique, KeySet& keys, const Ke } if (found) { // then add this clique - keys.insert(clique->conditional()->beginFrontals(), clique->conditional()->endFrontals()); - if(debug) clique->print("Key(s) marked in clique "); - if(debug) cout << "so marking key " << clique->conditional()->front() << endl; + keys.insert(clique->conditional()->beginFrontals(), + clique->conditional()->endFrontals()); + if (debug) clique->print("Key(s) marked in clique "); + if (debug) + cout << "so marking key " << clique->conditional()->front() << endl; } - for(const ISAM2Clique::shared_ptr& child: clique->children) { + for (const ISAM2::sharedClique& child : clique->children) { FindAll(child, keys, markedMask); } } /* ************************************************************************* */ -void ISAM2::Impl::ExpmapMasked(Values& values, const VectorValues& delta, - const KeySet& mask, boost::optional invalidateIfDebug, const KeyFormatter& keyFormatter) -{ +void ISAM2::Impl::ExpmapMasked(const VectorValues& delta, const KeySet& mask, + Values* values, + boost::optional invalidateIfDebug, + const KeyFormatter& keyFormatter) { // If debugging, invalidate if requested, otherwise do not invalidate. // Invalidating means setting expmapped entries to Inf, to trigger assertions // if we try to re-use them. @@ -235,65 +247,70 @@ void ISAM2::Impl::ExpmapMasked(Values& values, const VectorValues& delta, invalidateIfDebug = boost::none; #endif - assert(values.size() == delta.size()); + assert(values->size() == delta.size()); Values::iterator key_value; VectorValues::const_iterator key_delta; #ifdef GTSAM_USE_TBB - for(key_value = values.begin(); key_value != values.end(); ++key_value) - { + for (key_value = values->begin(); key_value != values->end(); ++key_value) { key_delta = delta.find(key_value->key); #else - for(key_value = values.begin(), key_delta = delta.begin(); key_value != values.end(); ++key_value, ++key_delta) - { + for (key_value = values->begin(), key_delta = delta.begin(); + key_value != values->end(); ++key_value, ++key_delta) { assert(key_value->key == key_delta->first); #endif Key var = key_value->key; - assert(delta[var].size() == (int)key_value->value.dim()); + assert(static_cast(delta[var].size()) == key_value->value.dim()); assert(delta[var].allFinite()); - if(mask.exists(var)) { + if (mask.exists(var)) { Value* retracted = key_value->value.retract_(delta[var]); key_value->value = *retracted; retracted->deallocate_(); - if(invalidateIfDebug) - (*invalidateIfDebug)[var].operator=(Vector::Constant(delta[var].rows(), numeric_limits::infinity())); // Strange syntax to work with clang++ (bug in clang?) + if (invalidateIfDebug) + (*invalidateIfDebug)[var].operator=(Vector::Constant( + delta[var].rows(), + numeric_limits::infinity())); // Strange syntax to work + // with clang++ (bug in + // clang?) } } } /* ************************************************************************* */ namespace internal { -inline static void optimizeInPlace(const boost::shared_ptr& clique, VectorValues& result) { +inline static void optimizeInPlace(const ISAM2::sharedClique& clique, + VectorValues* result) { // parents are assumed to already be solved and available in result - result.update(clique->conditional()->solve(result)); + result->update(clique->conditional()->solve(*result)); // starting from the root, call optimize on each conditional - for(const boost::shared_ptr& child: clique->children) + for (const ISAM2::sharedClique& child : clique->children) optimizeInPlace(child, result); } -} +} // namespace internal /* ************************************************************************* */ -size_t ISAM2::Impl::UpdateGaussNewtonDelta(const FastVector& roots, - const KeySet& replacedKeys, VectorValues& delta, double wildfireThreshold) { - +size_t ISAM2::Impl::UpdateGaussNewtonDelta( + const FastVector& roots, const KeySet& replacedKeys, + double wildfireThreshold, VectorValues* delta) { size_t lastBacksubVariableCount; if (wildfireThreshold <= 0.0) { // Threshold is zero or less, so do a full recalculation - for(const ISAM2::sharedClique& root: roots) + for (const ISAM2::sharedClique& root : roots) internal::optimizeInPlace(root, delta); - lastBacksubVariableCount = delta.size(); + lastBacksubVariableCount = delta->size(); } else { // Optimize with wildfire lastBacksubVariableCount = 0; - for(const ISAM2::sharedClique& root: roots) - lastBacksubVariableCount += optimizeWildfireNonRecursive( - root, wildfireThreshold, replacedKeys, delta); // modifies delta + for (const ISAM2::sharedClique& root : roots) + lastBacksubVariableCount += optimizeWildfire( + root, wildfireThreshold, replacedKeys, delta); // modifies delta #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) - for (VectorValues::const_iterator key_delta = delta.begin(); key_delta != delta.end(); ++key_delta) { - assert(delta[key_delta->first].allFinite()); + for (VectorValues::const_iterator key_delta = delta->begin(); + key_delta != delta->end(); ++key_delta) { + assert((*delta)[key_delta->first].allFinite()); } #endif } @@ -303,69 +320,77 @@ size_t ISAM2::Impl::UpdateGaussNewtonDelta(const FastVector /* ************************************************************************* */ namespace internal { -void updateRgProd(const boost::shared_ptr& clique, const KeySet& replacedKeys, - const VectorValues& grad, VectorValues& RgProd, size_t& varsUpdated) { - +void updateRgProd(const ISAM2::sharedClique& clique, const KeySet& replacedKeys, + const VectorValues& grad, VectorValues* RgProd, + size_t* varsUpdated) { // Check if any frontal or separator keys were recalculated, if so, we need // update deltas and recurse to children, but if not, we do not need to // recurse further because of the running separator property. bool anyReplaced = false; - for(Key j: *clique->conditional()) { - if(replacedKeys.exists(j)) { + for (Key j : *clique->conditional()) { + if (replacedKeys.exists(j)) { anyReplaced = true; break; } } - if(anyReplaced) { + if (anyReplaced) { // Update the current variable // Get VectorValues slice corresponding to current variables - Vector gR = grad.vector(FastVector(clique->conditional()->beginFrontals(), clique->conditional()->endFrontals())); - Vector gS = grad.vector(FastVector(clique->conditional()->beginParents(), clique->conditional()->endParents())); + Vector gR = + grad.vector(FastVector(clique->conditional()->beginFrontals(), + clique->conditional()->endFrontals())); + Vector gS = + grad.vector(FastVector(clique->conditional()->beginParents(), + clique->conditional()->endParents())); // Compute R*g and S*g for this clique - Vector RSgProd = clique->conditional()->get_R() * gR + clique->conditional()->get_S() * gS; + Vector RSgProd = clique->conditional()->get_R() * gR + + clique->conditional()->get_S() * gS; // Write into RgProd vector DenseIndex vectorPosition = 0; - for(Key frontal: clique->conditional()->frontals()) { - Vector& RgProdValue = RgProd[frontal]; + for (Key frontal : clique->conditional()->frontals()) { + Vector& RgProdValue = (*RgProd)[frontal]; RgProdValue = RSgProd.segment(vectorPosition, RgProdValue.size()); vectorPosition += RgProdValue.size(); } - // Now solve the part of the Newton's method point for this clique (back-substitution) - //(*clique)->solveInPlace(deltaNewton); + // Now solve the part of the Newton's method point for this clique + // (back-substitution) + // (*clique)->solveInPlace(deltaNewton); - varsUpdated += clique->conditional()->nrFrontals(); + *varsUpdated += clique->conditional()->nrFrontals(); // Recurse to children - for(const ISAM2Clique::shared_ptr& child: clique->children) { - updateRgProd(child, replacedKeys, grad, RgProd, varsUpdated); } + for (const ISAM2::sharedClique& child : clique->children) { + updateRgProd(child, replacedKeys, grad, RgProd, varsUpdated); + } } } -} +} // namespace internal /* ************************************************************************* */ -size_t ISAM2::Impl::UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys, - const VectorValues& gradAtZero, VectorValues& RgProd) { - +size_t ISAM2::Impl::UpdateRgProd(const ISAM2::Roots& roots, + const KeySet& replacedKeys, + const VectorValues& gradAtZero, + VectorValues* RgProd) { // Update variables size_t varsUpdated = 0; - for(const ISAM2::sharedClique& root: roots) { - internal::updateRgProd(root, replacedKeys, gradAtZero, RgProd, varsUpdated); + for (const ISAM2::sharedClique& root : roots) { + internal::updateRgProd(root, replacedKeys, gradAtZero, RgProd, + &varsUpdated); } return varsUpdated; } - + /* ************************************************************************* */ VectorValues ISAM2::Impl::ComputeGradientSearch(const VectorValues& gradAtZero, - const VectorValues& RgProd) -{ + const VectorValues& RgProd) { // Compute gradient squared-magnitude const double gradientSqNorm = gradAtZero.dot(gradAtZero); - + // Compute minimizing step size double RgNormSq = RgProd.vector().squaredNorm(); double step = -gradientSqNorm / RgNormSq; @@ -374,4 +399,4 @@ VectorValues ISAM2::Impl::ComputeGradientSearch(const VectorValues& gradAtZero, return step * gradAtZero; } -} +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2-impl.h b/gtsam/nonlinear/ISAM2-impl.h index 161932344..0e05ab453 100644 --- a/gtsam/nonlinear/ISAM2-impl.h +++ b/gtsam/nonlinear/ISAM2-impl.h @@ -108,18 +108,17 @@ struct GTSAM_EXPORT ISAM2::Impl { /** * Apply expmap to the given values, but only for indices appearing in * \c markedRelinMask. Values are expmapped in-place. - * \param [in, out] values The value to expmap in-place * \param delta The linear delta with which to expmap - * \param ordering The ordering * \param mask Mask on linear indices, only \c true entries are expmapped + * \param [in, out] values The value to expmap in-place * \param invalidateIfDebug If this is true, *and* NDEBUG is not defined, * expmapped deltas will be set to an invalid value (infinity) to catch bugs * where we might expmap something twice, or expmap it but then not * recalculate its delta. * @param keyFormatter Formatter for printing nonlinear keys during debugging */ - static void ExpmapMasked(Values& values, const VectorValues& delta, - const KeySet& mask, + static void ExpmapMasked( + const VectorValues& delta, const KeySet& mask, Values* values, boost::optional invalidateIfDebug = boost::none, const KeyFormatter& keyFormatter = DefaultKeyFormatter); @@ -127,14 +126,14 @@ struct GTSAM_EXPORT ISAM2::Impl { * Update the Newton's method step point, using wildfire */ static size_t UpdateGaussNewtonDelta(const FastVector& roots, - const KeySet& replacedKeys, VectorValues& delta, double wildfireThreshold); + const KeySet& replacedKeys, double wildfireThreshold, VectorValues* delta); /** * Update the RgProd (R*g) incrementally taking into account which variables * have been recalculated in \c replacedKeys. Only used in Dogleg. */ static size_t UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys, - const VectorValues& gradAtZero, VectorValues& RgProd); + const VectorValues& gradAtZero, VectorValues* RgProd); /** * Compute the gradient-search point. Only used in Dogleg. diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h index fecefd2a5..fb63dc428 100644 --- a/gtsam/nonlinear/ISAM2-inl.h +++ b/gtsam/nonlinear/ISAM2-inl.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -11,301 +11,24 @@ /** * @file ISAM2-inl.h - * @brief + * @brief * @author Richard Roberts * @date Mar 16, 2012 */ - #pragma once -#include -#include -#include +#include namespace gtsam { /* ************************************************************************* */ -template +template VALUE ISAM2::calculateEstimate(Key key) const { const Vector& delta = getDelta()[key]; return traits::Retract(theta_.at(key), delta); } /* ************************************************************************* */ -namespace internal { -template -void optimizeWildfire(const boost::shared_ptr& clique, double threshold, - KeySet& changed, const KeySet& replaced, VectorValues& delta, size_t& count) -{ - // if none of the variables in this clique (frontal and separator!) changed - // significantly, then by the running intersection property, none of the - // cliques in the children need to be processed - - // Are any clique variables part of the tree that has been redone? - bool cliqueReplaced = replaced.exists((*clique)->frontals().front()); -#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) - for(Key frontal: clique->conditional()->frontals()) { - assert(cliqueReplaced == replaced.exists(frontal)); - } -#endif - - // If not redone, then has one of the separator variables changed significantly? - bool recalculate = cliqueReplaced; - if(!recalculate) { - for(Key parent: clique->conditional()->parents()) { - if(changed.exists(parent)) { - recalculate = true; - break; - } - } - } - - // Solve clique if it was replaced, or if any parents were changed above the - // threshold or themselves replaced. - if(recalculate) { - - // Temporary copy of the original values, to check how much they change - FastVector originalValues(clique->conditional()->nrFrontals()); - GaussianConditional::const_iterator it; - for(it = clique->conditional()->beginFrontals(); it!=clique->conditional()->endFrontals(); it++) { - originalValues[it - clique->conditional()->beginFrontals()] = delta[*it]; - } - - // Back-substitute - delta.update(clique->conditional()->solve(delta)); - count += clique->conditional()->nrFrontals(); - - // Whether the values changed above a threshold, or always true if the - // clique was replaced. - bool valuesChanged = cliqueReplaced; - for(it = clique->conditional()->beginFrontals(); it != clique->conditional()->endFrontals(); it++) { - if(!valuesChanged) { - const Vector& oldValue(originalValues[it - clique->conditional()->beginFrontals()]); - const Vector& newValue(delta[*it]); - if((oldValue - newValue).lpNorm() >= threshold) { - valuesChanged = true; - break; - } - } else - break; - } - - // If the values were above the threshold or this clique was replaced - if(valuesChanged) { - // Set changed flag for each frontal variable and leave the new values - for(Key frontal: clique->conditional()->frontals()) { - changed.insert(frontal); - } - } else { - // Replace with the old values - for(it = clique->conditional()->beginFrontals(); it != clique->conditional()->endFrontals(); it++) { - delta[*it] = originalValues[it - clique->conditional()->beginFrontals()]; - } - } - - // Recurse to children - for(const typename CLIQUE::shared_ptr& child: clique->children) { - optimizeWildfire(child, threshold, changed, replaced, delta, count); - } - } -} - -template -bool optimizeWildfireNode(const boost::shared_ptr& clique, double threshold, - KeySet& changed, const KeySet& replaced, VectorValues& delta, size_t& count) -{ - // if none of the variables in this clique (frontal and separator!) changed - // significantly, then by the running intersection property, none of the - // cliques in the children need to be processed - - // Are any clique variables part of the tree that has been redone? - bool cliqueReplaced = replaced.exists(clique->conditional()->frontals().front()); -#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) - for(Key frontal: clique->conditional()->frontals()) { - assert(cliqueReplaced == replaced.exists(frontal)); - } -#endif - - // If not redone, then has one of the separator variables changed significantly? - bool recalculate = cliqueReplaced; - if(!recalculate) { - for(Key parent: clique->conditional()->parents()) { - if(changed.exists(parent)) { - recalculate = true; - break; - } - } - } - - // Solve clique if it was replaced, or if any parents were changed above the - // threshold or themselves replaced. - // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, potentially refactor - if(recalculate) - { - // Temporary copy of the original values, to check how much they change - FastVector originalValues(clique->conditional()->nrFrontals()); - GaussianConditional::const_iterator it; - for(it = clique->conditional()->beginFrontals(); it != clique->conditional()->endFrontals(); it++) { - originalValues[it - clique->conditional()->beginFrontals()] = delta[*it]; - } - - // Back-substitute - special version stores solution pointers in cliques for fast access. - { - // Create solution part pointers if necessary and possible - necessary if solnPointers_ is - // empty, and possible if either we're a root, or we have a parent with valid solnPointers_. - boost::shared_ptr parent = clique->parent_.lock(); - if(clique->solnPointers_.empty() && (clique->isRoot() || !parent->solnPointers_.empty())) - { - for(Key key: clique->conditional()->frontals()) - clique->solnPointers_.insert(std::make_pair(key, delta.find(key))); - for(Key key: clique->conditional()->parents()) - clique->solnPointers_.insert(std::make_pair(key, parent->solnPointers_.at(key))); - } - - // See if we can use solution part pointers - we can if they either already existed or were - // created above. - if(!clique->solnPointers_.empty()) - { - GaussianConditional& c = *clique->conditional(); - // Solve matrix - Vector xS; - { - // Count dimensions of vector - DenseIndex dim = 0; - FastVector parentPointers; - parentPointers.reserve(clique->conditional()->nrParents()); - for(Key parent: clique->conditional()->parents()) { - parentPointers.push_back(clique->solnPointers_.at(parent)); - dim += parentPointers.back()->second.size(); - } - - // Fill parent vector - xS.resize(dim); - DenseIndex vectorPos = 0; - for(const VectorValues::const_iterator& parentPointer: parentPointers) { - const Vector& parentVector = parentPointer->second; - xS.block(vectorPos,0,parentVector.size(),1) = parentVector.block(0,0,parentVector.size(),1); - vectorPos += parentVector.size(); - } - } - - // NOTE(gareth): We can no longer write: xS = b - S * xS - // This is because Eigen (as of 3.3) no longer evaluates S * xS into - // a temporary, and the operation trashes valus in xS. - // See: http://eigen.tuxfamily.org/index.php?title=3.3 - const Vector rhs = c.getb() - c.get_S() * xS; - const Vector solution = c.get_R().triangularView().solve(rhs); - - // Check for indeterminant solution - if(solution.hasNaN()) throw IndeterminantLinearSystemException(c.keys().front()); - - // Insert solution into a VectorValues - DenseIndex vectorPosition = 0; - for(GaussianConditional::const_iterator frontal = c.beginFrontals(); frontal != c.endFrontals(); ++frontal) { - clique->solnPointers_.at(*frontal)->second = solution.segment(vectorPosition, c.getDim(frontal)); - vectorPosition += c.getDim(frontal); - } - } - else - { - // Just call plain solve because we couldn't use solution pointers. - delta.update(clique->conditional()->solve(delta)); - } - } - count += clique->conditional()->nrFrontals(); - - // Whether the values changed above a threshold, or always true if the - // clique was replaced. - bool valuesChanged = cliqueReplaced; - for(it = clique->conditional()->beginFrontals(); it != clique->conditional()->endFrontals(); it++) { - if(!valuesChanged) { - const Vector& oldValue(originalValues[it - clique->conditional()->beginFrontals()]); - const Vector& newValue(delta[*it]); - if((oldValue - newValue).lpNorm() >= threshold) { - valuesChanged = true; - break; - } - } else - break; - } - - // If the values were above the threshold or this clique was replaced - if(valuesChanged) { - // Set changed flag for each frontal variable and leave the new values - for(Key frontal: clique->conditional()->frontals()) { - changed.insert(frontal); - } - } else { - // Replace with the old values - for(it = clique->conditional()->beginFrontals(); it != clique->conditional()->endFrontals(); it++) { - delta[*it] = originalValues[it - clique->conditional()->beginFrontals()]; - } - } - } - - return recalculate; -} - -} // namespace internal - -/* ************************************************************************* */ -template -size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, const KeySet& keys, VectorValues& delta) { - KeySet changed; - int count = 0; - // starting from the root, call optimize on each conditional - if(root) - internal::optimizeWildfire(root, threshold, changed, keys, delta, count); - return count; -} - -/* ************************************************************************* */ -template -size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, double threshold, const KeySet& keys, VectorValues& delta) -{ - KeySet changed; - size_t count = 0; - - if (root) { - std::stack > travStack; - travStack.push(root); - boost::shared_ptr currentNode = root; - while (!travStack.empty()) { - currentNode = travStack.top(); - travStack.pop(); - bool recalculate = internal::optimizeWildfireNode(currentNode, threshold, changed, keys, delta, count); - if (recalculate) { - for(const typename CLIQUE::shared_ptr& child: currentNode->children) { - travStack.push(child); - } - } - } - } - - return count; -} - -/* ************************************************************************* */ -template -void nnz_internal(const boost::shared_ptr& clique, int& result) { - int dimR = (int)clique->conditional()->rows(); - int dimSep = (int)clique->conditional()->get_S().cols(); - result += ((dimR+1)*dimR)/2 + dimSep*dimR; - // traverse the children - for(const typename CLIQUE::shared_ptr& child: clique->children) { - nnz_internal(child, result); - } -} - -/* ************************************************************************* */ -template -int calculate_nnz(const boost::shared_ptr& clique) { - int result = 0; - // starting from the root, add up entries of frontal and conditional matrices of each conditional - nnz_internal(clique, result); - return result; -} - -} +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index d4df01a68..bdd6b42bb 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -11,31 +11,41 @@ /** * @file ISAM2-inl.h - * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization. + * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid + * relinearization. * @author Michael Kaess, Richard Roberts */ -#include // for operator += +#include + +#include +#include +#include +#include + +#include // for operator += using namespace boost::assign; +#include #include #include -#include -namespace br { using namespace boost::range; using namespace boost::adaptors; } +namespace br { +using namespace boost::range; +using namespace boost::adaptors; +} // namespace br -#include #include +#include #include #include -#include // We need the inst file because we'll make a special JT templated on ISAM2 -#include -#include -#include +#include // We need the inst file because we'll make a special JT templated on ISAM2 #include +#include +#include +#include -#include #include -#include #include +#include using namespace std; @@ -49,11 +59,10 @@ static const bool disableReordering = false; static const double batchThreshold = 0.65; /* ************************************************************************* */ -// Special BayesTree class that uses ISAM2 cliques - this is the result of reeliminating ISAM2 -// subtrees. -class ISAM2BayesTree : public ISAM2::Base -{ -public: +// Special BayesTree class that uses ISAM2 cliques - this is the result of +// reeliminating ISAM2 subtrees. +class ISAM2BayesTree : public ISAM2::Base { + public: typedef ISAM2::Base Base; typedef ISAM2BayesTree This; typedef boost::shared_ptr shared_ptr; @@ -62,43 +71,58 @@ public: }; /* ************************************************************************* */ -// Special JunctionTree class that produces ISAM2 BayesTree cliques, used for reeliminating ISAM2 -// subtrees. -class ISAM2JunctionTree : public JunctionTree -{ -public: +// Special JunctionTree class that produces ISAM2 BayesTree cliques, used for +// reeliminating ISAM2 subtrees. +class ISAM2JunctionTree + : public JunctionTree { + public: typedef JunctionTree Base; typedef ISAM2JunctionTree This; typedef boost::shared_ptr shared_ptr; - ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree) : - Base(eliminationTree) {} + ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree) + : Base(eliminationTree) {} }; /* ************************************************************************* */ -std::string ISAM2DoglegParams::adaptationModeTranslator(const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) const { +std::string ISAM2DoglegParams::adaptationModeTranslator( + const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) + const { std::string s; switch (adaptationMode) { - case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: s = "SEARCH_EACH_ITERATION"; break; - case DoglegOptimizerImpl::ONE_STEP_PER_ITERATION: s = "ONE_STEP_PER_ITERATION"; break; - default: s = "UNDEFINED"; break; + case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: + s = "SEARCH_EACH_ITERATION"; + break; + case DoglegOptimizerImpl::ONE_STEP_PER_ITERATION: + s = "ONE_STEP_PER_ITERATION"; + break; + default: + s = "UNDEFINED"; + break; } return s; } /* ************************************************************************* */ -DoglegOptimizerImpl::TrustRegionAdaptationMode ISAM2DoglegParams::adaptationModeTranslator(const std::string& adaptationMode) const { - std::string s = adaptationMode; boost::algorithm::to_upper(s); - if (s == "SEARCH_EACH_ITERATION") return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; - if (s == "ONE_STEP_PER_ITERATION") return DoglegOptimizerImpl::ONE_STEP_PER_ITERATION; +DoglegOptimizerImpl::TrustRegionAdaptationMode +ISAM2DoglegParams::adaptationModeTranslator( + const std::string& adaptationMode) const { + std::string s = adaptationMode; + boost::algorithm::to_upper(s); + if (s == "SEARCH_EACH_ITERATION") + return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; + if (s == "ONE_STEP_PER_ITERATION") + return DoglegOptimizerImpl::ONE_STEP_PER_ITERATION; /* default is SEARCH_EACH_ITERATION */ return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; } /* ************************************************************************* */ -ISAM2Params::Factorization ISAM2Params::factorizationTranslator(const std::string& str) { - std::string s = str; boost::algorithm::to_upper(s); +ISAM2Params::Factorization ISAM2Params::factorizationTranslator( + const std::string& str) { + std::string s = str; + boost::algorithm::to_upper(s); if (s == "QR") return ISAM2Params::QR; if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; @@ -107,84 +131,347 @@ ISAM2Params::Factorization ISAM2Params::factorizationTranslator(const std::strin } /* ************************************************************************* */ -std::string ISAM2Params::factorizationTranslator(const ISAM2Params::Factorization& value) { +std::string ISAM2Params::factorizationTranslator( + const ISAM2Params::Factorization& value) { std::string s; switch (value) { - case ISAM2Params::QR: s = "QR"; break; - case ISAM2Params::CHOLESKY: s = "CHOLESKY"; break; - default: s = "UNDEFINED"; break; + case ISAM2Params::QR: + s = "QR"; + break; + case ISAM2Params::CHOLESKY: + s = "CHOLESKY"; + break; + default: + s = "UNDEFINED"; + break; } return s; } /* ************************************************************************* */ -void ISAM2Clique::setEliminationResult(const FactorGraphType::EliminationResult& eliminationResult) -{ +void ISAM2Clique::setEliminationResult( + const FactorGraphType::EliminationResult& eliminationResult) { conditional_ = eliminationResult.first; cachedFactor_ = eliminationResult.second; // Compute gradient contribution gradientContribution_.resize(conditional_->cols() - 1); - // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed reasons - gradientContribution_ << -conditional_->get_R().transpose() * conditional_->get_d(), - -conditional_->get_S().transpose() * conditional_->get_d(); + // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed + // reasons + gradientContribution_ << -conditional_->get_R().transpose() * + conditional_->get_d(), + -conditional_->get_S().transpose() * conditional_->get_d(); } /* ************************************************************************* */ bool ISAM2Clique::equals(const This& other, double tol) const { return Base::equals(other) && - ((!cachedFactor_ && !other.cachedFactor_) - || (cachedFactor_ && other.cachedFactor_ - && cachedFactor_->equals(*other.cachedFactor_, tol))); + ((!cachedFactor_ && !other.cachedFactor_) || + (cachedFactor_ && other.cachedFactor_ && + cachedFactor_->equals(*other.cachedFactor_, tol))); } /* ************************************************************************* */ -void ISAM2Clique::print(const std::string& s, const KeyFormatter& formatter) const -{ - Base::print(s,formatter); - if(cachedFactor_) +void ISAM2Clique::print(const std::string& s, + const KeyFormatter& formatter) const { + Base::print(s, formatter); + if (cachedFactor_) cachedFactor_->print(s + "Cached: ", formatter); else std::cout << s << "Cached empty" << std::endl; - if(gradientContribution_.rows() != 0) + if (gradientContribution_.rows() != 0) gtsam::print(gradientContribution_, "Gradient contribution: "); } /* ************************************************************************* */ -ISAM2::ISAM2(const ISAM2Params& params): params_(params), update_count_(0) { - if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) - doglegDelta_ = boost::get(params_.optimizationParams).initialDelta; +bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { + // if none of the variables in this clique (frontal and separator!) changed + // significantly, then by the running intersection property, none of the + // cliques in the children need to be processed + + // Are any clique variables part of the tree that has been redone? + bool dirty = replaced.exists(conditional_->frontals().front()); +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) + for (Key frontal : conditional_->frontals()) { + assert(dirty == replaced.exists(frontal)); + } +#endif + + // If not, then has one of the separator variables changed significantly? + if (!dirty) { + for (Key parent : conditional_->parents()) { + if (changed.exists(parent)) { + dirty = true; + break; + } + } + } + return dirty; +} +/* ************************************************************************* */ +FastVector ISAM2Clique::copyRelevantValues( + const VectorValues& delta) const { + FastVector values; + values.reserve(conditional_->nrFrontals()); + for (Key frontal : conditional_->frontals()) { + values.push_back(delta[frontal]); + } + return values; +} + +/* ************************************************************************* */ +bool ISAM2Clique::valuesChanged(const KeySet& replaced, + const FastVector& originalValues, + const VectorValues& delta, + double threshold) const { + if (replaced.exists(conditional_->frontals().front())) return true; + size_t i = 0; + for (Key frontal : conditional_->frontals()) { + const Vector diff = originalValues[i++] - delta[frontal]; + if (diff.lpNorm() >= threshold) { + return true; + } + } + return false; +} + +/* ************************************************************************* */ +/// Set changed flag for each frontal variable +void ISAM2Clique::markFrontalsAsChanged(KeySet* changed) const { + for (Key frontal : conditional_->frontals()) { + changed->insert(frontal); + } +} + +/* ************************************************************************* */ +void ISAM2Clique::restoreFromOriginals(const FastVector& originalValues, + VectorValues* delta) const { + size_t i = 0; + for (Key frontal : conditional_->frontals()) { + delta->at(frontal) = originalValues[i++]; + } +} + +/* ************************************************************************* */ +void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const { + if (isDirty(replaced, *changed)) { + // Temporary copy of the original values, to check how much they change + auto originalValues = copyRelevantValues(*delta); + + // Back-substitute + delta->update(conditional_->solve(*delta)); + count += conditional_->nrFrontals(); + + if (valuesChanged(replaced, originalValues, *delta, threshold)) { + markFrontalsAsChanged(changed); + } else { + restoreFromOriginals(originalValues, delta); + } + + // Recurse to children + for (const auto& child : children) { + child->optimizeWildfire(replaced, threshold, changed, delta, count); + } + } +} + +/* ************************************************************************* */ +bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const { + // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, + // potentially refactor + bool dirty = isDirty(replaced, *changed); + if (dirty) { + // Temporary copy of the original values, to check how much they change + auto originalValues = copyRelevantValues(*delta); + + // Back-substitute - special version stores solution pointers in cliques for + // fast access. + { + // Create solution part pointers if necessary and possible - necessary if + // solnPointers_ is empty, and possible if either we're a root, or we have + // a parent with valid solnPointers_. + ISAM2::sharedClique parent = parent_.lock(); + if (solnPointers_.empty() && + (isRoot() || !parent->solnPointers_.empty())) { + for (Key frontal : conditional_->frontals()) + solnPointers_.emplace(frontal, delta->find(frontal)); + for (Key parentKey : conditional_->parents()) { + assert(parent->solnPointers_.exists(parentKey)); + solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey)); + } + } + + // See if we can use solution part pointers - we can if they either + // already existed or were created above. + if (!solnPointers_.empty()) { + GaussianConditional& c = *conditional_; + // Solve matrix + Vector xS; + { + // Count dimensions of vector + DenseIndex dim = 0; + FastVector parentPointers; + parentPointers.reserve(conditional_->nrParents()); + for (Key parent : conditional_->parents()) { + parentPointers.push_back(solnPointers_.at(parent)); + dim += parentPointers.back()->second.size(); + } + + // Fill parent vector + xS.resize(dim); + DenseIndex vectorPos = 0; + for (const VectorValues::const_iterator& parentPointer : + parentPointers) { + const Vector& parentVector = parentPointer->second; + xS.block(vectorPos, 0, parentVector.size(), 1) = + parentVector.block(0, 0, parentVector.size(), 1); + vectorPos += parentVector.size(); + } + } + + // NOTE(gareth): We can no longer write: xS = b - S * xS + // This is because Eigen (as of 3.3) no longer evaluates S * xS into + // a temporary, and the operation trashes valus in xS. + // See: http://eigen.tuxfamily.org/index.php?title=3.3 + const Vector rhs = c.getb() - c.get_S() * xS; + const Vector solution = + c.get_R().triangularView().solve(rhs); + + // Check for indeterminant solution + if (solution.hasNaN()) + throw IndeterminantLinearSystemException(c.keys().front()); + + // Insert solution into a VectorValues + DenseIndex vectorPosition = 0; + for (GaussianConditional::const_iterator frontal = c.beginFrontals(); + frontal != c.endFrontals(); ++frontal) { + solnPointers_.at(*frontal)->second = + solution.segment(vectorPosition, c.getDim(frontal)); + vectorPosition += c.getDim(frontal); + } + } else { + // Just call plain solve because we couldn't use solution pointers. + delta->update(conditional_->solve(*delta)); + } + } + count += conditional_->nrFrontals(); + + if (valuesChanged(replaced, originalValues, *delta, threshold)) { + markFrontalsAsChanged(changed); + } else { + restoreFromOriginals(originalValues, delta); + } + } + + return dirty; +} + +/* ************************************************************************* */ +void ISAM2Clique::nnz_internal(size_t* result) const { + size_t dimR = conditional_->rows(); + size_t dimSep = conditional_->get_S().cols(); + *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR; + // traverse the children + for (const auto& child : children) { + child->nnz_internal(result); + } +} + +/* ************************************************************************* */ +size_t ISAM2Clique::calculate_nnz() const { + size_t result = 0; + nnz_internal(&result); + return result; +} + +/* ************************************************************************* */ +size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, + const KeySet& keys, VectorValues* delta) { + KeySet changed; + size_t count = 0; + // starting from the root, call optimize on each conditional + if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count); + return count; +} + +/* ************************************************************************* */ +// This version is non-recursive version, but seems to have +// a bug, as was diagnosed with ISAM2Example_SmartFactor. Disabled for now. +size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, + double threshold, const KeySet& keys, + VectorValues* delta) { + KeySet changed; + size_t count = 0; + + if (root) { + std::stack travStack; + travStack.push(root); + ISAM2::sharedClique currentNode = root; + while (!travStack.empty()) { + currentNode = travStack.top(); + travStack.pop(); + bool dirty = currentNode->optimizeWildfireNode(keys, threshold, &changed, + delta, &count); + if (dirty) { + for (const auto& child : currentNode->children) { + travStack.push(child); + } + } + } + } + + return count; +} + +/* ************************************************************************* */ +ISAM2::ISAM2(const ISAM2Params& params) : params_(params), update_count_(0) { + if (params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) + doglegDelta_ = + boost::get(params_.optimizationParams).initialDelta; } /* ************************************************************************* */ ISAM2::ISAM2() : update_count_(0) { - if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) - doglegDelta_ = boost::get(params_.optimizationParams).initialDelta; + if (params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) + doglegDelta_ = + boost::get(params_.optimizationParams).initialDelta; } /* ************************************************************************* */ bool ISAM2::equals(const ISAM2& other, double tol) const { - return Base::equals(other, tol) - && theta_.equals(other.theta_, tol) && variableIndex_.equals(other.variableIndex_, tol) - && nonlinearFactors_.equals(other.nonlinearFactors_, tol) - && fixedVariables_ == other.fixedVariables_; + return Base::equals(other, tol) && theta_.equals(other.theta_, tol) && + variableIndex_.equals(other.variableIndex_, tol) && + nonlinearFactors_.equals(other.nonlinearFactors_, tol) && + fixedVariables_ == other.fixedVariables_; } /* ************************************************************************* */ KeySet ISAM2::getAffectedFactors(const KeyList& keys) const { static const bool debug = false; - if(debug) cout << "Getting affected factors for "; - if(debug) { for(const Key key: keys) { cout << key << " "; } } - if(debug) cout << endl; + if (debug) cout << "Getting affected factors for "; + if (debug) { + for (const Key key : keys) { + cout << key << " "; + } + } + if (debug) cout << endl; NonlinearFactorGraph allAffected; KeySet indices; - for(const Key key: keys) { + for (const Key key : keys) { const VariableIndex::Factors& factors(variableIndex_[key]); indices.insert(factors.begin(), factors.end()); } - if(debug) cout << "Affected factors are: "; - if(debug) { for(const size_t index: indices) { cout << index << " "; } } - if(debug) cout << endl; + if (debug) cout << "Affected factors are: "; + if (debug) { + for (const size_t index : indices) { + cout << index << " "; + } + } + if (debug) cout << endl; return indices; } @@ -192,9 +479,8 @@ KeySet ISAM2::getAffectedFactors(const KeyList& keys) const { // retrieve all factors that ONLY contain the affected variables // (note that the remaining stuff is summarized in the cached factors) -GaussianFactorGraph::shared_ptr -ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const KeySet& relinKeys) const -{ +GaussianFactorGraph::shared_ptr ISAM2::relinearizeAffectedFactors( + const FastList& affectedKeys, const KeySet& relinKeys) const { gttic(getAffectedFactors); KeySet candidates = getAffectedFactors(affectedKeys); gttoc(getAffectedFactors); @@ -208,29 +494,31 @@ ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const KeySe gttoc(affectedKeysSet); gttic(check_candidates_and_linearize); - GaussianFactorGraph::shared_ptr linearized = boost::make_shared(); - for(Key idx: candidates) { + GaussianFactorGraph::shared_ptr linearized = + boost::make_shared(); + for (Key idx : candidates) { bool inside = true; bool useCachedLinear = params_.cacheLinearizedFactors; - for(Key key: nonlinearFactors_[idx]->keys()) { - if(affectedKeysSet.find(key) == affectedKeysSet.end()) { + for (Key key : nonlinearFactors_[idx]->keys()) { + if (affectedKeysSet.find(key) == affectedKeysSet.end()) { inside = false; break; } - if(useCachedLinear && relinKeys.find(key) != relinKeys.end()) + if (useCachedLinear && relinKeys.find(key) != relinKeys.end()) useCachedLinear = false; } - if(inside) { - if(useCachedLinear) { + if (inside) { + if (useCachedLinear) { #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS assert(linearFactors_[idx]); assert(linearFactors_[idx]->keys() == nonlinearFactors_[idx]->keys()); #endif linearized->push_back(linearFactors_[idx]); } else { - GaussianFactor::shared_ptr linearFactor = nonlinearFactors_[idx]->linearize(theta_); + GaussianFactor::shared_ptr linearFactor = + nonlinearFactors_[idx]->linearize(theta_); linearized->push_back(linearFactor); - if(params_.cacheLinearizedFactors) { + if (params_.cacheLinearizedFactors) { #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS assert(linearFactors_[idx]->keys() == linearFactor->keys()); #endif @@ -245,12 +533,13 @@ ISAM2::relinearizeAffectedFactors(const FastList& affectedKeys, const KeySe } /* ************************************************************************* */ -// find intermediate (linearized) factors from cache that are passed into the affected area +// find intermediate (linearized) factors from cache that are passed into the +// affected area GaussianFactorGraph ISAM2::getCachedBoundaryFactors(const Cliques& orphans) { GaussianFactorGraph cachedBoundary; - for(sharedClique orphan: orphans) { + for (sharedClique orphan : orphans) { // retrieve the cached factor and add to boundary cachedBoundary.push_back(orphan->cachedFactor()); } @@ -259,27 +548,27 @@ GaussianFactorGraph ISAM2::getCachedBoundaryFactors(const Cliques& orphans) { } /* ************************************************************************* */ -boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const KeySet& relinKeys, - const vector& observedKeys, - const KeySet& unusedIndices, - const boost::optional >& constrainKeys, - ISAM2Result& result) -{ - // TODO: new factors are linearized twice, the newFactors passed in are not used. +boost::shared_ptr ISAM2::recalculate( + const KeySet& markedKeys, const KeySet& relinKeys, + const vector& observedKeys, const KeySet& unusedIndices, + const boost::optional >& constrainKeys, + ISAM2Result& result) { + // TODO(dellaert): new factors are linearized twice, + // the newFactors passed in are not used. const bool debug = ISDEBUG("ISAM2 recalculate"); // Input: BayesTree(this), newFactors -//#define PRINT_STATS // figures for paper, disable for timing +// figures for paper, disable for timing #ifdef PRINT_STATS static int counter = 0; int maxClique = 0; double avgClique = 0; int numCliques = 0; int nnzR = 0; - if (counter>0) { // cannot call on empty tree - GaussianISAM2_P::CliqueData cdata = this->getCliqueData(); + if (counter > 0) { // cannot call on empty tree + GaussianISAM2_P::CliqueData cdata = this->getCliqueData(); GaussianISAM2_P::CliqueStats cstats = cdata.getStats(); maxClique = cstats.maxCONDITIONALSize; avgClique = cstats.avgCONDITIONALSize; @@ -289,81 +578,89 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke counter++; #endif - if(debug) { + if (debug) { cout << "markedKeys: "; - for(const Key key: markedKeys) { cout << key << " "; } + for (const Key key : markedKeys) { + cout << key << " "; + } cout << endl; cout << "observedKeys: "; - for(const Key key: observedKeys) { cout << key << " "; } + for (const Key key : observedKeys) { + cout << key << " "; + } cout << endl; } // 1. Remove top of Bayes tree and convert to a factor graph: - // (a) For each affected variable, remove the corresponding clique and all parents up to the root. - // (b) Store orphaned sub-trees \BayesTree_{O} of removed cliques. + // (a) For each affected variable, remove the corresponding clique and all + // parents up to the root. (b) Store orphaned sub-trees \BayesTree_{O} of + // removed cliques. gttic(removetop); Cliques orphans; GaussianBayesNet affectedBayesNet; - this->removeTop(FastVector(markedKeys.begin(), markedKeys.end()), affectedBayesNet, orphans); + this->removeTop(FastVector(markedKeys.begin(), markedKeys.end()), + affectedBayesNet, orphans); gttoc(removetop); // FactorGraph factors(affectedBayesNet); - // bug was here: we cannot reuse the original factors, because then the cached factors get messed up - // [all the necessary data is actually contained in the affectedBayesNet, including what was passed in from the boundaries, - // so this would be correct; however, in the process we also generate new cached_ entries that will be wrong (ie. they don't - // contain what would be passed up at a certain point if batch elimination was done, but that's what we need); we could choose - // not to update cached_ from here, but then the new information (and potentially different variable ordering) is not reflected - // in the cached_ values which again will be wrong] - // so instead we have to retrieve the original linearized factors AND add the cached factors from the boundary + // bug was here: we cannot reuse the original factors, because then the cached + // factors get messed up [all the necessary data is actually contained in the + // affectedBayesNet, including what was passed in from the boundaries, + // so this would be correct; however, in the process we also generate new + // cached_ entries that will be wrong (ie. they don't contain what would be + // passed up at a certain point if batch elimination was done, but that's + // what we need); we could choose not to update cached_ from here, but then + // the new information (and potentially different variable ordering) is not + // reflected in the cached_ values which again will be wrong] + // so instead we have to retrieve the original linearized factors AND add the + // cached factors from the boundary // BEGIN OF COPIED CODE - // ordering provides all keys in conditionals, there cannot be others because path to root included + // ordering provides all keys in conditionals, there cannot be others because + // path to root included gttic(affectedKeys); FastList affectedKeys; - for(const ConditionalType::shared_ptr& conditional: affectedBayesNet) - affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(), conditional->endFrontals()); + for (const ConditionalType::shared_ptr& conditional : affectedBayesNet) + affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(), + conditional->endFrontals()); gttoc(affectedKeys); - boost::shared_ptr affectedKeysSet(new KeySet()); // Will return this result + boost::shared_ptr affectedKeysSet( + new KeySet()); // Will return this result - if(affectedKeys.size() >= theta_.size() * batchThreshold) - { + if (affectedKeys.size() >= theta_.size() * batchThreshold) { // Do a batch step - reorder and relinearize all variables gttic(batch); gttic(add_keys); - br::copy(variableIndex_ | br::map_keys, std::inserter(*affectedKeysSet, affectedKeysSet->end())); + br::copy(variableIndex_ | br::map_keys, + std::inserter(*affectedKeysSet, affectedKeysSet->end())); // Removed unused keys: VariableIndex affectedFactorsVarIndex = variableIndex_; - affectedFactorsVarIndex.removeUnusedVariables(unusedIndices.begin(), unusedIndices.end()); + affectedFactorsVarIndex.removeUnusedVariables(unusedIndices.begin(), + unusedIndices.end()); - for (const Key key: unusedIndices) - { + for (const Key key : unusedIndices) { affectedKeysSet->erase(key); } gttoc(add_keys); gttic(ordering); Ordering order; - if(constrainKeys) - { - order = Ordering::ColamdConstrained(affectedFactorsVarIndex, *constrainKeys); - } - else - { - if(theta_.size() > observedKeys.size()) - { + if (constrainKeys) { + order = + Ordering::ColamdConstrained(affectedFactorsVarIndex, *constrainKeys); + } else { + if (theta_.size() > observedKeys.size()) { // Only if some variables are unconstrained FastMap constraintGroups; - for(Key var: observedKeys) - constraintGroups[var] = 1; - order = Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups); - } - else - { + for (Key var : observedKeys) constraintGroups[var] = 1; + order = Ordering::ColamdConstrained(affectedFactorsVarIndex, + constraintGroups); + } else { order = Ordering::Colamd(affectedFactorsVarIndex); } } @@ -371,18 +668,21 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke gttic(linearize); GaussianFactorGraph linearized = *nonlinearFactors_.linearize(theta_); - if(params_.cacheLinearizedFactors) - linearFactors_ = linearized; + if (params_.cacheLinearizedFactors) linearFactors_ = linearized; gttoc(linearize); gttic(eliminate); - ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree(linearized, affectedFactorsVarIndex, order)) - .eliminate(params_.getEliminationFunction()).first; + ISAM2BayesTree::shared_ptr bayesTree = + ISAM2JunctionTree( + GaussianEliminationTree(linearized, affectedFactorsVarIndex, order)) + .eliminate(params_.getEliminationFunction()) + .first; gttoc(eliminate); gttic(insert); this->clear(); - this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), bayesTree->roots().end()); + this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), + bayesTree->roots().end()); this->nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end()); gttoc(insert); @@ -394,8 +694,8 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke lastAffectedFactorCount = linearized.size(); // Reeliminated keys for detailed results - if(params_.enableDetailedResults) { - for(Key key: theta_.keys()) { + if (params_.enableDetailedResults) { + for (Key key : theta_.keys()) { result.detail->variableStatus[key].isReeliminated = true; } } @@ -403,23 +703,31 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke gttoc(batch); } else { - gttic(incremental); // 2. Add the new factors \Factors' into the resulting factor graph FastList affectedAndNewKeys; - affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(), affectedKeys.end()); - affectedAndNewKeys.insert(affectedAndNewKeys.end(), observedKeys.begin(), observedKeys.end()); + affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(), + affectedKeys.end()); + affectedAndNewKeys.insert(affectedAndNewKeys.end(), observedKeys.begin(), + observedKeys.end()); gttic(relinearizeAffected); - GaussianFactorGraph factors(*relinearizeAffectedFactors(affectedAndNewKeys, relinKeys)); - if(debug) factors.print("Relinearized factors: "); + GaussianFactorGraph factors( + *relinearizeAffectedFactors(affectedAndNewKeys, relinKeys)); + if (debug) factors.print("Relinearized factors: "); gttoc(relinearizeAffected); - if(debug) { cout << "Affected keys: "; for(const Key key: affectedKeys) { cout << key << " "; } cout << endl; } + if (debug) { + cout << "Affected keys: "; + for (const Key key : affectedKeys) { + cout << key << " "; + } + cout << endl; + } // Reeliminated keys for detailed results - if(params_.enableDetailedResults) { - for(Key key: affectedAndNewKeys) { + if (params_.enableDetailedResults) { + for (Key key : affectedAndNewKeys) { result.detail->variableStatus[key].isReeliminated = true; } } @@ -432,34 +740,38 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke #ifdef PRINT_STATS // output for generating figures - cout << "linear: #markedKeys: " << markedKeys.size() << " #affectedVariables: " << affectedKeys.size() - << " #affectedFactors: " << factors.size() << " maxCliqueSize: " << maxClique - << " avgCliqueSize: " << avgClique << " #Cliques: " << numCliques << " nnzR: " << nnzR << endl; + cout << "linear: #markedKeys: " << markedKeys.size() + << " #affectedVariables: " << affectedKeys.size() + << " #affectedFactors: " << factors.size() + << " maxCliqueSize: " << maxClique << " avgCliqueSize: " << avgClique + << " #Cliques: " << numCliques << " nnzR: " << nnzR << endl; #endif gttic(cached); // add the cached intermediate results from the boundary of the orphans ... GaussianFactorGraph cachedBoundary = getCachedBoundaryFactors(orphans); - if(debug) cachedBoundary.print("Boundary factors: "); + if (debug) cachedBoundary.print("Boundary factors: "); factors.push_back(cachedBoundary); gttoc(cached); gttic(orphans); // Add the orphaned subtrees - for(const sharedClique& orphan: orphans) + for (const sharedClique& orphan : orphans) factors += boost::make_shared >(orphan); gttoc(orphans); - // END OF COPIED CODE - // 3. Re-order and eliminate the factor graph into a Bayes net (Algorithm [alg:eliminate]), and re-assemble into a new Bayes tree (Algorithm [alg:BayesTree]) + // 3. Re-order and eliminate the factor graph into a Bayes net (Algorithm + // [alg:eliminate]), and re-assemble into a new Bayes tree (Algorithm + // [alg:BayesTree]) gttic(reorder_and_eliminate); gttic(list_to_set); // create a partial reordering for the new and contaminated factors - // markedKeys are passed in: those variables will be forced to the end in the ordering + // markedKeys are passed in: those variables will be forced to the end in + // the ordering affectedKeysSet->insert(markedKeys.begin(), markedKeys.end()); affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end()); gttoc(list_to_set); @@ -468,37 +780,46 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke gttic(ordering_constraints); // Create ordering constraints - FastMap constraintGroups; - if(constrainKeys) { + FastMap constraintGroups; + if (constrainKeys) { constraintGroups = *constrainKeys; } else { - constraintGroups = FastMap(); - const int group = observedKeys.size() < affectedFactorsVarIndex.size() ? 1 : 0; - for (Key var: observedKeys) + constraintGroups = FastMap(); + const int group = + observedKeys.size() < affectedFactorsVarIndex.size() ? 1 : 0; + for (Key var : observedKeys) constraintGroups.insert(make_pair(var, group)); } // Remove unaffected keys from the constraints - for(FastMap::iterator iter = constraintGroups.begin(); iter != constraintGroups.end(); /*Incremented in loop ++iter*/) { - if(unusedIndices.exists(iter->first) || !affectedKeysSet->exists(iter->first)) - constraintGroups.erase(iter ++); + for (FastMap::iterator iter = constraintGroups.begin(); + iter != constraintGroups.end(); + /*Incremented in loop ++iter*/) { + if (unusedIndices.exists(iter->first) || + !affectedKeysSet->exists(iter->first)) + constraintGroups.erase(iter++); else - ++ iter; + ++iter; } gttoc(ordering_constraints); // Generate ordering gttic(Ordering); - Ordering ordering = Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups); + Ordering ordering = + Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups); gttoc(Ordering); - ISAM2BayesTree::shared_ptr bayesTree = ISAM2JunctionTree(GaussianEliminationTree( - factors, affectedFactorsVarIndex, ordering)).eliminate(params_.getEliminationFunction()).first; + ISAM2BayesTree::shared_ptr bayesTree = + ISAM2JunctionTree( + GaussianEliminationTree(factors, affectedFactorsVarIndex, ordering)) + .eliminate(params_.getEliminationFunction()) + .first; gttoc(reorder_and_eliminate); gttic(reassemble); - this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), bayesTree->roots().end()); + this->roots_.insert(this->roots_.end(), bayesTree->roots().begin(), + bayesTree->roots().end()); this->nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end()); gttoc(reassemble); @@ -508,9 +829,9 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke } // Root clique variables for detailed results - if(params_.enableDetailedResults) { - for(const sharedNode& root: this->roots()) - for(Key var: *root->conditional()) + if (params_.enableDetailedResults) { + for (const sharedNode& root : this->roots()) + for (Key var : *root->conditional()) result.detail->variableStatus[var].inRootClique = true; } @@ -519,11 +840,12 @@ boost::shared_ptr ISAM2::recalculate(const KeySet& markedKeys, const Ke /* ************************************************************************* */ ISAM2Result ISAM2::update( - const NonlinearFactorGraph& newFactors, const Values& newTheta, const FactorIndices& removeFactorIndices, - const boost::optional >& constrainedKeys, const boost::optional >& noRelinKeys, - const boost::optional >& extraReelimKeys, bool force_relinearize) -{ - + const NonlinearFactorGraph& newFactors, const Values& newTheta, + const FactorIndices& removeFactorIndices, + const boost::optional >& constrainedKeys, + const boost::optional >& noRelinKeys, + const boost::optional >& extraReelimKeys, + bool force_relinearize) { const bool debug = ISDEBUG("ISAM2 update"); const bool verbose = ISDEBUG("ISAM2 update verbose"); @@ -538,18 +860,19 @@ ISAM2Result ISAM2::update( lastBacksubVariableCount = 0; lastNnzTop = 0; ISAM2Result result; - if(params_.enableDetailedResults) + if (params_.enableDetailedResults) result.detail = ISAM2Result::DetailedResults(); - const bool relinearizeThisStep = force_relinearize - || (params_.enableRelinearization && update_count_ % params_.relinearizeSkip == 0); + const bool relinearizeThisStep = + force_relinearize || (params_.enableRelinearization && + update_count_ % params_.relinearizeSkip == 0); - if(verbose) { + if (verbose) { cout << "ISAM2::update\n"; this->print("ISAM2: "); } // Update delta if we need it to check relinearization later - if(relinearizeThisStep) { + if (relinearizeThisStep) { gttic(updateDelta); updateDelta(disableReordering); gttoc(updateDelta); @@ -558,20 +881,23 @@ ISAM2Result ISAM2::update( gttic(push_back_factors); // 1. Add any new factors \Factors:=\Factors\cup\Factors'. // Add the new factor indices to the result struct - if(debug || verbose) newFactors.print("The new factors are: "); - Impl::AddFactorsStep1(newFactors, params_.findUnusedFactorSlots, nonlinearFactors_, result.newFactorsIndices); + if (debug || verbose) newFactors.print("The new factors are: "); + Impl::AddFactorsStep1(newFactors, params_.findUnusedFactorSlots, + nonlinearFactors_, result.newFactorsIndices); // Remove the removed factors - NonlinearFactorGraph removeFactors; removeFactors.reserve(removeFactorIndices.size()); - for(size_t index: removeFactorIndices) { + NonlinearFactorGraph removeFactors; + removeFactors.reserve(removeFactorIndices.size()); + for (size_t index : removeFactorIndices) { removeFactors.push_back(nonlinearFactors_[index]); nonlinearFactors_.remove(index); - if(params_.cacheLinearizedFactors) - linearFactors_.remove(index); + if (params_.cacheLinearizedFactors) linearFactors_.remove(index); } - // Remove removed factors from the variable index so we do not attempt to relinearize them - variableIndex_.remove(removeFactorIndices.begin(), removeFactorIndices.end(), removeFactors); + // Remove removed factors from the variable index so we do not attempt to + // relinearize them + variableIndex_.remove(removeFactorIndices.begin(), removeFactorIndices.end(), + removeFactors); // Compute unused keys and indices KeySet unusedKeys; @@ -580,123 +906,145 @@ ISAM2Result ISAM2::update( // Get keys from removed factors and new factors, and compute unused keys, // i.e., keys that are empty now and do not appear in the new factors. KeySet removedAndEmpty; - for(Key key: removeFactors.keys()) { - if(variableIndex_[key].empty()) + for (Key key : removeFactors.keys()) { + if (variableIndex_[key].empty()) removedAndEmpty.insert(removedAndEmpty.end(), key); } KeySet newFactorSymbKeys = newFactors.keys(); std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(), - newFactorSymbKeys.begin(), newFactorSymbKeys.end(), std::inserter(unusedKeys, unusedKeys.end())); + newFactorSymbKeys.begin(), newFactorSymbKeys.end(), + std::inserter(unusedKeys, unusedKeys.end())); // Get indices for unused keys - for(Key key: unusedKeys) { + for (Key key : unusedKeys) { unusedIndices.insert(unusedIndices.end(), key); } } gttoc(push_back_factors); gttic(add_new_variables); - // 2. Initialize any new variables \Theta_{new} and add \Theta:=\Theta\cup\Theta_{new}. + // 2. Initialize any new variables \Theta_{new} and add + // \Theta:=\Theta\cup\Theta_{new}. Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_); // New keys for detailed results - if(params_.enableDetailedResults) { - for(Key key: newTheta.keys()) { result.detail->variableStatus[key].isNew = true; } } + if (params_.enableDetailedResults) { + for (Key key : newTheta.keys()) { + result.detail->variableStatus[key].isNew = true; + } + } gttoc(add_new_variables); gttic(evaluate_error_before); - if(params_.evaluateNonlinearError) + if (params_.evaluateNonlinearError) result.errorBefore.reset(nonlinearFactors_.error(calculateEstimate())); gttoc(evaluate_error_before); gttic(gather_involved_keys); // 3. Mark linear update - KeySet markedKeys = newFactors.keys(); // Get keys from new factors + KeySet markedKeys = newFactors.keys(); // Get keys from new factors // Also mark keys involved in removed factors { - KeySet markedRemoveKeys = removeFactors.keys(); // Get keys involved in removed factors - markedKeys.insert(markedRemoveKeys.begin(), markedRemoveKeys.end()); // Add to the overall set of marked keys + KeySet markedRemoveKeys = + removeFactors.keys(); // Get keys involved in removed factors + markedKeys.insert( + markedRemoveKeys.begin(), + markedRemoveKeys.end()); // Add to the overall set of marked keys } // Also mark any provided extra re-eliminate keys - if(extraReelimKeys) { - for(Key key: *extraReelimKeys) { + if (extraReelimKeys) { + for (Key key : *extraReelimKeys) { markedKeys.insert(key); } } // Observed keys for detailed results - if(params_.enableDetailedResults) { - for(Key key: markedKeys) { + if (params_.enableDetailedResults) { + for (Key key : markedKeys) { result.detail->variableStatus[key].isObserved = true; } } // NOTE: we use assign instead of the iterator constructor here because this // is a vector of size_t, so the constructor unintentionally resolves to // vector(size_t count, Key value) instead of the iterator constructor. - FastVector observedKeys; observedKeys.reserve(markedKeys.size()); - for(Key index: markedKeys) { - if(unusedIndices.find(index) == unusedIndices.end()) // Only add if not unused - observedKeys.push_back(index); // Make a copy of these, as we'll soon add to them + FastVector observedKeys; + observedKeys.reserve(markedKeys.size()); + for (Key index : markedKeys) { + if (unusedIndices.find(index) == + unusedIndices.end()) // Only add if not unused + observedKeys.push_back( + index); // Make a copy of these, as we'll soon add to them } gttoc(gather_involved_keys); - // Check relinearization if we're at the nth step, or we are using a looser loop relin threshold + // Check relinearization if we're at the nth step, or we are using a looser + // loop relin threshold KeySet relinKeys; if (relinearizeThisStep) { gttic(gather_relinearize_keys); - // 4. Mark keys in \Delta above threshold \beta: J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}. - if(params_.enablePartialRelinearizationCheck) - relinKeys = Impl::CheckRelinearizationPartial(roots_, delta_, params_.relinearizeThreshold); + // 4. Mark keys in \Delta above threshold \beta: + // J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}. + if (params_.enablePartialRelinearizationCheck) + relinKeys = Impl::CheckRelinearizationPartial( + roots_, delta_, params_.relinearizeThreshold); else - relinKeys = Impl::CheckRelinearizationFull(delta_, params_.relinearizeThreshold); - if(disableReordering) relinKeys = Impl::CheckRelinearizationFull(delta_, 0.0); // This is used for debugging + relinKeys = + Impl::CheckRelinearizationFull(delta_, params_.relinearizeThreshold); + if (disableReordering) + relinKeys = Impl::CheckRelinearizationFull( + delta_, 0.0); // This is used for debugging // Remove from relinKeys any keys whose linearization points are fixed - for(Key key: fixedVariables_) { + for (Key key : fixedVariables_) { relinKeys.erase(key); } - if(noRelinKeys) { - for(Key key: *noRelinKeys) { + if (noRelinKeys) { + for (Key key : *noRelinKeys) { relinKeys.erase(key); } } // Above relin threshold keys for detailed results - if(params_.enableDetailedResults) { - for(Key key: relinKeys) { + if (params_.enableDetailedResults) { + for (Key key : relinKeys) { result.detail->variableStatus[key].isAboveRelinThreshold = true; - result.detail->variableStatus[key].isRelinearized = true; } } + result.detail->variableStatus[key].isRelinearized = true; + } + } // Add the variables being relinearized to the marked keys KeySet markedRelinMask; - for(const Key key: relinKeys) - markedRelinMask.insert(key); + for (const Key key : relinKeys) markedRelinMask.insert(key); markedKeys.insert(relinKeys.begin(), relinKeys.end()); gttoc(gather_relinearize_keys); gttic(fluid_find_all); - // 5. Mark all cliques that involve marked variables \Theta_{J} and all their ancestors. + // 5. Mark all cliques that involve marked variables \Theta_{J} and all + // their ancestors. if (!relinKeys.empty()) { - for(const sharedClique& root: roots_) + for (const sharedClique& root : roots_) // add other cliques that have the marked ones in the separator Impl::FindAll(root, markedKeys, markedRelinMask); // Relin involved keys for detailed results - if(params_.enableDetailedResults) { + if (params_.enableDetailedResults) { KeySet involvedRelinKeys; - for(const sharedClique& root: roots_) + for (const sharedClique& root : roots_) Impl::FindAll(root, involvedRelinKeys, markedRelinMask); - for(Key key: involvedRelinKeys) { - if(!result.detail->variableStatus[key].isAboveRelinThreshold) { + for (Key key : involvedRelinKeys) { + if (!result.detail->variableStatus[key].isAboveRelinThreshold) { result.detail->variableStatus[key].isRelinearizeInvolved = true; - result.detail->variableStatus[key].isRelinearized = true; } } + result.detail->variableStatus[key].isRelinearized = true; + } + } } } gttoc(fluid_find_all); gttic(expmap); - // 6. Update linearization point for marked variables: \Theta_{J}:=\Theta_{J}+\Delta_{J}. + // 6. Update linearization point for marked variables: + // \Theta_{J}:=\Theta_{J}+\Delta_{J}. if (!relinKeys.empty()) - Impl::ExpmapMasked(theta_, delta_, markedRelinMask, delta_); + Impl::ExpmapMasked(delta_, markedRelinMask, &theta_, delta_); gttoc(expmap); result.variablesRelinearized = markedKeys.size(); @@ -706,17 +1054,16 @@ ISAM2Result ISAM2::update( gttic(linearize_new); // 7. Linearize new factors - if(params_.cacheLinearizedFactors) { + if (params_.cacheLinearizedFactors) { gttic(linearize); - GaussianFactorGraph::shared_ptr linearFactors = newFactors.linearize(theta_); - if(params_.findUnusedFactorSlots) - { + GaussianFactorGraph::shared_ptr linearFactors = + newFactors.linearize(theta_); + if (params_.findUnusedFactorSlots) { linearFactors_.resize(nonlinearFactors_.size()); - for(size_t newFactorI = 0; newFactorI < newFactors.size(); ++newFactorI) - linearFactors_[result.newFactorsIndices[newFactorI]] = (*linearFactors)[newFactorI]; - } - else - { + for (size_t newFactorI = 0; newFactorI < newFactors.size(); ++newFactorI) + linearFactors_[result.newFactorsIndices[newFactorI]] = + (*linearFactors)[newFactorI]; + } else { linearFactors_.push_back(*linearFactors); } assert(nonlinearFactors_.size() == linearFactors_.size()); @@ -726,7 +1073,7 @@ ISAM2Result ISAM2::update( gttic(augment_VI); // Augment the variable index with the new factors - if(params_.findUnusedFactorSlots) + if (params_.findUnusedFactorSlots) variableIndex_.augment(newFactors, result.newFactorsIndices); else variableIndex_.augment(newFactors); @@ -734,26 +1081,28 @@ ISAM2Result ISAM2::update( gttic(recalculate); // 8. Redo top of Bayes tree - boost::shared_ptr replacedKeys; - if(!markedKeys.empty() || !observedKeys.empty()) - replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, unusedIndices, constrainedKeys, result); + boost::shared_ptr replacedKeys; + if (!markedKeys.empty() || !observedKeys.empty()) + replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, + unusedIndices, constrainedKeys, result); // Update replaced keys mask (accumulates until back-substitution takes place) - if(replacedKeys) + if (replacedKeys) deltaReplacedMask_.insert(replacedKeys->begin(), replacedKeys->end()); gttoc(recalculate); // Update data structures to remove unused keys - if(!unusedKeys.empty()) { + if (!unusedKeys.empty()) { gttic(remove_variables); - Impl::RemoveVariables(unusedKeys, roots_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, - deltaReplacedMask_, Base::nodes_, fixedVariables_); + Impl::RemoveVariables(unusedKeys, roots_, theta_, variableIndex_, delta_, + deltaNewton_, RgProd_, deltaReplacedMask_, + Base::nodes_, fixedVariables_); gttoc(remove_variables); } result.cliques = this->nodes().size(); gttic(evaluate_error_after); - if(params_.evaluateNonlinearError) + if (params_.evaluateNonlinearError) result.errorAfter.reset(nonlinearFactors_.error(calculateEstimate())); gttoc(evaluate_error_after); @@ -761,16 +1110,16 @@ ISAM2Result ISAM2::update( } /* ************************************************************************* */ -void ISAM2::marginalizeLeaves(const FastList& leafKeysList, - boost::optional marginalFactorsIndices, - boost::optional deletedFactorsIndices) -{ +void ISAM2::marginalizeLeaves( + const FastList& leafKeysList, + boost::optional marginalFactorsIndices, + boost::optional deletedFactorsIndices) { // Convert to ordered set KeySet leafKeys(leafKeysList.begin(), leafKeysList.end()); // Keep track of marginal factors - map from clique to the marginal factors // that should be incorporated into it, passed up from it's children. -// multimap marginalFactors; + // multimap marginalFactors; map > marginalFactors; // Keep track of factors that get summarized by removing cliques @@ -780,17 +1129,17 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, KeySet leafKeysRemoved; // Remove each variable and its subtrees - for(Key j: leafKeys) { - if(!leafKeysRemoved.exists(j)) { // If the index was not already removed by removing another subtree + for (Key j : leafKeys) { + if (!leafKeysRemoved.exists(j)) { // If the index was not already removed + // by removing another subtree // Traverse up the tree to find the root of the marginalized subtree sharedClique clique = nodes_[j]; - while(!clique->parent_._empty()) - { - // Check if parent contains a marginalized leaf variable. Only need to check the first - // variable because it is the closest to the leaves. + while (!clique->parent_._empty()) { + // Check if parent contains a marginalized leaf variable. Only need to + // check the first variable because it is the closest to the leaves. sharedClique parent = clique->parent(); - if(leafKeys.exists(parent->conditional()->front())) + if (leafKeys.exists(parent->conditional()->front())) clique = parent; else break; @@ -798,39 +1147,48 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, // See if we should remove the whole clique bool marginalizeEntireClique = true; - for(Key frontal: clique->conditional()->frontals()) { - if(!leafKeys.exists(frontal)) { + for (Key frontal : clique->conditional()->frontals()) { + if (!leafKeys.exists(frontal)) { marginalizeEntireClique = false; - break; } } + break; + } + } // Remove either the whole clique or part of it - if(marginalizeEntireClique) { - // Remove the whole clique and its subtree, and keep the marginal factor. + if (marginalizeEntireClique) { + // Remove the whole clique and its subtree, and keep the marginal + // factor. GaussianFactor::shared_ptr marginalFactor = clique->cachedFactor(); // We do not need the marginal factors associated with this clique // because their information is already incorporated in the new // marginal factor. So, now associate this marginal factor with the // parent of this clique. - marginalFactors[clique->parent()->conditional()->front()].push_back(marginalFactor); + marginalFactors[clique->parent()->conditional()->front()].push_back( + marginalFactor); // Now remove this clique and its subtree - all of its marginal // information has been stored in marginalFactors. - const Cliques removedCliques = this->removeSubtree(clique); // Remove the subtree and throw away the cliques - for(const sharedClique& removedClique: removedCliques) { + const Cliques removedCliques = this->removeSubtree( + clique); // Remove the subtree and throw away the cliques + for (const sharedClique& removedClique : removedCliques) { marginalFactors.erase(removedClique->conditional()->front()); - leafKeysRemoved.insert(removedClique->conditional()->beginFrontals(), removedClique->conditional()->endFrontals()); - for(Key frontal: removedClique->conditional()->frontals()) - { + leafKeysRemoved.insert(removedClique->conditional()->beginFrontals(), + removedClique->conditional()->endFrontals()); + for (Key frontal : removedClique->conditional()->frontals()) { // Add to factors to remove - const VariableIndex::Factors& involvedFactors = variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), involvedFactors.end()); + const VariableIndex::Factors& involvedFactors = + variableIndex_[frontal]; + factorIndicesToRemove.insert(involvedFactors.begin(), + involvedFactors.end()); // Check for non-leaf keys - if(!leafKeys.exists(frontal)) - throw runtime_error("Requesting to marginalize variables that are not leaves, the ISAM2 object is now in an inconsistent state so should no longer be used."); + if (!leafKeys.exists(frontal)) + throw runtime_error( + "Requesting to marginalize variables that are not leaves, " + "the ISAM2 object is now in an inconsistent state so should " + "no longer be used."); } } - } - else { + } else { // Reeliminate the current clique and the marginals from its children, // then keep only the marginal on the non-marginalized variables. We // get the childrens' marginals from any existing children, plus @@ -841,181 +1199,220 @@ void ISAM2::marginalizeLeaves(const FastList& leafKeysList, GaussianFactorGraph graph; KeySet factorsInSubtreeRoot; Cliques subtreesToRemove; - for(const sharedClique& child: clique->children) { + for (const sharedClique& child : clique->children) { // Remove subtree if child depends on any marginalized keys - for(Key parent: child->conditional()->parents()) { - if(leafKeys.exists(parent)) { + for (Key parent : child->conditional()->parents()) { + if (leafKeys.exists(parent)) { subtreesToRemove.push_back(child); - graph.push_back(child->cachedFactor()); // Add child marginal + graph.push_back(child->cachedFactor()); // Add child marginal break; } } } Cliques childrenRemoved; - for(const sharedClique& childToRemove: subtreesToRemove) { - const Cliques removedCliques = this->removeSubtree(childToRemove); // Remove the subtree and throw away the cliques - childrenRemoved.insert(childrenRemoved.end(), removedCliques.begin(), removedCliques.end()); - for(const sharedClique& removedClique: removedCliques) { + for (const sharedClique& childToRemove : subtreesToRemove) { + const Cliques removedCliques = this->removeSubtree( + childToRemove); // Remove the subtree and throw away the cliques + childrenRemoved.insert(childrenRemoved.end(), removedCliques.begin(), + removedCliques.end()); + for (const sharedClique& removedClique : removedCliques) { marginalFactors.erase(removedClique->conditional()->front()); - leafKeysRemoved.insert(removedClique->conditional()->beginFrontals(), removedClique->conditional()->endFrontals()); - for(Key frontal: removedClique->conditional()->frontals()) - { + leafKeysRemoved.insert( + removedClique->conditional()->beginFrontals(), + removedClique->conditional()->endFrontals()); + for (Key frontal : removedClique->conditional()->frontals()) { // Add to factors to remove - const VariableIndex::Factors& involvedFactors = variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), involvedFactors.end()); + const VariableIndex::Factors& involvedFactors = + variableIndex_[frontal]; + factorIndicesToRemove.insert(involvedFactors.begin(), + involvedFactors.end()); // Check for non-leaf keys - if(!leafKeys.exists(frontal)) - throw runtime_error("Requesting to marginalize variables that are not leaves, the ISAM2 object is now in an inconsistent state so should no longer be used."); + if (!leafKeys.exists(frontal)) + throw runtime_error( + "Requesting to marginalize variables that are not leaves, " + "the ISAM2 object is now in an inconsistent state so " + "should no longer be used."); } } } - // Add the factors that are pulled into the current clique by the marginalized variables. - // These are the factors that involve *marginalized* frontal variables in this clique - // but do not involve frontal variables of any of its children. - // TODO: reuse cached linear factors + // Add the factors that are pulled into the current clique by the + // marginalized variables. These are the factors that involve + // *marginalized* frontal variables in this clique but do not involve + // frontal variables of any of its children. + // TODO(dellaert): reuse cached linear factors KeySet factorsFromMarginalizedInClique_step1; - for(Key frontal: clique->conditional()->frontals()) { - if(leafKeys.exists(frontal)) - factorsFromMarginalizedInClique_step1.insert(variableIndex_[frontal].begin(), variableIndex_[frontal].end()); } + for (Key frontal : clique->conditional()->frontals()) { + if (leafKeys.exists(frontal)) + factorsFromMarginalizedInClique_step1.insert( + variableIndex_[frontal].begin(), variableIndex_[frontal].end()); + } // Remove any factors in subtrees that we're removing at this step - for(const sharedClique& removedChild: childrenRemoved) { - for(Key indexInClique: removedChild->conditional()->frontals()) { - for(Key factorInvolving: variableIndex_[indexInClique]) { - factorsFromMarginalizedInClique_step1.erase(factorInvolving); } } } + for (const sharedClique& removedChild : childrenRemoved) { + for (Key indexInClique : removedChild->conditional()->frontals()) { + for (Key factorInvolving : variableIndex_[indexInClique]) { + factorsFromMarginalizedInClique_step1.erase(factorInvolving); + } + } + } // Create factor graph from factor indices - for(size_t i: factorsFromMarginalizedInClique_step1) { - graph.push_back(nonlinearFactors_[i]->linearize(theta_)); } + for (size_t i : factorsFromMarginalizedInClique_step1) { + graph.push_back(nonlinearFactors_[i]->linearize(theta_)); + } - // Reeliminate the linear graph to get the marginal and discard the conditional - const KeySet cliqueFrontals(clique->conditional()->beginFrontals(), clique->conditional()->endFrontals()); + // Reeliminate the linear graph to get the marginal and discard the + // conditional + const KeySet cliqueFrontals(clique->conditional()->beginFrontals(), + clique->conditional()->endFrontals()); FastVector cliqueFrontalsToEliminate; - std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(), leafKeys.begin(), leafKeys.end(), - std::back_inserter(cliqueFrontalsToEliminate)); - pair eliminationResult1 = - params_.getEliminationFunction()(graph, Ordering(cliqueFrontalsToEliminate)); + std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(), + leafKeys.begin(), leafKeys.end(), + std::back_inserter(cliqueFrontalsToEliminate)); + pair + eliminationResult1 = params_.getEliminationFunction()( + graph, Ordering(cliqueFrontalsToEliminate)); // Add the resulting marginal - if(eliminationResult1.second) - marginalFactors[clique->conditional()->front()].push_back(eliminationResult1.second); + if (eliminationResult1.second) + marginalFactors[clique->conditional()->front()].push_back( + eliminationResult1.second); // Split the current clique // Find the position of the last leaf key in this clique DenseIndex nToRemove = 0; - while(leafKeys.exists(clique->conditional()->keys()[nToRemove])) - ++ nToRemove; + while (leafKeys.exists(clique->conditional()->keys()[nToRemove])) + ++nToRemove; // Make the clique's matrix appear as a subset - const DenseIndex dimToRemove = clique->conditional()->matrixObject().offset(nToRemove); + const DenseIndex dimToRemove = + clique->conditional()->matrixObject().offset(nToRemove); clique->conditional()->matrixObject().firstBlock() = nToRemove; clique->conditional()->matrixObject().rowStart() = dimToRemove; // Change the keys in the clique - FastVector originalKeys; originalKeys.swap(clique->conditional()->keys()); - clique->conditional()->keys().assign(originalKeys.begin() + nToRemove, originalKeys.end()); + FastVector originalKeys; + originalKeys.swap(clique->conditional()->keys()); + clique->conditional()->keys().assign(originalKeys.begin() + nToRemove, + originalKeys.end()); clique->conditional()->nrFrontals() -= nToRemove; - // Add to factors to remove factors involved in frontals of current clique - for(Key frontal: cliqueFrontalsToEliminate) - { - const VariableIndex::Factors& involvedFactors = variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), involvedFactors.end()); + // Add to factors to remove factors involved in frontals of current + // clique + for (Key frontal : cliqueFrontalsToEliminate) { + const VariableIndex::Factors& involvedFactors = + variableIndex_[frontal]; + factorIndicesToRemove.insert(involvedFactors.begin(), + involvedFactors.end()); } // Add removed keys - leafKeysRemoved.insert(cliqueFrontalsToEliminate.begin(), cliqueFrontalsToEliminate.end()); + leafKeysRemoved.insert(cliqueFrontalsToEliminate.begin(), + cliqueFrontalsToEliminate.end()); } } } - // At this point we have updated the BayesTree, now update the remaining iSAM2 data structures + // At this point we have updated the BayesTree, now update the remaining iSAM2 + // data structures // Gather factors to add - the new marginal factors GaussianFactorGraph factorsToAdd; typedef pair > Key_Factors; - for(const Key_Factors& key_factors: marginalFactors) { - for(const GaussianFactor::shared_ptr& factor: key_factors.second) { - if(factor) { + for (const Key_Factors& key_factors : marginalFactors) { + for (const GaussianFactor::shared_ptr& factor : key_factors.second) { + if (factor) { factorsToAdd.push_back(factor); - if(marginalFactorsIndices) + if (marginalFactorsIndices) marginalFactorsIndices->push_back(nonlinearFactors_.size()); - nonlinearFactors_.push_back(boost::make_shared( - factor)); - if(params_.cacheLinearizedFactors) - linearFactors_.push_back(factor); - for(Key factorKey: *factor) { - fixedVariables_.insert(factorKey); } + nonlinearFactors_.push_back( + boost::make_shared(factor)); + if (params_.cacheLinearizedFactors) linearFactors_.push_back(factor); + for (Key factorKey : *factor) { + fixedVariables_.insert(factorKey); + } } } } - variableIndex_.augment(factorsToAdd); // Augment the variable index + variableIndex_.augment(factorsToAdd); // Augment the variable index - // Remove the factors to remove that have been summarized in the newly-added marginal factors + // Remove the factors to remove that have been summarized in the newly-added + // marginal factors NonlinearFactorGraph removedFactors; - for(size_t i: factorIndicesToRemove) { + for (size_t i : factorIndicesToRemove) { removedFactors.push_back(nonlinearFactors_[i]); nonlinearFactors_.remove(i); - if(params_.cacheLinearizedFactors) - linearFactors_.remove(i); + if (params_.cacheLinearizedFactors) linearFactors_.remove(i); } - variableIndex_.remove(factorIndicesToRemove.begin(), factorIndicesToRemove.end(), removedFactors); + variableIndex_.remove(factorIndicesToRemove.begin(), + factorIndicesToRemove.end(), removedFactors); - if(deletedFactorsIndices) - deletedFactorsIndices->assign(factorIndicesToRemove.begin(), factorIndicesToRemove.end()); + if (deletedFactorsIndices) + deletedFactorsIndices->assign(factorIndicesToRemove.begin(), + factorIndicesToRemove.end()); // Remove the marginalized variables - Impl::RemoveVariables(KeySet(leafKeys.begin(), leafKeys.end()), roots_, theta_, variableIndex_, delta_, deltaNewton_, RgProd_, - deltaReplacedMask_, nodes_, fixedVariables_); + Impl::RemoveVariables(KeySet(leafKeys.begin(), leafKeys.end()), roots_, + theta_, variableIndex_, delta_, deltaNewton_, RgProd_, + deltaReplacedMask_, nodes_, fixedVariables_); } /* ************************************************************************* */ -void ISAM2::updateDelta(bool forceFullSolve) const -{ +void ISAM2::updateDelta(bool forceFullSolve) const { gttic(updateDelta); - if(params_.optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) { + if (params_.optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) { // If using Gauss-Newton, update with wildfireThreshold const ISAM2GaussNewtonParams& gaussNewtonParams = boost::get(params_.optimizationParams); - const double effectiveWildfireThreshold = forceFullSolve ? 0.0 : gaussNewtonParams.wildfireThreshold; + const double effectiveWildfireThreshold = + forceFullSolve ? 0.0 : gaussNewtonParams.wildfireThreshold; gttic(Wildfire_update); lastBacksubVariableCount = Impl::UpdateGaussNewtonDelta( - roots_, deltaReplacedMask_, delta_, effectiveWildfireThreshold); + roots_, deltaReplacedMask_, effectiveWildfireThreshold, &delta_); deltaReplacedMask_.clear(); gttoc(Wildfire_update); - } else if(params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) { + } else if (params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) { // If using Dogleg, do a Dogleg step const ISAM2DoglegParams& doglegParams = boost::get(params_.optimizationParams); - const double effectiveWildfireThreshold = forceFullSolve ? 0.0 : doglegParams.wildfireThreshold; + const double effectiveWildfireThreshold = + forceFullSolve ? 0.0 : doglegParams.wildfireThreshold; // Do one Dogleg iteration gttic(Dogleg_Iterate); // Compute Newton's method step gttic(Wildfire_update); - lastBacksubVariableCount = Impl::UpdateGaussNewtonDelta(roots_, deltaReplacedMask_, deltaNewton_, effectiveWildfireThreshold); + lastBacksubVariableCount = Impl::UpdateGaussNewtonDelta( + roots_, deltaReplacedMask_, effectiveWildfireThreshold, &deltaNewton_); gttoc(Wildfire_update); // Compute steepest descent step - const VectorValues gradAtZero = this->gradientAtZero(); // Compute gradient - Impl::UpdateRgProd(roots_, deltaReplacedMask_, gradAtZero, RgProd_); // Update RgProd - const VectorValues dx_u = Impl::ComputeGradientSearch(gradAtZero, RgProd_); // Compute gradient search point + const VectorValues gradAtZero = this->gradientAtZero(); // Compute gradient + Impl::UpdateRgProd(roots_, deltaReplacedMask_, gradAtZero, + &RgProd_); // Update RgProd + const VectorValues dx_u = Impl::ComputeGradientSearch( + gradAtZero, RgProd_); // Compute gradient search point - // Clear replaced keys mask because now we've updated deltaNewton_ and RgProd_ + // Clear replaced keys mask because now we've updated deltaNewton_ and + // RgProd_ deltaReplacedMask_.clear(); // Compute dogleg point - DoglegOptimizerImpl::IterationResult doglegResult(DoglegOptimizerImpl::Iterate( - *doglegDelta_, doglegParams.adaptationMode, dx_u, deltaNewton_, *this, nonlinearFactors_, - theta_, nonlinearFactors_.error(theta_), doglegParams.verbose)); + DoglegOptimizerImpl::IterationResult doglegResult( + DoglegOptimizerImpl::Iterate( + *doglegDelta_, doglegParams.adaptationMode, dx_u, deltaNewton_, + *this, nonlinearFactors_, theta_, nonlinearFactors_.error(theta_), + doglegParams.verbose)); gttoc(Dogleg_Iterate); gttic(Copy_dx_d); // Update Delta and linear step doglegDelta_ = doglegResult.delta; - delta_ = doglegResult.dx_d; // Copy the VectorValues containing with the linear solution + delta_ = + doglegResult + .dx_d; // Copy the VectorValues containing with the linear solution gttoc(Copy_dx_d); } } @@ -1037,60 +1434,62 @@ const Value& ISAM2::calculateEstimate(Key key) const { /* ************************************************************************* */ Values ISAM2::calculateBestEstimate() const { - updateDelta(true); // Force full solve when updating delta_ + updateDelta(true); // Force full solve when updating delta_ return theta_.retract(delta_); } /* ************************************************************************* */ Matrix ISAM2::marginalCovariance(Key key) const { - return marginalFactor(key, params_.getEliminationFunction())->information().inverse(); + return marginalFactor(key, params_.getEliminationFunction()) + ->information() + .inverse(); } /* ************************************************************************* */ const VectorValues& ISAM2::getDelta() const { - if(!deltaReplacedMask_.empty()) - updateDelta(); + if (!deltaReplacedMask_.empty()) updateDelta(); return delta_; } /* ************************************************************************* */ -double ISAM2::error(const VectorValues& x) const -{ +double ISAM2::error(const VectorValues& x) const { return GaussianFactorGraph(*this).error(x); } /* ************************************************************************* */ -static void gradientAtZeroTreeAdder(const boost::shared_ptr& root, VectorValues& g) { +static void gradientAtZeroTreeAdder(const boost::shared_ptr& root, + VectorValues* g) { // Loop through variables in each clique, adding contributions DenseIndex variablePosition = 0; - for(GaussianConditional::const_iterator jit = root->conditional()->begin(); jit != root->conditional()->end(); ++jit) { + for (GaussianConditional::const_iterator jit = root->conditional()->begin(); + jit != root->conditional()->end(); ++jit) { const DenseIndex dim = root->conditional()->getDim(jit); - pair pos_ins = - g.tryInsert(*jit, root->gradientContribution().segment(variablePosition, dim)); - if(!pos_ins.second) - pos_ins.first->second += root->gradientContribution().segment(variablePosition, dim); + pair pos_ins = g->tryInsert( + *jit, root->gradientContribution().segment(variablePosition, dim)); + if (!pos_ins.second) + pos_ins.first->second += + root->gradientContribution().segment(variablePosition, dim); variablePosition += dim; } // Recursively add contributions from children typedef boost::shared_ptr sharedClique; - for(const sharedClique& child: root->children) { + for (const sharedClique& child : root->children) { gradientAtZeroTreeAdder(child, g); } } /* ************************************************************************* */ -VectorValues ISAM2::gradientAtZero() const -{ +VectorValues ISAM2::gradientAtZero() const { // Create result VectorValues g; // Sum up contributions for each clique - for(const ISAM2::sharedClique& root: this->roots()) - gradientAtZeroTreeAdder(root, g); + for (const ISAM2::sharedClique& root : this->roots()) + gradientAtZeroTreeAdder(root, &g); return g; } -} +} // namespace gtsam /// namespace gtsam diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 235cb65a5..d3904067c 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -509,7 +509,7 @@ class GTSAM_EXPORT ISAM2Clique Base::FactorType::shared_ptr cachedFactor_; Vector gradientContribution_; - FastMap solnPointers_; + mutable FastMap solnPointers_; /// Default constructor ISAM2Clique() : Base() {} @@ -546,6 +546,45 @@ class GTSAM_EXPORT ISAM2Clique void print(const std::string& s = "", const KeyFormatter& formatter = DefaultKeyFormatter) const; + /** + * Check if clique was replaced, or if any parents were changed above the + * threshold or themselves replaced. + */ + bool isDirty(const KeySet& replaced, const KeySet& changed) const; + + /// Copy values in delta pertaining to this clique. + FastVector copyRelevantValues(const VectorValues& delta) const; + + /* + * Check whether the values changed above a threshold, or always true if the + * clique was replaced. + */ + bool valuesChanged(const KeySet& replaced, + const FastVector& originalValues, + const VectorValues& delta, double threshold) const; + + /// Set changed flag for each frontal variable + void markFrontalsAsChanged(KeySet* changed) const; + + /// Restore delta to original values, guided by frontal keys. + void restoreFromOriginals(const FastVector& originalValues, + VectorValues* delta) const; + + void optimizeWildfire(const KeySet& replaced, double threshold, KeySet* changed, + VectorValues* delta, + size_t* count) const; + + bool optimizeWildfireNode(const KeySet& replaced, double threshold, KeySet* changed, + VectorValues* delta, + size_t* count) const; + + /** + * Starting from the root, add up entries of frontal and conditional matrices + * of each conditional + */ + void nnz_internal(size_t* result) const; + size_t calculate_nnz() const; + private: /** Serialization function */ friend class boost::serialization::access; @@ -810,30 +849,23 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { template <> struct traits : public Testable {}; -/// Optimize the BayesTree, starting from the root. -/// @param replaced Needs to contain -/// all variables that are contained in the top of the Bayes tree that has been -/// redone. -/// @param delta The current solution, an offset from the linearization -/// point. -/// @param threshold The maximum change against the PREVIOUS delta for -/// non-replaced variables that can be ignored, ie. the old delta entry is kept -/// and recursive backsubstitution might eventually stop if none of the changed -/// variables are contained in the subtree. -/// @return The number of variables that were solved for -template -size_t optimizeWildfire(const boost::shared_ptr& root, double threshold, - const KeySet& replaced, VectorValues& delta); +/** + * Optimize the BayesTree, starting from the root. + * @param threshold The maximum change against the PREVIOUS delta for + * non-replaced variables that can be ignored, ie. the old delta entry is kept + * and recursive backsubstitution might eventually stop if none of the changed + * variables are contained in the subtree. + * @param replaced Needs to contain all variables that are contained in the top + * of the Bayes tree that has been redone. + * @return The number of variables that were solved for. + * @param delta The current solution, an offset from the linearization point. + */ +size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, + const KeySet& replaced, VectorValues* delta); -template -size_t optimizeWildfireNonRecursive(const boost::shared_ptr& root, +size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, double threshold, const KeySet& replaced, - VectorValues& delta); - -/// calculate the number of non-zero entries for the tree starting at clique -/// (use root for complete matrix) -template -int calculate_nnz(const boost::shared_ptr& clique); + VectorValues* delta); } // namespace gtsam diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index f56b458be..681c30587 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -843,7 +843,7 @@ TEST(ISAM2, calculate_nnz) { ISAM2 isam = createSlamlikeISAM2(); int expected = 241; - int actual = calculate_nnz(isam.roots().front()); + int actual = isam.roots().front()->calculate_nnz(); EXPECT_LONGS_EQUAL(expected, actual); } From e770490ae78d39b26b1b528e5f0a7fe5c85c04f5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 10:28:45 -0400 Subject: [PATCH 054/197] Made vector templated on Key container. --- gtsam/linear/VectorValues.cpp | 22 ---------------------- gtsam/linear/VectorValues.h | 21 ++++++++++++++++++++- 2 files changed, 20 insertions(+), 23 deletions(-) diff --git a/gtsam/linear/VectorValues.cpp b/gtsam/linear/VectorValues.cpp index 35afddb3a..b037aad92 100644 --- a/gtsam/linear/VectorValues.cpp +++ b/gtsam/linear/VectorValues.cpp @@ -160,28 +160,6 @@ namespace gtsam { return result; } - /* ************************************************************************* */ - Vector VectorValues::vector(const FastVector& keys) const - { - // Count dimensions and collect pointers to avoid double lookups - DenseIndex totalDim = 0; - FastVector items(keys.size()); - for(size_t i = 0; i < keys.size(); ++i) { - items[i] = &at(keys[i]); - totalDim += items[i]->size(); - } - - // Copy vectors - Vector result(totalDim); - DenseIndex pos = 0; - for(const Vector *v: items) { - result.segment(pos, v->size()) = *v; - pos += v->size(); - } - - return result; - } - /* ************************************************************************* */ Vector VectorValues::vector(const Dims& keys) const { diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index cb1e08f2d..2d8eb0ec0 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -244,7 +244,26 @@ namespace gtsam { Vector vector() const; /** Access a vector that is a subset of relevant keys. */ - Vector vector(const FastVector& keys) const; + template + Vector vector(const CONTAINER& keys) const { + DenseIndex totalDim = 0; + FastVector items; + items.reserve(keys.end() - keys.begin()); + for (Key key : keys) { + const Vector* v = &at(key); + totalDim += v->size(); + items.push_back(v); + } + + Vector result(totalDim); + DenseIndex pos = 0; + for (const Vector* v : items) { + result.segment(pos, v->size()) = *v; + pos += v->size(); + } + + return result; + } /** Access a vector that is a subset of relevant keys, dims version. */ Vector vector(const Dims& dims) const; From 34326c20ec5a39266e0e9a4a4f33381c3761b2d7 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 10:29:12 -0400 Subject: [PATCH 055/197] Cleaned up code cruft --- gtsam/linear/VectorValues.h | 128 ++++++++++++------------------------ 1 file changed, 41 insertions(+), 87 deletions(-) diff --git a/gtsam/linear/VectorValues.h b/gtsam/linear/VectorValues.h index 2d8eb0ec0..f187b56de 100644 --- a/gtsam/linear/VectorValues.h +++ b/gtsam/linear/VectorValues.h @@ -26,6 +26,9 @@ #include +#include +#include + namespace gtsam { /** @@ -43,10 +46,6 @@ namespace gtsam { * - \ref exists (Key) to check if a variable is present * - Other facilities like iterators, size(), dim(), etc. * - * Indices can be non-consecutive and inserted out-of-order, but you should not - * use indices that are larger than a reasonable array size because the indices - * correspond to positions in an internal array. - * * Example: * \code VectorValues values; @@ -64,12 +63,6 @@ namespace gtsam { * *

Advanced Interface and Performance Information

* - * Internally, all vector values are stored as part of one large vector. In - * gtsam this vector is always pre-allocated for efficiency, using the - * advanced interface described below. Accessing and modifying already-allocated - * values is \f$ O(1) \f$. Using the insert() function of the standard interface - * is slow because it requires re-allocating the internal vector. - * * For advanced usage, or where speed is important: * - Allocate space ahead of time using a pre-allocating constructor * (\ref AdvancedConstructors "Advanced Constructors"), Zero(), @@ -88,20 +81,18 @@ namespace gtsam { * \nosubgrouping */ class GTSAM_EXPORT VectorValues { - protected: + protected: typedef VectorValues This; - typedef ConcurrentMap Values; ///< Typedef for the collection of Vectors making up a VectorValues - Values values_; ///< Collection of Vectors making up this VectorValues + typedef ConcurrentMap Values; ///< Collection of Vectors making up a VectorValues + Values values_; ///< Vectors making up this VectorValues - public: - typedef Values::iterator iterator; ///< Iterator over vector values - typedef Values::const_iterator const_iterator; ///< Const iterator over vector values - //typedef Values::reverse_iterator reverse_iterator; ///< Reverse iterator over vector values - //typedef Values::const_reverse_iterator const_reverse_iterator; ///< Const reverse iterator over vector values - typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class - typedef Values::value_type value_type; ///< Typedef to pair, a key-value pair - typedef value_type KeyValuePair; ///< Typedef to pair, a key-value pair - typedef std::map Dims; + public: + typedef Values::iterator iterator; ///< Iterator over vector values + typedef Values::const_iterator const_iterator; ///< Const iterator over vector values + typedef boost::shared_ptr shared_ptr; ///< shared_ptr to this class + typedef Values::value_type value_type; ///< Typedef to pair + typedef value_type KeyValuePair; ///< Typedef to pair + typedef std::map Dims; ///< Keyed vector dimensions /// @name Standard Constructors /// @{ @@ -111,7 +102,8 @@ namespace gtsam { */ VectorValues() {} - /** Merge two VectorValues into one, this is more efficient than inserting elements one by one. */ + /** Merge two VectorValues into one, this is more efficient than inserting + * elements one by one. */ VectorValues(const VectorValues& first, const VectorValues& second); /** Create from another container holding pair. */ @@ -147,20 +139,26 @@ namespace gtsam { /** Check whether a variable with key \c j exists. */ bool exists(Key j) const { return find(j) != end(); } - /** Read/write access to the vector value with key \c j, throws std::out_of_range if \c j does not exist, identical to operator[](Key). */ + /** + * Read/write access to the vector value with key \c j, throws + * std::out_of_range if \c j does not exist, identical to operator[](Key). + */ Vector& at(Key j) { iterator item = find(j); - if(item == end()) + if (item == end()) throw std::out_of_range( "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues."); else return item->second; } - /** Access the vector value with key \c j (const version), throws std::out_of_range if \c j does not exist, identical to operator[](Key). */ + /** + * Access the vector value with key \c j (const version), throws + * std::out_of_range if \c j does not exist, identical to operator[](Key). + */ const Vector& at(Key j) const { const_iterator item = find(j); - if(item == end()) + if (item == end()) throw std::out_of_range( "Requested variable '" + DefaultKeyFormatter(j) + "' is not in this VectorValues."); else @@ -207,26 +205,30 @@ namespace gtsam { /** Erase the vector with the given key, or throw std::out_of_range if it does not exist */ void erase(Key var) { - if(values_.unsafe_erase(var) == 0) - throw std::invalid_argument("Requested variable '" + DefaultKeyFormatter(var) + "', is not in this VectorValues."); + if (values_.unsafe_erase(var) == 0) + throw std::invalid_argument("Requested variable '" + + DefaultKeyFormatter(var) + + "', is not in this VectorValues."); } /** Set all values to zero vectors. */ void setZero(); - iterator begin() { return values_.begin(); } ///< Iterator over variables - const_iterator begin() const { return values_.begin(); } ///< Iterator over variables - iterator end() { return values_.end(); } ///< Iterator over variables - const_iterator end() const { return values_.end(); } ///< Iterator over variables - //reverse_iterator rbegin() { return values_.rbegin(); } ///< Reverse iterator over variables - //const_reverse_iterator rbegin() const { return values_.rbegin(); } ///< Reverse iterator over variables - //reverse_iterator rend() { return values_.rend(); } ///< Reverse iterator over variables - //const_reverse_iterator rend() const { return values_.rend(); } ///< Reverse iterator over variables + iterator begin() { return values_.begin(); } ///< Iterator over variables + const_iterator begin() const { return values_.begin(); } ///< Iterator over variables + iterator end() { return values_.end(); } ///< Iterator over variables + const_iterator end() const { return values_.end(); } ///< Iterator over variables - /** Return the iterator corresponding to the requested key, or end() if no variable is present with this key. */ + /** + * Return the iterator corresponding to the requested key, or end() if no + * variable is present with this key. + */ iterator find(Key j) { return values_.find(j); } - /** Return the iterator corresponding to the requested key, or end() if no variable is present with this key. */ + /** + * Return the iterator corresponding to the requested key, or end() if no + * variable is present with this key. + */ const_iterator find(Key j) const { return values_.find(j); } /** print required by Testable for unit testing */ @@ -338,54 +340,6 @@ namespace gtsam { /// @} - /** - * scale a vector by a scalar - */ - //friend VectorValues operator*(const double a, const VectorValues &v) { - // VectorValues result = VectorValues::SameStructure(v); - // for(Key j = 0; j < v.size(); ++j) - // result.values_[j] = a * v.values_[j]; - // return result; - //} - - //// TODO: linear algebra interface seems to have been added for SPCG. - //friend void axpy(double alpha, const VectorValues& x, VectorValues& y) { - // if(x.size() != y.size()) - // throw std::invalid_argument("axpy(VectorValues) called with different vector sizes"); - // for(Key j = 0; j < x.size(); ++j) - // if(x.values_[j].size() == y.values_[j].size()) - // y.values_[j] += alpha * x.values_[j]; - // else - // throw std::invalid_argument("axpy(VectorValues) called with different vector sizes"); - //} - //// TODO: linear algebra interface seems to have been added for SPCG. - //friend void sqrt(VectorValues &x) { - // for(Key j = 0; j < x.size(); ++j) - // x.values_[j] = x.values_[j].cwiseSqrt(); - //} - - //// TODO: linear algebra interface seems to have been added for SPCG. - //friend void ediv(const VectorValues& numerator, const VectorValues& denominator, VectorValues &result) { - // if(numerator.size() != denominator.size() || numerator.size() != result.size()) - // throw std::invalid_argument("ediv(VectorValues) called with different vector sizes"); - // for(Key j = 0; j < numerator.size(); ++j) - // if(numerator.values_[j].size() == denominator.values_[j].size() && numerator.values_[j].size() == result.values_[j].size()) - // result.values_[j] = numerator.values_[j].cwiseQuotient(denominator.values_[j]); - // else - // throw std::invalid_argument("ediv(VectorValues) called with different vector sizes"); - //} - - //// TODO: linear algebra interface seems to have been added for SPCG. - //friend void edivInPlace(VectorValues& x, const VectorValues& y) { - // if(x.size() != y.size()) - // throw std::invalid_argument("edivInPlace(VectorValues) called with different vector sizes"); - // for(Key j = 0; j < x.size(); ++j) - // if(x.values_[j].size() == y.values_[j].size()) - // x.values_[j].array() /= y.values_[j].array(); - // else - // throw std::invalid_argument("edivInPlace(VectorValues) called with different vector sizes"); - //} - private: /** Serialization function */ friend class boost::serialization::access; From 5223713c1877be08f30a5b8a3307c282025ad175 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 10:30:27 -0400 Subject: [PATCH 056/197] Use VectorValues::vector rather than bespoke code for saving delta values. --- gtsam/nonlinear/ISAM2.cpp | 58 +++++++++++++++------------------------ gtsam/nonlinear/ISAM2.h | 52 ++++++++++++++++------------------- 2 files changed, 46 insertions(+), 64 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index bdd6b42bb..599219145 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -85,10 +85,10 @@ class ISAM2JunctionTree }; /* ************************************************************************* */ -std::string ISAM2DoglegParams::adaptationModeTranslator( +string ISAM2DoglegParams::adaptationModeTranslator( const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) const { - std::string s; + string s; switch (adaptationMode) { case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: s = "SEARCH_EACH_ITERATION"; @@ -106,8 +106,8 @@ std::string ISAM2DoglegParams::adaptationModeTranslator( /* ************************************************************************* */ DoglegOptimizerImpl::TrustRegionAdaptationMode ISAM2DoglegParams::adaptationModeTranslator( - const std::string& adaptationMode) const { - std::string s = adaptationMode; + const string& adaptationMode) const { + string s = adaptationMode; boost::algorithm::to_upper(s); if (s == "SEARCH_EACH_ITERATION") return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; @@ -120,8 +120,8 @@ ISAM2DoglegParams::adaptationModeTranslator( /* ************************************************************************* */ ISAM2Params::Factorization ISAM2Params::factorizationTranslator( - const std::string& str) { - std::string s = str; + const string& str) { + string s = str; boost::algorithm::to_upper(s); if (s == "QR") return ISAM2Params::QR; if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; @@ -131,9 +131,9 @@ ISAM2Params::Factorization ISAM2Params::factorizationTranslator( } /* ************************************************************************* */ -std::string ISAM2Params::factorizationTranslator( +string ISAM2Params::factorizationTranslator( const ISAM2Params::Factorization& value) { - std::string s; + string s; switch (value) { case ISAM2Params::QR: s = "QR"; @@ -171,13 +171,12 @@ bool ISAM2Clique::equals(const This& other, double tol) const { } /* ************************************************************************* */ -void ISAM2Clique::print(const std::string& s, - const KeyFormatter& formatter) const { +void ISAM2Clique::print(const string& s, const KeyFormatter& formatter) const { Base::print(s, formatter); if (cachedFactor_) cachedFactor_->print(s + "Cached: ", formatter); else - std::cout << s << "Cached empty" << std::endl; + cout << s << "Cached empty" << endl; if (gradientContribution_.rows() != 0) gtsam::print(gradientContribution_, "Gradient contribution: "); } @@ -207,31 +206,16 @@ bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { } return dirty; } -/* ************************************************************************* */ -FastVector ISAM2Clique::copyRelevantValues( - const VectorValues& delta) const { - FastVector values; - values.reserve(conditional_->nrFrontals()); - for (Key frontal : conditional_->frontals()) { - values.push_back(delta[frontal]); - } - return values; -} /* ************************************************************************* */ bool ISAM2Clique::valuesChanged(const KeySet& replaced, - const FastVector& originalValues, + const Vector& originalValues, const VectorValues& delta, double threshold) const { - if (replaced.exists(conditional_->frontals().front())) return true; - size_t i = 0; - for (Key frontal : conditional_->frontals()) { - const Vector diff = originalValues[i++] - delta[frontal]; - if (diff.lpNorm() >= threshold) { - return true; - } - } - return false; + auto frontals = conditional_->frontals(); + if (replaced.exists(frontals.front())) return true; + auto diff = originalValues - delta.vector(frontals); + return diff.lpNorm() >= threshold; } /* ************************************************************************* */ @@ -243,11 +227,13 @@ void ISAM2Clique::markFrontalsAsChanged(KeySet* changed) const { } /* ************************************************************************* */ -void ISAM2Clique::restoreFromOriginals(const FastVector& originalValues, +void ISAM2Clique::restoreFromOriginals(const Vector& originalValues, VectorValues* delta) const { - size_t i = 0; + size_t pos = 0; for (Key frontal : conditional_->frontals()) { - delta->at(frontal) = originalValues[i++]; + auto v = delta->at(frontal); + v = originalValues.segment(pos, v.size()); + pos += v.size(); } } @@ -257,7 +243,7 @@ void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, size_t* count) const { if (isDirty(replaced, *changed)) { // Temporary copy of the original values, to check how much they change - auto originalValues = copyRelevantValues(*delta); + auto originalValues = delta->vector(conditional_->frontals()); // Back-substitute delta->update(conditional_->solve(*delta)); @@ -285,7 +271,7 @@ bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, bool dirty = isDirty(replaced, *changed); if (dirty) { // Temporary copy of the original values, to check how much they change - auto originalValues = copyRelevantValues(*delta); + auto originalValues = delta->vector(conditional_->frontals()); // Back-substitute - special version stores solution pointers in cliques for // fast access. diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index d3904067c..465e5cd7f 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -546,36 +546,12 @@ class GTSAM_EXPORT ISAM2Clique void print(const std::string& s = "", const KeyFormatter& formatter = DefaultKeyFormatter) const; - /** - * Check if clique was replaced, or if any parents were changed above the - * threshold or themselves replaced. - */ - bool isDirty(const KeySet& replaced, const KeySet& changed) const; - - /// Copy values in delta pertaining to this clique. - FastVector copyRelevantValues(const VectorValues& delta) const; - - /* - * Check whether the values changed above a threshold, or always true if the - * clique was replaced. - */ - bool valuesChanged(const KeySet& replaced, - const FastVector& originalValues, - const VectorValues& delta, double threshold) const; - - /// Set changed flag for each frontal variable - void markFrontalsAsChanged(KeySet* changed) const; - - /// Restore delta to original values, guided by frontal keys. - void restoreFromOriginals(const FastVector& originalValues, - VectorValues* delta) const; - - void optimizeWildfire(const KeySet& replaced, double threshold, KeySet* changed, - VectorValues* delta, + void optimizeWildfire(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, size_t* count) const; - bool optimizeWildfireNode(const KeySet& replaced, double threshold, KeySet* changed, - VectorValues* delta, + bool optimizeWildfireNode(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, size_t* count) const; /** @@ -586,6 +562,26 @@ class GTSAM_EXPORT ISAM2Clique size_t calculate_nnz() const; private: + /** + * Check if clique was replaced, or if any parents were changed above the + * threshold or themselves replaced. + */ + bool isDirty(const KeySet& replaced, const KeySet& changed) const; + + /* + * Check whether the values changed above a threshold, or always true if the + * clique was replaced. + */ + bool valuesChanged(const KeySet& replaced, const Vector& originalValues, + const VectorValues& delta, double threshold) const; + + /// Set changed flag for each frontal variable + void markFrontalsAsChanged(KeySet* changed) const; + + /// Restore delta to original values, guided by frontal keys. + void restoreFromOriginals(const Vector& originalValues, + VectorValues* delta) const; + /** Serialization function */ friend class boost::serialization::access; template From ba644029853d360158a53c6e2ee1e7d3d2b2a25c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 10:47:32 -0400 Subject: [PATCH 057/197] Added fastBackSubstitute method --- gtsam/nonlinear/ISAM2.cpp | 145 ++++++++++++++++++++------------------ gtsam/nonlinear/ISAM2.h | 6 ++ 2 files changed, 81 insertions(+), 70 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 599219145..c16fe04da 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -207,6 +207,80 @@ bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { return dirty; } +/* ************************************************************************* */ +/** + * Back-substitute - special version stores solution pointers in cliques for + * fast access. + */ +void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const { + // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, + // potentially refactor + + // Create solution part pointers if necessary and possible - necessary if + // solnPointers_ is empty, and possible if either we're a root, or we have + // a parent with valid solnPointers_. + ISAM2::sharedClique parent = parent_.lock(); + if (solnPointers_.empty() && (isRoot() || !parent->solnPointers_.empty())) { + for (Key frontal : conditional_->frontals()) + solnPointers_.emplace(frontal, delta->find(frontal)); + for (Key parentKey : conditional_->parents()) { + assert(parent->solnPointers_.exists(parentKey)); + solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey)); + } + } + + // See if we can use solution part pointers - we can if they either + // already existed or were created above. + if (!solnPointers_.empty()) { + GaussianConditional& c = *conditional_; + // Solve matrix + Vector xS; + { + // Count dimensions of vector + DenseIndex dim = 0; + FastVector parentPointers; + parentPointers.reserve(conditional_->nrParents()); + for (Key parent : conditional_->parents()) { + parentPointers.push_back(solnPointers_.at(parent)); + dim += parentPointers.back()->second.size(); + } + + // Fill parent vector + xS.resize(dim); + DenseIndex vectorPos = 0; + for (const VectorValues::const_iterator& parentPointer : parentPointers) { + const Vector& parentVector = parentPointer->second; + xS.block(vectorPos, 0, parentVector.size(), 1) = + parentVector.block(0, 0, parentVector.size(), 1); + vectorPos += parentVector.size(); + } + } + + // NOTE(gareth): We can no longer write: xS = b - S * xS + // This is because Eigen (as of 3.3) no longer evaluates S * xS into + // a temporary, and the operation trashes valus in xS. + // See: http://eigen.tuxfamily.org/index.php?title=3.3 + const Vector rhs = c.getb() - c.get_S() * xS; + const Vector solution = c.get_R().triangularView().solve(rhs); + + // Check for indeterminant solution + if (solution.hasNaN()) + throw IndeterminantLinearSystemException(c.keys().front()); + + // Insert solution into a VectorValues + DenseIndex vectorPosition = 0; + for (GaussianConditional::const_iterator frontal = c.beginFrontals(); + frontal != c.endFrontals(); ++frontal) { + solnPointers_.at(*frontal)->second = + solution.segment(vectorPosition, c.getDim(frontal)); + vectorPosition += c.getDim(frontal); + } + } else { + // Just call plain solve because we couldn't use solution pointers. + delta->update(conditional_->solve(*delta)); + } +} + /* ************************************************************************* */ bool ISAM2Clique::valuesChanged(const KeySet& replaced, const Vector& originalValues, @@ -273,76 +347,7 @@ bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, // Temporary copy of the original values, to check how much they change auto originalValues = delta->vector(conditional_->frontals()); - // Back-substitute - special version stores solution pointers in cliques for - // fast access. - { - // Create solution part pointers if necessary and possible - necessary if - // solnPointers_ is empty, and possible if either we're a root, or we have - // a parent with valid solnPointers_. - ISAM2::sharedClique parent = parent_.lock(); - if (solnPointers_.empty() && - (isRoot() || !parent->solnPointers_.empty())) { - for (Key frontal : conditional_->frontals()) - solnPointers_.emplace(frontal, delta->find(frontal)); - for (Key parentKey : conditional_->parents()) { - assert(parent->solnPointers_.exists(parentKey)); - solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey)); - } - } - - // See if we can use solution part pointers - we can if they either - // already existed or were created above. - if (!solnPointers_.empty()) { - GaussianConditional& c = *conditional_; - // Solve matrix - Vector xS; - { - // Count dimensions of vector - DenseIndex dim = 0; - FastVector parentPointers; - parentPointers.reserve(conditional_->nrParents()); - for (Key parent : conditional_->parents()) { - parentPointers.push_back(solnPointers_.at(parent)); - dim += parentPointers.back()->second.size(); - } - - // Fill parent vector - xS.resize(dim); - DenseIndex vectorPos = 0; - for (const VectorValues::const_iterator& parentPointer : - parentPointers) { - const Vector& parentVector = parentPointer->second; - xS.block(vectorPos, 0, parentVector.size(), 1) = - parentVector.block(0, 0, parentVector.size(), 1); - vectorPos += parentVector.size(); - } - } - - // NOTE(gareth): We can no longer write: xS = b - S * xS - // This is because Eigen (as of 3.3) no longer evaluates S * xS into - // a temporary, and the operation trashes valus in xS. - // See: http://eigen.tuxfamily.org/index.php?title=3.3 - const Vector rhs = c.getb() - c.get_S() * xS; - const Vector solution = - c.get_R().triangularView().solve(rhs); - - // Check for indeterminant solution - if (solution.hasNaN()) - throw IndeterminantLinearSystemException(c.keys().front()); - - // Insert solution into a VectorValues - DenseIndex vectorPosition = 0; - for (GaussianConditional::const_iterator frontal = c.beginFrontals(); - frontal != c.endFrontals(); ++frontal) { - solnPointers_.at(*frontal)->second = - solution.segment(vectorPosition, c.getDim(frontal)); - vectorPosition += c.getDim(frontal); - } - } else { - // Just call plain solve because we couldn't use solution pointers. - delta->update(conditional_->solve(*delta)); - } - } + fastBackSubstitute(delta); count += conditional_->nrFrontals(); if (valuesChanged(replaced, originalValues, *delta, threshold)) { diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 465e5cd7f..b60a24644 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -568,6 +568,12 @@ class GTSAM_EXPORT ISAM2Clique */ bool isDirty(const KeySet& replaced, const KeySet& changed) const; + /** + * Back-substitute - special version stores solution pointers in cliques for + * fast access. + */ + void fastBackSubstitute(VectorValues* delta) const; + /* * Check whether the values changed above a threshold, or always true if the * clique was replaced. From 7fd8bc1bf5e5039a1b270620b48823298c2c8e10 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 11:19:25 -0400 Subject: [PATCH 058/197] Restored non-recursive version, disabled solution pointers back-substitute. --- gtsam/nonlinear/ISAM2-impl.cpp | 2 +- gtsam/nonlinear/ISAM2.cpp | 66 +++++++++++++++++----------------- gtsam/nonlinear/ISAM2.h | 2 ++ 3 files changed, 37 insertions(+), 33 deletions(-) diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index aa201138c..bc43c9b9d 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -304,7 +304,7 @@ size_t ISAM2::Impl::UpdateGaussNewtonDelta( // Optimize with wildfire lastBacksubVariableCount = 0; for (const ISAM2::sharedClique& root : roots) - lastBacksubVariableCount += optimizeWildfire( + lastBacksubVariableCount += optimizeWildfireNonRecursive( root, wildfireThreshold, replacedKeys, delta); // modifies delta #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index c16fe04da..f2b154cc4 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -213,6 +213,7 @@ bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { * fast access. */ void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const { +#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, // potentially refactor @@ -279,6 +280,9 @@ void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const { // Just call plain solve because we couldn't use solution pointers. delta->update(conditional_->solve(*delta)); } +#else + delta->update(conditional_->solve(*delta)); +#endif } /* ************************************************************************* */ @@ -312,6 +316,7 @@ void ISAM2Clique::restoreFromOriginals(const Vector& originalValues, } /* ************************************************************************* */ +// Note: not being used right now in favor of non-recursive version below. void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, KeySet* changed, VectorValues* delta, size_t* count) const { @@ -320,7 +325,7 @@ void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, auto originalValues = delta->vector(conditional_->frontals()); // Back-substitute - delta->update(conditional_->solve(*delta)); + fastBackSubstitute(delta); count += conditional_->nrFrontals(); if (valuesChanged(replaced, originalValues, *delta, threshold)) { @@ -336,6 +341,15 @@ void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, } } +size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, + const KeySet& keys, VectorValues* delta) { + KeySet changed; + size_t count = 0; + // starting from the root, call optimize on each conditional + if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count); + return count; +} + /* ************************************************************************* */ bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, KeySet* changed, VectorValues* delta, @@ -347,6 +361,7 @@ bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, // Temporary copy of the original values, to check how much they change auto originalValues = delta->vector(conditional_->frontals()); + // Back-substitute fastBackSubstitute(delta); count += conditional_->nrFrontals(); @@ -360,37 +375,6 @@ bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, return dirty; } -/* ************************************************************************* */ -void ISAM2Clique::nnz_internal(size_t* result) const { - size_t dimR = conditional_->rows(); - size_t dimSep = conditional_->get_S().cols(); - *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR; - // traverse the children - for (const auto& child : children) { - child->nnz_internal(result); - } -} - -/* ************************************************************************* */ -size_t ISAM2Clique::calculate_nnz() const { - size_t result = 0; - nnz_internal(&result); - return result; -} - -/* ************************************************************************* */ -size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, - const KeySet& keys, VectorValues* delta) { - KeySet changed; - size_t count = 0; - // starting from the root, call optimize on each conditional - if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count); - return count; -} - -/* ************************************************************************* */ -// This version is non-recursive version, but seems to have -// a bug, as was diagnosed with ISAM2Example_SmartFactor. Disabled for now. size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, double threshold, const KeySet& keys, VectorValues* delta) { @@ -417,6 +401,24 @@ size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, return count; } +/* ************************************************************************* */ +void ISAM2Clique::nnz_internal(size_t* result) const { + size_t dimR = conditional_->rows(); + size_t dimSep = conditional_->get_S().cols(); + *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR; + // traverse the children + for (const auto& child : children) { + child->nnz_internal(result); + } +} + +/* ************************************************************************* */ +size_t ISAM2Clique::calculate_nnz() const { + size_t result = 0; + nnz_internal(&result); + return result; +} + /* ************************************************************************* */ ISAM2::ISAM2(const ISAM2Params& params) : params_(params), update_count_(0) { if (params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index b60a24644..eb33038a7 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -509,7 +509,9 @@ class GTSAM_EXPORT ISAM2Clique Base::FactorType::shared_ptr cachedFactor_; Vector gradientContribution_; +#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE mutable FastMap solnPointers_; +#endif /// Default constructor ISAM2Clique() : Base() {} From d401edc9175cee01c5307263c0ac60523ca1ec2f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 12:58:48 -0400 Subject: [PATCH 059/197] Split ISAM2 Clique, Params, and Result out in different files, cleaned up headers, and removed ISAM2-inl.h header --- gtsam/nonlinear/ISAM2-inl.h | 34 -- gtsam/nonlinear/ISAM2.cpp | 384 +------------------- gtsam/nonlinear/ISAM2.h | 612 +------------------------------- gtsam/nonlinear/ISAM2Clique.cpp | 302 ++++++++++++++++ gtsam/nonlinear/ISAM2Clique.h | 157 ++++++++ gtsam/nonlinear/ISAM2Params.cpp | 89 +++++ gtsam/nonlinear/ISAM2Params.h | 365 +++++++++++++++++++ gtsam/nonlinear/ISAM2Result.h | 159 +++++++++ 8 files changed, 1103 insertions(+), 999 deletions(-) delete mode 100644 gtsam/nonlinear/ISAM2-inl.h create mode 100644 gtsam/nonlinear/ISAM2Clique.cpp create mode 100644 gtsam/nonlinear/ISAM2Clique.h create mode 100644 gtsam/nonlinear/ISAM2Params.cpp create mode 100644 gtsam/nonlinear/ISAM2Params.h create mode 100644 gtsam/nonlinear/ISAM2Result.h diff --git a/gtsam/nonlinear/ISAM2-inl.h b/gtsam/nonlinear/ISAM2-inl.h deleted file mode 100644 index fb63dc428..000000000 --- a/gtsam/nonlinear/ISAM2-inl.h +++ /dev/null @@ -1,34 +0,0 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file ISAM2-inl.h - * @brief - * @author Richard Roberts - * @date Mar 16, 2012 - */ - -#pragma once - -#include - -namespace gtsam { - -/* ************************************************************************* */ -template -VALUE ISAM2::calculateEstimate(Key key) const { - const Vector& delta = getDelta()[key]; - return traits::Retract(theta_.at(key), delta); -} - -/* ************************************************************************* */ - -} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index f2b154cc4..e543508b2 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -10,22 +10,21 @@ * -------------------------------------------------------------------------- */ /** - * @file ISAM2-inl.h + * @file ISAM2.cpp * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid * relinearization. - * @author Michael Kaess, Richard Roberts + * @author Michael Kaess, Richard Roberts, Frank Dellaert */ #include -#include -#include -#include -#include +#include +#include +#include +#include // We need the inst file because we'll make a special JT templated on ISAM2 +#include +#include -#include // for operator += -using namespace boost::assign; -#include #include #include namespace br { @@ -33,30 +32,19 @@ using namespace boost::range; using namespace boost::adaptors; } // namespace br -#include -#include -#include -#include -#include // We need the inst file because we'll make a special JT templated on ISAM2 -#include -#include -#include -#include - -#include -#include -#include +#include +#include +#include using namespace std; namespace gtsam { -// Instantiate base classes -template class BayesTreeCliqueBase; +// Instantiate base class template class BayesTree; -static const bool disableReordering = false; -static const double batchThreshold = 0.65; +static const bool kDisableReordering = false; +static const double kBatchThreshold = 0.65; /* ************************************************************************* */ // Special BayesTree class that uses ISAM2 cliques - this is the result of @@ -80,345 +68,10 @@ class ISAM2JunctionTree typedef ISAM2JunctionTree This; typedef boost::shared_ptr shared_ptr; - ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree) + explicit ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree) : Base(eliminationTree) {} }; -/* ************************************************************************* */ -string ISAM2DoglegParams::adaptationModeTranslator( - const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) - const { - string s; - switch (adaptationMode) { - case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: - s = "SEARCH_EACH_ITERATION"; - break; - case DoglegOptimizerImpl::ONE_STEP_PER_ITERATION: - s = "ONE_STEP_PER_ITERATION"; - break; - default: - s = "UNDEFINED"; - break; - } - return s; -} - -/* ************************************************************************* */ -DoglegOptimizerImpl::TrustRegionAdaptationMode -ISAM2DoglegParams::adaptationModeTranslator( - const string& adaptationMode) const { - string s = adaptationMode; - boost::algorithm::to_upper(s); - if (s == "SEARCH_EACH_ITERATION") - return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; - if (s == "ONE_STEP_PER_ITERATION") - return DoglegOptimizerImpl::ONE_STEP_PER_ITERATION; - - /* default is SEARCH_EACH_ITERATION */ - return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; -} - -/* ************************************************************************* */ -ISAM2Params::Factorization ISAM2Params::factorizationTranslator( - const string& str) { - string s = str; - boost::algorithm::to_upper(s); - if (s == "QR") return ISAM2Params::QR; - if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; - - /* default is CHOLESKY */ - return ISAM2Params::CHOLESKY; -} - -/* ************************************************************************* */ -string ISAM2Params::factorizationTranslator( - const ISAM2Params::Factorization& value) { - string s; - switch (value) { - case ISAM2Params::QR: - s = "QR"; - break; - case ISAM2Params::CHOLESKY: - s = "CHOLESKY"; - break; - default: - s = "UNDEFINED"; - break; - } - return s; -} - -/* ************************************************************************* */ -void ISAM2Clique::setEliminationResult( - const FactorGraphType::EliminationResult& eliminationResult) { - conditional_ = eliminationResult.first; - cachedFactor_ = eliminationResult.second; - // Compute gradient contribution - gradientContribution_.resize(conditional_->cols() - 1); - // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed - // reasons - gradientContribution_ << -conditional_->get_R().transpose() * - conditional_->get_d(), - -conditional_->get_S().transpose() * conditional_->get_d(); -} - -/* ************************************************************************* */ -bool ISAM2Clique::equals(const This& other, double tol) const { - return Base::equals(other) && - ((!cachedFactor_ && !other.cachedFactor_) || - (cachedFactor_ && other.cachedFactor_ && - cachedFactor_->equals(*other.cachedFactor_, tol))); -} - -/* ************************************************************************* */ -void ISAM2Clique::print(const string& s, const KeyFormatter& formatter) const { - Base::print(s, formatter); - if (cachedFactor_) - cachedFactor_->print(s + "Cached: ", formatter); - else - cout << s << "Cached empty" << endl; - if (gradientContribution_.rows() != 0) - gtsam::print(gradientContribution_, "Gradient contribution: "); -} - -/* ************************************************************************* */ -bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { - // if none of the variables in this clique (frontal and separator!) changed - // significantly, then by the running intersection property, none of the - // cliques in the children need to be processed - - // Are any clique variables part of the tree that has been redone? - bool dirty = replaced.exists(conditional_->frontals().front()); -#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) - for (Key frontal : conditional_->frontals()) { - assert(dirty == replaced.exists(frontal)); - } -#endif - - // If not, then has one of the separator variables changed significantly? - if (!dirty) { - for (Key parent : conditional_->parents()) { - if (changed.exists(parent)) { - dirty = true; - break; - } - } - } - return dirty; -} - -/* ************************************************************************* */ -/** - * Back-substitute - special version stores solution pointers in cliques for - * fast access. - */ -void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const { -#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE - // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, - // potentially refactor - - // Create solution part pointers if necessary and possible - necessary if - // solnPointers_ is empty, and possible if either we're a root, or we have - // a parent with valid solnPointers_. - ISAM2::sharedClique parent = parent_.lock(); - if (solnPointers_.empty() && (isRoot() || !parent->solnPointers_.empty())) { - for (Key frontal : conditional_->frontals()) - solnPointers_.emplace(frontal, delta->find(frontal)); - for (Key parentKey : conditional_->parents()) { - assert(parent->solnPointers_.exists(parentKey)); - solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey)); - } - } - - // See if we can use solution part pointers - we can if they either - // already existed or were created above. - if (!solnPointers_.empty()) { - GaussianConditional& c = *conditional_; - // Solve matrix - Vector xS; - { - // Count dimensions of vector - DenseIndex dim = 0; - FastVector parentPointers; - parentPointers.reserve(conditional_->nrParents()); - for (Key parent : conditional_->parents()) { - parentPointers.push_back(solnPointers_.at(parent)); - dim += parentPointers.back()->second.size(); - } - - // Fill parent vector - xS.resize(dim); - DenseIndex vectorPos = 0; - for (const VectorValues::const_iterator& parentPointer : parentPointers) { - const Vector& parentVector = parentPointer->second; - xS.block(vectorPos, 0, parentVector.size(), 1) = - parentVector.block(0, 0, parentVector.size(), 1); - vectorPos += parentVector.size(); - } - } - - // NOTE(gareth): We can no longer write: xS = b - S * xS - // This is because Eigen (as of 3.3) no longer evaluates S * xS into - // a temporary, and the operation trashes valus in xS. - // See: http://eigen.tuxfamily.org/index.php?title=3.3 - const Vector rhs = c.getb() - c.get_S() * xS; - const Vector solution = c.get_R().triangularView().solve(rhs); - - // Check for indeterminant solution - if (solution.hasNaN()) - throw IndeterminantLinearSystemException(c.keys().front()); - - // Insert solution into a VectorValues - DenseIndex vectorPosition = 0; - for (GaussianConditional::const_iterator frontal = c.beginFrontals(); - frontal != c.endFrontals(); ++frontal) { - solnPointers_.at(*frontal)->second = - solution.segment(vectorPosition, c.getDim(frontal)); - vectorPosition += c.getDim(frontal); - } - } else { - // Just call plain solve because we couldn't use solution pointers. - delta->update(conditional_->solve(*delta)); - } -#else - delta->update(conditional_->solve(*delta)); -#endif -} - -/* ************************************************************************* */ -bool ISAM2Clique::valuesChanged(const KeySet& replaced, - const Vector& originalValues, - const VectorValues& delta, - double threshold) const { - auto frontals = conditional_->frontals(); - if (replaced.exists(frontals.front())) return true; - auto diff = originalValues - delta.vector(frontals); - return diff.lpNorm() >= threshold; -} - -/* ************************************************************************* */ -/// Set changed flag for each frontal variable -void ISAM2Clique::markFrontalsAsChanged(KeySet* changed) const { - for (Key frontal : conditional_->frontals()) { - changed->insert(frontal); - } -} - -/* ************************************************************************* */ -void ISAM2Clique::restoreFromOriginals(const Vector& originalValues, - VectorValues* delta) const { - size_t pos = 0; - for (Key frontal : conditional_->frontals()) { - auto v = delta->at(frontal); - v = originalValues.segment(pos, v.size()); - pos += v.size(); - } -} - -/* ************************************************************************* */ -// Note: not being used right now in favor of non-recursive version below. -void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, - KeySet* changed, VectorValues* delta, - size_t* count) const { - if (isDirty(replaced, *changed)) { - // Temporary copy of the original values, to check how much they change - auto originalValues = delta->vector(conditional_->frontals()); - - // Back-substitute - fastBackSubstitute(delta); - count += conditional_->nrFrontals(); - - if (valuesChanged(replaced, originalValues, *delta, threshold)) { - markFrontalsAsChanged(changed); - } else { - restoreFromOriginals(originalValues, delta); - } - - // Recurse to children - for (const auto& child : children) { - child->optimizeWildfire(replaced, threshold, changed, delta, count); - } - } -} - -size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, - const KeySet& keys, VectorValues* delta) { - KeySet changed; - size_t count = 0; - // starting from the root, call optimize on each conditional - if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count); - return count; -} - -/* ************************************************************************* */ -bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, - KeySet* changed, VectorValues* delta, - size_t* count) const { - // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, - // potentially refactor - bool dirty = isDirty(replaced, *changed); - if (dirty) { - // Temporary copy of the original values, to check how much they change - auto originalValues = delta->vector(conditional_->frontals()); - - // Back-substitute - fastBackSubstitute(delta); - count += conditional_->nrFrontals(); - - if (valuesChanged(replaced, originalValues, *delta, threshold)) { - markFrontalsAsChanged(changed); - } else { - restoreFromOriginals(originalValues, delta); - } - } - - return dirty; -} - -size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, - double threshold, const KeySet& keys, - VectorValues* delta) { - KeySet changed; - size_t count = 0; - - if (root) { - std::stack travStack; - travStack.push(root); - ISAM2::sharedClique currentNode = root; - while (!travStack.empty()) { - currentNode = travStack.top(); - travStack.pop(); - bool dirty = currentNode->optimizeWildfireNode(keys, threshold, &changed, - delta, &count); - if (dirty) { - for (const auto& child : currentNode->children) { - travStack.push(child); - } - } - } - } - - return count; -} - -/* ************************************************************************* */ -void ISAM2Clique::nnz_internal(size_t* result) const { - size_t dimR = conditional_->rows(); - size_t dimSep = conditional_->get_S().cols(); - *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR; - // traverse the children - for (const auto& child : children) { - child->nnz_internal(result); - } -} - -/* ************************************************************************* */ -size_t ISAM2Clique::calculate_nnz() const { - size_t result = 0; - nnz_internal(&result); - return result; -} - /* ************************************************************************* */ ISAM2::ISAM2(const ISAM2Params& params) : params_(params), update_count_(0) { if (params_.optimizationParams.type() == typeid(ISAM2DoglegParams)) @@ -622,7 +275,7 @@ boost::shared_ptr ISAM2::recalculate( boost::shared_ptr affectedKeysSet( new KeySet()); // Will return this result - if (affectedKeys.size() >= theta_.size() * batchThreshold) { + if (affectedKeys.size() >= theta_.size() * kBatchThreshold) { // Do a batch step - reorder and relinearize all variables gttic(batch); @@ -867,7 +520,7 @@ ISAM2Result ISAM2::update( // Update delta if we need it to check relinearization later if (relinearizeThisStep) { gttic(updateDelta); - updateDelta(disableReordering); + updateDelta(kDisableReordering); gttoc(updateDelta); } @@ -982,7 +635,7 @@ ISAM2Result ISAM2::update( else relinKeys = Impl::CheckRelinearizationFull(delta_, params_.relinearizeThreshold); - if (disableReordering) + if (kDisableReordering) relinKeys = Impl::CheckRelinearizationFull( delta_, 0.0); // This is used for debugging @@ -1485,4 +1138,3 @@ VectorValues ISAM2::gradientAtZero() const { } } // namespace gtsam -/// namespace gtsam diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index eb33038a7..069d90cc8 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -13,593 +13,23 @@ * @file ISAM2.h * @brief Incremental update functionality (ISAM2) for BayesTree, with fluid * relinearization. - * @author Michael Kaess, Richard Roberts + * @author Michael Kaess, Richard Roberts, Frank Dellaert */ // \callgraph #pragma once -#include +#include +#include +#include +#include +#include + #include -#include -#include -#include - -#include - namespace gtsam { -/** - * @addtogroup ISAM2 - * Parameters for ISAM2 using Gauss-Newton optimization. Either this class or - * ISAM2DoglegParams should be specified as the optimizationParams in - * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). - */ -struct GTSAM_EXPORT ISAM2GaussNewtonParams { - double - wildfireThreshold; ///< Continue updating the linear delta only when - ///< changes are above this threshold (default: 0.001) - - /** Specify parameters as constructor arguments */ - ISAM2GaussNewtonParams( - double _wildfireThreshold = - 0.001 ///< see ISAM2GaussNewtonParams public variables, - ///< ISAM2GaussNewtonParams::wildfireThreshold - ) - : wildfireThreshold(_wildfireThreshold) {} - - void print(const std::string str = "") const { - using std::cout; - cout << str << "type: ISAM2GaussNewtonParams\n"; - cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; - cout.flush(); - } - - double getWildfireThreshold() const { return wildfireThreshold; } - void setWildfireThreshold(double wildfireThreshold) { - this->wildfireThreshold = wildfireThreshold; - } -}; - -/** - * @addtogroup ISAM2 - * Parameters for ISAM2 using Dogleg optimization. Either this class or - * ISAM2GaussNewtonParams should be specified as the optimizationParams in - * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). - */ -struct GTSAM_EXPORT ISAM2DoglegParams { - double initialDelta; ///< The initial trust region radius for Dogleg - double - wildfireThreshold; ///< Continue updating the linear delta only when - ///< changes are above this threshold (default: 1e-5) - DoglegOptimizerImpl::TrustRegionAdaptationMode - adaptationMode; ///< See description in - ///< DoglegOptimizerImpl::TrustRegionAdaptationMode - bool - verbose; ///< Whether Dogleg prints iteration and convergence information - - /** Specify parameters as constructor arguments */ - ISAM2DoglegParams( - double _initialDelta = 1.0, ///< see ISAM2DoglegParams::initialDelta - double _wildfireThreshold = - 1e-5, ///< see ISAM2DoglegParams::wildfireThreshold - DoglegOptimizerImpl::TrustRegionAdaptationMode _adaptationMode = - DoglegOptimizerImpl:: - SEARCH_EACH_ITERATION, ///< see ISAM2DoglegParams::adaptationMode - bool _verbose = false ///< see ISAM2DoglegParams::verbose - ) - : initialDelta(_initialDelta), - wildfireThreshold(_wildfireThreshold), - adaptationMode(_adaptationMode), - verbose(_verbose) {} - - void print(const std::string str = "") const { - using std::cout; - cout << str << "type: ISAM2DoglegParams\n"; - cout << str << "initialDelta: " << initialDelta << "\n"; - cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; - cout << str - << "adaptationMode: " << adaptationModeTranslator(adaptationMode) - << "\n"; - cout.flush(); - } - - double getInitialDelta() const { return initialDelta; } - double getWildfireThreshold() const { return wildfireThreshold; } - std::string getAdaptationMode() const { - return adaptationModeTranslator(adaptationMode); - } - bool isVerbose() const { return verbose; } - void setInitialDelta(double initialDelta) { - this->initialDelta = initialDelta; - } - void setWildfireThreshold(double wildfireThreshold) { - this->wildfireThreshold = wildfireThreshold; - } - void setAdaptationMode(const std::string& adaptationMode) { - this->adaptationMode = adaptationModeTranslator(adaptationMode); - } - void setVerbose(bool verbose) { this->verbose = verbose; } - - std::string adaptationModeTranslator( - const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) - const; - DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator( - const std::string& adaptationMode) const; -}; - -/** - * @addtogroup ISAM2 - * Parameters for the ISAM2 algorithm. Default parameter values are listed - * below. - */ -typedef FastMap ISAM2ThresholdMap; -typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue; -struct GTSAM_EXPORT ISAM2Params { - typedef boost::variant - OptimizationParams; ///< Either ISAM2GaussNewtonParams or - ///< ISAM2DoglegParams - typedef boost::variant > - RelinearizationThreshold; ///< Either a constant relinearization - ///< threshold or a per-variable-type set of - ///< thresholds - - /** Optimization parameters, this both selects the nonlinear optimization - * method and specifies its parameters, either ISAM2GaussNewtonParams or - * ISAM2DoglegParams. In the former, Gauss-Newton optimization will be used - * with the specified parameters, and in the latter Powell's dog-leg - * algorithm will be used with the specified parameters. - */ - OptimizationParams optimizationParams; - - /** Only relinearize variables whose linear delta magnitude is greater than - * this threshold (default: 0.1). If this is a FastMap instead - * of a double, then the threshold is specified for each dimension of each - * variable type. This parameter then maps from a character indicating the - * variable type to a Vector of thresholds for each dimension of that - * variable. For example, if Pose keys are of type TypedSymbol<'x',Pose3>, - * and landmark keys are of type TypedSymbol<'l',Point3>, then appropriate - * entries would be added with: - * \code - FastMap thresholds; - thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5).finished(); - // 0.1 rad rotation threshold, 0.5 m translation threshold thresholds['l'] = - Vector3(1.0, 1.0, 1.0); // 1.0 m landmark position threshold - params.relinearizeThreshold = thresholds; - \endcode - */ - RelinearizationThreshold relinearizeThreshold; - - int relinearizeSkip; ///< Only relinearize any variables every - ///< relinearizeSkip calls to ISAM2::update (default: - ///< 10) - - bool enableRelinearization; ///< Controls whether ISAM2 will ever relinearize - ///< any variables (default: true) - - bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error - ///< before and after the update, to return in - ///< ISAM2Result from update() - - enum Factorization { CHOLESKY, QR }; - /** Specifies whether to use QR or CHOESKY numerical factorization (default: - * CHOLESKY). Cholesky is faster but potentially numerically unstable for - * poorly-conditioned problems, which can occur when uncertainty is very low - * in some variables (or dimensions of variables) and very high in others. QR - * is slower but more numerically stable in poorly-conditioned problems. We - * suggest using the default of Cholesky unless gtsam sometimes throws - * IndefiniteLinearSystemException when your problem's Hessian is actually - * positive definite. For positive definite problems, numerical error - * accumulation can cause the problem to become numerically negative or - * indefinite as solving proceeds, especially when using Cholesky. - */ - Factorization factorization; - - /** Whether to cache linear factors (default: true). - * This can improve performance if linearization is expensive, but can hurt - * performance if linearization is very cleap due to computation to look up - * additional keys. - */ - bool cacheLinearizedFactors; - - KeyFormatter - keyFormatter; ///< A KeyFormatter for when keys are printed during - ///< debugging (default: DefaultKeyFormatter) - - bool enableDetailedResults; ///< Whether to compute and return - ///< ISAM2Result::detailedResults, this can - ///< increase running time (default: false) - - /** Check variables for relinearization in tree-order, stopping the check once - * a variable does not need to be relinearized (default: false). This can - * improve speed by only checking a small part of the top of the tree. - * However, variables below the check cut-off can accumulate significant - * deltas without triggering relinearization. This is particularly useful in - * exploration scenarios where real-time performance is desired over - * correctness. Use with caution. - */ - bool enablePartialRelinearizationCheck; - - /// When you will be removing many factors, e.g. when using ISAM2 as a - /// fixed-lag smoother, enable this option to add factors in the first - /// available factor slots, to avoid accumulating NULL factor slots, at the - /// cost of having to search for slots every time a factor is added. - bool findUnusedFactorSlots; - - /** - * Specify parameters as constructor arguments - * See the documentation of member variables above. - */ - ISAM2Params(OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), - RelinearizationThreshold _relinearizeThreshold = 0.1, - int _relinearizeSkip = 10, bool _enableRelinearization = true, - bool _evaluateNonlinearError = false, - Factorization _factorization = ISAM2Params::CHOLESKY, - bool _cacheLinearizedFactors = true, - const KeyFormatter& _keyFormatter = - DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter - ) - : optimizationParams(_optimizationParams), - relinearizeThreshold(_relinearizeThreshold), - relinearizeSkip(_relinearizeSkip), - enableRelinearization(_enableRelinearization), - evaluateNonlinearError(_evaluateNonlinearError), - factorization(_factorization), - cacheLinearizedFactors(_cacheLinearizedFactors), - keyFormatter(_keyFormatter), - enableDetailedResults(false), - enablePartialRelinearizationCheck(false), - findUnusedFactorSlots(false) {} - - /// print iSAM2 parameters - void print(const std::string& str = "") const { - using std::cout; - cout << str << "\n"; - - static const std::string kStr("optimizationParams: "); - if (optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) - boost::get(optimizationParams).print(); - else if (optimizationParams.type() == typeid(ISAM2DoglegParams)) - boost::get(optimizationParams).print(kStr); - else - cout << kStr << "{unknown type}\n"; - - cout << "relinearizeThreshold: "; - if (relinearizeThreshold.type() == typeid(double)) { - cout << boost::get(relinearizeThreshold) << "\n"; - } else { - cout << "{mapped}\n"; - for (const ISAM2ThresholdMapValue& value : - boost::get(relinearizeThreshold)) { - cout << " '" << value.first - << "' -> [" << value.second.transpose() << " ]\n"; - } - } - - cout << "relinearizeSkip: " << relinearizeSkip << "\n"; - cout << "enableRelinearization: " << enableRelinearization - << "\n"; - cout << "evaluateNonlinearError: " << evaluateNonlinearError - << "\n"; - cout << "factorization: " - << factorizationTranslator(factorization) << "\n"; - cout << "cacheLinearizedFactors: " << cacheLinearizedFactors - << "\n"; - cout << "enableDetailedResults: " << enableDetailedResults - << "\n"; - cout << "enablePartialRelinearizationCheck: " - << enablePartialRelinearizationCheck << "\n"; - cout << "findUnusedFactorSlots: " << findUnusedFactorSlots - << "\n"; - cout.flush(); - } - - /// @name Getters and Setters for all properties - /// @{ - - OptimizationParams getOptimizationParams() const { - return this->optimizationParams; - } - RelinearizationThreshold getRelinearizeThreshold() const { - return relinearizeThreshold; - } - int getRelinearizeSkip() const { return relinearizeSkip; } - bool isEnableRelinearization() const { return enableRelinearization; } - bool isEvaluateNonlinearError() const { return evaluateNonlinearError; } - std::string getFactorization() const { - return factorizationTranslator(factorization); - } - bool isCacheLinearizedFactors() const { return cacheLinearizedFactors; } - KeyFormatter getKeyFormatter() const { return keyFormatter; } - bool isEnableDetailedResults() const { return enableDetailedResults; } - bool isEnablePartialRelinearizationCheck() const { - return enablePartialRelinearizationCheck; - } - - void setOptimizationParams(OptimizationParams optimizationParams) { - this->optimizationParams = optimizationParams; - } - void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) { - this->relinearizeThreshold = relinearizeThreshold; - } - void setRelinearizeSkip(int relinearizeSkip) { - this->relinearizeSkip = relinearizeSkip; - } - void setEnableRelinearization(bool enableRelinearization) { - this->enableRelinearization = enableRelinearization; - } - void setEvaluateNonlinearError(bool evaluateNonlinearError) { - this->evaluateNonlinearError = evaluateNonlinearError; - } - void setFactorization(const std::string& factorization) { - this->factorization = factorizationTranslator(factorization); - } - void setCacheLinearizedFactors(bool cacheLinearizedFactors) { - this->cacheLinearizedFactors = cacheLinearizedFactors; - } - void setKeyFormatter(KeyFormatter keyFormatter) { - this->keyFormatter = keyFormatter; - } - void setEnableDetailedResults(bool enableDetailedResults) { - this->enableDetailedResults = enableDetailedResults; - } - void setEnablePartialRelinearizationCheck( - bool enablePartialRelinearizationCheck) { - this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; - } - - GaussianFactorGraph::Eliminate getEliminationFunction() const { - return factorization == CHOLESKY - ? (GaussianFactorGraph::Eliminate)EliminatePreferCholesky - : (GaussianFactorGraph::Eliminate)EliminateQR; - } - - /// @} - - /// @name Some utilities - /// @{ - - static Factorization factorizationTranslator(const std::string& str); - static std::string factorizationTranslator(const Factorization& value); - - /// @} -}; - -typedef FastVector FactorIndices; - -/** - * @addtogroup ISAM2 - * This struct is returned from ISAM2::update() and contains information about - * the update that is useful for determining whether the solution is - * converging, and about how much work was required for the update. See member - * variables for details and information about each entry. - */ -struct GTSAM_EXPORT ISAM2Result { - /** The nonlinear error of all of the factors, \a including new factors and - * variables added during the current call to ISAM2::update(). This error is - * calculated using the following variable values: - * \li Pre-existing variables will be evaluated by combining their - * linearization point before this call to update, with their partial linear - * delta, as computed by ISAM2::calculateEstimate(). - * \li New variables will be evaluated at their initialization points passed - * into the current call to update. - * \par Note: This will only be computed if - * ISAM2Params::evaluateNonlinearError is set to \c true, because there is - * some cost to this computation. - */ - boost::optional errorBefore; - - /** The nonlinear error of all of the factors computed after the current - * update, meaning that variables above the relinearization threshold - * (ISAM2Params::relinearizeThreshold) have been relinearized and new - * variables have undergone one linear update. Variable values are - * again computed by combining their linearization points with their - * partial linear deltas, by ISAM2::calculateEstimate(). - * \par Note: This will only be computed if - * ISAM2Params::evaluateNonlinearError is set to \c true, because there is - * some cost to this computation. - */ - boost::optional errorAfter; - - /** The number of variables that were relinearized because their linear - * deltas exceeded the reslinearization threshold - * (ISAM2Params::relinearizeThreshold), combined with any additional - * variables that had to be relinearized because they were involved in - * the same factor as a variable above the relinearization threshold. - * On steps where no relinearization is considered - * (see ISAM2Params::relinearizeSkip), this count will be zero. - */ - size_t variablesRelinearized; - - /** The number of variables that were reeliminated as parts of the Bayes' - * Tree were recalculated, due to new factors. When loop closures occur, - * this count will be large as the new loop-closing factors will tend to - * involve variables far away from the root, and everything up to the root - * will be reeliminated. - */ - size_t variablesReeliminated; - - /** The number of factors that were included in reelimination of the Bayes' - * tree. */ - size_t factorsRecalculated; - - /** The number of cliques in the Bayes' Tree */ - size_t cliques; - - /** The indices of the newly-added factors, in 1-to-1 correspondence with the - * factors passed as \c newFactors to ISAM2::update(). These indices may be - * used later to refer to the factors in order to remove them. - */ - FactorIndices newFactorsIndices; - - /** A struct holding detailed results, which must be enabled with - * ISAM2Params::enableDetailedResults. - */ - struct DetailedResults { - /** The status of a single variable, this struct is stored in - * DetailedResults::variableStatus */ - struct VariableStatus { - /** Whether the variable was just reeliminated, due to being relinearized, - * observed, new, or on the path up to the root clique from another - * reeliminated variable. */ - bool isReeliminated; - bool isAboveRelinThreshold; ///< Whether the variable was just - ///< relinearized due to being above the - ///< relinearization threshold - bool isRelinearizeInvolved; ///< Whether the variable was below the - ///< relinearization threshold but was - ///< relinearized by being involved in a - ///< factor with a variable above the - ///< relinearization threshold - bool isRelinearized; /// Whether the variable was relinearized, either by - /// being above the relinearization threshold or by - /// involvement. - bool isObserved; ///< Whether the variable was just involved in new - ///< factors - bool isNew; ///< Whether the variable itself was just added - bool inRootClique; ///< Whether the variable is in the root clique - VariableStatus() - : isReeliminated(false), - isAboveRelinThreshold(false), - isRelinearizeInvolved(false), - isRelinearized(false), - isObserved(false), - isNew(false), - inRootClique(false) {} - }; - - /** The status of each variable during this update, see VariableStatus. - */ - FastMap variableStatus; - }; - - /** Detailed results, if enabled by ISAM2Params::enableDetailedResults. See - * Detail for information about the results data stored here. */ - boost::optional detail; - - void print(const std::string str = "") const { - using std::cout; - cout << str << " Reelimintated: " << variablesReeliminated - << " Relinearized: " << variablesRelinearized - << " Cliques: " << cliques << std::endl; - } - - /** Getters and Setters */ - size_t getVariablesRelinearized() const { return variablesRelinearized; } - size_t getVariablesReeliminated() const { return variablesReeliminated; } - size_t getCliques() const { return cliques; } -}; - -/** - * Specialized Clique structure for ISAM2, incorporating caching and gradient - * contribution - * TODO: more documentation - */ -class GTSAM_EXPORT ISAM2Clique - : public BayesTreeCliqueBase { - public: - typedef ISAM2Clique This; - typedef BayesTreeCliqueBase Base; - typedef boost::shared_ptr shared_ptr; - typedef boost::weak_ptr weak_ptr; - typedef GaussianConditional ConditionalType; - typedef ConditionalType::shared_ptr sharedConditional; - - Base::FactorType::shared_ptr cachedFactor_; - Vector gradientContribution_; -#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE - mutable FastMap solnPointers_; -#endif - - /// Default constructor - ISAM2Clique() : Base() {} - - /// Copy constructor, does *not* copy solution pointers as these are invalid - /// in different trees. - ISAM2Clique(const ISAM2Clique& other) - : Base(other), - cachedFactor_(other.cachedFactor_), - gradientContribution_(other.gradientContribution_) {} - - /// Assignment operator, does *not* copy solution pointers as these are - /// invalid in different trees. - ISAM2Clique& operator=(const ISAM2Clique& other) { - Base::operator=(other); - cachedFactor_ = other.cachedFactor_; - gradientContribution_ = other.gradientContribution_; - return *this; - } - - /// Overridden to also store the remaining factor and gradient contribution - void setEliminationResult( - const FactorGraphType::EliminationResult& eliminationResult); - - /** Access the cached factor */ - Base::FactorType::shared_ptr& cachedFactor() { return cachedFactor_; } - - /** Access the gradient contribution */ - const Vector& gradientContribution() const { return gradientContribution_; } - - bool equals(const This& other, double tol = 1e-9) const; - - /** print this node */ - void print(const std::string& s = "", - const KeyFormatter& formatter = DefaultKeyFormatter) const; - - void optimizeWildfire(const KeySet& replaced, double threshold, - KeySet* changed, VectorValues* delta, - size_t* count) const; - - bool optimizeWildfireNode(const KeySet& replaced, double threshold, - KeySet* changed, VectorValues* delta, - size_t* count) const; - - /** - * Starting from the root, add up entries of frontal and conditional matrices - * of each conditional - */ - void nnz_internal(size_t* result) const; - size_t calculate_nnz() const; - - private: - /** - * Check if clique was replaced, or if any parents were changed above the - * threshold or themselves replaced. - */ - bool isDirty(const KeySet& replaced, const KeySet& changed) const; - - /** - * Back-substitute - special version stores solution pointers in cliques for - * fast access. - */ - void fastBackSubstitute(VectorValues* delta) const; - - /* - * Check whether the values changed above a threshold, or always true if the - * clique was replaced. - */ - bool valuesChanged(const KeySet& replaced, const Vector& originalValues, - const VectorValues& delta, double threshold) const; - - /// Set changed flag for each frontal variable - void markFrontalsAsChanged(KeySet* changed) const; - - /// Restore delta to original values, guided by frontal keys. - void restoreFromOriginals(const Vector& originalValues, - VectorValues* delta) const; - - /** Serialization function */ - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); - ar& BOOST_SERIALIZATION_NVP(cachedFactor_); - ar& BOOST_SERIALIZATION_NVP(gradientContribution_); - } -}; // \struct ISAM2Clique - /** * @addtogroup ISAM2 * Implementation of the full ISAM2 algorithm for incremental nonlinear @@ -643,7 +73,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { * until it is needed. */ mutable KeySet - deltaReplacedMask_; // TODO: Make sure accessed in the right way + deltaReplacedMask_; // TODO(dellaert): Make sure accessed in the right way /** All original nonlinear factors are stored here to use during * relinearization */ @@ -768,7 +198,11 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { * @return */ template - VALUE calculateEstimate(Key key) const; + VALUE calculateEstimate(Key key) const { + const Vector& delta = getDelta()[key]; + return traits::Retract(theta_.at(key), delta); + } + /** Compute an estimate for a single variable using its incomplete linear * delta computed during the last update. This is faster than calling the @@ -846,32 +280,12 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { const boost::optional >& constrainKeys, ISAM2Result& result); void updateDelta(bool forceFullSolve = false) const; - }; // ISAM2 /// traits template <> struct traits : public Testable {}; -/** - * Optimize the BayesTree, starting from the root. - * @param threshold The maximum change against the PREVIOUS delta for - * non-replaced variables that can be ignored, ie. the old delta entry is kept - * and recursive backsubstitution might eventually stop if none of the changed - * variables are contained in the subtree. - * @param replaced Needs to contain all variables that are contained in the top - * of the Bayes tree that has been redone. - * @return The number of variables that were solved for. - * @param delta The current solution, an offset from the linearization point. - */ -size_t optimizeWildfire(const ISAM2::sharedClique& root, double threshold, - const KeySet& replaced, VectorValues* delta); - -size_t optimizeWildfireNonRecursive(const ISAM2::sharedClique& root, - double threshold, const KeySet& replaced, - VectorValues* delta); - } // namespace gtsam #include -#include diff --git a/gtsam/nonlinear/ISAM2Clique.cpp b/gtsam/nonlinear/ISAM2Clique.cpp new file mode 100644 index 000000000..6e03b0680 --- /dev/null +++ b/gtsam/nonlinear/ISAM2Clique.cpp @@ -0,0 +1,302 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ISAM2Clique.cpp + * @brief Specialized iSAM2 Clique + * @author Michael Kaess, Richard Roberts, Frank Dellaert + */ + +#include +#include +#include +#include +#include + +using namespace std; + +namespace gtsam { + +// Instantiate base class +template class BayesTreeCliqueBase; + +/* ************************************************************************* */ +void ISAM2Clique::setEliminationResult( + const FactorGraphType::EliminationResult& eliminationResult) { + conditional_ = eliminationResult.first; + cachedFactor_ = eliminationResult.second; + // Compute gradient contribution + gradientContribution_.resize(conditional_->cols() - 1); + // Rewrite -(R * P')'*d as -(d' * R * P')' for computational speed + // reasons + gradientContribution_ << -conditional_->get_R().transpose() * + conditional_->get_d(), + -conditional_->get_S().transpose() * conditional_->get_d(); +} + +/* ************************************************************************* */ +bool ISAM2Clique::equals(const This& other, double tol) const { + return Base::equals(other) && + ((!cachedFactor_ && !other.cachedFactor_) || + (cachedFactor_ && other.cachedFactor_ && + cachedFactor_->equals(*other.cachedFactor_, tol))); +} + +/* ************************************************************************* */ +void ISAM2Clique::print(const string& s, const KeyFormatter& formatter) const { + Base::print(s, formatter); + if (cachedFactor_) + cachedFactor_->print(s + "Cached: ", formatter); + else + cout << s << "Cached empty" << endl; + if (gradientContribution_.rows() != 0) + gtsam::print(gradientContribution_, "Gradient contribution: "); +} + +/* ************************************************************************* */ +bool ISAM2Clique::isDirty(const KeySet& replaced, const KeySet& changed) const { + // if none of the variables in this clique (frontal and separator!) changed + // significantly, then by the running intersection property, none of the + // cliques in the children need to be processed + + // Are any clique variables part of the tree that has been redone? + bool dirty = replaced.exists(conditional_->frontals().front()); +#if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS) + for (Key frontal : conditional_->frontals()) { + assert(dirty == replaced.exists(frontal)); + } +#endif + + // If not, then has one of the separator variables changed significantly? + if (!dirty) { + for (Key parent : conditional_->parents()) { + if (changed.exists(parent)) { + dirty = true; + break; + } + } + } + return dirty; +} + +/* ************************************************************************* */ +/** + * Back-substitute - special version stores solution pointers in cliques for + * fast access. + */ +void ISAM2Clique::fastBackSubstitute(VectorValues* delta) const { +#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE + // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, + // potentially refactor + + // Create solution part pointers if necessary and possible - necessary if + // solnPointers_ is empty, and possible if either we're a root, or we have + // a parent with valid solnPointers_. + ISAM2Clique::shared_ptr parent = parent_.lock(); + if (solnPointers_.empty() && (isRoot() || !parent->solnPointers_.empty())) { + for (Key frontal : conditional_->frontals()) + solnPointers_.emplace(frontal, delta->find(frontal)); + for (Key parentKey : conditional_->parents()) { + assert(parent->solnPointers_.exists(parentKey)); + solnPointers_.emplace(parentKey, parent->solnPointers_.at(parentKey)); + } + } + + // See if we can use solution part pointers - we can if they either + // already existed or were created above. + if (!solnPointers_.empty()) { + GaussianConditional& c = *conditional_; + // Solve matrix + Vector xS; + { + // Count dimensions of vector + DenseIndex dim = 0; + FastVector parentPointers; + parentPointers.reserve(conditional_->nrParents()); + for (Key parent : conditional_->parents()) { + parentPointers.push_back(solnPointers_.at(parent)); + dim += parentPointers.back()->second.size(); + } + + // Fill parent vector + xS.resize(dim); + DenseIndex vectorPos = 0; + for (const VectorValues::const_iterator& parentPointer : parentPointers) { + const Vector& parentVector = parentPointer->second; + xS.block(vectorPos, 0, parentVector.size(), 1) = + parentVector.block(0, 0, parentVector.size(), 1); + vectorPos += parentVector.size(); + } + } + + // NOTE(gareth): We can no longer write: xS = b - S * xS + // This is because Eigen (as of 3.3) no longer evaluates S * xS into + // a temporary, and the operation trashes valus in xS. + // See: http://eigen.tuxfamily.org/index.php?title=3.3 + const Vector rhs = c.getb() - c.get_S() * xS; + const Vector solution = c.get_R().triangularView().solve(rhs); + + // Check for indeterminant solution + if (solution.hasNaN()) + throw IndeterminantLinearSystemException(c.keys().front()); + + // Insert solution into a VectorValues + DenseIndex vectorPosition = 0; + for (GaussianConditional::const_iterator frontal = c.beginFrontals(); + frontal != c.endFrontals(); ++frontal) { + solnPointers_.at(*frontal)->second = + solution.segment(vectorPosition, c.getDim(frontal)); + vectorPosition += c.getDim(frontal); + } + } else { + // Just call plain solve because we couldn't use solution pointers. + delta->update(conditional_->solve(*delta)); + } +#else + delta->update(conditional_->solve(*delta)); +#endif +} + +/* ************************************************************************* */ +bool ISAM2Clique::valuesChanged(const KeySet& replaced, + const Vector& originalValues, + const VectorValues& delta, + double threshold) const { + auto frontals = conditional_->frontals(); + if (replaced.exists(frontals.front())) return true; + auto diff = originalValues - delta.vector(frontals); + return diff.lpNorm() >= threshold; +} + +/* ************************************************************************* */ +/// Set changed flag for each frontal variable +void ISAM2Clique::markFrontalsAsChanged(KeySet* changed) const { + for (Key frontal : conditional_->frontals()) { + changed->insert(frontal); + } +} + +/* ************************************************************************* */ +void ISAM2Clique::restoreFromOriginals(const Vector& originalValues, + VectorValues* delta) const { + size_t pos = 0; + for (Key frontal : conditional_->frontals()) { + auto v = delta->at(frontal); + v = originalValues.segment(pos, v.size()); + pos += v.size(); + } +} + +/* ************************************************************************* */ +// Note: not being used right now in favor of non-recursive version below. +void ISAM2Clique::optimizeWildfire(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const { + if (isDirty(replaced, *changed)) { + // Temporary copy of the original values, to check how much they change + auto originalValues = delta->vector(conditional_->frontals()); + + // Back-substitute + fastBackSubstitute(delta); + count += conditional_->nrFrontals(); + + if (valuesChanged(replaced, originalValues, *delta, threshold)) { + markFrontalsAsChanged(changed); + } else { + restoreFromOriginals(originalValues, delta); + } + + // Recurse to children + for (const auto& child : children) { + child->optimizeWildfire(replaced, threshold, changed, delta, count); + } + } +} + +size_t optimizeWildfire(const ISAM2Clique::shared_ptr& root, double threshold, + const KeySet& keys, VectorValues* delta) { + KeySet changed; + size_t count = 0; + // starting from the root, call optimize on each conditional + if (root) root->optimizeWildfire(keys, threshold, &changed, delta, &count); + return count; +} + +/* ************************************************************************* */ +bool ISAM2Clique::optimizeWildfireNode(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const { + // TODO(gareth): This code shares a lot of logic w/ linearAlgorithms-inst, + // potentially refactor + bool dirty = isDirty(replaced, *changed); + if (dirty) { + // Temporary copy of the original values, to check how much they change + auto originalValues = delta->vector(conditional_->frontals()); + + // Back-substitute + fastBackSubstitute(delta); + count += conditional_->nrFrontals(); + + if (valuesChanged(replaced, originalValues, *delta, threshold)) { + markFrontalsAsChanged(changed); + } else { + restoreFromOriginals(originalValues, delta); + } + } + + return dirty; +} + +size_t optimizeWildfireNonRecursive(const ISAM2Clique::shared_ptr& root, + double threshold, const KeySet& keys, + VectorValues* delta) { + KeySet changed; + size_t count = 0; + + if (root) { + std::stack travStack; + travStack.push(root); + ISAM2Clique::shared_ptr currentNode = root; + while (!travStack.empty()) { + currentNode = travStack.top(); + travStack.pop(); + bool dirty = currentNode->optimizeWildfireNode(keys, threshold, &changed, + delta, &count); + if (dirty) { + for (const auto& child : currentNode->children) { + travStack.push(child); + } + } + } + } + + return count; +} + +/* ************************************************************************* */ +void ISAM2Clique::nnz_internal(size_t* result) const { + size_t dimR = conditional_->rows(); + size_t dimSep = conditional_->get_S().cols(); + *result += ((dimR + 1) * dimR) / 2 + dimSep * dimR; + // traverse the children + for (const auto& child : children) { + child->nnz_internal(result); + } +} + +/* ************************************************************************* */ +size_t ISAM2Clique::calculate_nnz() const { + size_t result = 0; + nnz_internal(&result); + return result; +} + +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h new file mode 100644 index 000000000..fecc8d335 --- /dev/null +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -0,0 +1,157 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ISAM2Clique.h + * @brief Specialized iSAM2 Clique + * @author Michael Kaess, Richard Roberts + */ + +// \callgraph + +#pragma once + +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +/** + * Specialized Clique structure for ISAM2, incorporating caching and gradient + * contribution + * TODO: more documentation + */ +class GTSAM_EXPORT ISAM2Clique + : public BayesTreeCliqueBase { + public: + typedef ISAM2Clique This; + typedef BayesTreeCliqueBase Base; + typedef boost::shared_ptr shared_ptr; + typedef boost::weak_ptr weak_ptr; + typedef GaussianConditional ConditionalType; + typedef ConditionalType::shared_ptr sharedConditional; + + Base::FactorType::shared_ptr cachedFactor_; + Vector gradientContribution_; +#ifdef USE_BROKEN_FAST_BACKSUBSTITUTE + mutable FastMap solnPointers_; +#endif + + /// Default constructor + ISAM2Clique() : Base() {} + + /// Copy constructor, does *not* copy solution pointers as these are invalid + /// in different trees. + ISAM2Clique(const ISAM2Clique& other) + : Base(other), + cachedFactor_(other.cachedFactor_), + gradientContribution_(other.gradientContribution_) {} + + /// Assignment operator, does *not* copy solution pointers as these are + /// invalid in different trees. + ISAM2Clique& operator=(const ISAM2Clique& other) { + Base::operator=(other); + cachedFactor_ = other.cachedFactor_; + gradientContribution_ = other.gradientContribution_; + return *this; + } + + /// Overridden to also store the remaining factor and gradient contribution + void setEliminationResult( + const FactorGraphType::EliminationResult& eliminationResult); + + /** Access the cached factor */ + Base::FactorType::shared_ptr& cachedFactor() { return cachedFactor_; } + + /** Access the gradient contribution */ + const Vector& gradientContribution() const { return gradientContribution_; } + + bool equals(const This& other, double tol = 1e-9) const; + + /** print this node */ + void print(const std::string& s = "", + const KeyFormatter& formatter = DefaultKeyFormatter) const; + + void optimizeWildfire(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const; + + bool optimizeWildfireNode(const KeySet& replaced, double threshold, + KeySet* changed, VectorValues* delta, + size_t* count) const; + + /** + * Starting from the root, add up entries of frontal and conditional matrices + * of each conditional + */ + void nnz_internal(size_t* result) const; + size_t calculate_nnz() const; + + private: + /** + * Check if clique was replaced, or if any parents were changed above the + * threshold or themselves replaced. + */ + bool isDirty(const KeySet& replaced, const KeySet& changed) const; + + /** + * Back-substitute - special version stores solution pointers in cliques for + * fast access. + */ + void fastBackSubstitute(VectorValues* delta) const; + + /* + * Check whether the values changed above a threshold, or always true if the + * clique was replaced. + */ + bool valuesChanged(const KeySet& replaced, const Vector& originalValues, + const VectorValues& delta, double threshold) const; + + /// Set changed flag for each frontal variable + void markFrontalsAsChanged(KeySet* changed) const; + + /// Restore delta to original values, guided by frontal keys. + void restoreFromOriginals(const Vector& originalValues, + VectorValues* delta) const; + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base); + ar& BOOST_SERIALIZATION_NVP(cachedFactor_); + ar& BOOST_SERIALIZATION_NVP(gradientContribution_); + } +}; // \struct ISAM2Clique + +/** + * Optimize the BayesTree, starting from the root. + * @param threshold The maximum change against the PREVIOUS delta for + * non-replaced variables that can be ignored, ie. the old delta entry is kept + * and recursive backsubstitution might eventually stop if none of the changed + * variables are contained in the subtree. + * @param replaced Needs to contain all variables that are contained in the top + * of the Bayes tree that has been redone. + * @return The number of variables that were solved for. + * @param delta The current solution, an offset from the linearization point. + */ +size_t optimizeWildfire(const ISAM2Clique::shared_ptr& root, double threshold, + const KeySet& replaced, VectorValues* delta); + +size_t optimizeWildfireNonRecursive(const ISAM2Clique::shared_ptr& root, + double threshold, const KeySet& replaced, + VectorValues* delta); + +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2Params.cpp b/gtsam/nonlinear/ISAM2Params.cpp new file mode 100644 index 000000000..c768ce427 --- /dev/null +++ b/gtsam/nonlinear/ISAM2Params.cpp @@ -0,0 +1,89 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ISAM2Params.cpp + * @brief Parameters for iSAM 2. + * @author Michael Kaess, Richard Roberts, Frank Dellaert + */ + +#include +#include + +using namespace std; + +namespace gtsam { + +/* ************************************************************************* */ +string ISAM2DoglegParams::adaptationModeTranslator( + const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) + const { + string s; + switch (adaptationMode) { + case DoglegOptimizerImpl::SEARCH_EACH_ITERATION: + s = "SEARCH_EACH_ITERATION"; + break; + case DoglegOptimizerImpl::ONE_STEP_PER_ITERATION: + s = "ONE_STEP_PER_ITERATION"; + break; + default: + s = "UNDEFINED"; + break; + } + return s; +} + +/* ************************************************************************* */ +DoglegOptimizerImpl::TrustRegionAdaptationMode +ISAM2DoglegParams::adaptationModeTranslator( + const string& adaptationMode) const { + string s = adaptationMode; + boost::algorithm::to_upper(s); + if (s == "SEARCH_EACH_ITERATION") + return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; + if (s == "ONE_STEP_PER_ITERATION") + return DoglegOptimizerImpl::ONE_STEP_PER_ITERATION; + + /* default is SEARCH_EACH_ITERATION */ + return DoglegOptimizerImpl::SEARCH_EACH_ITERATION; +} + +/* ************************************************************************* */ +ISAM2Params::Factorization ISAM2Params::factorizationTranslator( + const string& str) { + string s = str; + boost::algorithm::to_upper(s); + if (s == "QR") return ISAM2Params::QR; + if (s == "CHOLESKY") return ISAM2Params::CHOLESKY; + + /* default is CHOLESKY */ + return ISAM2Params::CHOLESKY; +} + +/* ************************************************************************* */ +string ISAM2Params::factorizationTranslator( + const ISAM2Params::Factorization& value) { + string s; + switch (value) { + case ISAM2Params::QR: + s = "QR"; + break; + case ISAM2Params::CHOLESKY: + s = "CHOLESKY"; + break; + default: + s = "UNDEFINED"; + break; + } + return s; +} + +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2Params.h b/gtsam/nonlinear/ISAM2Params.h new file mode 100644 index 000000000..afddd1f8e --- /dev/null +++ b/gtsam/nonlinear/ISAM2Params.h @@ -0,0 +1,365 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ISAM2Params.h + * @brief Parameters for iSAM 2. + * @author Michael Kaess, Richard Roberts, Frank Dellaert + */ + +// \callgraph + +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * @addtogroup ISAM2 + * Parameters for ISAM2 using Gauss-Newton optimization. Either this class or + * ISAM2DoglegParams should be specified as the optimizationParams in + * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). + */ +struct GTSAM_EXPORT ISAM2GaussNewtonParams { + double + wildfireThreshold; ///< Continue updating the linear delta only when + ///< changes are above this threshold (default: 0.001) + + /** Specify parameters as constructor arguments */ + ISAM2GaussNewtonParams( + double _wildfireThreshold = + 0.001 ///< see ISAM2GaussNewtonParams public variables, + ///< ISAM2GaussNewtonParams::wildfireThreshold + ) + : wildfireThreshold(_wildfireThreshold) {} + + void print(const std::string str = "") const { + using std::cout; + cout << str << "type: ISAM2GaussNewtonParams\n"; + cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + cout.flush(); + } + + double getWildfireThreshold() const { return wildfireThreshold; } + void setWildfireThreshold(double wildfireThreshold) { + this->wildfireThreshold = wildfireThreshold; + } +}; + +/** + * @addtogroup ISAM2 + * Parameters for ISAM2 using Dogleg optimization. Either this class or + * ISAM2GaussNewtonParams should be specified as the optimizationParams in + * ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&). + */ +struct GTSAM_EXPORT ISAM2DoglegParams { + double initialDelta; ///< The initial trust region radius for Dogleg + double + wildfireThreshold; ///< Continue updating the linear delta only when + ///< changes are above this threshold (default: 1e-5) + DoglegOptimizerImpl::TrustRegionAdaptationMode + adaptationMode; ///< See description in + ///< DoglegOptimizerImpl::TrustRegionAdaptationMode + bool + verbose; ///< Whether Dogleg prints iteration and convergence information + + /** Specify parameters as constructor arguments */ + ISAM2DoglegParams( + double _initialDelta = 1.0, ///< see ISAM2DoglegParams::initialDelta + double _wildfireThreshold = + 1e-5, ///< see ISAM2DoglegParams::wildfireThreshold + DoglegOptimizerImpl::TrustRegionAdaptationMode _adaptationMode = + DoglegOptimizerImpl:: + SEARCH_EACH_ITERATION, ///< see ISAM2DoglegParams::adaptationMode + bool _verbose = false ///< see ISAM2DoglegParams::verbose + ) + : initialDelta(_initialDelta), + wildfireThreshold(_wildfireThreshold), + adaptationMode(_adaptationMode), + verbose(_verbose) {} + + void print(const std::string str = "") const { + using std::cout; + cout << str << "type: ISAM2DoglegParams\n"; + cout << str << "initialDelta: " << initialDelta << "\n"; + cout << str << "wildfireThreshold: " << wildfireThreshold << "\n"; + cout << str + << "adaptationMode: " << adaptationModeTranslator(adaptationMode) + << "\n"; + cout.flush(); + } + + double getInitialDelta() const { return initialDelta; } + double getWildfireThreshold() const { return wildfireThreshold; } + std::string getAdaptationMode() const { + return adaptationModeTranslator(adaptationMode); + } + bool isVerbose() const { return verbose; } + void setInitialDelta(double initialDelta) { + this->initialDelta = initialDelta; + } + void setWildfireThreshold(double wildfireThreshold) { + this->wildfireThreshold = wildfireThreshold; + } + void setAdaptationMode(const std::string& adaptationMode) { + this->adaptationMode = adaptationModeTranslator(adaptationMode); + } + void setVerbose(bool verbose) { this->verbose = verbose; } + + std::string adaptationModeTranslator( + const DoglegOptimizerImpl::TrustRegionAdaptationMode& adaptationMode) + const; + DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator( + const std::string& adaptationMode) const; +}; + +/** + * @addtogroup ISAM2 + * Parameters for the ISAM2 algorithm. Default parameter values are listed + * below. + */ +typedef FastMap ISAM2ThresholdMap; +typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue; +struct GTSAM_EXPORT ISAM2Params { + typedef boost::variant + OptimizationParams; ///< Either ISAM2GaussNewtonParams or + ///< ISAM2DoglegParams + typedef boost::variant > + RelinearizationThreshold; ///< Either a constant relinearization + ///< threshold or a per-variable-type set of + ///< thresholds + + /** Optimization parameters, this both selects the nonlinear optimization + * method and specifies its parameters, either ISAM2GaussNewtonParams or + * ISAM2DoglegParams. In the former, Gauss-Newton optimization will be used + * with the specified parameters, and in the latter Powell's dog-leg + * algorithm will be used with the specified parameters. + */ + OptimizationParams optimizationParams; + + /** Only relinearize variables whose linear delta magnitude is greater than + * this threshold (default: 0.1). If this is a FastMap instead + * of a double, then the threshold is specified for each dimension of each + * variable type. This parameter then maps from a character indicating the + * variable type to a Vector of thresholds for each dimension of that + * variable. For example, if Pose keys are of type TypedSymbol<'x',Pose3>, + * and landmark keys are of type TypedSymbol<'l',Point3>, then appropriate + * entries would be added with: + * \code + FastMap thresholds; + thresholds['x'] = (Vector(6) << 0.1, 0.1, 0.1, 0.5, 0.5, 0.5).finished(); + // 0.1 rad rotation threshold, 0.5 m translation threshold thresholds['l'] = + Vector3(1.0, 1.0, 1.0); // 1.0 m landmark position threshold + params.relinearizeThreshold = thresholds; + \endcode + */ + RelinearizationThreshold relinearizeThreshold; + + int relinearizeSkip; ///< Only relinearize any variables every + ///< relinearizeSkip calls to ISAM2::update (default: + ///< 10) + + bool enableRelinearization; ///< Controls whether ISAM2 will ever relinearize + ///< any variables (default: true) + + bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error + ///< before and after the update, to return in + ///< ISAM2Result from update() + + enum Factorization { CHOLESKY, QR }; + /** Specifies whether to use QR or CHOESKY numerical factorization (default: + * CHOLESKY). Cholesky is faster but potentially numerically unstable for + * poorly-conditioned problems, which can occur when uncertainty is very low + * in some variables (or dimensions of variables) and very high in others. QR + * is slower but more numerically stable in poorly-conditioned problems. We + * suggest using the default of Cholesky unless gtsam sometimes throws + * IndefiniteLinearSystemException when your problem's Hessian is actually + * positive definite. For positive definite problems, numerical error + * accumulation can cause the problem to become numerically negative or + * indefinite as solving proceeds, especially when using Cholesky. + */ + Factorization factorization; + + /** Whether to cache linear factors (default: true). + * This can improve performance if linearization is expensive, but can hurt + * performance if linearization is very cleap due to computation to look up + * additional keys. + */ + bool cacheLinearizedFactors; + + KeyFormatter + keyFormatter; ///< A KeyFormatter for when keys are printed during + ///< debugging (default: DefaultKeyFormatter) + + bool enableDetailedResults; ///< Whether to compute and return + ///< ISAM2Result::detailedResults, this can + ///< increase running time (default: false) + + /** Check variables for relinearization in tree-order, stopping the check once + * a variable does not need to be relinearized (default: false). This can + * improve speed by only checking a small part of the top of the tree. + * However, variables below the check cut-off can accumulate significant + * deltas without triggering relinearization. This is particularly useful in + * exploration scenarios where real-time performance is desired over + * correctness. Use with caution. + */ + bool enablePartialRelinearizationCheck; + + /// When you will be removing many factors, e.g. when using ISAM2 as a + /// fixed-lag smoother, enable this option to add factors in the first + /// available factor slots, to avoid accumulating NULL factor slots, at the + /// cost of having to search for slots every time a factor is added. + bool findUnusedFactorSlots; + + /** + * Specify parameters as constructor arguments + * See the documentation of member variables above. + */ + ISAM2Params(OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), + RelinearizationThreshold _relinearizeThreshold = 0.1, + int _relinearizeSkip = 10, bool _enableRelinearization = true, + bool _evaluateNonlinearError = false, + Factorization _factorization = ISAM2Params::CHOLESKY, + bool _cacheLinearizedFactors = true, + const KeyFormatter& _keyFormatter = + DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter + ) + : optimizationParams(_optimizationParams), + relinearizeThreshold(_relinearizeThreshold), + relinearizeSkip(_relinearizeSkip), + enableRelinearization(_enableRelinearization), + evaluateNonlinearError(_evaluateNonlinearError), + factorization(_factorization), + cacheLinearizedFactors(_cacheLinearizedFactors), + keyFormatter(_keyFormatter), + enableDetailedResults(false), + enablePartialRelinearizationCheck(false), + findUnusedFactorSlots(false) {} + + /// print iSAM2 parameters + void print(const std::string& str = "") const { + using std::cout; + cout << str << "\n"; + + static const std::string kStr("optimizationParams: "); + if (optimizationParams.type() == typeid(ISAM2GaussNewtonParams)) + boost::get(optimizationParams).print(); + else if (optimizationParams.type() == typeid(ISAM2DoglegParams)) + boost::get(optimizationParams).print(kStr); + else + cout << kStr << "{unknown type}\n"; + + cout << "relinearizeThreshold: "; + if (relinearizeThreshold.type() == typeid(double)) { + cout << boost::get(relinearizeThreshold) << "\n"; + } else { + cout << "{mapped}\n"; + for (const ISAM2ThresholdMapValue& value : + boost::get(relinearizeThreshold)) { + cout << " '" << value.first + << "' -> [" << value.second.transpose() << " ]\n"; + } + } + + cout << "relinearizeSkip: " << relinearizeSkip << "\n"; + cout << "enableRelinearization: " << enableRelinearization + << "\n"; + cout << "evaluateNonlinearError: " << evaluateNonlinearError + << "\n"; + cout << "factorization: " + << factorizationTranslator(factorization) << "\n"; + cout << "cacheLinearizedFactors: " << cacheLinearizedFactors + << "\n"; + cout << "enableDetailedResults: " << enableDetailedResults + << "\n"; + cout << "enablePartialRelinearizationCheck: " + << enablePartialRelinearizationCheck << "\n"; + cout << "findUnusedFactorSlots: " << findUnusedFactorSlots + << "\n"; + cout.flush(); + } + + /// @name Getters and Setters for all properties + /// @{ + + OptimizationParams getOptimizationParams() const { + return this->optimizationParams; + } + RelinearizationThreshold getRelinearizeThreshold() const { + return relinearizeThreshold; + } + int getRelinearizeSkip() const { return relinearizeSkip; } + bool isEnableRelinearization() const { return enableRelinearization; } + bool isEvaluateNonlinearError() const { return evaluateNonlinearError; } + std::string getFactorization() const { + return factorizationTranslator(factorization); + } + bool isCacheLinearizedFactors() const { return cacheLinearizedFactors; } + KeyFormatter getKeyFormatter() const { return keyFormatter; } + bool isEnableDetailedResults() const { return enableDetailedResults; } + bool isEnablePartialRelinearizationCheck() const { + return enablePartialRelinearizationCheck; + } + + void setOptimizationParams(OptimizationParams optimizationParams) { + this->optimizationParams = optimizationParams; + } + void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) { + this->relinearizeThreshold = relinearizeThreshold; + } + void setRelinearizeSkip(int relinearizeSkip) { + this->relinearizeSkip = relinearizeSkip; + } + void setEnableRelinearization(bool enableRelinearization) { + this->enableRelinearization = enableRelinearization; + } + void setEvaluateNonlinearError(bool evaluateNonlinearError) { + this->evaluateNonlinearError = evaluateNonlinearError; + } + void setFactorization(const std::string& factorization) { + this->factorization = factorizationTranslator(factorization); + } + void setCacheLinearizedFactors(bool cacheLinearizedFactors) { + this->cacheLinearizedFactors = cacheLinearizedFactors; + } + void setKeyFormatter(KeyFormatter keyFormatter) { + this->keyFormatter = keyFormatter; + } + void setEnableDetailedResults(bool enableDetailedResults) { + this->enableDetailedResults = enableDetailedResults; + } + void setEnablePartialRelinearizationCheck( + bool enablePartialRelinearizationCheck) { + this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck; + } + + GaussianFactorGraph::Eliminate getEliminationFunction() const { + return factorization == CHOLESKY + ? (GaussianFactorGraph::Eliminate)EliminatePreferCholesky + : (GaussianFactorGraph::Eliminate)EliminateQR; + } + + /// @} + + /// @name Some utilities + /// @{ + + static Factorization factorizationTranslator(const std::string& str); + static std::string factorizationTranslator(const Factorization& value); + + /// @} +}; + +} // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2Result.h b/gtsam/nonlinear/ISAM2Result.h new file mode 100644 index 000000000..1539d90c4 --- /dev/null +++ b/gtsam/nonlinear/ISAM2Result.h @@ -0,0 +1,159 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file ISAM2Result.h + * @brief Class that stores detailed iSAM2 result. + * @author Michael Kaess, Richard Roberts, Frank Dellaert + */ + +// \callgraph + +#pragma once + +#include +#include + +#include +#include +#include +#include + +#include + +namespace gtsam { + +typedef FastVector FactorIndices; + +/** + * @addtogroup ISAM2 + * This struct is returned from ISAM2::update() and contains information about + * the update that is useful for determining whether the solution is + * converging, and about how much work was required for the update. See member + * variables for details and information about each entry. + */ +struct GTSAM_EXPORT ISAM2Result { + /** The nonlinear error of all of the factors, \a including new factors and + * variables added during the current call to ISAM2::update(). This error is + * calculated using the following variable values: + * \li Pre-existing variables will be evaluated by combining their + * linearization point before this call to update, with their partial linear + * delta, as computed by ISAM2::calculateEstimate(). + * \li New variables will be evaluated at their initialization points passed + * into the current call to update. + * \par Note: This will only be computed if + * ISAM2Params::evaluateNonlinearError is set to \c true, because there is + * some cost to this computation. + */ + boost::optional errorBefore; + + /** The nonlinear error of all of the factors computed after the current + * update, meaning that variables above the relinearization threshold + * (ISAM2Params::relinearizeThreshold) have been relinearized and new + * variables have undergone one linear update. Variable values are + * again computed by combining their linearization points with their + * partial linear deltas, by ISAM2::calculateEstimate(). + * \par Note: This will only be computed if + * ISAM2Params::evaluateNonlinearError is set to \c true, because there is + * some cost to this computation. + */ + boost::optional errorAfter; + + /** The number of variables that were relinearized because their linear + * deltas exceeded the reslinearization threshold + * (ISAM2Params::relinearizeThreshold), combined with any additional + * variables that had to be relinearized because they were involved in + * the same factor as a variable above the relinearization threshold. + * On steps where no relinearization is considered + * (see ISAM2Params::relinearizeSkip), this count will be zero. + */ + size_t variablesRelinearized; + + /** The number of variables that were reeliminated as parts of the Bayes' + * Tree were recalculated, due to new factors. When loop closures occur, + * this count will be large as the new loop-closing factors will tend to + * involve variables far away from the root, and everything up to the root + * will be reeliminated. + */ + size_t variablesReeliminated; + + /** The number of factors that were included in reelimination of the Bayes' + * tree. */ + size_t factorsRecalculated; + + /** The number of cliques in the Bayes' Tree */ + size_t cliques; + + /** The indices of the newly-added factors, in 1-to-1 correspondence with the + * factors passed as \c newFactors to ISAM2::update(). These indices may be + * used later to refer to the factors in order to remove them. + */ + FactorIndices newFactorsIndices; + + /** A struct holding detailed results, which must be enabled with + * ISAM2Params::enableDetailedResults. + */ + struct DetailedResults { + /** The status of a single variable, this struct is stored in + * DetailedResults::variableStatus */ + struct VariableStatus { + /** Whether the variable was just reeliminated, due to being relinearized, + * observed, new, or on the path up to the root clique from another + * reeliminated variable. */ + bool isReeliminated; + bool isAboveRelinThreshold; ///< Whether the variable was just + ///< relinearized due to being above the + ///< relinearization threshold + bool isRelinearizeInvolved; ///< Whether the variable was below the + ///< relinearization threshold but was + ///< relinearized by being involved in a + ///< factor with a variable above the + ///< relinearization threshold + bool isRelinearized; /// Whether the variable was relinearized, either by + /// being above the relinearization threshold or by + /// involvement. + bool isObserved; ///< Whether the variable was just involved in new + ///< factors + bool isNew; ///< Whether the variable itself was just added + bool inRootClique; ///< Whether the variable is in the root clique + VariableStatus() + : isReeliminated(false), + isAboveRelinThreshold(false), + isRelinearizeInvolved(false), + isRelinearized(false), + isObserved(false), + isNew(false), + inRootClique(false) {} + }; + + /** The status of each variable during this update, see VariableStatus. + */ + FastMap variableStatus; + }; + + /** Detailed results, if enabled by ISAM2Params::enableDetailedResults. See + * Detail for information about the results data stored here. */ + boost::optional detail; + + void print(const std::string str = "") const { + using std::cout; + cout << str << " Reelimintated: " << variablesReeliminated + << " Relinearized: " << variablesRelinearized + << " Cliques: " << cliques << std::endl; + } + + /** Getters and Setters */ + size_t getVariablesRelinearized() const { return variablesRelinearized; } + size_t getVariablesReeliminated() const { return variablesReeliminated; } + size_t getCliques() const { return cliques; } +}; + +} // namespace gtsam From 63b7d64fea2febfabfe2909e151ec82140950836 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 14:09:52 -0400 Subject: [PATCH 060/197] Fixed headers --- gtsam/inference/BayesTreeCliqueBase.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h index eae886785..055a03939 100644 --- a/gtsam/inference/BayesTreeCliqueBase.h +++ b/gtsam/inference/BayesTreeCliqueBase.h @@ -17,9 +17,13 @@ #pragma once -#include +#include +#include #include #include +#include + +#include namespace gtsam { From d6edc217abb64ac9e76323d69c38d483c7722649 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 14:11:00 -0400 Subject: [PATCH 061/197] Changed several Impl functions to methods in ISAM2 and ISAM2Clique --- gtsam/nonlinear/ISAM2-impl.cpp | 131 ++++---------------------------- gtsam/nonlinear/ISAM2-impl.h | 66 ++-------------- gtsam/nonlinear/ISAM2.cpp | 76 +++++++++++++++--- gtsam/nonlinear/ISAM2.h | 24 ++++++ gtsam/nonlinear/ISAM2Clique.cpp | 27 ++++++- gtsam/nonlinear/ISAM2Clique.h | 21 ++++- tests/testGaussianISAM2.cpp | 2 +- 7 files changed, 154 insertions(+), 193 deletions(-) diff --git a/gtsam/nonlinear/ISAM2-impl.cpp b/gtsam/nonlinear/ISAM2-impl.cpp index bc43c9b9d..8a8813af5 100644 --- a/gtsam/nonlinear/ISAM2-impl.cpp +++ b/gtsam/nonlinear/ISAM2-impl.cpp @@ -31,27 +31,12 @@ using namespace std; namespace gtsam { -/* ************************************************************************* */ -void ISAM2::Impl::AddVariables(const Values& newTheta, Values& theta, - VectorValues& delta, VectorValues& deltaNewton, - VectorValues& RgProd, - const KeyFormatter& keyFormatter) { - const bool debug = ISDEBUG("ISAM2 AddVariables"); - - theta.insert(newTheta); - if (debug) newTheta.print("The new variables are: "); - // Add zeros into the VectorValues - delta.insert(newTheta.zeroVectors()); - deltaNewton.insert(newTheta.zeroVectors()); - RgProd.insert(newTheta.zeroVectors()); -} - /* ************************************************************************* */ void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors, bool useUnusedSlots, - NonlinearFactorGraph& nonlinearFactors, - FactorIndices& newFactorIndices) { - newFactorIndices.resize(newFactors.size()); + NonlinearFactorGraph* nonlinearFactors, + FactorIndices* newFactorIndices) { + newFactorIndices->resize(newFactors.size()); if (useUnusedSlots) { size_t globalFactorIndex = 0; @@ -65,44 +50,24 @@ void ISAM2::Impl::AddFactorsStep1(const NonlinearFactorGraph& newFactors, // if so, increase globalFactorIndex. If the current factor in // nonlinearFactors is unused, break out of the loop and use the current // slot. - if (globalFactorIndex >= nonlinearFactors.size()) - nonlinearFactors.resize(nonlinearFactors.size() + newFactors.size() - - newFactorIndex); - else if (nonlinearFactors[globalFactorIndex]) + if (globalFactorIndex >= nonlinearFactors->size()) + nonlinearFactors->resize(nonlinearFactors->size() + + newFactors.size() - newFactorIndex); + else if ((*nonlinearFactors)[globalFactorIndex]) ++globalFactorIndex; else break; } while (true); // Use the current slot, updating nonlinearFactors and newFactorSlots. - nonlinearFactors[globalFactorIndex] = newFactors[newFactorIndex]; - newFactorIndices[newFactorIndex] = globalFactorIndex; + (*nonlinearFactors)[globalFactorIndex] = newFactors[newFactorIndex]; + (*newFactorIndices)[newFactorIndex] = globalFactorIndex; } } else { // We're not looking for unused slots, so just add the factors at the end. for (size_t i = 0; i < newFactors.size(); ++i) - newFactorIndices[i] = i + nonlinearFactors.size(); - nonlinearFactors.push_back(newFactors); - } -} - -/* ************************************************************************* */ -void ISAM2::Impl::RemoveVariables(const KeySet& unusedKeys, - const FastVector& roots, - Values& theta, VariableIndex& variableIndex, - VectorValues& delta, - VectorValues& deltaNewton, - VectorValues& RgProd, KeySet& replacedKeys, - Base::Nodes& nodes, KeySet& fixedVariables) { - variableIndex.removeUnusedVariables(unusedKeys.begin(), unusedKeys.end()); - for (Key key : unusedKeys) { - delta.erase(key); - deltaNewton.erase(key); - RgProd.erase(key); - replacedKeys.erase(key); - nodes.unsafe_erase(key); - theta.erase(key); - fixedVariables.erase(key); + (*newFactorIndices)[i] = i + nonlinearFactors->size(); + nonlinearFactors->push_back(newFactors); } } @@ -195,7 +160,7 @@ static void CheckRelinearizationRecursiveMap( /* ************************************************************************* */ KeySet ISAM2::Impl::CheckRelinearizationPartial( - const FastVector& roots, const VectorValues& delta, + const ISAM2::Roots& roots, const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) { KeySet relinKeys; for (const ISAM2::sharedClique& root : roots) { @@ -210,71 +175,6 @@ KeySet ISAM2::Impl::CheckRelinearizationPartial( return relinKeys; } -/* ************************************************************************* */ -void ISAM2::Impl::FindAll(ISAM2::sharedClique clique, KeySet& keys, - const KeySet& markedMask) { - static const bool debug = false; - // does the separator contain any of the variables? - bool found = false; - for (Key key : clique->conditional()->parents()) { - if (markedMask.exists(key)) { - found = true; - break; - } - } - if (found) { - // then add this clique - keys.insert(clique->conditional()->beginFrontals(), - clique->conditional()->endFrontals()); - if (debug) clique->print("Key(s) marked in clique "); - if (debug) - cout << "so marking key " << clique->conditional()->front() << endl; - } - for (const ISAM2::sharedClique& child : clique->children) { - FindAll(child, keys, markedMask); - } -} - -/* ************************************************************************* */ -void ISAM2::Impl::ExpmapMasked(const VectorValues& delta, const KeySet& mask, - Values* values, - boost::optional invalidateIfDebug, - const KeyFormatter& keyFormatter) { - // If debugging, invalidate if requested, otherwise do not invalidate. - // Invalidating means setting expmapped entries to Inf, to trigger assertions - // if we try to re-use them. -#ifdef NDEBUG - invalidateIfDebug = boost::none; -#endif - - assert(values->size() == delta.size()); - Values::iterator key_value; - VectorValues::const_iterator key_delta; -#ifdef GTSAM_USE_TBB - for (key_value = values->begin(); key_value != values->end(); ++key_value) { - key_delta = delta.find(key_value->key); -#else - for (key_value = values->begin(), key_delta = delta.begin(); - key_value != values->end(); ++key_value, ++key_delta) { - assert(key_value->key == key_delta->first); -#endif - Key var = key_value->key; - assert(static_cast(delta[var].size()) == key_value->value.dim()); - assert(delta[var].allFinite()); - if (mask.exists(var)) { - Value* retracted = key_value->value.retract_(delta[var]); - key_value->value = *retracted; - retracted->deallocate_(); - if (invalidateIfDebug) - (*invalidateIfDebug)[var].operator=(Vector::Constant( - delta[var].rows(), - numeric_limits::infinity())); // Strange syntax to work - // with clang++ (bug in - // clang?) - } - } -} - /* ************************************************************************* */ namespace internal { inline static void optimizeInPlace(const ISAM2::sharedClique& clique, @@ -289,9 +189,10 @@ inline static void optimizeInPlace(const ISAM2::sharedClique& clique, } // namespace internal /* ************************************************************************* */ -size_t ISAM2::Impl::UpdateGaussNewtonDelta( - const FastVector& roots, const KeySet& replacedKeys, - double wildfireThreshold, VectorValues* delta) { +size_t ISAM2::Impl::UpdateGaussNewtonDelta(const ISAM2::Roots& roots, + const KeySet& replacedKeys, + double wildfireThreshold, + VectorValues* delta) { size_t lastBacksubVariableCount; if (wildfireThreshold <= 0.0) { diff --git a/gtsam/nonlinear/ISAM2-impl.h b/gtsam/nonlinear/ISAM2-impl.h index 0e05ab453..8a30fb8cd 100644 --- a/gtsam/nonlinear/ISAM2-impl.h +++ b/gtsam/nonlinear/ISAM2-impl.h @@ -23,7 +23,6 @@ namespace gtsam { struct GTSAM_EXPORT ISAM2::Impl { - struct GTSAM_EXPORT PartialSolveResult { ISAM2::sharedClique bayesTree; }; @@ -32,35 +31,14 @@ struct GTSAM_EXPORT ISAM2::Impl { size_t nFullSystemVars; enum { /*AS_ADDED,*/ COLAMD } algorithm; enum { NO_CONSTRAINT, CONSTRAIN_LAST } constrain; - boost::optional > constrainedKeys; + boost::optional > constrainedKeys; }; - /** - * Add new variables to the ISAM2 system. - * @param newTheta Initial values for new variables - * @param theta Current solution to be augmented with new initialization - * @param delta Current linear delta to be augmented with zeros - * @param ordering Current ordering to be augmented with new variables - * @param nodes Current BayesTree::Nodes index to be augmented with slots for new variables - * @param keyFormatter Formatter for printing nonlinear keys during debugging - */ - static void AddVariables(const Values& newTheta, Values& theta, VectorValues& delta, - VectorValues& deltaNewton, VectorValues& RgProd, - const KeyFormatter& keyFormatter = DefaultKeyFormatter); - /// Perform the first part of the bookkeeping updates for adding new factors. Adds them to the /// complete list of nonlinear factors, and populates the list of new factor indices, both /// optionally finding and reusing empty factor slots. static void AddFactorsStep1(const NonlinearFactorGraph& newFactors, bool useUnusedSlots, - NonlinearFactorGraph& nonlinearFactors, FactorIndices& newFactorIndices); - - /** - * Remove variables from the ISAM2 system. - */ - static void RemoveVariables(const KeySet& unusedKeys, const FastVector& roots, - Values& theta, VariableIndex& variableIndex, VectorValues& delta, VectorValues& deltaNewton, - VectorValues& RgProd, KeySet& replacedKeys, Base::Nodes& nodes, - KeySet& fixedVariables); + NonlinearFactorGraph* nonlinearFactors, FactorIndices* newFactorIndices); /** * Find the set of variables to be relinearized according to relinearizeThreshold. @@ -85,47 +63,13 @@ struct GTSAM_EXPORT ISAM2::Impl { * @return The set of variable indices in delta whose magnitude is greater than or * equal to relinearizeThreshold */ - static KeySet CheckRelinearizationPartial(const FastVector& roots, + static KeySet CheckRelinearizationPartial(const ISAM2::Roots& roots, const VectorValues& delta, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold); - /** - * Recursively search this clique and its children for marked keys appearing - * in the separator, and add the *frontal* keys of any cliques whose - * separator contains any marked keys to the set \c keys. The purpose of - * this is to discover the cliques that need to be redone due to information - * propagating to them from cliques that directly contain factors being - * relinearized. - * - * The original comment says this finds all variables directly connected to - * the marked ones by measurements. Is this true, because it seems like this - * would also pull in variables indirectly connected through other frontal or - * separator variables? - * - * Alternatively could we trace up towards the root for each variable here? - */ - static void FindAll(ISAM2Clique::shared_ptr clique, KeySet& keys, const KeySet& markedMask); - - /** - * Apply expmap to the given values, but only for indices appearing in - * \c markedRelinMask. Values are expmapped in-place. - * \param delta The linear delta with which to expmap - * \param mask Mask on linear indices, only \c true entries are expmapped - * \param [in, out] values The value to expmap in-place - * \param invalidateIfDebug If this is true, *and* NDEBUG is not defined, - * expmapped deltas will be set to an invalid value (infinity) to catch bugs - * where we might expmap something twice, or expmap it but then not - * recalculate its delta. - * @param keyFormatter Formatter for printing nonlinear keys during debugging - */ - static void ExpmapMasked( - const VectorValues& delta, const KeySet& mask, Values* values, - boost::optional invalidateIfDebug = boost::none, - const KeyFormatter& keyFormatter = DefaultKeyFormatter); - /** * Update the Newton's method step point, using wildfire */ - static size_t UpdateGaussNewtonDelta(const FastVector& roots, + static size_t UpdateGaussNewtonDelta(const ISAM2::Roots& roots, const KeySet& replacedKeys, double wildfireThreshold, VectorValues* delta); /** @@ -134,7 +78,7 @@ struct GTSAM_EXPORT ISAM2::Impl { */ static size_t UpdateRgProd(const ISAM2::Roots& roots, const KeySet& replacedKeys, const VectorValues& gradAtZero, VectorValues* RgProd); - + /** * Compute the gradient-search point. Only used in Dogleg. */ diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index e543508b2..2f44063ac 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -33,6 +33,7 @@ using namespace boost::adaptors; } // namespace br #include +#include #include #include @@ -484,6 +485,62 @@ boost::shared_ptr ISAM2::recalculate( return affectedKeysSet; } +/* ************************************************************************* */ +void ISAM2::addVariables(const Values& newTheta) { + const bool debug = ISDEBUG("ISAM2 AddVariables"); + + theta_.insert(newTheta); + if (debug) newTheta.print("The new variables are: "); + // Add zeros into the VectorValues + delta_.insert(newTheta.zeroVectors()); + deltaNewton_.insert(newTheta.zeroVectors()); + RgProd_.insert(newTheta.zeroVectors()); +} + +/* ************************************************************************* */ +void ISAM2::removeVariables(const KeySet& unusedKeys) { + variableIndex_.removeUnusedVariables(unusedKeys.begin(), unusedKeys.end()); + for (Key key : unusedKeys) { + delta_.erase(key); + deltaNewton_.erase(key); + RgProd_.erase(key); + deltaReplacedMask_.erase(key); + Base::nodes_.unsafe_erase(key); + theta_.erase(key); + fixedVariables_.erase(key); + } +} + +/* ************************************************************************* */ +void ISAM2::expmapMasked(const KeySet& mask) { + assert(theta_.size() == delta_.size()); + Values::iterator key_value; + VectorValues::const_iterator key_delta; +#ifdef GTSAM_USE_TBB + for (key_value = theta_.begin(); key_value != theta_.end(); ++key_value) { + key_delta = delta_.find(key_value->key); +#else + for (key_value = theta_.begin(), key_delta = delta_.begin(); + key_value != theta_.end(); ++key_value, ++key_delta) { + assert(key_value->key == key_delta->first); +#endif + Key var = key_value->key; + assert(static_cast(delta_[var].size()) == key_value->value.dim()); + assert(delta_[var].allFinite()); + if (mask.exists(var)) { + Value* retracted = key_value->value.retract_(delta_[var]); + key_value->value = *retracted; + retracted->deallocate_(); +#ifndef NDEBUG + // If debugging, invalidate delta_ entries to Inf, to trigger assertions + // if we try to re-use them. + delta_[var] = Vector::Constant(delta_[var].rows(), + numeric_limits::infinity()); +#endif + } + } +} + /* ************************************************************************* */ ISAM2Result ISAM2::update( const NonlinearFactorGraph& newFactors, const Values& newTheta, @@ -529,7 +586,7 @@ ISAM2Result ISAM2::update( // Add the new factor indices to the result struct if (debug || verbose) newFactors.print("The new factors are: "); Impl::AddFactorsStep1(newFactors, params_.findUnusedFactorSlots, - nonlinearFactors_, result.newFactorsIndices); + &nonlinearFactors_, &result.newFactorsIndices); // Remove the removed factors NonlinearFactorGraph removeFactors; @@ -571,7 +628,7 @@ ISAM2Result ISAM2::update( gttic(add_new_variables); // 2. Initialize any new variables \Theta_{new} and add // \Theta:=\Theta\cup\Theta_{new}. - Impl::AddVariables(newTheta, theta_, delta_, deltaNewton_, RgProd_); + addVariables(newTheta); // New keys for detailed results if (params_.enableDetailedResults) { for (Key key : newTheta.keys()) { @@ -669,13 +726,13 @@ ISAM2Result ISAM2::update( if (!relinKeys.empty()) { for (const sharedClique& root : roots_) // add other cliques that have the marked ones in the separator - Impl::FindAll(root, markedKeys, markedRelinMask); + root->findAll(markedRelinMask, &markedKeys); // Relin involved keys for detailed results if (params_.enableDetailedResults) { KeySet involvedRelinKeys; for (const sharedClique& root : roots_) - Impl::FindAll(root, involvedRelinKeys, markedRelinMask); + root->findAll(markedRelinMask, &involvedRelinKeys); for (Key key : involvedRelinKeys) { if (!result.detail->variableStatus[key].isAboveRelinThreshold) { result.detail->variableStatus[key].isRelinearizeInvolved = true; @@ -689,8 +746,7 @@ ISAM2Result ISAM2::update( gttic(expmap); // 6. Update linearization point for marked variables: // \Theta_{J}:=\Theta_{J}+\Delta_{J}. - if (!relinKeys.empty()) - Impl::ExpmapMasked(delta_, markedRelinMask, &theta_, delta_); + if (!relinKeys.empty()) expmapMasked(markedRelinMask); gttoc(expmap); result.variablesRelinearized = markedKeys.size(); @@ -740,9 +796,7 @@ ISAM2Result ISAM2::update( // Update data structures to remove unused keys if (!unusedKeys.empty()) { gttic(remove_variables); - Impl::RemoveVariables(unusedKeys, roots_, theta_, variableIndex_, delta_, - deltaNewton_, RgProd_, deltaReplacedMask_, - Base::nodes_, fixedVariables_); + removeVariables(unusedKeys); gttoc(remove_variables); } result.cliques = this->nodes().size(); @@ -998,9 +1052,7 @@ void ISAM2::marginalizeLeaves( factorIndicesToRemove.end()); // Remove the marginalized variables - Impl::RemoveVariables(KeySet(leafKeys.begin(), leafKeys.end()), roots_, - theta_, variableIndex_, delta_, deltaNewton_, RgProd_, - deltaReplacedMask_, nodes_, fixedVariables_); + removeVariables(KeySet(leafKeys.begin(), leafKeys.end())); } /* ************************************************************************* */ diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 069d90cc8..2de8eb608 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -269,6 +269,29 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { /// @} protected: + /** + * Add new variables to the ISAM2 system. + * @param newTheta Initial values for new variables + * @param theta Current solution to be augmented with new initialization + * @param delta Current linear delta to be augmented with zeros + * @param deltaNewton + * @param RgProd + * @param keyFormatter Formatter for printing nonlinear keys during debugging + */ + void addVariables(const Values& newTheta); + + /** + * Remove variables from the ISAM2 system. + */ + void removeVariables(const KeySet& unusedKeys); + + /** + * Apply expmap to the given values, but only for indices appearing in + * \c mask. Values are expmapped in-place. + * \param mask Mask on linear indices, only \c true entries are expmapped + */ + void expmapMasked(const KeySet& mask); + FastSet getAffectedFactors(const FastList& keys) const; GaussianFactorGraph::shared_ptr relinearizeAffectedFactors( const FastList& affectedKeys, const KeySet& relinKeys) const; @@ -279,6 +302,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { const std::vector& observedKeys, const KeySet& unusedIndices, const boost::optional >& constrainKeys, ISAM2Result& result); + void updateDelta(bool forceFullSolve = false) const; }; // ISAM2 diff --git a/gtsam/nonlinear/ISAM2Clique.cpp b/gtsam/nonlinear/ISAM2Clique.cpp index 6e03b0680..c55ca7959 100644 --- a/gtsam/nonlinear/ISAM2Clique.cpp +++ b/gtsam/nonlinear/ISAM2Clique.cpp @@ -15,10 +15,10 @@ * @author Michael Kaess, Richard Roberts, Frank Dellaert */ -#include +#include #include #include -#include +#include #include using namespace std; @@ -299,4 +299,27 @@ size_t ISAM2Clique::calculate_nnz() const { return result; } +/* ************************************************************************* */ +void ISAM2Clique::findAll(const KeySet& markedMask, KeySet* keys) const { + static const bool debug = false; + // does the separator contain any of the variables? + bool found = false; + for (Key key : conditional()->parents()) { + if (markedMask.exists(key)) { + found = true; + break; + } + } + if (found) { + // then add this clique + keys->insert(conditional()->beginFrontals(), conditional()->endFrontals()); + if (debug) print("Key(s) marked in clique "); + if (debug) cout << "so marking key " << conditional()->front() << endl; + } + for (const auto& child : children) { + child->findAll(markedMask, keys); + } +} + +/* ************************************************************************* */ } // namespace gtsam diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index fecc8d335..3c53e3d72 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -19,11 +19,11 @@ #pragma once +#include +#include #include #include #include -#include -#include #include namespace gtsam { @@ -99,6 +99,23 @@ class GTSAM_EXPORT ISAM2Clique void nnz_internal(size_t* result) const; size_t calculate_nnz() const; + /** + * Recursively search this clique and its children for marked keys appearing + * in the separator, and add the *frontal* keys of any cliques whose + * separator contains any marked keys to the set \c keys. The purpose of + * this is to discover the cliques that need to be redone due to information + * propagating to them from cliques that directly contain factors being + * relinearized. + * + * The original comment says this finds all variables directly connected to + * the marked ones by measurements. Is this true, because it seems like this + * would also pull in variables indirectly connected through other frontal or + * separator variables? + * + * Alternatively could we trace up towards the root for each variable here? + */ + void findAll(const KeySet& markedMask, KeySet* keys) const; + private: /** * Check if clique was replaced, or if any parents were changed above the diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp index 681c30587..d6ca896dd 100644 --- a/tests/testGaussianISAM2.cpp +++ b/tests/testGaussianISAM2.cpp @@ -304,7 +304,7 @@ TEST(ISAM2, AddFactorsStep1) FactorIndices actualNewFactorIndices; - ISAM2::Impl::AddFactorsStep1(newFactors, true, nonlinearFactors, actualNewFactorIndices); + ISAM2::Impl::AddFactorsStep1(newFactors, true, &nonlinearFactors, &actualNewFactorIndices); EXPECT(assert_equal(expectedNonlinearFactors, nonlinearFactors)); EXPECT(assert_container_equality(expectedNewFactorIndices, actualNewFactorIndices)); From 2fe2f1ad190614904256068b2da1d7a7f2a35b14 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 14:22:20 -0400 Subject: [PATCH 062/197] input/output convention --- gtsam/nonlinear/ISAM2.cpp | 18 +++++++++--------- gtsam/nonlinear/ISAM2.h | 2 +- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 2f44063ac..1c6da94a7 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -199,7 +199,7 @@ boost::shared_ptr ISAM2::recalculate( const KeySet& markedKeys, const KeySet& relinKeys, const vector& observedKeys, const KeySet& unusedIndices, const boost::optional >& constrainKeys, - ISAM2Result& result) { + ISAM2Result* result) { // TODO(dellaert): new factors are linearized twice, // the newFactors passed in are not used. @@ -333,8 +333,8 @@ boost::shared_ptr ISAM2::recalculate( this->nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end()); gttoc(insert); - result.variablesReeliminated = affectedKeysSet->size(); - result.factorsRecalculated = nonlinearFactors_.size(); + result->variablesReeliminated = affectedKeysSet->size(); + result->factorsRecalculated = nonlinearFactors_.size(); lastAffectedMarkedCount = markedKeys.size(); lastAffectedVariableCount = affectedKeysSet->size(); @@ -343,7 +343,7 @@ boost::shared_ptr ISAM2::recalculate( // Reeliminated keys for detailed results if (params_.enableDetailedResults) { for (Key key : theta_.keys()) { - result.detail->variableStatus[key].isReeliminated = true; + result->detail->variableStatus[key].isReeliminated = true; } } @@ -375,12 +375,12 @@ boost::shared_ptr ISAM2::recalculate( // Reeliminated keys for detailed results if (params_.enableDetailedResults) { for (Key key : affectedAndNewKeys) { - result.detail->variableStatus[key].isReeliminated = true; + result->detail->variableStatus[key].isReeliminated = true; } } - result.variablesReeliminated = affectedAndNewKeys.size(); - result.factorsRecalculated = factors.size(); + result->variablesReeliminated = affectedAndNewKeys.size(); + result->factorsRecalculated = factors.size(); lastAffectedMarkedCount = markedKeys.size(); lastAffectedVariableCount = affectedKeys.size(); lastAffectedFactorCount = factors.size(); @@ -479,7 +479,7 @@ boost::shared_ptr ISAM2::recalculate( if (params_.enableDetailedResults) { for (const sharedNode& root : this->roots()) for (Key var : *root->conditional()) - result.detail->variableStatus[var].inRootClique = true; + result->detail->variableStatus[var].inRootClique = true; } return affectedKeysSet; @@ -786,7 +786,7 @@ ISAM2Result ISAM2::update( boost::shared_ptr replacedKeys; if (!markedKeys.empty() || !observedKeys.empty()) replacedKeys = recalculate(markedKeys, relinKeys, observedKeys, - unusedIndices, constrainedKeys, result); + unusedIndices, constrainedKeys, &result); // Update replaced keys mask (accumulates until back-substitution takes place) if (replacedKeys) diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 2de8eb608..5d448d786 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -301,7 +301,7 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { const KeySet& markedKeys, const KeySet& relinKeys, const std::vector& observedKeys, const KeySet& unusedIndices, const boost::optional >& constrainKeys, - ISAM2Result& result); + ISAM2Result* result); void updateDelta(bool forceFullSolve = false) const; }; // ISAM2 From c50b3cd6beb7c695fc067cb3e01087748e8452df Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 15:13:47 -0400 Subject: [PATCH 063/197] Eliminated some copypasta with lambda --- gtsam/nonlinear/ISAM2.cpp | 112 +++++++++++++++----------------------- 1 file changed, 44 insertions(+), 68 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index 1c6da94a7..cad9add9f 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -141,8 +141,7 @@ GaussianFactorGraph::shared_ptr ISAM2::relinearizeAffectedFactors( gttoc(affectedKeysSet); gttic(check_candidates_and_linearize); - GaussianFactorGraph::shared_ptr linearized = - boost::make_shared(); + auto linearized = boost::make_shared(); for (Key idx : candidates) { bool inside = true; bool useCachedLinear = params_.cacheLinearizedFactors; @@ -162,8 +161,7 @@ GaussianFactorGraph::shared_ptr ISAM2::relinearizeAffectedFactors( #endif linearized->push_back(linearFactors_[idx]); } else { - GaussianFactor::shared_ptr linearFactor = - nonlinearFactors_[idx]->linearize(theta_); + auto linearFactor = nonlinearFactors_[idx]->linearize(theta_); linearized->push_back(linearFactor); if (params_.cacheLinearizedFactors) { #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS @@ -268,7 +266,7 @@ boost::shared_ptr ISAM2::recalculate( // path to root included gttic(affectedKeys); FastList affectedKeys; - for (const ConditionalType::shared_ptr& conditional : affectedBayesNet) + for (const auto& conditional : affectedBayesNet) affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(), conditional->endFrontals()); gttoc(affectedKeys); @@ -758,8 +756,7 @@ ISAM2Result ISAM2::update( // 7. Linearize new factors if (params_.cacheLinearizedFactors) { gttic(linearize); - GaussianFactorGraph::shared_ptr linearFactors = - newFactors.linearize(theta_); + auto linearFactors = newFactors.linearize(theta_); if (params_.findUnusedFactorSlots) { linearFactors_.resize(nonlinearFactors_.size()); for (size_t newFactorI = 0; newFactorI < newFactors.size(); ++newFactorI) @@ -822,11 +819,35 @@ void ISAM2::marginalizeLeaves( // multimap marginalFactors; map > marginalFactors; + // Keep track of variables removed in subtrees + KeySet leafKeysRemoved; + // Keep track of factors that get summarized by removing cliques KeySet factorIndicesToRemove; - // Keep track of variables removed in subtrees - KeySet leafKeysRemoved; + // Remove the subtree and throw away the cliques + auto trackingRemoveSubtree = [&](const sharedClique& subtreeRoot) { + const Cliques removedCliques = this->removeSubtree(subtreeRoot); + for (const sharedClique& removedClique : removedCliques) { + auto cg = removedClique->conditional(); + marginalFactors.erase(cg->front()); + leafKeysRemoved.insert(cg->beginFrontals(), cg->endFrontals()); + for (Key frontal : cg->frontals()) { + // Add to factors to remove + const auto& involved = variableIndex_[frontal]; + factorIndicesToRemove.insert(involved.begin(), involved.end()); +#if !defined(NDEBUG) + // Check for non-leaf keys + if (!leafKeys.exists(frontal)) + throw std::runtime_error( + "Requesting to marginalize variables that are not leaves, " + "the ISAM2 object is now in an inconsistent state so should " + "no longer be used."); +#endif + } + } + return removedCliques; + }; // Remove each variable and its subtrees for (Key j : leafKeys) { @@ -858,7 +879,7 @@ void ISAM2::marginalizeLeaves( if (marginalizeEntireClique) { // Remove the whole clique and its subtree, and keep the marginal // factor. - GaussianFactor::shared_ptr marginalFactor = clique->cachedFactor(); + auto marginalFactor = clique->cachedFactor(); // We do not need the marginal factors associated with this clique // because their information is already incorporated in the new // marginal factor. So, now associate this marginal factor with the @@ -867,27 +888,7 @@ void ISAM2::marginalizeLeaves( marginalFactor); // Now remove this clique and its subtree - all of its marginal // information has been stored in marginalFactors. - const Cliques removedCliques = this->removeSubtree( - clique); // Remove the subtree and throw away the cliques - for (const sharedClique& removedClique : removedCliques) { - marginalFactors.erase(removedClique->conditional()->front()); - leafKeysRemoved.insert(removedClique->conditional()->beginFrontals(), - removedClique->conditional()->endFrontals()); - for (Key frontal : removedClique->conditional()->frontals()) { - // Add to factors to remove - const VariableIndex::Factors& involvedFactors = - variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), - involvedFactors.end()); - - // Check for non-leaf keys - if (!leafKeys.exists(frontal)) - throw runtime_error( - "Requesting to marginalize variables that are not leaves, " - "the ISAM2 object is now in an inconsistent state so should " - "no longer be used."); - } - } + trackingRemoveSubtree(clique); } else { // Reeliminate the current clique and the marginals from its children, // then keep only the marginal on the non-marginalized variables. We @@ -910,31 +911,10 @@ void ISAM2::marginalizeLeaves( } } Cliques childrenRemoved; - for (const sharedClique& childToRemove : subtreesToRemove) { - const Cliques removedCliques = this->removeSubtree( - childToRemove); // Remove the subtree and throw away the cliques - childrenRemoved.insert(childrenRemoved.end(), removedCliques.begin(), - removedCliques.end()); - for (const sharedClique& removedClique : removedCliques) { - marginalFactors.erase(removedClique->conditional()->front()); - leafKeysRemoved.insert( - removedClique->conditional()->beginFrontals(), - removedClique->conditional()->endFrontals()); - for (Key frontal : removedClique->conditional()->frontals()) { - // Add to factors to remove - const VariableIndex::Factors& involvedFactors = - variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), - involvedFactors.end()); - - // Check for non-leaf keys - if (!leafKeys.exists(frontal)) - throw runtime_error( - "Requesting to marginalize variables that are not leaves, " - "the ISAM2 object is now in an inconsistent state so " - "should no longer be used."); - } - } + for (const sharedClique& subtree : subtreesToRemove) { + const Cliques removed = trackingRemoveSubtree(subtree); + childrenRemoved.insert(childrenRemoved.end(), removed.begin(), + removed.end()); } // Add the factors that are pulled into the current clique by the @@ -969,9 +949,8 @@ void ISAM2::marginalizeLeaves( std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(), leafKeys.begin(), leafKeys.end(), std::back_inserter(cliqueFrontalsToEliminate)); - pair - eliminationResult1 = params_.getEliminationFunction()( - graph, Ordering(cliqueFrontalsToEliminate)); + auto eliminationResult1 = params_.getEliminationFunction()( + graph, Ordering(cliqueFrontalsToEliminate)); // Add the resulting marginal if (eliminationResult1.second) @@ -997,13 +976,11 @@ void ISAM2::marginalizeLeaves( originalKeys.end()); clique->conditional()->nrFrontals() -= nToRemove; - // Add to factors to remove factors involved in frontals of current - // clique + // Add to factorIndicesToRemove any factors involved in frontals of + // current clique for (Key frontal : cliqueFrontalsToEliminate) { - const VariableIndex::Factors& involvedFactors = - variableIndex_[frontal]; - factorIndicesToRemove.insert(involvedFactors.begin(), - involvedFactors.end()); + const auto& involved = variableIndex_[frontal]; + factorIndicesToRemove.insert(involved.begin(), involved.end()); } // Add removed keys @@ -1018,9 +995,8 @@ void ISAM2::marginalizeLeaves( // Gather factors to add - the new marginal factors GaussianFactorGraph factorsToAdd; - typedef pair > Key_Factors; - for (const Key_Factors& key_factors : marginalFactors) { - for (const GaussianFactor::shared_ptr& factor : key_factors.second) { + for (const auto& key_factors : marginalFactors) { + for (const auto& factor : key_factors.second) { if (factor) { factorsToAdd.push_back(factor); if (marginalFactorsIndices) From 3e0ee2052d0c333f004179e85cefce97cbafc4f3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 15:26:36 -0400 Subject: [PATCH 064/197] Small cleanup of copy/paste call --- gtsam/nonlinear/ISAM2.cpp | 24 ++++++++++-------------- 1 file changed, 10 insertions(+), 14 deletions(-) diff --git a/gtsam/nonlinear/ISAM2.cpp b/gtsam/nonlinear/ISAM2.cpp index cad9add9f..df07050de 100644 --- a/gtsam/nonlinear/ISAM2.cpp +++ b/gtsam/nonlinear/ISAM2.cpp @@ -943,8 +943,8 @@ void ISAM2::marginalizeLeaves( // Reeliminate the linear graph to get the marginal and discard the // conditional - const KeySet cliqueFrontals(clique->conditional()->beginFrontals(), - clique->conditional()->endFrontals()); + auto cg = clique->conditional(); + const KeySet cliqueFrontals(cg->beginFrontals(), cg->endFrontals()); FastVector cliqueFrontalsToEliminate; std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(), leafKeys.begin(), leafKeys.end(), @@ -954,27 +954,23 @@ void ISAM2::marginalizeLeaves( // Add the resulting marginal if (eliminationResult1.second) - marginalFactors[clique->conditional()->front()].push_back( - eliminationResult1.second); + marginalFactors[cg->front()].push_back(eliminationResult1.second); // Split the current clique // Find the position of the last leaf key in this clique DenseIndex nToRemove = 0; - while (leafKeys.exists(clique->conditional()->keys()[nToRemove])) - ++nToRemove; + while (leafKeys.exists(cg->keys()[nToRemove])) ++nToRemove; // Make the clique's matrix appear as a subset - const DenseIndex dimToRemove = - clique->conditional()->matrixObject().offset(nToRemove); - clique->conditional()->matrixObject().firstBlock() = nToRemove; - clique->conditional()->matrixObject().rowStart() = dimToRemove; + const DenseIndex dimToRemove = cg->matrixObject().offset(nToRemove); + cg->matrixObject().firstBlock() = nToRemove; + cg->matrixObject().rowStart() = dimToRemove; // Change the keys in the clique FastVector originalKeys; - originalKeys.swap(clique->conditional()->keys()); - clique->conditional()->keys().assign(originalKeys.begin() + nToRemove, - originalKeys.end()); - clique->conditional()->nrFrontals() -= nToRemove; + originalKeys.swap(cg->keys()); + cg->keys().assign(originalKeys.begin() + nToRemove, originalKeys.end()); + cg->nrFrontals() -= nToRemove; // Add to factorIndicesToRemove any factors involved in frontals of // current clique From efa35e6a82aed346bff5e2aed6851f1f089d14b6 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 30 Sep 2018 17:22:53 -0400 Subject: [PATCH 065/197] Cleaned up example --- examples/VisualISAM2Example.cpp | 88 ++++++++++++++++++--------------- 1 file changed, 49 insertions(+), 39 deletions(-) diff --git a/examples/VisualISAM2Example.cpp b/examples/VisualISAM2Example.cpp index 157768be7..751b776f6 100644 --- a/examples/VisualISAM2Example.cpp +++ b/examples/VisualISAM2Example.cpp @@ -11,8 +11,8 @@ /** * @file VisualISAM2Example.cpp - * @brief A visualSLAM example for the structure-from-motion problem on a simulated dataset - * This version uses iSAM2 to solve the problem incrementally + * @brief A visualSLAM example for the structure-from-motion problem on a + * simulated dataset This version uses iSAM2 to solve the problem incrementally * @author Duy-Nguyen Ta */ @@ -25,27 +25,28 @@ // For loading the data #include "SFMdata.h" -// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). +// Camera observations of landmarks will be stored as Point2 (x, y). #include -// Each variable in the system (poses and landmarks) must be identified with a unique key. -// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). -// Here we will use Symbols +// Each variable in the system (poses and landmarks) must be identified with a +// unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols +// (X1, X2, L1). Here we will use Symbols #include -// We want to use iSAM2 to solve the structure-from-motion problem incrementally, so -// include iSAM2 here +// We want to use iSAM2 to solve the structure-from-motion problem +// incrementally, so include iSAM2 here #include -// iSAM2 requires as input a set set of new factors to be added stored in a factor graph, -// and initial guesses for any new variables used in the added factors +// iSAM2 requires as input a set of new factors to be added stored in a factor +// graph, and initial guesses for any new variables used in the added factors #include #include -// In GTSAM, measurement functions are represented as 'factors'. Several common factors -// have been provided with the library for solving robotics/SLAM/Bundle Adjustment problems. -// Here we will use Projection factors to model the camera's landmark observations. -// Also, we will initialize the robot at some location using a Prior factor. +// In GTSAM, measurement functions are represented as 'factors'. Several common +// factors have been provided with the library for solving robotics/SLAM/Bundle +// Adjustment problems. Here we will use Projection factors to model the +// camera's landmark observations. Also, we will initialize the robot at some +// location using a Prior factor. #include #include @@ -56,12 +57,11 @@ using namespace gtsam; /* ************************************************************************* */ int main(int argc, char* argv[]) { - // Define the camera calibration parameters Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); - // Define the camera observation noise model - noiseModel::Isotropic::shared_ptr measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v + // Define the camera observation noise model, 1 pixel stddev + auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0); // Create the set of ground-truth landmarks vector points = createPoints(); @@ -69,10 +69,12 @@ int main(int argc, char* argv[]) { // Create the set of ground-truth poses vector poses = createPoses(); - // Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps to maintain proper linearization - // and efficient variable ordering, iSAM2 performs partial relinearization/reordering at each step. A parameter - // structure is available that allows the user to set various properties, such as the relinearization threshold - // and type of linear solver. For this example, we we set the relinearization threshold small so the iSAM2 result + // Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps + // to maintain proper linearization and efficient variable ordering, iSAM2 + // performs partial relinearization/reordering at each step. A parameter + // structure is available that allows the user to set various properties, such + // as the relinearization threshold and type of linear solver. For this + // example, we we set the relinearization threshold small so the iSAM2 result // will approach the batch result. ISAM2Params parameters; parameters.relinearizeThreshold = 0.01; @@ -83,44 +85,52 @@ int main(int argc, char* argv[]) { NonlinearFactorGraph graph; Values initialEstimate; - // Loop over the different poses, adding the observations to iSAM incrementally + // Loop over the poses, adding the observations to iSAM incrementally for (size_t i = 0; i < poses.size(); ++i) { - // Add factors for each landmark observation for (size_t j = 0; j < points.size(); ++j) { SimpleCamera camera(poses[i], *K); Point2 measurement = camera.project(points[j]); - graph.emplace_shared >(measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K); + graph.emplace_shared >( + measurement, measurementNoise, Symbol('x', i), Symbol('l', j), K); } // Add an initial guess for the current pose // Intentionally initialize the variables off from the ground truth - initialEstimate.insert(Symbol('x', i), poses[i].compose(Pose3(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)))); + static Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25), + Point3(0.05, -0.10, 0.20)); + initialEstimate.insert(Symbol('x', i), poses[i] * kDeltaPose); - // If this is the first iteration, add a prior on the first pose to set the coordinate frame - // and a prior on the first landmark to set the scale - // Also, as iSAM solves incrementally, we must wait until each is observed at least twice before - // adding it to iSAM. - if( i == 0) { - // Add a prior on pose x0 - noiseModel::Diagonal::shared_ptr poseNoise = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.3),Vector3::Constant(0.1)).finished()); // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw - graph.emplace_shared >(Symbol('x', 0), poses[0], poseNoise); + // If this is the first iteration, add a prior on the first pose to set the + // coordinate frame and a prior on the first landmark to set the scale Also, + // as iSAM solves incrementally, we must wait until each is observed at + // least twice before adding it to iSAM. + if (i == 0) { + // Add a prior on pose x0, 30cm std on x,y,z and 0.1 rad on roll,pitch,yaw + static auto kPosePrior = noiseModel::Diagonal::Sigmas( + (Vector(6) << Vector3::Constant(0.3), Vector3::Constant(0.1)) + .finished()); + graph.emplace_shared >(Symbol('x', 0), poses[0], + kPosePrior); // Add a prior on landmark l0 - noiseModel::Isotropic::shared_ptr pointNoise = noiseModel::Isotropic::Sigma(3, 0.1); - graph.emplace_shared >(Symbol('l', 0), points[0], pointNoise); // add directly to graph + static auto kPointPrior = noiseModel::Isotropic::Sigma(3, 0.1); + graph.emplace_shared >(Symbol('l', 0), points[0], + kPointPrior); // Add initial guesses to all observed landmarks // Intentionally initialize the variables off from the ground truth + static Point3 kDeltaPoint(-0.25, 0.20, 0.15); for (size_t j = 0; j < points.size(); ++j) - initialEstimate.insert(Symbol('l', j), points[j] +Point3(-0.25, 0.20, 0.15)); + initialEstimate.insert(Symbol('l', j), points[j] + kDeltaPoint); } else { // Update iSAM with the new factors isam.update(graph, initialEstimate); - // Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver. - // If accuracy is desired at the expense of time, update(*) can be called additional times - // to perform multiple optimizer iterations every step. + // Each call to iSAM2 update(*) performs one iteration of the iterative + // nonlinear solver. If accuracy is desired at the expense of time, + // update(*) can be called additional times to perform multiple optimizer + // iterations every step. isam.update(); Values currentEstimate = isam.calculateEstimate(); cout << "****************************************************" << endl; From 3116fd30b9e4a9530dca07d9c95ea6ff3dc2a9c3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 2 Oct 2018 21:53:49 -0400 Subject: [PATCH 066/197] Fixed lint errors --- gtsam/linear/GaussianConditional.cpp | 62 +++++++++++++--------------- 1 file changed, 28 insertions(+), 34 deletions(-) diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index eefb6302f..60187d129 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -12,11 +12,13 @@ /** * @file GaussianConditional.cpp * @brief Conditional Gaussian Base class - * @author Christian Potthast + * @author Christian Potthast, Frank Dellaert */ -#include -#include +#include +#include +#include + #include #ifdef __GNUC__ #pragma GCC diagnostic push @@ -28,9 +30,9 @@ #pragma GCC diagnostic pop #endif -#include -#include -#include +#include +#include +#include using namespace std; @@ -54,38 +56,36 @@ namespace gtsam { BaseFactor(key, R, name1, S, name2, T, d, sigmas), BaseConditional(1) {} /* ************************************************************************* */ - void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const - { + void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const { cout << s << " Conditional density "; - for(const_iterator it = beginFrontals(); it != endFrontals(); ++it) { + for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { cout << (boost::format("[%1%]")%(formatter(*it))).str() << " "; } cout << endl; cout << formatMatrixIndented(" R = ", get_R()) << endl; - for(const_iterator it = beginParents() ; it != endParents() ; ++it ) { + for (const_iterator it = beginParents() ; it != endParents() ; ++it) { cout << formatMatrixIndented((boost::format(" S[%1%] = ")%(formatter(*it))).str(), getA(it)) << endl; } cout << formatMatrixIndented(" d = ", getb(), true) << "\n"; - if(model_) + if (model_) model_->print(" Noise model: "); else cout << " No noise model" << endl; } /* ************************************************************************* */ - bool GaussianConditional::equals(const GaussianFactor& f, double tol) const - { - if (const GaussianConditional* c = dynamic_cast(&f)) - { + bool GaussianConditional::equals(const GaussianFactor& f, double tol) const { + if (const GaussianConditional* c = dynamic_cast(&f)) { // check if the size of the parents_ map is the same if (parents().size() != c->parents().size()) return false; // check if R_ and d_ are linear independent for (DenseIndex i = 0; i < Ab_.rows(); i++) { - list rows1; rows1.push_back(Vector(get_R().row(i))); - list rows2; rows2.push_back(Vector(c->get_R().row(i))); + list rows1, rows2; + rows1.push_back(Vector(get_R().row(i))); + rows2.push_back(Vector(c->get_R().row(i))); // check if the matrices are the same // iterate over the parents_ map @@ -109,16 +109,13 @@ namespace gtsam { return false; return true; - } - else - { + } else { return false; } } /* ************************************************************************* */ - VectorValues GaussianConditional::solve(const VectorValues& x) const - { + VectorValues GaussianConditional::solve(const VectorValues& x) const { // Concatenate all vector values that correspond to parent variables const Vector xS = x.vector(FastVector(beginParents(), endParents())); @@ -146,8 +143,7 @@ namespace gtsam { /* ************************************************************************* */ VectorValues GaussianConditional::solveOtherRHS( - const VectorValues& parents, const VectorValues& rhs) const - { + const VectorValues& parents, const VectorValues& rhs) const { // Concatenate all vector values that correspond to parent variables Vector xS = parents.vector(FastVector(beginParents(), endParents())); @@ -159,13 +155,13 @@ namespace gtsam { Vector soln = get_R().triangularView().solve(xS); // Scale by sigmas - if(model_) + if (model_) soln.array() *= model_->sigmas().array(); // Insert solution into a VectorValues VectorValues result; DenseIndex vectorPosition = 0; - for(const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { + for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { result.insert(*frontal, soln.segment(vectorPosition, getDim(frontal))); vectorPosition += getDim(frontal); } @@ -174,8 +170,7 @@ namespace gtsam { } /* ************************************************************************* */ - void GaussianConditional::solveTransposeInPlace(VectorValues& gy) const - { + void GaussianConditional::solveTransposeInPlace(VectorValues& gy) const { Vector frontalVec = gy.vector(FastVector(beginFrontals(), endFrontals())); frontalVec = gtsam::backSubstituteUpper(frontalVec, Matrix(get_R())); @@ -186,25 +181,24 @@ namespace gtsam { gy[*it] += -1.0 * Matrix(getA(it)).transpose() * frontalVec; // Scale by sigmas - if(model_) + if (model_) frontalVec.array() *= model_->sigmas().array(); // Write frontal solution into a VectorValues DenseIndex vectorPosition = 0; - for(const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { + for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { gy[*frontal] = frontalVec.segment(vectorPosition, getDim(frontal)); vectorPosition += getDim(frontal); } } /* ************************************************************************* */ - void GaussianConditional::scaleFrontalsBySigma(VectorValues& gy) const - { + void GaussianConditional::scaleFrontalsBySigma(VectorValues& gy) const { DenseIndex vectorPosition = 0; - for(const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { + for (const_iterator frontal = beginFrontals(); frontal != endFrontals(); ++frontal) { gy[*frontal].array() *= model_->sigmas().segment(vectorPosition, getDim(frontal)).array(); vectorPosition += getDim(frontal); } } -} +} // namespace gtsam From 566315f47da97a5735d7fdb3c4cbb0388047fba2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 2 Oct 2018 23:25:27 -0400 Subject: [PATCH 067/197] Solved overloading --- tests/testNonlinearOptimizer.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 9ddbbb1b2..3d30d6880 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -20,13 +20,12 @@ #include #include #include -#include -#include #include #include #include #include #include +#include #include #include @@ -394,19 +393,20 @@ class IterativeLM: public LevenbergMarquardtOptimizer { /// Solver specific parameters ConjugateGradientParameters cgParams_; + Values initial_; public: /// Constructor IterativeLM(const NonlinearFactorGraph& graph, const Values& initialValues, const ConjugateGradientParameters &p, const LevenbergMarquardtParams& params = LevenbergMarquardtParams::LegacyDefaults()) : - LevenbergMarquardtOptimizer(graph, initialValues, params), cgParams_(p) { + LevenbergMarquardtOptimizer(graph, initialValues, params), cgParams_(p), initial_(initialValues) { } /// Solve that uses conjugate gradient virtual VectorValues solve(const GaussianFactorGraph &gfg, - const Values& initial, const NonlinearOptimizerParams& params) const { - VectorValues zeros = initial.zeroVectors(); + const NonlinearOptimizerParams& params) const { + VectorValues zeros = initial_.zeroVectors(); return conjugateGradientDescent(gfg, zeros, cgParams_); } }; From 366b2485c1d53c21d887a08357d6383c4dfe8b21 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:00:22 -0400 Subject: [PATCH 068/197] Fixed warnings flagged by Ubuntu g++ --- gtsam/3rdparty/CCOLAMD/Source/ccolamd.c | 11 ++-- gtsam/3rdparty/metis/GKlib/csr.c | 32 ++++++----- gtsam/3rdparty/metis/GKlib/getopt.c | 71 +++++++++++++------------ gtsam/inference/BayesTree-inst.h | 14 ++--- 4 files changed, 66 insertions(+), 62 deletions(-) diff --git a/gtsam/3rdparty/CCOLAMD/Source/ccolamd.c b/gtsam/3rdparty/CCOLAMD/Source/ccolamd.c index 9a08e3ea8..d5e8da2f0 100644 --- a/gtsam/3rdparty/CCOLAMD/Source/ccolamd.c +++ b/gtsam/3rdparty/CCOLAMD/Source/ccolamd.c @@ -1560,8 +1560,9 @@ PUBLIC Int CCOLAMD_2 /* returns TRUE if successful, FALSE otherwise */ Int *dead_cols ; Int set1 ; Int set2 ; +#ifndef NDEBUG Int cs ; - +#endif int ok ; #ifndef NDEBUG @@ -1909,8 +1910,10 @@ PUBLIC Int CCOLAMD_2 /* returns TRUE if successful, FALSE otherwise */ p [k] = col ; ASSERT (A [col] == EMPTY) ; - cs = CMEMBER (col) ; +#ifndef NDEBUG + cs = CMEMBER (col) ; ASSERT (k >= cset_start [cs] && k < cset_start [cs+1]) ; +#endif A [col] = k ; k++ ; @@ -1926,11 +1929,11 @@ PUBLIC Int CCOLAMD_2 /* returns TRUE if successful, FALSE otherwise */ if (A [col] == EMPTY) { k = Col [col].shared2.order ; - cs = CMEMBER (col) ; #ifndef NDEBUG + cs = CMEMBER (col) ; dead_cols [cs]-- ; -#endif ASSERT (k >= cset_start [cs] && k < cset_start [cs+1]) ; +#endif DEBUG1 (("ccolamd output ordering: k "ID" col "ID " (dense or null col)\n", k, col)) ; p [k] = col ; diff --git a/gtsam/3rdparty/metis/GKlib/csr.c b/gtsam/3rdparty/metis/GKlib/csr.c index a19d793bd..57934ee9d 100644 --- a/gtsam/3rdparty/metis/GKlib/csr.c +++ b/gtsam/3rdparty/metis/GKlib/csr.c @@ -1323,29 +1323,27 @@ void gk_csr_Normalize(gk_csr_t *mat, int what, int norm) ssize_t *ptr; float *val, sum; - if (what&GK_CSR_ROW && mat->rowval) { - n = mat->nrows; + if (what & GK_CSR_ROW && mat->rowval) { + n = mat->nrows; ptr = mat->rowptr; val = mat->rowval; - #pragma omp parallel if (ptr[n] > OMPMINOPS) +#pragma omp parallel if (ptr[n] > OMPMINOPS) { - #pragma omp for private(j,sum) schedule(static) - for (i=0; i 0 */ +#pragma omp for private(j, sum) schedule(static) + for (i = 0; i < n; i++) { + for (sum = 0.0, j = ptr[i]; j < ptr[i + 1]; j++) { + if (norm == 2) + sum += val[j] * val[j]; + else if (norm == 1) + sum += val[j]; /* assume val[j] > 0 */ } if (sum > 0) { - if (norm == 2) - sum=1.0/sqrt(sum); - else if (norm == 1) - sum=1.0/sum; - for (j=ptr[i]; jconditional_->frontals()) { - if(!first) parent += ","; first = false; + for (Key index : clique->conditional_->frontals()) { + if (!first) parent += ","; + first = false; parent += indexFormatter(index); } - if(clique->parent()){ + if (clique->parent()) { parent += " : "; s << parentnum << "->" << num << "\n"; } first = true; - for(Key sep: clique->conditional_->parents()) { - if(!first) parent += ","; first = false; + for (Key sep : clique->conditional_->parents()) { + if (!first) parent += ","; + first = false; parent += indexFormatter(sep); } parent += "\"];\n"; s << parent; parentnum = num; - for(sharedClique c: clique->children) { + for (sharedClique c : clique->children) { num++; saveGraph(s, c, indexFormatter, parentnum); } From 4faac98f512314da1d5e0033b3897d43e2d5addd Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:00:49 -0400 Subject: [PATCH 069/197] Pointed pipeline to new docker image, using latest system Eigen3 --- bitbucket-pipelines.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 2d8b7f061..288a40b14 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -3,14 +3,16 @@ # Only use spaces to indent your .yml configuration. # ----- # You can specify a custom docker image from Docker Hub as your build environment. -image: ilssim/cmake-boost-qt5 +image: dellaert/ubuntu-boost-tbb-eigen3:latest pipelines: default: - step: + caches: + - docker script: # Modify the commands below to build your repository. - mkdir build - cd build - - cmake .. + - cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_USE_EIGEN_MKL=OFF .. - make - make check \ No newline at end of file From e742cde2c8a53ba905f0f9ba44ae447a5d02d2a2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:03:45 -0400 Subject: [PATCH 070/197] Fixed pipeline config --- bitbucket-pipelines.yml | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 288a40b14..33204aea2 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -1,15 +1,12 @@ -# This is a sample build configuration for C++ – Make. -# Check our guides at https://confluence.atlassian.com/x/5Q4SMw for more examples. -# Only use spaces to indent your .yml configuration. +# Built from sample configuration for C++ – Make. +# Check https://confluence.atlassian.com/x/5Q4SMw for more examples. # ----- -# You can specify a custom docker image from Docker Hub as your build environment. +# Our custom docker image from Docker Hub as the build environment. image: dellaert/ubuntu-boost-tbb-eigen3:latest pipelines: default: - step: - caches: - - docker script: # Modify the commands below to build your repository. - mkdir build - cd build From 5d49177c8a50f8b0d394f93dfee4400150d45fe3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:38:11 -0400 Subject: [PATCH 071/197] Added docker file to build pipeline docker image --- docker/ubuntu-boost-tbb-eigen3/Dockerfile | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 docker/ubuntu-boost-tbb-eigen3/Dockerfile diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb-eigen3/Dockerfile new file mode 100644 index 000000000..b400c0538 --- /dev/null +++ b/docker/ubuntu-boost-tbb-eigen3/Dockerfile @@ -0,0 +1,18 @@ +# Get the base Ubuntu image from Docker Hub +FROM ubuntu:latest + +# Update apps on the base image +RUN apt-get -y update && apt-get install -y + +# Install C++ +RUN apt-get -y install build-essential + +# Install boost and cmake +RUN apt-get -y install libboost-all-dev cmake + +# Install TBB +RUN apt-get -y install libtbb-dev + +# Install latest Eigen +RUN apt-get install -y libeigen3-dev + From eb4659bcb66d7f7a55dd21e7f66cf10c449f0b62 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:38:32 -0400 Subject: [PATCH 072/197] Added -j4 flags --- bitbucket-pipelines.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 33204aea2..8a8d5dd14 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -11,5 +11,5 @@ pipelines: - mkdir build - cd build - cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_USE_EIGEN_MKL=OFF .. - - make - - make check \ No newline at end of file + - make -j4 + - make -j4 check \ No newline at end of file From ca80678ffcdb069e0301e8c49a1efaf8ebabc9a3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:38:50 -0400 Subject: [PATCH 073/197] Fixed more warnings --- examples/SolverComparer.cpp | 2 +- gtsam/3rdparty/metis/GKlib/csr.c | 31 +++++++++++++++---------------- gtsam/base/cholesky.cpp | 5 +++-- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index deaf3b781..63c512edb 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -206,7 +206,7 @@ int main(int argc, char *argv[]) { } #ifdef GTSAM_USE_TBB - std::auto_ptr init; + std::unique_ptr init; if(nThreads > 0) { cout << "Using " << nThreads << " threads" << endl; init.reset(new tbb::task_scheduler_init(nThreads)); diff --git a/gtsam/3rdparty/metis/GKlib/csr.c b/gtsam/3rdparty/metis/GKlib/csr.c index 57934ee9d..4f6213c49 100644 --- a/gtsam/3rdparty/metis/GKlib/csr.c +++ b/gtsam/3rdparty/metis/GKlib/csr.c @@ -1349,27 +1349,26 @@ void gk_csr_Normalize(gk_csr_t *mat, int what, int norm) } } - if (what&GK_CSR_COL && mat->colval) { - n = mat->ncols; + if (what & GK_CSR_COL && mat->colval) { + n = mat->ncols; ptr = mat->colptr; val = mat->colval; - #pragma omp parallel if (ptr[n] > OMPMINOPS) +#pragma omp parallel if (ptr[n] > OMPMINOPS) { - #pragma omp for private(j,sum) schedule(static) - for (i=0; i 0) { - if (norm == 2) - sum=1.0/sqrt(sum); - else if (norm == 1) - sum=1.0/sum; - for (j=ptr[i]; j= 0 && nFrontal <= size_t(n)); + assert(ABC.rows() >= topleft); + const size_t n = static_cast(ABC.rows() - topleft); + assert(nFrontal <= size_t(n)); // Create views on blocks auto A = ABC.block(topleft, topleft, nFrontal, nFrontal); From 90373d878666e3e5719077512e965456c4b62720 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:51:20 -0400 Subject: [PATCH 074/197] Solved overloading, cherry-picked from fix/isam2 branch --- tests/testNonlinearOptimizer.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 9ddbbb1b2..3d30d6880 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -20,13 +20,12 @@ #include #include #include -#include -#include #include #include #include #include #include +#include #include #include @@ -394,19 +393,20 @@ class IterativeLM: public LevenbergMarquardtOptimizer { /// Solver specific parameters ConjugateGradientParameters cgParams_; + Values initial_; public: /// Constructor IterativeLM(const NonlinearFactorGraph& graph, const Values& initialValues, const ConjugateGradientParameters &p, const LevenbergMarquardtParams& params = LevenbergMarquardtParams::LegacyDefaults()) : - LevenbergMarquardtOptimizer(graph, initialValues, params), cgParams_(p) { + LevenbergMarquardtOptimizer(graph, initialValues, params), cgParams_(p), initial_(initialValues) { } /// Solve that uses conjugate gradient virtual VectorValues solve(const GaussianFactorGraph &gfg, - const Values& initial, const NonlinearOptimizerParams& params) const { - VectorValues zeros = initial.zeroVectors(); + const NonlinearOptimizerParams& params) const { + VectorValues zeros = initial_.zeroVectors(); return conjugateGradientDescent(gfg, zeros, cgParams_); } }; From f60e3332a4a3fb1a0519f1a832de23ad9fa1b5c8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 21:51:42 -0400 Subject: [PATCH 075/197] Made explicit float to avoid ambiguous overload. --- gtsam/geometry/tests/testPoint2.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/gtsam/geometry/tests/testPoint2.cpp b/gtsam/geometry/tests/testPoint2.cpp index e2a5bcdea..8b9e8a7e6 100644 --- a/gtsam/geometry/tests/testPoint2.cpp +++ b/gtsam/geometry/tests/testPoint2.cpp @@ -100,12 +100,12 @@ TEST( Point2, expmap) { /* ************************************************************************* */ TEST( Point2, arithmetic) { - EXPECT(assert_equal( Point2(-5,-6), -Point2(5,6) )); - EXPECT(assert_equal( Point2(5,6), Point2(4,5)+Point2(1,1))); - EXPECT(assert_equal( Point2(3,4), Point2(4,5)-Point2(1,1) )); - EXPECT(assert_equal( Point2(8,6), Point2(4,3)*2)); - EXPECT(assert_equal( Point2(4,6), 2*Point2(2,3))); - EXPECT(assert_equal( Point2(2,3), Point2(4,6)/2)); + EXPECT(assert_equal(Point2(-5, -6), -Point2(5, 6))); + EXPECT(assert_equal(Point2(5, 6), Point2(4, 5) + Point2(1, 1))); + EXPECT(assert_equal(Point2(3, 4), Point2(4, 5) - Point2(1, 1))); + EXPECT(assert_equal(Point2(8, 6), Point2(4, 3) * 2)); + EXPECT(assert_equal(Point2(4, 6), 2.0 * Point2(2, 3))); + EXPECT(assert_equal(Point2(2, 3), Point2(4, 6) / 2)); } /* ************************************************************************* */ From 1bc479fc3c992b8009579ee8a1eaf61bfabb375d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 22:54:36 -0400 Subject: [PATCH 076/197] Fixed some lint errors --- gtsam/geometry/Unit3.cpp | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index dacb5c3fd..00edc1ad4 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -21,7 +21,7 @@ #include #include -#include // for GTSAM_USE_TBB +#include // for GTSAM_USE_TBB #ifdef __clang__ # pragma clang diagnostic push @@ -36,13 +36,14 @@ #include #include #include +#include using namespace std; namespace gtsam { /* ************************************************************************* */ -Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2,3> H) { +Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2, 3> H) { // 3*3 Derivative of representation with respect to point is 3*3: Matrix3 D_p_point; Unit3 direction; @@ -54,7 +55,7 @@ Unit3 Unit3::FromPoint3(const Point3& point, OptionalJacobian<2,3> H) { /* ************************************************************************* */ Unit3 Unit3::Random(boost::mt19937 & rng) { - // TODO allow any engine without including all of boost :-( + // TODO(dellaert): allow any engine without including all of boost :-( boost::uniform_on_sphere randomDirection(3); // This variate_generator object is required for versions of boost somewhere // around 1.46, instead of drawing directly using boost::uniform_on_sphere(rng). @@ -161,7 +162,8 @@ Matrix3 Unit3::skew() const { } /* ************************************************************************* */ -double Unit3::dot(const Unit3& q, OptionalJacobian<1,2> H_p, OptionalJacobian<1,2> H_q) const { +double Unit3::dot(const Unit3& q, OptionalJacobian<1, 2> H_p, + OptionalJacobian<1, 2> H_q) const { // Get the unit vectors of each, and the derivative. Matrix32 H_pn_p; Point3 pn = point3(H_p ? &H_pn_p : nullptr); @@ -185,7 +187,7 @@ double Unit3::dot(const Unit3& q, OptionalJacobian<1,2> H_p, OptionalJacobian<1, } /* ************************************************************************* */ -Vector2 Unit3::error(const Unit3& q, OptionalJacobian<2,2> H_q) const { +Vector2 Unit3::error(const Unit3& q, OptionalJacobian<2, 2> H_q) const { // 2D error is equal to B'*q, as B is 3x2 matrix and q is 3x1 const Vector2 xi = basis().transpose() * q.p_; if (H_q) { @@ -195,7 +197,8 @@ Vector2 Unit3::error(const Unit3& q, OptionalJacobian<2,2> H_q) const { } /* ************************************************************************* */ -Vector2 Unit3::errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p, OptionalJacobian<2, 2> H_q) const { +Vector2 Unit3::errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p, + OptionalJacobian<2, 2> H_q) const { // Get the point3 of this, and the derivative. Matrix32 H_qn_q; const Point3 qn = q.point3(H_q ? &H_qn_q : nullptr); @@ -230,7 +233,7 @@ Vector2 Unit3::errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p, OptionalJ } /* ************************************************************************* */ -double Unit3::distance(const Unit3& q, OptionalJacobian<1,2> H) const { +double Unit3::distance(const Unit3& q, OptionalJacobian<1, 2> H) const { Matrix2 H_xi_q; const Vector2 xi = error(q, H ? &H_xi_q : nullptr); const double theta = xi.norm(); @@ -277,4 +280,4 @@ Vector2 Unit3::localCoordinates(const Unit3& other) const { } /* ************************************************************************* */ -} +} // namespace gtsam From b9f080456c4164f11812c6ae1f960bd6adb741ca Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 22:54:48 -0400 Subject: [PATCH 077/197] Catch exception by value --- wrap/FileWriter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wrap/FileWriter.cpp b/wrap/FileWriter.cpp index 783661819..2c3843b37 100644 --- a/wrap/FileWriter.cpp +++ b/wrap/FileWriter.cpp @@ -29,7 +29,7 @@ void FileWriter::emit(bool add_header, bool force_overwrite) const { bool file_exists = true; try { existing_contents = file_contents(filename_.c_str(), add_header); - } catch (CantOpenFile) { + } catch (const CantOpenFile& e) { file_exists = false; } From 845574860fb7dbbf631de84067036e79ad15ec21 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 22:55:46 -0400 Subject: [PATCH 078/197] Try cosmic rather than latest (which throws internal compiler error) --- docker/ubuntu-boost-tbb-eigen3/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb-eigen3/Dockerfile index b400c0538..bb2bf4719 100644 --- a/docker/ubuntu-boost-tbb-eigen3/Dockerfile +++ b/docker/ubuntu-boost-tbb-eigen3/Dockerfile @@ -1,5 +1,5 @@ # Get the base Ubuntu image from Docker Hub -FROM ubuntu:latest +FROM ubuntu:cosmic # Update apps on the base image RUN apt-get -y update && apt-get install -y From a932d4bd5e06f9b906a70a592a079669042198c0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 23:13:15 -0400 Subject: [PATCH 079/197] Trying xenial --- bitbucket-pipelines.yml | 2 +- docker/ubuntu-boost-tbb-eigen3/Dockerfile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 8a8d5dd14..58e27c79a 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -2,7 +2,7 @@ # Check https://confluence.atlassian.com/x/5Q4SMw for more examples. # ----- # Our custom docker image from Docker Hub as the build environment. -image: dellaert/ubuntu-boost-tbb-eigen3:latest +image: dellaert/ubuntu-boost-tbb-eigen3:xenial pipelines: default: diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb-eigen3/Dockerfile index bb2bf4719..dda4fbbaf 100644 --- a/docker/ubuntu-boost-tbb-eigen3/Dockerfile +++ b/docker/ubuntu-boost-tbb-eigen3/Dockerfile @@ -1,5 +1,5 @@ # Get the base Ubuntu image from Docker Hub -FROM ubuntu:cosmic +FROM ubuntu:xenial # Update apps on the base image RUN apt-get -y update && apt-get install -y From 632dcd0bf2cf60e755bb40216f85706b6222f611 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 23:24:19 -0400 Subject: [PATCH 080/197] Trying bionic, again, with -j2 flag --- bitbucket-pipelines.yml | 6 +++--- docker/ubuntu-boost-tbb-eigen3/Dockerfile | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 58e27c79a..d41ba7f26 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -2,7 +2,7 @@ # Check https://confluence.atlassian.com/x/5Q4SMw for more examples. # ----- # Our custom docker image from Docker Hub as the build environment. -image: dellaert/ubuntu-boost-tbb-eigen3:xenial +image: dellaert/ubuntu-boost-tbb-eigen3:bionic pipelines: default: @@ -11,5 +11,5 @@ pipelines: - mkdir build - cd build - cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_USE_EIGEN_MKL=OFF .. - - make -j4 - - make -j4 check \ No newline at end of file + - make -j2 + - make -j2 check \ No newline at end of file diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb-eigen3/Dockerfile index dda4fbbaf..33aa1ab96 100644 --- a/docker/ubuntu-boost-tbb-eigen3/Dockerfile +++ b/docker/ubuntu-boost-tbb-eigen3/Dockerfile @@ -1,5 +1,5 @@ # Get the base Ubuntu image from Docker Hub -FROM ubuntu:xenial +FROM ubuntu:bionic # Update apps on the base image RUN apt-get -y update && apt-get install -y From 285e2da5a808c6b88d2d0f389d0ba3d0bab6d159 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 23:55:49 -0400 Subject: [PATCH 081/197] Fixed lint errors --- gtsam/geometry/Unit3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index 00edc1ad4..e0e0ecb56 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -257,7 +257,7 @@ Unit3 Unit3::retract(const Vector2& v) const { std::cos(theta) * p_ + xi_hat * (sin(theta) / theta); return Unit3(exp_p_xi_hat); } - + /* ************************************************************************* */ Vector2 Unit3::localCoordinates(const Unit3& other) const { const double x = p_.dot(other.p_); From e1466b2609daa9ca06bfef9e1732a6f8a9dde540 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 08:45:42 -0400 Subject: [PATCH 082/197] Fixed uninitialized problem --- gtsam_unstable/slam/SmartRangeFactor.h | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 5e107ea58..2170c8599 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -14,7 +14,12 @@ #include #include #include + +#include #include +#include +#include +#include namespace gtsam { @@ -83,6 +88,7 @@ public: /** * Triangulate a point from at least three pose-range pairs * Checks for best pair that includes first point + * Raise runtime_error if not well defined. */ Point2 triangulate(const Values& x) const { //gttic_(triangulate); @@ -96,7 +102,7 @@ public: Circle2 circle1 = circles.front(); boost::optional best_fh; - boost::optional best_circle; + boost::optional bestCircle2; // loop over all circles for(const Circle2& it: circles) { @@ -111,13 +117,14 @@ public: // if h is large, the intersections are well defined. if (fh && (!best_fh || fh->y() > best_fh->y())) { best_fh = fh; - best_circle = it; + bestCircle2 = it; } } // use best fh to find actual intersection points + if (bestCircle2 && best_fh) { std::list intersections = circleCircleIntersection( - circle1.center, best_circle->center, best_fh); + circle1.center, bestCircle2->center, best_fh); // pick winner based on other measurements double error1 = 0, error2 = 0; @@ -127,7 +134,10 @@ public: error2 += distance2(it.center, p2); } return (error1 < error2) ? p1 : p2; - //gttoc_(triangulate); + } else { + throw std::runtime_error("triangulate failed"); + } + // gttoc_(triangulate); } /** From a34a9b8ff1512e62f738c6a276cd38204ec32f49 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 08:46:30 -0400 Subject: [PATCH 083/197] Fixed remaining lint errors --- gtsam_unstable/slam/SmartRangeFactor.h | 31 ++++++++++++-------------- 1 file changed, 14 insertions(+), 17 deletions(-) diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 2170c8599..3164b360e 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -28,8 +28,7 @@ namespace gtsam { * @addtogroup SLAM */ class SmartRangeFactor: public NoiseModelFactor { -protected: - + protected: struct Circle2 { Circle2(const Point2& p, double r) : center(p), radius(r) { @@ -40,11 +39,10 @@ protected: typedef SmartRangeFactor This; - std::vector measurements_; ///< Range measurements - double variance_; ///< variance on noise - -public: + std::vector measurements_; ///< Range measurements + double variance_; ///< variance on noise + public: /** Default constructor: don't use directly */ SmartRangeFactor() { } @@ -53,7 +51,7 @@ public: * Constructor * @param s standard deviation of range measurement noise */ - SmartRangeFactor(double s) : + explicit SmartRangeFactor(double s) : NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) { } @@ -91,7 +89,7 @@ public: * Raise runtime_error if not well defined. */ Point2 triangulate(const Values& x) const { - //gttic_(triangulate); + // gttic_(triangulate); // create n circles corresponding to measured range around each pose std::list circles; size_t n = size(); @@ -105,11 +103,11 @@ public: boost::optional bestCircle2; // loop over all circles - for(const Circle2& it: circles) { + for (const Circle2& it : circles) { // distance between circle centers. double d = distance2(circle1.center, it.center); if (d < 1e-9) - continue; // skip circles that are in the same location + continue; // skip circles that are in the same location // Find f and h, the intersection points in normalized circles boost::optional fh = circleCircleIntersection( circle1.radius / d, it.radius / d); @@ -129,7 +127,7 @@ public: // pick winner based on other measurements double error1 = 0, error2 = 0; Point2 p1 = intersections.front(), p2 = intersections.back(); - for(const Circle2& it: circles) { + for (const Circle2& it : circles) { error1 += distance2(it.center, p1); error2 += distance2(it.center, p2); } @@ -147,19 +145,20 @@ public: boost::optional&> H = boost::none) const { size_t n = size(); if (n < 3) { - if (H) + if (H) { // set Jacobians to zero for n<3 for (size_t j = 0; j < n; j++) (*H)[j] = Matrix::Zero(3, 1); + } return Z_1x1; } else { Vector error = Z_1x1; // triangulate to get the optimized point - // TODO: Should we have a (better?) variant that does this in relative coordinates ? + // TODO(dellaert): Should we have a (better?) variant that does this in relative coordinates ? Point2 optimizedPoint = triangulate(x); - // TODO: triangulation should be followed by an optimization given poses + // TODO(dellaert): triangulation should be followed by an optimization given poses // now evaluate the errors between predicted and measured range for (size_t j = 0; j < n; j++) { const Pose2& pose = x.at(keys_[j]); @@ -178,8 +177,6 @@ public: return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - }; - -} // \namespace gtsam +} // \namespace gtsam From 767c5d41ee8ef3914ce855997a984849702988ae Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 09:11:50 -0400 Subject: [PATCH 084/197] Showed compiler that B_ is always initialized --- gtsam/geometry/Unit3.cpp | 100 +++++++++++++++++++-------------------- 1 file changed, 49 insertions(+), 51 deletions(-) diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index e0e0ecb56..2c49f72e7 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -74,61 +74,59 @@ const Matrix32& Unit3::basis(OptionalJacobian<6, 2> H) const { tbb::mutex::scoped_lock lock(B_mutex_); #endif - // Return cached basis if available and the Jacobian isn't needed. if (B_ && !H) { + // Return cached basis if available and the Jacobian isn't needed. return *B_; - } - - // Return cached basis and derivatives if available. - if (B_ && H && H_B_) { + } else if (B_ && H && H_B_) { + // Return cached basis and derivatives if available. *H = *H_B_; + return *B_; + } else { + B_.reset(Matrix32()); + // Get the unit vector and derivative wrt this. + // NOTE(hayk): We can't call point3(), because it would recursively call basis(). + const Point3 n(p_); + + // Get the axis of rotation with the minimum projected length of the point + Point3 axis(0, 0, 1); + double mx = fabs(n.x()), my = fabs(n.y()), mz = fabs(n.z()); + if ((mx <= my) && (mx <= mz)) { + axis = Point3(1.0, 0.0, 0.0); + } else if ((my <= mx) && (my <= mz)) { + axis = Point3(0.0, 1.0, 0.0); + } + + // Choose the direction of the first basis vector b1 in the tangent plane by crossing n with + // the chosen axis. + Matrix33 H_B1_n; + Point3 B1 = gtsam::cross(n, axis, H ? &H_B1_n : nullptr); + + // Normalize result to get a unit vector: b1 = B1 / |B1|. + Matrix33 H_b1_B1; + Point3 b1 = normalize(B1, H ? &H_b1_B1 : nullptr); + + // Get the second basis vector b2, which is orthogonal to n and b1, by crossing them. + // No need to normalize this, p and b1 are orthogonal unit vectors. + Matrix33 H_b2_n, H_b2_b1; + Point3 b2 = gtsam::cross(n, b1, H ? &H_b2_n : nullptr, H ? &H_b2_b1 : nullptr); + + // Create the basis by stacking b1 and b2. + (*B_) << b1.x(), b2.x(), b1.y(), b2.y(), b1.z(), b2.z(); + + if (H) { + // Chain rule tomfoolery to compute the derivative. + const Matrix32& H_n_p = *B_; + const Matrix32 H_b1_p = H_b1_B1 * H_B1_n * H_n_p; + const Matrix32 H_b2_p = H_b2_n * H_n_p + H_b2_b1 * H_b1_p; + + // Cache the derivative and fill the result. + H_B_.reset(Matrix62()); + (*H_B_) << H_b1_p, H_b2_p; + *H = *H_B_; + } + return *B_; } - - // Get the unit vector and derivative wrt this. - // NOTE(hayk): We can't call point3(), because it would recursively call basis(). - const Point3 n(p_); - - // Get the axis of rotation with the minimum projected length of the point - Point3 axis(0, 0, 1); - double mx = fabs(n.x()), my = fabs(n.y()), mz = fabs(n.z()); - if ((mx <= my) && (mx <= mz)) { - axis = Point3(1.0, 0.0, 0.0); - } else if ((my <= mx) && (my <= mz)) { - axis = Point3(0.0, 1.0, 0.0); - } - - // Choose the direction of the first basis vector b1 in the tangent plane by crossing n with - // the chosen axis. - Matrix33 H_B1_n; - Point3 B1 = gtsam::cross(n, axis, H ? &H_B1_n : nullptr); - - // Normalize result to get a unit vector: b1 = B1 / |B1|. - Matrix33 H_b1_B1; - Point3 b1 = normalize(B1, H ? &H_b1_B1 : nullptr); - - // Get the second basis vector b2, which is orthogonal to n and b1, by crossing them. - // No need to normalize this, p and b1 are orthogonal unit vectors. - Matrix33 H_b2_n, H_b2_b1; - Point3 b2 = gtsam::cross(n, b1, H ? &H_b2_n : nullptr, H ? &H_b2_b1 : nullptr); - - // Create the basis by stacking b1 and b2. - B_.reset(Matrix32()); - (*B_) << b1.x(), b2.x(), b1.y(), b2.y(), b1.z(), b2.z(); - - if (H) { - // Chain rule tomfoolery to compute the derivative. - const Matrix32& H_n_p = *B_; - const Matrix32 H_b1_p = H_b1_B1 * H_B1_n * H_n_p; - const Matrix32 H_b2_p = H_b2_n * H_n_p + H_b2_b1 * H_b1_p; - - // Cache the derivative and fill the result. - H_B_.reset(Matrix62()); - (*H_B_) << H_b1_p, H_b2_p; - *H = *H_B_; - } - - return *B_; } /* ************************************************************************* */ @@ -257,7 +255,7 @@ Unit3 Unit3::retract(const Vector2& v) const { std::cos(theta) * p_ + xi_hat * (sin(theta) / theta); return Unit3(exp_p_xi_hat); } - + /* ************************************************************************* */ Vector2 Unit3::localCoordinates(const Unit3& other) const { const double x = p_.dot(other.p_); From 1cf5a2a80b7ea367ca116a468afee93a9dfe38af Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 8 Oct 2018 23:55:49 -0400 Subject: [PATCH 085/197] Fixed lint errors --- gtsam/geometry/Unit3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/Unit3.cpp b/gtsam/geometry/Unit3.cpp index 00edc1ad4..e0e0ecb56 100644 --- a/gtsam/geometry/Unit3.cpp +++ b/gtsam/geometry/Unit3.cpp @@ -257,7 +257,7 @@ Unit3 Unit3::retract(const Vector2& v) const { std::cos(theta) * p_ + xi_hat * (sin(theta) / theta); return Unit3(exp_p_xi_hat); } - + /* ************************************************************************* */ Vector2 Unit3::localCoordinates(const Unit3& other) const { const double x = p_.dot(other.p_); From 560ee010c2c13a09036c7eb22189ccab7ee50030 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 08:45:42 -0400 Subject: [PATCH 086/197] Fixed uninitialized problem --- gtsam_unstable/slam/SmartRangeFactor.h | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 5e107ea58..2170c8599 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -14,7 +14,12 @@ #include #include #include + +#include #include +#include +#include +#include namespace gtsam { @@ -83,6 +88,7 @@ public: /** * Triangulate a point from at least three pose-range pairs * Checks for best pair that includes first point + * Raise runtime_error if not well defined. */ Point2 triangulate(const Values& x) const { //gttic_(triangulate); @@ -96,7 +102,7 @@ public: Circle2 circle1 = circles.front(); boost::optional best_fh; - boost::optional best_circle; + boost::optional bestCircle2; // loop over all circles for(const Circle2& it: circles) { @@ -111,13 +117,14 @@ public: // if h is large, the intersections are well defined. if (fh && (!best_fh || fh->y() > best_fh->y())) { best_fh = fh; - best_circle = it; + bestCircle2 = it; } } // use best fh to find actual intersection points + if (bestCircle2 && best_fh) { std::list intersections = circleCircleIntersection( - circle1.center, best_circle->center, best_fh); + circle1.center, bestCircle2->center, best_fh); // pick winner based on other measurements double error1 = 0, error2 = 0; @@ -127,7 +134,10 @@ public: error2 += distance2(it.center, p2); } return (error1 < error2) ? p1 : p2; - //gttoc_(triangulate); + } else { + throw std::runtime_error("triangulate failed"); + } + // gttoc_(triangulate); } /** From 7da4824568071d6b42d56bd33aa39aad840b20f5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 08:46:30 -0400 Subject: [PATCH 087/197] Fixed remaining lint errors --- gtsam_unstable/slam/SmartRangeFactor.h | 31 ++++++++++++-------------- 1 file changed, 14 insertions(+), 17 deletions(-) diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 2170c8599..3164b360e 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -28,8 +28,7 @@ namespace gtsam { * @addtogroup SLAM */ class SmartRangeFactor: public NoiseModelFactor { -protected: - + protected: struct Circle2 { Circle2(const Point2& p, double r) : center(p), radius(r) { @@ -40,11 +39,10 @@ protected: typedef SmartRangeFactor This; - std::vector measurements_; ///< Range measurements - double variance_; ///< variance on noise - -public: + std::vector measurements_; ///< Range measurements + double variance_; ///< variance on noise + public: /** Default constructor: don't use directly */ SmartRangeFactor() { } @@ -53,7 +51,7 @@ public: * Constructor * @param s standard deviation of range measurement noise */ - SmartRangeFactor(double s) : + explicit SmartRangeFactor(double s) : NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) { } @@ -91,7 +89,7 @@ public: * Raise runtime_error if not well defined. */ Point2 triangulate(const Values& x) const { - //gttic_(triangulate); + // gttic_(triangulate); // create n circles corresponding to measured range around each pose std::list circles; size_t n = size(); @@ -105,11 +103,11 @@ public: boost::optional bestCircle2; // loop over all circles - for(const Circle2& it: circles) { + for (const Circle2& it : circles) { // distance between circle centers. double d = distance2(circle1.center, it.center); if (d < 1e-9) - continue; // skip circles that are in the same location + continue; // skip circles that are in the same location // Find f and h, the intersection points in normalized circles boost::optional fh = circleCircleIntersection( circle1.radius / d, it.radius / d); @@ -129,7 +127,7 @@ public: // pick winner based on other measurements double error1 = 0, error2 = 0; Point2 p1 = intersections.front(), p2 = intersections.back(); - for(const Circle2& it: circles) { + for (const Circle2& it : circles) { error1 += distance2(it.center, p1); error2 += distance2(it.center, p2); } @@ -147,19 +145,20 @@ public: boost::optional&> H = boost::none) const { size_t n = size(); if (n < 3) { - if (H) + if (H) { // set Jacobians to zero for n<3 for (size_t j = 0; j < n; j++) (*H)[j] = Matrix::Zero(3, 1); + } return Z_1x1; } else { Vector error = Z_1x1; // triangulate to get the optimized point - // TODO: Should we have a (better?) variant that does this in relative coordinates ? + // TODO(dellaert): Should we have a (better?) variant that does this in relative coordinates ? Point2 optimizedPoint = triangulate(x); - // TODO: triangulation should be followed by an optimization given poses + // TODO(dellaert): triangulation should be followed by an optimization given poses // now evaluate the errors between predicted and measured range for (size_t j = 0; j < n; j++) { const Pose2& pose = x.at(keys_[j]); @@ -178,8 +177,6 @@ public: return boost::static_pointer_cast( gtsam::NonlinearFactor::shared_ptr(new This(*this))); } - }; - -} // \namespace gtsam +} // \namespace gtsam From e37ff1e1058a15f564b8a38efb72e264c4fff808 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 9 Oct 2018 12:57:56 -0400 Subject: [PATCH 088/197] Switched to Eigen 3.3.4 --- gtsam/3rdparty/Eigen/.hg_archival.txt | 4 - gtsam/3rdparty/Eigen/.hgeol | 3 + gtsam/3rdparty/Eigen/.hgignore | 2 + gtsam/3rdparty/Eigen/.hgtags | 22 +- gtsam/3rdparty/Eigen/CMakeLists.txt | 218 +- gtsam/3rdparty/Eigen/CTestConfig.cmake | 4 +- gtsam/3rdparty/Eigen/Eigen/Array | 11 - gtsam/3rdparty/Eigen/Eigen/CMakeLists.txt | 2 +- gtsam/3rdparty/Eigen/Eigen/Cholesky | 17 +- gtsam/3rdparty/Eigen/Eigen/CholmodSupport | 11 +- gtsam/3rdparty/Eigen/Eigen/Core | 290 +- gtsam/3rdparty/Eigen/Eigen/Eigen | 2 +- gtsam/3rdparty/Eigen/Eigen/Eigen2Support | 95 - gtsam/3rdparty/Eigen/Eigen/Eigenvalues | 15 +- gtsam/3rdparty/Eigen/Eigen/Geometry | 59 +- gtsam/3rdparty/Eigen/Eigen/Householder | 7 + .../Eigen/Eigen/IterativeLinearSolvers | 24 +- gtsam/3rdparty/Eigen/Eigen/Jacobi | 7 + gtsam/3rdparty/Eigen/Eigen/LU | 21 +- gtsam/3rdparty/Eigen/Eigen/LeastSquares | 32 - gtsam/3rdparty/Eigen/Eigen/MetisSupport | 7 + gtsam/3rdparty/Eigen/Eigen/OrderingMethods | 7 + gtsam/3rdparty/Eigen/Eigen/PaStiXSupport | 12 +- gtsam/3rdparty/Eigen/Eigen/PardisoSupport | 9 +- gtsam/3rdparty/Eigen/Eigen/QR | 26 +- gtsam/3rdparty/Eigen/Eigen/QtAlignedMalloc | 10 +- gtsam/3rdparty/Eigen/Eigen/SPQRSupport | 9 +- gtsam/3rdparty/Eigen/Eigen/SVD | 28 +- gtsam/3rdparty/Eigen/Eigen/Sparse | 15 +- gtsam/3rdparty/Eigen/Eigen/SparseCholesky | 2 - gtsam/3rdparty/Eigen/Eigen/SparseCore | 33 +- gtsam/3rdparty/Eigen/Eigen/SparseLU | 3 - gtsam/3rdparty/Eigen/Eigen/SparseQR | 10 +- gtsam/3rdparty/Eigen/Eigen/StdDeque | 2 +- gtsam/3rdparty/Eigen/Eigen/StdList | 2 +- gtsam/3rdparty/Eigen/Eigen/StdVector | 2 +- gtsam/3rdparty/Eigen/Eigen/SuperLUSupport | 13 +- gtsam/3rdparty/Eigen/Eigen/UmfPackSupport | 10 +- gtsam/3rdparty/Eigen/Eigen/src/CMakeLists.txt | 7 - .../Eigen/Eigen/src/Cholesky/CMakeLists.txt | 6 - .../3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h | 268 +- gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h | 168 +- .../src/Cholesky/{LLT_MKL.h => LLT_LAPACKE.h} | 45 +- .../Eigen/src/CholmodSupport/CMakeLists.txt | 6 - .../Eigen/src/CholmodSupport/CholmodSupport.h | 284 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h | 154 +- .../3rdparty/Eigen/Eigen/src/Core/ArrayBase.h | 76 +- .../Eigen/Eigen/src/Core/ArrayWrapper.h | 151 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h | 540 +- .../Eigen/Eigen/src/Core/AssignEvaluator.h | 935 + .../Eigen/Eigen/src/Core/Assign_MKL.h | 256 +- .../Eigen/Eigen/src/Core/BandMatrix.h | 61 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h | 279 +- .../Eigen/Eigen/src/Core/BooleanRedux.h | 42 +- .../Eigen/Eigen/src/Core/CMakeLists.txt | 10 - .../Eigen/Eigen/src/Core/CommaInitializer.h | 15 +- .../Eigen/Eigen/src/Core/ConditionEstimator.h | 175 + .../Eigen/Eigen/src/Core/CoreEvaluators.h | 1671 ++ .../Eigen/Eigen/src/Core/CoreIterators.h | 142 +- .../Eigen/Eigen/src/Core/CwiseBinaryOp.h | 166 +- .../Eigen/Eigen/src/Core/CwiseNullaryOp.h | 322 +- .../Eigen/Eigen/src/Core/CwiseTernaryOp.h | 197 + .../Eigen/Eigen/src/Core/CwiseUnaryOp.h | 111 +- .../Eigen/Eigen/src/Core/CwiseUnaryView.h | 81 +- .../3rdparty/Eigen/Eigen/src/Core/DenseBase.h | 384 +- .../Eigen/Eigen/src/Core/DenseCoeffsBase.h | 281 +- .../Eigen/Eigen/src/Core/DenseStorage.h | 452 +- .../3rdparty/Eigen/Eigen/src/Core/Diagonal.h | 66 +- .../Eigen/Eigen/src/Core/DiagonalMatrix.h | 140 +- .../Eigen/Eigen/src/Core/DiagonalProduct.h | 107 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h | 160 +- .../3rdparty/Eigen/Eigen/src/Core/EigenBase.h | 50 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h | 140 - .../Eigen/Eigen/src/Core/ForceAlignedAccess.h | 24 +- .../3rdparty/Eigen/Eigen/src/Core/Functors.h | 1029 - gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h | 13 +- .../Eigen/Eigen/src/Core/GeneralProduct.h | 497 +- .../Eigen/Eigen/src/Core/GenericPacketMath.h | 351 +- .../Eigen/Eigen/src/Core/GlobalFunctions.h | 163 +- gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h | 57 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Inverse.h | 118 + gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h | 110 +- gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h | 98 +- .../Eigen/Eigen/src/Core/MathFunctions.h | 831 +- .../Eigen/Eigen/src/Core/MathFunctionsImpl.h | 78 + gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h | 241 +- .../Eigen/Eigen/src/Core/MatrixBase.h | 317 +- .../Eigen/Eigen/src/Core/NestByValue.h | 45 +- gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h | 82 +- .../3rdparty/Eigen/Eigen/src/Core/NumTraits.h | 138 +- .../Eigen/Eigen/src/Core/PermutationMatrix.h | 365 +- .../Eigen/Eigen/src/Core/PlainObjectBase.h | 451 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h | 186 + .../Eigen/Eigen/src/Core/ProductBase.h | 290 - .../Eigen/Eigen/src/Core/ProductEvaluators.h | 1105 ++ gtsam/3rdparty/Eigen/Eigen/src/Core/Random.h | 58 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h | 210 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h | 199 +- .../3rdparty/Eigen/Eigen/src/Core/Replicate.h | 95 +- .../Eigen/Eigen/src/Core/ReturnByValue.h | 54 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h | 223 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h | 22 +- .../Eigen/Eigen/src/Core/SelfAdjointView.h | 296 +- .../Eigen/Eigen/src/Core/SelfCwiseBinaryOp.h | 182 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Solve.h | 188 + .../Eigen/Eigen/src/Core/SolveTriangular.h | 77 +- .../Eigen/Eigen/src/Core/SolverBase.h | 130 + .../Eigen/Eigen/src/Core/StableNorm.h | 54 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Stride.h | 25 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Swap.h | 149 +- .../3rdparty/Eigen/Eigen/src/Core/Transpose.h | 185 +- .../Eigen/Eigen/src/Core/Transpositions.h | 246 +- .../Eigen/Eigen/src/Core/TriangularMatrix.h | 1166 +- .../Eigen/Eigen/src/Core/VectorBlock.h | 27 +- .../Eigen/Eigen/src/Core/VectorwiseOp.h | 339 +- gtsam/3rdparty/Eigen/Eigen/src/Core/Visitor.h | 77 +- .../Eigen/Eigen/src/Core/arch/AVX/Complex.h | 483 + .../Eigen/src/Core/arch/AVX/MathFunctions.h | 439 + .../Eigen/src/Core/arch/AVX/PacketMath.h | 633 + .../Eigen/src/Core/arch/AVX/TypeCasting.h | 51 + .../src/Core/arch/AVX512/MathFunctions.h | 396 + .../Eigen/src/Core/arch/AVX512/PacketMath.h | 1316 ++ .../src/Core/arch/AltiVec/CMakeLists.txt | 6 - .../Eigen/src/Core/arch/AltiVec/Complex.h | 354 +- .../src/Core/arch/AltiVec/MathFunctions.h | 322 + .../Eigen/src/Core/arch/AltiVec/PacketMath.h | 798 +- .../Eigen/Eigen/src/Core/arch/CMakeLists.txt | 4 - .../Eigen/Eigen/src/Core/arch/CUDA/Complex.h | 103 + .../Eigen/Eigen/src/Core/arch/CUDA/Half.h | 635 + .../Eigen/src/Core/arch/CUDA/MathFunctions.h | 91 + .../Eigen/src/Core/arch/CUDA/PacketMath.h | 333 + .../Eigen/src/Core/arch/CUDA/PacketMathHalf.h | 1123 ++ .../Eigen/src/Core/arch/CUDA/TypeCasting.h | 212 + .../src/Core/arch/Default/CMakeLists.txt | 6 - .../Eigen/src/Core/arch/NEON/CMakeLists.txt | 6 - .../Eigen/Eigen/src/Core/arch/NEON/Complex.h | 251 +- .../Eigen/src/Core/arch/NEON/MathFunctions.h | 91 + .../Eigen/src/Core/arch/NEON/PacketMath.h | 415 +- .../Eigen/src/Core/arch/SSE/CMakeLists.txt | 6 - .../Eigen/Eigen/src/Core/arch/SSE/Complex.h | 99 +- .../Eigen/src/Core/arch/SSE/MathFunctions.h | 113 +- .../Eigen/src/Core/arch/SSE/PacketMath.h | 416 +- .../Eigen/src/Core/arch/SSE/TypeCasting.h | 77 + .../Eigen/src/Core/arch/ZVector/Complex.h | 394 + .../src/Core/arch/ZVector/MathFunctions.h | 137 + .../Eigen/src/Core/arch/ZVector/PacketMath.h | 945 + .../src/Core/functors/AssignmentFunctors.h | 168 + .../Eigen/src/Core/functors/BinaryFunctors.h | 482 + .../Eigen/src/Core/functors/NullaryFunctors.h | 188 + .../Eigen/src/Core/functors/StlFunctors.h | 132 + .../Eigen/src/Core/functors/TernaryFunctors.h | 25 + .../Eigen/src/Core/functors/UnaryFunctors.h | 792 + .../Eigen/src/Core/products/CMakeLists.txt | 6 - .../src/Core/products/CoeffBasedProduct.h | 476 - .../Core/products/GeneralBlockPanelKernel.h | 2314 ++- .../src/Core/products/GeneralMatrixMatrix.h | 363 +- .../products/GeneralMatrixMatrixTriangular.h | 145 +- ...h => GeneralMatrixMatrixTriangular_BLAS.h} | 67 +- ...atrix_MKL.h => GeneralMatrixMatrix_BLAS.h} | 47 +- .../src/Core/products/GeneralMatrixVector.h | 305 +- ...ector_MKL.h => GeneralMatrixVector_BLAS.h} | 68 +- .../Eigen/src/Core/products/Parallelizer.h | 71 +- .../Core/products/SelfadjointMatrixMatrix.h | 341 +- ...x_MKL.h => SelfadjointMatrixMatrix_BLAS.h} | 136 +- .../Core/products/SelfadjointMatrixVector.h | 123 +- ...r_MKL.h => SelfadjointMatrixVector_BLAS.h} | 49 +- .../src/Core/products/SelfadjointProduct.h | 26 +- .../Core/products/SelfadjointRank2Update.h | 8 +- .../Core/products/TriangularMatrixMatrix.h | 138 +- ...ix_MKL.h => TriangularMatrixMatrix_BLAS.h} | 111 +- .../Core/products/TriangularMatrixVector.h | 174 +- ...or_MKL.h => TriangularMatrixVector_BLAS.h} | 96 +- .../Core/products/TriangularSolverMatrix.h | 73 +- ...ix_MKL.h => TriangularSolverMatrix_BLAS.h} | 56 +- .../Core/products/TriangularSolverVector.h | 24 +- .../Eigen/Eigen/src/Core/util/BlasUtil.h | 217 +- .../Eigen/Eigen/src/Core/util/CMakeLists.txt | 6 - .../Eigen/Eigen/src/Core/util/Constants.h | 160 +- .../src/Core/util/DisableStupidWarnings.h | 31 +- .../Eigen/src/Core/util/ForwardDeclarations.h | 134 +- .../Eigen/Eigen/src/Core/util/MKL_support.h | 50 +- .../Eigen/Eigen/src/Core/util/Macros.h | 560 +- .../Eigen/Eigen/src/Core/util/Memory.h | 493 +- .../3rdparty/Eigen/Eigen/src/Core/util/Meta.h | 359 +- .../src/Core/util/ReenableStupidWarnings.h | 10 + .../Eigen/Eigen/src/Core/util/StaticAssert.h | 40 +- .../Eigen/Eigen/src/Core/util/XprHelper.h | 582 +- .../Eigen/Eigen/src/Eigen2Support/Block.h | 126 - .../Eigen/src/Eigen2Support/CMakeLists.txt | 8 - .../Eigen/Eigen/src/Eigen2Support/Cwise.h | 192 - .../Eigen/src/Eigen2Support/CwiseOperators.h | 298 - .../src/Eigen2Support/Geometry/AlignedBox.h | 159 - .../Eigen/src/Eigen2Support/Geometry/All.h | 115 - .../src/Eigen2Support/Geometry/AngleAxis.h | 214 - .../src/Eigen2Support/Geometry/CMakeLists.txt | 6 - .../src/Eigen2Support/Geometry/Hyperplane.h | 254 - .../Eigen2Support/Geometry/ParametrizedLine.h | 141 - .../src/Eigen2Support/Geometry/Quaternion.h | 495 - .../src/Eigen2Support/Geometry/Rotation2D.h | 145 - .../src/Eigen2Support/Geometry/RotationBase.h | 123 - .../src/Eigen2Support/Geometry/Scaling.h | 167 - .../src/Eigen2Support/Geometry/Transform.h | 786 - .../src/Eigen2Support/Geometry/Translation.h | 184 - .../Eigen/Eigen/src/Eigen2Support/LU.h | 120 - .../Eigen/Eigen/src/Eigen2Support/Lazy.h | 71 - .../Eigen/src/Eigen2Support/LeastSquares.h | 169 - .../Eigen/Eigen/src/Eigen2Support/Macros.h | 20 - .../Eigen/src/Eigen2Support/MathFunctions.h | 57 - .../Eigen/Eigen/src/Eigen2Support/Memory.h | 45 - .../Eigen/Eigen/src/Eigen2Support/Meta.h | 75 - .../Eigen/Eigen/src/Eigen2Support/Minor.h | 117 - .../Eigen/Eigen/src/Eigen2Support/QR.h | 67 - .../Eigen/Eigen/src/Eigen2Support/SVD.h | 637 - .../src/Eigen2Support/TriangularSolver.h | 42 - .../Eigen/src/Eigen2Support/VectorBlock.h | 94 - .../Eigen/src/Eigenvalues/CMakeLists.txt | 6 - .../src/Eigenvalues/ComplexEigenSolver.h | 25 +- .../Eigen/src/Eigenvalues/ComplexSchur.h | 19 +- ...plexSchur_MKL.h => ComplexSchur_LAPACKE.h} | 40 +- .../Eigen/Eigen/src/Eigenvalues/EigenSolver.h | 113 +- .../src/Eigenvalues/GeneralizedEigenSolver.h | 211 +- .../GeneralizedSelfAdjointEigenSolver.h | 3 +- .../src/Eigenvalues/HessenbergDecomposition.h | 15 +- .../Eigen/Eigen/src/Eigenvalues/RealQZ.h | 46 +- .../Eigen/Eigen/src/Eigenvalues/RealSchur.h | 41 +- .../{RealSchur_MKL.h => RealSchur_LAPACKE.h} | 38 +- .../src/Eigenvalues/SelfAdjointEigenSolver.h | 325 +- ...MKL.h => SelfAdjointEigenSolver_LAPACKE.h} | 42 +- .../src/Eigenvalues/Tridiagonalization.h | 35 +- .../Eigen/Eigen/src/Geometry/AlignedBox.h | 96 +- .../Eigen/Eigen/src/Geometry/AngleAxis.h | 85 +- .../Eigen/Eigen/src/Geometry/CMakeLists.txt | 8 - .../Eigen/Eigen/src/Geometry/EulerAngles.h | 22 +- .../Eigen/Eigen/src/Geometry/Homogeneous.h | 290 +- .../Eigen/Eigen/src/Geometry/Hyperplane.h | 64 +- .../Eigen/Eigen/src/Geometry/OrthoMethods.h | 58 +- .../Eigen/src/Geometry/ParametrizedLine.h | 60 +- .../Eigen/Eigen/src/Geometry/Quaternion.h | 229 +- .../Eigen/Eigen/src/Geometry/Rotation2D.h | 85 +- .../Eigen/Eigen/src/Geometry/RotationBase.h | 48 +- .../Eigen/Eigen/src/Geometry/Scaling.h | 38 +- .../Eigen/Eigen/src/Geometry/Transform.h | 254 +- .../Eigen/Eigen/src/Geometry/Translation.h | 54 +- .../Eigen/Eigen/src/Geometry/Umeyama.h | 19 +- .../Eigen/src/Geometry/arch/CMakeLists.txt | 6 - .../Eigen/src/Geometry/arch/Geometry_SSE.h | 86 +- .../Eigen/src/Householder/BlockHouseholder.h | 77 +- .../Eigen/src/Householder/CMakeLists.txt | 6 - .../Eigen/Eigen/src/Householder/Householder.h | 4 +- .../src/Householder/HouseholderSequence.h | 56 +- .../BasicPreconditioners.h | 129 +- .../src/IterativeLinearSolvers/BiCGSTAB.h | 97 +- .../src/IterativeLinearSolvers/CMakeLists.txt | 6 - .../ConjugateGradient.h | 137 +- .../IncompleteCholesky.h | 400 + .../IterativeLinearSolvers/IncompleteLUT.h | 138 +- .../IterativeSolverBase.h | 342 +- .../LeastSquareConjugateGradient.h | 216 + .../IterativeLinearSolvers/SolveWithGuess.h | 115 + .../Eigen/Eigen/src/Jacobi/CMakeLists.txt | 6 - .../3rdparty/Eigen/Eigen/src/Jacobi/Jacobi.h | 76 +- .../Eigen/Eigen/src/LU/CMakeLists.txt | 8 - .../3rdparty/Eigen/Eigen/src/LU/Determinant.h | 2 +- gtsam/3rdparty/Eigen/Eigen/src/LU/FullPivLU.h | 316 +- .../Eigen/src/LU/{Inverse.h => InverseImpl.h} | 81 +- .../Eigen/Eigen/src/LU/PartialPivLU.h | 254 +- ...tialPivLU_MKL.h => PartialPivLU_LAPACKE.h} | 26 +- .../Eigen/Eigen/src/LU/arch/CMakeLists.txt | 6 - .../Eigen/Eigen/src/LU/arch/Inverse_SSE.h | 23 +- .../Eigen/src/MetisSupport/CMakeLists.txt | 6 - .../Eigen/src/MetisSupport/MetisSupport.h | 18 +- .../Eigen/Eigen/src/OrderingMethods/Amd.h | 83 +- .../Eigen/src/OrderingMethods/CMakeLists.txt | 6 - .../Eigen/src/OrderingMethods/Eigen_Colamd.h | 412 +- .../Eigen/src/OrderingMethods/Ordering.h | 51 +- .../Eigen/src/PaStiXSupport/CMakeLists.txt | 6 - .../Eigen/src/PaStiXSupport/PaStiXSupport.h | 151 +- .../Eigen/src/PardisoSupport/CMakeLists.txt | 6 - .../Eigen/src/PardisoSupport/PardisoSupport.h | 230 +- .../Eigen/Eigen/src/QR/CMakeLists.txt | 6 - .../Eigen/Eigen/src/QR/ColPivHouseholderQR.h | 290 +- ...QR_MKL.h => ColPivHouseholderQR_LAPACKE.h} | 47 +- .../src/QR/CompleteOrthogonalDecomposition.h | 562 + .../Eigen/Eigen/src/QR/FullPivHouseholderQR.h | 189 +- .../Eigen/Eigen/src/QR/HouseholderQR.h | 124 +- ...holderQR_MKL.h => HouseholderQR_LAPACKE.h} | 29 +- .../Eigen/src/SPQRSupport/CMakeLists.txt | 6 - .../src/SPQRSupport/SuiteSparseQRSupport.h | 123 +- gtsam/3rdparty/Eigen/Eigen/src/SVD/BDCSVD.h | 1231 ++ .../Eigen/Eigen/src/SVD/CMakeLists.txt | 6 - .../3rdparty/Eigen/Eigen/src/SVD/JacobiSVD.h | 332 +- .../{JacobiSVD_MKL.h => JacobiSVD_LAPACKE.h} | 48 +- .../{unsupported => }/Eigen/src/SVD/SVDBase.h | 199 +- .../Eigen/src/SVD/UpperBidiagonalization.h | 330 +- .../Eigen/src/SparseCholesky/CMakeLists.txt | 6 - .../src/SparseCholesky/SimplicialCholesky.h | 272 +- .../SparseCholesky/SimplicialCholesky_impl.h | 34 +- .../Eigen/Eigen/src/SparseCore/AmbiVector.h | 98 +- .../Eigen/Eigen/src/SparseCore/CMakeLists.txt | 6 - .../Eigen/src/SparseCore/CompressedStorage.h | 138 +- .../ConservativeSparseSparseProduct.h | 214 +- .../Eigen/src/SparseCore/MappedSparseMatrix.h | 164 +- .../Eigen/Eigen/src/SparseCore/SparseAssign.h | 216 + .../Eigen/Eigen/src/SparseCore/SparseBlock.h | 1226 +- .../Eigen/src/SparseCore/SparseColEtree.h | 44 +- .../src/SparseCore/SparseCompressedBase.h | 341 + .../src/SparseCore/SparseCwiseBinaryOp.h | 684 +- .../Eigen/src/SparseCore/SparseCwiseUnaryOp.h | 155 +- .../Eigen/src/SparseCore/SparseDenseProduct.h | 429 +- .../src/SparseCore/SparseDiagonalProduct.h | 234 +- .../Eigen/Eigen/src/SparseCore/SparseDot.h | 17 +- .../Eigen/Eigen/src/SparseCore/SparseFuzzy.h | 29 +- .../Eigen/Eigen/src/SparseCore/SparseMap.h | 305 + .../Eigen/Eigen/src/SparseCore/SparseMatrix.h | 637 +- .../Eigen/src/SparseCore/SparseMatrixBase.h | 269 +- .../Eigen/src/SparseCore/SparsePermutation.h | 170 +- .../Eigen/src/SparseCore/SparseProduct.h | 291 +- .../Eigen/Eigen/src/SparseCore/SparseRedux.h | 5 +- .../Eigen/Eigen/src/SparseCore/SparseRef.h | 397 + .../src/SparseCore/SparseSelfAdjointView.h | 569 +- .../Eigen/src/SparseCore/SparseSolverBase.h | 124 + .../SparseSparseProductWithPruning.h | 86 +- .../Eigen/src/SparseCore/SparseTranspose.h | 99 +- .../src/SparseCore/SparseTriangularView.h | 268 +- .../Eigen/Eigen/src/SparseCore/SparseUtil.h | 104 +- .../Eigen/Eigen/src/SparseCore/SparseVector.h | 214 +- .../Eigen/Eigen/src/SparseCore/SparseView.h | 234 +- .../Eigen/src/SparseCore/TriangularSolver.h | 117 +- .../Eigen/Eigen/src/SparseLU/CMakeLists.txt | 6 - .../Eigen/Eigen/src/SparseLU/SparseLU.h | 221 +- .../Eigen/Eigen/src/SparseLU/SparseLUImpl.h | 10 +- .../Eigen/src/SparseLU/SparseLU_Memory.h | 15 +- .../Eigen/src/SparseLU/SparseLU_Structs.h | 3 +- .../src/SparseLU/SparseLU_SupernodalMatrix.h | 69 +- .../Eigen/Eigen/src/SparseLU/SparseLU_Utils.h | 10 +- .../Eigen/src/SparseLU/SparseLU_column_bmod.h | 7 +- .../Eigen/src/SparseLU/SparseLU_column_dfs.h | 38 +- .../src/SparseLU/SparseLU_copy_to_ucol.h | 7 +- .../Eigen/src/SparseLU/SparseLU_gemm_kernel.h | 93 +- .../src/SparseLU/SparseLU_heap_relax_snode.h | 21 +- .../Eigen/src/SparseLU/SparseLU_kernel_bmod.h | 52 +- .../Eigen/src/SparseLU/SparseLU_panel_bmod.h | 6 +- .../Eigen/src/SparseLU/SparseLU_panel_dfs.h | 44 +- .../Eigen/src/SparseLU/SparseLU_pivotL.h | 12 +- .../Eigen/src/SparseLU/SparseLU_pruneL.h | 7 +- .../Eigen/src/SparseLU/SparseLU_relax_snode.h | 12 +- .../Eigen/Eigen/src/SparseQR/CMakeLists.txt | 6 - .../Eigen/Eigen/src/SparseQR/SparseQR.h | 187 +- .../Eigen/Eigen/src/StlSupport/CMakeLists.txt | 6 - .../Eigen/Eigen/src/StlSupport/StdDeque.h | 2 +- .../Eigen/Eigen/src/StlSupport/StdList.h | 4 +- .../Eigen/Eigen/src/StlSupport/StdVector.h | 5 + .../Eigen/Eigen/src/StlSupport/details.h | 16 +- .../Eigen/src/SuperLUSupport/CMakeLists.txt | 6 - .../Eigen/src/SuperLUSupport/SuperLUSupport.h | 209 +- .../Eigen/src/UmfPackSupport/CMakeLists.txt | 6 - .../Eigen/src/UmfPackSupport/UmfPackSupport.h | 317 +- .../Eigen/Eigen/src/misc/CMakeLists.txt | 6 - gtsam/3rdparty/Eigen/Eigen/src/misc/Image.h | 2 - gtsam/3rdparty/Eigen/Eigen/src/misc/Kernel.h | 4 +- .../Eigen/Eigen/src/misc/RealSvd2x2.h | 55 + gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h | 76 - .../Eigen/Eigen/src/misc/SparseSolve.h | 128 - gtsam/3rdparty/Eigen/Eigen/src/misc/blas.h | 404 +- gtsam/3rdparty/Eigen/Eigen/src/misc/lapack.h | 152 + gtsam/3rdparty/Eigen/Eigen/src/misc/lapacke.h | 16291 ++++++++++++++++ .../Eigen/Eigen/src/misc/lapacke_mangling.h | 17 + .../Eigen/src/plugins/ArrayCwiseBinaryOps.h | 207 +- .../Eigen/src/plugins/ArrayCwiseUnaryOps.h | 499 +- .../Eigen/Eigen/src/plugins/BlockMethods.h | 1203 +- .../Eigen/Eigen/src/plugins/CMakeLists.txt | 6 - .../Eigen/src/plugins/CommonCwiseBinaryOps.h | 75 +- .../Eigen/src/plugins/CommonCwiseUnaryOps.h | 193 +- .../Eigen/src/plugins/MatrixCwiseBinaryOps.h | 29 +- .../Eigen/src/plugins/MatrixCwiseUnaryOps.h | 107 +- gtsam/3rdparty/Eigen/README.md | 3 + gtsam/3rdparty/Eigen/bench/BenchTimer.h | 10 +- .../Eigen/bench/analyze-blocking-sizes.cpp | 876 + gtsam/3rdparty/Eigen/bench/benchCholesky.cpp | 16 +- gtsam/3rdparty/Eigen/bench/bench_gemm.cpp | 117 +- gtsam/3rdparty/Eigen/bench/bench_norm.cpp | 117 +- .../Eigen/bench/benchmark-blocking-sizes.cpp | 677 + gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt | 31 +- .../Eigen/bench/btl/actions/action_axpby.hh | 2 +- .../Eigen/bench/btl/actions/action_axpy.hh | 2 +- .../Eigen/bench/btl/cmake/FindACML.cmake | 2 + .../Eigen/bench/btl/cmake/FindATLAS.cmake | 26 +- .../Eigen/bench/btl/cmake/FindBLAZE.cmake | 31 + .../Eigen/bench/btl/cmake/FindCBLAS.cmake | 1 + .../Eigen/bench/btl/cmake/FindGOTO.cmake | 15 - .../Eigen/bench/btl/cmake/FindGOTO2.cmake | 25 - .../Eigen/bench/btl/cmake/FindOPENBLAS.cmake | 17 + .../Eigen/bench/btl/data/action_settings.txt | 34 +- .../bench/btl/data/perlib_plot_settings.txt | 4 +- .../Eigen/bench/btl/generic_bench/bench.hh | 4 +- .../btl/generic_bench/bench_parameter.hh | 4 +- .../Eigen/bench/btl/generic_bench/btl.hh | 4 +- .../btl/generic_bench/init/init_function.hh | 8 +- .../btl/generic_bench/init/init_matrix.hh | 10 +- .../btl/generic_bench/init/init_vector.hh | 2 +- .../timers/portable_perf_analyzer.hh | 2 +- .../generic_bench/timers/portable_timer.hh | 46 +- .../btl/generic_bench/utils/size_lin_log.hh | 2 +- .../Eigen/bench/btl/libs/BLAS/CMakeLists.txt | 29 +- .../btl/libs/BLAS/blas_interface_impl.hh | 6 +- .../bench/btl/libs/BLAS/c_interface_base.h | 6 +- .../Eigen/bench/btl/libs/BLAS/main.cpp | 10 +- .../Eigen/bench/btl/libs/STL/STL_interface.hh | 4 +- .../Eigen/bench/btl/libs/blaze/CMakeLists.txt | 13 + .../bench/btl/libs/blaze/blaze_interface.hh | 140 + .../Eigen/bench/btl/libs/blaze/main.cpp | 40 + .../bench/btl/libs/eigen2/eigen2_interface.hh | 2 +- .../bench/btl/libs/eigen3/eigen3_interface.hh | 58 +- .../Eigen/bench/btl/libs/eigen3/main_adv.cpp | 14 +- .../bench/btl/libs/tensors/CMakeLists.txt | 44 + .../bench/btl/libs/tensors/main_linear.cpp | 23 + .../bench/btl/libs/tensors/main_matmat.cpp | 21 + .../bench/btl/libs/tensors/main_vecmat.cpp | 21 + .../btl/libs/tensors/tensor_interface.hh | 105 + gtsam/3rdparty/Eigen/bench/dense_solvers.cpp | 186 + gtsam/3rdparty/Eigen/bench/eig33.cpp | 57 +- .../bench/perf_monitoring/gemm/changesets.txt | 61 + .../Eigen/bench/perf_monitoring/gemm/gemm.cpp | 67 + .../perf_monitoring/gemm/gemm_settings.txt | 15 + .../bench/perf_monitoring/gemm/lazy_gemm.cpp | 98 + .../gemm/lazy_gemm_settings.txt | 15 + .../bench/perf_monitoring/gemm/make_plot.sh | 38 + .../Eigen/bench/perf_monitoring/gemm/run.sh | 156 + .../Eigen/bench/spbench/CMakeLists.txt | 29 +- .../Eigen/bench/spbench/spbenchstyle.h | 3 +- gtsam/3rdparty/Eigen/bench/tensors/README | 21 + .../3rdparty/Eigen/bench/tensors/benchmark.h | 49 + .../Eigen/bench/tensors/benchmark_main.cc | 237 + .../tensors/contraction_benchmarks_cpu.cc | 39 + .../Eigen/bench/tensors/tensor_benchmarks.h | 478 + .../bench/tensors/tensor_benchmarks_cpu.cc | 168 + .../tensors/tensor_benchmarks_fp16_gpu.cu | 77 + .../bench/tensors/tensor_benchmarks_gpu.cu | 75 + .../bench/tensors/tensor_benchmarks_sycl.cc | 37 + gtsam/3rdparty/Eigen/blas/CMakeLists.txt | 25 +- .../Eigen/blas/PackedTriangularMatrixVector.h | 4 +- gtsam/3rdparty/Eigen/blas/chbmv.f | 310 - gtsam/3rdparty/Eigen/blas/chpmv.f | 272 - gtsam/3rdparty/Eigen/blas/common.h | 44 +- gtsam/3rdparty/Eigen/blas/ctbmv.f | 366 - gtsam/3rdparty/Eigen/blas/double.cpp | 11 +- gtsam/3rdparty/Eigen/blas/drotm.f | 147 - gtsam/3rdparty/Eigen/blas/drotmg.f | 206 - gtsam/3rdparty/Eigen/blas/dsbmv.f | 304 - gtsam/3rdparty/Eigen/blas/dspmv.f | 265 - gtsam/3rdparty/Eigen/blas/dtbmv.f | 335 - gtsam/3rdparty/Eigen/blas/f2c/chbmv.c | 487 + gtsam/3rdparty/Eigen/blas/f2c/chpmv.c | 438 + gtsam/3rdparty/Eigen/blas/f2c/complexdots.c | 84 + gtsam/3rdparty/Eigen/blas/f2c/ctbmv.c | 647 + gtsam/3rdparty/Eigen/blas/f2c/d_cnjg.c | 6 + gtsam/3rdparty/Eigen/blas/f2c/datatypes.h | 24 + gtsam/3rdparty/Eigen/blas/f2c/drotm.c | 215 + gtsam/3rdparty/Eigen/blas/f2c/drotmg.c | 293 + gtsam/3rdparty/Eigen/blas/f2c/dsbmv.c | 366 + gtsam/3rdparty/Eigen/blas/f2c/dspmv.c | 316 + gtsam/3rdparty/Eigen/blas/f2c/dtbmv.c | 428 + gtsam/3rdparty/Eigen/blas/f2c/lsame.c | 117 + gtsam/3rdparty/Eigen/blas/f2c/r_cnjg.c | 6 + gtsam/3rdparty/Eigen/blas/f2c/srotm.c | 216 + gtsam/3rdparty/Eigen/blas/f2c/srotmg.c | 295 + gtsam/3rdparty/Eigen/blas/f2c/ssbmv.c | 368 + gtsam/3rdparty/Eigen/blas/f2c/sspmv.c | 316 + gtsam/3rdparty/Eigen/blas/f2c/stbmv.c | 428 + gtsam/3rdparty/Eigen/blas/f2c/zhbmv.c | 488 + gtsam/3rdparty/Eigen/blas/f2c/zhpmv.c | 438 + gtsam/3rdparty/Eigen/blas/f2c/ztbmv.c | 647 + .../Eigen/blas/{ => fortran}/complexdots.f | 0 gtsam/3rdparty/Eigen/blas/level1_cplx_impl.h | 54 +- gtsam/3rdparty/Eigen/blas/level1_impl.h | 49 +- gtsam/3rdparty/Eigen/blas/level1_real_impl.h | 22 +- gtsam/3rdparty/Eigen/blas/level2_cplx_impl.h | 116 +- gtsam/3rdparty/Eigen/blas/level2_impl.h | 427 +- gtsam/3rdparty/Eigen/blas/level2_real_impl.h | 168 +- gtsam/3rdparty/Eigen/blas/level3_impl.h | 458 +- gtsam/3rdparty/Eigen/blas/lsame.f | 85 - gtsam/3rdparty/Eigen/blas/single.cpp | 2 +- gtsam/3rdparty/Eigen/blas/srotm.f | 148 - gtsam/3rdparty/Eigen/blas/srotmg.f | 208 - gtsam/3rdparty/Eigen/blas/ssbmv.f | 306 - gtsam/3rdparty/Eigen/blas/sspmv.f | 265 - gtsam/3rdparty/Eigen/blas/stbmv.f | 335 - gtsam/3rdparty/Eigen/blas/testing/cblat1.f | 83 +- gtsam/3rdparty/Eigen/blas/testing/cblat2.f | 188 +- gtsam/3rdparty/Eigen/blas/testing/cblat3.f | 185 +- gtsam/3rdparty/Eigen/blas/testing/dblat2.f | 186 +- gtsam/3rdparty/Eigen/blas/testing/dblat3.f | 168 +- gtsam/3rdparty/Eigen/blas/testing/sblat2.f | 186 +- gtsam/3rdparty/Eigen/blas/testing/sblat3.f | 168 +- gtsam/3rdparty/Eigen/blas/testing/zblat1.f | 83 +- gtsam/3rdparty/Eigen/blas/testing/zblat2.f | 188 +- gtsam/3rdparty/Eigen/blas/testing/zblat3.f | 189 +- gtsam/3rdparty/Eigen/blas/xerbla.cpp | 4 +- gtsam/3rdparty/Eigen/blas/zhbmv.f | 310 - gtsam/3rdparty/Eigen/blas/zhpmv.f | 272 - gtsam/3rdparty/Eigen/blas/ztbmv.f | 366 - .../Eigen/cmake/Eigen3Config.cmake.in | 21 + .../Eigen/cmake/Eigen3ConfigLegacy.cmake.in | 30 + .../Eigen/cmake/EigenConfigureTesting.cmake | 22 +- .../cmake/EigenDetermineVSServicePack.cmake | 18 +- gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake | 344 +- .../3rdparty/Eigen/cmake/EigenUninstall.cmake | 40 + gtsam/3rdparty/Eigen/cmake/FindAdolc.cmake | 2 +- gtsam/3rdparty/Eigen/cmake/FindBLAS.cmake | 1503 +- gtsam/3rdparty/Eigen/cmake/FindBLASEXT.cmake | 380 + .../3rdparty/Eigen/cmake/FindComputeCpp.cmake | 245 + gtsam/3rdparty/Eigen/cmake/FindEigen3.cmake | 28 +- gtsam/3rdparty/Eigen/cmake/FindHWLOC.cmake | 331 + gtsam/3rdparty/Eigen/cmake/FindMetis.cmake | 299 +- gtsam/3rdparty/Eigen/cmake/FindPTSCOTCH.cmake | 423 + gtsam/3rdparty/Eigen/cmake/FindPastix.cmake | 717 +- gtsam/3rdparty/Eigen/cmake/FindScotch.cmake | 379 +- gtsam/3rdparty/Eigen/cmake/FindSuperLU.cmake | 79 +- gtsam/3rdparty/Eigen/cmake/UseEigen3.cmake | 6 + .../Eigen/cmake/language_support.cmake | 3 +- gtsam/3rdparty/Eigen/debug/gdb/printers.py | 12 +- .../Eigen/demos/opengl/quaternion_demo.cpp | 2 +- .../3rdparty/Eigen/demos/opengl/trackball.cpp | 2 +- .../Eigen/doc/A05_PortingFrom2To3.dox | 15 +- .../Eigen/doc/A10_Eigen2SupportModes.dox | 95 - .../Eigen/doc/AsciiQuickReference.txt | 116 +- gtsam/3rdparty/Eigen/doc/B01_Experimental.dox | 6 +- gtsam/3rdparty/Eigen/doc/CMakeLists.txt | 12 + .../Eigen/doc/CoeffwiseMathFunctionsTable.dox | 525 + gtsam/3rdparty/Eigen/doc/CustomizingEigen.dox | 188 - .../doc/CustomizingEigen_CustomScalar.dox | 120 + .../doc/CustomizingEigen_InheritingMatrix.dox | 34 + .../doc/CustomizingEigen_NullaryExpr.dox | 86 + .../Eigen/doc/CustomizingEigen_Plugins.dox | 69 + .../Eigen/doc/DenseDecompositionBenchmark.dox | 42 + gtsam/3rdparty/Eigen/doc/Doxyfile.in | 52 +- .../Eigen/doc/FixedSizeVectorizable.dox | 4 +- .../Eigen/doc/InplaceDecomposition.dox | 115 + gtsam/3rdparty/Eigen/doc/LeastSquares.dox | 70 + gtsam/3rdparty/Eigen/doc/Manual.dox | 31 +- .../Eigen/doc/MatrixfreeSolverExample.dox | 20 + .../3rdparty/Eigen/doc/NewExpressionType.dox | 143 + gtsam/3rdparty/Eigen/doc/Overview.dox | 4 +- .../Eigen/doc/PreprocessorDirectives.dox | 80 +- gtsam/3rdparty/Eigen/doc/QuickReference.dox | 138 +- .../Eigen/doc/SparseLinearSystems.dox | 93 +- .../Eigen/doc/SparseQuickReference.dox | 16 +- gtsam/3rdparty/Eigen/doc/StlContainers.dox | 4 +- .../Eigen/doc/StructHavingEigenMembers.dox | 24 +- gtsam/3rdparty/Eigen/doc/TemplateKeyword.dox | 17 +- gtsam/3rdparty/Eigen/doc/TopicAliasing.dox | 30 +- gtsam/3rdparty/Eigen/doc/TopicCMakeGuide.dox | 52 + .../Eigen/doc/TopicLazyEvaluation.dox | 4 +- .../doc/TopicLinearAlgebraDecompositions.dox | 8 +- .../Eigen/doc/TopicMultithreading.dox | 16 +- .../3rdparty/Eigen/doc/TutorialArrayClass.dox | 2 +- gtsam/3rdparty/Eigen/doc/TutorialGeometry.dox | 9 +- .../Eigen/doc/TutorialLinearAlgebra.dox | 37 +- ...TutorialReductionsVisitorsBroadcasting.dox | 29 +- .../Eigen/doc/TutorialReshapeSlicing.dox | 65 + gtsam/3rdparty/Eigen/doc/TutorialSparse.dox | 16 +- .../Eigen/doc/UnalignedArrayAssert.dox | 23 +- .../Eigen/doc/UsingBlasLapackBackends.dox | 133 + gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox | 96 +- gtsam/3rdparty/Eigen/doc/UsingNVCC.dox | 32 + gtsam/3rdparty/Eigen/doc/eigendoxy.css | 41 +- .../Eigen/doc/examples/CMakeLists.txt | 5 + .../examples/CustomizingEigen_Inheritance.cpp | 30 + .../3rdparty/Eigen/doc/examples/Cwise_erf.cpp | 9 + .../Eigen/doc/examples/Cwise_erfc.cpp | 9 + .../Eigen/doc/examples/Cwise_lgamma.cpp | 9 + .../doc/examples/MatrixBase_cwise_const.cpp | 18 - .../Eigen/doc/examples/TutorialInplaceLU.cpp | 61 + .../TutorialLinAlgInverseDeterminant.cpp | 2 +- ...rsBroadcasting_reductions_operatornorm.cpp | 18 + .../Eigen/doc/examples/make_circulant.cpp | 11 + .../doc/examples/make_circulant.cpp.entry | 5 + .../doc/examples/make_circulant.cpp.evaluator | 32 + .../examples/make_circulant.cpp.expression | 20 + .../doc/examples/make_circulant.cpp.main | 8 + .../doc/examples/make_circulant.cpp.preamble | 4 + .../doc/examples/make_circulant.cpp.traits | 19 + .../Eigen/doc/examples/make_circulant2.cpp | 52 + .../Eigen/doc/examples/matrixfree_cg.cpp | 128 + .../Eigen/doc/examples/nullary_indexing.cpp | 66 + gtsam/3rdparty/Eigen/doc/ftv2node.png | Bin 0 -> 86 bytes gtsam/3rdparty/Eigen/doc/ftv2pnode.png | Bin 0 -> 229 bytes .../Eigen/doc/snippets/BiCGSTAB_simple.cpp | 11 + .../doc/snippets/BiCGSTAB_step_by_step.cpp | 14 + .../Eigen/doc/snippets/CMakeLists.txt | 2 - .../3rdparty/Eigen/doc/snippets/Cwise_arg.cpp | 3 + .../doc/snippets/Cwise_array_power_array.cpp | 4 + .../Eigen/doc/snippets/Cwise_atan.cpp | 2 + .../Eigen/doc/snippets/Cwise_boolean_not.cpp | 5 + .../Eigen/doc/snippets/Cwise_boolean_xor.cpp | 2 + .../Eigen/doc/snippets/Cwise_ceil.cpp | 3 + .../Eigen/doc/snippets/Cwise_cosh.cpp | 2 + .../Eigen/doc/snippets/Cwise_floor.cpp | 3 + .../Eigen/doc/snippets/Cwise_isFinite.cpp | 5 + .../Eigen/doc/snippets/Cwise_isInf.cpp | 5 + .../Eigen/doc/snippets/Cwise_isNaN.cpp | 5 + .../Eigen/doc/snippets/Cwise_log10.cpp | 2 + .../Eigen/doc/snippets/Cwise_round.cpp | 3 + .../doc/snippets/Cwise_scalar_power_array.cpp | 2 + .../Eigen/doc/snippets/Cwise_sign.cpp | 2 + .../Eigen/doc/snippets/Cwise_sinh.cpp | 2 + .../Eigen/doc/snippets/Cwise_tanh.cpp | 2 + .../doc/snippets/DenseBase_LinSpacedInt.cpp | 8 + .../snippets/DirectionWise_hnormalized.cpp | 7 + .../doc/snippets/EigenSolver_eigenvectors.cpp | 4 +- .../snippets/LeastSquaresNormalEquations.cpp | 4 + .../Eigen/doc/snippets/LeastSquaresQR.cpp | 4 + .../doc/snippets/MatrixBase_cwiseSign.cpp | 4 + .../doc/snippets/MatrixBase_hnormalized.cpp | 6 + .../doc/snippets/MatrixBase_homogeneous.cpp | 6 + .../Eigen/doc/snippets/MatrixBase_marked.cpp | 14 - .../Eigen/doc/snippets/MatrixBase_part.cpp | 13 - .../snippets/MatrixBase_selfadjointView.cpp | 6 + ...ract.cpp => MatrixBase_triangularView.cpp} | 12 +- .../Eigen/doc/snippets/PartialRedux_count.cpp | 4 +- .../doc/snippets/SparseMatrix_coeffs.cpp | 9 + .../doc/snippets/TopicAliasing_mult4.cpp | 5 + .../doc/snippets/TopicAliasing_mult5.cpp | 5 + .../Eigen/doc/snippets/Triangular_solve.cpp | 11 + .../Tutorial_AdvancedInitialization_Join.cpp | 2 +- .../doc/snippets/Tutorial_ReshapeMat2Mat.cpp | 6 + .../doc/snippets/Tutorial_ReshapeMat2Vec.cpp | 11 + .../doc/snippets/Tutorial_SlicingCol.cpp | 11 + .../doc/snippets/Tutorial_SlicingVec.cpp | 4 + .../doc/snippets/VectorwiseOp_homogeneous.cpp | 7 + .../Eigen/doc/snippets/compile_snippet.cpp.in | 10 +- .../Eigen/doc/special_examples/CMakeLists.txt | 14 + .../Tutorial_sparse_example.cpp | 2 + .../Tutorial_sparse_example_details.cpp | 2 +- .../doc/special_examples/random_cpp11.cpp | 14 + gtsam/3rdparty/Eigen/failtest/CMakeLists.txt | 21 + gtsam/3rdparty/Eigen/failtest/bdcsvd_int.cpp | 14 + ...seunaryview_nonconst_ctor_on_const_xpr.cpp | 15 + ...unaryview_on_const_type_actually_const.cpp | 16 + ...adjointview_nonconst_ctor_on_const_xpr.cpp | 15 + ...jointview_on_const_type_actually_const.cpp | 16 + .../3rdparty/Eigen/failtest/sparse_ref_1.cpp | 18 + .../3rdparty/Eigen/failtest/sparse_ref_2.cpp | 15 + .../3rdparty/Eigen/failtest/sparse_ref_3.cpp | 15 + .../3rdparty/Eigen/failtest/sparse_ref_4.cpp | 15 + .../3rdparty/Eigen/failtest/sparse_ref_5.cpp | 16 + .../failtest/sparse_storage_mismatch.cpp | 16 + gtsam/3rdparty/Eigen/failtest/swap_1.cpp | 14 + gtsam/3rdparty/Eigen/failtest/swap_2.cpp | 14 + gtsam/3rdparty/Eigen/failtest/ternary_1.cpp | 13 + gtsam/3rdparty/Eigen/failtest/ternary_2.cpp | 13 + ...angularview_nonconst_ctor_on_const_xpr.cpp | 15 + ...gularview_on_const_type_actually_const.cpp | 16 + .../3rdparty/Eigen/lapack/complex_double.cpp | 3 +- .../3rdparty/Eigen/lapack/complex_single.cpp | 3 +- gtsam/3rdparty/Eigen/lapack/double.cpp | 3 +- gtsam/3rdparty/Eigen/lapack/eigenvalues.cpp | 27 +- gtsam/3rdparty/Eigen/lapack/lapack_common.h | 8 +- gtsam/3rdparty/Eigen/lapack/single.cpp | 3 +- gtsam/3rdparty/Eigen/lapack/svd.cpp | 138 + gtsam/3rdparty/Eigen/scripts/buildtests.in | 6 +- gtsam/3rdparty/Eigen/scripts/check.in | 2 +- gtsam/3rdparty/Eigen/scripts/eigen_gen_docs | 2 +- gtsam/3rdparty/Eigen/test/CMakeLists.txt | 234 +- gtsam/3rdparty/Eigen/test/adjoint.cpp | 42 +- gtsam/3rdparty/Eigen/test/array.cpp | 245 +- .../3rdparty/Eigen/test/array_for_matrix.cpp | 56 +- gtsam/3rdparty/Eigen/test/array_of_string.cpp | 32 + gtsam/3rdparty/Eigen/test/array_replicate.cpp | 13 + gtsam/3rdparty/Eigen/test/array_reverse.cpp | 32 +- gtsam/3rdparty/Eigen/test/bandmatrix.cpp | 3 - gtsam/3rdparty/Eigen/test/basicstuff.cpp | 86 +- gtsam/3rdparty/Eigen/test/bdcsvd.cpp | 111 + gtsam/3rdparty/Eigen/test/bicgstab.cpp | 16 +- gtsam/3rdparty/Eigen/test/block.cpp | 31 +- gtsam/3rdparty/Eigen/test/boostmultiprec.cpp | 201 + gtsam/3rdparty/Eigen/test/bug1213.cpp | 13 + gtsam/3rdparty/Eigen/test/bug1213.h | 8 + gtsam/3rdparty/Eigen/test/bug1213_main.cpp | 18 + gtsam/3rdparty/Eigen/test/cholesky.cpp | 157 +- gtsam/3rdparty/Eigen/test/cholmod_support.cpp | 15 +- .../3rdparty/Eigen/test/commainitializer.cpp | 4 +- .../Eigen/test/conjugate_gradient.cpp | 18 +- gtsam/3rdparty/Eigen/test/constructor.cpp | 84 + gtsam/3rdparty/Eigen/test/ctorleak.cpp | 69 + gtsam/3rdparty/Eigen/test/cuda_basic.cu | 173 + gtsam/3rdparty/Eigen/test/cuda_common.h | 101 + gtsam/3rdparty/Eigen/test/cwiseop.cpp | 187 - gtsam/3rdparty/Eigen/test/dense_storage.cpp | 76 + gtsam/3rdparty/Eigen/test/diagonal.cpp | 24 + .../3rdparty/Eigen/test/diagonalmatrices.cpp | 27 + gtsam/3rdparty/Eigen/test/dynalloc.cpp | 66 +- .../3rdparty/Eigen/test/eigen2/CMakeLists.txt | 61 - .../Eigen/test/eigen2/eigen2_adjoint.cpp | 99 - .../Eigen/test/eigen2/eigen2_alignedbox.cpp | 60 - .../Eigen/test/eigen2/eigen2_array.cpp | 142 - .../Eigen/test/eigen2/eigen2_basicstuff.cpp | 105 - .../Eigen/test/eigen2/eigen2_bug_132.cpp | 26 - .../Eigen/test/eigen2/eigen2_cholesky.cpp | 113 - .../test/eigen2/eigen2_commainitializer.cpp | 46 - .../Eigen/test/eigen2/eigen2_cwiseop.cpp | 158 - .../Eigen/test/eigen2/eigen2_determinant.cpp | 61 - .../Eigen/test/eigen2/eigen2_dynalloc.cpp | 131 - .../Eigen/test/eigen2/eigen2_eigensolver.cpp | 146 - .../test/eigen2/eigen2_first_aligned.cpp | 49 - .../Eigen/test/eigen2/eigen2_geometry.cpp | 432 - .../eigen2_geometry_with_eigen2_prefix.cpp | 435 - .../Eigen/test/eigen2/eigen2_hyperplane.cpp | 126 - .../Eigen/test/eigen2/eigen2_inverse.cpp | 62 - .../test/eigen2/eigen2_linearstructure.cpp | 83 - .../3rdparty/Eigen/test/eigen2/eigen2_lu.cpp | 122 - .../3rdparty/Eigen/test/eigen2/eigen2_map.cpp | 114 - .../Eigen/test/eigen2/eigen2_meta.cpp | 60 - .../Eigen/test/eigen2/eigen2_miscmatrices.cpp | 48 - .../Eigen/test/eigen2/eigen2_mixingtypes.cpp | 77 - .../Eigen/test/eigen2/eigen2_nomalloc.cpp | 53 - .../Eigen/test/eigen2/eigen2_packetmath.cpp | 132 - .../test/eigen2/eigen2_parametrizedline.cpp | 62 - .../test/eigen2/eigen2_prec_inverse_4x4.cpp | 84 - .../test/eigen2/eigen2_product_large.cpp | 45 - .../test/eigen2/eigen2_product_small.cpp | 22 - .../3rdparty/Eigen/test/eigen2/eigen2_qr.cpp | 69 - .../Eigen/test/eigen2/eigen2_qtvector.cpp | 158 - .../Eigen/test/eigen2/eigen2_regression.cpp | 136 - .../Eigen/test/eigen2/eigen2_sizeof.cpp | 31 - .../Eigen/test/eigen2/eigen2_smallvectors.cpp | 42 - .../Eigen/test/eigen2/eigen2_sparse_basic.cpp | 317 - .../test/eigen2/eigen2_sparse_product.cpp | 115 - .../test/eigen2/eigen2_sparse_solvers.cpp | 200 - .../test/eigen2/eigen2_sparse_vector.cpp | 84 - .../Eigen/test/eigen2/eigen2_stdvector.cpp | 148 - .../Eigen/test/eigen2/eigen2_submatrices.cpp | 142 - .../3rdparty/Eigen/test/eigen2/eigen2_sum.cpp | 71 - .../3rdparty/Eigen/test/eigen2/eigen2_svd.cpp | 87 - .../Eigen/test/eigen2/eigen2_swap.cpp | 83 - .../Eigen/test/eigen2/eigen2_triangular.cpp | 148 - .../test/eigen2/eigen2_unalignedassert.cpp | 116 - .../Eigen/test/eigen2/eigen2_visitor.cpp | 116 - gtsam/3rdparty/Eigen/test/eigen2/gsl_helper.h | 175 - gtsam/3rdparty/Eigen/test/eigen2/main.h | 399 - gtsam/3rdparty/Eigen/test/eigen2/product.h | 129 - gtsam/3rdparty/Eigen/test/eigen2/runtest.sh | 28 - gtsam/3rdparty/Eigen/test/eigen2/sparse.h | 154 - .../Eigen/test/eigen2/testsuite.cmake | 197 - gtsam/3rdparty/Eigen/test/eigen2support.cpp | 1 - .../Eigen/test/eigensolver_complex.cpp | 71 +- .../test/eigensolver_generalized_real.cpp | 54 +- .../Eigen/test/eigensolver_generic.cpp | 49 +- .../Eigen/test/eigensolver_selfadjoint.cpp | 184 +- gtsam/3rdparty/Eigen/test/evaluator_common.h | 0 gtsam/3rdparty/Eigen/test/evaluators.cpp | 499 + gtsam/3rdparty/Eigen/test/fastmath.cpp | 99 + gtsam/3rdparty/Eigen/test/first_aligned.cpp | 6 +- gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp | 11 +- gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp | 20 +- gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp | 24 +- gtsam/3rdparty/Eigen/test/geo_hyperplane.cpp | 39 +- .../3rdparty/Eigen/test/geo_orthomethods.cpp | 14 +- .../Eigen/test/geo_parametrizedline.cpp | 10 +- gtsam/3rdparty/Eigen/test/geo_quaternion.cpp | 51 +- .../Eigen/test/geo_transformations.cpp | 95 +- gtsam/3rdparty/Eigen/test/half_float.cpp | 264 + .../Eigen/test/incomplete_cholesky.cpp | 65 + .../Eigen/test/inplace_decomposition.cpp | 110 + gtsam/3rdparty/Eigen/test/integer_types.cpp | 8 + gtsam/3rdparty/Eigen/test/inverse.cpp | 15 +- gtsam/3rdparty/Eigen/test/is_same_dense.cpp | 33 + gtsam/3rdparty/Eigen/test/jacobisvd.cpp | 386 +- gtsam/3rdparty/Eigen/test/linearstructure.cpp | 67 +- gtsam/3rdparty/Eigen/test/lscg.cpp | 37 + gtsam/3rdparty/Eigen/test/lu.cpp | 83 +- gtsam/3rdparty/Eigen/test/main.h | 295 +- gtsam/3rdparty/Eigen/test/mapped_matrix.cpp | 86 +- .../3rdparty/Eigen/test/mapstaticmethods.cpp | 6 +- gtsam/3rdparty/Eigen/test/mapstride.cpp | 43 +- gtsam/3rdparty/Eigen/test/meta.cpp | 24 + gtsam/3rdparty/Eigen/test/metis_support.cpp | 22 +- gtsam/3rdparty/Eigen/test/mixingtypes.cpp | 202 +- gtsam/3rdparty/Eigen/test/mpl2only.cpp | 22 + gtsam/3rdparty/Eigen/test/nesting_ops.cpp | 86 +- gtsam/3rdparty/Eigen/test/nomalloc.cpp | 59 +- gtsam/3rdparty/Eigen/test/nullary.cpp | 225 +- gtsam/3rdparty/Eigen/test/numext.cpp | 53 + gtsam/3rdparty/Eigen/test/packetmath.cpp | 425 +- gtsam/3rdparty/Eigen/test/pastix_support.cpp | 10 + .../Eigen/test/permutationmatrices.cpp | 62 +- gtsam/3rdparty/Eigen/test/product.h | 58 +- gtsam/3rdparty/Eigen/test/product_extra.cpp | 146 +- gtsam/3rdparty/Eigen/test/product_large.cpp | 32 +- gtsam/3rdparty/Eigen/test/product_mmtr.cpp | 39 +- .../Eigen/test/product_notemporary.cpp | 60 +- .../Eigen/test/product_selfadjoint.cpp | 9 +- gtsam/3rdparty/Eigen/test/product_small.cpp | 247 +- gtsam/3rdparty/Eigen/test/product_symm.cpp | 18 + gtsam/3rdparty/Eigen/test/product_syrk.cpp | 5 +- gtsam/3rdparty/Eigen/test/product_trmm.cpp | 22 +- gtsam/3rdparty/Eigen/test/product_trmv.cpp | 6 +- gtsam/3rdparty/Eigen/test/product_trsolve.cpp | 18 +- gtsam/3rdparty/Eigen/test/qr.cpp | 9 +- gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp | 206 +- gtsam/3rdparty/Eigen/test/qr_fullpivoting.cpp | 34 +- gtsam/3rdparty/Eigen/test/rand.cpp | 118 + gtsam/3rdparty/Eigen/test/real_qz.cpp | 16 +- gtsam/3rdparty/Eigen/test/redux.cpp | 13 +- gtsam/3rdparty/Eigen/test/ref.cpp | 27 +- gtsam/3rdparty/Eigen/test/runtest.sh | 20 - gtsam/3rdparty/Eigen/test/rvalue_types.cpp | 64 + gtsam/3rdparty/Eigen/test/schur_complex.cpp | 4 +- gtsam/3rdparty/Eigen/test/schur_real.cpp | 4 +- gtsam/3rdparty/Eigen/test/selfadjoint.cpp | 15 +- .../Eigen/test/simplicial_cholesky.cpp | 28 +- gtsam/3rdparty/Eigen/test/sizeof.cpp | 17 +- gtsam/3rdparty/Eigen/test/sizeoverflow.cpp | 2 - gtsam/3rdparty/Eigen/test/sparse.h | 23 +- gtsam/3rdparty/Eigen/test/sparse_basic.cpp | 656 +- gtsam/3rdparty/Eigen/test/sparse_block.cpp | 317 + .../Eigen/test/sparse_permutations.cpp | 95 +- gtsam/3rdparty/Eigen/test/sparse_product.cpp | 205 +- gtsam/3rdparty/Eigen/test/sparse_ref.cpp | 139 + gtsam/3rdparty/Eigen/test/sparse_solver.h | 388 +- gtsam/3rdparty/Eigen/test/sparse_vector.cpp | 75 +- gtsam/3rdparty/Eigen/test/sparselu.cpp | 28 +- gtsam/3rdparty/Eigen/test/sparseqr.cpp | 12 +- gtsam/3rdparty/Eigen/test/spqr_support.cpp | 8 +- gtsam/3rdparty/Eigen/test/stable_norm.cpp | 105 +- ...newstdvector.cpp => stddeque_overload.cpp} | 77 +- .../3rdparty/Eigen/test/stdlist_overload.cpp | 192 + gtsam/3rdparty/Eigen/test/stdvector.cpp | 6 +- .../Eigen/test/stdvector_overload.cpp | 6 +- gtsam/3rdparty/Eigen/test/superlu_support.cpp | 1 + gtsam/3rdparty/Eigen/test/svd_common.h | 483 + gtsam/3rdparty/Eigen/test/svd_fill.h | 119 + gtsam/3rdparty/Eigen/test/swap.cpp | 23 +- gtsam/3rdparty/Eigen/test/testsuite.cmake | 229 - gtsam/3rdparty/Eigen/test/triangular.cpp | 19 +- gtsam/3rdparty/Eigen/test/umfpack_support.cpp | 1 + gtsam/3rdparty/Eigen/test/unalignedassert.cpp | 93 +- gtsam/3rdparty/Eigen/test/unalignedcount.cpp | 9 +- .../Eigen/test/upperbidiagonalization.cpp | 2 +- .../Eigen/test/vectorization_logic.cpp | 340 +- gtsam/3rdparty/Eigen/test/vectorwiseop.cpp | 75 +- gtsam/3rdparty/Eigen/test/zerosized.cpp | 20 +- .../Eigen/unsupported/Eigen/AdolcForward | 2 +- .../Eigen/unsupported/Eigen/AlignedVector3 | 38 +- .../Eigen/unsupported/Eigen/CMakeLists.txt | 31 +- .../unsupported/Eigen/CXX11/CMakeLists.txt | 8 + .../Eigen/unsupported/Eigen/CXX11/Tensor | 152 + .../unsupported/Eigen/CXX11/TensorSymmetry | 42 + .../Eigen/unsupported/Eigen/CXX11/ThreadPool | 65 + .../Eigen/CXX11/src/Tensor/README.md | 1757 ++ .../Eigen/CXX11/src/Tensor/Tensor.h | 527 + .../Eigen/CXX11/src/Tensor/TensorArgMax.h | 299 + .../Eigen/CXX11/src/Tensor/TensorAssign.h | 181 + .../Eigen/CXX11/src/Tensor/TensorBase.h | 1010 + .../CXX11/src/Tensor/TensorBroadcasting.h | 392 + .../Eigen/CXX11/src/Tensor/TensorChipping.h | 384 + .../CXX11/src/Tensor/TensorConcatenation.h | 361 + .../CXX11/src/Tensor/TensorContraction.h | 628 + .../src/Tensor/TensorContractionBlocking.h | 56 + .../CXX11/src/Tensor/TensorContractionCuda.h | 1391 ++ .../src/Tensor/TensorContractionMapper.h | 467 + .../src/Tensor/TensorContractionThreadPool.h | 1052 + .../Eigen/CXX11/src/Tensor/TensorConversion.h | 279 + .../CXX11/src/Tensor/TensorConvolution.h | 1104 ++ .../Eigen/CXX11/src/Tensor/TensorCostModel.h | 212 + .../Eigen/CXX11/src/Tensor/TensorCustomOp.h | 313 + .../Eigen/CXX11/src/Tensor/TensorDevice.h | 68 + .../Eigen/CXX11/src/Tensor/TensorDeviceCuda.h | 337 + .../CXX11/src/Tensor/TensorDeviceDefault.h | 81 + .../Eigen/CXX11/src/Tensor/TensorDeviceSycl.h | 122 + .../CXX11/src/Tensor/TensorDeviceThreadPool.h | 279 + .../CXX11/src/Tensor/TensorDimensionList.h | 236 + .../Eigen/CXX11/src/Tensor/TensorDimensions.h | 428 + .../Eigen/CXX11/src/Tensor/TensorEvalTo.h | 181 + .../Eigen/CXX11/src/Tensor/TensorEvaluator.h | 633 + .../Eigen/CXX11/src/Tensor/TensorExecutor.h | 288 + .../Eigen/CXX11/src/Tensor/TensorExpr.h | 371 + .../Eigen/CXX11/src/Tensor/TensorFFT.h | 651 + .../Eigen/CXX11/src/Tensor/TensorFixedSize.h | 389 + .../Eigen/CXX11/src/Tensor/TensorForcedEval.h | 167 + .../src/Tensor/TensorForwardDeclarations.h | 109 + .../Eigen/CXX11/src/Tensor/TensorFunctors.h | 489 + .../Eigen/CXX11/src/Tensor/TensorGenerator.h | 185 + .../CXX11/src/Tensor/TensorGlobalFunctions.h | 33 + .../Eigen/CXX11/src/Tensor/TensorIO.h | 79 + .../Eigen/CXX11/src/Tensor/TensorImagePatch.h | 509 + .../Eigen/CXX11/src/Tensor/TensorIndexList.h | 725 + .../Eigen/CXX11/src/Tensor/TensorInflation.h | 229 + .../CXX11/src/Tensor/TensorInitializer.h | 82 + .../Eigen/CXX11/src/Tensor/TensorIntDiv.h | 253 + .../Eigen/CXX11/src/Tensor/TensorLayoutSwap.h | 209 + .../Eigen/CXX11/src/Tensor/TensorMacros.h | 54 + .../Eigen/CXX11/src/Tensor/TensorMap.h | 321 + .../Eigen/CXX11/src/Tensor/TensorMeta.h | 218 + .../Eigen/CXX11/src/Tensor/TensorMorphing.h | 888 + .../Eigen/CXX11/src/Tensor/TensorPadding.h | 397 + .../Eigen/CXX11/src/Tensor/TensorPatch.h | 269 + .../Eigen/CXX11/src/Tensor/TensorRandom.h | 276 + .../Eigen/CXX11/src/Tensor/TensorReduction.h | 781 + .../CXX11/src/Tensor/TensorReductionCuda.h | 750 + .../CXX11/src/Tensor/TensorReductionSycl.h | 242 + .../Eigen/CXX11/src/Tensor/TensorRef.h | 429 + .../Eigen/CXX11/src/Tensor/TensorReverse.h | 288 + .../Eigen/CXX11/src/Tensor/TensorScan.h | 287 + .../Eigen/CXX11/src/Tensor/TensorShuffling.h | 264 + .../Eigen/CXX11/src/Tensor/TensorStorage.h | 146 + .../Eigen/CXX11/src/Tensor/TensorStriding.h | 338 + .../Eigen/CXX11/src/Tensor/TensorSycl.h | 82 + .../TensorSyclConvertToDeviceExpression.h | 121 + .../src/Tensor/TensorSyclExprConstructor.h | 239 + .../src/Tensor/TensorSyclExtractAccessor.h | 204 + .../src/Tensor/TensorSyclExtractFunctors.h | 177 + .../CXX11/src/Tensor/TensorSyclLeafCount.h | 114 + .../src/Tensor/TensorSyclPlaceHolderExpr.h | 181 + .../Eigen/CXX11/src/Tensor/TensorSyclRun.h | 70 + .../Eigen/CXX11/src/Tensor/TensorSyclTuple.h | 234 + .../Eigen/CXX11/src/Tensor/TensorTraits.h | 272 + .../Eigen/CXX11/src/Tensor/TensorUInt128.h | 248 + .../CXX11/src/Tensor/TensorVolumePatch.h | 608 + .../src/TensorSymmetry/DynamicSymmetry.h | 293 + .../CXX11/src/TensorSymmetry/StaticSymmetry.h | 236 + .../Eigen/CXX11/src/TensorSymmetry/Symmetry.h | 338 + .../TensorSymmetry/util/TemplateGroupTheory.h | 666 + .../Eigen/CXX11/src/ThreadPool/EventCount.h | 233 + .../src/ThreadPool/NonBlockingThreadPool.h | 274 + .../Eigen/CXX11/src/ThreadPool/RunQueue.h | 210 + .../CXX11/src/ThreadPool/SimpleThreadPool.h | 154 + .../CXX11/src/ThreadPool/ThreadEnvironment.h | 38 + .../Eigen/CXX11/src/ThreadPool/ThreadLocal.h | 22 + .../src/ThreadPool/ThreadPoolInterface.h | 33 + .../Eigen/CXX11/src/ThreadPool/ThreadYield.h | 20 + .../Eigen/CXX11/src/util/CXX11Meta.h | 542 + .../Eigen/CXX11/src/util/CXX11Workarounds.h | 88 + .../Eigen/CXX11/src/util/EmulateArray.h | 267 + .../Eigen/CXX11/src/util/EmulateCXX11Meta.h | 311 + .../Eigen/CXX11/src/util/MaxSizeVector.h | 141 + .../Eigen/unsupported/Eigen/EulerAngles | 43 + .../Eigen/unsupported/Eigen/IterativeSolvers | 5 +- .../Eigen/unsupported/Eigen/KroneckerProduct | 2 + .../Eigen/unsupported/Eigen/MPRealSupport | 100 +- .../Eigen/unsupported/Eigen/MatrixFunctions | 76 +- .../Eigen/unsupported/Eigen/OpenGLSupport | 20 +- gtsam/3rdparty/Eigen/unsupported/Eigen/SVD | 39 - .../Eigen/unsupported/Eigen/SparseExtra | 3 - .../Eigen/unsupported/Eigen/SpecialFunctions | 63 + .../Eigen/src/AutoDiff/AutoDiffJacobian.h | 51 +- .../Eigen/src/AutoDiff/AutoDiffScalar.h | 247 +- .../Eigen/src/AutoDiff/CMakeLists.txt | 6 - .../unsupported/Eigen/src/BVH/CMakeLists.txt | 6 - .../unsupported/Eigen/src/CMakeLists.txt | 15 - .../ArpackSelfAdjointEigenSolver.h | 14 +- .../Eigen/src/EulerAngles/CMakeLists.txt | 6 + .../Eigen/src/EulerAngles/EulerAngles.h | 386 + .../Eigen/src/EulerAngles/EulerSystem.h | 326 + .../unsupported/Eigen/src/FFT/CMakeLists.txt | 6 - .../Eigen/src/IterativeSolvers/CMakeLists.txt | 6 - .../Eigen/src/IterativeSolvers/DGMRES.h | 57 +- .../Eigen/src/IterativeSolvers/GMRES.h | 390 +- .../src/IterativeSolvers/IncompleteCholesky.h | 278 - .../Eigen/src/IterativeSolvers/IncompleteLU.h | 39 +- .../Eigen/src/IterativeSolvers/MINRES.h | 84 +- .../Eigen/src/IterativeSolvers/Scaling.h | 6 +- .../Eigen/src/KroneckerProduct/CMakeLists.txt | 6 - .../KroneckerProduct/KroneckerTensorProduct.h | 183 +- .../src/LevenbergMarquardt/CMakeLists.txt | 6 - .../Eigen/src/LevenbergMarquardt/LMcovar.h | 1 - .../Eigen/src/LevenbergMarquardt/LMpar.h | 2 +- .../Eigen/src/LevenbergMarquardt/LMqrsolv.h | 9 +- .../LevenbergMarquardt/LevenbergMarquardt.h | 31 +- .../Eigen/src/MatrixFunctions/CMakeLists.txt | 6 - .../src/MatrixFunctions/MatrixExponential.h | 711 +- .../src/MatrixFunctions/MatrixFunction.h | 713 +- .../MatrixFunctions/MatrixFunctionAtomic.h | 131 - .../src/MatrixFunctions/MatrixLogarithm.h | 517 +- .../Eigen/src/MatrixFunctions/MatrixPower.h | 397 +- .../src/MatrixFunctions/MatrixSquareRoot.h | 452 +- .../Eigen/src/MatrixFunctions/StemFunction.h | 172 +- .../src/MoreVectorization/CMakeLists.txt | 6 - .../src/NonLinearOptimization/CMakeLists.txt | 6 - .../HybridNonLinearSolver.h | 4 +- .../LevenbergMarquardt.h | 25 +- .../Eigen/src/NumericalDiff/CMakeLists.txt | 6 - .../Eigen/src/Polynomials/CMakeLists.txt | 6 - .../Eigen/src/Polynomials/PolynomialSolver.h | 33 +- .../Eigen/src/Polynomials/PolynomialUtils.h | 2 +- .../Eigen/unsupported/Eigen/src/SVD/BDCSVD.h | 748 - .../unsupported/Eigen/src/SVD/CMakeLists.txt | 6 - .../unsupported/Eigen/src/SVD/JacobiSVD.h | 782 - .../unsupported/Eigen/src/SVD/TODOBdcsvd.txt | 29 - .../Eigen/src/SVD/doneInBDCSVD.txt | 21 - .../Eigen/src/Skyline/CMakeLists.txt | 6 - .../Eigen/src/Skyline/SkylineProduct.h | 6 +- .../Eigen/src/SparseExtra/BlockSparseMatrix.h | 1079 + .../Eigen/src/SparseExtra/CMakeLists.txt | 6 - .../src/SparseExtra/DynamicSparseMatrix.h | 71 +- .../Eigen/src/SparseExtra/MarketIO.h | 21 +- .../src/SparseExtra/MatrixMarketIterator.h | 43 +- .../Eigen/src/SparseExtra/RandomSetter.h | 10 +- .../SpecialFunctionsArrayAPI.h | 124 + .../SpecialFunctionsFunctors.h | 236 + .../SpecialFunctions/SpecialFunctionsHalf.h | 47 + .../SpecialFunctions/SpecialFunctionsImpl.h | 1565 ++ .../SpecialFunctionsPacketMath.h | 58 + .../arch/CUDA/CudaSpecialFunctions.h | 165 + .../Eigen/src/Splines/CMakeLists.txt | 6 - .../unsupported/Eigen/src/Splines/Spline.h | 74 +- .../Eigen/src/Splines/SplineFitting.h | 274 + .../unsupported/Eigen/src/Splines/SplineFwd.h | 3 + .../Eigen/unsupported/doc/Overview.dox | 11 +- .../unsupported/doc/examples/BVH_Example.cpp | 4 +- .../unsupported/doc/examples/EulerAngles.cpp | 46 + .../Eigen/unsupported/test/CMakeLists.txt | 177 +- .../Eigen/unsupported/test/EulerAngles.cpp | 208 + .../3rdparty/Eigen/unsupported/test/FFTW.cpp | 32 +- .../test/NonLinearOptimization.cpp | 46 +- .../Eigen/unsupported/test/alignedvector3.cpp | 29 +- .../Eigen/unsupported/test/autodiff.cpp | 195 +- .../unsupported/test/autodiff_scalar.cpp | 98 + .../Eigen/unsupported/test/bdcsvd.cpp | 213 - .../unsupported/test/cxx11_eventcount.cpp | 142 + .../Eigen/unsupported/test/cxx11_meta.cpp | 357 + .../test/cxx11_non_blocking_thread_pool.cpp | 107 + .../Eigen/unsupported/test/cxx11_runqueue.cpp | 235 + .../unsupported/test/cxx11_tensor_argmax.cpp | 294 + .../test/cxx11_tensor_argmax_cuda.cu | 254 + .../unsupported/test/cxx11_tensor_assign.cpp | 370 + .../test/cxx11_tensor_broadcast_sycl.cpp | 74 + .../test/cxx11_tensor_broadcasting.cpp | 194 + .../test/cxx11_tensor_cast_float16_cuda.cu | 82 + .../unsupported/test/cxx11_tensor_casts.cpp | 115 + .../test/cxx11_tensor_chipping.cpp | 425 + .../test/cxx11_tensor_comparisons.cpp | 84 + .../test/cxx11_tensor_complex_cuda.cu | 153 + .../cxx11_tensor_complex_cwise_ops_cuda.cu | 97 + .../test/cxx11_tensor_concatenation.cpp | 137 + .../unsupported/test/cxx11_tensor_const.cpp | 62 + .../test/cxx11_tensor_contract_cuda.cu | 216 + .../test/cxx11_tensor_contraction.cpp | 545 + .../test/cxx11_tensor_convolution.cpp | 149 + .../unsupported/test/cxx11_tensor_cuda.cu | 1287 ++ .../test/cxx11_tensor_custom_index.cpp | 100 + .../test/cxx11_tensor_custom_op.cpp | 111 + .../unsupported/test/cxx11_tensor_device.cu | 390 + .../test/cxx11_tensor_device_sycl.cpp | 31 + .../test/cxx11_tensor_dimension.cpp | 69 + .../unsupported/test/cxx11_tensor_empty.cpp | 40 + .../unsupported/test/cxx11_tensor_expr.cpp | 314 + .../unsupported/test/cxx11_tensor_fft.cpp | 273 + .../test/cxx11_tensor_fixed_size.cpp | 261 + .../test/cxx11_tensor_forced_eval.cpp | 79 + .../test/cxx11_tensor_forced_eval_sycl.cpp | 70 + .../test/cxx11_tensor_generator.cpp | 91 + .../unsupported/test/cxx11_tensor_ifft.cpp | 154 + .../test/cxx11_tensor_image_patch.cpp | 757 + .../test/cxx11_tensor_index_list.cpp | 386 + .../test/cxx11_tensor_inflation.cpp | 81 + .../unsupported/test/cxx11_tensor_intdiv.cpp | 147 + .../unsupported/test/cxx11_tensor_io.cpp | 136 + .../test/cxx11_tensor_layout_swap.cpp | 61 + .../unsupported/test/cxx11_tensor_lvalue.cpp | 42 + .../unsupported/test/cxx11_tensor_map.cpp | 277 + .../unsupported/test/cxx11_tensor_math.cpp | 46 + .../test/cxx11_tensor_mixed_indices.cpp | 53 + .../test/cxx11_tensor_morphing.cpp | 485 + .../test/cxx11_tensor_notification.cpp | 81 + .../test/cxx11_tensor_of_complex.cpp | 103 + .../test/cxx11_tensor_of_const_values.cpp | 105 + .../test/cxx11_tensor_of_float16_cuda.cu | 494 + .../test/cxx11_tensor_of_strings.cpp | 152 + .../unsupported/test/cxx11_tensor_padding.cpp | 93 + .../unsupported/test/cxx11_tensor_patch.cpp | 172 + .../unsupported/test/cxx11_tensor_random.cpp | 78 + .../test/cxx11_tensor_random_cuda.cu | 88 + .../test/cxx11_tensor_reduction.cpp | 508 + .../test/cxx11_tensor_reduction_cuda.cu | 157 + .../test/cxx11_tensor_reduction_sycl.cpp | 138 + .../unsupported/test/cxx11_tensor_ref.cpp | 248 + .../unsupported/test/cxx11_tensor_reverse.cpp | 190 + .../test/cxx11_tensor_roundings.cpp | 62 + .../unsupported/test/cxx11_tensor_scan.cpp | 110 + .../test/cxx11_tensor_scan_cuda.cu | 79 + .../test/cxx11_tensor_shuffling.cpp | 228 + .../unsupported/test/cxx11_tensor_simple.cpp | 327 + .../test/cxx11_tensor_striding.cpp | 119 + .../unsupported/test/cxx11_tensor_sugar.cpp | 81 + .../unsupported/test/cxx11_tensor_sycl.cpp | 159 + .../test/cxx11_tensor_symmetry.cpp | 818 + .../test/cxx11_tensor_thread_pool.cpp | 373 + .../unsupported/test/cxx11_tensor_uint128.cpp | 160 + .../test/cxx11_tensor_volume_patch.cpp | 112 + .../Eigen/unsupported/test/forward_adolc.cpp | 4 +- .../Eigen/unsupported/test/jacobisvd.cpp | 198 - .../unsupported/test/kronecker_product.cpp | 89 +- .../unsupported/test/levenberg_marquardt.cpp | 93 +- .../unsupported/test/matrix_function.cpp | 6 +- .../Eigen/unsupported/test/matrix_functions.h | 42 +- .../Eigen/unsupported/test/matrix_power.cpp | 169 +- .../Eigen/unsupported/test/minres.cpp | 19 +- .../Eigen/unsupported/test/mpreal/mpreal.h | 856 +- .../Eigen/unsupported/test/mpreal_support.cpp | 10 +- .../unsupported/test/polynomialsolver.cpp | 7 +- .../Eigen/unsupported/test/sparse_extra.cpp | 1 - .../unsupported/test/special_functions.cpp | 345 + .../Eigen/unsupported/test/splines.cpp | 73 +- .../Eigen/unsupported/test/svd_common.h | 261 - 1105 files changed, 142156 insertions(+), 45264 deletions(-) delete mode 100644 gtsam/3rdparty/Eigen/.hg_archival.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/Array delete mode 100644 gtsam/3rdparty/Eigen/Eigen/Eigen2Support delete mode 100644 gtsam/3rdparty/Eigen/Eigen/LeastSquares mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/PardisoSupport delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Cholesky/CMakeLists.txt rename gtsam/3rdparty/Eigen/Eigen/src/Cholesky/{LLT_MKL.h => LLT_LAPACKE.h} (71%) delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/AssignEvaluator.h mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/ConditionEstimator.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/CoreEvaluators.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseTernaryOp.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/Inverse.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctionsImpl.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/ProductEvaluators.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/Solve.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/SolverBase.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX/Complex.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX/MathFunctions.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX/PacketMath.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX/TypeCasting.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX512/MathFunctions.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AVX512/PacketMath.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/MathFunctions.h mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/AltiVec/PacketMath.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/Complex.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/Half.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/MathFunctions.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/PacketMath.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/PacketMathHalf.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/CUDA/TypeCasting.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/Default/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/NEON/MathFunctions.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/CMakeLists.txt mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/PacketMath.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/SSE/TypeCasting.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/ZVector/Complex.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/ZVector/MathFunctions.h create mode 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/arch/ZVector/PacketMath.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/AssignmentFunctors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/BinaryFunctors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/NullaryFunctors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/StlFunctors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/TernaryFunctors.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/functors/UnaryFunctors.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/products/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/products/CoeffBasedProduct.h rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{GeneralMatrixMatrixTriangular_MKL.h => GeneralMatrixMatrixTriangular_BLAS.h} (68%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{GeneralMatrixMatrix_MKL.h => GeneralMatrixMatrix_BLAS.h} (76%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{GeneralMatrixVector_MKL.h => GeneralMatrixVector_BLAS.h} (60%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{SelfadjointMatrixMatrix_MKL.h => SelfadjointMatrixMatrix_BLAS.h} (68%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{SelfadjointMatrixVector_MKL.h => SelfadjointMatrixVector_BLAS.h} (72%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{TriangularMatrixMatrix_MKL.h => TriangularMatrixMatrix_BLAS.h} (76%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{TriangularMatrixVector_MKL.h => TriangularMatrixVector_BLAS.h} (74%) rename gtsam/3rdparty/Eigen/Eigen/src/Core/products/{TriangularSolverMatrix_MKL.h => TriangularSolverMatrix_BLAS.h} (75%) mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/util/BlasUtil.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Core/util/CMakeLists.txt mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/util/DisableStupidWarnings.h mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/util/MKL_support.h mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Core/util/Meta.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Block.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Cwise.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/CwiseOperators.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AlignedBox.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/All.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/AngleAxis.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Hyperplane.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/ParametrizedLine.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Quaternion.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Rotation2D.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/RotationBase.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Scaling.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Transform.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Geometry/Translation.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LU.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Lazy.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/LeastSquares.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Macros.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/MathFunctions.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Memory.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Meta.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/Minor.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/QR.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/SVD.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/TriangularSolver.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigen2Support/VectorBlock.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/CMakeLists.txt rename gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/{ComplexSchur_MKL.h => ComplexSchur_LAPACKE.h} (65%) rename gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/{RealSchur_MKL.h => RealSchur_LAPACKE.h} (64%) rename gtsam/3rdparty/Eigen/Eigen/src/Eigenvalues/{SelfAdjointEigenSolver_MKL.h => SelfAdjointEigenSolver_LAPACKE.h} (62%) delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Geometry/CMakeLists.txt mode change 100644 => 100755 gtsam/3rdparty/Eigen/Eigen/src/Geometry/Scaling.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Geometry/arch/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Householder/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/Jacobi/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/LU/CMakeLists.txt rename gtsam/3rdparty/Eigen/Eigen/src/LU/{Inverse.h => InverseImpl.h} (86%) rename gtsam/3rdparty/Eigen/Eigen/src/LU/{PartialPivLU_MKL.h => PartialPivLU_LAPACKE.h} (77%) delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/LU/arch/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/MetisSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/OrderingMethods/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/PaStiXSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/PardisoSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/QR/CMakeLists.txt rename gtsam/3rdparty/Eigen/Eigen/src/QR/{ColPivHouseholderQR_MKL.h => ColPivHouseholderQR_LAPACKE.h} (64%) create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/QR/CompleteOrthogonalDecomposition.h rename gtsam/3rdparty/Eigen/Eigen/src/QR/{HouseholderQR_MKL.h => HouseholderQR_LAPACKE.h} (77%) delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SPQRSupport/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SVD/BDCSVD.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SVD/CMakeLists.txt rename gtsam/3rdparty/Eigen/Eigen/src/SVD/{JacobiSVD_MKL.h => JacobiSVD_LAPACKE.h} (62%) rename gtsam/3rdparty/Eigen/{unsupported => }/Eigen/src/SVD/SVDBase.h (52%) delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCholesky/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseAssign.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseCompressedBase.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseMap.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseRef.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseCore/SparseSolverBase.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseLU/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SparseQR/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/StlSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/SuperLUSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/UmfPackSupport/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/RealSvd2x2.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/Solve.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/SparseSolve.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/lapack.h create mode 100755 gtsam/3rdparty/Eigen/Eigen/src/misc/lapacke.h create mode 100644 gtsam/3rdparty/Eigen/Eigen/src/misc/lapacke_mangling.h delete mode 100644 gtsam/3rdparty/Eigen/Eigen/src/plugins/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/README.md create mode 100644 gtsam/3rdparty/Eigen/bench/analyze-blocking-sizes.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/benchmark-blocking-sizes.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/btl/cmake/FindBLAZE.cmake delete mode 100644 gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO.cmake delete mode 100644 gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO2.cmake create mode 100644 gtsam/3rdparty/Eigen/bench/btl/cmake/FindOPENBLAS.cmake create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/blaze/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/blaze/blaze_interface.hh create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/blaze/main.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/tensors/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_linear.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_matmat.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_vecmat.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/btl/libs/tensors/tensor_interface.hh create mode 100644 gtsam/3rdparty/Eigen/bench/dense_solvers.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/changesets.txt create mode 100644 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm_settings.txt create mode 100644 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm.cpp create mode 100644 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm_settings.txt create mode 100755 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/make_plot.sh create mode 100755 gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/run.sh create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/README create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/benchmark.h create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/benchmark_main.cc create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/contraction_benchmarks_cpu.cc create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks.h create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_cpu.cc create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_gpu.cu create mode 100644 gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_sycl.cc delete mode 100644 gtsam/3rdparty/Eigen/blas/chbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/chpmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/ctbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/drotm.f delete mode 100644 gtsam/3rdparty/Eigen/blas/drotmg.f delete mode 100644 gtsam/3rdparty/Eigen/blas/dsbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/dspmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/dtbmv.f create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/chbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/chpmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/complexdots.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/ctbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/d_cnjg.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/datatypes.h create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/drotm.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/drotmg.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/dsbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/dspmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/dtbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/lsame.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/r_cnjg.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/srotm.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/srotmg.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/ssbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/sspmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/stbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/zhbmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/zhpmv.c create mode 100644 gtsam/3rdparty/Eigen/blas/f2c/ztbmv.c rename gtsam/3rdparty/Eigen/blas/{ => fortran}/complexdots.f (100%) delete mode 100644 gtsam/3rdparty/Eigen/blas/lsame.f delete mode 100644 gtsam/3rdparty/Eigen/blas/srotm.f delete mode 100644 gtsam/3rdparty/Eigen/blas/srotmg.f delete mode 100644 gtsam/3rdparty/Eigen/blas/ssbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/sspmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/stbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/zhbmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/zhpmv.f delete mode 100644 gtsam/3rdparty/Eigen/blas/ztbmv.f create mode 100644 gtsam/3rdparty/Eigen/cmake/Eigen3Config.cmake.in create mode 100644 gtsam/3rdparty/Eigen/cmake/Eigen3ConfigLegacy.cmake.in create mode 100644 gtsam/3rdparty/Eigen/cmake/EigenUninstall.cmake create mode 100644 gtsam/3rdparty/Eigen/cmake/FindBLASEXT.cmake create mode 100644 gtsam/3rdparty/Eigen/cmake/FindComputeCpp.cmake create mode 100644 gtsam/3rdparty/Eigen/cmake/FindHWLOC.cmake create mode 100644 gtsam/3rdparty/Eigen/cmake/FindPTSCOTCH.cmake create mode 100644 gtsam/3rdparty/Eigen/cmake/UseEigen3.cmake delete mode 100644 gtsam/3rdparty/Eigen/doc/A10_Eigen2SupportModes.dox create mode 100644 gtsam/3rdparty/Eigen/doc/CoeffwiseMathFunctionsTable.dox delete mode 100644 gtsam/3rdparty/Eigen/doc/CustomizingEigen.dox create mode 100644 gtsam/3rdparty/Eigen/doc/CustomizingEigen_CustomScalar.dox create mode 100644 gtsam/3rdparty/Eigen/doc/CustomizingEigen_InheritingMatrix.dox create mode 100644 gtsam/3rdparty/Eigen/doc/CustomizingEigen_NullaryExpr.dox create mode 100644 gtsam/3rdparty/Eigen/doc/CustomizingEigen_Plugins.dox create mode 100644 gtsam/3rdparty/Eigen/doc/DenseDecompositionBenchmark.dox create mode 100644 gtsam/3rdparty/Eigen/doc/InplaceDecomposition.dox create mode 100644 gtsam/3rdparty/Eigen/doc/LeastSquares.dox create mode 100644 gtsam/3rdparty/Eigen/doc/MatrixfreeSolverExample.dox create mode 100644 gtsam/3rdparty/Eigen/doc/NewExpressionType.dox create mode 100644 gtsam/3rdparty/Eigen/doc/TopicCMakeGuide.dox create mode 100644 gtsam/3rdparty/Eigen/doc/TutorialReshapeSlicing.dox create mode 100644 gtsam/3rdparty/Eigen/doc/UsingBlasLapackBackends.dox create mode 100644 gtsam/3rdparty/Eigen/doc/UsingNVCC.dox create mode 100644 gtsam/3rdparty/Eigen/doc/examples/CustomizingEigen_Inheritance.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/Cwise_erf.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/Cwise_erfc.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/Cwise_lgamma.cpp delete mode 100644 gtsam/3rdparty/Eigen/doc/examples/MatrixBase_cwise_const.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/TutorialInplaceLU.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.entry create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.evaluator create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.expression create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.main create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.preamble create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.traits create mode 100644 gtsam/3rdparty/Eigen/doc/examples/make_circulant2.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/matrixfree_cg.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/examples/nullary_indexing.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/ftv2node.png create mode 100644 gtsam/3rdparty/Eigen/doc/ftv2pnode.png create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_simple.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_step_by_step.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_arg.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_array_power_array.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_atan.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_not.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_xor.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_ceil.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_cosh.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_floor.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_isFinite.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_isInf.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_isNaN.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_log10.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_round.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_scalar_power_array.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_sign.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_sinh.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Cwise_tanh.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/DenseBase_LinSpacedInt.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/DirectionWise_hnormalized.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresNormalEquations.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresQR.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_cwiseSign.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_hnormalized.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_homogeneous.cpp delete mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_marked.cpp delete mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_part.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_selfadjointView.cpp rename gtsam/3rdparty/Eigen/doc/snippets/{MatrixBase_extract.cpp => MatrixBase_triangularView.cpp} (55%) create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/SparseMatrix_coeffs.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult4.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult5.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Triangular_solve.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingCol.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingVec.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/snippets/VectorwiseOp_homogeneous.cpp create mode 100644 gtsam/3rdparty/Eigen/doc/special_examples/random_cpp11.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/bdcsvd_int.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/selfadjointview_on_const_type_actually_const.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_ref_1.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_ref_2.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_ref_3.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_ref_4.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_ref_5.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/sparse_storage_mismatch.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/swap_1.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/swap_2.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/ternary_1.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/ternary_2.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp create mode 100644 gtsam/3rdparty/Eigen/failtest/triangularview_on_const_type_actually_const.cpp create mode 100644 gtsam/3rdparty/Eigen/lapack/svd.cpp create mode 100644 gtsam/3rdparty/Eigen/test/array_of_string.cpp create mode 100644 gtsam/3rdparty/Eigen/test/bdcsvd.cpp create mode 100644 gtsam/3rdparty/Eigen/test/boostmultiprec.cpp create mode 100644 gtsam/3rdparty/Eigen/test/bug1213.cpp create mode 100644 gtsam/3rdparty/Eigen/test/bug1213.h create mode 100644 gtsam/3rdparty/Eigen/test/bug1213_main.cpp create mode 100644 gtsam/3rdparty/Eigen/test/constructor.cpp create mode 100644 gtsam/3rdparty/Eigen/test/ctorleak.cpp create mode 100644 gtsam/3rdparty/Eigen/test/cuda_basic.cu create mode 100644 gtsam/3rdparty/Eigen/test/cuda_common.h delete mode 100644 gtsam/3rdparty/Eigen/test/cwiseop.cpp create mode 100644 gtsam/3rdparty/Eigen/test/dense_storage.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_adjoint.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_alignedbox.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_array.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_basicstuff.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_bug_132.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_cholesky.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_commainitializer.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_cwiseop.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_determinant.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_dynalloc.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_eigensolver.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_first_aligned.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_hyperplane.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_inverse.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_linearstructure.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_lu.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_map.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_meta.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_miscmatrices.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_mixingtypes.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_nomalloc.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_packetmath.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_parametrizedline.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_large.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_small.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_qr.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_qtvector.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_regression.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sizeof.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_smallvectors.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_basic.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_product.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_solvers.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_vector.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_stdvector.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_submatrices.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_sum.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_svd.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_swap.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_triangular.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_unalignedassert.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/eigen2_visitor.cpp delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/gsl_helper.h delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/main.h delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/product.h delete mode 100755 gtsam/3rdparty/Eigen/test/eigen2/runtest.sh delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/sparse.h delete mode 100644 gtsam/3rdparty/Eigen/test/eigen2/testsuite.cmake create mode 100644 gtsam/3rdparty/Eigen/test/evaluator_common.h create mode 100644 gtsam/3rdparty/Eigen/test/evaluators.cpp create mode 100644 gtsam/3rdparty/Eigen/test/fastmath.cpp mode change 100644 => 100755 gtsam/3rdparty/Eigen/test/geo_transformations.cpp create mode 100644 gtsam/3rdparty/Eigen/test/half_float.cpp create mode 100644 gtsam/3rdparty/Eigen/test/incomplete_cholesky.cpp create mode 100644 gtsam/3rdparty/Eigen/test/inplace_decomposition.cpp create mode 100644 gtsam/3rdparty/Eigen/test/is_same_dense.cpp create mode 100644 gtsam/3rdparty/Eigen/test/lscg.cpp create mode 100644 gtsam/3rdparty/Eigen/test/mpl2only.cpp create mode 100644 gtsam/3rdparty/Eigen/test/numext.cpp create mode 100644 gtsam/3rdparty/Eigen/test/rand.cpp delete mode 100755 gtsam/3rdparty/Eigen/test/runtest.sh create mode 100644 gtsam/3rdparty/Eigen/test/rvalue_types.cpp create mode 100644 gtsam/3rdparty/Eigen/test/sparse_block.cpp create mode 100644 gtsam/3rdparty/Eigen/test/sparse_ref.cpp rename gtsam/3rdparty/Eigen/test/{eigen2/eigen2_newstdvector.cpp => stddeque_overload.cpp} (56%) create mode 100644 gtsam/3rdparty/Eigen/test/stdlist_overload.cpp create mode 100644 gtsam/3rdparty/Eigen/test/svd_common.h create mode 100644 gtsam/3rdparty/Eigen/test/svd_fill.h delete mode 100644 gtsam/3rdparty/Eigen/test/testsuite.cmake create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/Tensor create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/TensorSymmetry create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/ThreadPool create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/README.md create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionSycl.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRef.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReverse.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScan.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorShuffling.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStorage.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStriding.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSycl.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclConvertToDeviceExpression.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExprConstructor.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExtractAccessor.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclExtractFunctors.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclLeafCount.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclPlaceHolderExpr.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclRun.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorSyclTuple.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTraits.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorUInt128.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorVolumePatch.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/DynamicSymmetry.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/StaticSymmetry.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/Symmetry.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/EventCount.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/NonBlockingThreadPool.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/RunQueue.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/SimpleThreadPool.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadEnvironment.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadLocal.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadPoolInterface.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadYield.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/util/CXX11Meta.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/util/CXX11Workarounds.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/util/EmulateArray.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/util/EmulateCXX11Meta.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/util/MaxSizeVector.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/EulerAngles delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/SVD create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/SpecialFunctions mode change 100644 => 100755 gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/AutoDiff/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/BVH/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/EulerAngles/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/EulerAngles/EulerAngles.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/EulerAngles/EulerSystem.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/FFT/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteCholesky.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/KroneckerProduct/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/LevenbergMarquardt/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunctionAtomic.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/MoreVectorization/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/NonLinearOptimization/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/NumericalDiff/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/Polynomials/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SVD/BDCSVD.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SVD/CMakeLists.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SVD/JacobiSVD.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SVD/TODOBdcsvd.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SVD/doneInBDCSVD.txt delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/Skyline/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/BlockSparseMatrix.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SparseExtra/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsArrayAPI.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsFunctors.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsHalf.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsImpl.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsPacketMath.h create mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/SpecialFunctions/arch/CUDA/CudaSpecialFunctions.h delete mode 100644 gtsam/3rdparty/Eigen/unsupported/Eigen/src/Splines/CMakeLists.txt create mode 100644 gtsam/3rdparty/Eigen/unsupported/doc/examples/EulerAngles.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/EulerAngles.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/autodiff_scalar.cpp delete mode 100644 gtsam/3rdparty/Eigen/unsupported/test/bdcsvd.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_eventcount.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_meta.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_non_blocking_thread_pool.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_runqueue.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_argmax.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_argmax_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_assign.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_broadcast_sycl.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_broadcasting.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_cast_float16_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_casts.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_chipping.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_comparisons.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_complex_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_complex_cwise_ops_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_concatenation.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_const.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_contract_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_contraction.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_convolution.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_custom_index.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_custom_op.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_device.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_device_sycl.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_dimension.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_empty.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_expr.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_fft.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_fixed_size.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_forced_eval.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_forced_eval_sycl.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_generator.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_ifft.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_image_patch.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_index_list.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_inflation.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_intdiv.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_io.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_layout_swap.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_lvalue.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_map.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_math.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_mixed_indices.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_morphing.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_notification.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_of_complex.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_of_const_values.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_of_float16_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_of_strings.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_padding.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_patch.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_random.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_random_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_reduction.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_reduction_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_reduction_sycl.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_ref.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_reverse.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_roundings.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_scan.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_scan_cuda.cu create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_shuffling.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_simple.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_striding.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_sugar.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_sycl.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_symmetry.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_thread_pool.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_uint128.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/cxx11_tensor_volume_patch.cpp delete mode 100644 gtsam/3rdparty/Eigen/unsupported/test/jacobisvd.cpp create mode 100644 gtsam/3rdparty/Eigen/unsupported/test/special_functions.cpp delete mode 100644 gtsam/3rdparty/Eigen/unsupported/test/svd_common.h diff --git a/gtsam/3rdparty/Eigen/.hg_archival.txt b/gtsam/3rdparty/Eigen/.hg_archival.txt deleted file mode 100644 index 4dd5bd180..000000000 --- a/gtsam/3rdparty/Eigen/.hg_archival.txt +++ /dev/null @@ -1,4 +0,0 @@ -repo: 8a21fd850624c931e448cbcfb38168cb2717c790 -node: b9cd8366d4e8f49471c7afafc4c2a1b00e54a54d -branch: 3.2 -tag: 3.2.10 diff --git a/gtsam/3rdparty/Eigen/.hgeol b/gtsam/3rdparty/Eigen/.hgeol index 423676d31..5327df161 100644 --- a/gtsam/3rdparty/Eigen/.hgeol +++ b/gtsam/3rdparty/Eigen/.hgeol @@ -1,6 +1,9 @@ [patterns] +*.sh = LF +*.MINPACK = CRLF scripts/*.in = LF debug/msvc/*.dat = CRLF +debug/msvc/*.natvis = CRLF unsupported/test/mpreal/*.* = CRLF ** = native diff --git a/gtsam/3rdparty/Eigen/.hgignore b/gtsam/3rdparty/Eigen/.hgignore index e33ba2e9d..769a47f1f 100644 --- a/gtsam/3rdparty/Eigen/.hgignore +++ b/gtsam/3rdparty/Eigen/.hgignore @@ -30,3 +30,5 @@ log patch a a.* +lapack/testing +lapack/reference diff --git a/gtsam/3rdparty/Eigen/.hgtags b/gtsam/3rdparty/Eigen/.hgtags index c83128570..32ec946a2 100644 --- a/gtsam/3rdparty/Eigen/.hgtags +++ b/gtsam/3rdparty/Eigen/.hgtags @@ -21,15 +21,13 @@ a810d5dbab47acfe65b3350236efdd98f67d4d8a 3.1.0-alpha1 8383e883ebcc6f14695ff0b5e20bb631abab43fb 3.1.0-rc1 bf4cb8c934fa3a79f45f1e629610f0225e93e493 3.1.0-rc2 da195914abcc1d739027cbee7c52077aab30b336 3.2-beta1 -4b687cad1d23066f66863f4f87298447298443df 3.2-rc1 -1eeda7b1258bcd306018c0738e2b6a8543661141 3.2-rc2 -ffa86ffb557094721ca71dcea6aed2651b9fd610 3.2.0 -6b38706d90a9fe182e66ab88477b3dbde34b9f66 3.2.1 -1306d75b4a21891e59ff9bd96678882cf831e39f 3.2.2 -36fd1ba04c120cfdd90f3e4cede47f43b21d19ad 3.2.3 -10219c95fe653d4962aa9db4946f6fbea96dd740 3.2.4 -bdd17ee3b1b3a166cd5ec36dcad4fc1f3faf774a 3.2.5 -c58038c56923e0fd86de3ded18e03df442e66dfb 3.2.6 -b30b87236a1b1552af32ac34075ee5696a9b5a33 3.2.7 -07105f7124f9aef00a68c85e0fc606e65d3d6c15 3.2.8 -dc6cfdf9bcec5efc7b6593bddbbb3d675de53524 3.2.9 +a8e0d153fc5e239ef8b06e3665f1f9e8cb8d49c8 before-evaluators +09a8e21866106b49c5dec1d6d543e5794e82efa0 3.3-alpha1 +ce5a455b34c0a0ac3545a1497cb4a16c38ed90e8 3.3-beta1 +69d418c0699907bcd0bf9e0b3ba0a112ed091d85 3.3-beta2 +bef509908b9da05d0d07ffc0da105e2c8c6d3996 3.3-rc1 +04ab5fa4b241754afcf631117572276444c67239 3.3-rc2 +26667be4f70baf4f0d39e96f330714c87b399090 3.3.0 +f562a193118d4f40514e2f4a0ace6e974926ef06 3.3.1 +da9b4e14c2550e0d11078a3c39e6d56eba9905df 3.3.2 +67e894c6cd8f5f1f604b27d37ed47fdf012674ff 3.3.3 diff --git a/gtsam/3rdparty/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/CMakeLists.txt index 77e9f2d35..f5840025b 100644 --- a/gtsam/3rdparty/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/CMakeLists.txt @@ -1,4 +1,5 @@ -project(Eigen) +project(Eigen3) + cmake_minimum_required(VERSION 2.8.5) # guard against in-source builds @@ -7,6 +8,11 @@ if(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR}) message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ") endif() +# Alias Eigen_*_DIR to Eigen3_*_DIR: + +set(Eigen_SOURCE_DIR ${Eigen3_SOURCE_DIR}) +set(Eigen_BINARY_DIR ${Eigen3_BINARY_DIR}) + # guard against bad build-type strings if (NOT CMAKE_BUILD_TYPE) @@ -92,9 +98,11 @@ else() endif() option(EIGEN_BUILD_BTL "Build benchmark suite" OFF) -if(NOT WIN32) + +# Disable pkgconfig only for native Windows builds +if(NOT WIN32 OR NOT CMAKE_HOST_SYSTEM_NAME MATCHES Windows) option(EIGEN_BUILD_PKGCONFIG "Build pkg-config .pc file for Eigen" ON) -endif(NOT WIN32) +endif() set(CMAKE_INCLUDE_CURRENT_DIR ON) @@ -108,7 +116,8 @@ endif() set(EIGEN_TEST_MAX_SIZE "320" CACHE STRING "Maximal matrix/vector size, default is 320") macro(ei_add_cxx_compiler_flag FLAG) - string(REGEX REPLACE "-" "" SFLAG ${FLAG}) + string(REGEX REPLACE "-" "" SFLAG1 ${FLAG}) + string(REGEX REPLACE "\\+" "p" SFLAG ${SFLAG1}) check_cxx_compiler_flag(${FLAG} COMPILER_SUPPORT_${SFLAG}) if(COMPILER_SUPPORT_${SFLAG}) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${FLAG}") @@ -117,18 +126,13 @@ endmacro(ei_add_cxx_compiler_flag) if(NOT MSVC) # We assume that other compilers are partly compatible with GNUCC - - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fexceptions") - set(CMAKE_CXX_FLAGS_DEBUG "-g3") - set(CMAKE_CXX_FLAGS_RELEASE "-g0 -O2") - - # clang outputs some warnings for unknwon flags that are not caught by check_cxx_compiler_flag + + # clang outputs some warnings for unknown flags that are not caught by check_cxx_compiler_flag # adding -Werror turns such warnings into errors check_cxx_compiler_flag("-Werror" COMPILER_SUPPORT_WERROR) if(COMPILER_SUPPORT_WERROR) set(CMAKE_REQUIRED_FLAGS "-Werror") endif() - ei_add_cxx_compiler_flag("-pedantic") ei_add_cxx_compiler_flag("-Wall") ei_add_cxx_compiler_flag("-Wextra") @@ -142,6 +146,18 @@ if(NOT MSVC) ei_add_cxx_compiler_flag("-Wpointer-arith") ei_add_cxx_compiler_flag("-Wwrite-strings") ei_add_cxx_compiler_flag("-Wformat-security") + ei_add_cxx_compiler_flag("-Wshorten-64-to-32") + ei_add_cxx_compiler_flag("-Wlogical-op") + ei_add_cxx_compiler_flag("-Wenum-conversion") + ei_add_cxx_compiler_flag("-Wc++11-extensions") + ei_add_cxx_compiler_flag("-Wdouble-promotion") +# ei_add_cxx_compiler_flag("-Wconversion") + + # -Wshadow is insanely too strict with gcc, hopefully it will become usable with gcc 6 + # if(NOT CMAKE_COMPILER_IS_GNUCXX OR (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER "5.0.0")) + if(NOT CMAKE_COMPILER_IS_GNUCXX) + ei_add_cxx_compiler_flag("-Wshadow") + endif() ei_add_cxx_compiler_flag("-Wno-psabi") ei_add_cxx_compiler_flag("-Wno-variadic-macros") @@ -151,7 +167,8 @@ if(NOT MSVC) ei_add_cxx_compiler_flag("-fno-common") ei_add_cxx_compiler_flag("-fstrict-aliasing") ei_add_cxx_compiler_flag("-wd981") # disable ICC's "operands are evaluated in unspecified order" remark - ei_add_cxx_compiler_flag("-wd2304") # disbale ICC's "warning #2304: non-explicit constructor with single argument may cause implicit type conversion" produced by -Wnon-virtual-dtor + ei_add_cxx_compiler_flag("-wd2304") # disable ICC's "warning #2304: non-explicit constructor with single argument may cause implicit type conversion" produced by -Wnon-virtual-dtor + # The -ansi flag must be added last, otherwise it is also used as a linker flag by check_cxx_compiler_flag making it fails # Moreover we should not set both -strict-ansi and -ansi @@ -163,6 +180,11 @@ if(NOT MSVC) else() ei_add_cxx_compiler_flag("-ansi") endif() + + if(ANDROID_NDK) + ei_add_cxx_compiler_flag("-pie") + ei_add_cxx_compiler_flag("-fPIE") + endif() set(CMAKE_REQUIRED_FLAGS "") @@ -196,18 +218,65 @@ if(NOT MSVC) message(STATUS "Enabling SSE4.2 in tests/examples") endif() + option(EIGEN_TEST_AVX "Enable/Disable AVX in tests/examples" OFF) + if(EIGEN_TEST_AVX) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mavx") + message(STATUS "Enabling AVX in tests/examples") + endif() + + option(EIGEN_TEST_FMA "Enable/Disable FMA in tests/examples" OFF) + if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfma") + message(STATUS "Enabling FMA in tests/examples") + endif() + + option(EIGEN_TEST_AVX512 "Enable/Disable AVX512 in tests/examples" OFF) + if(EIGEN_TEST_AVX512) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mavx512f -fabi-version=6 -DEIGEN_ENABLE_AVX512") + message(STATUS "Enabling AVX512 in tests/examples") + endif() + + option(EIGEN_TEST_F16C "Enable/Disable F16C in tests/examples" OFF) + if(EIGEN_TEST_F16C) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mf16c") + message(STATUS "Enabling F16C in tests/examples") + endif() + option(EIGEN_TEST_ALTIVEC "Enable/Disable AltiVec in tests/examples" OFF) if(EIGEN_TEST_ALTIVEC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -maltivec -mabi=altivec") message(STATUS "Enabling AltiVec in tests/examples") endif() + option(EIGEN_TEST_VSX "Enable/Disable VSX in tests/examples" OFF) + if(EIGEN_TEST_VSX) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -m64 -mvsx") + message(STATUS "Enabling VSX in tests/examples") + endif() + option(EIGEN_TEST_NEON "Enable/Disable Neon in tests/examples" OFF) if(EIGEN_TEST_NEON) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon -mcpu=cortex-a8") + if(EIGEN_TEST_FMA) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon-vfpv4") + else() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfpu=neon") + endif() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -mfloat-abi=hard") message(STATUS "Enabling NEON in tests/examples") endif() + option(EIGEN_TEST_NEON64 "Enable/Disable Neon in tests/examples" OFF) + if(EIGEN_TEST_NEON64) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") + message(STATUS "Enabling NEON in tests/examples") + endif() + + option(EIGEN_TEST_ZVECTOR "Enable/Disable S390X(zEC13) ZVECTOR in tests/examples" OFF) + if(EIGEN_TEST_ZVECTOR) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -march=z13 -mzvector") + message(STATUS "Enabling S390X(zEC13) ZVECTOR in tests/examples") + endif() + check_cxx_compiler_flag("-fopenmp" COMPILER_SUPPORT_OPENMP) if(COMPILER_SUPPORT_OPENMP) option(EIGEN_TEST_OPENMP "Enable/Disable OpenMP in tests/examples" OFF) @@ -284,11 +353,23 @@ if(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT) message(STATUS "Disabling alignment in tests/examples") endif() -option(EIGEN_TEST_C++0x "Enables all C++0x features." OFF) +option(EIGEN_TEST_NO_EXCEPTIONS "Disables C++ exceptions" OFF) +if(EIGEN_TEST_NO_EXCEPTIONS) + ei_add_cxx_compiler_flag("-fno-exceptions") + message(STATUS "Disabling exceptions in tests/examples") +endif() + +option(EIGEN_TEST_CXX11 "Enable testing with C++11 and C++11 features (e.g. Tensor module)." OFF) + +set(EIGEN_CUDA_COMPUTE_ARCH 30 CACHE STRING "The CUDA compute architecture level to target when compiling CUDA code") include_directories(${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_BINARY_DIR}) # Backward compatibility support for EIGEN_INCLUDE_INSTALL_DIR +if(EIGEN_INCLUDE_INSTALL_DIR) + message(WARNING "EIGEN_INCLUDE_INSTALL_DIR is deprecated. Use INCLUDE_INSTALL_DIR instead.") +endif() + if(EIGEN_INCLUDE_INSTALL_DIR AND NOT INCLUDE_INSTALL_DIR) set(INCLUDE_INSTALL_DIR ${EIGEN_INCLUDE_INSTALL_DIR} CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed") @@ -298,9 +379,8 @@ else() CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed" ) endif() - set(CMAKEPACKAGE_INSTALL_DIR - "${CMAKE_INSTALL_LIBDIR}/cmake/eigen3" + "${CMAKE_INSTALL_DATADIR}/eigen3/cmake" CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where Eigen3Config.cmake is installed" ) set(PKGCONFIG_INSTALL_DIR @@ -308,6 +388,7 @@ set(PKGCONFIG_INSTALL_DIR CACHE PATH "The directory relative to CMAKE_PREFIX_PATH where eigen3.pc is installed" ) + # similar to set_target_properties but append the property instead of overwriting it macro(ei_add_target_property target prop value) @@ -329,7 +410,7 @@ if(EIGEN_BUILD_PKGCONFIG) install(FILES ${CMAKE_CURRENT_BINARY_DIR}/eigen3.pc DESTINATION ${PKGCONFIG_INSTALL_DIR} ) -endif(EIGEN_BUILD_PKGCONFIG) +endif() add_subdirectory(Eigen) @@ -355,6 +436,13 @@ else() add_subdirectory(lapack EXCLUDE_FROM_ALL) endif() +# add SYCL +option(EIGEN_TEST_SYCL "Add Sycl support." OFF) +if(EIGEN_TEST_SYCL) + set (CMAKE_MODULE_PATH "${CMAKE_ROOT}/Modules" "cmake/Modules/" "${CMAKE_MODULE_PATH}") + include(FindComputeCpp) +endif() + add_subdirectory(unsupported) add_subdirectory(demos EXCLUDE_FROM_ALL) @@ -403,6 +491,7 @@ if(cmake_generator_tolower MATCHES "makefile") message(STATUS "make check | Build and run the unit-tests. Read this page:") message(STATUS " | http://eigen.tuxfamily.org/index.php?title=Tests") message(STATUS "make blas | Build BLAS library (not the same thing as Eigen)") + message(STATUS "make uninstall| Removes files installed by make install") message(STATUS "--------------+--------------------------------------------------------------") else() message(STATUS "To build/run the unit tests, read this page:") @@ -410,3 +499,98 @@ else() endif() message(STATUS "") + + +set ( EIGEN_VERSION_STRING ${EIGEN_VERSION_NUMBER} ) +set ( EIGEN_VERSION_MAJOR ${EIGEN_WORLD_VERSION} ) +set ( EIGEN_VERSION_MINOR ${EIGEN_MAJOR_VERSION} ) +set ( EIGEN_VERSION_PATCH ${EIGEN_MINOR_VERSION} ) +set ( EIGEN_DEFINITIONS "") +set ( EIGEN_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/${INCLUDE_INSTALL_DIR}" ) +set ( EIGEN_ROOT_DIR ${CMAKE_INSTALL_PREFIX} ) + +# Interface libraries require at least CMake 3.0 +if (NOT CMAKE_VERSION VERSION_LESS 3.0) + include (CMakePackageConfigHelpers) + + # Imported target support + add_library (eigen INTERFACE) + + target_compile_definitions (eigen INTERFACE ${EIGEN_DEFINITIONS}) + target_include_directories (eigen INTERFACE + $ + $ + ) + + # Export as title case Eigen + set_target_properties (eigen PROPERTIES EXPORT_NAME Eigen) + + install (TARGETS eigen EXPORT Eigen3Targets) + + configure_package_config_file ( + ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3Config.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + PATH_VARS EIGEN_INCLUDE_DIR EIGEN_ROOT_DIR + INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} + NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components + ) + # Remove CMAKE_SIZEOF_VOID_P from Eigen3ConfigVersion.cmake since Eigen does + # not depend on architecture specific settings or libraries. More + # specifically, an Eigen3Config.cmake generated from a 64 bit target can be + # used for 32 bit targets as well (and vice versa). + set (_Eigen3_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P}) + unset (CMAKE_SIZEOF_VOID_P) + write_basic_package_version_file (Eigen3ConfigVersion.cmake + VERSION ${EIGEN_VERSION_NUMBER} + COMPATIBILITY SameMajorVersion) + set (CMAKE_SIZEOF_VOID_P ${_Eigen3_CMAKE_SIZEOF_VOID_P}) + + # The Eigen target will be located in the Eigen3 namespace. Other CMake + # targets can refer to it using Eigen3::Eigen. + export (TARGETS eigen NAMESPACE Eigen3:: FILE Eigen3Targets.cmake) + # Export Eigen3 package to CMake registry such that it can be easily found by + # CMake even if it has not been installed to a standard directory. + export (PACKAGE Eigen3) + + install (EXPORT Eigen3Targets NAMESPACE Eigen3:: DESTINATION ${CMAKEPACKAGE_INSTALL_DIR}) + +else (NOT CMAKE_VERSION VERSION_LESS 3.0) + # Fallback to legacy Eigen3Config.cmake without the imported target + + # If CMakePackageConfigHelpers module is available (CMake >= 2.8.8) + # create a relocatable Config file, otherwise leave the hardcoded paths + include(CMakePackageConfigHelpers OPTIONAL RESULT_VARIABLE CPCH_PATH) + + if(CPCH_PATH) + configure_package_config_file ( + ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3ConfigLegacy.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + PATH_VARS EIGEN_INCLUDE_DIR EIGEN_ROOT_DIR + INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} + NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components + ) + else() + # The PACKAGE_* variables are defined by the configure_package_config_file + # but without it we define them manually to the hardcoded paths + set(PACKAGE_INIT "") + set(PACKAGE_EIGEN_INCLUDE_DIR ${EIGEN_INCLUDE_DIR}) + set(PACKAGE_EIGEN_ROOT_DIR ${EIGEN_ROOT_DIR}) + configure_file ( ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3ConfigLegacy.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + @ONLY ESCAPE_QUOTES ) + endif() + + write_basic_package_version_file( Eigen3ConfigVersion.cmake + VERSION ${EIGEN_VERSION_NUMBER} + COMPATIBILITY SameMajorVersion ) + +endif (NOT CMAKE_VERSION VERSION_LESS 3.0) + +install ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/cmake/UseEigen3.cmake + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake + ${CMAKE_CURRENT_BINARY_DIR}/Eigen3ConfigVersion.cmake + DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} ) + +# Add uninstall target +add_custom_target ( uninstall + COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_SOURCE_DIR}/cmake/EigenUninstall.cmake) diff --git a/gtsam/3rdparty/Eigen/CTestConfig.cmake b/gtsam/3rdparty/Eigen/CTestConfig.cmake index 0557c491a..755b47323 100644 --- a/gtsam/3rdparty/Eigen/CTestConfig.cmake +++ b/gtsam/3rdparty/Eigen/CTestConfig.cmake @@ -4,10 +4,10 @@ ## # The following are required to uses Dart and the Cdash dashboard ## ENABLE_TESTING() ## INCLUDE(CTest) -set(CTEST_PROJECT_NAME "Eigen3.2") +set(CTEST_PROJECT_NAME "Eigen3.3") set(CTEST_NIGHTLY_START_TIME "00:00:00 UTC") set(CTEST_DROP_METHOD "http") set(CTEST_DROP_SITE "manao.inria.fr") -set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen3.2") +set(CTEST_DROP_LOCATION "/CDash/submit.php?project=Eigen3.3") set(CTEST_DROP_SITE_CDASH TRUE) diff --git a/gtsam/3rdparty/Eigen/Eigen/Array b/gtsam/3rdparty/Eigen/Eigen/Array deleted file mode 100644 index 3d004fb69..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/Array +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef EIGEN_ARRAY_MODULE_H -#define EIGEN_ARRAY_MODULE_H - -// include Core first to handle Eigen2 support macros -#include "Core" - -#ifndef EIGEN2_SUPPORT - #error The Eigen/Array header does no longer exist in Eigen3. All that functionality has moved to Eigen/Core. -#endif - -#endif // EIGEN_ARRAY_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/CMakeLists.txt index a92dd6f6c..9eb502b79 100644 --- a/gtsam/3rdparty/Eigen/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/Eigen/CMakeLists.txt @@ -16,4 +16,4 @@ install(FILES DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel ) -add_subdirectory(src) +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen COMPONENT Devel FILES_MATCHING PATTERN "*.h") diff --git a/gtsam/3rdparty/Eigen/Eigen/Cholesky b/gtsam/3rdparty/Eigen/Eigen/Cholesky index f727f5d89..369d1f5ec 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Cholesky +++ b/gtsam/3rdparty/Eigen/Eigen/Cholesky @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_CHOLESKY_MODULE_H #define EIGEN_CHOLESKY_MODULE_H @@ -10,20 +17,22 @@ * * * This module provides two variants of the Cholesky decomposition for selfadjoint (hermitian) matrices. - * Those decompositions are accessible via the following MatrixBase methods: - * - MatrixBase::llt(), + * Those decompositions are also accessible via the following methods: + * - MatrixBase::llt() * - MatrixBase::ldlt() + * - SelfAdjointView::llt() + * - SelfAdjointView::ldlt() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" #include "src/Cholesky/LLT.h" #include "src/Cholesky/LDLT.h" #ifdef EIGEN_USE_LAPACKE -#include "src/Cholesky/LLT_MKL.h" +#include "src/misc/lapacke.h" +#include "src/Cholesky/LLT_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/CholmodSupport b/gtsam/3rdparty/Eigen/Eigen/CholmodSupport index 88c29a646..bed8924d3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/CholmodSupport +++ b/gtsam/3rdparty/Eigen/Eigen/CholmodSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_CHOLMODSUPPORT_MODULE_H #define EIGEN_CHOLMODSUPPORT_MODULE_H @@ -33,12 +40,8 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/CholmodSupport/CholmodSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_CHOLMODSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Core b/gtsam/3rdparty/Eigen/Eigen/Core index 509c529e1..0f7fa630d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Core +++ b/gtsam/3rdparty/Eigen/Eigen/Core @@ -14,6 +14,58 @@ // first thing Eigen does: stop the compiler from committing suicide #include "src/Core/util/DisableStupidWarnings.h" +// Handle NVCC/CUDA/SYCL +#if defined(__CUDACC__) || defined(__SYCL_DEVICE_ONLY__) + // Do not try asserts on CUDA and SYCL! + #ifndef EIGEN_NO_DEBUG + #define EIGEN_NO_DEBUG + #endif + + #ifdef EIGEN_INTERNAL_DEBUGGING + #undef EIGEN_INTERNAL_DEBUGGING + #endif + + #ifdef EIGEN_EXCEPTIONS + #undef EIGEN_EXCEPTIONS + #endif + + // All functions callable from CUDA code must be qualified with __device__ + #ifdef __CUDACC__ + // Do not try to vectorize on CUDA and SYCL! + #ifndef EIGEN_DONT_VECTORIZE + #define EIGEN_DONT_VECTORIZE + #endif + + #define EIGEN_DEVICE_FUNC __host__ __device__ + // We need math_functions.hpp to ensure that that EIGEN_USING_STD_MATH macro + // works properly on the device side + #include + #else + #define EIGEN_DEVICE_FUNC + #endif + +#else + #define EIGEN_DEVICE_FUNC + +#endif + +// When compiling CUDA device code with NVCC, pull in math functions from the +// global namespace. In host mode, and when device doee with clang, use the +// std versions. +#if defined(__CUDA_ARCH__) && defined(__NVCC__) + #define EIGEN_USING_STD_MATH(FUNC) using ::FUNC; +#else + #define EIGEN_USING_STD_MATH(FUNC) using std::FUNC; +#endif + +#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) && !defined(EIGEN_EXCEPTIONS) && !defined(EIGEN_USE_SYCL) + #define EIGEN_EXCEPTIONS +#endif + +#ifdef EIGEN_EXCEPTIONS + #include +#endif + // then include this file where all our macros are defined. It's really important to do it first because // it's where we do all the alignment settings (platform detection and honoring the user's will if he // defined e.g. EIGEN_DONT_ALIGN) so it needs to be done before we do anything with vectorization. @@ -21,7 +73,7 @@ // Disable the ipa-cp-clone optimization flag with MinGW 6.x or newer (enabled by default with -O3) // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=556 for details. -#if defined(__MINGW32__) && EIGEN_GNUC_AT_LEAST(4,6) +#if EIGEN_COMP_MINGW && EIGEN_GNUC_AT_LEAST(4,6) #pragma GCC optimize ("-fno-ipa-cp-clone") #endif @@ -31,26 +83,26 @@ // and inclusion of their respective header files #include "src/Core/util/MKL_support.h" -// if alignment is disabled, then disable vectorization. Note: EIGEN_ALIGN is the proper check, it takes into -// account both the user's will (EIGEN_DONT_ALIGN) and our own platform checks -#if !EIGEN_ALIGN +// if alignment is disabled, then disable vectorization. Note: EIGEN_MAX_ALIGN_BYTES is the proper check, it takes into +// account both the user's will (EIGEN_MAX_ALIGN_BYTES,EIGEN_DONT_ALIGN) and our own platform checks +#if EIGEN_MAX_ALIGN_BYTES==0 #ifndef EIGEN_DONT_VECTORIZE #define EIGEN_DONT_VECTORIZE #endif #endif -#ifdef _MSC_VER +#if EIGEN_COMP_MSVC #include // for _aligned_malloc -- need it regardless of whether vectorization is enabled - #if (_MSC_VER >= 1500) // 2008 or later + #if (EIGEN_COMP_MSVC >= 1500) // 2008 or later // Remember that usage of defined() in a #define is undefined by the standard. // a user reported that in 64-bit mode, MSVC doesn't care to define _M_IX86_FP. - #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || defined(_M_X64) + #if (defined(_M_IX86_FP) && (_M_IX86_FP >= 2)) || EIGEN_ARCH_x86_64 #define EIGEN_SSE2_ON_MSVC_2008_OR_LATER #endif #endif #else // Remember that usage of defined() in a #define is undefined by the standard - #if (defined __SSE2__) && ( (!defined __GNUC__) || (defined __INTEL_COMPILER) || EIGEN_GNUC_AT_LEAST(4,2) ) + #if (defined __SSE2__) && ( (!EIGEN_COMP_GNUC) || EIGEN_COMP_ICC || EIGEN_GNUC_AT_LEAST(4,2) ) #define EIGEN_SSE2_ON_NON_MSVC_BUT_NOT_OLD_GCC #endif #endif @@ -82,6 +134,28 @@ #ifdef __SSE4_2__ #define EIGEN_VECTORIZE_SSE4_2 #endif + #ifdef __AVX__ + #define EIGEN_VECTORIZE_AVX + #define EIGEN_VECTORIZE_SSE3 + #define EIGEN_VECTORIZE_SSSE3 + #define EIGEN_VECTORIZE_SSE4_1 + #define EIGEN_VECTORIZE_SSE4_2 + #endif + #ifdef __AVX2__ + #define EIGEN_VECTORIZE_AVX2 + #endif + #ifdef __FMA__ + #define EIGEN_VECTORIZE_FMA + #endif + #if defined(__AVX512F__) && defined(EIGEN_ENABLE_AVX512) + #define EIGEN_VECTORIZE_AVX512 + #define EIGEN_VECTORIZE_AVX2 + #define EIGEN_VECTORIZE_AVX + #define EIGEN_VECTORIZE_FMA + #ifdef __AVX512DQ__ + #define EIGEN_VECTORIZE_AVX512DQ + #endif + #endif // include files @@ -95,9 +169,10 @@ extern "C" { // In theory we should only include immintrin.h and not the other *mmintrin.h header files directly. // Doing so triggers some issues with ICC. However old gcc versions seems to not have this file, thus: - #if defined(__INTEL_COMPILER) && __INTEL_COMPILER >= 1110 + #if EIGEN_COMP_ICC >= 1110 #include #else + #include #include #include #ifdef EIGEN_VECTORIZE_SSE3 @@ -112,8 +187,20 @@ #ifdef EIGEN_VECTORIZE_SSE4_2 #include #endif + #if defined(EIGEN_VECTORIZE_AVX) || defined(EIGEN_VECTORIZE_AVX512) + #include + #endif #endif } // end extern "C" + #elif defined __VSX__ + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_VSX + #include + // We need to #undef all these ugly tokens defined in + // => use __vector instead of vector + #undef bool + #undef vector + #undef pixel #elif defined __ALTIVEC__ #define EIGEN_VECTORIZE #define EIGEN_VECTORIZE_ALTIVEC @@ -123,13 +210,35 @@ #undef bool #undef vector #undef pixel - #elif defined __ARM_NEON + #elif (defined __ARM_NEON) || (defined __ARM_NEON__) #define EIGEN_VECTORIZE #define EIGEN_VECTORIZE_NEON #include + #elif (defined __s390x__ && defined __VEC__) + #define EIGEN_VECTORIZE + #define EIGEN_VECTORIZE_ZVECTOR + #include #endif #endif +#if defined(__F16C__) && !defined(EIGEN_COMP_CLANG) + // We can use the optimized fp16 to float and float to fp16 conversion routines + #define EIGEN_HAS_FP16_C +#endif + +#if defined __CUDACC__ + #define EIGEN_VECTORIZE_CUDA + #include + #if defined __CUDACC_VER__ && __CUDACC_VER__ >= 70500 + #define EIGEN_HAS_CUDA_FP16 + #endif +#endif + +#if defined EIGEN_HAS_CUDA_FP16 + #include + #include +#endif + #if (defined _OPENMP) && (!defined EIGEN_DONT_PARALLELIZE) #define EIGEN_HAS_OPENMP #endif @@ -139,7 +248,7 @@ #endif // MSVC for windows mobile does not have the errno.h file -#if !(defined(_MSC_VER) && defined(_WIN32_WCE)) && !defined(__ARMCC_VERSION) +#if !(EIGEN_COMP_MSVC && EIGEN_OS_WINCE) && !EIGEN_COMP_ARM #define EIGEN_HAS_ERRNO #endif @@ -159,29 +268,30 @@ // for min/max: #include +// for std::is_nothrow_move_assignable +#ifdef EIGEN_INCLUDE_TYPE_TRAITS +#include +#endif + // for outputting debug info #ifdef EIGEN_DEBUG_ASSIGN #include #endif // required for __cpuid, needs to be included after cmath -#if defined(_MSC_VER) && (defined(_M_IX86)||defined(_M_X64)) && (!defined(_WIN32_WCE)) +#if EIGEN_COMP_MSVC && EIGEN_ARCH_i386_OR_x86_64 && !EIGEN_OS_WINCE #include #endif -#if defined(_CPPUNWIND) || defined(__EXCEPTIONS) - #define EIGEN_EXCEPTIONS -#endif - -#ifdef EIGEN_EXCEPTIONS - #include -#endif - /** \brief Namespace containing all symbols from the %Eigen library. */ namespace Eigen { inline static const char *SimdInstructionSetsInUse(void) { -#if defined(EIGEN_VECTORIZE_SSE4_2) +#if defined(EIGEN_VECTORIZE_AVX512) + return "AVX512, FMA, AVX2, AVX, SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_AVX) + return "AVX SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; +#elif defined(EIGEN_VECTORIZE_SSE4_2) return "SSE, SSE2, SSE3, SSSE3, SSE4.1, SSE4.2"; #elif defined(EIGEN_VECTORIZE_SSE4_1) return "SSE, SSE2, SSE3, SSSE3, SSE4.1"; @@ -193,8 +303,12 @@ inline static const char *SimdInstructionSetsInUse(void) { return "SSE, SSE2"; #elif defined(EIGEN_VECTORIZE_ALTIVEC) return "AltiVec"; +#elif defined(EIGEN_VECTORIZE_VSX) + return "VSX"; #elif defined(EIGEN_VECTORIZE_NEON) return "ARM NEON"; +#elif defined(EIGEN_VECTORIZE_ZVECTOR) + return "S390X ZVECTOR"; #else return "None"; #endif @@ -202,42 +316,21 @@ inline static const char *SimdInstructionSetsInUse(void) { } // end namespace Eigen -#define STAGE10_FULL_EIGEN2_API 10 -#define STAGE20_RESOLVE_API_CONFLICTS 20 -#define STAGE30_FULL_EIGEN3_API 30 -#define STAGE40_FULL_EIGEN3_STRICTNESS 40 -#define STAGE99_NO_EIGEN2_SUPPORT 99 - -#if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE40_FULL_EIGEN3_STRICTNESS -#elif defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API -#elif defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE20_RESOLVE_API_CONFLICTS -#elif defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API - #define EIGEN2_SUPPORT - #define EIGEN2_SUPPORT_STAGE STAGE10_FULL_EIGEN2_API -#elif defined EIGEN2_SUPPORT - // default to stage 3, that's what it's always meant - #define EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API - #define EIGEN2_SUPPORT_STAGE STAGE30_FULL_EIGEN3_API -#else - #define EIGEN2_SUPPORT_STAGE STAGE99_NO_EIGEN2_SUPPORT +#if defined EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS || defined EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API || defined EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS || defined EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API || defined EIGEN2_SUPPORT +// This will generate an error message: +#error Eigen2-support is only available up to version 3.2. Please go to "http://eigen.tuxfamily.org/index.php?title=Eigen2" for further information #endif -#ifdef EIGEN2_SUPPORT -#undef minor -#endif +namespace Eigen { // we use size_t frequently and we'll never remember to prepend it with std:: everytime just to // ensure QNX/QCC support using std::size_t; -// gcc 4.6.0 wants std:: for ptrdiff_t +// gcc 4.6.0 wants std:: for ptrdiff_t using std::ptrdiff_t; +} + /** \defgroup Core_Module Core module * This is the main module of Eigen providing dense matrix and vector support * (both fixed and dynamic size) with all the features corresponding to a BLAS library @@ -249,8 +342,8 @@ using std::ptrdiff_t; */ #include "src/Core/util/Constants.h" -#include "src/Core/util/ForwardDeclarations.h" #include "src/Core/util/Meta.h" +#include "src/Core/util/ForwardDeclarations.h" #include "src/Core/util/StaticAssert.h" #include "src/Core/util/XprHelper.h" #include "src/Core/util/Memory.h" @@ -258,41 +351,92 @@ using std::ptrdiff_t; #include "src/Core/NumTraits.h" #include "src/Core/MathFunctions.h" #include "src/Core/GenericPacketMath.h" +#include "src/Core/MathFunctionsImpl.h" -#if defined EIGEN_VECTORIZE_SSE +#if defined EIGEN_VECTORIZE_AVX512 + #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/AVX/PacketMath.h" + #include "src/Core/arch/AVX512/PacketMath.h" + #include "src/Core/arch/AVX512/MathFunctions.h" +#elif defined EIGEN_VECTORIZE_AVX + // Use AVX for floats and doubles, SSE for integers + #include "src/Core/arch/SSE/PacketMath.h" + #include "src/Core/arch/SSE/Complex.h" + #include "src/Core/arch/SSE/MathFunctions.h" + #include "src/Core/arch/AVX/PacketMath.h" + #include "src/Core/arch/AVX/MathFunctions.h" + #include "src/Core/arch/AVX/Complex.h" + #include "src/Core/arch/AVX/TypeCasting.h" +#elif defined EIGEN_VECTORIZE_SSE #include "src/Core/arch/SSE/PacketMath.h" #include "src/Core/arch/SSE/MathFunctions.h" #include "src/Core/arch/SSE/Complex.h" -#elif defined EIGEN_VECTORIZE_ALTIVEC + #include "src/Core/arch/SSE/TypeCasting.h" +#elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) #include "src/Core/arch/AltiVec/PacketMath.h" + #include "src/Core/arch/AltiVec/MathFunctions.h" #include "src/Core/arch/AltiVec/Complex.h" #elif defined EIGEN_VECTORIZE_NEON #include "src/Core/arch/NEON/PacketMath.h" + #include "src/Core/arch/NEON/MathFunctions.h" #include "src/Core/arch/NEON/Complex.h" +#elif defined EIGEN_VECTORIZE_ZVECTOR + #include "src/Core/arch/ZVector/PacketMath.h" + #include "src/Core/arch/ZVector/MathFunctions.h" + #include "src/Core/arch/ZVector/Complex.h" +#endif + +// Half float support +#include "src/Core/arch/CUDA/Half.h" +#include "src/Core/arch/CUDA/PacketMathHalf.h" +#include "src/Core/arch/CUDA/TypeCasting.h" + +#if defined EIGEN_VECTORIZE_CUDA + #include "src/Core/arch/CUDA/PacketMath.h" + #include "src/Core/arch/CUDA/MathFunctions.h" #endif #include "src/Core/arch/Default/Settings.h" -#include "src/Core/Functors.h" +#include "src/Core/functors/TernaryFunctors.h" +#include "src/Core/functors/BinaryFunctors.h" +#include "src/Core/functors/UnaryFunctors.h" +#include "src/Core/functors/NullaryFunctors.h" +#include "src/Core/functors/StlFunctors.h" +#include "src/Core/functors/AssignmentFunctors.h" + +// Specialized functors to enable the processing of complex numbers +// on CUDA devices +#include "src/Core/arch/CUDA/Complex.h" + +#include "src/Core/IO.h" #include "src/Core/DenseCoeffsBase.h" #include "src/Core/DenseBase.h" #include "src/Core/MatrixBase.h" #include "src/Core/EigenBase.h" +#include "src/Core/Product.h" +#include "src/Core/CoreEvaluators.h" +#include "src/Core/AssignEvaluator.h" + #ifndef EIGEN_PARSED_BY_DOXYGEN // work around Doxygen bug triggered by Assign.h r814874 // at least confirmed with Doxygen 1.5.5 and 1.5.6 #include "src/Core/Assign.h" #endif +#include "src/Core/ArrayBase.h" #include "src/Core/util/BlasUtil.h" #include "src/Core/DenseStorage.h" #include "src/Core/NestByValue.h" -#include "src/Core/ForceAlignedAccess.h" + +// #include "src/Core/ForceAlignedAccess.h" + #include "src/Core/ReturnByValue.h" #include "src/Core/NoAlias.h" #include "src/Core/PlainObjectBase.h" #include "src/Core/Matrix.h" #include "src/Core/Array.h" +#include "src/Core/CwiseTernaryOp.h" #include "src/Core/CwiseBinaryOp.h" #include "src/Core/CwiseUnaryOp.h" #include "src/Core/CwiseNullaryOp.h" @@ -300,32 +444,32 @@ using std::ptrdiff_t; #include "src/Core/SelfCwiseBinaryOp.h" #include "src/Core/Dot.h" #include "src/Core/StableNorm.h" -#include "src/Core/MapBase.h" #include "src/Core/Stride.h" +#include "src/Core/MapBase.h" #include "src/Core/Map.h" +#include "src/Core/Ref.h" #include "src/Core/Block.h" #include "src/Core/VectorBlock.h" -#include "src/Core/Ref.h" #include "src/Core/Transpose.h" #include "src/Core/DiagonalMatrix.h" #include "src/Core/Diagonal.h" #include "src/Core/DiagonalProduct.h" -#include "src/Core/PermutationMatrix.h" -#include "src/Core/Transpositions.h" #include "src/Core/Redux.h" #include "src/Core/Visitor.h" #include "src/Core/Fuzzy.h" -#include "src/Core/IO.h" #include "src/Core/Swap.h" #include "src/Core/CommaInitializer.h" -#include "src/Core/Flagged.h" -#include "src/Core/ProductBase.h" #include "src/Core/GeneralProduct.h" +#include "src/Core/Solve.h" +#include "src/Core/Inverse.h" +#include "src/Core/SolverBase.h" +#include "src/Core/PermutationMatrix.h" +#include "src/Core/Transpositions.h" #include "src/Core/TriangularMatrix.h" #include "src/Core/SelfAdjointView.h" #include "src/Core/products/GeneralBlockPanelKernel.h" #include "src/Core/products/Parallelizer.h" -#include "src/Core/products/CoeffBasedProduct.h" +#include "src/Core/ProductEvaluators.h" #include "src/Core/products/GeneralMatrixVector.h" #include "src/Core/products/GeneralMatrixMatrix.h" #include "src/Core/SolveTriangular.h" @@ -340,6 +484,7 @@ using std::ptrdiff_t; #include "src/Core/products/TriangularSolverVector.h" #include "src/Core/BandMatrix.h" #include "src/Core/CoreIterators.h" +#include "src/Core/ConditionEstimator.h" #include "src/Core/BooleanRedux.h" #include "src/Core/Select.h" @@ -347,18 +492,17 @@ using std::ptrdiff_t; #include "src/Core/Random.h" #include "src/Core/Replicate.h" #include "src/Core/Reverse.h" -#include "src/Core/ArrayBase.h" #include "src/Core/ArrayWrapper.h" #ifdef EIGEN_USE_BLAS -#include "src/Core/products/GeneralMatrixMatrix_MKL.h" -#include "src/Core/products/GeneralMatrixVector_MKL.h" -#include "src/Core/products/GeneralMatrixMatrixTriangular_MKL.h" -#include "src/Core/products/SelfadjointMatrixMatrix_MKL.h" -#include "src/Core/products/SelfadjointMatrixVector_MKL.h" -#include "src/Core/products/TriangularMatrixMatrix_MKL.h" -#include "src/Core/products/TriangularMatrixVector_MKL.h" -#include "src/Core/products/TriangularSolverMatrix_MKL.h" +#include "src/Core/products/GeneralMatrixMatrix_BLAS.h" +#include "src/Core/products/GeneralMatrixVector_BLAS.h" +#include "src/Core/products/GeneralMatrixMatrixTriangular_BLAS.h" +#include "src/Core/products/SelfadjointMatrixMatrix_BLAS.h" +#include "src/Core/products/SelfadjointMatrixVector_BLAS.h" +#include "src/Core/products/TriangularMatrixMatrix_BLAS.h" +#include "src/Core/products/TriangularMatrixVector_BLAS.h" +#include "src/Core/products/TriangularSolverMatrix_BLAS.h" #endif // EIGEN_USE_BLAS #ifdef EIGEN_USE_MKL_VML @@ -369,8 +513,4 @@ using std::ptrdiff_t; #include "src/Core/util/ReenableStupidWarnings.h" -#ifdef EIGEN2_SUPPORT -#include "Eigen2Support" -#endif - #endif // EIGEN_CORE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Eigen b/gtsam/3rdparty/Eigen/Eigen/Eigen index 19b40ea4e..654c8dc63 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Eigen +++ b/gtsam/3rdparty/Eigen/Eigen/Eigen @@ -1,2 +1,2 @@ #include "Dense" -//#include "Sparse" +#include "Sparse" diff --git a/gtsam/3rdparty/Eigen/Eigen/Eigen2Support b/gtsam/3rdparty/Eigen/Eigen/Eigen2Support deleted file mode 100644 index 6aa009d20..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/Eigen2Support +++ /dev/null @@ -1,95 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN2SUPPORT_H -#define EIGEN2SUPPORT_H - -#if (!defined(EIGEN2_SUPPORT)) || (!defined(EIGEN_CORE_H)) -#error Eigen2 support must be enabled by defining EIGEN2_SUPPORT before including any Eigen header -#endif - -#ifndef EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#if defined(__GNUC__) || defined(__INTEL_COMPILER) || defined(__clang__) -#warning "Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. (Define EIGEN_NO_EIGEN2_DEPRECATED_WARNING to disable this warning)" -#else -#pragma message ("Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. (Define EIGEN_NO_EIGEN2_DEPRECATED_WARNING to disable this warning)") -#endif - -#endif // EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#include "src/Core/util/DisableStupidWarnings.h" - -/** \ingroup Support_modules - * \defgroup Eigen2Support_Module Eigen2 support module - * - * \warning Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3. - * - * This module provides a couple of deprecated functions improving the compatibility with Eigen2. - * - * To use it, define EIGEN2_SUPPORT before including any Eigen header - * \code - * #define EIGEN2_SUPPORT - * \endcode - * - */ - -#include "src/Eigen2Support/Macros.h" -#include "src/Eigen2Support/Memory.h" -#include "src/Eigen2Support/Meta.h" -#include "src/Eigen2Support/Lazy.h" -#include "src/Eigen2Support/Cwise.h" -#include "src/Eigen2Support/CwiseOperators.h" -#include "src/Eigen2Support/TriangularSolver.h" -#include "src/Eigen2Support/Block.h" -#include "src/Eigen2Support/VectorBlock.h" -#include "src/Eigen2Support/Minor.h" -#include "src/Eigen2Support/MathFunctions.h" - - -#include "src/Core/util/ReenableStupidWarnings.h" - -// Eigen2 used to include iostream -#include - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, SizeSuffix) \ -using Eigen::Matrix##SizeSuffix##TypeSuffix; \ -using Eigen::Vector##SizeSuffix##TypeSuffix; \ -using Eigen::RowVector##SizeSuffix##TypeSuffix; - -#define EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(TypeSuffix) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 2) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 3) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, 4) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE_AND_SIZE(TypeSuffix, X) \ - -#define EIGEN_USING_MATRIX_TYPEDEFS \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(i) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(f) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(d) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cf) \ -EIGEN_USING_MATRIX_TYPEDEFS_FOR_TYPE(cd) - -#define USING_PART_OF_NAMESPACE_EIGEN \ -EIGEN_USING_MATRIX_TYPEDEFS \ -using Eigen::Matrix; \ -using Eigen::MatrixBase; \ -using Eigen::ei_random; \ -using Eigen::ei_real; \ -using Eigen::ei_imag; \ -using Eigen::ei_conj; \ -using Eigen::ei_abs; \ -using Eigen::ei_abs2; \ -using Eigen::ei_sqrt; \ -using Eigen::ei_exp; \ -using Eigen::ei_log; \ -using Eigen::ei_sin; \ -using Eigen::ei_cos; - -#endif // EIGEN2SUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/Eigenvalues b/gtsam/3rdparty/Eigen/Eigen/Eigenvalues index 53c5a73a2..009e529e1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Eigenvalues +++ b/gtsam/3rdparty/Eigen/Eigen/Eigenvalues @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_EIGENVALUES_MODULE_H #define EIGEN_EIGENVALUES_MODULE_H @@ -25,6 +32,7 @@ * \endcode */ +#include "src/misc/RealSvd2x2.h" #include "src/Eigenvalues/Tridiagonalization.h" #include "src/Eigenvalues/RealSchur.h" #include "src/Eigenvalues/EigenSolver.h" @@ -37,9 +45,10 @@ #include "src/Eigenvalues/GeneralizedEigenSolver.h" #include "src/Eigenvalues/MatrixBaseEigenvalues.h" #ifdef EIGEN_USE_LAPACKE -#include "src/Eigenvalues/RealSchur_MKL.h" -#include "src/Eigenvalues/ComplexSchur_MKL.h" -#include "src/Eigenvalues/SelfAdjointEigenSolver_MKL.h" +#include "src/misc/lapacke.h" +#include "src/Eigenvalues/RealSchur_LAPACKE.h" +#include "src/Eigenvalues/ComplexSchur_LAPACKE.h" +#include "src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Geometry b/gtsam/3rdparty/Eigen/Eigen/Geometry index efd9d4504..716d52952 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Geometry +++ b/gtsam/3rdparty/Eigen/Eigen/Geometry @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_GEOMETRY_MODULE_H #define EIGEN_GEOMETRY_MODULE_H @@ -9,21 +16,17 @@ #include "LU" #include -#ifndef M_PI -#define M_PI 3.14159265358979323846 -#endif - /** \defgroup Geometry_Module Geometry module - * - * * * This module provides support for: * - fixed-size homogeneous transformations * - translation, scaling, 2D and 3D rotations - * - quaternions - * - \ref MatrixBase::cross() "cross product" - * - \ref MatrixBase::unitOrthogonal() "orthognal vector generation" - * - some linear components: parametrized-lines and hyperplanes + * - \link Quaternion quaternions \endlink + * - cross products (\ref MatrixBase::cross, \ref MatrixBase::cross3) + * - orthognal vector generation (\ref MatrixBase::unitOrthogonal) + * - some linear components: \link ParametrizedLine parametrized-lines \endlink and \link Hyperplane hyperplanes \endlink + * - \link AlignedBox axis aligned bounding boxes \endlink + * - \link umeyama least-square transformation fitting \endlink * * \code * #include @@ -33,27 +36,23 @@ #include "src/Geometry/OrthoMethods.h" #include "src/Geometry/EulerAngles.h" -#if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - #include "src/Geometry/Homogeneous.h" - #include "src/Geometry/RotationBase.h" - #include "src/Geometry/Rotation2D.h" - #include "src/Geometry/Quaternion.h" - #include "src/Geometry/AngleAxis.h" - #include "src/Geometry/Transform.h" - #include "src/Geometry/Translation.h" - #include "src/Geometry/Scaling.h" - #include "src/Geometry/Hyperplane.h" - #include "src/Geometry/ParametrizedLine.h" - #include "src/Geometry/AlignedBox.h" - #include "src/Geometry/Umeyama.h" +#include "src/Geometry/Homogeneous.h" +#include "src/Geometry/RotationBase.h" +#include "src/Geometry/Rotation2D.h" +#include "src/Geometry/Quaternion.h" +#include "src/Geometry/AngleAxis.h" +#include "src/Geometry/Transform.h" +#include "src/Geometry/Translation.h" +#include "src/Geometry/Scaling.h" +#include "src/Geometry/Hyperplane.h" +#include "src/Geometry/ParametrizedLine.h" +#include "src/Geometry/AlignedBox.h" +#include "src/Geometry/Umeyama.h" - #if defined EIGEN_VECTORIZE_SSE - #include "src/Geometry/arch/Geometry_SSE.h" - #endif -#endif - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/Geometry/All.h" +// Use the SSE optimized version whenever possible. At the moment the +// SSE version doesn't compile when AVX is enabled +#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX +#include "src/Geometry/arch/Geometry_SSE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Householder b/gtsam/3rdparty/Eigen/Eigen/Householder index 6e348db5c..89cd81b1a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Householder +++ b/gtsam/3rdparty/Eigen/Eigen/Householder @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_HOUSEHOLDER_MODULE_H #define EIGEN_HOUSEHOLDER_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers b/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers index 0f4159dc1..957d5750b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers +++ b/gtsam/3rdparty/Eigen/Eigen/IterativeLinearSolvers @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H #define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H @@ -12,28 +19,29 @@ * This module currently provides iterative methods to solve problems of the form \c A \c x = \c b, where \c A is a squared matrix, usually very large and sparse. * Those solvers are accessible via the following classes: * - ConjugateGradient for selfadjoint (hermitian) matrices, + * - LeastSquaresConjugateGradient for rectangular least-square problems, * - BiCGSTAB for general square matrices. * * These iterative solvers are associated with some preconditioners: * - IdentityPreconditioner - not really useful - * - DiagonalPreconditioner - also called JAcobi preconditioner, work very well on diagonal dominant matrices. - * - IncompleteILUT - incomplete LU factorization with dual thresholding + * - DiagonalPreconditioner - also called Jacobi preconditioner, work very well on diagonal dominant matrices. + * - IncompleteLUT - incomplete LU factorization with dual thresholding * * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport. * - * \code - * #include - * \endcode + \code + #include + \endcode */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - +#include "src/IterativeLinearSolvers/SolveWithGuess.h" #include "src/IterativeLinearSolvers/IterativeSolverBase.h" #include "src/IterativeLinearSolvers/BasicPreconditioners.h" #include "src/IterativeLinearSolvers/ConjugateGradient.h" +#include "src/IterativeLinearSolvers/LeastSquareConjugateGradient.h" #include "src/IterativeLinearSolvers/BiCGSTAB.h" #include "src/IterativeLinearSolvers/IncompleteLUT.h" +#include "src/IterativeLinearSolvers/IncompleteCholesky.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Jacobi b/gtsam/3rdparty/Eigen/Eigen/Jacobi index ba8a4dc36..17c1d785a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Jacobi +++ b/gtsam/3rdparty/Eigen/Eigen/Jacobi @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_JACOBI_MODULE_H #define EIGEN_JACOBI_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/LU b/gtsam/3rdparty/Eigen/Eigen/LU index db5795504..6f6c55629 100644 --- a/gtsam/3rdparty/Eigen/Eigen/LU +++ b/gtsam/3rdparty/Eigen/Eigen/LU @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_LU_MODULE_H #define EIGEN_LU_MODULE_H @@ -16,25 +23,23 @@ * \endcode */ -#include "src/misc/Solve.h" #include "src/misc/Kernel.h" #include "src/misc/Image.h" #include "src/LU/FullPivLU.h" #include "src/LU/PartialPivLU.h" #ifdef EIGEN_USE_LAPACKE -#include "src/LU/PartialPivLU_MKL.h" +#include "src/misc/lapacke.h" +#include "src/LU/PartialPivLU_LAPACKE.h" #endif #include "src/LU/Determinant.h" -#include "src/LU/Inverse.h" +#include "src/LU/InverseImpl.h" -#if defined EIGEN_VECTORIZE_SSE +// Use the SSE optimized version whenever possible. At the moment the +// SSE version doesn't compile when AVX is enabled +#if defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX #include "src/LU/arch/Inverse_SSE.h" #endif -#ifdef EIGEN2_SUPPORT - #include "src/Eigen2Support/LU.h" -#endif - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_LU_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/LeastSquares b/gtsam/3rdparty/Eigen/Eigen/LeastSquares deleted file mode 100644 index 35137c25d..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/LeastSquares +++ /dev/null @@ -1,32 +0,0 @@ -#ifndef EIGEN_REGRESSION_MODULE_H -#define EIGEN_REGRESSION_MODULE_H - -#ifndef EIGEN2_SUPPORT -#error LeastSquares is only available in Eigen2 support mode (define EIGEN2_SUPPORT) -#endif - -// exclude from normal eigen3-only documentation -#ifdef EIGEN2_SUPPORT - -#include "Core" - -#include "src/Core/util/DisableStupidWarnings.h" - -#include "Eigenvalues" -#include "Geometry" - -/** \defgroup LeastSquares_Module LeastSquares module - * This module provides linear regression and related features. - * - * \code - * #include - * \endcode - */ - -#include "src/Eigen2Support/LeastSquares.h" - -#include "src/Core/util/ReenableStupidWarnings.h" - -#endif // EIGEN2_SUPPORT - -#endif // EIGEN_REGRESSION_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/MetisSupport b/gtsam/3rdparty/Eigen/Eigen/MetisSupport index 6a113f7a8..85c41bf34 100644 --- a/gtsam/3rdparty/Eigen/Eigen/MetisSupport +++ b/gtsam/3rdparty/Eigen/Eigen/MetisSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_METISSUPPORT_MODULE_H #define EIGEN_METISSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/OrderingMethods b/gtsam/3rdparty/Eigen/Eigen/OrderingMethods index 7c0f1ffff..d8ea36193 100644 --- a/gtsam/3rdparty/Eigen/Eigen/OrderingMethods +++ b/gtsam/3rdparty/Eigen/Eigen/OrderingMethods @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_ORDERINGMETHODS_MODULE_H #define EIGEN_ORDERINGMETHODS_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport b/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport index 7c616ee5e..de3a63b4d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport +++ b/gtsam/3rdparty/Eigen/Eigen/PaStiXSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_PASTIXSUPPORT_MODULE_H #define EIGEN_PASTIXSUPPORT_MODULE_H @@ -5,7 +12,6 @@ #include "src/Core/util/DisableStupidWarnings.h" -#include extern "C" { #include #include @@ -35,12 +41,8 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/PaStiXSupport/PaStiXSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_PASTIXSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/PardisoSupport b/gtsam/3rdparty/Eigen/Eigen/PardisoSupport old mode 100644 new mode 100755 index 99330ce7a..340edf51f --- a/gtsam/3rdparty/Eigen/Eigen/PardisoSupport +++ b/gtsam/3rdparty/Eigen/Eigen/PardisoSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_PARDISOSUPPORT_MODULE_H #define EIGEN_PARDISOSUPPORT_MODULE_H @@ -7,8 +14,6 @@ #include -#include - /** \ingroup Support_modules * \defgroup PardisoSupport_Module PardisoSupport module * diff --git a/gtsam/3rdparty/Eigen/Eigen/QR b/gtsam/3rdparty/Eigen/Eigen/QR index ac5b02693..80838e3bd 100644 --- a/gtsam/3rdparty/Eigen/Eigen/QR +++ b/gtsam/3rdparty/Eigen/Eigen/QR @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_QR_MODULE_H #define EIGEN_QR_MODULE_H @@ -15,31 +22,26 @@ * * This module provides various QR decompositions * This module also provides some MatrixBase methods, including: - * - MatrixBase::qr(), + * - MatrixBase::householderQr() + * - MatrixBase::colPivHouseholderQr() + * - MatrixBase::fullPivHouseholderQr() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" #include "src/QR/HouseholderQR.h" #include "src/QR/FullPivHouseholderQR.h" #include "src/QR/ColPivHouseholderQR.h" +#include "src/QR/CompleteOrthogonalDecomposition.h" #ifdef EIGEN_USE_LAPACKE -#include "src/QR/HouseholderQR_MKL.h" -#include "src/QR/ColPivHouseholderQR_MKL.h" -#endif - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/QR.h" +#include "src/misc/lapacke.h" +#include "src/QR/HouseholderQR_LAPACKE.h" +#include "src/QR/ColPivHouseholderQR_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" -#ifdef EIGEN2_SUPPORT -#include "Eigenvalues" -#endif - #endif // EIGEN_QR_MODULE_H /* vim: set filetype=cpp et sw=2 ts=2 ai: */ diff --git a/gtsam/3rdparty/Eigen/Eigen/QtAlignedMalloc b/gtsam/3rdparty/Eigen/Eigen/QtAlignedMalloc index 46f7d83b7..c6571f129 100644 --- a/gtsam/3rdparty/Eigen/Eigen/QtAlignedMalloc +++ b/gtsam/3rdparty/Eigen/Eigen/QtAlignedMalloc @@ -1,3 +1,9 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #ifndef EIGEN_QTMALLOC_MODULE_H #define EIGEN_QTMALLOC_MODULE_H @@ -8,7 +14,7 @@ #include "src/Core/util/DisableStupidWarnings.h" -void *qMalloc(size_t size) +void *qMalloc(std::size_t size) { return Eigen::internal::aligned_malloc(size); } @@ -18,7 +24,7 @@ void qFree(void *ptr) Eigen::internal::aligned_free(ptr); } -void *qRealloc(void *ptr, size_t size) +void *qRealloc(void *ptr, std::size_t size) { void* newPtr = Eigen::internal::aligned_malloc(size); memcpy(newPtr, ptr, size); diff --git a/gtsam/3rdparty/Eigen/Eigen/SPQRSupport b/gtsam/3rdparty/Eigen/Eigen/SPQRSupport index 7f1eb4770..f70390c17 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SPQRSupport +++ b/gtsam/3rdparty/Eigen/Eigen/SPQRSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPQRSUPPORT_MODULE_H #define EIGEN_SPQRSUPPORT_MODULE_H @@ -21,8 +28,6 @@ * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" #include "src/CholmodSupport/CholmodSupport.h" #include "src/SPQRSupport/SuiteSparseQRSupport.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/SVD b/gtsam/3rdparty/Eigen/Eigen/SVD index fd310017a..86143c23d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SVD +++ b/gtsam/3rdparty/Eigen/Eigen/SVD @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SVD_MODULE_H #define EIGEN_SVD_MODULE_H @@ -12,23 +19,26 @@ * * * This module provides SVD decomposition for matrices (both real and complex). - * This decomposition is accessible via the following MatrixBase method: + * Two decomposition algorithms are provided: + * - JacobiSVD implementing two-sided Jacobi iterations is numerically very accurate, fast for small matrices, but very slow for larger ones. + * - BDCSVD implementing a recursive divide & conquer strategy on top of an upper-bidiagonalization which remains fast for large problems. + * These decompositions are accessible via the respective classes and following MatrixBase methods: * - MatrixBase::jacobiSvd() + * - MatrixBase::bdcSvd() * * \code * #include * \endcode */ -#include "src/misc/Solve.h" -#include "src/SVD/JacobiSVD.h" -#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT) -#include "src/SVD/JacobiSVD_MKL.h" -#endif +#include "src/misc/RealSvd2x2.h" #include "src/SVD/UpperBidiagonalization.h" - -#ifdef EIGEN2_SUPPORT -#include "src/Eigen2Support/SVD.h" +#include "src/SVD/SVDBase.h" +#include "src/SVD/JacobiSVD.h" +#include "src/SVD/BDCSVD.h" +#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT) +#include "src/misc/lapacke.h" +#include "src/SVD/JacobiSVD_LAPACKE.h" #endif #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/Sparse b/gtsam/3rdparty/Eigen/Eigen/Sparse index 7cc9c0913..136e681a1 100644 --- a/gtsam/3rdparty/Eigen/Eigen/Sparse +++ b/gtsam/3rdparty/Eigen/Eigen/Sparse @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSE_MODULE_H #define EIGEN_SPARSE_MODULE_H @@ -11,14 +18,16 @@ * - \ref SparseQR_Module * - \ref IterativeLinearSolvers_Module * - * \code - * #include - * \endcode + \code + #include + \endcode */ #include "SparseCore" #include "OrderingMethods" +#ifndef EIGEN_MPL2_ONLY #include "SparseCholesky" +#endif #include "SparseLU" #include "SparseQR" #include "IterativeLinearSolvers" diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseCholesky b/gtsam/3rdparty/Eigen/Eigen/SparseCholesky index 9f5056aa1..b6a320c40 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SparseCholesky +++ b/gtsam/3rdparty/Eigen/Eigen/SparseCholesky @@ -34,8 +34,6 @@ #error The SparseCholesky module has nothing to offer in MPL2 only mode #endif -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" #include "src/SparseCholesky/SimplicialCholesky.h" #ifndef EIGEN_MPL2_ONLY diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseCore b/gtsam/3rdparty/Eigen/Eigen/SparseCore index 24bcf0156..76966c4c4 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SparseCore +++ b/gtsam/3rdparty/Eigen/Eigen/SparseCore @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSECORE_MODULE_H #define EIGEN_SPARSECORE_MODULE_H @@ -26,37 +33,35 @@ * This module depends on: Core. */ -namespace Eigen { - -/** The type used to identify a general sparse storage. */ -struct Sparse {}; - -} - #include "src/SparseCore/SparseUtil.h" #include "src/SparseCore/SparseMatrixBase.h" +#include "src/SparseCore/SparseAssign.h" #include "src/SparseCore/CompressedStorage.h" #include "src/SparseCore/AmbiVector.h" +#include "src/SparseCore/SparseCompressedBase.h" #include "src/SparseCore/SparseMatrix.h" +#include "src/SparseCore/SparseMap.h" #include "src/SparseCore/MappedSparseMatrix.h" #include "src/SparseCore/SparseVector.h" -#include "src/SparseCore/SparseBlock.h" -#include "src/SparseCore/SparseTranspose.h" +#include "src/SparseCore/SparseRef.h" #include "src/SparseCore/SparseCwiseUnaryOp.h" #include "src/SparseCore/SparseCwiseBinaryOp.h" +#include "src/SparseCore/SparseTranspose.h" +#include "src/SparseCore/SparseBlock.h" #include "src/SparseCore/SparseDot.h" -#include "src/SparseCore/SparsePermutation.h" #include "src/SparseCore/SparseRedux.h" -#include "src/SparseCore/SparseFuzzy.h" +#include "src/SparseCore/SparseView.h" +#include "src/SparseCore/SparseDiagonalProduct.h" #include "src/SparseCore/ConservativeSparseSparseProduct.h" #include "src/SparseCore/SparseSparseProductWithPruning.h" #include "src/SparseCore/SparseProduct.h" #include "src/SparseCore/SparseDenseProduct.h" -#include "src/SparseCore/SparseDiagonalProduct.h" -#include "src/SparseCore/SparseTriangularView.h" #include "src/SparseCore/SparseSelfAdjointView.h" +#include "src/SparseCore/SparseTriangularView.h" #include "src/SparseCore/TriangularSolver.h" -#include "src/SparseCore/SparseView.h" +#include "src/SparseCore/SparsePermutation.h" +#include "src/SparseCore/SparseFuzzy.h" +#include "src/SparseCore/SparseSolverBase.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseLU b/gtsam/3rdparty/Eigen/Eigen/SparseLU index 8527a49bd..38b38b531 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SparseLU +++ b/gtsam/3rdparty/Eigen/Eigen/SparseLU @@ -20,9 +20,6 @@ * Please, see the documentation of the SparseLU class for more details. */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - // Ordering interface #include "OrderingMethods" diff --git a/gtsam/3rdparty/Eigen/Eigen/SparseQR b/gtsam/3rdparty/Eigen/Eigen/SparseQR index 4ee42065e..a6f3b7f7d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SparseQR +++ b/gtsam/3rdparty/Eigen/Eigen/SparseQR @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SPARSEQR_MODULE_H #define EIGEN_SPARSEQR_MODULE_H @@ -21,9 +28,6 @@ * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "OrderingMethods" #include "src/SparseCore/SparseColEtree.h" #include "src/SparseQR/SparseQR.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/StdDeque b/gtsam/3rdparty/Eigen/Eigen/StdDeque index f27234778..bc68397be 100644 --- a/gtsam/3rdparty/Eigen/Eigen/StdDeque +++ b/gtsam/3rdparty/Eigen/Eigen/StdDeque @@ -14,7 +14,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...) diff --git a/gtsam/3rdparty/Eigen/Eigen/StdList b/gtsam/3rdparty/Eigen/Eigen/StdList index 225c1e18f..4c6262c08 100644 --- a/gtsam/3rdparty/Eigen/Eigen/StdList +++ b/gtsam/3rdparty/Eigen/Eigen/StdList @@ -13,7 +13,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...) diff --git a/gtsam/3rdparty/Eigen/Eigen/StdVector b/gtsam/3rdparty/Eigen/Eigen/StdVector index 6b22627f6..0c4697ad5 100644 --- a/gtsam/3rdparty/Eigen/Eigen/StdVector +++ b/gtsam/3rdparty/Eigen/Eigen/StdVector @@ -14,7 +14,7 @@ #include "Core" #include -#if (defined(_MSC_VER) && defined(_WIN64)) /* MSVC auto aligns in 64 bit builds */ +#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */ #define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...) diff --git a/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport b/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport index 575e14fbc..59312a82d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport +++ b/gtsam/3rdparty/Eigen/Eigen/SuperLUSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_SUPERLUSUPPORT_MODULE_H #define EIGEN_SUPERLUSUPPORT_MODULE_H @@ -36,6 +43,8 @@ namespace Eigen { struct SluMatrix; } * - class SuperLU: a supernodal sequential LU factorization. * - class SuperILU: a supernodal sequential incomplete LU factorization (to be used as a preconditioner for iterative methods). * + * \warning This wrapper requires at least versions 4.0 of SuperLU. The 3.x versions are not supported. + * * \warning When including this module, you have to use SUPERLU_EMPTY instead of EMPTY which is no longer defined because it is too polluting. * * \code @@ -48,12 +57,8 @@ namespace Eigen { struct SluMatrix; } * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/SuperLUSupport/SuperLUSupport.h" - #include "src/Core/util/ReenableStupidWarnings.h" #endif // EIGEN_SUPERLUSUPPORT_MODULE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport b/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport index 7b1b66064..00eec8087 100644 --- a/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport +++ b/gtsam/3rdparty/Eigen/Eigen/UmfPackSupport @@ -1,3 +1,10 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #ifndef EIGEN_UMFPACKSUPPORT_MODULE_H #define EIGEN_UMFPACKSUPPORT_MODULE_H @@ -26,9 +33,6 @@ extern "C" { * */ -#include "src/misc/Solve.h" -#include "src/misc/SparseSolve.h" - #include "src/UmfPackSupport/UmfPackSupport.h" #include "src/Core/util/ReenableStupidWarnings.h" diff --git a/gtsam/3rdparty/Eigen/Eigen/src/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/CMakeLists.txt deleted file mode 100644 index c326f374d..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/CMakeLists.txt +++ /dev/null @@ -1,7 +0,0 @@ -file(GLOB Eigen_src_subdirectories "*") -escape_string_as_regex(ESCAPED_CMAKE_CURRENT_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}") -foreach(f ${Eigen_src_subdirectories}) - if(NOT f MATCHES "\\.txt" AND NOT f MATCHES "${ESCAPED_CMAKE_CURRENT_SOURCE_DIR}/[.].+" ) - add_subdirectory(${f}) - endif() -endforeach() diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/CMakeLists.txt deleted file mode 100644 index d01488b41..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -FILE(GLOB Eigen_Cholesky_SRCS "*.h") - -INSTALL(FILES - ${Eigen_Cholesky_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/Cholesky COMPONENT Devel - ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h index abd30bd91..fcee7b2e3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LDLT.h @@ -13,7 +13,7 @@ #ifndef EIGEN_LDLT_H #define EIGEN_LDLT_H -namespace Eigen { +namespace Eigen { namespace internal { template struct LDLT_Traits; @@ -28,8 +28,8 @@ namespace internal { * * \brief Robust Cholesky decomposition of a matrix with pivoting * - * \param MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition - * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * \tparam _MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition + * \tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. * The other triangular part won't be read. * * Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite @@ -43,7 +43,9 @@ namespace internal { * Remember that Cholesky decompositions are not rank-revealing. Also, do not use a Cholesky * decomposition to determine whether a system of equations has a solution. * - * \sa MatrixBase::ldlt(), class LLT + * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. + * + * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt(), class LLT */ template class LDLT { @@ -52,15 +54,15 @@ template class LDLT enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, - Options = MatrixType::Options & ~RowMajorBit, // these are the options for the TmpMatrixType, we need a ColMajor matrix here! MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - typedef typename MatrixType::Index Index; - typedef Matrix TmpMatrixType; + typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 + typedef typename MatrixType::StorageIndex StorageIndex; + typedef Matrix TmpMatrixType; typedef Transpositions TranspositionType; typedef PermutationMatrix PermutationType; @@ -72,11 +74,11 @@ template class LDLT * The default constructor is useful in cases in which the user intends to * perform decompositions via LDLT::compute(const MatrixType&). */ - LDLT() - : m_matrix(), - m_transpositions(), + LDLT() + : m_matrix(), + m_transpositions(), m_sign(internal::ZeroSign), - m_isInitialized(false) + m_isInitialized(false) {} /** \brief Default Constructor with memory preallocation @@ -85,7 +87,7 @@ template class LDLT * according to the specified problem \a size. * \sa LDLT() */ - LDLT(Index size) + explicit LDLT(Index size) : m_matrix(size, size), m_transpositions(size), m_temporary(size), @@ -96,16 +98,35 @@ template class LDLT /** \brief Constructor with decomposition * * This calculates the decomposition for the input \a matrix. + * * \sa LDLT(Index size) */ - LDLT(const MatrixType& matrix) + template + explicit LDLT(const EigenBase& matrix) : m_matrix(matrix.rows(), matrix.cols()), m_transpositions(matrix.rows()), m_temporary(matrix.rows()), m_sign(internal::ZeroSign), m_isInitialized(false) { - compute(matrix); + compute(matrix.derived()); + } + + /** \brief Constructs a LDLT factorization from a given matrix + * + * This overloaded constructor is provided for \link InplaceDecomposition inplace decomposition \endlink when \c MatrixType is a Eigen::Ref. + * + * \sa LDLT(const EigenBase&) + */ + template + explicit LDLT(EigenBase& matrix) + : m_matrix(matrix.derived()), + m_transpositions(matrix.rows()), + m_temporary(matrix.rows()), + m_sign(internal::ZeroSign), + m_isInitialized(false) + { + compute(matrix.derived()); } /** Clear any existing decomposition @@ -151,13 +172,6 @@ template class LDLT eigen_assert(m_isInitialized && "LDLT is not initialized."); return m_sign == internal::PositiveSemiDef || m_sign == internal::ZeroSign; } - - #ifdef EIGEN2_SUPPORT - inline bool isPositiveDefinite() const - { - return isPositive(); - } - #endif /** \returns true if the matrix is negative (semidefinite) */ inline bool isNegative(void) const @@ -173,37 +187,38 @@ template class LDLT * \note_about_checking_solutions * * More precisely, this method solves \f$ A x = b \f$ using the decomposition \f$ A = P^T L D L^* P \f$ - * by solving the systems \f$ P^T y_1 = b \f$, \f$ L y_2 = y_1 \f$, \f$ D y_3 = y_2 \f$, + * by solving the systems \f$ P^T y_1 = b \f$, \f$ L y_2 = y_1 \f$, \f$ D y_3 = y_2 \f$, * \f$ L^* y_4 = y_3 \f$ and \f$ P x = y_4 \f$ in succession. If the matrix \f$ A \f$ is singular, then * \f$ D \f$ will also be singular (all the other matrices are invertible). In that case, the * least-square solution of \f$ D y_3 = y_2 \f$ is computed. This does not mean that this function * computes the least-square solution of \f$ A x = b \f$ is \f$ A \f$ is singular. * - * \sa MatrixBase::ldlt() + * \sa MatrixBase::ldlt(), SelfAdjointView::ldlt() */ template - inline const internal::solve_retval + inline const Solve solve(const MatrixBase& b) const { eigen_assert(m_isInitialized && "LDLT is not initialized."); eigen_assert(m_matrix.rows()==b.rows() && "LDLT::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); + return Solve(*this, b.derived()); } - #ifdef EIGEN2_SUPPORT - template - bool solve(const MatrixBase& b, ResultType *result) const - { - *result = this->solve(b); - return true; - } - #endif - template bool solveInPlace(MatrixBase &bAndX) const; - LDLT& compute(const MatrixType& matrix); + template + LDLT& compute(const EigenBase& matrix); + + /** \returns an estimate of the reciprocal condition number of the matrix of + * which \c *this is the LDLT decomposition. + */ + RealScalar rcond() const + { + eigen_assert(m_isInitialized && "LDLT is not initialized."); + return internal::rcond_estimate_helper(m_l1_norm, *this); + } template LDLT& rankUpdate(const MatrixBase& w, const RealScalar& alpha=1); @@ -220,6 +235,13 @@ template class LDLT MatrixType reconstructedMatrix() const; + /** \returns the adjoint of \c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint. + * + * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as: + * \code x = decomposition.adjoint().solve(b) \endcode + */ + const LDLT& adjoint() const { return *this; }; + inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } @@ -231,11 +253,17 @@ template class LDLT ComputationInfo info() const { eigen_assert(m_isInitialized && "LDLT is not initialized."); - return Success; + return m_info; } + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + EIGEN_DEVICE_FUNC + void _solve_impl(const RhsType &rhs, DstType &dst) const; + #endif + protected: - + static void check_template_parameters() { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); @@ -248,10 +276,12 @@ template class LDLT * is not stored), and the diagonal entries correspond to D. */ MatrixType m_matrix; + RealScalar m_l1_norm; TranspositionType m_transpositions; TmpMatrixType m_temporary; internal::SignMatrix m_sign; bool m_isInitialized; + ComputationInfo m_info; }; namespace internal { @@ -266,15 +296,17 @@ template<> struct ldlt_inplace using std::abs; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; + typedef typename TranspositionType::StorageIndex IndexType; eigen_assert(mat.rows()==mat.cols()); const Index size = mat.rows(); + bool found_zero_pivot = false; + bool ret = true; if (size <= 1) { transpositions.setIdentity(); - if (numext::real(mat.coeff(0,0)) > 0) sign = PositiveSemiDef; - else if (numext::real(mat.coeff(0,0)) < 0) sign = NegativeSemiDef; + if (numext::real(mat.coeff(0,0)) > static_cast(0) ) sign = PositiveSemiDef; + else if (numext::real(mat.coeff(0,0)) < static_cast(0)) sign = NegativeSemiDef; else sign = ZeroSign; return true; } @@ -286,7 +318,7 @@ template<> struct ldlt_inplace mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner); index_of_biggest_in_corner += k; - transpositions.coeffRef(k) = index_of_biggest_in_corner; + transpositions.coeffRef(k) = IndexType(index_of_biggest_in_corner); if(k != index_of_biggest_in_corner) { // apply the transposition while taking care to consider only @@ -295,7 +327,7 @@ template<> struct ldlt_inplace mat.row(k).head(k).swap(mat.row(index_of_biggest_in_corner).head(k)); mat.col(k).tail(s).swap(mat.col(index_of_biggest_in_corner).tail(s)); std::swap(mat.coeffRef(k,k),mat.coeffRef(index_of_biggest_in_corner,index_of_biggest_in_corner)); - for(int i=k+1;i struct ldlt_inplace if(rs>0) A21.noalias() -= A20 * temp.head(k); } - + // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot - // was smaller than the cutoff value. However, soince LDLT is not rank-revealing - // we should only make sure we do not introduce INF or NaN values. - // LAPACK also uses 0 as the cutoff value. + // was smaller than the cutoff value. However, since LDLT is not rank-revealing + // we should only make sure that we do not introduce INF or NaN values. + // Remark that LAPACK also uses 0 as the cutoff value. RealScalar realAkk = numext::real(mat.coeffRef(k,k)); - if((rs>0) && (abs(realAkk) > RealScalar(0))) + bool pivot_is_valid = (abs(realAkk) > RealScalar(0)); + + if(k==0 && !pivot_is_valid) + { + // The entire diagonal is zero, there is nothing more to do + // except filling the transpositions, and checking whether the matrix is zero. + sign = ZeroSign; + for(Index j = 0; j0) && pivot_is_valid) A21 /= realAkk; + if(found_zero_pivot && pivot_is_valid) ret = false; // factorization failed + else if(!pivot_is_valid) found_zero_pivot = true; + if (sign == PositiveSemiDef) { - if (realAkk < 0) sign = Indefinite; + if (realAkk < static_cast(0)) sign = Indefinite; } else if (sign == NegativeSemiDef) { - if (realAkk > 0) sign = Indefinite; + if (realAkk > static_cast(0)) sign = Indefinite; } else if (sign == ZeroSign) { - if (realAkk > 0) sign = PositiveSemiDef; - else if (realAkk < 0) sign = NegativeSemiDef; + if (realAkk > static_cast(0)) sign = PositiveSemiDef; + else if (realAkk < static_cast(0)) sign = NegativeSemiDef; } } - return true; + return ret; } // Reference for the algorithm: Davis and Hager, "Multiple Rank @@ -356,7 +406,6 @@ template<> struct ldlt_inplace using numext::isfinite; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; const Index size = mat.rows(); eigen_assert(mat.cols() == size && w.size()==size); @@ -420,16 +469,16 @@ template struct LDLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m; } - static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } }; template struct LDLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } - static inline MatrixU getU(const MatrixType& m) { return m; } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); } }; } // end namespace internal @@ -437,21 +486,35 @@ template struct LDLT_Traits /** Compute / recompute the LDLT decomposition A = L D L^* = U^* D U of \a matrix */ template -LDLT& LDLT::compute(const MatrixType& a) +template +LDLT& LDLT::compute(const EigenBase& a) { check_template_parameters(); - + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); - m_matrix = a; + m_matrix = a.derived(); + + // Compute matrix L1 norm = max abs column sum. + m_l1_norm = RealScalar(0); + // TODO move this code to SelfAdjointView + for (Index col = 0; col < size; ++col) { + RealScalar abs_col_sum; + if (_UpLo == Lower) + abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>(); + else + abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>(); + if (abs_col_sum > m_l1_norm) + m_l1_norm = abs_col_sum; + } m_transpositions.resize(size); m_isInitialized = false; m_temporary.resize(size); m_sign = internal::ZeroSign; - internal::ldlt_inplace::unblocked(m_matrix, m_transpositions, m_temporary, m_sign); + m_info = internal::ldlt_inplace::unblocked(m_matrix, m_transpositions, m_temporary, m_sign) ? Success : NumericalIssue; m_isInitialized = true; return *this; @@ -466,18 +529,19 @@ template template LDLT& LDLT::rankUpdate(const MatrixBase& w, const typename LDLT::RealScalar& sigma) { + typedef typename TranspositionType::StorageIndex IndexType; const Index size = w.rows(); if (m_isInitialized) { eigen_assert(m_matrix.rows()==size); } else - { + { m_matrix.resize(size,size); m_matrix.setZero(); m_transpositions.resize(size); for (Index i = 0; i < size; i++) - m_transpositions.coeffRef(i) = i; + m_transpositions.coeffRef(i) = IndexType(i); m_temporary.resize(size); m_sign = sigma>=0 ? internal::PositiveSemiDef : internal::NegativeSemiDef; m_isInitialized = true; @@ -488,53 +552,45 @@ LDLT& LDLT::rankUpdate(const MatrixBase -struct solve_retval, Rhs> - : solve_retval_base, Rhs> +#ifndef EIGEN_PARSED_BY_DOXYGEN +template +template +void LDLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const { - typedef LDLT<_MatrixType,_UpLo> LDLTType; - EIGEN_MAKE_SOLVE_HELPERS(LDLTType,Rhs) + eigen_assert(rhs.rows() == rows()); + // dst = P b + dst = m_transpositions * rhs; - template void evalTo(Dest& dst) const + // dst = L^-1 (P b) + matrixL().solveInPlace(dst); + + // dst = D^-1 (L^-1 P b) + // more precisely, use pseudo-inverse of D (see bug 241) + using std::abs; + const typename Diagonal::RealReturnType vecD(vectorD()); + // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon + // as motivated by LAPACK's xGELSS: + // RealScalar tolerance = numext::maxi(vecD.array().abs().maxCoeff() * NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); + // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest + // diagonal element is not well justified and leads to numerical issues in some cases. + // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. + RealScalar tolerance = RealScalar(1) / NumTraits::highest(); + + for (Index i = 0; i < vecD.size(); ++i) { - eigen_assert(rhs().rows() == dec().matrixLDLT().rows()); - // dst = P b - dst = dec().transpositionsP() * rhs(); - - // dst = L^-1 (P b) - dec().matrixL().solveInPlace(dst); - - // dst = D^-1 (L^-1 P b) - // more precisely, use pseudo-inverse of D (see bug 241) - using std::abs; - using std::max; - typedef typename LDLTType::MatrixType MatrixType; - typedef typename LDLTType::RealScalar RealScalar; - const typename Diagonal::RealReturnType vectorD(dec().vectorD()); - // In some previous versions, tolerance was set to the max of 1/highest and the maximal diagonal entry * epsilon - // as motivated by LAPACK's xGELSS: - // RealScalar tolerance = (max)(vectorD.array().abs().maxCoeff() *NumTraits::epsilon(),RealScalar(1) / NumTraits::highest()); - // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest - // diagonal element is not well justified and to numerical issues in some cases. - // Moreover, Lapack's xSYTRS routines use 0 for the tolerance. - RealScalar tolerance = RealScalar(1) / NumTraits::highest(); - - for (Index i = 0; i < vectorD.size(); ++i) { - if(abs(vectorD(i)) > tolerance) - dst.row(i) /= vectorD(i); - else - dst.row(i).setZero(); - } - - // dst = L^-T (D^-1 L^-1 P b) - dec().matrixU().solveInPlace(dst); - - // dst = P^-1 (L^-T D^-1 L^-1 P b) = A^-1 b - dst = dec().transpositionsP().transpose() * dst; + if(abs(vecD(i)) > tolerance) + dst.row(i) /= vecD(i); + else + dst.row(i).setZero(); } -}; + + // dst = L^-T (D^-1 L^-1 P b) + matrixU().solveInPlace(dst); + + // dst = P^-1 (L^-T D^-1 L^-1 P b) = A^-1 b + dst = m_transpositions.transpose() * dst; } +#endif /** \internal use x = ldlt_object.solve(x); * @@ -588,6 +644,7 @@ MatrixType LDLT::reconstructedMatrix() const /** \cholesky_module * \returns the Cholesky decomposition with full pivoting without square root of \c *this + * \sa MatrixBase::ldlt() */ template inline const LDLT::PlainObject, UpLo> @@ -598,6 +655,7 @@ SelfAdjointView::ldlt() const /** \cholesky_module * \returns the Cholesky decomposition with full pivoting without square root of \c *this + * \sa SelfAdjointView::ldlt() */ template inline const LDLT::PlainObject> diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h index 7c11a2dc2..87ca8d423 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT.h @@ -10,7 +10,7 @@ #ifndef EIGEN_LLT_H #define EIGEN_LLT_H -namespace Eigen { +namespace Eigen { namespace internal{ template struct LLT_Traits; @@ -22,8 +22,8 @@ template struct LLT_Traits; * * \brief Standard Cholesky decomposition (LL^T) of a matrix and associated features * - * \param MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition - * \param UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. + * \tparam _MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition + * \tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper. * The other triangular part won't be read. * * This class performs a LL^T Cholesky decomposition of a symmetric, positive definite @@ -40,8 +40,10 @@ template struct LLT_Traits; * * Example: \include LLT_example.cpp * Output: \verbinclude LLT_example.out - * - * \sa MatrixBase::llt(), class LDLT + * + * This class supports the \link InplaceDecomposition inplace decomposition \endlink mechanism. + * + * \sa MatrixBase::llt(), SelfAdjointView::llt(), class LDLT */ /* HEY THIS DOX IS DISABLED BECAUSE THERE's A BUG EITHER HERE OR IN LDLT ABOUT THAT (OR BOTH) * Note that during the decomposition, only the upper triangular part of A is considered. Therefore, @@ -54,12 +56,12 @@ template class LLT enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, - Options = MatrixType::Options, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; - typedef typename MatrixType::Index Index; + typedef Eigen::Index Index; ///< \deprecated since Eigen 3.3 + typedef typename MatrixType::StorageIndex StorageIndex; enum { PacketSize = internal::packet_traits::size, @@ -83,14 +85,30 @@ template class LLT * according to the specified problem \a size. * \sa LLT() */ - LLT(Index size) : m_matrix(size, size), + explicit LLT(Index size) : m_matrix(size, size), m_isInitialized(false) {} - LLT(const MatrixType& matrix) + template + explicit LLT(const EigenBase& matrix) : m_matrix(matrix.rows(), matrix.cols()), m_isInitialized(false) { - compute(matrix); + compute(matrix.derived()); + } + + /** \brief Constructs a LDLT factorization from a given matrix + * + * This overloaded constructor is provided for \link InplaceDecomposition inplace decomposition \endlink when + * \c MatrixType is a Eigen::Ref. + * + * \sa LLT(const EigenBase&) + */ + template + explicit LLT(EigenBase& matrix) + : m_matrix(matrix.derived()), + m_isInitialized(false) + { + compute(matrix.derived()); } /** \returns a view of the upper triangular matrix U */ @@ -115,33 +133,33 @@ template class LLT * Example: \include LLT_solve.cpp * Output: \verbinclude LLT_solve.out * - * \sa solveInPlace(), MatrixBase::llt() + * \sa solveInPlace(), MatrixBase::llt(), SelfAdjointView::llt() */ template - inline const internal::solve_retval + inline const Solve solve(const MatrixBase& b) const { eigen_assert(m_isInitialized && "LLT is not initialized."); eigen_assert(m_matrix.rows()==b.rows() && "LLT::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); + return Solve(*this, b.derived()); } - #ifdef EIGEN2_SUPPORT - template - bool solve(const MatrixBase& b, ResultType *result) const - { - *result = this->solve(b); - return true; - } - - bool isPositiveDefinite() const { return true; } - #endif - template void solveInPlace(MatrixBase &bAndX) const; - LLT& compute(const MatrixType& matrix); + template + LLT& compute(const EigenBase& matrix); + + /** \returns an estimate of the reciprocal condition number of the matrix of + * which \c *this is the Cholesky decomposition. + */ + RealScalar rcond() const + { + eigen_assert(m_isInitialized && "LLT is not initialized."); + eigen_assert(m_info == Success && "LLT failed because matrix appears to be negative"); + return internal::rcond_estimate_helper(m_l1_norm, *this); + } /** \returns the LLT decomposition matrix * @@ -167,24 +185,38 @@ template class LLT return m_info; } + /** \returns the adjoint of \c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint. + * + * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as: + * \code x = decomposition.adjoint().solve(b) \endcode + */ + const LLT& adjoint() const { return *this; }; + inline Index rows() const { return m_matrix.rows(); } inline Index cols() const { return m_matrix.cols(); } template LLT rankUpdate(const VectorType& vec, const RealScalar& sigma = 1); + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + EIGEN_DEVICE_FUNC + void _solve_impl(const RhsType &rhs, DstType &dst) const; + #endif + protected: - + static void check_template_parameters() { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar); } - + /** \internal * Used to compute and store L * The strict upper part is not used and even not initialized. */ MatrixType m_matrix; + RealScalar m_l1_norm; bool m_isInitialized; ComputationInfo m_info; }; @@ -194,12 +226,11 @@ namespace internal { template struct llt_inplace; template -static typename MatrixType::Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) +static Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) { using std::sqrt; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; typedef typename MatrixType::ColXpr ColXpr; typedef typename internal::remove_all::type ColXprCleaned; typedef typename ColXprCleaned::SegmentReturnType ColXprSegment; @@ -268,11 +299,10 @@ template struct llt_inplace { typedef typename NumTraits::Real RealScalar; template - static typename MatrixType::Index unblocked(MatrixType& mat) + static Index unblocked(MatrixType& mat) { using std::sqrt; - typedef typename MatrixType::Index Index; - + eigen_assert(mat.rows()==mat.cols()); const Index size = mat.rows(); for(Index k = 0; k < size; ++k) @@ -295,9 +325,8 @@ template struct llt_inplace } template - static typename MatrixType::Index blocked(MatrixType& m) + static Index blocked(MatrixType& m) { - typedef typename MatrixType::Index Index; eigen_assert(m.rows()==m.cols()); Index size = m.rows(); if(size<32) @@ -322,36 +351,36 @@ template struct llt_inplace Index ret; if((ret=unblocked(A11))>=0) return k+ret; if(rs>0) A11.adjoint().template triangularView().template solveInPlace(A21); - if(rs>0) A22.template selfadjointView().rankUpdate(A21,-1); // bottleneck + if(rs>0) A22.template selfadjointView().rankUpdate(A21,typename NumTraits::Literal(-1)); // bottleneck } return -1; } template - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } }; - + template struct llt_inplace { typedef typename NumTraits::Real RealScalar; template - static EIGEN_STRONG_INLINE typename MatrixType::Index unblocked(MatrixType& mat) + static EIGEN_STRONG_INLINE Index unblocked(MatrixType& mat) { Transpose matt(mat); return llt_inplace::unblocked(matt); } template - static EIGEN_STRONG_INLINE typename MatrixType::Index blocked(MatrixType& mat) + static EIGEN_STRONG_INLINE Index blocked(MatrixType& mat) { Transpose matt(mat); return llt_inplace::blocked(matt); } template - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma) { Transpose matt(mat); return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); @@ -362,8 +391,8 @@ template struct LLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m; } - static inline MatrixU getU(const MatrixType& m) { return m.adjoint(); } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); } static bool inplace_decomposition(MatrixType& m) { return llt_inplace::blocked(m)==-1; } }; @@ -372,8 +401,8 @@ template struct LLT_Traits { typedef const TriangularView MatrixL; typedef const TriangularView MatrixU; - static inline MatrixL getL(const MatrixType& m) { return m.adjoint(); } - static inline MatrixU getU(const MatrixType& m) { return m; } + static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); } + static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); } static bool inplace_decomposition(MatrixType& m) { return llt_inplace::blocked(m)==-1; } }; @@ -388,14 +417,28 @@ template struct LLT_Traits * Output: \verbinclude TutorialLinAlgComputeTwice.out */ template -LLT& LLT::compute(const MatrixType& a) +template +LLT& LLT::compute(const EigenBase& a) { check_template_parameters(); - + eigen_assert(a.rows()==a.cols()); const Index size = a.rows(); m_matrix.resize(size, size); - m_matrix = a; + m_matrix = a.derived(); + + // Compute matrix L1 norm = max abs column sum. + m_l1_norm = RealScalar(0); + // TODO move this code to SelfAdjointView + for (Index col = 0; col < size; ++col) { + RealScalar abs_col_sum; + if (_UpLo == Lower) + abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>(); + else + abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>(); + if (abs_col_sum > m_l1_norm) + m_l1_norm = abs_col_sum; + } m_isInitialized = true; bool ok = Traits::inplace_decomposition(m_matrix); @@ -423,33 +466,24 @@ LLT<_MatrixType,_UpLo> LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, c return *this; } - -namespace internal { -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef LLT<_MatrixType,UpLo> LLTType; - EIGEN_MAKE_SOLVE_HELPERS(LLTType,Rhs) - template void evalTo(Dest& dst) const - { - dst = rhs(); - dec().solveInPlace(dst); - } -}; +#ifndef EIGEN_PARSED_BY_DOXYGEN +template +template +void LLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const +{ + dst = rhs; + solveInPlace(dst); } +#endif /** \internal use x = llt_object.solve(x); - * + * * This is the \em in-place version of solve(). * * \param bAndX represents both the right-hand side matrix b and result x. * - * \returns true always! If you need to check for existence of solutions, use another decomposition like LU, QR, or SVD. - * - * This version avoids a copy when the right hand side matrix b is not - * needed anymore. + * This version avoids a copy when the right hand side matrix b is not needed anymore. * * \sa LLT::solve(), MatrixBase::llt() */ @@ -475,6 +509,7 @@ MatrixType LLT::reconstructedMatrix() const /** \cholesky_module * \returns the LLT decomposition of \c *this + * \sa SelfAdjointView::llt() */ template inline const LLT::PlainObject> @@ -485,6 +520,7 @@ MatrixBase::llt() const /** \cholesky_module * \returns the LLT decomposition of \c *this + * \sa SelfAdjointView::llt() */ template inline const LLT::PlainObject, UpLo> diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_LAPACKE.h similarity index 71% rename from gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h rename to gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_LAPACKE.h index f7c365aee..bc6489e69 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_MKL.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Cholesky/LLT_LAPACKE.h @@ -25,41 +25,38 @@ SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ******************************************************************************** - * Content : Eigen bindings to Intel(R) MKL + * Content : Eigen bindings to LAPACKe * LLt decomposition based on LAPACKE_?potrf function. ******************************************************************************** */ -#ifndef EIGEN_LLT_MKL_H -#define EIGEN_LLT_MKL_H - -#include "../Core/util/MKL_support.h" -#include +#ifndef EIGEN_LLT_LAPACKE_H +#define EIGEN_LLT_LAPACKE_H namespace Eigen { namespace internal { -template struct mkl_llt; +template struct lapacke_llt; -#define EIGEN_MKL_LLT(EIGTYPE, MKLTYPE, MKLPREFIX) \ -template<> struct mkl_llt \ +#define EIGEN_LAPACKE_LLT(EIGTYPE, BLASTYPE, LAPACKE_PREFIX) \ +template<> struct lapacke_llt \ { \ template \ - static inline typename MatrixType::Index potrf(MatrixType& m, char uplo) \ + static inline Index potrf(MatrixType& m, char uplo) \ { \ lapack_int matrix_order; \ lapack_int size, lda, info, StorageOrder; \ EIGTYPE* a; \ eigen_assert(m.rows()==m.cols()); \ /* Set up parameters for ?potrf */ \ - size = m.rows(); \ + size = convert_index(m.rows()); \ StorageOrder = MatrixType::Flags&RowMajorBit?RowMajor:ColMajor; \ matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \ a = &(m.coeffRef(0,0)); \ - lda = m.outerStride(); \ + lda = convert_index(m.outerStride()); \ \ - info = LAPACKE_##MKLPREFIX##potrf( matrix_order, uplo, size, (MKLTYPE*)a, lda ); \ + info = LAPACKE_##LAPACKE_PREFIX##potrf( matrix_order, uplo, size, (BLASTYPE*)a, lda ); \ info = (info==0) ? -1 : info>0 ? info-1 : size; \ return info; \ } \ @@ -67,36 +64,36 @@ template<> struct mkl_llt \ template<> struct llt_inplace \ { \ template \ - static typename MatrixType::Index blocked(MatrixType& m) \ + static Index blocked(MatrixType& m) \ { \ - return mkl_llt::potrf(m, 'L'); \ + return lapacke_llt::potrf(m, 'L'); \ } \ template \ - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } \ }; \ template<> struct llt_inplace \ { \ template \ - static typename MatrixType::Index blocked(MatrixType& m) \ + static Index blocked(MatrixType& m) \ { \ - return mkl_llt::potrf(m, 'U'); \ + return lapacke_llt::potrf(m, 'U'); \ } \ template \ - static typename MatrixType::Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ + static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \ { \ Transpose matt(mat); \ return llt_inplace::rankUpdate(matt, vec.conjugate(), sigma); \ } \ }; -EIGEN_MKL_LLT(double, double, d) -EIGEN_MKL_LLT(float, float, s) -EIGEN_MKL_LLT(dcomplex, MKL_Complex16, z) -EIGEN_MKL_LLT(scomplex, MKL_Complex8, c) +EIGEN_LAPACKE_LLT(double, double, d) +EIGEN_LAPACKE_LLT(float, float, s) +EIGEN_LAPACKE_LLT(dcomplex, lapack_complex_double, z) +EIGEN_LAPACKE_LLT(scomplex, lapack_complex_float, c) } // end namespace internal } // end namespace Eigen -#endif // EIGEN_LLT_MKL_H +#endif // EIGEN_LLT_LAPACKE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt deleted file mode 100644 index 814dfa613..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CMakeLists.txt +++ /dev/null @@ -1,6 +0,0 @@ -FILE(GLOB Eigen_CholmodSupport_SRCS "*.h") - -INSTALL(FILES - ${Eigen_CholmodSupport_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/CholmodSupport COMPONENT Devel - ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h index 99dbe171c..571972023 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/CholmodSupport/CholmodSupport.h @@ -14,46 +14,52 @@ namespace Eigen { namespace internal { -template -void cholmod_configure_matrix(CholmodType& mat) -{ - if (internal::is_same::value) - { - mat.xtype = CHOLMOD_REAL; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same::value) - { +template struct cholmod_configure_matrix; + +template<> struct cholmod_configure_matrix { + template + static void run(CholmodType& mat) { mat.xtype = CHOLMOD_REAL; mat.dtype = CHOLMOD_DOUBLE; } - else if (internal::is_same >::value) - { - mat.xtype = CHOLMOD_COMPLEX; - mat.dtype = CHOLMOD_SINGLE; - } - else if (internal::is_same >::value) - { +}; + +template<> struct cholmod_configure_matrix > { + template + static void run(CholmodType& mat) { mat.xtype = CHOLMOD_COMPLEX; mat.dtype = CHOLMOD_DOUBLE; } - else - { - eigen_assert(false && "Scalar type not supported by CHOLMOD"); - } -} +}; + +// Other scalar types are not yet suppotred by Cholmod +// template<> struct cholmod_configure_matrix { +// template +// static void run(CholmodType& mat) { +// mat.xtype = CHOLMOD_REAL; +// mat.dtype = CHOLMOD_SINGLE; +// } +// }; +// +// template<> struct cholmod_configure_matrix > { +// template +// static void run(CholmodType& mat) { +// mat.xtype = CHOLMOD_COMPLEX; +// mat.dtype = CHOLMOD_SINGLE; +// } +// }; } // namespace internal /** Wraps the Eigen sparse matrix \a mat into a Cholmod sparse matrix object. * Note that the data are shared. */ -template -cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) +template +cholmod_sparse viewAsCholmod(Ref > mat) { cholmod_sparse res; res.nzmax = mat.nonZeros(); - res.nrow = mat.rows();; + res.nrow = mat.rows(); res.ncol = mat.cols(); res.p = mat.outerIndexPtr(); res.i = mat.innerIndexPtr(); @@ -74,11 +80,11 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) res.dtype = 0; res.stype = -1; - if (internal::is_same<_Index,int>::value) + if (internal::is_same<_StorageIndex,int>::value) { res.itype = CHOLMOD_INT; } - else if (internal::is_same<_Index,SuiteSparse_long>::value) + else if (internal::is_same<_StorageIndex,long>::value) { res.itype = CHOLMOD_LONG; } @@ -88,7 +94,7 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) } // setup res.xtype - internal::cholmod_configure_matrix<_Scalar>(res); + internal::cholmod_configure_matrix<_Scalar>::run(res); res.stype = 0; @@ -98,16 +104,23 @@ cholmod_sparse viewAsCholmod(SparseMatrix<_Scalar,_Options,_Index>& mat) template const cholmod_sparse viewAsCholmod(const SparseMatrix<_Scalar,_Options,_Index>& mat) { - cholmod_sparse res = viewAsCholmod(mat.const_cast_derived()); + cholmod_sparse res = viewAsCholmod(Ref >(mat.const_cast_derived())); + return res; +} + +template +const cholmod_sparse viewAsCholmod(const SparseVector<_Scalar,_Options,_Index>& mat) +{ + cholmod_sparse res = viewAsCholmod(Ref >(mat.const_cast_derived())); return res; } /** Returns a view of the Eigen sparse matrix \a mat as Cholmod sparse matrix. * The data are not copied but shared. */ template -cholmod_sparse viewAsCholmod(const SparseSelfAdjointView, UpLo>& mat) +cholmod_sparse viewAsCholmod(const SparseSelfAdjointView, UpLo>& mat) { - cholmod_sparse res = viewAsCholmod(mat.matrix().const_cast_derived()); + cholmod_sparse res = viewAsCholmod(Ref >(mat.matrix().const_cast_derived())); if(UpLo==Upper) res.stype = 1; if(UpLo==Lower) res.stype = -1; @@ -131,19 +144,19 @@ cholmod_dense viewAsCholmod(MatrixBase& mat) res.x = (void*)(mat.derived().data()); res.z = 0; - internal::cholmod_configure_matrix(res); + internal::cholmod_configure_matrix::run(res); return res; } /** Returns a view of the Cholmod sparse matrix \a cm as an Eigen sparse matrix. * The data are not copied but shared. */ -template -MappedSparseMatrix viewAsEigen(cholmod_sparse& cm) +template +MappedSparseMatrix viewAsEigen(cholmod_sparse& cm) { - return MappedSparseMatrix - (cm.nrow, cm.ncol, static_cast(cm.p)[cm.ncol], - static_cast(cm.p), static_cast(cm.i),static_cast(cm.x) ); + return MappedSparseMatrix + (cm.nrow, cm.ncol, static_cast(cm.p)[cm.ncol], + static_cast(cm.p), static_cast(cm.i),static_cast(cm.x) ); } enum CholmodMode { @@ -157,29 +170,39 @@ enum CholmodMode { * \sa class CholmodSupernodalLLT, class CholmodSimplicialLDLT, class CholmodSimplicialLLT */ template -class CholmodBase : internal::noncopyable +class CholmodBase : public SparseSolverBase { + protected: + typedef SparseSolverBase Base; + using Base::derived; + using Base::m_isInitialized; public: typedef _MatrixType MatrixType; enum { UpLo = _UpLo }; typedef typename MatrixType::Scalar Scalar; typedef typename MatrixType::RealScalar RealScalar; typedef MatrixType CholMatrixType; - typedef typename MatrixType::Index Index; + typedef typename MatrixType::StorageIndex StorageIndex; + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime, + MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime + }; public: CholmodBase() - : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) + : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false) { - m_shiftOffset[0] = m_shiftOffset[1] = RealScalar(0.0); + EIGEN_STATIC_ASSERT((internal::is_same::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY); + m_shiftOffset[0] = m_shiftOffset[1] = 0.0; cholmod_start(&m_cholmod); } - CholmodBase(const MatrixType& matrix) - : m_cholmodFactor(0), m_info(Success), m_isInitialized(false) + explicit CholmodBase(const MatrixType& matrix) + : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false) { - m_shiftOffset[0] = m_shiftOffset[1] = RealScalar(0.0); + EIGEN_STATIC_ASSERT((internal::is_same::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY); + m_shiftOffset[0] = m_shiftOffset[1] = 0.0; cholmod_start(&m_cholmod); compute(matrix); } @@ -191,11 +214,8 @@ class CholmodBase : internal::noncopyable cholmod_finish(&m_cholmod); } - inline Index cols() const { return m_cholmodFactor->n; } - inline Index rows() const { return m_cholmodFactor->n; } - - Derived& derived() { return *static_cast(this); } - const Derived& derived() const { return *static_cast(this); } + inline StorageIndex cols() const { return internal::convert_index(m_cholmodFactor->n); } + inline StorageIndex rows() const { return internal::convert_index(m_cholmodFactor->n); } /** \brief Reports whether previous computation was successful. * @@ -216,34 +236,6 @@ class CholmodBase : internal::noncopyable return derived(); } - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ - template - inline const internal::solve_retval - solve(const MatrixBase& b) const - { - eigen_assert(m_isInitialized && "LLT is not initialized."); - eigen_assert(rows()==b.rows() - && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::solve_retval(*this, b.derived()); - } - - /** \returns the solution x of \f$ A x = b \f$ using the current decomposition of A. - * - * \sa compute() - */ - template - inline const internal::sparse_solve_retval - solve(const SparseMatrixBase& b) const - { - eigen_assert(m_isInitialized && "LLT is not initialized."); - eigen_assert(rows()==b.rows() - && "CholmodDecomposition::solve(): invalid number of rows of the right hand side matrix b"); - return internal::sparse_solve_retval(*this, b.derived()); - } - /** Performs a symbolic decomposition on the sparsity pattern of \a matrix. * * This function is particularly useful when solving for several problems having the same structure. @@ -277,7 +269,7 @@ class CholmodBase : internal::noncopyable eigen_assert(m_analysisIsOk && "You must first call analyzePattern()"); cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView()); cholmod_factorize_p(&A, m_shiftOffset, 0, 0, m_cholmodFactor, &m_cholmod); - + // If the factorization failed, minor is the column at which it did. On success minor == n. this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue); m_factorizationIsOk = true; @@ -290,20 +282,22 @@ class CholmodBase : internal::noncopyable #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal */ template - void _solve(const MatrixBase &b, MatrixBase &dest) const + void _solve_impl(const MatrixBase &b, MatrixBase &dest) const { eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); const Index size = m_cholmodFactor->n; EIGEN_UNUSED_VARIABLE(size); eigen_assert(size==b.rows()); + + // Cholmod needs column-major stoarge without inner-stride, which corresponds to the default behavior of Ref. + Ref > b_ref(b.derived()); - // note: cd stands for Cholmod Dense - Rhs& b_ref(b.const_cast_derived()); cholmod_dense b_cd = viewAsCholmod(b_ref); cholmod_dense* x_cd = cholmod_solve(CHOLMOD_A, m_cholmodFactor, &b_cd, &m_cholmod); if(!x_cd) { this->m_info = NumericalIssue; + return; } // TODO optimize this copy by swapping when possible (be careful with alignment, etc.) dest = Matrix::Map(reinterpret_cast(x_cd->x),b.rows(),b.cols()); @@ -311,8 +305,8 @@ class CholmodBase : internal::noncopyable } /** \internal */ - template - void _solve(const SparseMatrix &b, SparseMatrix &dest) const + template + void _solve_impl(const SparseMatrixBase &b, SparseMatrixBase &dest) const { eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); const Index size = m_cholmodFactor->n; @@ -320,14 +314,16 @@ class CholmodBase : internal::noncopyable eigen_assert(size==b.rows()); // note: cs stands for Cholmod Sparse - cholmod_sparse b_cs = viewAsCholmod(b); + Ref > b_ref(b.const_cast_derived()); + cholmod_sparse b_cs = viewAsCholmod(b_ref); cholmod_sparse* x_cs = cholmod_spsolve(CHOLMOD_A, m_cholmodFactor, &b_cs, &m_cholmod); if(!x_cs) { this->m_info = NumericalIssue; + return; } // TODO optimize this copy by swapping when possible (be careful with alignment, etc.) - dest = viewAsEigen(*x_cs); + dest.derived() = viewAsEigen(*x_cs); cholmod_free_sparse(&x_cs, &m_cholmod); } #endif // EIGEN_PARSED_BY_DOXYGEN @@ -344,10 +340,61 @@ class CholmodBase : internal::noncopyable */ Derived& setShift(const RealScalar& offset) { - m_shiftOffset[0] = offset; + m_shiftOffset[0] = double(offset); return derived(); } + /** \returns the determinant of the underlying matrix from the current factorization */ + Scalar determinant() const + { + using std::exp; + return exp(logDeterminant()); + } + + /** \returns the log determinant of the underlying matrix from the current factorization */ + Scalar logDeterminant() const + { + using std::log; + using numext::real; + eigen_assert(m_factorizationIsOk && "The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()"); + + RealScalar logDet = 0; + Scalar *x = static_cast(m_cholmodFactor->x); + if (m_cholmodFactor->is_super) + { + // Supernodal factorization stored as a packed list of dense column-major blocs, + // as described by the following structure: + + // super[k] == index of the first column of the j-th super node + StorageIndex *super = static_cast(m_cholmodFactor->super); + // pi[k] == offset to the description of row indices + StorageIndex *pi = static_cast(m_cholmodFactor->pi); + // px[k] == offset to the respective dense block + StorageIndex *px = static_cast(m_cholmodFactor->px); + + Index nb_super_nodes = m_cholmodFactor->nsuper; + for (Index k=0; k < nb_super_nodes; ++k) + { + StorageIndex ncols = super[k + 1] - super[k]; + StorageIndex nrows = pi[k + 1] - pi[k]; + + Map, 0, InnerStride<> > sk(x + px[k], ncols, InnerStride<>(nrows+1)); + logDet += sk.real().log().sum(); + } + } + else + { + // Simplicial factorization stored as standard CSC matrix. + StorageIndex *p = static_cast(m_cholmodFactor->p); + Index size = m_cholmodFactor->n; + for (Index k=0; kis_ll) + logDet *= 2.0; + return logDet; + }; + template void dumpMemory(Stream& /*s*/) {} @@ -355,9 +402,8 @@ class CholmodBase : internal::noncopyable protected: mutable cholmod_common m_cholmod; cholmod_factor* m_cholmodFactor; - RealScalar m_shiftOffset[2]; + double m_shiftOffset[2]; mutable ComputationInfo m_info; - bool m_isInitialized; int m_factorizationIsOk; int m_analysisIsOk; }; @@ -376,9 +422,13 @@ class CholmodBase : internal::noncopyable * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLLT + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLLT */ template class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT<_MatrixType, _UpLo> > @@ -395,7 +445,7 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl CholmodSimplicialLLT(const MatrixType& matrix) : Base() { init(); - Base::compute(matrix); + this->compute(matrix); } ~CholmodSimplicialLLT() {} @@ -423,9 +473,13 @@ class CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimpl * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers, class CholmodSupernodalLLT, class SimplicialLDLT + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLDLT */ template class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT<_MatrixType, _UpLo> > @@ -442,7 +496,7 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp CholmodSimplicialLDLT(const MatrixType& matrix) : Base() { init(); - Base::compute(matrix); + this->compute(matrix); } ~CholmodSimplicialLDLT() {} @@ -468,9 +522,13 @@ class CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimp * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept */ template class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT<_MatrixType, _UpLo> > @@ -487,7 +545,7 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper CholmodSupernodalLLT(const MatrixType& matrix) : Base() { init(); - Base::compute(matrix); + this->compute(matrix); } ~CholmodSupernodalLLT() {} @@ -515,9 +573,13 @@ class CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSuper * \tparam _UpLo the triangular part that will be used for the computations. It can be Lower * or Upper. Default is Lower. * + * \implsparsesolverconcept + * * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed. * - * \sa \ref TutorialSparseDirectSolvers + * \warning Only double precision real and complex scalar types are supported by Cholmod. + * + * \sa \ref TutorialSparseSolverConcept */ template class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecomposition<_MatrixType, _UpLo> > @@ -534,7 +596,7 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom CholmodDecomposition(const MatrixType& matrix) : Base() { init(); - Base::compute(matrix); + this->compute(matrix); } ~CholmodDecomposition() {} @@ -572,36 +634,6 @@ class CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecom } }; -namespace internal { - -template -struct solve_retval, Rhs> - : solve_retval_base, Rhs> -{ - typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; - EIGEN_MAKE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -template -struct sparse_solve_retval, Rhs> - : sparse_solve_retval_base, Rhs> -{ - typedef CholmodBase<_MatrixType,_UpLo,Derived> Dec; - EIGEN_MAKE_SPARSE_SOLVE_HELPERS(Dec,Rhs) - - template void evalTo(Dest& dst) const - { - dec()._solve(rhs(),dst); - } -}; - -} // end namespace internal - } // end namespace Eigen #endif // EIGEN_CHOLMODSUPPORT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h index 0b9c38c82..e10020d4f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Array.h @@ -12,7 +12,16 @@ namespace Eigen { -/** \class Array +namespace internal { +template +struct traits > : traits > +{ + typedef ArrayXpr XprKind; + typedef ArrayBase > XprBase; +}; +} + +/** \class Array * \ingroup Core_Module * * \brief General-purpose arrays with easy API for coefficient-wise operations @@ -24,20 +33,14 @@ namespace Eigen { * API for the %Matrix class provides easy access to linear-algebra * operations. * - * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_ARRAY_PLUGIN. + * See documentation of class Matrix for detailed information on the template parameters + * storage layout. * - * \sa \ref TutorialArrayClass, \ref TopicClassHierarchy + * This class can be extended with the help of the plugin mechanism described on the page + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_ARRAY_PLUGIN. + * + * \sa \blank \ref TutorialArrayClass, \ref TopicClassHierarchy */ -namespace internal { -template -struct traits > : traits > -{ - typedef ArrayXpr XprKind; - typedef ArrayBase > XprBase; -}; -} - template class Array : public PlainObjectBase > @@ -69,11 +72,27 @@ class Array * the usage of 'using'. This should be done only for operator=. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array& operator=(const EigenBase &other) { return Base::operator=(other); } + /** Set all the entries to \a value. + * \sa DenseBase::setConstant(), DenseBase::fill() + */ + /* This overload is needed because the usage of + * using Base::operator=; + * fails on MSVC. Since the code below is working with GCC and MSVC, we skipped + * the usage of 'using'. This should be done only for operator=. + */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array& operator=(const Scalar &value) + { + Base::setConstant(value); + return *this; + } + /** Copies the value of the expression \a other into \c *this with automatic resizing. * * *this might be resized to match the dimensions of \a other. If *this was a null matrix (not already initialized), @@ -84,7 +103,8 @@ class Array * remain row-vectors and vectors remain vectors. */ template - EIGEN_STRONG_INLINE Array& operator=(const ArrayBase& other) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array& operator=(const DenseBase& other) { return Base::_set(other); } @@ -92,11 +112,12 @@ class Array /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array& operator=(const Array& other) { return Base::_set(other); } - + /** Default constructor. * * For fixed-size matrices, does nothing. @@ -107,6 +128,7 @@ class Array * * \sa resize(Index,Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array() : Base() { Base::_check_template_params(); @@ -116,6 +138,7 @@ class Array #ifndef EIGEN_PARSED_BY_DOXYGEN // FIXME is it still needed ?? /** \internal */ + EIGEN_DEVICE_FUNC Array(internal::constructor_without_unaligned_array_assert) : Base(internal::constructor_without_unaligned_array_assert()) { @@ -124,56 +147,64 @@ class Array } #endif -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - Array(Array&& other) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + Array(Array&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) : Base(std::move(other)) { Base::_check_template_params(); if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) Base::_set_noalias(other); } - Array& operator=(Array&& other) + EIGEN_DEVICE_FUNC + Array& operator=(Array&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) { other.swap(*this); return *this; } #endif - /** Constructs a vector or row-vector with given dimension. \only_for_vectors - * - * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, - * it is redundant to pass the dimension here, so it makes more sense to use the default - * constructor Matrix() instead. - */ - EIGEN_STRONG_INLINE explicit Array(Index dim) - : Base(dim, RowsAtCompileTime == 1 ? 1 : dim, ColsAtCompileTime == 1 ? 1 : dim) + #ifndef EIGEN_PARSED_BY_DOXYGEN + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Array(const T& x) { Base::_check_template_params(); - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Array) - eigen_assert(dim >= 0); - eigen_assert(SizeAtCompileTime == Dynamic || SizeAtCompileTime == dim); - EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + Base::template _init1(x); } - #ifndef EIGEN_PARSED_BY_DOXYGEN template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const T0& val0, const T1& val1) { Base::_check_template_params(); this->template _init2(val0, val1); } #else - /** constructs an uninitialized matrix with \a rows rows and \a cols columns. + /** \brief Constructs a fixed-sized array initialized with coefficients starting at \a data */ + EIGEN_DEVICE_FUNC explicit Array(const Scalar *data); + /** Constructs a vector or row-vector with given dimension. \only_for_vectors * - * This is useful for dynamic-size matrices. For fixed-size matrices, + * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, + * it is redundant to pass the dimension here, so it makes more sense to use the default + * constructor Array() instead. + */ + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Array(Index dim); + /** constructs an initialized 1x1 Array with the given coefficient */ + Array(const Scalar& value); + /** constructs an uninitialized array with \a rows rows and \a cols columns. + * + * This is useful for dynamic-size arrays. For fixed-size arrays, * it is redundant to pass these parameters, so one should use the default constructor - * Matrix() instead. */ + * Array() instead. */ Array(Index rows, Index cols); /** constructs an initialized 2D vector with given coefficients */ Array(const Scalar& val0, const Scalar& val1); #endif /** constructs an initialized 3D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2) { Base::_check_template_params(); @@ -183,6 +214,7 @@ class Array m_storage.data()[2] = val2; } /** constructs an initialized 4D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Scalar& val0, const Scalar& val1, const Scalar& val2, const Scalar& val3) { Base::_check_template_params(); @@ -193,51 +225,27 @@ class Array m_storage.data()[3] = val3; } - explicit Array(const Scalar *data); - - /** Constructor copying the value of the expression \a other */ - template - EIGEN_STRONG_INLINE Array(const ArrayBase& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } /** Copy constructor */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Array(const Array& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } - /** Copy constructor with in-place evaluation */ - template - EIGEN_STRONG_INLINE Array(const ReturnByValue& other) - { - Base::_check_template_params(); - Base::resize(other.rows(), other.cols()); - other.evalTo(*this); - } + : Base(other) + { } + + private: + struct PrivateType {}; + public: /** \sa MatrixBase::operator=(const EigenBase&) */ template - EIGEN_STRONG_INLINE Array(const EigenBase &other) - : Base(other.derived().rows() * other.derived().cols(), other.derived().rows(), other.derived().cols()) - { - Base::_check_template_params(); - Base::_resize_to_match(other); - *this = other; - } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Array(const EigenBase &other, + typename internal::enable_if::value, + PrivateType>::type = PrivateType()) + : Base(other.derived()) + { } - /** Override MatrixBase::swap() since for dynamic-sized matrices of same type it is enough to swap the - * data pointers. - */ - template - void swap(ArrayBase const & other) - { this->_swap(other.derived()); } - - inline Index innerStride() const { return 1; } - inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } #ifdef EIGEN_ARRAY_PLUGIN #include EIGEN_ARRAY_PLUGIN diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h index 33ff55371..3dbc7084c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayBase.h @@ -32,7 +32,7 @@ template class MatrixWrapper; * \tparam Derived is the derived type, e.g., an array or an expression type. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_ARRAYBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_ARRAYBASE_PLUGIN. * * \sa class MatrixBase, \ref TopicClassHierarchy */ @@ -47,13 +47,11 @@ template class ArrayBase typedef ArrayBase Eigen_BaseClassForSpecializationOfGlobalMathFuncImpl; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; typedef DenseBase Base; - using Base::operator*; using Base::RowsAtCompileTime; using Base::ColsAtCompileTime; using Base::SizeAtCompileTime; @@ -62,8 +60,7 @@ template class ArrayBase using Base::MaxSizeAtCompileTime; using Base::IsVectorAtCompileTime; using Base::Flags; - using Base::CoeffReadCost; - + using Base::derived; using Base::const_cast_derived; using Base::rows; @@ -83,25 +80,14 @@ template class ArrayBase #endif // not EIGEN_PARSED_BY_DOXYGEN #ifndef EIGEN_PARSED_BY_DOXYGEN - /** \internal the plain matrix type corresponding to this expression. Note that is not necessarily - * exactly the return type of eval(): in the case of plain matrices, the return type of eval() is a const - * reference to a matrix, not a matrix! It is however guaranteed that the return type of eval() is either - * PlainObject or const PlainObject&. - */ - typedef Array::Scalar, - internal::traits::RowsAtCompileTime, - internal::traits::ColsAtCompileTime, - AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), - internal::traits::MaxRowsAtCompileTime, - internal::traits::MaxColsAtCompileTime - > PlainObject; - + typedef typename Base::PlainObject PlainObject; /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; #endif // not EIGEN_PARSED_BY_DOXYGEN #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::ArrayBase +#define EIGEN_DOC_UNARY_ADDONS(X,Y) # include "../plugins/CommonCwiseUnaryOps.h" # include "../plugins/MatrixCwiseUnaryOps.h" # include "../plugins/ArrayCwiseUnaryOps.h" @@ -112,44 +98,62 @@ template class ArrayBase # include EIGEN_ARRAYBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS +#undef EIGEN_DOC_UNARY_ADDONS /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const ArrayBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } + + /** Set all the entries to \a value. + * \sa DenseBase::setConstant(), DenseBase::fill() */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator=(const Scalar &value) + { Base::setConstant(value); return derived(); } - Derived& operator+=(const Scalar& scalar) - { return *this = derived() + scalar; } - Derived& operator-=(const Scalar& scalar) - { return *this = derived() - scalar; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator+=(const Scalar& scalar); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator-=(const Scalar& scalar); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator+=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator-=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator*=(const ArrayBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator/=(const ArrayBase& other); public: + EIGEN_DEVICE_FUNC ArrayBase& array() { return *this; } + EIGEN_DEVICE_FUNC const ArrayBase& array() const { return *this; } /** \returns an \link Eigen::MatrixBase Matrix \endlink expression of this array * \sa MatrixBase::array() */ - MatrixWrapper matrix() { return derived(); } - const MatrixWrapper matrix() const { return derived(); } + EIGEN_DEVICE_FUNC + MatrixWrapper matrix() { return MatrixWrapper(derived()); } + EIGEN_DEVICE_FUNC + const MatrixWrapper matrix() const { return MatrixWrapper(derived()); } // template // inline void evalTo(Dest& dst) const { dst = matrix(); } protected: + EIGEN_DEVICE_FUNC ArrayBase() : Base() {} private: @@ -171,11 +175,10 @@ template class ArrayBase */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator-=(const ArrayBase &other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } @@ -185,11 +188,10 @@ ArrayBase::operator-=(const ArrayBase &other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator+=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } @@ -199,11 +201,10 @@ ArrayBase::operator+=(const ArrayBase& other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator*=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::mul_assign_op()); return derived(); } @@ -213,11 +214,10 @@ ArrayBase::operator*=(const ArrayBase& other) */ template template -EIGEN_STRONG_INLINE Derived & +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived & ArrayBase::operator/=(const ArrayBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::div_assign_op()); return derived(); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h index b4641e2a0..688aadd62 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ArrayWrapper.h @@ -32,7 +32,8 @@ struct traits > // Let's remove NestByRefBit enum { Flags0 = traits::type >::Flags, - Flags = Flags0 & ~NestByRefBit + LvalueBitFlag = is_lvalue::value ? LvalueBit : 0, + Flags = (Flags0 & ~(NestByRefBit | LvalueBit)) | LvalueBitFlag }; }; } @@ -44,6 +45,7 @@ class ArrayWrapper : public ArrayBase > typedef ArrayBase Base; EIGEN_DENSE_PUBLIC_INTERFACE(ArrayWrapper) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(ArrayWrapper) + typedef typename internal::remove_all::type NestedExpression; typedef typename internal::conditional< internal::is_lvalue::value, @@ -51,76 +53,45 @@ class ArrayWrapper : public ArrayBase > const Scalar >::type ScalarWithConstIfNotLvalue; - typedef typename internal::nested::type NestedExpressionType; + typedef typename internal::ref_selector::non_const_type NestedExpressionType; - inline ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} + using Base::coeffRef; + EIGEN_DEVICE_FUNC + explicit EIGEN_STRONG_INLINE ArrayWrapper(ExpressionType& matrix) : m_expression(matrix) {} + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline ScalarWithConstIfNotLvalue* data() { return m_expression.const_cast_derived().data(); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_expression.data(); } - inline CoeffReturnType coeff(Index rowId, Index colId) const - { - return m_expression.coeff(rowId, colId); - } - - inline Scalar& coeffRef(Index rowId, Index colId) - { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_expression.coeff(index); - } - - inline Scalar& coeffRef(Index index) - { - return m_expression.const_cast_derived().coeffRef(index); + return m_expression.coeffRef(rowId, colId); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { - return m_expression.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index rowId, Index colId) const - { - return m_expression.template packet(rowId, colId); - } - - template - inline void writePacket(Index rowId, Index colId, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(rowId, colId, val); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_expression.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(index, val); + return m_expression.coeffRef(index); } template + EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { dst = m_expression; } const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC nestedExpression() const { return m_expression; @@ -128,10 +99,12 @@ class ArrayWrapper : public ArrayBase > /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index) */ - void resize(Index newSize) { m_expression.const_cast_derived().resize(newSize); } + EIGEN_DEVICE_FUNC + void resize(Index newSize) { m_expression.resize(newSize); } /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index,Index)*/ - void resize(Index nbRows, Index nbCols) { m_expression.const_cast_derived().resize(nbRows,nbCols); } + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { m_expression.resize(rows,cols); } protected: NestedExpressionType m_expression; @@ -157,7 +130,8 @@ struct traits > // Let's remove NestByRefBit enum { Flags0 = traits::type >::Flags, - Flags = Flags0 & ~NestByRefBit + LvalueBitFlag = is_lvalue::value ? LvalueBit : 0, + Flags = (Flags0 & ~(NestByRefBit | LvalueBit)) | LvalueBitFlag }; }; } @@ -169,6 +143,7 @@ class MatrixWrapper : public MatrixBase > typedef MatrixBase > Base; EIGEN_DENSE_PUBLIC_INTERFACE(MatrixWrapper) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(MatrixWrapper) + typedef typename internal::remove_all::type NestedExpression; typedef typename internal::conditional< internal::is_lvalue::value, @@ -176,72 +151,40 @@ class MatrixWrapper : public MatrixBase > const Scalar >::type ScalarWithConstIfNotLvalue; - typedef typename internal::nested::type NestedExpressionType; + typedef typename internal::ref_selector::non_const_type NestedExpressionType; - inline MatrixWrapper(ExpressionType& a_matrix) : m_expression(a_matrix) {} + using Base::coeffRef; + EIGEN_DEVICE_FUNC + explicit inline MatrixWrapper(ExpressionType& matrix) : m_expression(matrix) {} + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline ScalarWithConstIfNotLvalue* data() { return m_expression.const_cast_derived().data(); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return m_expression.data(); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_expression.data(); } - inline CoeffReturnType coeff(Index rowId, Index colId) const - { - return m_expression.coeff(rowId, colId); - } - - inline Scalar& coeffRef(Index rowId, Index colId) - { - return m_expression.const_cast_derived().coeffRef(rowId, colId); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { return m_expression.derived().coeffRef(rowId, colId); } - inline CoeffReturnType coeff(Index index) const - { - return m_expression.coeff(index); - } - - inline Scalar& coeffRef(Index index) - { - return m_expression.const_cast_derived().coeffRef(index); - } - + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { - return m_expression.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index rowId, Index colId) const - { - return m_expression.template packet(rowId, colId); - } - - template - inline void writePacket(Index rowId, Index colId, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(rowId, colId, val); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_expression.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& val) - { - m_expression.const_cast_derived().template writePacket(index, val); + return m_expression.coeffRef(index); } + EIGEN_DEVICE_FUNC const typename internal::remove_all::type& nestedExpression() const { @@ -250,10 +193,12 @@ class MatrixWrapper : public MatrixBase > /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index) */ - void resize(Index newSize) { m_expression.const_cast_derived().resize(newSize); } + EIGEN_DEVICE_FUNC + void resize(Index newSize) { m_expression.resize(newSize); } /** Forwards the resizing request to the nested expression * \sa DenseBase::resize(Index,Index)*/ - void resize(Index nbRows, Index nbCols) { m_expression.const_cast_derived().resize(nbRows,nbCols); } + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { m_expression.resize(rows,cols); } protected: NestedExpressionType m_expression; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h index f48173172..53806ba33 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign.h @@ -14,478 +14,6 @@ namespace Eigen { -namespace internal { - -/*************************************************************************** -* Part 1 : the logic deciding a strategy for traversal and unrolling * -***************************************************************************/ - -template -struct assign_traits -{ -public: - enum { - DstIsAligned = Derived::Flags & AlignedBit, - DstHasDirectAccess = Derived::Flags & DirectAccessBit, - SrcIsAligned = OtherDerived::Flags & AlignedBit, - JointAlignment = bool(DstIsAligned) && bool(SrcIsAligned) ? Aligned : Unaligned - }; - -private: - enum { - InnerSize = int(Derived::IsVectorAtCompileTime) ? int(Derived::SizeAtCompileTime) - : int(Derived::Flags)&RowMajorBit ? int(Derived::ColsAtCompileTime) - : int(Derived::RowsAtCompileTime), - InnerMaxSize = int(Derived::IsVectorAtCompileTime) ? int(Derived::MaxSizeAtCompileTime) - : int(Derived::Flags)&RowMajorBit ? int(Derived::MaxColsAtCompileTime) - : int(Derived::MaxRowsAtCompileTime), - MaxSizeAtCompileTime = Derived::SizeAtCompileTime, - PacketSize = packet_traits::size - }; - - enum { - StorageOrdersAgree = (int(Derived::IsRowMajor) == int(OtherDerived::IsRowMajor)), - MightVectorize = StorageOrdersAgree - && (int(Derived::Flags) & int(OtherDerived::Flags) & ActualPacketAccessBit), - MayInnerVectorize = MightVectorize && int(InnerSize)!=Dynamic && int(InnerSize)%int(PacketSize)==0 - && int(DstIsAligned) && int(SrcIsAligned), - MayLinearize = StorageOrdersAgree && (int(Derived::Flags) & int(OtherDerived::Flags) & LinearAccessBit), - MayLinearVectorize = MightVectorize && MayLinearize && DstHasDirectAccess - && (DstIsAligned || MaxSizeAtCompileTime == Dynamic), - /* If the destination isn't aligned, we have to do runtime checks and we don't unroll, - so it's only good for large enough sizes. */ - MaySliceVectorize = MightVectorize && DstHasDirectAccess - && (int(InnerMaxSize)==Dynamic || int(InnerMaxSize)>=3*PacketSize) - /* slice vectorization can be slow, so we only want it if the slices are big, which is - indicated by InnerMaxSize rather than InnerSize, think of the case of a dynamic block - in a fixed-size matrix */ - }; - -public: - enum { - Traversal = int(MayInnerVectorize) ? int(InnerVectorizedTraversal) - : int(MayLinearVectorize) ? int(LinearVectorizedTraversal) - : int(MaySliceVectorize) ? int(SliceVectorizedTraversal) - : int(MayLinearize) ? int(LinearTraversal) - : int(DefaultTraversal), - Vectorized = int(Traversal) == InnerVectorizedTraversal - || int(Traversal) == LinearVectorizedTraversal - || int(Traversal) == SliceVectorizedTraversal - }; - -private: - enum { - UnrollingLimit = EIGEN_UNROLLING_LIMIT * (Vectorized ? int(PacketSize) : 1), - MayUnrollCompletely = int(Derived::SizeAtCompileTime) != Dynamic - && int(OtherDerived::CoeffReadCost) != Dynamic - && int(Derived::SizeAtCompileTime) * int(OtherDerived::CoeffReadCost) <= int(UnrollingLimit), - MayUnrollInner = int(InnerSize) != Dynamic - && int(OtherDerived::CoeffReadCost) != Dynamic - && int(InnerSize) * int(OtherDerived::CoeffReadCost) <= int(UnrollingLimit) - }; - -public: - enum { - Unrolling = (int(Traversal) == int(InnerVectorizedTraversal) || int(Traversal) == int(DefaultTraversal)) - ? ( - int(MayUnrollCompletely) ? int(CompleteUnrolling) - : int(MayUnrollInner) ? int(InnerUnrolling) - : int(NoUnrolling) - ) - : int(Traversal) == int(LinearVectorizedTraversal) - ? ( bool(MayUnrollCompletely) && bool(DstIsAligned) ? int(CompleteUnrolling) : int(NoUnrolling) ) - : int(Traversal) == int(LinearTraversal) - ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) : int(NoUnrolling) ) - : int(NoUnrolling) - }; - -#ifdef EIGEN_DEBUG_ASSIGN - static void debug() - { - EIGEN_DEBUG_VAR(DstIsAligned) - EIGEN_DEBUG_VAR(SrcIsAligned) - EIGEN_DEBUG_VAR(JointAlignment) - EIGEN_DEBUG_VAR(InnerSize) - EIGEN_DEBUG_VAR(InnerMaxSize) - EIGEN_DEBUG_VAR(PacketSize) - EIGEN_DEBUG_VAR(StorageOrdersAgree) - EIGEN_DEBUG_VAR(MightVectorize) - EIGEN_DEBUG_VAR(MayLinearize) - EIGEN_DEBUG_VAR(MayInnerVectorize) - EIGEN_DEBUG_VAR(MayLinearVectorize) - EIGEN_DEBUG_VAR(MaySliceVectorize) - EIGEN_DEBUG_VAR(Traversal) - EIGEN_DEBUG_VAR(UnrollingLimit) - EIGEN_DEBUG_VAR(MayUnrollCompletely) - EIGEN_DEBUG_VAR(MayUnrollInner) - EIGEN_DEBUG_VAR(Unrolling) - } -#endif -}; - -/*************************************************************************** -* Part 2 : meta-unrollers -***************************************************************************/ - -/************************ -*** Default traversal *** -************************/ - -template -struct assign_DefaultTraversal_CompleteUnrolling -{ - enum { - outer = Index / Derived1::InnerSizeAtCompileTime, - inner = Index % Derived1::InnerSizeAtCompileTime - }; - - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.copyCoeffByOuterInner(outer, inner, src); - assign_DefaultTraversal_CompleteUnrolling::run(dst, src); - } -}; - -template -struct assign_DefaultTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -template -struct assign_DefaultTraversal_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, typename Derived1::Index outer) - { - dst.copyCoeffByOuterInner(outer, Index, src); - assign_DefaultTraversal_InnerUnrolling::run(dst, src, outer); - } -}; - -template -struct assign_DefaultTraversal_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, typename Derived1::Index) {} -}; - -/*********************** -*** Linear traversal *** -***********************/ - -template -struct assign_LinearTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.copyCoeff(Index, src); - assign_LinearTraversal_CompleteUnrolling::run(dst, src); - } -}; - -template -struct assign_LinearTraversal_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -/************************** -*** Inner vectorization *** -**************************/ - -template -struct assign_innervec_CompleteUnrolling -{ - enum { - outer = Index / Derived1::InnerSizeAtCompileTime, - inner = Index % Derived1::InnerSizeAtCompileTime, - JointAlignment = assign_traits::JointAlignment - }; - - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - dst.template copyPacketByOuterInner(outer, inner, src); - assign_innervec_CompleteUnrolling::size, Stop>::run(dst, src); - } -}; - -template -struct assign_innervec_CompleteUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &) {} -}; - -template -struct assign_innervec_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src, typename Derived1::Index outer) - { - dst.template copyPacketByOuterInner(outer, Index, src); - assign_innervec_InnerUnrolling::size, Stop>::run(dst, src, outer); - } -}; - -template -struct assign_innervec_InnerUnrolling -{ - static EIGEN_STRONG_INLINE void run(Derived1 &, const Derived2 &, typename Derived1::Index) {} -}; - -/*************************************************************************** -* Part 3 : implementation of all cases -***************************************************************************/ - -template::Traversal, - int Unrolling = assign_traits::Unrolling, - int Version = Specialized> -struct assign_impl; - -/************************ -*** Default traversal *** -************************/ - -template -struct assign_impl -{ - static inline void run(Derived1 &, const Derived2 &) { } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - for(Index inner = 0; inner < innerSize; ++inner) - dst.copyCoeffByOuterInner(outer, inner, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_DefaultTraversal_CompleteUnrolling - ::run(dst, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - assign_DefaultTraversal_InnerUnrolling - ::run(dst, src, outer); - } -}; - -/*********************** -*** Linear traversal *** -***********************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index size = dst.size(); - for(Index i = 0; i < size; ++i) - dst.copyCoeff(i, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_LinearTraversal_CompleteUnrolling - ::run(dst, src); - } -}; - -/************************** -*** Inner vectorization *** -**************************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - const Index packetSize = packet_traits::size; - for(Index outer = 0; outer < outerSize; ++outer) - for(Index inner = 0; inner < innerSize; inner+=packetSize) - dst.template copyPacketByOuterInner(outer, inner, src); - } -}; - -template -struct assign_impl -{ - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - assign_innervec_CompleteUnrolling - ::run(dst, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) - assign_innervec_InnerUnrolling - ::run(dst, src, outer); - } -}; - -/*************************** -*** Linear vectorization *** -***************************/ - -template -struct unaligned_assign_impl -{ - template - static EIGEN_STRONG_INLINE void run(const Derived&, OtherDerived&, typename Derived::Index, typename Derived::Index) {} -}; - -template <> -struct unaligned_assign_impl -{ - // MSVC must not inline this functions. If it does, it fails to optimize the - // packet access path. -#ifdef _MSC_VER - template - static EIGEN_DONT_INLINE void run(const Derived& src, OtherDerived& dst, typename Derived::Index start, typename Derived::Index end) -#else - template - static EIGEN_STRONG_INLINE void run(const Derived& src, OtherDerived& dst, typename Derived::Index start, typename Derived::Index end) -#endif - { - for (typename Derived::Index index = start; index < end; ++index) - dst.copyCoeff(index, src); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - const Index size = dst.size(); - typedef packet_traits PacketTraits; - enum { - packetSize = PacketTraits::size, - dstAlignment = PacketTraits::AlignedOnScalar ? Aligned : int(assign_traits::DstIsAligned) , - srcAlignment = assign_traits::JointAlignment - }; - const Index alignedStart = assign_traits::DstIsAligned ? 0 - : internal::first_aligned(&dst.coeffRef(0), size); - const Index alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize; - - unaligned_assign_impl::DstIsAligned!=0>::run(src,dst,0,alignedStart); - - for(Index index = alignedStart; index < alignedEnd; index += packetSize) - { - dst.template copyPacket(index, src); - } - - unaligned_assign_impl<>::run(src,dst,alignedEnd,size); - } -}; - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static EIGEN_STRONG_INLINE void run(Derived1 &dst, const Derived2 &src) - { - enum { size = Derived1::SizeAtCompileTime, - packetSize = packet_traits::size, - alignedSize = (size/packetSize)*packetSize }; - - assign_innervec_CompleteUnrolling::run(dst, src); - assign_DefaultTraversal_CompleteUnrolling::run(dst, src); - } -}; - -/************************** -*** Slice vectorization *** -***************************/ - -template -struct assign_impl -{ - typedef typename Derived1::Index Index; - static inline void run(Derived1 &dst, const Derived2 &src) - { - typedef typename Derived1::Scalar Scalar; - typedef packet_traits PacketTraits; - enum { - packetSize = PacketTraits::size, - alignable = PacketTraits::AlignedOnScalar, - dstIsAligned = assign_traits::DstIsAligned, - dstAlignment = alignable ? Aligned : int(dstIsAligned), - srcAlignment = assign_traits::JointAlignment - }; - const Scalar *dst_ptr = &dst.coeffRef(0,0); - if((!bool(dstIsAligned)) && (size_t(dst_ptr) % sizeof(Scalar))>0) - { - // the pointer is not aligend-on scalar, so alignment is not possible - return assign_impl::run(dst, src); - } - const Index packetAlignedMask = packetSize - 1; - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - const Index alignedStep = alignable ? (packetSize - dst.outerStride() % packetSize) & packetAlignedMask : 0; - Index alignedStart = ((!alignable) || bool(dstIsAligned)) ? 0 : internal::first_aligned(dst_ptr, innerSize); - - for(Index outer = 0; outer < outerSize; ++outer) - { - const Index alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask); - // do the non-vectorizable part of the assignment - for(Index inner = 0; inner(outer, inner, src); - - // do the non-vectorizable part of the assignment - for(Index inner = alignedEnd; inner((alignedStart+alignedStep)%packetSize, innerSize); - } - } -}; - -} // end namespace internal - -/*************************************************************************** -* Part 4 : implementation of DenseBase methods -***************************************************************************/ - template template EIGEN_STRONG_INLINE Derived& DenseBase @@ -499,90 +27,62 @@ EIGEN_STRONG_INLINE Derived& DenseBase EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Derived,OtherDerived) EIGEN_STATIC_ASSERT(SameType,YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) -#ifdef EIGEN_DEBUG_ASSIGN - internal::assign_traits::debug(); -#endif eigen_assert(rows() == other.rows() && cols() == other.cols()); - internal::assign_impl::Traversal) - : int(InvalidTraversal)>::run(derived(),other.derived()); -#ifndef EIGEN_NO_DEBUG - checkTransposeAliasing(other.derived()); -#endif + internal::call_assignment_no_alias(derived(),other.derived()); + return derived(); } -namespace internal { - -template::Flags) & EvalBeforeAssigningBit) != 0, - bool NeedToTranspose = ((int(Derived::RowsAtCompileTime) == 1 && int(OtherDerived::ColsAtCompileTime) == 1) - | // FIXME | instead of || to please GCC 4.4.0 stupid warning "suggest parentheses around &&". - // revert to || as soon as not needed anymore. - (int(Derived::ColsAtCompileTime) == 1 && int(OtherDerived::RowsAtCompileTime) == 1)) - && int(Derived::SizeAtCompileTime) != 1> -struct assign_selector; - -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); } - template - static EIGEN_STRONG_INLINE Derived& evalTo(ActualDerived& dst, const ActualOtherDerived& other) { other.evalTo(dst); return dst; } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.eval()); } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose()); } - template - static EIGEN_STRONG_INLINE Derived& evalTo(ActualDerived& dst, const ActualOtherDerived& other) { Transpose dstTrans(dst); other.evalTo(dstTrans); return dst; } -}; -template -struct assign_selector { - static EIGEN_STRONG_INLINE Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.transpose().eval()); } -}; - -} // end namespace internal - template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const MatrixBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const DenseBase& other) { - return internal::assign_selector::run(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const EigenBase& other) { - return internal::assign_selector::evalTo(derived(), other.derived()); + internal::call_assignment(derived(), other.derived()); + return derived(); } template template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::operator=(const ReturnByValue& other) { - return internal::assign_selector::evalTo(derived(), other.derived()); + other.derived().evalTo(derived()); + return derived(); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/AssignEvaluator.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/AssignEvaluator.h new file mode 100644 index 000000000..b0ec7b7ca --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/AssignEvaluator.h @@ -0,0 +1,935 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2011-2014 Gael Guennebaud +// Copyright (C) 2011-2012 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_ASSIGN_EVALUATOR_H +#define EIGEN_ASSIGN_EVALUATOR_H + +namespace Eigen { + +// This implementation is based on Assign.h + +namespace internal { + +/*************************************************************************** +* Part 1 : the logic deciding a strategy for traversal and unrolling * +***************************************************************************/ + +// copy_using_evaluator_traits is based on assign_traits + +template +struct copy_using_evaluator_traits +{ + typedef typename DstEvaluator::XprType Dst; + typedef typename Dst::Scalar DstScalar; + + enum { + DstFlags = DstEvaluator::Flags, + SrcFlags = SrcEvaluator::Flags + }; + +public: + enum { + DstAlignment = DstEvaluator::Alignment, + SrcAlignment = SrcEvaluator::Alignment, + DstHasDirectAccess = DstFlags & DirectAccessBit, + JointAlignment = EIGEN_PLAIN_ENUM_MIN(DstAlignment,SrcAlignment) + }; + +private: + enum { + InnerSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::SizeAtCompileTime) + : int(DstFlags)&RowMajorBit ? int(Dst::ColsAtCompileTime) + : int(Dst::RowsAtCompileTime), + InnerMaxSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::MaxSizeAtCompileTime) + : int(DstFlags)&RowMajorBit ? int(Dst::MaxColsAtCompileTime) + : int(Dst::MaxRowsAtCompileTime), + OuterStride = int(outer_stride_at_compile_time::ret), + MaxSizeAtCompileTime = Dst::SizeAtCompileTime + }; + + // TODO distinguish between linear traversal and inner-traversals + typedef typename find_best_packet::type LinearPacketType; + typedef typename find_best_packet::type InnerPacketType; + + enum { + LinearPacketSize = unpacket_traits::size, + InnerPacketSize = unpacket_traits::size + }; + +public: + enum { + LinearRequiredAlignment = unpacket_traits::alignment, + InnerRequiredAlignment = unpacket_traits::alignment + }; + +private: + enum { + DstIsRowMajor = DstFlags&RowMajorBit, + SrcIsRowMajor = SrcFlags&RowMajorBit, + StorageOrdersAgree = (int(DstIsRowMajor) == int(SrcIsRowMajor)), + MightVectorize = bool(StorageOrdersAgree) + && (int(DstFlags) & int(SrcFlags) & ActualPacketAccessBit) + && bool(functor_traits::PacketAccess), + MayInnerVectorize = MightVectorize + && int(InnerSize)!=Dynamic && int(InnerSize)%int(InnerPacketSize)==0 + && int(OuterStride)!=Dynamic && int(OuterStride)%int(InnerPacketSize)==0 + && (EIGEN_UNALIGNED_VECTORIZE || int(JointAlignment)>=int(InnerRequiredAlignment)), + MayLinearize = bool(StorageOrdersAgree) && (int(DstFlags) & int(SrcFlags) & LinearAccessBit), + MayLinearVectorize = bool(MightVectorize) && MayLinearize && DstHasDirectAccess + && (EIGEN_UNALIGNED_VECTORIZE || (int(DstAlignment)>=int(LinearRequiredAlignment)) || MaxSizeAtCompileTime == Dynamic), + /* If the destination isn't aligned, we have to do runtime checks and we don't unroll, + so it's only good for large enough sizes. */ + MaySliceVectorize = bool(MightVectorize) && bool(DstHasDirectAccess) + && (int(InnerMaxSize)==Dynamic || int(InnerMaxSize)>=(EIGEN_UNALIGNED_VECTORIZE?InnerPacketSize:(3*InnerPacketSize))) + /* slice vectorization can be slow, so we only want it if the slices are big, which is + indicated by InnerMaxSize rather than InnerSize, think of the case of a dynamic block + in a fixed-size matrix + However, with EIGEN_UNALIGNED_VECTORIZE and unrolling, slice vectorization is still worth it */ + }; + +public: + enum { + Traversal = int(MayLinearVectorize) && (LinearPacketSize>InnerPacketSize) ? int(LinearVectorizedTraversal) + : int(MayInnerVectorize) ? int(InnerVectorizedTraversal) + : int(MayLinearVectorize) ? int(LinearVectorizedTraversal) + : int(MaySliceVectorize) ? int(SliceVectorizedTraversal) + : int(MayLinearize) ? int(LinearTraversal) + : int(DefaultTraversal), + Vectorized = int(Traversal) == InnerVectorizedTraversal + || int(Traversal) == LinearVectorizedTraversal + || int(Traversal) == SliceVectorizedTraversal + }; + + typedef typename conditional::type PacketType; + +private: + enum { + ActualPacketSize = int(Traversal)==LinearVectorizedTraversal ? LinearPacketSize + : Vectorized ? InnerPacketSize + : 1, + UnrollingLimit = EIGEN_UNROLLING_LIMIT * ActualPacketSize, + MayUnrollCompletely = int(Dst::SizeAtCompileTime) != Dynamic + && int(Dst::SizeAtCompileTime) * (int(DstEvaluator::CoeffReadCost)+int(SrcEvaluator::CoeffReadCost)) <= int(UnrollingLimit), + MayUnrollInner = int(InnerSize) != Dynamic + && int(InnerSize) * (int(DstEvaluator::CoeffReadCost)+int(SrcEvaluator::CoeffReadCost)) <= int(UnrollingLimit) + }; + +public: + enum { + Unrolling = (int(Traversal) == int(InnerVectorizedTraversal) || int(Traversal) == int(DefaultTraversal)) + ? ( + int(MayUnrollCompletely) ? int(CompleteUnrolling) + : int(MayUnrollInner) ? int(InnerUnrolling) + : int(NoUnrolling) + ) + : int(Traversal) == int(LinearVectorizedTraversal) + ? ( bool(MayUnrollCompletely) && ( EIGEN_UNALIGNED_VECTORIZE || (int(DstAlignment)>=int(LinearRequiredAlignment))) + ? int(CompleteUnrolling) + : int(NoUnrolling) ) + : int(Traversal) == int(LinearTraversal) + ? ( bool(MayUnrollCompletely) ? int(CompleteUnrolling) + : int(NoUnrolling) ) +#if EIGEN_UNALIGNED_VECTORIZE + : int(Traversal) == int(SliceVectorizedTraversal) + ? ( bool(MayUnrollInner) ? int(InnerUnrolling) + : int(NoUnrolling) ) +#endif + : int(NoUnrolling) + }; + +#ifdef EIGEN_DEBUG_ASSIGN + static void debug() + { + std::cerr << "DstXpr: " << typeid(typename DstEvaluator::XprType).name() << std::endl; + std::cerr << "SrcXpr: " << typeid(typename SrcEvaluator::XprType).name() << std::endl; + std::cerr.setf(std::ios::hex, std::ios::basefield); + std::cerr << "DstFlags" << " = " << DstFlags << " (" << demangle_flags(DstFlags) << " )" << std::endl; + std::cerr << "SrcFlags" << " = " << SrcFlags << " (" << demangle_flags(SrcFlags) << " )" << std::endl; + std::cerr.unsetf(std::ios::hex); + EIGEN_DEBUG_VAR(DstAlignment) + EIGEN_DEBUG_VAR(SrcAlignment) + EIGEN_DEBUG_VAR(LinearRequiredAlignment) + EIGEN_DEBUG_VAR(InnerRequiredAlignment) + EIGEN_DEBUG_VAR(JointAlignment) + EIGEN_DEBUG_VAR(InnerSize) + EIGEN_DEBUG_VAR(InnerMaxSize) + EIGEN_DEBUG_VAR(LinearPacketSize) + EIGEN_DEBUG_VAR(InnerPacketSize) + EIGEN_DEBUG_VAR(ActualPacketSize) + EIGEN_DEBUG_VAR(StorageOrdersAgree) + EIGEN_DEBUG_VAR(MightVectorize) + EIGEN_DEBUG_VAR(MayLinearize) + EIGEN_DEBUG_VAR(MayInnerVectorize) + EIGEN_DEBUG_VAR(MayLinearVectorize) + EIGEN_DEBUG_VAR(MaySliceVectorize) + std::cerr << "Traversal" << " = " << Traversal << " (" << demangle_traversal(Traversal) << ")" << std::endl; + EIGEN_DEBUG_VAR(SrcEvaluator::CoeffReadCost) + EIGEN_DEBUG_VAR(UnrollingLimit) + EIGEN_DEBUG_VAR(MayUnrollCompletely) + EIGEN_DEBUG_VAR(MayUnrollInner) + std::cerr << "Unrolling" << " = " << Unrolling << " (" << demangle_unrolling(Unrolling) << ")" << std::endl; + std::cerr << std::endl; + } +#endif +}; + +/*************************************************************************** +* Part 2 : meta-unrollers +***************************************************************************/ + +/************************ +*** Default traversal *** +************************/ + +template +struct copy_using_evaluator_DefaultTraversal_CompleteUnrolling +{ + // FIXME: this is not very clean, perhaps this information should be provided by the kernel? + typedef typename Kernel::DstEvaluatorType DstEvaluatorType; + typedef typename DstEvaluatorType::XprType DstXprType; + + enum { + outer = Index / DstXprType::InnerSizeAtCompileTime, + inner = Index % DstXprType::InnerSizeAtCompileTime + }; + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + kernel.assignCoeffByOuterInner(outer, inner); + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_DefaultTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +template +struct copy_using_evaluator_DefaultTraversal_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, Index outer) + { + kernel.assignCoeffByOuterInner(outer, Index_); + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } +}; + +template +struct copy_using_evaluator_DefaultTraversal_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&, Index) { } +}; + +/*********************** +*** Linear traversal *** +***********************/ + +template +struct copy_using_evaluator_LinearTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel& kernel) + { + kernel.assignCoeff(Index); + copy_using_evaluator_LinearTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_LinearTraversal_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +/************************** +*** Inner vectorization *** +**************************/ + +template +struct copy_using_evaluator_innervec_CompleteUnrolling +{ + // FIXME: this is not very clean, perhaps this information should be provided by the kernel? + typedef typename Kernel::DstEvaluatorType DstEvaluatorType; + typedef typename DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { + outer = Index / DstXprType::InnerSizeAtCompileTime, + inner = Index % DstXprType::InnerSizeAtCompileTime, + SrcAlignment = Kernel::AssignmentTraits::SrcAlignment, + DstAlignment = Kernel::AssignmentTraits::DstAlignment + }; + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + kernel.template assignPacketByOuterInner(outer, inner); + enum { NextIndex = Index + unpacket_traits::size }; + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + } +}; + +template +struct copy_using_evaluator_innervec_CompleteUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&) { } +}; + +template +struct copy_using_evaluator_innervec_InnerUnrolling +{ + typedef typename Kernel::PacketType PacketType; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, Index outer) + { + kernel.template assignPacketByOuterInner(outer, Index_); + enum { NextIndex = Index_ + unpacket_traits::size }; + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + } +}; + +template +struct copy_using_evaluator_innervec_InnerUnrolling +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &, Index) { } +}; + +/*************************************************************************** +* Part 3 : implementation of all cases +***************************************************************************/ + +// dense_assignment_loop is based on assign_impl + +template +struct dense_assignment_loop; + +/************************ +*** Default traversal *** +************************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static void EIGEN_STRONG_INLINE run(Kernel &kernel) + { + for(Index outer = 0; outer < kernel.outerSize(); ++outer) { + for(Index inner = 0; inner < kernel.innerSize(); ++inner) { + kernel.assignCoeffByOuterInner(outer, inner); + } + } + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + + const Index outerSize = kernel.outerSize(); + for(Index outer = 0; outer < outerSize; ++outer) + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } +}; + +/*************************** +*** Linear vectorization *** +***************************/ + + +// The goal of unaligned_dense_assignment_loop is simply to factorize the handling +// of the non vectorizable beginning and ending parts + +template +struct unaligned_dense_assignment_loop +{ + // if IsAligned = true, then do nothing + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel&, Index, Index) {} +}; + +template <> +struct unaligned_dense_assignment_loop +{ + // MSVC must not inline this functions. If it does, it fails to optimize the + // packet access path. + // FIXME check which version exhibits this issue +#if EIGEN_COMP_MSVC + template + static EIGEN_DONT_INLINE void run(Kernel &kernel, + Index start, + Index end) +#else + template + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel, + Index start, + Index end) +#endif + { + for (Index index = start; index < end; ++index) + kernel.assignCoeff(index); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index size = kernel.size(); + typedef typename Kernel::Scalar Scalar; + typedef typename Kernel::PacketType PacketType; + enum { + requestedAlignment = Kernel::AssignmentTraits::LinearRequiredAlignment, + packetSize = unpacket_traits::size, + dstIsAligned = int(Kernel::AssignmentTraits::DstAlignment)>=int(requestedAlignment), + dstAlignment = packet_traits::AlignedOnScalar ? int(requestedAlignment) + : int(Kernel::AssignmentTraits::DstAlignment), + srcAlignment = Kernel::AssignmentTraits::JointAlignment + }; + const Index alignedStart = dstIsAligned ? 0 : internal::first_aligned(kernel.dstDataPtr(), size); + const Index alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize; + + unaligned_dense_assignment_loop::run(kernel, 0, alignedStart); + + for(Index index = alignedStart; index < alignedEnd; index += packetSize) + kernel.template assignPacket(index); + + unaligned_dense_assignment_loop<>::run(kernel, alignedEnd, size); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { size = DstXprType::SizeAtCompileTime, + packetSize =unpacket_traits::size, + alignedSize = (size/packetSize)*packetSize }; + + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + copy_using_evaluator_DefaultTraversal_CompleteUnrolling::run(kernel); + } +}; + +/************************** +*** Inner vectorization *** +**************************/ + +template +struct dense_assignment_loop +{ + typedef typename Kernel::PacketType PacketType; + enum { + SrcAlignment = Kernel::AssignmentTraits::SrcAlignment, + DstAlignment = Kernel::AssignmentTraits::DstAlignment + }; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index innerSize = kernel.innerSize(); + const Index outerSize = kernel.outerSize(); + const Index packetSize = unpacket_traits::size; + for(Index outer = 0; outer < outerSize; ++outer) + for(Index inner = 0; inner < innerSize; inner+=packetSize) + kernel.template assignPacketByOuterInner(outer, inner); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_innervec_CompleteUnrolling::run(kernel); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::AssignmentTraits Traits; + const Index outerSize = kernel.outerSize(); + for(Index outer = 0; outer < outerSize; ++outer) + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + } +}; + +/*********************** +*** Linear traversal *** +***********************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + const Index size = kernel.size(); + for(Index i = 0; i < size; ++i) + kernel.assignCoeff(i); + } +}; + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + copy_using_evaluator_LinearTraversal_CompleteUnrolling::run(kernel); + } +}; + +/************************** +*** Slice vectorization *** +***************************/ + +template +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::Scalar Scalar; + typedef typename Kernel::PacketType PacketType; + enum { + packetSize = unpacket_traits::size, + requestedAlignment = int(Kernel::AssignmentTraits::InnerRequiredAlignment), + alignable = packet_traits::AlignedOnScalar || int(Kernel::AssignmentTraits::DstAlignment)>=sizeof(Scalar), + dstIsAligned = int(Kernel::AssignmentTraits::DstAlignment)>=int(requestedAlignment), + dstAlignment = alignable ? int(requestedAlignment) + : int(Kernel::AssignmentTraits::DstAlignment) + }; + const Scalar *dst_ptr = kernel.dstDataPtr(); + if((!bool(dstIsAligned)) && (UIntPtr(dst_ptr) % sizeof(Scalar))>0) + { + // the pointer is not aligend-on scalar, so alignment is not possible + return dense_assignment_loop::run(kernel); + } + const Index packetAlignedMask = packetSize - 1; + const Index innerSize = kernel.innerSize(); + const Index outerSize = kernel.outerSize(); + const Index alignedStep = alignable ? (packetSize - kernel.outerStride() % packetSize) & packetAlignedMask : 0; + Index alignedStart = ((!alignable) || bool(dstIsAligned)) ? 0 : internal::first_aligned(dst_ptr, innerSize); + + for(Index outer = 0; outer < outerSize; ++outer) + { + const Index alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask); + // do the non-vectorizable part of the assignment + for(Index inner = 0; inner(outer, inner); + + // do the non-vectorizable part of the assignment + for(Index inner = alignedEnd; inner +struct dense_assignment_loop +{ + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void run(Kernel &kernel) + { + typedef typename Kernel::DstEvaluatorType::XprType DstXprType; + typedef typename Kernel::PacketType PacketType; + + enum { size = DstXprType::InnerSizeAtCompileTime, + packetSize =unpacket_traits::size, + vectorizableSize = (size/packetSize)*packetSize }; + + for(Index outer = 0; outer < kernel.outerSize(); ++outer) + { + copy_using_evaluator_innervec_InnerUnrolling::run(kernel, outer); + copy_using_evaluator_DefaultTraversal_InnerUnrolling::run(kernel, outer); + } + } +}; +#endif + + +/*************************************************************************** +* Part 4 : Generic dense assignment kernel +***************************************************************************/ + +// This class generalize the assignment of a coefficient (or packet) from one dense evaluator +// to another dense writable evaluator. +// It is parametrized by the two evaluators, and the actual assignment functor. +// This abstraction level permits to keep the evaluation loops as simple and as generic as possible. +// One can customize the assignment using this generic dense_assignment_kernel with different +// functors, or by completely overloading it, by-passing a functor. +template +class generic_dense_assignment_kernel +{ +protected: + typedef typename DstEvaluatorTypeT::XprType DstXprType; + typedef typename SrcEvaluatorTypeT::XprType SrcXprType; +public: + + typedef DstEvaluatorTypeT DstEvaluatorType; + typedef SrcEvaluatorTypeT SrcEvaluatorType; + typedef typename DstEvaluatorType::Scalar Scalar; + typedef copy_using_evaluator_traits AssignmentTraits; + typedef typename AssignmentTraits::PacketType PacketType; + + + EIGEN_DEVICE_FUNC generic_dense_assignment_kernel(DstEvaluatorType &dst, const SrcEvaluatorType &src, const Functor &func, DstXprType& dstExpr) + : m_dst(dst), m_src(src), m_functor(func), m_dstExpr(dstExpr) + { + #ifdef EIGEN_DEBUG_ASSIGN + AssignmentTraits::debug(); + #endif + } + + EIGEN_DEVICE_FUNC Index size() const { return m_dstExpr.size(); } + EIGEN_DEVICE_FUNC Index innerSize() const { return m_dstExpr.innerSize(); } + EIGEN_DEVICE_FUNC Index outerSize() const { return m_dstExpr.outerSize(); } + EIGEN_DEVICE_FUNC Index rows() const { return m_dstExpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_dstExpr.cols(); } + EIGEN_DEVICE_FUNC Index outerStride() const { return m_dstExpr.outerStride(); } + + EIGEN_DEVICE_FUNC DstEvaluatorType& dstEvaluator() { return m_dst; } + EIGEN_DEVICE_FUNC const SrcEvaluatorType& srcEvaluator() const { return m_src; } + + /// Assign src(row,col) to dst(row,col) through the assignment functor. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index row, Index col) + { + m_functor.assignCoeff(m_dst.coeffRef(row,col), m_src.coeff(row,col)); + } + + /// \sa assignCoeff(Index,Index) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeff(Index index) + { + m_functor.assignCoeff(m_dst.coeffRef(index), m_src.coeff(index)); + } + + /// \sa assignCoeff(Index,Index) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignCoeffByOuterInner(Index outer, Index inner) + { + Index row = rowIndexByOuterInner(outer, inner); + Index col = colIndexByOuterInner(outer, inner); + assignCoeff(row, col); + } + + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index row, Index col) + { + m_functor.template assignPacket(&m_dst.coeffRef(row,col), m_src.template packet(row,col)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacket(Index index) + { + m_functor.template assignPacket(&m_dst.coeffRef(index), m_src.template packet(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void assignPacketByOuterInner(Index outer, Index inner) + { + Index row = rowIndexByOuterInner(outer, inner); + Index col = colIndexByOuterInner(outer, inner); + assignPacket(row, col); + } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Index rowIndexByOuterInner(Index outer, Index inner) + { + typedef typename DstEvaluatorType::ExpressionTraits Traits; + return int(Traits::RowsAtCompileTime) == 1 ? 0 + : int(Traits::ColsAtCompileTime) == 1 ? inner + : int(DstEvaluatorType::Flags)&RowMajorBit ? outer + : inner; + } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Index colIndexByOuterInner(Index outer, Index inner) + { + typedef typename DstEvaluatorType::ExpressionTraits Traits; + return int(Traits::ColsAtCompileTime) == 1 ? 0 + : int(Traits::RowsAtCompileTime) == 1 ? inner + : int(DstEvaluatorType::Flags)&RowMajorBit ? inner + : outer; + } + + EIGEN_DEVICE_FUNC const Scalar* dstDataPtr() const + { + return m_dstExpr.data(); + } + +protected: + DstEvaluatorType& m_dst; + const SrcEvaluatorType& m_src; + const Functor &m_functor; + // TODO find a way to avoid the needs of the original expression + DstXprType& m_dstExpr; +}; + +/*************************************************************************** +* Part 5 : Entry point for dense rectangular assignment +***************************************************************************/ + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void resize_if_allowed(DstXprType &dst, const SrcXprType& src, const Functor &/*func*/) +{ + EIGEN_ONLY_USED_FOR_DEBUG(dst); + EIGEN_ONLY_USED_FOR_DEBUG(src); + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void resize_if_allowed(DstXprType &dst, const SrcXprType& src, const internal::assign_op &/*func*/) +{ + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if(((dst.rows()!=dstRows) || (dst.cols()!=dstCols))) + dst.resize(dstRows, dstCols); + eigen_assert(dst.rows() == dstRows && dst.cols() == dstCols); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const SrcXprType& src, const Functor &func) +{ + typedef evaluator DstEvaluatorType; + typedef evaluator SrcEvaluatorType; + + SrcEvaluatorType srcEvaluator(src); + + // NOTE To properly handle A = (A*A.transpose())/s with A rectangular, + // we need to resize the destination after the source evaluator has been created. + resize_if_allowed(dst, src, func); + + DstEvaluatorType dstEvaluator(dst); + + typedef generic_dense_assignment_kernel Kernel; + Kernel kernel(dstEvaluator, srcEvaluator, func, dst.const_cast_derived()); + + dense_assignment_loop::run(kernel); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_dense_assignment_loop(DstXprType& dst, const SrcXprType& src) +{ + call_dense_assignment_loop(dst, src, internal::assign_op()); +} + +/*************************************************************************** +* Part 6 : Generic assignment +***************************************************************************/ + +// Based on the respective shapes of the destination and source, +// the class AssignmentKind determine the kind of assignment mechanism. +// AssignmentKind must define a Kind typedef. +template struct AssignmentKind; + +// Assignement kind defined in this file: +struct Dense2Dense {}; +struct EigenBase2EigenBase {}; + +template struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; +template<> struct AssignmentKind { typedef Dense2Dense Kind; }; + +// This is the main assignment class +template< typename DstXprType, typename SrcXprType, typename Functor, + typename Kind = typename AssignmentKind< typename evaluator_traits::Shape , typename evaluator_traits::Shape >::Kind, + typename EnableIf = void> +struct Assignment; + + +// The only purpose of this call_assignment() function is to deal with noalias() / "assume-aliasing" and automatic transposition. +// Indeed, I (Gael) think that this concept of "assume-aliasing" was a mistake, and it makes thing quite complicated. +// So this intermediate function removes everything related to "assume-aliasing" such that Assignment +// does not has to bother about these annoying details. + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src) +{ + call_assignment(dst, src, internal::assign_op()); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(const Dst& dst, const Src& src) +{ + call_assignment(dst, src, internal::assign_op()); +} + +// Deal with "assume-aliasing" +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src, const Func& func, typename enable_if< evaluator_assume_aliasing::value, void*>::type = 0) +{ + typename plain_matrix_type::type tmp(src); + call_assignment_no_alias(dst, tmp, func); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(Dst& dst, const Src& src, const Func& func, typename enable_if::value, void*>::type = 0) +{ + call_assignment_no_alias(dst, src, func); +} + +// by-pass "assume-aliasing" +// When there is no aliasing, we require that 'dst' has been properly resized +template class StorageBase, typename Src, typename Func> +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment(NoAlias& dst, const Src& src, const Func& func) +{ + call_assignment_no_alias(dst.expression(), src, func); +} + + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias(Dst& dst, const Src& src, const Func& func) +{ + enum { + NeedToTranspose = ( (int(Dst::RowsAtCompileTime) == 1 && int(Src::ColsAtCompileTime) == 1) + || (int(Dst::ColsAtCompileTime) == 1 && int(Src::RowsAtCompileTime) == 1) + ) && int(Dst::SizeAtCompileTime) != 1 + }; + + typedef typename internal::conditional, Dst>::type ActualDstTypeCleaned; + typedef typename internal::conditional, Dst&>::type ActualDstType; + ActualDstType actualDst(dst); + + // TODO check whether this is the right place to perform these checks: + EIGEN_STATIC_ASSERT_LVALUE(Dst) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(ActualDstTypeCleaned,Src) + EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename ActualDstTypeCleaned::Scalar,typename Src::Scalar); + + Assignment::run(actualDst, src, func); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias(Dst& dst, const Src& src) +{ + call_assignment_no_alias(dst, src, internal::assign_op()); +} + +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias_no_transpose(Dst& dst, const Src& src, const Func& func) +{ + // TODO check whether this is the right place to perform these checks: + EIGEN_STATIC_ASSERT_LVALUE(Dst) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src) + EIGEN_CHECK_BINARY_COMPATIBILIY(Func,typename Dst::Scalar,typename Src::Scalar); + + Assignment::run(dst, src, func); +} +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +void call_assignment_no_alias_no_transpose(Dst& dst, const Src& src) +{ + call_assignment_no_alias_no_transpose(dst, src, internal::assign_op()); +} + +// forward declaration +template void check_for_aliasing(const Dst &dst, const Src &src); + +// Generic Dense to Dense assignment +// Note that the last template argument "Weak" is needed to make it possible to perform +// both partial specialization+SFINAE without ambiguous specialization +template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak> +struct Assignment +{ + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const Functor &func) + { +#ifndef EIGEN_NO_DEBUG + internal::check_for_aliasing(dst, src); +#endif + + call_dense_assignment_loop(dst, src, func); + } +}; + +// Generic assignment through evalTo. +// TODO: not sure we have to keep that one, but it helps porting current code to new evaluator mechanism. +// Note that the last template argument "Weak" is needed to make it possible to perform +// both partial specialization+SFINAE without ambiguous specialization +template< typename DstXprType, typename SrcXprType, typename Functor, typename Weak> +struct Assignment +{ + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.evalTo(dst); + } + + // NOTE The following two functions are templated to avoid their instanciation if not needed + // This is needed because some expressions supports evalTo only and/or have 'void' as scalar type. + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.addTo(dst); + } + + template + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.subTo(dst); + } +}; + +} // namespace internal + +} // end namespace Eigen + +#endif // EIGEN_ASSIGN_EVALUATOR_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h old mode 100644 new mode 100755 index 7772951b9..6c2ab9264 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Assign_MKL.h @@ -1,6 +1,7 @@ /* Copyright (c) 2011, Intel Corporation. All rights reserved. - + Copyright (C) 2015 Gael Guennebaud + Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: @@ -37,17 +38,13 @@ namespace Eigen { namespace internal { -template struct vml_call -{ enum { IsSupported = 0 }; }; - -template +template class vml_assign_traits { private: enum { DstHasDirectAccess = Dst::Flags & DirectAccessBit, SrcHasDirectAccess = Src::Flags & DirectAccessBit, - StorageOrdersAgree = (int(Dst::IsRowMajor) == int(Src::IsRowMajor)), InnerSize = int(Dst::IsVectorAtCompileTime) ? int(Dst::SizeAtCompileTime) : int(Dst::Flags)&RowMajorBit ? int(Dst::ColsAtCompileTime) @@ -57,165 +54,120 @@ class vml_assign_traits : int(Dst::MaxRowsAtCompileTime), MaxSizeAtCompileTime = Dst::SizeAtCompileTime, - MightEnableVml = vml_call::IsSupported && StorageOrdersAgree && DstHasDirectAccess && SrcHasDirectAccess - && Src::InnerStrideAtCompileTime==1 && Dst::InnerStrideAtCompileTime==1, + MightEnableVml = StorageOrdersAgree && DstHasDirectAccess && SrcHasDirectAccess && Src::InnerStrideAtCompileTime==1 && Dst::InnerStrideAtCompileTime==1, MightLinearize = MightEnableVml && (int(Dst::Flags) & int(Src::Flags) & LinearAccessBit), VmlSize = MightLinearize ? MaxSizeAtCompileTime : InnerMaxSize, - LargeEnough = VmlSize==Dynamic || VmlSize>=EIGEN_MKL_VML_THRESHOLD, - MayEnableVml = MightEnableVml && LargeEnough, - MayLinearize = MayEnableVml && MightLinearize + LargeEnough = VmlSize==Dynamic || VmlSize>=EIGEN_MKL_VML_THRESHOLD }; public: enum { - Traversal = MayLinearize ? LinearVectorizedTraversal - : MayEnableVml ? InnerVectorizedTraversal - : DefaultTraversal + EnableVml = MightEnableVml && LargeEnough, + Traversal = MightLinearize ? LinearTraversal : DefaultTraversal }; }; -template::Traversal > -struct vml_assign_impl - : assign_impl,Traversal,Unrolling,BuiltIn> -{ -}; - -template -struct vml_assign_impl -{ - typedef typename Derived1::Scalar Scalar; - typedef typename Derived1::Index Index; - static inline void run(Derived1& dst, const CwiseUnaryOp& src) - { - // in case we want to (or have to) skip VML at runtime we can call: - // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); - const Index innerSize = dst.innerSize(); - const Index outerSize = dst.outerSize(); - for(Index outer = 0; outer < outerSize; ++outer) { - const Scalar *src_ptr = src.IsRowMajor ? &(src.nestedExpression().coeffRef(outer,0)) : - &(src.nestedExpression().coeffRef(0, outer)); - Scalar *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); - vml_call::run(src.functor(), innerSize, src_ptr, dst_ptr ); - } - } -}; - -template -struct vml_assign_impl -{ - static inline void run(Derived1& dst, const CwiseUnaryOp& src) - { - // in case we want to (or have to) skip VML at runtime we can call: - // assign_impl,Traversal,Unrolling,BuiltIn>::run(dst,src); - vml_call::run(src.functor(), dst.size(), src.nestedExpression().data(), dst.data() ); - } -}; - -// Macroses - -#define EIGEN_MKL_VML_SPECIALIZE_ASSIGN(TRAVERSAL,UNROLLING) \ - template \ - struct assign_impl, TRAVERSAL, UNROLLING, Specialized> { \ - static inline void run(Derived1 &dst, const Eigen::CwiseUnaryOp &src) { \ - vml_assign_impl::run(dst, src); \ - } \ - }; - -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(DefaultTraversal,InnerUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(InnerVectorizedTraversal,InnerUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,CompleteUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(LinearVectorizedTraversal,NoUnrolling) -EIGEN_MKL_VML_SPECIALIZE_ASSIGN(SliceVectorizedTraversal,NoUnrolling) - - +#define EIGEN_PP_EXPAND(ARG) ARG #if !defined (EIGEN_FAST_MATH) || (EIGEN_FAST_MATH != 1) -#define EIGEN_MKL_VML_MODE VML_HA +#define EIGEN_VMLMODE_EXPAND_LA , VML_HA #else -#define EIGEN_MKL_VML_MODE VML_LA +#define EIGEN_VMLMODE_EXPAND_LA , VML_LA #endif -#define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst); \ - } \ +#define EIGEN_VMLMODE_EXPAND__ + +#define EIGEN_VMLMODE_PREFIX_LA vm +#define EIGEN_VMLMODE_PREFIX__ v +#define EIGEN_VMLMODE_PREFIX(VMLMODE) EIGEN_CAT(EIGEN_VMLMODE_PREFIX_,VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE, VMLMODE) \ + template< typename DstXprType, typename SrcXprNested> \ + struct Assignment, SrcXprNested>, assign_op, \ + Dense2Dense, typename enable_if::EnableVml>::type> { \ + typedef CwiseUnaryOp, SrcXprNested> SrcXprType; \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ + if(vml_assign_traits::Traversal==LinearTraversal) { \ + VMLOP(dst.size(), (const VMLTYPE*)src.nestedExpression().data(), \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + } else { \ + const Index outerSize = dst.outerSize(); \ + for(Index outer = 0; outer < outerSize; ++outer) { \ + const EIGENTYPE *src_ptr = src.IsRowMajor ? &(src.nestedExpression().coeffRef(outer,0)) : \ + &(src.nestedExpression().coeffRef(0, outer)); \ + EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ + VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + } \ + } \ + } \ + }; \ + + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),s##VMLOP), float, float, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),d##VMLOP), double, double, VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),c##VMLOP), scomplex, MKL_Complex8, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, EIGEN_CAT(EIGEN_VMLMODE_PREFIX(VMLMODE),z##VMLOP), dcomplex, MKL_Complex16, VMLMODE) + +#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP, VMLMODE) \ + EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(EIGENOP, VMLOP, VMLMODE) + + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sin, Sin, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(asin, Asin, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sinh, Sinh, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(cos, Cos, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(acos, Acos, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(cosh, Cosh, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(tan, Tan, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(atan, Atan, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(tanh, Tanh, LA) +// EIGEN_MKL_VML_DECLARE_UNARY_CALLS(abs, Abs, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(exp, Exp, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(log, Ln, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(log10, Log10, LA) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS(sqrt, Sqrt, _) + +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(square, Sqr, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_CPLX(arg, Arg, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(round, Round, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(floor, Floor, _) +EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(ceil, Ceil, _) + +#define EIGEN_MKL_VML_DECLARE_POW_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE, VMLMODE) \ + template< typename DstXprType, typename SrcXprNested, typename Plain> \ + struct Assignment, SrcXprNested, \ + const CwiseNullaryOp,Plain> >, assign_op, \ + Dense2Dense, typename enable_if::EnableVml>::type> { \ + typedef CwiseBinaryOp, SrcXprNested, \ + const CwiseNullaryOp,Plain> > SrcXprType; \ + static void run(DstXprType &dst, const SrcXprType &src, const assign_op &/*func*/) { \ + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); \ + VMLTYPE exponent = reinterpret_cast(src.rhs().functor().m_other); \ + if(vml_assign_traits::Traversal==LinearTraversal) \ + { \ + VMLOP( dst.size(), (const VMLTYPE*)src.lhs().data(), exponent, \ + (VMLTYPE*)dst.data() EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE) ); \ + } else { \ + const Index outerSize = dst.outerSize(); \ + for(Index outer = 0; outer < outerSize; ++outer) { \ + const EIGENTYPE *src_ptr = src.IsRowMajor ? &(src.lhs().coeffRef(outer,0)) : \ + &(src.lhs().coeffRef(0, outer)); \ + EIGENTYPE *dst_ptr = dst.IsRowMajor ? &(dst.coeffRef(outer,0)) : &(dst.coeffRef(0, outer)); \ + VMLOP( dst.innerSize(), (const VMLTYPE*)src_ptr, exponent, \ + (VMLTYPE*)dst_ptr EIGEN_PP_EXPAND(EIGEN_VMLMODE_EXPAND_##VMLMODE)); \ + } \ + } \ + } \ }; - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& /*func*/, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ - VMLOP(size, (const VMLTYPE*)src, (VMLTYPE*)dst, vmlMode); \ - } \ - }; - -#define EIGEN_MKL_VML_DECLARE_POW_CALL(EIGENOP, VMLOP, EIGENTYPE, VMLTYPE) \ - template<> struct vml_call< scalar_##EIGENOP##_op > { \ - enum { IsSupported = 1 }; \ - static inline void run( const scalar_##EIGENOP##_op& func, \ - int size, const EIGENTYPE* src, EIGENTYPE* dst) { \ - EIGENTYPE exponent = func.m_exponent; \ - MKL_INT64 vmlMode = EIGEN_MKL_VML_MODE; \ - VMLOP(&size, (const VMLTYPE*)src, (const VMLTYPE*)&exponent, \ - (VMLTYPE*)dst, &vmlMode); \ - } \ - }; - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vs##VMLOP, float, float) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vd##VMLOP, double, double) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vc##VMLOP, scomplex, MKL_Complex8) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL(EIGENOP, vz##VMLOP, dcomplex, MKL_Complex16) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX(EIGENOP, VMLOP) - - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vms##VMLOP, float, float) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmd##VMLOP, double, double) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmc##VMLOP, scomplex, MKL_Complex8) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALL_LA(EIGENOP, vmz##VMLOP, dcomplex, MKL_Complex16) - -#define EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL_LA(EIGENOP, VMLOP) \ - EIGEN_MKL_VML_DECLARE_UNARY_CALLS_COMPLEX_LA(EIGENOP, VMLOP) - - -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sin, Sin) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(asin, Asin) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(cos, Cos) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(acos, Acos) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(tan, Tan) -//EIGEN_MKL_VML_DECLARE_UNARY_CALLS(abs, Abs) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(exp, Exp) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(log, Ln) -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_LA(sqrt, Sqrt) - -EIGEN_MKL_VML_DECLARE_UNARY_CALLS_REAL(square, Sqr) - -// The vm*powx functions are not avaibale in the windows version of MKL. -#ifndef _WIN32 -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmspowx_, float, float) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmdpowx_, double, double) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmcpowx_, scomplex, MKL_Complex8) -EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmzpowx_, dcomplex, MKL_Complex16) -#endif + +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmsPowx, float, float, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmdPowx, double, double, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmcPowx, scomplex, MKL_Complex8, LA) +EIGEN_MKL_VML_DECLARE_POW_CALL(pow, vmzPowx, dcomplex, MKL_Complex16, LA) } // end namespace internal diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h index ffd7fe8b3..4978c9140 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/BandMatrix.h @@ -32,7 +32,7 @@ class BandMatrixBase : public EigenBase }; typedef typename internal::traits::Scalar Scalar; typedef Matrix DenseMatrixType; - typedef typename DenseMatrixType::Index Index; + typedef typename DenseMatrixType::StorageIndex StorageIndex; typedef typename internal::traits::CoefficientsType CoefficientsType; typedef EigenBase Base; @@ -161,15 +161,15 @@ class BandMatrixBase : public EigenBase * * \brief Represents a rectangular matrix with a banded storage * - * \param _Scalar Numeric type, i.e. float, double, int - * \param Rows Number of rows, or \b Dynamic - * \param Cols Number of columns, or \b Dynamic - * \param Supers Number of super diagonal - * \param Subs Number of sub diagonal - * \param _Options A combination of either \b #RowMajor or \b #ColMajor, and of \b #SelfAdjoint - * The former controls \ref TopicStorageOrders "storage order", and defaults to - * column-major. The latter controls whether the matrix represents a selfadjoint - * matrix in which case either Supers of Subs have to be null. + * \tparam _Scalar Numeric type, i.e. float, double, int + * \tparam _Rows Number of rows, or \b Dynamic + * \tparam _Cols Number of columns, or \b Dynamic + * \tparam _Supers Number of super diagonal + * \tparam _Subs Number of sub diagonal + * \tparam _Options A combination of either \b #RowMajor or \b #ColMajor, and of \b #SelfAdjoint + * The former controls \ref TopicStorageOrders "storage order", and defaults to + * column-major. The latter controls whether the matrix represents a selfadjoint + * matrix in which case either Supers of Subs have to be null. * * \sa class TridiagonalMatrix */ @@ -179,7 +179,7 @@ struct traits > { typedef _Scalar Scalar; typedef Dense StorageKind; - typedef DenseIndex Index; + typedef Eigen::Index StorageIndex; enum { CoeffReadCost = NumTraits::ReadCost, RowsAtCompileTime = _Rows, @@ -201,10 +201,10 @@ class BandMatrix : public BandMatrixBase::Scalar Scalar; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; typedef typename internal::traits::CoefficientsType CoefficientsType; - inline BandMatrix(Index rows=Rows, Index cols=Cols, Index supers=Supers, Index subs=Subs) + explicit inline BandMatrix(Index rows=Rows, Index cols=Cols, Index supers=Supers, Index subs=Subs) : m_coeffs(1+supers+subs,cols), m_rows(rows), m_supers(supers), m_subs(subs) { @@ -241,7 +241,7 @@ struct traits::CoeffReadCost, RowsAtCompileTime = _Rows, @@ -264,9 +264,9 @@ class BandMatrixWrapper : public BandMatrixBase::Scalar Scalar; typedef typename internal::traits::CoefficientsType CoefficientsType; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; - inline BandMatrixWrapper(const CoefficientsType& coeffs, Index rows=_Rows, Index cols=_Cols, Index supers=_Supers, Index subs=_Subs) + explicit inline BandMatrixWrapper(const CoefficientsType& coeffs, Index rows=_Rows, Index cols=_Cols, Index supers=_Supers, Index subs=_Subs) : m_coeffs(coeffs), m_rows(rows), m_supers(supers), m_subs(subs) { @@ -302,9 +302,9 @@ class BandMatrixWrapper : public BandMatrixBase class TridiagonalMatrix : public BandMatrix { typedef BandMatrix Base; - typedef typename Base::Index Index; + typedef typename Base::StorageIndex StorageIndex; public: - TridiagonalMatrix(Index size = Size) : Base(size,size,Options&SelfAdjoint?0:1,1) {} + explicit TridiagonalMatrix(Index size = Size) : Base(size,size,Options&SelfAdjoint?0:1,1) {} inline typename Base::template DiagonalIntReturnType<1>::Type super() { return Base::template diagonal<1>(); } @@ -327,6 +327,25 @@ class TridiagonalMatrix : public BandMatrix +struct evaluator_traits > + : public evaluator_traits_base > +{ + typedef BandShape Shape; +}; + +template +struct evaluator_traits > + : public evaluator_traits_base > +{ + typedef BandShape Shape; +}; + +template<> struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; + } // end namespace internal } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h index 87bedfa46..11de45c2e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Block.h @@ -13,14 +13,70 @@ namespace Eigen { +namespace internal { +template +struct traits > : traits +{ + typedef typename traits::Scalar Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::XprKind XprKind; + typedef typename ref_selector::type XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + enum{ + MatrixRows = traits::RowsAtCompileTime, + MatrixCols = traits::ColsAtCompileTime, + RowsAtCompileTime = MatrixRows == 0 ? 0 : BlockRows, + ColsAtCompileTime = MatrixCols == 0 ? 0 : BlockCols, + MaxRowsAtCompileTime = BlockRows==0 ? 0 + : RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) + : int(traits::MaxRowsAtCompileTime), + MaxColsAtCompileTime = BlockCols==0 ? 0 + : ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) + : int(traits::MaxColsAtCompileTime), + + XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, + IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + : XprTypeIsRowMajor, + HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), + InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), + InnerStrideAtCompileTime = HasSameStorageOrderAsXprType + ? int(inner_stride_at_compile_time::ret) + : int(outer_stride_at_compile_time::ret), + OuterStrideAtCompileTime = HasSameStorageOrderAsXprType + ? int(outer_stride_at_compile_time::ret) + : int(inner_stride_at_compile_time::ret), + + // FIXME, this traits is rather specialized for dense object and it needs to be cleaned further + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, + Flags = (traits::Flags & (DirectAccessBit | (InnerPanel?CompressedAccessBit:0))) | FlagsLvalueBit | FlagsRowMajorBit, + // FIXME DirectAccessBit should not be handled by expressions + // + // Alignment is needed by MapBase's assertions + // We can sefely set it to false here. Internal alignment errors will be detected by an eigen_internal_assert in the respective evaluator + Alignment = 0 + }; +}; + +template::ret> class BlockImpl_dense; + +} // end namespace internal + +template class BlockImpl; + /** \class Block * \ingroup Core_Module * * \brief Expression of a fixed-size or dynamic-size block * - * \param XprType the type of the expression in which we are taking a block - * \param BlockRows the number of rows of the block we are taking at compile time (optional) - * \param BlockCols the number of columns of the block we are taking at compile time (optional) + * \tparam XprType the type of the expression in which we are taking a block + * \tparam BlockRows the number of rows of the block we are taking at compile time (optional) + * \tparam BlockCols the number of columns of the block we are taking at compile time (optional) + * \tparam InnerPanel is true, if the block maps to a set of rows of a row major matrix or + * to set of columns of a column major matrix (optional). The parameter allows to determine + * at compile time whether aligned access is possible on the block expression. * * This class represents an expression of either a fixed-size or dynamic-size block. It is the return * type of DenseBase::block(Index,Index,Index,Index) and DenseBase::block(Index,Index) and @@ -44,61 +100,6 @@ namespace Eigen { * * \sa DenseBase::block(Index,Index,Index,Index), DenseBase::block(Index,Index), class VectorBlock */ - -namespace internal { -template -struct traits > : traits -{ - typedef typename traits::Scalar Scalar; - typedef typename traits::StorageKind StorageKind; - typedef typename traits::XprKind XprKind; - typedef typename nested::type XprTypeNested; - typedef typename remove_reference::type _XprTypeNested; - enum{ - MatrixRows = traits::RowsAtCompileTime, - MatrixCols = traits::ColsAtCompileTime, - RowsAtCompileTime = MatrixRows == 0 ? 0 : BlockRows, - ColsAtCompileTime = MatrixCols == 0 ? 0 : BlockCols, - MaxRowsAtCompileTime = BlockRows==0 ? 0 - : RowsAtCompileTime != Dynamic ? int(RowsAtCompileTime) - : int(traits::MaxRowsAtCompileTime), - MaxColsAtCompileTime = BlockCols==0 ? 0 - : ColsAtCompileTime != Dynamic ? int(ColsAtCompileTime) - : int(traits::MaxColsAtCompileTime), - XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0, - IsRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 - : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 - : XprTypeIsRowMajor, - HasSameStorageOrderAsXprType = (IsRowMajor == XprTypeIsRowMajor), - InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), - InnerStrideAtCompileTime = HasSameStorageOrderAsXprType - ? int(inner_stride_at_compile_time::ret) - : int(outer_stride_at_compile_time::ret), - OuterStrideAtCompileTime = HasSameStorageOrderAsXprType - ? int(outer_stride_at_compile_time::ret) - : int(inner_stride_at_compile_time::ret), - MaskPacketAccessBit = (InnerSize == Dynamic || (InnerSize % packet_traits::size) == 0) - && (InnerStrideAtCompileTime == 1) - ? PacketAccessBit : 0, - MaskAlignedBit = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % 16) == 0)) ? AlignedBit : 0, - FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (traits::Flags&LinearAccessBit))) ? LinearAccessBit : 0, - FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, - FlagsRowMajorBit = IsRowMajor ? RowMajorBit : 0, - Flags0 = traits::Flags & ( (HereditaryBits & ~RowMajorBit) | - DirectAccessBit | - MaskPacketAccessBit | - MaskAlignedBit), - Flags = Flags0 | FlagsLinearAccessBit | FlagsLvalueBit | FlagsRowMajorBit - }; -}; - -template::ret> class BlockImpl_dense; - -} // end namespace internal - -template class BlockImpl; - template class Block : public BlockImpl::StorageKind> { @@ -108,9 +109,12 @@ template class typedef Impl Base; EIGEN_GENERIC_PUBLIC_INTERFACE(Block) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Block) + + typedef typename internal::remove_all::type NestedExpression; /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline Block(XprType& xpr, Index i) : Impl(xpr,i) { eigen_assert( (i>=0) && ( @@ -120,25 +124,27 @@ template class /** Fixed-size constructor */ - inline Block(XprType& xpr, Index a_startRow, Index a_startCol) - : Impl(xpr, a_startRow, a_startCol) + EIGEN_DEVICE_FUNC + inline Block(XprType& xpr, Index startRow, Index startCol) + : Impl(xpr, startRow, startCol) { EIGEN_STATIC_ASSERT(RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic,THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE) - eigen_assert(a_startRow >= 0 && BlockRows >= 1 && a_startRow + BlockRows <= xpr.rows() - && a_startCol >= 0 && BlockCols >= 1 && a_startCol + BlockCols <= xpr.cols()); + eigen_assert(startRow >= 0 && BlockRows >= 0 && startRow + BlockRows <= xpr.rows() + && startCol >= 0 && BlockCols >= 0 && startCol + BlockCols <= xpr.cols()); } /** Dynamic-size constructor */ + EIGEN_DEVICE_FUNC inline Block(XprType& xpr, - Index a_startRow, Index a_startCol, + Index startRow, Index startCol, Index blockRows, Index blockCols) - : Impl(xpr, a_startRow, a_startCol, blockRows, blockCols) + : Impl(xpr, startRow, startCol, blockRows, blockCols) { eigen_assert((RowsAtCompileTime==Dynamic || RowsAtCompileTime==blockRows) && (ColsAtCompileTime==Dynamic || ColsAtCompileTime==blockCols)); - eigen_assert(a_startRow >= 0 && blockRows >= 0 && a_startRow <= xpr.rows() - blockRows - && a_startCol >= 0 && blockCols >= 0 && a_startCol <= xpr.cols() - blockCols); + eigen_assert(startRow >= 0 && blockRows >= 0 && startRow <= xpr.rows() - blockRows + && startCol >= 0 && blockCols >= 0 && startCol <= xpr.cols() - blockCols); } }; @@ -149,14 +155,15 @@ class BlockImpl : public internal::BlockImpl_dense { typedef internal::BlockImpl_dense Impl; - typedef typename XprType::Index Index; + typedef typename XprType::StorageIndex StorageIndex; public: typedef Impl Base; EIGEN_INHERIT_ASSIGNMENT_OPERATORS(BlockImpl) - inline BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} - inline BlockImpl(XprType& xpr, Index a_startRow, Index a_startCol) : Impl(xpr, a_startRow, a_startCol) {} - inline BlockImpl(XprType& xpr, Index a_startRow, Index a_startCol, Index blockRows, Index blockCols) - : Impl(xpr, a_startRow, a_startCol, blockRows, blockCols) {} + EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index i) : Impl(xpr,i) {} + EIGEN_DEVICE_FUNC inline BlockImpl(XprType& xpr, Index startRow, Index startCol) : Impl(xpr, startRow, startCol) {} + EIGEN_DEVICE_FUNC + inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) + : Impl(xpr, startRow, startCol, blockRows, blockCols) {} }; namespace internal { @@ -166,16 +173,18 @@ template >::type { typedef Block BlockType; + typedef typename internal::ref_selector::non_const_type XprTypeNested; public: typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(BlockType) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(BlockImpl_dense) - class InnerIterator; + // class InnerIterator; // FIXME apparently never used /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index i) : m_xpr(xpr), // It is a row if and only if BlockRows==1 and BlockCols==XprType::ColsAtCompileTime, @@ -190,75 +199,76 @@ template inline PacketScalar packet(Index rowId, Index colId) const { - return m_xpr.template packet - (rowId + m_startRow.value(), colId + m_startCol.value()); + return m_xpr.template packet(rowId + m_startRow.value(), colId + m_startCol.value()); } template inline void writePacket(Index rowId, Index colId, const PacketScalar& val) { - m_xpr.const_cast_derived().template writePacket - (rowId + m_startRow.value(), colId + m_startCol.value(), val); + m_xpr.template writePacket(rowId + m_startRow.value(), colId + m_startCol.value(), val); } template @@ -272,40 +282,46 @@ template inline void writePacket(Index index, const PacketScalar& val) { - m_xpr.const_cast_derived().template writePacket + m_xpr.template writePacket (m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index), m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0), val); } #ifdef EIGEN_PARSED_BY_DOXYGEN /** \sa MapBase::data() */ - inline const Scalar* data() const; - inline Index innerStride() const; - inline Index outerStride() const; + EIGEN_DEVICE_FUNC inline const Scalar* data() const; + EIGEN_DEVICE_FUNC inline Index innerStride() const; + EIGEN_DEVICE_FUNC inline Index outerStride() const; #endif - const typename internal::remove_all::type& nestedExpression() const + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + XprType& nestedExpression() { return m_xpr; } - Index startRow() const + EIGEN_DEVICE_FUNC + StorageIndex startRow() const { return m_startRow.value(); } - Index startCol() const + EIGEN_DEVICE_FUNC + StorageIndex startCol() const { return m_startCol.value(); } protected: - const typename XprType::Nested m_xpr; - const internal::variable_if_dynamic m_startRow; - const internal::variable_if_dynamic m_startCol; - const internal::variable_if_dynamic m_blockRows; - const internal::variable_if_dynamic m_blockCols; + XprTypeNested m_xpr; + const internal::variable_if_dynamic m_startRow; + const internal::variable_if_dynamic m_startCol; + const internal::variable_if_dynamic m_blockRows; + const internal::variable_if_dynamic m_blockCols; }; /** \internal Internal implementation of dense Blocks in the direct access case.*/ @@ -314,6 +330,10 @@ class BlockImpl_dense : public MapBase > { typedef Block BlockType; + typedef typename internal::ref_selector::non_const_type XprTypeNested; + enum { + XprTypeIsRowMajor = (int(traits::Flags)&RowMajorBit) != 0 + }; public: typedef MapBase Base; @@ -322,42 +342,52 @@ class BlockImpl_dense /** Column or Row constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index i) - : Base(internal::const_cast_ptr(&xpr.coeffRef( - (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? i : 0, - (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? i : 0)), + : Base(xpr.data() + i * ( ((BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) && (!XprTypeIsRowMajor)) + || ((BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) && ( XprTypeIsRowMajor)) ? xpr.innerStride() : xpr.outerStride()), BlockRows==1 ? 1 : xpr.rows(), BlockCols==1 ? 1 : xpr.cols()), - m_xpr(xpr) + m_xpr(xpr), + m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? i : 0), + m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? i : 0) { init(); } /** Fixed-size constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index startRow, Index startCol) - : Base(internal::const_cast_ptr(&xpr.coeffRef(startRow,startCol))), m_xpr(xpr) + : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol)), + m_xpr(xpr), m_startRow(startRow), m_startCol(startCol) { init(); } /** Dynamic-size constructor */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols) - : Base(internal::const_cast_ptr(&xpr.coeffRef(startRow,startCol)), blockRows, blockCols), - m_xpr(xpr) + : Base(xpr.data()+xpr.innerStride()*(XprTypeIsRowMajor?startCol:startRow) + xpr.outerStride()*(XprTypeIsRowMajor?startRow:startCol), blockRows, blockCols), + m_xpr(xpr), m_startRow(startRow), m_startCol(startCol) { init(); } - const typename internal::remove_all::type& nestedExpression() const + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + XprType& nestedExpression() { return m_xpr; } /** \sa MapBase::innerStride() */ + EIGEN_DEVICE_FUNC inline Index innerStride() const { return internal::traits::HasSameStorageOrderAsXprType @@ -366,11 +396,24 @@ class BlockImpl_dense } /** \sa MapBase::outerStride() */ + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_outerStride; } + EIGEN_DEVICE_FUNC + StorageIndex startRow() const + { + return m_startRow.value(); + } + + EIGEN_DEVICE_FUNC + StorageIndex startCol() const + { + return m_startCol.value(); + } + #ifndef __SUNPRO_CC // FIXME sunstudio is not friendly with the above friend... // META-FIXME there is no 'friend' keyword around here. Is this obsolete? @@ -379,6 +422,7 @@ class BlockImpl_dense #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal used by allowAligned() */ + EIGEN_DEVICE_FUNC inline BlockImpl_dense(XprType& xpr, const Scalar* data, Index blockRows, Index blockCols) : Base(data, blockRows, blockCols), m_xpr(xpr) { @@ -387,6 +431,7 @@ class BlockImpl_dense #endif protected: + EIGEN_DEVICE_FUNC void init() { m_outerStride = internal::traits::HasSameStorageOrderAsXprType @@ -394,7 +439,9 @@ class BlockImpl_dense : m_xpr.innerStride(); } - typename XprType::Nested m_xpr; + XprTypeNested m_xpr; + const internal::variable_if_dynamic m_startRow; + const internal::variable_if_dynamic m_startCol; Index m_outerStride; }; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h index be9f48a8c..8409d8749 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/BooleanRedux.h @@ -17,9 +17,10 @@ namespace internal { template struct all_unroller { + typedef typename Derived::ExpressionTraits Traits; enum { - col = (UnrollCount-1) / Derived::RowsAtCompileTime, - row = (UnrollCount-1) % Derived::RowsAtCompileTime + col = (UnrollCount-1) / Traits::RowsAtCompileTime, + row = (UnrollCount-1) % Traits::RowsAtCompileTime }; static inline bool run(const Derived &mat) @@ -43,11 +44,12 @@ struct all_unroller template struct any_unroller { + typedef typename Derived::ExpressionTraits Traits; enum { - col = (UnrollCount-1) / Derived::RowsAtCompileTime, - row = (UnrollCount-1) % Derived::RowsAtCompileTime + col = (UnrollCount-1) / Traits::RowsAtCompileTime, + row = (UnrollCount-1) % Traits::RowsAtCompileTime }; - + static inline bool run(const Derived &mat) { return any_unroller::run(mat) || mat.coeff(row, col); @@ -78,19 +80,19 @@ struct any_unroller template inline bool DenseBase::all() const { + typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && CoeffReadCost != Dynamic - && NumTraits::AddCost != Dynamic - && SizeAtCompileTime * (CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT }; + Evaluator evaluator(derived()); if(unroll) - return internal::all_unroller::run(derived()); + return internal::all_unroller::run(evaluator); else { for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if (!coeff(i, j)) return false; + if (!evaluator.coeff(i, j)) return false; return true; } } @@ -102,19 +104,19 @@ inline bool DenseBase::all() const template inline bool DenseBase::any() const { + typedef internal::evaluator Evaluator; enum { unroll = SizeAtCompileTime != Dynamic - && CoeffReadCost != Dynamic - && NumTraits::AddCost != Dynamic - && SizeAtCompileTime * (CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT + && SizeAtCompileTime * (Evaluator::CoeffReadCost + NumTraits::AddCost) <= EIGEN_UNROLLING_LIMIT }; + Evaluator evaluator(derived()); if(unroll) - return internal::any_unroller::run(derived()); + return internal::any_unroller::run(evaluator); else { for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if (coeff(i, j)) return true; + if (evaluator.coeff(i, j)) return true; return false; } } @@ -124,7 +126,7 @@ inline bool DenseBase::any() const * \sa all(), any() */ template -inline typename DenseBase::Index DenseBase::count() const +inline Eigen::Index DenseBase::count() const { return derived().template cast().template cast().sum(); } @@ -136,7 +138,11 @@ inline typename DenseBase::Index DenseBase::count() const template inline bool DenseBase::hasNaN() const { +#if EIGEN_COMP_MSVC || (defined __FAST_MATH__) + return derived().array().isNaN().any(); +#else return !((derived().array()==derived().array()).all()); +#endif } /** \returns true if \c *this contains only finite numbers, i.e., no NaN and no +/-INF values. @@ -146,7 +152,11 @@ inline bool DenseBase::hasNaN() const template inline bool DenseBase::allFinite() const { +#if EIGEN_COMP_MSVC || (defined __FAST_MATH__) + return derived().array().isFinite().all(); +#else return !((derived()-derived()).hasNaN()); +#endif } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CMakeLists.txt b/gtsam/3rdparty/Eigen/Eigen/src/Core/CMakeLists.txt deleted file mode 100644 index 2346fc2bb..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -FILE(GLOB Eigen_Core_SRCS "*.h") - -INSTALL(FILES - ${Eigen_Core_SRCS} - DESTINATION ${INCLUDE_INSTALL_DIR}/Eigen/src/Core COMPONENT Devel - ) - -ADD_SUBDIRECTORY(products) -ADD_SUBDIRECTORY(util) -ADD_SUBDIRECTORY(arch) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h index 5dd3adeae..d218e9814 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CommaInitializer.h @@ -22,14 +22,14 @@ namespace Eigen { * the return type of MatrixBase::operator<<, and most of the time this is the only * way it is used. * - * \sa \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() + * \sa \blank \ref MatrixBaseCommaInitRef "MatrixBase::operator<<", CommaInitializer::finished() */ template struct CommaInitializer { typedef typename XprType::Scalar Scalar; - typedef typename XprType::Index Index; + EIGEN_DEVICE_FUNC inline CommaInitializer(XprType& xpr, const Scalar& s) : m_xpr(xpr), m_row(0), m_col(1), m_currentBlockRows(1) { @@ -37,6 +37,7 @@ struct CommaInitializer } template + EIGEN_DEVICE_FUNC inline CommaInitializer(XprType& xpr, const DenseBase& other) : m_xpr(xpr), m_row(0), m_col(other.cols()), m_currentBlockRows(other.rows()) { @@ -46,6 +47,7 @@ struct CommaInitializer /* Copy/Move constructor which transfers ownership. This is crucial in * absence of return value optimization to avoid assertions during destruction. */ // FIXME in C++11 mode this could be replaced by a proper RValue constructor + EIGEN_DEVICE_FUNC inline CommaInitializer(const CommaInitializer& o) : m_xpr(o.m_xpr), m_row(o.m_row), m_col(o.m_col), m_currentBlockRows(o.m_currentBlockRows) { // Mark original object as finished. In absence of R-value references we need to const_cast: @@ -55,6 +57,7 @@ struct CommaInitializer } /* inserts a scalar value in the target matrix */ + EIGEN_DEVICE_FUNC CommaInitializer& operator,(const Scalar& s) { if (m_col==m_xpr.cols()) @@ -74,6 +77,7 @@ struct CommaInitializer /* inserts a matrix expression in the target matrix */ template + EIGEN_DEVICE_FUNC CommaInitializer& operator,(const DenseBase& other) { if (m_col==m_xpr.cols() && (other.cols()!=0 || other.rows()!=m_currentBlockRows)) @@ -93,7 +97,11 @@ struct CommaInitializer return *this; } + EIGEN_DEVICE_FUNC inline ~CommaInitializer() +#if defined VERIFY_RAISES_ASSERT && (!defined EIGEN_NO_ASSERTION_CHECKING) && defined EIGEN_EXCEPTIONS + EIGEN_EXCEPTION_SPEC(Eigen::eigen_assert_exception) +#endif { finished(); } @@ -105,6 +113,7 @@ struct CommaInitializer * quaternion.fromRotationMatrix((Matrix3f() << axis0, axis1, axis2).finished()); * \endcode */ + EIGEN_DEVICE_FUNC inline XprType& finished() { eigen_assert(((m_row+m_currentBlockRows) == m_xpr.rows() || m_xpr.cols() == 0) && m_col == m_xpr.cols() @@ -112,7 +121,7 @@ struct CommaInitializer return m_xpr; } - XprType& m_xpr; // target expression + XprType& m_xpr; // target expression Index m_row; // current row id Index m_col; // current col id Index m_currentBlockRows; // current block height diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ConditionEstimator.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ConditionEstimator.h new file mode 100644 index 000000000..aa7efdc76 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ConditionEstimator.h @@ -0,0 +1,175 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Rasmus Munk Larsen (rmlarsen@google.com) +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CONDITIONESTIMATOR_H +#define EIGEN_CONDITIONESTIMATOR_H + +namespace Eigen { + +namespace internal { + +template +struct rcond_compute_sign { + static inline Vector run(const Vector& v) { + const RealVector v_abs = v.cwiseAbs(); + return (v_abs.array() == static_cast(0)) + .select(Vector::Ones(v.size()), v.cwiseQuotient(v_abs)); + } +}; + +// Partial specialization to avoid elementwise division for real vectors. +template +struct rcond_compute_sign { + static inline Vector run(const Vector& v) { + return (v.array() < static_cast(0)) + .select(-Vector::Ones(v.size()), Vector::Ones(v.size())); + } +}; + +/** + * \returns an estimate of ||inv(matrix)||_1 given a decomposition of + * \a matrix that implements .solve() and .adjoint().solve() methods. + * + * This function implements Algorithms 4.1 and 5.1 from + * http://www.maths.manchester.ac.uk/~higham/narep/narep135.pdf + * which also forms the basis for the condition number estimators in + * LAPACK. Since at most 10 calls to the solve method of dec are + * performed, the total cost is O(dims^2), as opposed to O(dims^3) + * needed to compute the inverse matrix explicitly. + * + * The most common usage is in estimating the condition number + * ||matrix||_1 * ||inv(matrix)||_1. The first term ||matrix||_1 can be + * computed directly in O(n^2) operations. + * + * Supports the following decompositions: FullPivLU, PartialPivLU, LDLT, and + * LLT. + * + * \sa FullPivLU, PartialPivLU, LDLT, LLT. + */ +template +typename Decomposition::RealScalar rcond_invmatrix_L1_norm_estimate(const Decomposition& dec) +{ + typedef typename Decomposition::MatrixType MatrixType; + typedef typename Decomposition::Scalar Scalar; + typedef typename Decomposition::RealScalar RealScalar; + typedef typename internal::plain_col_type::type Vector; + typedef typename internal::plain_col_type::type RealVector; + const bool is_complex = (NumTraits::IsComplex != 0); + + eigen_assert(dec.rows() == dec.cols()); + const Index n = dec.rows(); + if (n == 0) + return 0; + + // Disable Index to float conversion warning +#ifdef __INTEL_COMPILER + #pragma warning push + #pragma warning ( disable : 2259 ) +#endif + Vector v = dec.solve(Vector::Ones(n) / Scalar(n)); +#ifdef __INTEL_COMPILER + #pragma warning pop +#endif + + // lower_bound is a lower bound on + // ||inv(matrix)||_1 = sup_v ||inv(matrix) v||_1 / ||v||_1 + // and is the objective maximized by the ("super-") gradient ascent + // algorithm below. + RealScalar lower_bound = v.template lpNorm<1>(); + if (n == 1) + return lower_bound; + + // Gradient ascent algorithm follows: We know that the optimum is achieved at + // one of the simplices v = e_i, so in each iteration we follow a + // super-gradient to move towards the optimal one. + RealScalar old_lower_bound = lower_bound; + Vector sign_vector(n); + Vector old_sign_vector; + Index v_max_abs_index = -1; + Index old_v_max_abs_index = v_max_abs_index; + for (int k = 0; k < 4; ++k) + { + sign_vector = internal::rcond_compute_sign::run(v); + if (k > 0 && !is_complex && sign_vector == old_sign_vector) { + // Break if the solution stagnated. + break; + } + // v_max_abs_index = argmax |real( inv(matrix)^T * sign_vector )| + v = dec.adjoint().solve(sign_vector); + v.real().cwiseAbs().maxCoeff(&v_max_abs_index); + if (v_max_abs_index == old_v_max_abs_index) { + // Break if the solution stagnated. + break; + } + // Move to the new simplex e_j, where j = v_max_abs_index. + v = dec.solve(Vector::Unit(n, v_max_abs_index)); // v = inv(matrix) * e_j. + lower_bound = v.template lpNorm<1>(); + if (lower_bound <= old_lower_bound) { + // Break if the gradient step did not increase the lower_bound. + break; + } + if (!is_complex) { + old_sign_vector = sign_vector; + } + old_v_max_abs_index = v_max_abs_index; + old_lower_bound = lower_bound; + } + // The following calculates an independent estimate of ||matrix||_1 by + // multiplying matrix by a vector with entries of slowly increasing + // magnitude and alternating sign: + // v_i = (-1)^{i} (1 + (i / (dim-1))), i = 0,...,dim-1. + // This improvement to Hager's algorithm above is due to Higham. It was + // added to make the algorithm more robust in certain corner cases where + // large elements in the matrix might otherwise escape detection due to + // exact cancellation (especially when op and op_adjoint correspond to a + // sequence of backsubstitutions and permutations), which could cause + // Hager's algorithm to vastly underestimate ||matrix||_1. + Scalar alternating_sign(RealScalar(1)); + for (Index i = 0; i < n; ++i) { + // The static_cast is needed when Scalar is a complex and RealScalar implements expression templates + v[i] = alternating_sign * static_cast(RealScalar(1) + (RealScalar(i) / (RealScalar(n - 1)))); + alternating_sign = -alternating_sign; + } + v = dec.solve(v); + const RealScalar alternate_lower_bound = (2 * v.template lpNorm<1>()) / (3 * RealScalar(n)); + return numext::maxi(lower_bound, alternate_lower_bound); +} + +/** \brief Reciprocal condition number estimator. + * + * Computing a decomposition of a dense matrix takes O(n^3) operations, while + * this method estimates the condition number quickly and reliably in O(n^2) + * operations. + * + * \returns an estimate of the reciprocal condition number + * (1 / (||matrix||_1 * ||inv(matrix)||_1)) of matrix, given ||matrix||_1 and + * its decomposition. Supports the following decompositions: FullPivLU, + * PartialPivLU, LDLT, and LLT. + * + * \sa FullPivLU, PartialPivLU, LDLT, LLT. + */ +template +typename Decomposition::RealScalar +rcond_estimate_helper(typename Decomposition::RealScalar matrix_norm, const Decomposition& dec) +{ + typedef typename Decomposition::RealScalar RealScalar; + eigen_assert(dec.rows() == dec.cols()); + if (dec.rows() == 0) return RealScalar(1); + if (matrix_norm == RealScalar(0)) return RealScalar(0); + if (dec.rows() == 1) return RealScalar(1); + const RealScalar inverse_matrix_norm = rcond_invmatrix_L1_norm_estimate(dec); + return (inverse_matrix_norm == RealScalar(0) ? RealScalar(0) + : (RealScalar(1) / inverse_matrix_norm) / matrix_norm); +} + +} // namespace internal + +} // namespace Eigen + +#endif diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreEvaluators.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreEvaluators.h new file mode 100644 index 000000000..f7c1effca --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreEvaluators.h @@ -0,0 +1,1671 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2011-2014 Gael Guennebaud +// Copyright (C) 2011-2012 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#ifndef EIGEN_COREEVALUATORS_H +#define EIGEN_COREEVALUATORS_H + +namespace Eigen { + +namespace internal { + +// This class returns the evaluator kind from the expression storage kind. +// Default assumes index based accessors +template +struct storage_kind_to_evaluator_kind { + typedef IndexBased Kind; +}; + +// This class returns the evaluator shape from the expression storage kind. +// It can be Dense, Sparse, Triangular, Diagonal, SelfAdjoint, Band, etc. +template struct storage_kind_to_shape; + +template<> struct storage_kind_to_shape { typedef DenseShape Shape; }; +template<> struct storage_kind_to_shape { typedef SolverShape Shape; }; +template<> struct storage_kind_to_shape { typedef PermutationShape Shape; }; +template<> struct storage_kind_to_shape { typedef TranspositionsShape Shape; }; + +// Evaluators have to be specialized with respect to various criteria such as: +// - storage/structure/shape +// - scalar type +// - etc. +// Therefore, we need specialization of evaluator providing additional template arguments for each kind of evaluators. +// We currently distinguish the following kind of evaluators: +// - unary_evaluator for expressions taking only one arguments (CwiseUnaryOp, CwiseUnaryView, Transpose, MatrixWrapper, ArrayWrapper, Reverse, Replicate) +// - binary_evaluator for expression taking two arguments (CwiseBinaryOp) +// - ternary_evaluator for expression taking three arguments (CwiseTernaryOp) +// - product_evaluator for linear algebra products (Product); special case of binary_evaluator because it requires additional tags for dispatching. +// - mapbase_evaluator for Map, Block, Ref +// - block_evaluator for Block (special dispatching to a mapbase_evaluator or unary_evaluator) + +template< typename T, + typename Arg1Kind = typename evaluator_traits::Kind, + typename Arg2Kind = typename evaluator_traits::Kind, + typename Arg3Kind = typename evaluator_traits::Kind, + typename Arg1Scalar = typename traits::Scalar, + typename Arg2Scalar = typename traits::Scalar, + typename Arg3Scalar = typename traits::Scalar> struct ternary_evaluator; + +template< typename T, + typename LhsKind = typename evaluator_traits::Kind, + typename RhsKind = typename evaluator_traits::Kind, + typename LhsScalar = typename traits::Scalar, + typename RhsScalar = typename traits::Scalar> struct binary_evaluator; + +template< typename T, + typename Kind = typename evaluator_traits::Kind, + typename Scalar = typename T::Scalar> struct unary_evaluator; + +// evaluator_traits contains traits for evaluator + +template +struct evaluator_traits_base +{ + // by default, get evaluator kind and shape from storage + typedef typename storage_kind_to_evaluator_kind::StorageKind>::Kind Kind; + typedef typename storage_kind_to_shape::StorageKind>::Shape Shape; +}; + +// Default evaluator traits +template +struct evaluator_traits : public evaluator_traits_base +{ +}; + +template::Shape > +struct evaluator_assume_aliasing { + static const bool value = false; +}; + +// By default, we assume a unary expression: +template +struct evaluator : public unary_evaluator +{ + typedef unary_evaluator Base; + EIGEN_DEVICE_FUNC explicit evaluator(const T& xpr) : Base(xpr) {} +}; + + +// TODO: Think about const-correctness +template +struct evaluator + : evaluator +{ + EIGEN_DEVICE_FUNC + explicit evaluator(const T& xpr) : evaluator(xpr) {} +}; + +// ---------- base class for all evaluators ---------- + +template +struct evaluator_base : public noncopyable +{ + // TODO that's not very nice to have to propagate all these traits. They are currently only needed to handle outer,inner indices. + typedef traits ExpressionTraits; + + enum { + Alignment = 0 + }; +}; + +// -------------------- Matrix and Array -------------------- +// +// evaluator is a common base class for the +// Matrix and Array evaluators. +// Here we directly specialize evaluator. This is not really a unary expression, and it is, by definition, dense, +// so no need for more sophisticated dispatching. + +template +struct evaluator > + : evaluator_base +{ + typedef PlainObjectBase PlainObjectType; + typedef typename PlainObjectType::Scalar Scalar; + typedef typename PlainObjectType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = PlainObjectType::IsRowMajor, + IsVectorAtCompileTime = PlainObjectType::IsVectorAtCompileTime, + RowsAtCompileTime = PlainObjectType::RowsAtCompileTime, + ColsAtCompileTime = PlainObjectType::ColsAtCompileTime, + + CoeffReadCost = NumTraits::ReadCost, + Flags = traits::EvaluatorFlags, + Alignment = traits::Alignment + }; + + EIGEN_DEVICE_FUNC evaluator() + : m_data(0), + m_outerStride(IsVectorAtCompileTime ? 0 + : int(IsRowMajor) ? ColsAtCompileTime + : RowsAtCompileTime) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC explicit evaluator(const PlainObjectType& m) + : m_data(m.data()), m_outerStride(IsVectorAtCompileTime ? 0 : m.outerStride()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + if (IsRowMajor) + return m_data[row * m_outerStride.value() + col]; + else + return m_data[row + col * m_outerStride.value()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_data[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + if (IsRowMajor) + return const_cast(m_data)[row * m_outerStride.value() + col]; + else + return const_cast(m_data)[row + col * m_outerStride.value()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return const_cast(m_data)[index]; + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + if (IsRowMajor) + return ploadt(m_data + row * m_outerStride.value() + col); + else + return ploadt(m_data + row + col * m_outerStride.value()); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return ploadt(m_data + index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + if (IsRowMajor) + return pstoret + (const_cast(m_data) + row * m_outerStride.value() + col, x); + else + return pstoret + (const_cast(m_data) + row + col * m_outerStride.value(), x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + return pstoret(const_cast(m_data) + index, x); + } + +protected: + const Scalar *m_data; + + // We do not need to know the outer stride for vectors + variable_if_dynamic m_outerStride; +}; + +template +struct evaluator > + : evaluator > > +{ + typedef Matrix XprType; + + EIGEN_DEVICE_FUNC evaluator() {} + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) + : evaluator >(m) + { } +}; + +template +struct evaluator > + : evaluator > > +{ + typedef Array XprType; + + EIGEN_DEVICE_FUNC evaluator() {} + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& m) + : evaluator >(m) + { } +}; + +// -------------------- Transpose -------------------- + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef Transpose XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = evaluator::Flags ^ RowMajorBit, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& t) : m_argImpl(t.nestedExpression()) {} + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(col, row); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(col, row); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename XprType::Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(col, row); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_argImpl.template packet(index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + m_argImpl.template writePacket(col, row, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + m_argImpl.template writePacket(index, x); + } + +protected: + evaluator m_argImpl; +}; + +// -------------------- CwiseNullaryOp -------------------- +// Like Matrix and Array, this is not really a unary expression, so we directly specialize evaluator. +// Likewise, there is not need to more sophisticated dispatching here. + +template::value, + bool has_unary = has_unary_operator::value, + bool has_binary = has_binary_operator::value> +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { return op(i,j); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { return op(i); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { return op.template packetOp(i,j); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { return op.template packetOp(i); } +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType=0, IndexType=0) const { return op(); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType=0, IndexType=0) const { return op.template packetOp(); } +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j=0) const { return op(i,j); } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j=0) const { return op.template packetOp(i,j); } +}; + +// We need the following specialization for vector-only functors assigned to a runtime vector, +// for instance, using linspace and assigning a RowVectorXd to a MatrixXd or even a row of a MatrixXd. +// In this case, i==0 and j is used for the actual iteration. +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { + eigen_assert(i==0 || j==0); + return op(i+j); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { + eigen_assert(i==0 || j==0); + return op.template packetOp(i+j); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { return op(i); } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { return op.template packetOp(i); } +}; + +template +struct nullary_wrapper {}; + +#if 0 && EIGEN_COMP_MSVC>0 +// Disable this ugly workaround. This is now handled in traits::match, +// but this piece of code might still become handly if some other weird compilation +// erros pop up again. + +// MSVC exhibits a weird compilation error when +// compiling: +// Eigen::MatrixXf A = MatrixXf::Random(3,3); +// Ref R = 2.f*A; +// and that has_*ary_operator> have not been instantiated yet. +// The "problem" is that evaluator<2.f*A> is instantiated by traits::match<2.f*A> +// and at that time has_*ary_operator returns true regardless of T. +// Then nullary_wrapper is badly instantiated as nullary_wrapper<.,.,true,true,true>. +// The trick is thus to defer the proper instantiation of nullary_wrapper when coeff(), +// and packet() are really instantiated as implemented below: + +// This is a simple wrapper around Index to enforce the re-instantiation of +// has_*ary_operator when needed. +template struct nullary_wrapper_workaround_msvc { + nullary_wrapper_workaround_msvc(const T&); + operator T()const; +}; + +template +struct nullary_wrapper +{ + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i, IndexType j) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().operator()(op,i,j); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator()(const NullaryOp& op, IndexType i) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().operator()(op,i); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i, IndexType j) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().template packetOp(op,i,j); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T packetOp(const NullaryOp& op, IndexType i) const { + return nullary_wrapper >::value, + has_unary_operator >::value, + has_binary_operator >::value>().template packetOp(op,i); + } +}; +#endif // MSVC workaround + +template +struct evaluator > + : evaluator_base > +{ + typedef CwiseNullaryOp XprType; + typedef typename internal::remove_all::type PlainObjectTypeCleaned; + + enum { + CoeffReadCost = internal::functor_traits::Cost, + + Flags = (evaluator::Flags + & ( HereditaryBits + | (functor_has_linear_access::ret ? LinearAccessBit : 0) + | (functor_traits::PacketAccess ? PacketAccessBit : 0))) + | (functor_traits::IsRepeatable ? 0 : EvalBeforeNestingBit), + Alignment = AlignedMax + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& n) + : m_functor(n.functor()), m_wrapper() + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(IndexType row, IndexType col) const + { + return m_wrapper(m_functor, row, col); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(IndexType index) const + { + return m_wrapper(m_functor,index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(IndexType row, IndexType col) const + { + return m_wrapper.template packetOp(m_functor, row, col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(IndexType index) const + { + return m_wrapper.template packetOp(m_functor, index); + } + +protected: + const NullaryOp m_functor; + const internal::nullary_wrapper m_wrapper; +}; + +// -------------------- CwiseUnaryOp -------------------- + +template +struct unary_evaluator, IndexBased > + : evaluator_base > +{ + typedef CwiseUnaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + + Flags = evaluator::Flags + & (HereditaryBits | LinearAccessBit | (functor_traits::PacketAccess ? PacketAccessBit : 0)), + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit unary_evaluator(const XprType& op) + : m_functor(op.functor()), + m_argImpl(op.nestedExpression()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_functor(m_argImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_functor(m_argImpl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_functor.packetOp(m_argImpl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_functor.packetOp(m_argImpl.template packet(index)); + } + +protected: + const UnaryOp m_functor; + evaluator m_argImpl; +}; + +// -------------------- CwiseTernaryOp -------------------- + +// this is a ternary expression +template +struct evaluator > + : public ternary_evaluator > +{ + typedef CwiseTernaryOp XprType; + typedef ternary_evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +template +struct ternary_evaluator, IndexBased, IndexBased> + : evaluator_base > +{ + typedef CwiseTernaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + + Arg1Flags = evaluator::Flags, + Arg2Flags = evaluator::Flags, + Arg3Flags = evaluator::Flags, + SameType = is_same::value && is_same::value, + StorageOrdersAgree = (int(Arg1Flags)&RowMajorBit)==(int(Arg2Flags)&RowMajorBit) && (int(Arg1Flags)&RowMajorBit)==(int(Arg3Flags)&RowMajorBit), + Flags0 = (int(Arg1Flags) | int(Arg2Flags) | int(Arg3Flags)) & ( + HereditaryBits + | (int(Arg1Flags) & int(Arg2Flags) & int(Arg3Flags) & + ( (StorageOrdersAgree ? LinearAccessBit : 0) + | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) + ) + ) + ), + Flags = (Flags0 & ~RowMajorBit) | (Arg1Flags & RowMajorBit), + Alignment = EIGEN_PLAIN_ENUM_MIN( + EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, evaluator::Alignment), + evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit ternary_evaluator(const XprType& xpr) + : m_functor(xpr.functor()), + m_arg1Impl(xpr.arg1()), + m_arg2Impl(xpr.arg2()), + m_arg3Impl(xpr.arg3()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_functor(m_arg1Impl.coeff(row, col), m_arg2Impl.coeff(row, col), m_arg3Impl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_functor(m_arg1Impl.coeff(index), m_arg2Impl.coeff(index), m_arg3Impl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_functor.packetOp(m_arg1Impl.template packet(row, col), + m_arg2Impl.template packet(row, col), + m_arg3Impl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_functor.packetOp(m_arg1Impl.template packet(index), + m_arg2Impl.template packet(index), + m_arg3Impl.template packet(index)); + } + +protected: + const TernaryOp m_functor; + evaluator m_arg1Impl; + evaluator m_arg2Impl; + evaluator m_arg3Impl; +}; + +// -------------------- CwiseBinaryOp -------------------- + +// this is a binary expression +template +struct evaluator > + : public binary_evaluator > +{ + typedef CwiseBinaryOp XprType; + typedef binary_evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +template +struct binary_evaluator, IndexBased, IndexBased> + : evaluator_base > +{ + typedef CwiseBinaryOp XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + evaluator::CoeffReadCost + functor_traits::Cost, + + LhsFlags = evaluator::Flags, + RhsFlags = evaluator::Flags, + SameType = is_same::value, + StorageOrdersAgree = (int(LhsFlags)&RowMajorBit)==(int(RhsFlags)&RowMajorBit), + Flags0 = (int(LhsFlags) | int(RhsFlags)) & ( + HereditaryBits + | (int(LhsFlags) & int(RhsFlags) & + ( (StorageOrdersAgree ? LinearAccessBit : 0) + | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) + ) + ) + ), + Flags = (Flags0 & ~RowMajorBit) | (LhsFlags & RowMajorBit), + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment,evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit binary_evaluator(const XprType& xpr) + : m_functor(xpr.functor()), + m_lhsImpl(xpr.lhs()), + m_rhsImpl(xpr.rhs()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_functor(m_lhsImpl.coeff(row, col), m_rhsImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_functor(m_lhsImpl.coeff(index), m_rhsImpl.coeff(index)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_functor.packetOp(m_lhsImpl.template packet(row, col), + m_rhsImpl.template packet(row, col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_functor.packetOp(m_lhsImpl.template packet(index), + m_rhsImpl.template packet(index)); + } + +protected: + const BinaryOp m_functor; + evaluator m_lhsImpl; + evaluator m_rhsImpl; +}; + +// -------------------- CwiseUnaryView -------------------- + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef CwiseUnaryView XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost + functor_traits::Cost, + + Flags = (evaluator::Flags & (HereditaryBits | LinearAccessBit | DirectAccessBit)), + + Alignment = 0 // FIXME it is not very clear why alignment is necessarily lost... + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& op) + : m_unaryOp(op.functor()), + m_argImpl(op.nestedExpression()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits::Cost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_unaryOp(m_argImpl.coeff(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_unaryOp(m_argImpl.coeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_unaryOp(m_argImpl.coeffRef(row, col)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_unaryOp(m_argImpl.coeffRef(index)); + } + +protected: + const UnaryOp m_unaryOp; + evaluator m_argImpl; +}; + +// -------------------- Map -------------------- + +// FIXME perhaps the PlainObjectType could be provided by Derived::PlainObject ? +// but that might complicate template specialization +template +struct mapbase_evaluator; + +template +struct mapbase_evaluator : evaluator_base +{ + typedef Derived XprType; + typedef typename XprType::PointerType PointerType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = XprType::RowsAtCompileTime, + ColsAtCompileTime = XprType::ColsAtCompileTime, + CoeffReadCost = NumTraits::ReadCost + }; + + EIGEN_DEVICE_FUNC explicit mapbase_evaluator(const XprType& map) + : m_data(const_cast(map.data())), + m_innerStride(map.innerStride()), + m_outerStride(map.outerStride()) + { + EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(evaluator::Flags&PacketAccessBit, internal::inner_stride_at_compile_time::ret==1), + PACKET_ACCESS_REQUIRES_TO_HAVE_INNER_STRIDE_FIXED_TO_1); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_data[col * colStride() + row * rowStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_data[index * m_innerStride.value()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_data[col * colStride() + row * rowStride()]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_data[index * m_innerStride.value()]; + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + PointerType ptr = m_data + row * rowStride() + col * colStride(); + return internal::ploadt(ptr); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return internal::ploadt(m_data + index * m_innerStride.value()); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + PointerType ptr = m_data + row * rowStride() + col * colStride(); + return internal::pstoret(ptr, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + internal::pstoret(m_data + index * m_innerStride.value(), x); + } +protected: + EIGEN_DEVICE_FUNC + inline Index rowStride() const { return XprType::IsRowMajor ? m_outerStride.value() : m_innerStride.value(); } + EIGEN_DEVICE_FUNC + inline Index colStride() const { return XprType::IsRowMajor ? m_innerStride.value() : m_outerStride.value(); } + + PointerType m_data; + const internal::variable_if_dynamic m_innerStride; + const internal::variable_if_dynamic m_outerStride; +}; + +template +struct evaluator > + : public mapbase_evaluator, PlainObjectType> +{ + typedef Map XprType; + typedef typename XprType::Scalar Scalar; + // TODO: should check for smaller packet types once we can handle multi-sized packet types + typedef typename packet_traits::type PacketScalar; + + enum { + InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 + ? int(PlainObjectType::InnerStrideAtCompileTime) + : int(StrideType::InnerStrideAtCompileTime), + OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 + ? int(PlainObjectType::OuterStrideAtCompileTime) + : int(StrideType::OuterStrideAtCompileTime), + HasNoInnerStride = InnerStrideAtCompileTime == 1, + HasNoOuterStride = StrideType::OuterStrideAtCompileTime == 0, + HasNoStride = HasNoInnerStride && HasNoOuterStride, + IsDynamicSize = PlainObjectType::SizeAtCompileTime==Dynamic, + + PacketAccessMask = bool(HasNoInnerStride) ? ~int(0) : ~int(PacketAccessBit), + LinearAccessMask = bool(HasNoStride) || bool(PlainObjectType::IsVectorAtCompileTime) ? ~int(0) : ~int(LinearAccessBit), + Flags = int( evaluator::Flags) & (LinearAccessMask&PacketAccessMask), + + Alignment = int(MapOptions)&int(AlignedMask) + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& map) + : mapbase_evaluator(map) + { } +}; + +// -------------------- Ref -------------------- + +template +struct evaluator > + : public mapbase_evaluator, PlainObjectType> +{ + typedef Ref XprType; + + enum { + Flags = evaluator >::Flags, + Alignment = evaluator >::Alignment + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& ref) + : mapbase_evaluator(ref) + { } +}; + +// -------------------- Block -------------------- + +template::ret> struct block_evaluator; + +template +struct evaluator > + : block_evaluator +{ + typedef Block XprType; + typedef typename XprType::Scalar Scalar; + // TODO: should check for smaller packet types once we can handle multi-sized packet types + typedef typename packet_traits::type PacketScalar; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + + RowsAtCompileTime = traits::RowsAtCompileTime, + ColsAtCompileTime = traits::ColsAtCompileTime, + MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = traits::MaxColsAtCompileTime, + + ArgTypeIsRowMajor = (int(evaluator::Flags)&RowMajorBit) != 0, + IsRowMajor = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 + : ArgTypeIsRowMajor, + HasSameStorageOrderAsArgType = (IsRowMajor == ArgTypeIsRowMajor), + InnerSize = IsRowMajor ? int(ColsAtCompileTime) : int(RowsAtCompileTime), + InnerStrideAtCompileTime = HasSameStorageOrderAsArgType + ? int(inner_stride_at_compile_time::ret) + : int(outer_stride_at_compile_time::ret), + OuterStrideAtCompileTime = HasSameStorageOrderAsArgType + ? int(outer_stride_at_compile_time::ret) + : int(inner_stride_at_compile_time::ret), + MaskPacketAccessBit = (InnerStrideAtCompileTime == 1) ? PacketAccessBit : 0, + + FlagsLinearAccessBit = (RowsAtCompileTime == 1 || ColsAtCompileTime == 1 || (InnerPanel && (evaluator::Flags&LinearAccessBit))) ? LinearAccessBit : 0, + FlagsRowMajorBit = XprType::Flags&RowMajorBit, + Flags0 = evaluator::Flags & ( (HereditaryBits & ~RowMajorBit) | + DirectAccessBit | + MaskPacketAccessBit), + Flags = Flags0 | FlagsLinearAccessBit | FlagsRowMajorBit, + + PacketAlignment = unpacket_traits::alignment, + Alignment0 = (InnerPanel && (OuterStrideAtCompileTime!=Dynamic) && (((OuterStrideAtCompileTime * int(sizeof(Scalar))) % int(PacketAlignment)) == 0)) ? int(PacketAlignment) : 0, + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, Alignment0) + }; + typedef block_evaluator block_evaluator_type; + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& block) : block_evaluator_type(block) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } +}; + +// no direct-access => dispatch to a unary evaluator +template +struct block_evaluator + : unary_evaluator > +{ + typedef Block XprType; + + EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) + : unary_evaluator(block) + {} +}; + +template +struct unary_evaluator, IndexBased> + : evaluator_base > +{ + typedef Block XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& block) + : m_argImpl(block.nestedExpression()), + m_startRow(block.startRow()), + m_startCol(block.startCol()) + { } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + RowsAtCompileTime = XprType::RowsAtCompileTime + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(m_startRow.value() + row, m_startCol.value() + col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return coeff(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(m_startRow.value() + row, m_startCol.value() + col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return coeffRef(RowsAtCompileTime == 1 ? 0 : index, RowsAtCompileTime == 1 ? index : 0); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(m_startRow.value() + row, m_startCol.value() + col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return packet(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + return m_argImpl.template writePacket(m_startRow.value() + row, m_startCol.value() + col, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + return writePacket(RowsAtCompileTime == 1 ? 0 : index, + RowsAtCompileTime == 1 ? index : 0, + x); + } + +protected: + evaluator m_argImpl; + const variable_if_dynamic m_startRow; + const variable_if_dynamic m_startCol; +}; + +// TODO: This evaluator does not actually use the child evaluator; +// all action is via the data() as returned by the Block expression. + +template +struct block_evaluator + : mapbase_evaluator, + typename Block::PlainObject> +{ + typedef Block XprType; + typedef typename XprType::Scalar Scalar; + + EIGEN_DEVICE_FUNC explicit block_evaluator(const XprType& block) + : mapbase_evaluator(block) + { + // TODO: for the 3.3 release, this should be turned to an internal assertion, but let's keep it as is for the beta lifetime + eigen_assert(((internal::UIntPtr(block.data()) % EIGEN_PLAIN_ENUM_MAX(1,evaluator::Alignment)) == 0) && "data is not aligned"); + } +}; + + +// -------------------- Select -------------------- +// NOTE shall we introduce a ternary_evaluator? + +// TODO enable vectorization for Select +template +struct evaluator > + : evaluator_base > +{ + typedef Select XprType; + enum { + CoeffReadCost = evaluator::CoeffReadCost + + EIGEN_PLAIN_ENUM_MAX(evaluator::CoeffReadCost, + evaluator::CoeffReadCost), + + Flags = (unsigned int)evaluator::Flags & evaluator::Flags & HereditaryBits, + + Alignment = EIGEN_PLAIN_ENUM_MIN(evaluator::Alignment, evaluator::Alignment) + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& select) + : m_conditionImpl(select.conditionMatrix()), + m_thenImpl(select.thenMatrix()), + m_elseImpl(select.elseMatrix()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + if (m_conditionImpl.coeff(row, col)) + return m_thenImpl.coeff(row, col); + else + return m_elseImpl.coeff(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + if (m_conditionImpl.coeff(index)) + return m_thenImpl.coeff(index); + else + return m_elseImpl.coeff(index); + } + +protected: + evaluator m_conditionImpl; + evaluator m_thenImpl; + evaluator m_elseImpl; +}; + + +// -------------------- Replicate -------------------- + +template +struct unary_evaluator > + : evaluator_base > +{ + typedef Replicate XprType; + typedef typename XprType::CoeffReturnType CoeffReturnType; + enum { + Factor = (RowFactor==Dynamic || ColFactor==Dynamic) ? Dynamic : RowFactor*ColFactor + }; + typedef typename internal::nested_eval::type ArgTypeNested; + typedef typename internal::remove_all::type ArgTypeNestedCleaned; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + LinearAccessMask = XprType::IsVectorAtCompileTime ? LinearAccessBit : 0, + Flags = (evaluator::Flags & (HereditaryBits|LinearAccessMask) & ~RowMajorBit) | (traits::Flags & RowMajorBit), + + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& replicate) + : m_arg(replicate.nestedExpression()), + m_argImpl(m_arg), + m_rows(replicate.nestedExpression().rows()), + m_cols(replicate.nestedExpression().cols()) + {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + // try to avoid using modulo; this is a pure optimization strategy + const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 + : RowFactor==1 ? row + : row % m_rows.value(); + const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 + : ColFactor==1 ? col + : col % m_cols.value(); + + return m_argImpl.coeff(actual_row, actual_col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + // try to avoid using modulo; this is a pure optimization strategy + const Index actual_index = internal::traits::RowsAtCompileTime==1 + ? (ColFactor==1 ? index : index%m_cols.value()) + : (RowFactor==1 ? index : index%m_rows.value()); + + return m_argImpl.coeff(actual_index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 + : RowFactor==1 ? row + : row % m_rows.value(); + const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 + : ColFactor==1 ? col + : col % m_cols.value(); + + return m_argImpl.template packet(actual_row, actual_col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + const Index actual_index = internal::traits::RowsAtCompileTime==1 + ? (ColFactor==1 ? index : index%m_cols.value()) + : (RowFactor==1 ? index : index%m_rows.value()); + + return m_argImpl.template packet(actual_index); + } + +protected: + const ArgTypeNested m_arg; + evaluator m_argImpl; + const variable_if_dynamic m_rows; + const variable_if_dynamic m_cols; +}; + + +// -------------------- PartialReduxExpr -------------------- + +template< typename ArgType, typename MemberOp, int Direction> +struct evaluator > + : evaluator_base > +{ + typedef PartialReduxExpr XprType; + typedef typename internal::nested_eval::type ArgTypeNested; + typedef typename internal::remove_all::type ArgTypeNestedCleaned; + typedef typename ArgType::Scalar InputScalar; + typedef typename XprType::Scalar Scalar; + enum { + TraversalSize = Direction==int(Vertical) ? int(ArgType::RowsAtCompileTime) : int(ArgType::ColsAtCompileTime) + }; + typedef typename MemberOp::template Cost CostOpType; + enum { + CoeffReadCost = TraversalSize==Dynamic ? HugeCost + : TraversalSize * evaluator::CoeffReadCost + int(CostOpType::value), + + Flags = (traits::Flags&RowMajorBit) | (evaluator::Flags&(HereditaryBits&(~RowMajorBit))) | LinearAccessBit, + + Alignment = 0 // FIXME this will need to be improved once PartialReduxExpr is vectorized + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType xpr) + : m_arg(xpr.nestedExpression()), m_functor(xpr.functor()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(TraversalSize==Dynamic ? HugeCost : int(CostOpType::value)); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index i, Index j) const + { + if (Direction==Vertical) + return m_functor(m_arg.col(j)); + else + return m_functor(m_arg.row(i)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Scalar coeff(Index index) const + { + if (Direction==Vertical) + return m_functor(m_arg.col(index)); + else + return m_functor(m_arg.row(index)); + } + +protected: + typename internal::add_const_on_value_type::type m_arg; + const MemberOp m_functor; +}; + + +// -------------------- MatrixWrapper and ArrayWrapper -------------------- +// +// evaluator_wrapper_base is a common base class for the +// MatrixWrapper and ArrayWrapper evaluators. + +template +struct evaluator_wrapper_base + : evaluator_base +{ + typedef typename remove_all::type ArgType; + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = evaluator::Flags, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC explicit evaluator_wrapper_base(const ArgType& arg) : m_argImpl(arg) {} + + typedef typename ArgType::Scalar Scalar; + typedef typename ArgType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(row, col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + return m_argImpl.template packet(row, col); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + return m_argImpl.template packet(index); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + m_argImpl.template writePacket(row, col, x); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + m_argImpl.template writePacket(index, x); + } + +protected: + evaluator m_argImpl; +}; + +template +struct unary_evaluator > + : evaluator_wrapper_base > +{ + typedef MatrixWrapper XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + : evaluator_wrapper_base >(wrapper.nestedExpression()) + { } +}; + +template +struct unary_evaluator > + : evaluator_wrapper_base > +{ + typedef ArrayWrapper XprType; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& wrapper) + : evaluator_wrapper_base >(wrapper.nestedExpression()) + { } +}; + + +// -------------------- Reverse -------------------- + +// defined in Reverse.h: +template struct reverse_packet_cond; + +template +struct unary_evaluator > + : evaluator_base > +{ + typedef Reverse XprType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + IsRowMajor = XprType::IsRowMajor, + IsColMajor = !IsRowMajor, + ReverseRow = (Direction == Vertical) || (Direction == BothDirections), + ReverseCol = (Direction == Horizontal) || (Direction == BothDirections), + ReversePacket = (Direction == BothDirections) + || ((Direction == Vertical) && IsColMajor) + || ((Direction == Horizontal) && IsRowMajor), + + CoeffReadCost = evaluator::CoeffReadCost, + + // let's enable LinearAccess only with vectorization because of the product overhead + // FIXME enable DirectAccess with negative strides? + Flags0 = evaluator::Flags, + LinearAccess = ( (Direction==BothDirections) && (int(Flags0)&PacketAccessBit) ) + || ((ReverseRow && XprType::ColsAtCompileTime==1) || (ReverseCol && XprType::RowsAtCompileTime==1)) + ? LinearAccessBit : 0, + + Flags = int(Flags0) & (HereditaryBits | PacketAccessBit | LinearAccess), + + Alignment = 0 // FIXME in some rare cases, Alignment could be preserved, like a Vector4f. + }; + + EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& reverse) + : m_argImpl(reverse.nestedExpression()), + m_rows(ReverseRow ? reverse.nestedExpression().rows() : 1), + m_cols(ReverseCol ? reverse.nestedExpression().cols() : 1) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index col) const + { + return m_argImpl.coeff(ReverseRow ? m_rows.value() - row - 1 : row, + ReverseCol ? m_cols.value() - col - 1 : col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(m_rows.value() * m_cols.value() - index - 1); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index col) + { + return m_argImpl.coeffRef(ReverseRow ? m_rows.value() - row - 1 : row, + ReverseCol ? m_cols.value() - col - 1 : col); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(m_rows.value() * m_cols.value() - index - 1); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index row, Index col) const + { + enum { + PacketSize = unpacket_traits::size, + OffsetRow = ReverseRow && IsColMajor ? PacketSize : 1, + OffsetCol = ReverseCol && IsRowMajor ? PacketSize : 1 + }; + typedef internal::reverse_packet_cond reverse_packet; + return reverse_packet::run(m_argImpl.template packet( + ReverseRow ? m_rows.value() - row - OffsetRow : row, + ReverseCol ? m_cols.value() - col - OffsetCol : col)); + } + + template + EIGEN_STRONG_INLINE + PacketType packet(Index index) const + { + enum { PacketSize = unpacket_traits::size }; + return preverse(m_argImpl.template packet(m_rows.value() * m_cols.value() - index - PacketSize)); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index row, Index col, const PacketType& x) + { + // FIXME we could factorize some code with packet(i,j) + enum { + PacketSize = unpacket_traits::size, + OffsetRow = ReverseRow && IsColMajor ? PacketSize : 1, + OffsetCol = ReverseCol && IsRowMajor ? PacketSize : 1 + }; + typedef internal::reverse_packet_cond reverse_packet; + m_argImpl.template writePacket( + ReverseRow ? m_rows.value() - row - OffsetRow : row, + ReverseCol ? m_cols.value() - col - OffsetCol : col, + reverse_packet::run(x)); + } + + template + EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketType& x) + { + enum { PacketSize = unpacket_traits::size }; + m_argImpl.template writePacket + (m_rows.value() * m_cols.value() - index - PacketSize, preverse(x)); + } + +protected: + evaluator m_argImpl; + + // If we do not reverse rows, then we do not need to know the number of rows; same for columns + // Nonetheless, in this case it is important to set to 1 such that the coeff(index) method works fine for vectors. + const variable_if_dynamic m_rows; + const variable_if_dynamic m_cols; +}; + + +// -------------------- Diagonal -------------------- + +template +struct evaluator > + : evaluator_base > +{ + typedef Diagonal XprType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + + Flags = (unsigned int)(evaluator::Flags & (HereditaryBits | DirectAccessBit) & ~RowMajorBit) | LinearAccessBit, + + Alignment = 0 + }; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& diagonal) + : m_argImpl(diagonal.nestedExpression()), + m_index(diagonal.index()) + { } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index row, Index) const + { + return m_argImpl.coeff(row + rowOffset(), row + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + CoeffReturnType coeff(Index index) const + { + return m_argImpl.coeff(index + rowOffset(), index + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index row, Index) + { + return m_argImpl.coeffRef(row + rowOffset(), row + colOffset()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Scalar& coeffRef(Index index) + { + return m_argImpl.coeffRef(index + rowOffset(), index + colOffset()); + } + +protected: + evaluator m_argImpl; + const internal::variable_if_dynamicindex m_index; + +private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value() > 0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value() > 0 ? m_index.value() : 0; } +}; + + +//---------------------------------------------------------------------- +// deprecated code +//---------------------------------------------------------------------- + +// -------------------- EvalToTemp -------------------- + +// expression class for evaluating nested expression to a temporary + +template class EvalToTemp; + +template +struct traits > + : public traits +{ }; + +template +class EvalToTemp + : public dense_xpr_base >::type +{ + public: + + typedef typename dense_xpr_base::type Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(EvalToTemp) + + explicit EvalToTemp(const ArgType& arg) + : m_arg(arg) + { } + + const ArgType& arg() const + { + return m_arg; + } + + Index rows() const + { + return m_arg.rows(); + } + + Index cols() const + { + return m_arg.cols(); + } + + private: + const ArgType& m_arg; +}; + +template +struct evaluator > + : public evaluator +{ + typedef EvalToTemp XprType; + typedef typename ArgType::PlainObject PlainObject; + typedef evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : m_result(xpr.arg()) + { + ::new (static_cast(this)) Base(m_result); + } + + // This constructor is used when nesting an EvalTo evaluator in another evaluator + EIGEN_DEVICE_FUNC evaluator(const ArgType& arg) + : m_result(arg) + { + ::new (static_cast(this)) Base(m_result); + } + +protected: + PlainObject m_result; +}; + +} // namespace internal + +} // end namespace Eigen + +#endif // EIGEN_COREEVALUATORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreIterators.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreIterators.h index 6da4683d2..4eb42b93a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreIterators.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CoreIterators.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,47 +15,113 @@ namespace Eigen { /* This file contains the respective InnerIterator definition of the expressions defined in Eigen/Core */ -/** \ingroup SparseCore_Module - * \class InnerIterator - * \brief An InnerIterator allows to loop over the element of a sparse (or dense) matrix or expression - * - * todo +namespace internal { + +template +class inner_iterator_selector; + +} + +/** \class InnerIterator + * \brief An InnerIterator allows to loop over the element of any matrix expression. + * + * \warning To be used with care because an evaluator is constructed every time an InnerIterator iterator is constructed. + * + * TODO: add a usage example */ - -// generic version for dense matrix and expressions -template class DenseBase::InnerIterator +template +class InnerIterator { - protected: - typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; - - enum { IsRowMajor = (Derived::Flags&RowMajorBit)==RowMajorBit }; - public: - EIGEN_STRONG_INLINE InnerIterator(const Derived& expr, Index outer) - : m_expression(expr), m_inner(0), m_outer(outer), m_end(expr.innerSize()) - {} - - EIGEN_STRONG_INLINE Scalar value() const - { - return (IsRowMajor) ? m_expression.coeff(m_outer, m_inner) - : m_expression.coeff(m_inner, m_outer); - } - - EIGEN_STRONG_INLINE InnerIterator& operator++() { m_inner++; return *this; } - - EIGEN_STRONG_INLINE Index index() const { return m_inner; } - inline Index row() const { return IsRowMajor ? m_outer : index(); } - inline Index col() const { return IsRowMajor ? index() : m_outer; } - - EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; } - - protected: - const Derived& m_expression; - Index m_inner; - const Index m_outer; - const Index m_end; +protected: + typedef internal::inner_iterator_selector::Kind> IteratorType; + typedef internal::evaluator EvaluatorType; + typedef typename internal::traits::Scalar Scalar; +public: + /** Construct an iterator over the \a outerId -th row or column of \a xpr */ + InnerIterator(const XprType &xpr, const Index &outerId) + : m_eval(xpr), m_iter(m_eval, outerId, xpr.innerSize()) + {} + + /// \returns the value of the current coefficient. + EIGEN_STRONG_INLINE Scalar value() const { return m_iter.value(); } + /** Increment the iterator \c *this to the next non-zero coefficient. + * Explicit zeros are not skipped over. To skip explicit zeros, see class SparseView + */ + EIGEN_STRONG_INLINE InnerIterator& operator++() { m_iter.operator++(); return *this; } + /// \returns the column or row index of the current coefficient. + EIGEN_STRONG_INLINE Index index() const { return m_iter.index(); } + /// \returns the row index of the current coefficient. + EIGEN_STRONG_INLINE Index row() const { return m_iter.row(); } + /// \returns the column index of the current coefficient. + EIGEN_STRONG_INLINE Index col() const { return m_iter.col(); } + /// \returns \c true if the iterator \c *this still references a valid coefficient. + EIGEN_STRONG_INLINE operator bool() const { return m_iter; } + +protected: + EvaluatorType m_eval; + IteratorType m_iter; +private: + // If you get here, then you're not using the right InnerIterator type, e.g.: + // SparseMatrix A; + // SparseMatrix::InnerIterator it(A,0); + template InnerIterator(const EigenBase&,Index outer); }; +namespace internal { + +// Generic inner iterator implementation for dense objects +template +class inner_iterator_selector +{ +protected: + typedef evaluator EvaluatorType; + typedef typename traits::Scalar Scalar; + enum { IsRowMajor = (XprType::Flags&RowMajorBit)==RowMajorBit }; + +public: + EIGEN_STRONG_INLINE inner_iterator_selector(const EvaluatorType &eval, const Index &outerId, const Index &innerSize) + : m_eval(eval), m_inner(0), m_outer(outerId), m_end(innerSize) + {} + + EIGEN_STRONG_INLINE Scalar value() const + { + return (IsRowMajor) ? m_eval.coeff(m_outer, m_inner) + : m_eval.coeff(m_inner, m_outer); + } + + EIGEN_STRONG_INLINE inner_iterator_selector& operator++() { m_inner++; return *this; } + + EIGEN_STRONG_INLINE Index index() const { return m_inner; } + inline Index row() const { return IsRowMajor ? m_outer : index(); } + inline Index col() const { return IsRowMajor ? index() : m_outer; } + + EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; } + +protected: + const EvaluatorType& m_eval; + Index m_inner; + const Index m_outer; + const Index m_end; +}; + +// For iterator-based evaluator, inner-iterator is already implemented as +// evaluator<>::InnerIterator +template +class inner_iterator_selector + : public evaluator::InnerIterator +{ +protected: + typedef typename evaluator::InnerIterator Base; + typedef evaluator EvaluatorType; + +public: + EIGEN_STRONG_INLINE inner_iterator_selector(const EvaluatorType &eval, const Index &outerId, const Index &/*innerSize*/) + : Base(eval, outerId) + {} +}; + +} // end namespace internal + } // end namespace Eigen #endif // EIGEN_COREITERATORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h index 519a866e6..a36765e39 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseBinaryOp.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2009 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2006-2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -13,26 +13,6 @@ namespace Eigen { -/** \class CwiseBinaryOp - * \ingroup Core_Module - * - * \brief Generic expression where a coefficient-wise binary operator is applied to two expressions - * - * \param BinaryOp template functor implementing the operator - * \param Lhs the type of the left-hand side - * \param Rhs the type of the right-hand side - * - * This class represents an expression where a coefficient-wise binary operator is applied to two expressions. - * It is the return type of binary operators, by which we mean only those binary operators where - * both the left-hand side and the right-hand side are Eigen expressions. - * For example, the return type of matrix1+matrix2 is a CwiseBinaryOp. - * - * Most of the time, this is the only way that it is used, so you typically don't have to name - * CwiseBinaryOp types explicitly. - * - * \sa MatrixBase::binaryExpr(const MatrixBase &,const CustomBinaryOp &) const, class CwiseUnaryOp, class CwiseNullaryOp - */ - namespace internal { template struct traits > @@ -52,77 +32,75 @@ struct traits > // we still want to handle the case when the result type is different. typedef typename result_of< BinaryOp( - typename Lhs::Scalar, - typename Rhs::Scalar + const typename Lhs::Scalar&, + const typename Rhs::Scalar& ) >::type Scalar; - typedef typename promote_storage_type::StorageKind, - typename traits::StorageKind>::ret StorageKind; - typedef typename promote_index_type::Index, - typename traits::Index>::type Index; + typedef typename cwise_promote_storage_type::StorageKind, + typename traits::StorageKind, + BinaryOp>::ret StorageKind; + typedef typename promote_index_type::StorageIndex, + typename traits::StorageIndex>::type StorageIndex; typedef typename Lhs::Nested LhsNested; typedef typename Rhs::Nested RhsNested; typedef typename remove_reference::type _LhsNested; typedef typename remove_reference::type _RhsNested; enum { - LhsCoeffReadCost = _LhsNested::CoeffReadCost, - RhsCoeffReadCost = _RhsNested::CoeffReadCost, - LhsFlags = _LhsNested::Flags, - RhsFlags = _RhsNested::Flags, - SameType = is_same::value, - StorageOrdersAgree = (int(Lhs::Flags)&RowMajorBit)==(int(Rhs::Flags)&RowMajorBit), - Flags0 = (int(LhsFlags) | int(RhsFlags)) & ( - HereditaryBits - | (int(LhsFlags) & int(RhsFlags) & - ( AlignedBit - | (StorageOrdersAgree ? LinearAccessBit : 0) - | (functor_traits::PacketAccess && StorageOrdersAgree && SameType ? PacketAccessBit : 0) - ) - ) - ), - Flags = (Flags0 & ~RowMajorBit) | (LhsFlags & RowMajorBit), - Cost0 = EIGEN_ADD_COST(LhsCoeffReadCost,RhsCoeffReadCost), - CoeffReadCost = EIGEN_ADD_COST(Cost0,functor_traits::Cost) + Flags = cwise_promote_storage_order::StorageKind,typename traits::StorageKind,_LhsNested::Flags & RowMajorBit,_RhsNested::Flags & RowMajorBit>::value }; }; } // end namespace internal -// we require Lhs and Rhs to have the same scalar type. Currently there is no example of a binary functor -// that would take two operands of different types. If there were such an example, then this check should be -// moved to the BinaryOp functors, on a per-case basis. This would however require a change in the BinaryOp functors, as -// currently they take only one typename Scalar template parameter. -// It is tempting to always allow mixing different types but remember that this is often impossible in the vectorized paths. -// So allowing mixing different types gives very unexpected errors when enabling vectorization, when the user tries to -// add together a float matrix and a double matrix. -#define EIGEN_CHECK_BINARY_COMPATIBILIY(BINOP,LHS,RHS) \ - EIGEN_STATIC_ASSERT((internal::functor_is_product_like::ret \ - ? int(internal::scalar_product_traits::Defined) \ - : int(internal::is_same::value)), \ - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - template class CwiseBinaryOpImpl; -template -class CwiseBinaryOp : internal::no_assignment_operator, +/** \class CwiseBinaryOp + * \ingroup Core_Module + * + * \brief Generic expression where a coefficient-wise binary operator is applied to two expressions + * + * \tparam BinaryOp template functor implementing the operator + * \tparam LhsType the type of the left-hand side + * \tparam RhsType the type of the right-hand side + * + * This class represents an expression where a coefficient-wise binary operator is applied to two expressions. + * It is the return type of binary operators, by which we mean only those binary operators where + * both the left-hand side and the right-hand side are Eigen expressions. + * For example, the return type of matrix1+matrix2 is a CwiseBinaryOp. + * + * Most of the time, this is the only way that it is used, so you typically don't have to name + * CwiseBinaryOp types explicitly. + * + * \sa MatrixBase::binaryExpr(const MatrixBase &,const CustomBinaryOp &) const, class CwiseUnaryOp, class CwiseNullaryOp + */ +template +class CwiseBinaryOp : public CwiseBinaryOpImpl< - BinaryOp, Lhs, Rhs, - typename internal::promote_storage_type::StorageKind, - typename internal::traits::StorageKind>::ret> + BinaryOp, LhsType, RhsType, + typename internal::cwise_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + BinaryOp>::ret>, + internal::no_assignment_operator { public: + + typedef typename internal::remove_all::type Functor; + typedef typename internal::remove_all::type Lhs; + typedef typename internal::remove_all::type Rhs; typedef typename CwiseBinaryOpImpl< - BinaryOp, Lhs, Rhs, - typename internal::promote_storage_type::StorageKind, - typename internal::traits::StorageKind>::ret>::Base Base; + BinaryOp, LhsType, RhsType, + typename internal::cwise_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + BinaryOp>::ret>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseBinaryOp) - typedef typename internal::nested::type LhsNested; - typedef typename internal::nested::type RhsNested; + typedef typename internal::ref_selector::type LhsNested; + typedef typename internal::ref_selector::type RhsNested; typedef typename internal::remove_reference::type _LhsNested; typedef typename internal::remove_reference::type _RhsNested; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CwiseBinaryOp(const Lhs& aLhs, const Rhs& aRhs, const BinaryOp& func = BinaryOp()) : m_lhs(aLhs), m_rhs(aRhs), m_functor(func) { @@ -132,6 +110,7 @@ class CwiseBinaryOp : internal::no_assignment_operator, eigen_assert(aLhs.rows() == aRhs.rows() && aLhs.cols() == aRhs.cols()); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { // return the fixed size type if available to enable compile time optimizations if (internal::traits::type>::RowsAtCompileTime==Dynamic) @@ -139,6 +118,7 @@ class CwiseBinaryOp : internal::no_assignment_operator, else return m_lhs.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { // return the fixed size type if available to enable compile time optimizations if (internal::traits::type>::ColsAtCompileTime==Dynamic) @@ -148,10 +128,13 @@ class CwiseBinaryOp : internal::no_assignment_operator, } /** \returns the left hand side nested expression */ + EIGEN_DEVICE_FUNC const _LhsNested& lhs() const { return m_lhs; } /** \returns the right hand side nested expression */ + EIGEN_DEVICE_FUNC const _RhsNested& rhs() const { return m_rhs; } /** \returns the functor representing the binary operation */ + EIGEN_DEVICE_FUNC const BinaryOp& functor() const { return m_functor; } protected: @@ -160,41 +143,13 @@ class CwiseBinaryOp : internal::no_assignment_operator, const BinaryOp m_functor; }; -template -class CwiseBinaryOpImpl - : public internal::dense_xpr_base >::type +// Generic API dispatcher +template +class CwiseBinaryOpImpl + : public internal::generic_xpr_base >::type { - typedef CwiseBinaryOp Derived; - public: - - typedef typename internal::dense_xpr_base >::type Base; - EIGEN_DENSE_PUBLIC_INTERFACE( Derived ) - - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return derived().functor()(derived().lhs().coeff(rowId, colId), - derived().rhs().coeff(rowId, colId)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return derived().functor().packetOp(derived().lhs().template packet(rowId, colId), - derived().rhs().template packet(rowId, colId)); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return derived().functor()(derived().lhs().coeff(index), - derived().rhs().coeff(index)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return derived().functor().packetOp(derived().lhs().template packet(index), - derived().rhs().template packet(index)); - } +public: + typedef typename internal::generic_xpr_base >::type Base; }; /** replaces \c *this by \c *this - \a other. @@ -206,8 +161,7 @@ template EIGEN_STRONG_INLINE Derived & MatrixBase::operator-=(const MatrixBase &other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } @@ -220,11 +174,11 @@ template EIGEN_STRONG_INLINE Derived & MatrixBase::operator+=(const MatrixBase& other) { - SelfCwiseBinaryOp, Derived, OtherDerived> tmp(derived()); - tmp = other.derived(); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } } // end namespace Eigen #endif // EIGEN_CWISE_BINARY_OP_H + diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h index a93bab2d0..ddd607e38 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseNullaryOp.h @@ -12,13 +12,24 @@ namespace Eigen { +namespace internal { +template +struct traits > : traits +{ + enum { + Flags = traits::Flags & RowMajorBit + }; +}; + +} // namespace internal + /** \class CwiseNullaryOp * \ingroup Core_Module * * \brief Generic expression of a matrix where all coefficients are defined by a functor * - * \param NullaryOp template functor implementing the operator - * \param PlainObjectType the underlying plain matrix/array type + * \tparam NullaryOp template functor implementing the operator + * \tparam PlainObjectType the underlying plain matrix/array type * * This class represents an expression of a generic nullary operator. * It is the return type of the Ones(), Zero(), Constant(), Identity() and Random() methods, @@ -27,68 +38,49 @@ namespace Eigen { * However, if you want to write a function returning such an expression, you * will need to use this class. * - * \sa class CwiseUnaryOp, class CwiseBinaryOp, DenseBase::NullaryExpr() + * The functor NullaryOp must expose one of the following method: + + + + +
\c operator()() if the procedural generation does not depend on the coefficient entries (e.g., random numbers)
\c operator()(Index i)if the procedural generation makes sense for vectors only and that it depends on the coefficient index \c i (e.g., linspace)
\c operator()(Index i,Index j)if the procedural generation depends on the matrix coordinates \c i, \c j (e.g., to generate a checkerboard with 0 and 1)
+ * It is also possible to expose the last two operators if the generation makes sense for matrices but can be optimized for vectors. + * + * See DenseBase::NullaryExpr(Index,const CustomNullaryOp&) for an example binding + * C++11 random number generators. + * + * A nullary expression can also be used to implement custom sophisticated matrix manipulations + * that cannot be covered by the existing set of natively supported matrix manipulations. + * See this \ref TopicCustomizing_NullaryExpr "page" for some examples and additional explanations + * on the behavior of CwiseNullaryOp. + * + * \sa class CwiseUnaryOp, class CwiseBinaryOp, DenseBase::NullaryExpr */ - -namespace internal { template -struct traits > : traits -{ - enum { - Flags = (traits::Flags - & ( HereditaryBits - | (functor_has_linear_access::ret ? LinearAccessBit : 0) - | (functor_traits::PacketAccess ? PacketAccessBit : 0))) - | (functor_traits::IsRepeatable ? 0 : EvalBeforeNestingBit), - CoeffReadCost = functor_traits::Cost - }; -}; -} - -template -class CwiseNullaryOp : internal::no_assignment_operator, - public internal::dense_xpr_base< CwiseNullaryOp >::type +class CwiseNullaryOp : public internal::dense_xpr_base< CwiseNullaryOp >::type, internal::no_assignment_operator { public: typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(CwiseNullaryOp) - CwiseNullaryOp(Index nbRows, Index nbCols, const NullaryOp& func = NullaryOp()) - : m_rows(nbRows), m_cols(nbCols), m_functor(func) + EIGEN_DEVICE_FUNC + CwiseNullaryOp(Index rows, Index cols, const NullaryOp& func = NullaryOp()) + : m_rows(rows), m_cols(cols), m_functor(func) { - eigen_assert(nbRows >= 0 - && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == nbRows) - && nbCols >= 0 - && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == nbCols)); + eigen_assert(rows >= 0 + && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == rows) + && cols >= 0 + && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == cols)); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { return m_rows.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { return m_cols.value(); } - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return m_functor(rowId, colId); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return m_functor.packetOp(rowId, colId); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return m_functor(index); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return m_functor.packetOp(index); - } - /** \returns the functor representing the nullary operation */ + EIGEN_DEVICE_FUNC const NullaryOp& functor() const { return m_functor; } protected: @@ -113,10 +105,10 @@ class CwiseNullaryOp : internal::no_assignment_operator, */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& func) { - return CwiseNullaryOp(rows, cols, func); + return CwiseNullaryOp(rows, cols, func); } /** \returns an expression of a matrix defined by a custom functor \a func @@ -132,16 +124,19 @@ DenseBase::NullaryExpr(Index rows, Index cols, const CustomNullaryOp& f * * The template parameter \a CustomNullaryOp is the type of the functor. * + * Here is an example with C++11 random generators: \include random_cpp11.cpp + * Output: \verbinclude random_cpp11.out + * * \sa class CwiseNullaryOp */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - if(RowsAtCompileTime == 1) return CwiseNullaryOp(1, size, func); - else return CwiseNullaryOp(size, 1, func); + if(RowsAtCompileTime == 1) return CwiseNullaryOp(1, size, func); + else return CwiseNullaryOp(size, 1, func); } /** \returns an expression of a matrix defined by a custom functor \a func @@ -155,19 +150,19 @@ DenseBase::NullaryExpr(Index size, const CustomNullaryOp& func) */ template template -EIGEN_STRONG_INLINE const CwiseNullaryOp +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseNullaryOp::PlainObject> DenseBase::NullaryExpr(const CustomNullaryOp& func) { - return CwiseNullaryOp(RowsAtCompileTime, ColsAtCompileTime, func); + return CwiseNullaryOp(RowsAtCompileTime, ColsAtCompileTime, func); } /** \returns an expression of a constant matrix of value \a value * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this DenseBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, - * it is redundant to pass \a nbRows and \a nbCols as arguments, so Zero() should be used + * it is redundant to pass \a rows and \a cols as arguments, so Zero() should be used * instead. * * The template parameter \a CustomNullaryOp is the type of the functor. @@ -176,9 +171,9 @@ DenseBase::NullaryExpr(const CustomNullaryOp& func) */ template EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Constant(Index nbRows, Index nbCols, const Scalar& value) +DenseBase::Constant(Index rows, Index cols, const Scalar& value) { - return DenseBase::NullaryExpr(nbRows, nbCols, internal::scalar_constant_op(value)); + return DenseBase::NullaryExpr(rows, cols, internal::scalar_constant_op(value)); } /** \returns an expression of a constant matrix of value \a value @@ -197,7 +192,7 @@ DenseBase::Constant(Index nbRows, Index nbCols, const Scalar& value) * \sa class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Constant(Index size, const Scalar& value) { return DenseBase::NullaryExpr(size, internal::scalar_constant_op(value)); @@ -213,53 +208,40 @@ DenseBase::Constant(Index size, const Scalar& value) * \sa class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Constant(const Scalar& value) { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) return DenseBase::NullaryExpr(RowsAtCompileTime, ColsAtCompileTime, internal::scalar_constant_op(value)); } -/** - * \brief Sets a linearly space vector. +/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(Index,const Scalar&,const Scalar&) * - * The function generates 'size' equally spaced values in the closed interval [low,high]. - * This particular version of LinSpaced() uses sequential access, i.e. vector access is - * assumed to be a(0), a(1), ..., a(size). This assumption allows for better vectorization - * and yields faster code than the random access version. - * - * When size is set to 1, a vector of length 1 containing 'high' is returned. - * - * \only_for_vectors - * - * Example: \include DenseBase_LinSpaced_seq.cpp - * Output: \verbinclude DenseBase_LinSpaced_seq.out - * - * \sa setLinSpaced(Index,const Scalar&,const Scalar&), LinSpaced(Index,Scalar,Scalar), CwiseNullaryOp + * \sa LinSpaced(Index,Scalar,Scalar), setLinSpaced(Index,const Scalar&,const Scalar&) */ template -EIGEN_STRONG_INLINE const typename DenseBase::SequentialLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } -/** - * \copydoc DenseBase::LinSpaced(Sequential_t, Index, const Scalar&, const Scalar&) - * Special version for fixed size types which does not require the size parameter. +/** \deprecated because of accuracy loss. In Eigen 3.3, it is an alias for LinSpaced(const Scalar&,const Scalar&) + * + * \sa LinSpaced(Scalar,Scalar) */ template -EIGEN_STRONG_INLINE const typename DenseBase::SequentialLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. @@ -269,14 +251,24 @@ DenseBase::LinSpaced(Sequential_t, const Scalar& low, const Scalar& hig * Example: \include DenseBase_LinSpaced.cpp * Output: \verbinclude DenseBase_LinSpaced.out * - * \sa setLinSpaced(Index,const Scalar&,const Scalar&), LinSpaced(Sequential_t,Index,const Scalar&,const Scalar&,Index), CwiseNullaryOp + * For integer scalar types, an even spacing is possible if and only if the length of the range, + * i.e., \c high-low is a scalar multiple of \c size-1, or if \c size is a scalar multiple of the + * number of values \c high-low+1 (meaning each value can be repeated the same number of time). + * If one of these two considions is not satisfied, then \c high is lowered to the largest value + * satisfying one of this constraint. + * Here are some examples: + * + * Example: \include DenseBase_LinSpacedInt.cpp + * Output: \verbinclude DenseBase_LinSpacedInt.out + * + * \sa setLinSpaced(Index,const Scalar&,const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(Index size, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); + return DenseBase::NullaryExpr(size, internal::linspaced_op(low,high,size)); } /** @@ -284,22 +276,23 @@ DenseBase::LinSpaced(Index size, const Scalar& low, const Scalar& high) * Special version for fixed size types which does not require the size parameter. */ template -EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::RandomAccessLinSpacedReturnType DenseBase::LinSpaced(const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); + return DenseBase::NullaryExpr(Derived::SizeAtCompileTime, internal::linspaced_op(low,high,Derived::SizeAtCompileTime)); } /** \returns true if all coefficients in this matrix are approximately equal to \a val, to within precision \a prec */ template -bool DenseBase::isApproxToConstant +EIGEN_DEVICE_FUNC bool DenseBase::isApproxToConstant (const Scalar& val, const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if(!internal::isApprox(this->coeff(i, j), val, prec)) + if(!internal::isApprox(self.coeff(i, j), val, prec)) return false; return true; } @@ -308,7 +301,7 @@ bool DenseBase::isApproxToConstant * * \returns true if all coefficients in this matrix are approximately equal to \a value, to within precision \a prec */ template -bool DenseBase::isConstant +EIGEN_DEVICE_FUNC bool DenseBase::isConstant (const Scalar& val, const RealScalar& prec) const { return isApproxToConstant(val, prec); @@ -319,22 +312,22 @@ bool DenseBase::isConstant * \sa setConstant(), Constant(), class CwiseNullaryOp */ template -EIGEN_STRONG_INLINE void DenseBase::fill(const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void DenseBase::fill(const Scalar& val) { setConstant(val); } -/** Sets all coefficients in this expression to \a value. +/** Sets all coefficients in this expression to value \a val. * * \sa fill(), setConstant(Index,const Scalar&), setConstant(Index,Index,const Scalar&), setZero(), setOnes(), Constant(), class CwiseNullaryOp, setZero(), setOnes() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) { return derived() = Constant(rows(), cols(), val); } -/** Resizes to the given \a size, and sets all coefficients in this expression to the given \a value. +/** Resizes to the given \a size, and sets all coefficients in this expression to the given value \a val. * * \only_for_vectors * @@ -344,17 +337,17 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setConstant(const Scalar& val) * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setConstant(Index size, const Scalar& val) { resize(size); return setConstant(val); } -/** Resizes to the given size, and sets all coefficients in this expression to the given \a value. +/** Resizes to the given size, and sets all coefficients in this expression to the given value \a val. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * \param val the value to which all coefficients are set * * Example: \include Matrix_setConstant_int_int.cpp @@ -363,15 +356,15 @@ PlainObjectBase::setConstant(Index size, const Scalar& val) * \sa MatrixBase::setConstant(const Scalar&), setConstant(Index,const Scalar&), class CwiseNullaryOp, MatrixBase::Constant(const Scalar&) */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setConstant(Index nbRows, Index nbCols, const Scalar& val) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setConstant(Index rows, Index cols, const Scalar& val) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(val); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * * The function generates 'size' equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. @@ -381,27 +374,33 @@ PlainObjectBase::setConstant(Index nbRows, Index nbCols, const Scalar& * Example: \include DenseBase_setLinSpaced.cpp * Output: \verbinclude DenseBase_setLinSpaced.out * - * \sa CwiseNullaryOp + * For integer scalar types, do not miss the explanations on the definition + * of \link LinSpaced(Index,const Scalar&,const Scalar&) even spacing \endlink. + * + * \sa LinSpaced(Index,const Scalar&,const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index newSize, const Scalar& low, const Scalar& high) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(Index newSize, const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); + return derived() = Derived::NullaryExpr(newSize, internal::linspaced_op(low,high,newSize)); } /** - * \brief Sets a linearly space vector. + * \brief Sets a linearly spaced vector. * - * The function fill *this with equally spaced values in the closed interval [low,high]. + * The function fills \c *this with equally spaced values in the closed interval [low,high]. * When size is set to 1, a vector of length 1 containing 'high' is returned. * * \only_for_vectors * - * \sa setLinSpaced(Index, const Scalar&, const Scalar&), CwiseNullaryOp + * For integer scalar types, do not miss the explanations on the definition + * of \link LinSpaced(Index,const Scalar&,const Scalar&) even spacing \endlink. + * + * \sa LinSpaced(Index,const Scalar&,const Scalar&), setLinSpaced(Index, const Scalar&, const Scalar&), CwiseNullaryOp */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, const Scalar& high) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, const Scalar& high) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return setLinSpaced(size(), low, high); @@ -424,10 +423,10 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setLinSpaced(const Scalar& low, * \sa Zero(), Zero(Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Zero(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +DenseBase::Zero(Index rows, Index cols) { - return Constant(nbRows, nbCols, Scalar(0)); + return Constant(rows, cols, Scalar(0)); } /** \returns an expression of a zero vector. @@ -447,7 +446,7 @@ DenseBase::Zero(Index nbRows, Index nbCols) * \sa Zero(), Zero(Index,Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Zero(Index size) { return Constant(size, Scalar(0)); @@ -464,7 +463,7 @@ DenseBase::Zero(Index size) * \sa Zero(Index), Zero(Index,Index) */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Zero() { return Constant(Scalar(0)); @@ -479,11 +478,12 @@ DenseBase::Zero() * \sa class CwiseNullaryOp, Zero() */ template -bool DenseBase::isZero(const RealScalar& prec) const +EIGEN_DEVICE_FUNC bool DenseBase::isZero(const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) for(Index i = 0; i < rows(); ++i) - if(!internal::isMuchSmallerThan(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.coeff(i, j), static_cast(1), prec)) return false; return true; } @@ -496,7 +496,7 @@ bool DenseBase::isZero(const RealScalar& prec) const * \sa class CwiseNullaryOp, Zero() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setZero() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setZero() { return setConstant(Scalar(0)); } @@ -511,7 +511,7 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setZero() * \sa DenseBase::setZero(), setZero(Index,Index), class CwiseNullaryOp, DenseBase::Zero() */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setZero(Index newSize) { resize(newSize); @@ -520,8 +520,8 @@ PlainObjectBase::setZero(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to zero. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setZero_int_int.cpp * Output: \verbinclude Matrix_setZero_int_int.out @@ -529,10 +529,10 @@ PlainObjectBase::setZero(Index newSize) * \sa DenseBase::setZero(), setZero(Index), class CwiseNullaryOp, DenseBase::Zero() */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setZero(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setZero(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(Scalar(0)); } @@ -540,7 +540,7 @@ PlainObjectBase::setZero(Index nbRows, Index nbCols) /** \returns an expression of a matrix where all coefficients equal one. * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, @@ -553,10 +553,10 @@ PlainObjectBase::setZero(Index nbRows, Index nbCols) * \sa Ones(), Ones(Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType -DenseBase::Ones(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +DenseBase::Ones(Index rows, Index cols) { - return Constant(nbRows, nbCols, Scalar(1)); + return Constant(rows, cols, Scalar(1)); } /** \returns an expression of a vector where all coefficients equal one. @@ -576,7 +576,7 @@ DenseBase::Ones(Index nbRows, Index nbCols) * \sa Ones(), Ones(Index,Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Ones(Index newSize) { return Constant(newSize, Scalar(1)); @@ -593,7 +593,7 @@ DenseBase::Ones(Index newSize) * \sa Ones(Index), Ones(Index,Index), isOnes(), class Ones */ template -EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename DenseBase::ConstantReturnType DenseBase::Ones() { return Constant(Scalar(1)); @@ -608,7 +608,7 @@ DenseBase::Ones() * \sa class CwiseNullaryOp, Ones() */ template -bool DenseBase::isOnes +EIGEN_DEVICE_FUNC bool DenseBase::isOnes (const RealScalar& prec) const { return isApproxToConstant(Scalar(1), prec); @@ -622,7 +622,7 @@ bool DenseBase::isOnes * \sa class CwiseNullaryOp, Ones() */ template -EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() { return setConstant(Scalar(1)); } @@ -637,7 +637,7 @@ EIGEN_STRONG_INLINE Derived& DenseBase::setOnes() * \sa MatrixBase::setOnes(), setOnes(Index,Index), class CwiseNullaryOp, MatrixBase::Ones() */ template -EIGEN_STRONG_INLINE Derived& +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& PlainObjectBase::setOnes(Index newSize) { resize(newSize); @@ -646,8 +646,8 @@ PlainObjectBase::setOnes(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to one. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setOnes_int_int.cpp * Output: \verbinclude Matrix_setOnes_int_int.out @@ -655,10 +655,10 @@ PlainObjectBase::setOnes(Index newSize) * \sa MatrixBase::setOnes(), setOnes(Index), class CwiseNullaryOp, MatrixBase::Ones() */ template -EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setOnes(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& +PlainObjectBase::setOnes(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setConstant(Scalar(1)); } @@ -666,7 +666,7 @@ PlainObjectBase::setOnes(Index nbRows, Index nbCols) /** \returns an expression of the identity matrix (not necessarily square). * - * The parameters \a nbRows and \a nbCols are the number of rows and of columns of + * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, @@ -679,10 +679,10 @@ PlainObjectBase::setOnes(Index nbRows, Index nbCols) * \sa Identity(), setIdentity(), isIdentity() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType -MatrixBase::Identity(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType +MatrixBase::Identity(Index rows, Index cols) { - return DenseBase::NullaryExpr(nbRows, nbCols, internal::scalar_identity_op()); + return DenseBase::NullaryExpr(rows, cols, internal::scalar_identity_op()); } /** \returns an expression of the identity matrix (not necessarily square). @@ -696,7 +696,7 @@ MatrixBase::Identity(Index nbRows, Index nbCols) * \sa Identity(Index,Index), setIdentity(), isIdentity() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::IdentityReturnType MatrixBase::Identity() { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) @@ -716,18 +716,19 @@ template bool MatrixBase::isIdentity (const RealScalar& prec) const { + typename internal::nested_eval::type self(derived()); for(Index j = 0; j < cols(); ++j) { for(Index i = 0; i < rows(); ++i) { if(i == j) { - if(!internal::isApprox(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isApprox(self.coeff(i, j), static_cast(1), prec)) return false; } else { - if(!internal::isMuchSmallerThan(this->coeff(i, j), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.coeff(i, j), static_cast(1), prec)) return false; } } @@ -740,6 +741,7 @@ namespace internal { template=16)> struct setIdentity_impl { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Derived& run(Derived& m) { return m = Derived::Identity(m.rows(), m.cols()); @@ -749,11 +751,11 @@ struct setIdentity_impl template struct setIdentity_impl { - typedef typename Derived::Index Index; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Derived& run(Derived& m) { m.setZero(); - const Index size = (std::min)(m.rows(), m.cols()); + const Index size = numext::mini(m.rows(), m.cols()); for(Index i = 0; i < size; ++i) m.coeffRef(i,i) = typename Derived::Scalar(1); return m; } @@ -769,15 +771,15 @@ struct setIdentity_impl * \sa class CwiseNullaryOp, Identity(), Identity(Index,Index), isIdentity() */ template -EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() { return internal::setIdentity_impl::run(derived()); } /** \brief Resizes to the given size, and writes the identity expression (not necessarily square) into *this. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setIdentity_int_int.cpp * Output: \verbinclude Matrix_setIdentity_int_int.out @@ -785,9 +787,9 @@ EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity() * \sa MatrixBase::setIdentity(), class CwiseNullaryOp, MatrixBase::Identity() */ template -EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index nbRows, Index nbCols) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index rows, Index cols) { - derived().resize(nbRows, nbCols); + derived().resize(rows, cols); return setIdentity(); } @@ -798,7 +800,7 @@ EIGEN_STRONG_INLINE Derived& MatrixBase::setIdentity(Index nbRows, Inde * \sa MatrixBase::Unit(Index), MatrixBase::UnitX(), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index newSize, Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index newSize, Index i) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return BasisReturnType(SquareMatrixType::Identity(newSize,newSize), i); @@ -813,7 +815,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::UnitX(), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index i) +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::Unit(Index i) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) return BasisReturnType(SquareMatrixType::Identity(),i); @@ -826,7 +828,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitX() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitX() { return Derived::Unit(0); } /** \returns an expression of the Y axis unit vector (0,1{,0}^*) @@ -836,7 +838,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitY() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitY() { return Derived::Unit(1); } /** \returns an expression of the Z axis unit vector (0,0,1{,0}^*) @@ -846,7 +848,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitZ() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitZ() { return Derived::Unit(2); } /** \returns an expression of the W axis unit vector (0,0,0,1) @@ -856,7 +858,7 @@ EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBa * \sa MatrixBase::Unit(Index,Index), MatrixBase::Unit(Index), MatrixBase::UnitY(), MatrixBase::UnitZ(), MatrixBase::UnitW() */ template -EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitW() +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename MatrixBase::BasisReturnType MatrixBase::UnitW() { return Derived::Unit(3); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseTernaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseTernaryOp.h new file mode 100644 index 000000000..9f3576fec --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseTernaryOp.h @@ -0,0 +1,197 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2014 Gael Guennebaud +// Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2016 Eugene Brevdo +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CWISE_TERNARY_OP_H +#define EIGEN_CWISE_TERNARY_OP_H + +namespace Eigen { + +namespace internal { +template +struct traits > { + // we must not inherit from traits since it has + // the potential to cause problems with MSVC + typedef typename remove_all::type Ancestor; + typedef typename traits::XprKind XprKind; + enum { + RowsAtCompileTime = traits::RowsAtCompileTime, + ColsAtCompileTime = traits::ColsAtCompileTime, + MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = traits::MaxColsAtCompileTime + }; + + // even though we require Arg1, Arg2, and Arg3 to have the same scalar type + // (see CwiseTernaryOp constructor), + // we still want to handle the case when the result type is different. + typedef typename result_of::type Scalar; + + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::StorageIndex StorageIndex; + + typedef typename Arg1::Nested Arg1Nested; + typedef typename Arg2::Nested Arg2Nested; + typedef typename Arg3::Nested Arg3Nested; + typedef typename remove_reference::type _Arg1Nested; + typedef typename remove_reference::type _Arg2Nested; + typedef typename remove_reference::type _Arg3Nested; + enum { Flags = _Arg1Nested::Flags & RowMajorBit }; +}; +} // end namespace internal + +template +class CwiseTernaryOpImpl; + +/** \class CwiseTernaryOp + * \ingroup Core_Module + * + * \brief Generic expression where a coefficient-wise ternary operator is + * applied to two expressions + * + * \tparam TernaryOp template functor implementing the operator + * \tparam Arg1Type the type of the first argument + * \tparam Arg2Type the type of the second argument + * \tparam Arg3Type the type of the third argument + * + * This class represents an expression where a coefficient-wise ternary + * operator is applied to three expressions. + * It is the return type of ternary operators, by which we mean only those + * ternary operators where + * all three arguments are Eigen expressions. + * For example, the return type of betainc(matrix1, matrix2, matrix3) is a + * CwiseTernaryOp. + * + * Most of the time, this is the only way that it is used, so you typically + * don't have to name + * CwiseTernaryOp types explicitly. + * + * \sa MatrixBase::ternaryExpr(const MatrixBase &, const + * MatrixBase &, const CustomTernaryOp &) const, class CwiseBinaryOp, + * class CwiseUnaryOp, class CwiseNullaryOp + */ +template +class CwiseTernaryOp : public CwiseTernaryOpImpl< + TernaryOp, Arg1Type, Arg2Type, Arg3Type, + typename internal::traits::StorageKind>, + internal::no_assignment_operator +{ + public: + typedef typename internal::remove_all::type Arg1; + typedef typename internal::remove_all::type Arg2; + typedef typename internal::remove_all::type Arg3; + + typedef typename CwiseTernaryOpImpl< + TernaryOp, Arg1Type, Arg2Type, Arg3Type, + typename internal::traits::StorageKind>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseTernaryOp) + + typedef typename internal::ref_selector::type Arg1Nested; + typedef typename internal::ref_selector::type Arg2Nested; + typedef typename internal::ref_selector::type Arg3Nested; + typedef typename internal::remove_reference::type _Arg1Nested; + typedef typename internal::remove_reference::type _Arg2Nested; + typedef typename internal::remove_reference::type _Arg3Nested; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE CwiseTernaryOp(const Arg1& a1, const Arg2& a2, + const Arg3& a3, + const TernaryOp& func = TernaryOp()) + : m_arg1(a1), m_arg2(a2), m_arg3(a3), m_functor(func) { + // require the sizes to match + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Arg1, Arg2) + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Arg1, Arg3) + + // The index types should match + EIGEN_STATIC_ASSERT((internal::is_same< + typename internal::traits::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same< + typename internal::traits::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + + eigen_assert(a1.rows() == a2.rows() && a1.cols() == a2.cols() && + a1.rows() == a3.rows() && a1.cols() == a3.cols()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index rows() const { + // return the fixed size type if available to enable compile time + // optimizations + if (internal::traits::type>:: + RowsAtCompileTime == Dynamic && + internal::traits::type>:: + RowsAtCompileTime == Dynamic) + return m_arg3.rows(); + else if (internal::traits::type>:: + RowsAtCompileTime == Dynamic && + internal::traits::type>:: + RowsAtCompileTime == Dynamic) + return m_arg2.rows(); + else + return m_arg1.rows(); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index cols() const { + // return the fixed size type if available to enable compile time + // optimizations + if (internal::traits::type>:: + ColsAtCompileTime == Dynamic && + internal::traits::type>:: + ColsAtCompileTime == Dynamic) + return m_arg3.cols(); + else if (internal::traits::type>:: + ColsAtCompileTime == Dynamic && + internal::traits::type>:: + ColsAtCompileTime == Dynamic) + return m_arg2.cols(); + else + return m_arg1.cols(); + } + + /** \returns the first argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg1Nested& arg1() const { return m_arg1; } + /** \returns the first argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg2Nested& arg2() const { return m_arg2; } + /** \returns the third argument nested expression */ + EIGEN_DEVICE_FUNC + const _Arg3Nested& arg3() const { return m_arg3; } + /** \returns the functor representing the ternary operation */ + EIGEN_DEVICE_FUNC + const TernaryOp& functor() const { return m_functor; } + + protected: + Arg1Nested m_arg1; + Arg2Nested m_arg2; + Arg3Nested m_arg3; + const TernaryOp m_functor; +}; + +// Generic API dispatcher +template +class CwiseTernaryOpImpl + : public internal::generic_xpr_base< + CwiseTernaryOp >::type { + public: + typedef typename internal::generic_xpr_base< + CwiseTernaryOp >::type Base; +}; + +} // end namespace Eigen + +#endif // EIGEN_CWISE_TERNARY_OP_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h index f7ee60e98..1d2dd19f2 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryOp.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2006-2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -13,13 +13,32 @@ namespace Eigen { +namespace internal { +template +struct traits > + : traits +{ + typedef typename result_of< + UnaryOp(const typename XprType::Scalar&) + >::type Scalar; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + enum { + Flags = _XprTypeNested::Flags & RowMajorBit + }; +}; +} + +template +class CwiseUnaryOpImpl; + /** \class CwiseUnaryOp * \ingroup Core_Module * * \brief Generic expression where a coefficient-wise unary operator is applied to an expression * - * \param UnaryOp template functor implementing the operator - * \param XprType the type of the expression to which we are applying the unary operator + * \tparam UnaryOp template functor implementing the operator + * \tparam XprType the type of the expression to which we are applying the unary operator * * This class represents an expression where a unary operator is applied to an expression. * It is the return type of all operations taking exactly 1 input expression, regardless of the @@ -32,93 +51,51 @@ namespace Eigen { * * \sa MatrixBase::unaryExpr(const CustomUnaryOp &) const, class CwiseBinaryOp, class CwiseNullaryOp */ - -namespace internal { template -struct traits > - : traits -{ - typedef typename result_of< - UnaryOp(typename XprType::Scalar) - >::type Scalar; - typedef typename XprType::Nested XprTypeNested; - typedef typename remove_reference::type _XprTypeNested; - enum { - Flags = _XprTypeNested::Flags & ( - HereditaryBits | LinearAccessBit | AlignedBit - | (functor_traits::PacketAccess ? PacketAccessBit : 0)), - CoeffReadCost = EIGEN_ADD_COST(_XprTypeNested::CoeffReadCost, functor_traits::Cost) - }; -}; -} - -template -class CwiseUnaryOpImpl; - -template -class CwiseUnaryOp : internal::no_assignment_operator, - public CwiseUnaryOpImpl::StorageKind> +class CwiseUnaryOp : public CwiseUnaryOpImpl::StorageKind>, internal::no_assignment_operator { public: typedef typename CwiseUnaryOpImpl::StorageKind>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseUnaryOp) + typedef typename internal::ref_selector::type XprTypeNested; + typedef typename internal::remove_all::type NestedExpression; - inline CwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit CwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) : m_xpr(xpr), m_functor(func) {} - EIGEN_STRONG_INLINE Index rows() const { return m_xpr.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index cols() const { return m_xpr.cols(); } /** \returns the functor representing the unary operation */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const UnaryOp& functor() const { return m_functor; } /** \returns the nested expression */ - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& nestedExpression() const { return m_xpr; } /** \returns the nested expression */ - typename internal::remove_all::type& - nestedExpression() { return m_xpr.const_cast_derived(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename internal::remove_all::type& + nestedExpression() { return m_xpr; } protected: - typename XprType::Nested m_xpr; + XprTypeNested m_xpr; const UnaryOp m_functor; }; -// This is the generic implementation for dense storage. -// It can be used for any expression types implementing the dense concept. -template -class CwiseUnaryOpImpl - : public internal::dense_xpr_base >::type +// Generic API dispatcher +template +class CwiseUnaryOpImpl + : public internal::generic_xpr_base >::type { - public: - - typedef CwiseUnaryOp Derived; - typedef typename internal::dense_xpr_base >::type Base; - EIGEN_DENSE_PUBLIC_INTERFACE(Derived) - - EIGEN_STRONG_INLINE const Scalar coeff(Index rowId, Index colId) const - { - return derived().functor()(derived().nestedExpression().coeff(rowId, colId)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index rowId, Index colId) const - { - return derived().functor().packetOp(derived().nestedExpression().template packet(rowId, colId)); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index index) const - { - return derived().functor()(derived().nestedExpression().coeff(index)); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index index) const - { - return derived().functor().packetOp(derived().nestedExpression().template packet(index)); - } +public: + typedef typename internal::generic_xpr_base >::type Base; }; } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h index f3b2ffeb6..271033056 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/CwiseUnaryView.h @@ -12,33 +12,19 @@ namespace Eigen { -/** \class CwiseUnaryView - * \ingroup Core_Module - * - * \brief Generic lvalue expression of a coefficient-wise unary operator of a matrix or a vector - * - * \param ViewOp template functor implementing the view - * \param MatrixType the type of the matrix we are applying the unary operator - * - * This class represents a lvalue expression of a generic unary view operator of a matrix or a vector. - * It is the return type of real() and imag(), and most of the time this is the only way it is used. - * - * \sa MatrixBase::unaryViewExpr(const CustomUnaryOp &) const, class CwiseUnaryOp - */ - namespace internal { template struct traits > : traits { typedef typename result_of< - ViewOp(typename traits::Scalar) + ViewOp(const typename traits::Scalar&) >::type Scalar; typedef typename MatrixType::Nested MatrixTypeNested; typedef typename remove_all::type _MatrixTypeNested; enum { - Flags = (traits<_MatrixTypeNested>::Flags & (HereditaryBits | LvalueBit | LinearAccessBit | DirectAccessBit)), - CoeffReadCost = EIGEN_ADD_COST(traits<_MatrixTypeNested>::CoeffReadCost, functor_traits::Cost), + FlagsLvalueBit = is_lvalue::value ? LvalueBit : 0, + Flags = traits<_MatrixTypeNested>::Flags & (RowMajorBit | FlagsLvalueBit | DirectAccessBit), // FIXME DirectAccessBit should not be handled by expressions MatrixTypeInnerStride = inner_stride_at_compile_time::ret, // need to cast the sizeof's from size_t to int explicitly, otherwise: // "error: no integral type can represent all of the enumerator values @@ -55,6 +41,19 @@ struct traits > template class CwiseUnaryViewImpl; +/** \class CwiseUnaryView + * \ingroup Core_Module + * + * \brief Generic lvalue expression of a coefficient-wise unary operator of a matrix or a vector + * + * \tparam ViewOp template functor implementing the view + * \tparam MatrixType the type of the matrix we are applying the unary operator + * + * This class represents a lvalue expression of a generic unary view operator of a matrix or a vector. + * It is the return type of real() and imag(), and most of the time this is the only way it is used. + * + * \sa MatrixBase::unaryViewExpr(const CustomUnaryOp &) const, class CwiseUnaryOp + */ template class CwiseUnaryView : public CwiseUnaryViewImpl::StorageKind> { @@ -62,8 +61,10 @@ class CwiseUnaryView : public CwiseUnaryViewImpl::StorageKind>::Base Base; EIGEN_GENERIC_PUBLIC_INTERFACE(CwiseUnaryView) + typedef typename internal::ref_selector::non_const_type MatrixTypeNested; + typedef typename internal::remove_all::type NestedExpression; - inline CwiseUnaryView(const MatrixType& mat, const ViewOp& func = ViewOp()) + explicit inline CwiseUnaryView(MatrixType& mat, const ViewOp& func = ViewOp()) : m_matrix(mat), m_functor(func) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryView) @@ -75,19 +76,27 @@ class CwiseUnaryView : public CwiseUnaryViewImpl::type& + const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } /** \returns the nested expression */ - typename internal::remove_all::type& + typename internal::remove_reference::type& nestedExpression() { return m_matrix.const_cast_derived(); } protected: - // FIXME changed from MatrixType::Nested because of a weird compilation error with sun CC - typename internal::nested::type m_matrix; + MatrixTypeNested m_matrix; ViewOp m_functor; }; +// Generic API dispatcher +template +class CwiseUnaryViewImpl + : public internal::generic_xpr_base >::type +{ +public: + typedef typename internal::generic_xpr_base >::type Base; +}; + template class CwiseUnaryViewImpl : public internal::dense_xpr_base< CwiseUnaryView >::type @@ -100,38 +109,18 @@ class CwiseUnaryViewImpl EIGEN_DENSE_PUBLIC_INTERFACE(Derived) EIGEN_INHERIT_ASSIGNMENT_OPERATORS(CwiseUnaryViewImpl) - inline Scalar* data() { return &coeffRef(0); } - inline const Scalar* data() const { return &coeff(0); } + EIGEN_DEVICE_FUNC inline Scalar* data() { return &(this->coeffRef(0)); } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return &(this->coeff(0)); } - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return derived().nestedExpression().innerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } - inline Index outerStride() const + EIGEN_DEVICE_FUNC inline Index outerStride() const { return derived().nestedExpression().outerStride() * sizeof(typename internal::traits::Scalar) / sizeof(Scalar); } - - EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const - { - return derived().functor()(derived().nestedExpression().coeff(row, col)); - } - - EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const - { - return derived().functor()(derived().nestedExpression().coeff(index)); - } - - EIGEN_STRONG_INLINE Scalar& coeffRef(Index row, Index col) - { - return derived().functor()(const_cast_derived().nestedExpression().coeffRef(row, col)); - } - - EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) - { - return derived().functor()(const_cast_derived().nestedExpression().coeffRef(index)); - } }; } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h index 4b371b075..90066ae73 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseBase.h @@ -34,37 +34,45 @@ static inline void check_DenseIndex_is_signed() { * \tparam Derived is the derived type, e.g., a matrix type or an expression. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_DENSEBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_DENSEBASE_PLUGIN. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseBase #ifndef EIGEN_PARSED_BY_DOXYGEN - : public internal::special_scalar_op_base::Scalar, - typename NumTraits::Scalar>::Real, - DenseCoeffsBase > -#else : public DenseCoeffsBase +#else + : public DenseCoeffsBase #endif // not EIGEN_PARSED_BY_DOXYGEN { public: - class InnerIterator; + /** Inner iterator type to iterate over the coefficients of a row or column. + * \sa class InnerIterator + */ + typedef Eigen::InnerIterator InnerIterator; typedef typename internal::traits::StorageKind StorageKind; - /** \brief The type of indices - * \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE. - * \sa \ref TopicPreprocessorDirectives. - */ - typedef typename internal::traits::Index Index; + /** + * \brief The type used to store indices + * \details This typedef is relevant for types that store multiple indices such as + * PermutationMatrix or Transpositions, otherwise it defaults to Eigen::Index + * \sa \blank \ref TopicPreprocessorDirectives, Eigen::Index, SparseMatrixBase. + */ + typedef typename internal::traits::StorageIndex StorageIndex; + /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. */ typedef typename internal::traits::Scalar Scalar; - typedef typename internal::packet_traits::type PacketScalar; + + /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex, etc. + * + * It is an alias for the Scalar type */ + typedef Scalar value_type; + typedef typename NumTraits::Real RealScalar; - typedef internal::special_scalar_op_base > Base; + typedef DenseCoeffsBase Base; - using Base::operator*; using Base::derived; using Base::const_cast_derived; using Base::rows; @@ -74,16 +82,6 @@ template class DenseBase using Base::colIndexByOuterInner; using Base::coeff; using Base::coeffByOuterInner; - using Base::packet; - using Base::packetByOuterInner; - using Base::writePacket; - using Base::writePacketByOuterInner; - using Base::coeffRef; - using Base::coeffRefByOuterInner; - using Base::copyCoeff; - using Base::copyCoeffByOuterInner; - using Base::copyPacket; - using Base::copyPacketByOuterInner; using Base::operator(); using Base::operator[]; using Base::x; @@ -169,19 +167,46 @@ template class DenseBase InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime) : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime), - CoeffReadCost = internal::traits::CoeffReadCost, - /**< This is a rough measure of how expensive it is to read one coefficient from - * this expression. - */ - InnerStrideAtCompileTime = internal::inner_stride_at_compile_time::ret, OuterStrideAtCompileTime = internal::outer_stride_at_compile_time::ret }; + + typedef typename internal::find_best_packet::type PacketScalar; - enum { ThisConstantIsPrivateInPlainObjectBase }; + enum { IsPlainObjectBase = 0 }; + + /** The plain matrix type corresponding to this expression. + * \sa PlainObject */ + typedef Matrix::Scalar, + internal::traits::RowsAtCompileTime, + internal::traits::ColsAtCompileTime, + AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), + internal::traits::MaxRowsAtCompileTime, + internal::traits::MaxColsAtCompileTime + > PlainMatrix; + + /** The plain array type corresponding to this expression. + * \sa PlainObject */ + typedef Array::Scalar, + internal::traits::RowsAtCompileTime, + internal::traits::ColsAtCompileTime, + AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), + internal::traits::MaxRowsAtCompileTime, + internal::traits::MaxColsAtCompileTime + > PlainArray; + + /** \brief The plain matrix or array type corresponding to this expression. + * + * This is not necessarily exactly the return type of eval(). In the case of plain matrices, + * the return type of eval() is a const reference to a matrix, not a matrix! It is however guaranteed + * that the return type of eval() is either PlainObject or const PlainObject&. + */ + typedef typename internal::conditional::XprKind,MatrixXpr >::value, + PlainMatrix, PlainArray>::type PlainObject; /** \returns the number of nonzero coefficients which is in practice the number * of stored coefficients. */ + EIGEN_DEVICE_FUNC inline Index nonZeros() const { return size(); } /** \returns the outer size. @@ -189,6 +214,7 @@ template class DenseBase * \note For a vector, this returns just 1. For a matrix (non-vector), this is the major dimension * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of columns for a * column-major matrix, and the number of rows for a row-major matrix. */ + EIGEN_DEVICE_FUNC Index outerSize() const { return IsVectorAtCompileTime ? 1 @@ -200,6 +226,7 @@ template class DenseBase * \note For a vector, this is just the size. For a matrix (non-vector), this is the minor dimension * with respect to the \ref TopicStorageOrders "storage order", i.e., the number of rows for a * column-major matrix, and the number of columns for a row-major matrix. */ + EIGEN_DEVICE_FUNC Index innerSize() const { return IsVectorAtCompileTime ? this->size() @@ -210,6 +237,7 @@ template class DenseBase * Matrix::resize() and Array::resize(). The present method only asserts that the new size equals the old size, and does * nothing else. */ + EIGEN_DEVICE_FUNC void resize(Index newSize) { EIGEN_ONLY_USED_FOR_DEBUG(newSize); @@ -220,22 +248,22 @@ template class DenseBase * Matrix::resize() and Array::resize(). The present method only asserts that the new size equals the old size, and does * nothing else. */ - void resize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + void resize(Index rows, Index cols) { - EIGEN_ONLY_USED_FOR_DEBUG(nbRows); - EIGEN_ONLY_USED_FOR_DEBUG(nbCols); - eigen_assert(nbRows == this->rows() && nbCols == this->cols() + EIGEN_ONLY_USED_FOR_DEBUG(rows); + EIGEN_ONLY_USED_FOR_DEBUG(cols); + eigen_assert(rows == this->rows() && cols == this->cols() && "DenseBase::resize() does not actually allow to resize."); } #ifndef EIGEN_PARSED_BY_DOXYGEN - /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; - /** \internal Represents a vector with linearly spaced coefficients that allows sequential access only. */ - typedef CwiseNullaryOp,Derived> SequentialLinSpacedReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; + /** \internal \deprecated Represents a vector with linearly spaced coefficients that allows sequential access only. */ + typedef CwiseNullaryOp,PlainObject> SequentialLinSpacedReturnType; /** \internal Represents a vector with linearly spaced coefficients that allows random access. */ - typedef CwiseNullaryOp,Derived> RandomAccessLinSpacedReturnType; + typedef CwiseNullaryOp,PlainObject> RandomAccessLinSpacedReturnType; /** \internal the return type of MatrixBase::eigenvalues() */ typedef Matrix::Scalar>::Real, internal::traits::ColsAtCompileTime, 1> EigenvaluesReturnType; @@ -243,120 +271,133 @@ template class DenseBase /** Copies \a other into *this. \returns a reference to *this. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator+=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator-=(const EigenBase &other); template + EIGEN_DEVICE_FUNC Derived& operator=(const ReturnByValue& func); - /** \internal Copies \a other into *this without evaluating other. \returns a reference to *this. */ + /** \internal + * Copies \a other into *this without evaluating other. \returns a reference to *this. + * \deprecated */ template + EIGEN_DEVICE_FUNC Derived& lazyAssign(const DenseBase& other); - /** \internal Evaluates \a other into *this. \returns a reference to *this. */ - template - Derived& lazyAssign(const ReturnByValue& other); - + EIGEN_DEVICE_FUNC CommaInitializer operator<< (const Scalar& s); + /** \deprecated it now returns \c *this */ template - const Flagged flagged() const; + EIGEN_DEPRECATED + const Derived& flagged() const + { return derived(); } template + EIGEN_DEVICE_FUNC CommaInitializer operator<< (const DenseBase& other); - Eigen::Transpose transpose(); - typedef typename internal::add_const >::type ConstTransposeReturnType; + typedef Transpose TransposeReturnType; + EIGEN_DEVICE_FUNC + TransposeReturnType transpose(); + typedef typename internal::add_const >::type ConstTransposeReturnType; + EIGEN_DEVICE_FUNC ConstTransposeReturnType transpose() const; + EIGEN_DEVICE_FUNC void transposeInPlace(); -#ifndef EIGEN_NO_DEBUG - protected: - template - void checkTransposeAliasing(const OtherDerived& other) const; - public: -#endif - - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(Index rows, Index cols, const Scalar& value); - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(Index size, const Scalar& value); - static const ConstantReturnType + EIGEN_DEVICE_FUNC static const ConstantReturnType Constant(const Scalar& value); - static const SequentialLinSpacedReturnType + EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType LinSpaced(Sequential_t, Index size, const Scalar& low, const Scalar& high); - static const RandomAccessLinSpacedReturnType + EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(Index size, const Scalar& low, const Scalar& high); - static const SequentialLinSpacedReturnType + EIGEN_DEVICE_FUNC static const SequentialLinSpacedReturnType LinSpaced(Sequential_t, const Scalar& low, const Scalar& high); - static const RandomAccessLinSpacedReturnType + EIGEN_DEVICE_FUNC static const RandomAccessLinSpacedReturnType LinSpaced(const Scalar& low, const Scalar& high); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(Index rows, Index cols, const CustomNullaryOp& func); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(Index size, const CustomNullaryOp& func); - template - static const CwiseNullaryOp + template EIGEN_DEVICE_FUNC + static const CwiseNullaryOp NullaryExpr(const CustomNullaryOp& func); - static const ConstantReturnType Zero(Index rows, Index cols); - static const ConstantReturnType Zero(Index size); - static const ConstantReturnType Zero(); - static const ConstantReturnType Ones(Index rows, Index cols); - static const ConstantReturnType Ones(Index size); - static const ConstantReturnType Ones(); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(Index size); + EIGEN_DEVICE_FUNC static const ConstantReturnType Zero(); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(Index size); + EIGEN_DEVICE_FUNC static const ConstantReturnType Ones(); - void fill(const Scalar& value); - Derived& setConstant(const Scalar& value); - Derived& setLinSpaced(Index size, const Scalar& low, const Scalar& high); - Derived& setLinSpaced(const Scalar& low, const Scalar& high); - Derived& setZero(); - Derived& setOnes(); - Derived& setRandom(); + EIGEN_DEVICE_FUNC void fill(const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setConstant(const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setLinSpaced(Index size, const Scalar& low, const Scalar& high); + EIGEN_DEVICE_FUNC Derived& setLinSpaced(const Scalar& low, const Scalar& high); + EIGEN_DEVICE_FUNC Derived& setZero(); + EIGEN_DEVICE_FUNC Derived& setOnes(); + EIGEN_DEVICE_FUNC Derived& setRandom(); - template + template EIGEN_DEVICE_FUNC bool isApprox(const DenseBase& other, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const RealScalar& other, const RealScalar& prec = NumTraits::dummy_precision()) const; - template + template EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const DenseBase& other, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isApproxToConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isZero(const RealScalar& prec = NumTraits::dummy_precision()) const; - bool isOnes(const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isApproxToConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isConstant(const Scalar& value, const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isZero(const RealScalar& prec = NumTraits::dummy_precision()) const; + EIGEN_DEVICE_FUNC bool isOnes(const RealScalar& prec = NumTraits::dummy_precision()) const; inline bool hasNaN() const; inline bool allFinite() const; - inline Derived& operator*=(const Scalar& other); - inline Derived& operator/=(const Scalar& other); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator*=(const Scalar& other); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator/=(const Scalar& other); typedef typename internal::add_const_on_value_type::type>::type EvalReturnType; /** \returns the matrix or vector obtained by evaluating this expression. * * Notice that in the case of a plain matrix or vector (not an expression) this function just returns * a const reference, in order to avoid a useless copy. + * + * \warning Be carefull with eval() and the auto C++ keyword, as detailed in this \link TopicPitfalls_auto_keyword page \endlink. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvalReturnType eval() const { // Even though MSVC does not honor strong inlining when the return type @@ -364,61 +405,78 @@ template class DenseBase // size types on MSVC. return typename internal::eval::type(derived()); } - + /** swaps *this with the expression \a other. * */ template - void swap(const DenseBase& other, - int = OtherDerived::ThisConstantIsPrivateInPlainObjectBase) + EIGEN_DEVICE_FUNC + void swap(const DenseBase& other) { - SwapWrapper(derived()).lazyAssign(other.derived()); + EIGEN_STATIC_ASSERT(!OtherDerived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); + eigen_assert(rows()==other.rows() && cols()==other.cols()); + call_assignment(derived(), other.const_cast_derived(), internal::swap_assign_op()); } /** swaps *this with the matrix or array \a other. * */ template + EIGEN_DEVICE_FUNC void swap(PlainObjectBase& other) { - SwapWrapper(derived()).lazyAssign(other.derived()); + eigen_assert(rows()==other.rows() && cols()==other.cols()); + call_assignment(derived(), other.derived(), internal::swap_assign_op()); } + EIGEN_DEVICE_FUNC inline const NestByValue nestByValue() const; + EIGEN_DEVICE_FUNC inline const ForceAlignedAccess forceAlignedAccess() const; + EIGEN_DEVICE_FUNC inline ForceAlignedAccess forceAlignedAccess(); + template EIGEN_DEVICE_FUNC + inline const typename internal::conditional,Derived&>::type forceAlignedAccessIf() const; + template EIGEN_DEVICE_FUNC + inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); - inline const NestByValue nestByValue() const; - inline const ForceAlignedAccess forceAlignedAccess() const; - inline ForceAlignedAccess forceAlignedAccess(); - template inline const typename internal::conditional,Derived&>::type forceAlignedAccessIf() const; - template inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); + EIGEN_DEVICE_FUNC Scalar sum() const; + EIGEN_DEVICE_FUNC Scalar mean() const; + EIGEN_DEVICE_FUNC Scalar trace() const; - Scalar sum() const; - Scalar mean() const; - Scalar trace() const; + EIGEN_DEVICE_FUNC Scalar prod() const; - Scalar prod() const; + EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff() const; + EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff() const; - typename internal::traits::Scalar minCoeff() const; - typename internal::traits::Scalar maxCoeff() const; - - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* row, IndexType* col) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* row, IndexType* col) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar minCoeff(IndexType* index) const; - template + template EIGEN_DEVICE_FUNC typename internal::traits::Scalar maxCoeff(IndexType* index) const; template - typename internal::result_of::Scalar)>::type - redux(const BinaryOp& func) const; + EIGEN_DEVICE_FUNC + Scalar redux(const BinaryOp& func) const; template + EIGEN_DEVICE_FUNC void visit(Visitor& func) const; - inline const WithFormat format(const IOFormat& fmt) const; + /** \returns a WithFormat proxy object allowing to print a matrix the with given + * format \a fmt. + * + * See class IOFormat for some examples. + * + * \sa class IOFormat, class WithFormat + */ + inline const WithFormat format(const IOFormat& fmt) const + { + return WithFormat(derived(), fmt); + } /** \returns the unique coefficient of a 1x1 expression */ + EIGEN_DEVICE_FUNC CoeffReturnType value() const { EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) @@ -426,23 +484,44 @@ template class DenseBase return derived().coeff(0,0); } - bool all(void) const; - bool any(void) const; - Index count() const; + EIGEN_DEVICE_FUNC bool all() const; + EIGEN_DEVICE_FUNC bool any() const; + EIGEN_DEVICE_FUNC Index count() const; typedef VectorwiseOp RowwiseReturnType; typedef const VectorwiseOp ConstRowwiseReturnType; typedef VectorwiseOp ColwiseReturnType; typedef const VectorwiseOp ConstColwiseReturnType; - ConstRowwiseReturnType rowwise() const; - RowwiseReturnType rowwise(); - ConstColwiseReturnType colwise() const; - ColwiseReturnType colwise(); + /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + * + * Example: \include MatrixBase_rowwise.cpp + * Output: \verbinclude MatrixBase_rowwise.out + * + * \sa colwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting + */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC inline ConstRowwiseReturnType rowwise() const { + return ConstRowwiseReturnType(derived()); + } + EIGEN_DEVICE_FUNC RowwiseReturnType rowwise(); - static const CwiseNullaryOp,Derived> Random(Index rows, Index cols); - static const CwiseNullaryOp,Derived> Random(Index size); - static const CwiseNullaryOp,Derived> Random(); + /** \returns a VectorwiseOp wrapper of *this providing additional partial reduction operations + * + * Example: \include MatrixBase_colwise.cpp + * Output: \verbinclude MatrixBase_colwise.out + * + * \sa rowwise(), class VectorwiseOp, \ref TutorialReductionsVisitorsBroadcasting + */ + EIGEN_DEVICE_FUNC inline ConstColwiseReturnType colwise() const { + return ConstColwiseReturnType(derived()); + } + EIGEN_DEVICE_FUNC ColwiseReturnType colwise(); + + typedef CwiseNullaryOp,PlainObject> RandomReturnType; + static const RandomReturnType Random(Index rows, Index cols); + static const RandomReturnType Random(Index size); + static const RandomReturnType Random(); template const Select @@ -460,45 +539,56 @@ template class DenseBase template RealScalar lpNorm() const; template - inline const Replicate replicate() const; - - typedef Replicate ReplicateReturnType; - inline const ReplicateReturnType replicate(Index rowFacor,Index colFactor) const; + EIGEN_DEVICE_FUNC + const Replicate replicate() const; + /** + * \return an expression of the replication of \c *this + * + * Example: \include MatrixBase_replicate_int_int.cpp + * Output: \verbinclude MatrixBase_replicate_int_int.out + * + * \sa VectorwiseOp::replicate(), DenseBase::replicate(), class Replicate + */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC + const Replicate replicate(Index rowFactor, Index colFactor) const + { + return Replicate(derived(), rowFactor, colFactor); + } typedef Reverse ReverseReturnType; typedef const Reverse ConstReverseReturnType; - ReverseReturnType reverse(); - ConstReverseReturnType reverse() const; - void reverseInPlace(); + EIGEN_DEVICE_FUNC ReverseReturnType reverse(); + /** This is the const version of reverse(). */ + //Code moved here due to a CUDA compiler bug + EIGEN_DEVICE_FUNC ConstReverseReturnType reverse() const + { + return ConstReverseReturnType(derived()); + } + EIGEN_DEVICE_FUNC void reverseInPlace(); #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::DenseBase +#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL +#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) # include "../plugins/BlockMethods.h" # ifdef EIGEN_DENSEBASE_PLUGIN # include EIGEN_DENSEBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS - -#ifdef EIGEN2_SUPPORT - - Block corner(CornerType type, Index cRows, Index cCols); - const Block corner(CornerType type, Index cRows, Index cCols) const; - template - Block corner(CornerType type); - template - const Block corner(CornerType type) const; - -#endif // EIGEN2_SUPPORT - +#undef EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL +#undef EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF // disable the use of evalTo for dense objects with a nice compilation error - template inline void evalTo(Dest& ) const + template + EIGEN_DEVICE_FUNC + inline void evalTo(Dest& ) const { EIGEN_STATIC_ASSERT((internal::is_same::value),THE_EVAL_EVALTO_FUNCTION_SHOULD_NEVER_BE_CALLED_FOR_DENSE_OBJECTS); } protected: /** Default constructor. Do nothing. */ - DenseBase() + EIGEN_DEVICE_FUNC DenseBase() { /* Just checks for self-consistency of the flags. * Only do it when debugging Eigen, as this borders on paranoiac and could slow compilation down @@ -511,9 +601,9 @@ template class DenseBase } private: - explicit DenseBase(int); - DenseBase(int,int); - template explicit DenseBase(const DenseBase&); + EIGEN_DEVICE_FUNC explicit DenseBase(int); + EIGEN_DEVICE_FUNC DenseBase(int,int); + template EIGEN_DEVICE_FUNC explicit DenseBase(const DenseBase&); }; } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h index 3c890f215..c4af48ab6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseCoeffsBase.h @@ -35,7 +35,6 @@ class DenseCoeffsBase : public EigenBase { public: typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; @@ -61,6 +60,7 @@ class DenseCoeffsBase : public EigenBase using Base::size; using Base::derived; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowIndexByOuterInner(Index outer, Index inner) const { return int(Derived::RowsAtCompileTime) == 1 ? 0 @@ -69,6 +69,7 @@ class DenseCoeffsBase : public EigenBase : inner; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colIndexByOuterInner(Index outer, Index inner) const { return int(Derived::ColsAtCompileTime) == 1 ? 0 @@ -91,13 +92,15 @@ class DenseCoeffsBase : public EigenBase * * \sa operator()(Index,Index) const, coeffRef(Index,Index), coeff(Index) const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index row, Index col) const { eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().coeff(row, col); + && col >= 0 && col < cols()); + return internal::evaluator(derived()).coeff(row,col); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffByOuterInner(Index outer, Index inner) const { return coeff(rowIndexByOuterInner(outer, inner), @@ -108,11 +111,12 @@ class DenseCoeffsBase : public EigenBase * * \sa operator()(Index,Index), operator[](Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator()(Index row, Index col) const { eigen_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); - return derived().coeff(row, col); + return coeff(row, col); } /** Short version: don't use this function, use @@ -130,11 +134,14 @@ class DenseCoeffsBase : public EigenBase * \sa operator[](Index) const, coeffRef(Index), coeff(Index,Index) const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + EIGEN_STATIC_ASSERT(internal::evaluator::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) eigen_internal_assert(index >= 0 && index < size()); - return derived().coeff(index); + return internal::evaluator(derived()).coeff(index); } @@ -146,15 +153,14 @@ class DenseCoeffsBase : public EigenBase * z() const, w() const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator[](Index index) const { - #ifndef EIGEN2_SUPPORT EIGEN_STATIC_ASSERT(Derived::IsVectorAtCompileTime, THE_BRACKET_OPERATOR_IS_ONLY_FOR_VECTORS__USE_THE_PARENTHESIS_OPERATOR_INSTEAD) - #endif eigen_assert(index >= 0 && index < size()); - return derived().coeff(index); + return coeff(index); } /** \returns the coefficient at given index. @@ -167,32 +173,49 @@ class DenseCoeffsBase : public EigenBase * z() const, w() const */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType operator()(Index index) const { eigen_assert(index >= 0 && index < size()); - return derived().coeff(index); + return coeff(index); } /** equivalent to operator[](0). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType x() const { return (*this)[0]; } /** equivalent to operator[](1). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - y() const { return (*this)[1]; } + y() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=2, OUT_OF_RANGE_ACCESS); + return (*this)[1]; + } /** equivalent to operator[](2). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - z() const { return (*this)[2]; } + z() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=3, OUT_OF_RANGE_ACCESS); + return (*this)[2]; + } /** equivalent to operator[](3). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType - w() const { return (*this)[3]; } + w() const + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=4, OUT_OF_RANGE_ACCESS); + return (*this)[3]; + } /** \internal * \returns the packet of coefficients starting at the given row and column. It is your responsibility @@ -207,9 +230,9 @@ class DenseCoeffsBase : public EigenBase template EIGEN_STRONG_INLINE PacketReturnType packet(Index row, Index col) const { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().template packet(row,col); + typedef typename internal::packet_traits::type DefaultPacketType; + eigen_internal_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); + return internal::evaluator(derived()).template packet(row,col); } @@ -234,8 +257,11 @@ class DenseCoeffsBase : public EigenBase template EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const { + EIGEN_STATIC_ASSERT(internal::evaluator::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) + typedef typename internal::packet_traits::type DefaultPacketType; eigen_internal_assert(index >= 0 && index < size()); - return derived().template packet(index); + return internal::evaluator(derived()).template packet(index); } protected: @@ -278,7 +304,6 @@ class DenseCoeffsBase : public DenseCoeffsBase Base; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -311,13 +336,15 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && row < rows() - && col >= 0 && col < cols()); - return derived().coeffRef(row, col); + && col >= 0 && col < cols()); + return internal::evaluator(derived()).coeffRef(row,col); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRefByOuterInner(Index outer, Index inner) { @@ -330,12 +357,13 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && row < rows() && col >= 0 && col < cols()); - return derived().coeffRef(row, col); + return coeffRef(row, col); } @@ -354,11 +382,14 @@ class DenseCoeffsBase : public DenseCoeffsBase::Flags & LinearAccessBit, + THIS_COEFFICIENT_ACCESSOR_TAKING_ONE_ACCESS_IS_ONLY_FOR_EXPRESSIONS_ALLOWING_LINEAR_ACCESS) eigen_internal_assert(index >= 0 && index < size()); - return derived().coeffRef(index); + return internal::evaluator(derived()).coeffRef(index); } /** \returns a reference to the coefficient at given index. @@ -368,15 +399,14 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && index < size()); - return derived().coeffRef(index); + return coeffRef(index); } /** \returns a reference to the coefficient at given index. @@ -388,167 +418,49 @@ class DenseCoeffsBase : public DenseCoeffsBase= 0 && index < size()); - return derived().coeffRef(index); + return coeffRef(index); } /** equivalent to operator[](0). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& x() { return (*this)[0]; } /** equivalent to operator[](1). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - y() { return (*this)[1]; } + y() + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=2, OUT_OF_RANGE_ACCESS); + return (*this)[1]; + } /** equivalent to operator[](2). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - z() { return (*this)[2]; } + z() + { + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=3, OUT_OF_RANGE_ACCESS); + return (*this)[2]; + } /** equivalent to operator[](3). */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& - w() { return (*this)[3]; } - - /** \internal - * Stores the given packet of coefficients, at the given row and column of this expression. It is your responsibility - * to ensure that a packet really starts there. This method is only available on expressions having the - * PacketAccessBit. - * - * The \a LoadMode parameter may have the value \a #Aligned or \a #Unaligned. Its effect is to select - * the appropriate vectorization instruction. Aligned access is faster, but is only possible for packets - * starting at an address which is a multiple of the packet size. - */ - - template - EIGEN_STRONG_INLINE void writePacket - (Index row, Index col, const typename internal::packet_traits::type& val) + w() { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().template writePacket(row,col,val); + EIGEN_STATIC_ASSERT(Derived::SizeAtCompileTime==-1 || Derived::SizeAtCompileTime>=4, OUT_OF_RANGE_ACCESS); + return (*this)[3]; } - - - /** \internal */ - template - EIGEN_STRONG_INLINE void writePacketByOuterInner - (Index outer, Index inner, const typename internal::packet_traits::type& val) - { - writePacket(rowIndexByOuterInner(outer, inner), - colIndexByOuterInner(outer, inner), - val); - } - - /** \internal - * Stores the given packet of coefficients, at the given index in this expression. It is your responsibility - * to ensure that a packet really starts there. This method is only available on expressions having the - * PacketAccessBit and the LinearAccessBit. - * - * The \a LoadMode parameter may have the value \a Aligned or \a Unaligned. Its effect is to select - * the appropriate vectorization instruction. Aligned access is faster, but is only possible for packets - * starting at an address which is a multiple of the packet size. - */ - template - EIGEN_STRONG_INLINE void writePacket - (Index index, const typename internal::packet_traits::type& val) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().template writePacket(index,val); - } - -#ifndef EIGEN_PARSED_BY_DOXYGEN - - /** \internal Copies the coefficient at position (row,col) of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyCoeff(Index row, Index col, const DenseBase& other) - { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().coeffRef(row, col) = other.derived().coeff(row, col); - } - - /** \internal Copies the coefficient at the given index of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyCoeff(Index index, const DenseBase& other) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().coeffRef(index) = other.derived().coeff(index); - } - - - template - EIGEN_STRONG_INLINE void copyCoeffByOuterInner(Index outer, Index inner, const DenseBase& other) - { - const Index row = rowIndexByOuterInner(outer,inner); - const Index col = colIndexByOuterInner(outer,inner); - // derived() is important here: copyCoeff() may be reimplemented in Derived! - derived().copyCoeff(row, col, other); - } - - /** \internal Copies the packet at position (row,col) of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyPacket(Index row, Index col, const DenseBase& other) - { - eigen_internal_assert(row >= 0 && row < rows() - && col >= 0 && col < cols()); - derived().template writePacket(row, col, - other.derived().template packet(row, col)); - } - - /** \internal Copies the packet at the given index of other into *this. - * - * This method is overridden in SwapWrapper, allowing swap() assignments to share 99% of their code - * with usual assignments. - * - * Outside of this internal usage, this method has probably no usefulness. It is hidden in the public API dox. - */ - - template - EIGEN_STRONG_INLINE void copyPacket(Index index, const DenseBase& other) - { - eigen_internal_assert(index >= 0 && index < size()); - derived().template writePacket(index, - other.derived().template packet(index)); - } - - /** \internal */ - template - EIGEN_STRONG_INLINE void copyPacketByOuterInner(Index outer, Index inner, const DenseBase& other) - { - const Index row = rowIndexByOuterInner(outer,inner); - const Index col = colIndexByOuterInner(outer,inner); - // derived() is important here: copyCoeff() may be reimplemented in Derived! - derived().template copyPacket< OtherDerived, StoreMode, LoadMode>(row, col, other); - } -#endif - }; /** \brief Base class providing direct read-only coefficient access to matrices and arrays. @@ -560,7 +472,7 @@ class DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read-only using * \c operator() . * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseCoeffsBase : public DenseCoeffsBase @@ -568,7 +480,6 @@ class DenseCoeffsBase : public DenseCoeffsBase Base; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; @@ -581,6 +492,7 @@ class DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase : public DenseCoeffsBase which defines functions to access entries read/write using * \c operator(). * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class DenseCoeffsBase @@ -639,7 +554,6 @@ class DenseCoeffsBase public: typedef DenseCoeffsBase Base; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename NumTraits::Real RealScalar; @@ -652,6 +566,7 @@ class DenseCoeffsBase * * \sa outerStride(), rowStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index innerStride() const { return derived().innerStride(); @@ -662,6 +577,7 @@ class DenseCoeffsBase * * \sa innerStride(), rowStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index outerStride() const { return derived().outerStride(); @@ -677,6 +593,7 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), colStride() */ + EIGEN_DEVICE_FUNC inline Index rowStride() const { return Derived::IsRowMajor ? outerStride() : innerStride(); @@ -686,6 +603,7 @@ class DenseCoeffsBase * * \sa innerStride(), outerStride(), rowStride() */ + EIGEN_DEVICE_FUNC inline Index colStride() const { return Derived::IsRowMajor ? innerStride() : outerStride(); @@ -694,33 +612,42 @@ class DenseCoeffsBase namespace internal { -template +template struct first_aligned_impl { - static inline typename Derived::Index run(const Derived&) + static inline Index run(const Derived&) { return 0; } }; -template -struct first_aligned_impl +template +struct first_aligned_impl { - static inline typename Derived::Index run(const Derived& m) + static inline Index run(const Derived& m) { - return internal::first_aligned(&m.const_cast_derived().coeffRef(0,0), m.size()); + return internal::first_aligned(m.data(), m.size()); } }; -/** \internal \returns the index of the first element of the array that is well aligned for vectorization. +/** \internal \returns the index of the first element of the array stored by \a m that is properly aligned with respect to \a Alignment for vectorization. + * + * \tparam Alignment requested alignment in Bytes. * * There is also the variant first_aligned(const Scalar*, Integer) defined in Memory.h. See it for more * documentation. */ -template -static inline typename Derived::Index first_aligned(const Derived& m) +template +static inline Index first_aligned(const DenseBase& m) { - return first_aligned_impl - - ::run(m); + enum { ReturnZero = (int(evaluator::Alignment) >= Alignment) || !(Derived::Flags & DirectAccessBit) }; + return first_aligned_impl::run(m.derived()); +} + +template +static inline Index first_default_aligned(const DenseBase& m) +{ + typedef typename Derived::Scalar Scalar; + typedef typename packet_traits::type DefaultPacketType; + return internal::first_aligned::alignment),Derived>(m); } template::ret> diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h index 568493cba..7958feeb9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DenseStorage.h @@ -3,7 +3,7 @@ // // Copyright (C) 2008 Gael Guennebaud // Copyright (C) 2006-2009 Benoit Jacob -// Copyright (C) 2010 Hauke Heibel +// Copyright (C) 2010-2013 Hauke Heibel // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -13,9 +13,9 @@ #define EIGEN_MATRIXSTORAGE_H #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN EIGEN_DENSE_STORAGE_CTOR_PLUGIN; + #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(X) X; EIGEN_DENSE_STORAGE_CTOR_PLUGIN; #else - #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + #define EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(X) #endif namespace Eigen { @@ -24,7 +24,9 @@ namespace internal { struct constructor_without_unaligned_array_assert {}; -template void check_static_allocation_size() +template +EIGEN_DEVICE_FUNC +void check_static_allocation_size() { // if EIGEN_STACK_ALLOCATION_LIMIT is defined to 0, then no limit #if EIGEN_STACK_ALLOCATION_LIMIT @@ -38,18 +40,19 @@ template void check_static_allocation_size() */ template + : compute_default_alignment::value > struct plain_array { T array[Size]; - plain_array() + EIGEN_DEVICE_FUNC + plain_array() { check_static_allocation_size(); } - plain_array(constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) { check_static_allocation_size(); } @@ -64,29 +67,88 @@ struct plain_array template EIGEN_ALWAYS_INLINE PtrType eigen_unaligned_array_assert_workaround_gcc47(PtrType array) { return array; } #define EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(sizemask) \ - eigen_assert((reinterpret_cast(eigen_unaligned_array_assert_workaround_gcc47(array)) & sizemask) == 0 \ + eigen_assert((internal::UIntPtr(eigen_unaligned_array_assert_workaround_gcc47(array)) & (sizemask)) == 0 \ && "this assertion is explained here: " \ "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" \ " **** READ THIS WEB PAGE !!! ****"); #else #define EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(sizemask) \ - eigen_assert((reinterpret_cast(array) & sizemask) == 0 \ + eigen_assert((internal::UIntPtr(array) & (sizemask)) == 0 \ && "this assertion is explained here: " \ "http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html" \ " **** READ THIS WEB PAGE !!! ****"); #endif template -struct plain_array +struct plain_array { - EIGEN_USER_ALIGN16 T array[Size]; + EIGEN_ALIGN_TO_BOUNDARY(8) T array[Size]; + EIGEN_DEVICE_FUNC plain_array() - { - EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(0xf); + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(7); check_static_allocation_size(); } + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(16) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(15); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(32) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(31); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC + plain_array(constructor_without_unaligned_array_assert) + { + check_static_allocation_size(); + } +}; + +template +struct plain_array +{ + EIGEN_ALIGN_TO_BOUNDARY(64) T array[Size]; + + EIGEN_DEVICE_FUNC + plain_array() + { + EIGEN_MAKE_UNALIGNED_ARRAY_ASSERT(63); + check_static_allocation_size(); + } + + EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) { check_static_allocation_size(); @@ -96,9 +158,9 @@ struct plain_array template struct plain_array { - EIGEN_USER_ALIGN16 T array[1]; - plain_array() {} - plain_array(constructor_without_unaligned_array_assert) {} + T array[1]; + EIGEN_DEVICE_FUNC plain_array() {} + EIGEN_DEVICE_FUNC plain_array(constructor_without_unaligned_array_assert) {} }; } // end namespace internal @@ -122,41 +184,54 @@ template class DenseSt { internal::plain_array m_data; public: - DenseStorage() {} - DenseStorage(internal::constructor_without_unaligned_array_assert) - : m_data(internal::constructor_without_unaligned_array_assert()) {} - DenseStorage(const DenseStorage& other) : m_data(other.m_data) {} - DenseStorage& operator=(const DenseStorage& other) - { - if (this != &other) m_data = other.m_data; - return *this; + EIGEN_DEVICE_FUNC DenseStorage() { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = Size) } - DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } - static DenseIndex rows(void) {return _Rows;} - static DenseIndex cols(void) {return _Cols;} - void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - void resize(DenseIndex,DenseIndex,DenseIndex) {} - const T *data() const { return m_data.array; } - T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) + : m_data(internal::constructor_without_unaligned_array_assert()) {} + EIGEN_DEVICE_FUNC + DenseStorage(const DenseStorage& other) : m_data(other.m_data) { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = Size) + } + EIGEN_DEVICE_FUNC + DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) m_data = other.m_data; + return *this; + } + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows==_Rows && cols==_Cols); + EIGEN_UNUSED_VARIABLE(size); + EIGEN_UNUSED_VARIABLE(rows); + EIGEN_UNUSED_VARIABLE(cols); + } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); } + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void resize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // null matrix template class DenseStorage { public: - DenseStorage() {} - DenseStorage(internal::constructor_without_unaligned_array_assert) {} - DenseStorage(const DenseStorage&) {} - DenseStorage& operator=(const DenseStorage&) { return *this; } - DenseStorage(DenseIndex,DenseIndex,DenseIndex) {} - void swap(DenseStorage& ) {} - static DenseIndex rows(void) {return _Rows;} - static DenseIndex cols(void) {return _Cols;} - void conservativeResize(DenseIndex,DenseIndex,DenseIndex) {} - void resize(DenseIndex,DenseIndex,DenseIndex) {} - const T *data() const { return 0; } - T *data() { return 0; } + EIGEN_DEVICE_FUNC DenseStorage() {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) {} + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage&) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage&) { return *this; } + EIGEN_DEVICE_FUNC DenseStorage(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& ) {} + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC void resize(Index,Index,Index) {} + EIGEN_DEVICE_FUNC const T *data() const { return 0; } + EIGEN_DEVICE_FUNC T *data() { return 0; } }; // more specializations for null matrices; these are necessary to resolve ambiguities @@ -173,74 +248,74 @@ template class DenseStorage class DenseStorage { internal::plain_array m_data; - DenseIndex m_rows; - DenseIndex m_cols; + Index m_rows; + Index m_cols; public: - DenseStorage() : m_rows(0), m_cols(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_rows(0), m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_rows(0), m_cols(0) {} - DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows), m_cols(other.m_cols) {} - DenseStorage& operator=(const DenseStorage& other) - { + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows), m_cols(other.m_cols) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { if (this != &other) { m_data = other.m_data; m_rows = other.m_rows; m_cols = other.m_cols; } - return *this; + return *this; } - DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) : m_rows(nbRows), m_cols(nbCols) {} - void swap(DenseStorage& other) + EIGEN_DEVICE_FUNC DenseStorage(Index, Index rows, Index cols) : m_rows(rows), m_cols(cols) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - DenseIndex rows() const {return m_rows;} - DenseIndex cols() const {return m_cols;} - void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) { m_rows = nbRows; m_cols = nbCols; } - void resize(DenseIndex, DenseIndex nbRows, DenseIndex nbCols) { m_rows = nbRows; m_cols = nbCols; } - const T *data() const { return m_data.array; } - T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC Index rows() const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols() const {return m_cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index, Index rows, Index cols) { m_rows = rows; m_cols = cols; } + EIGEN_DEVICE_FUNC void resize(Index, Index rows, Index cols) { m_rows = rows; m_cols = cols; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // dynamic-size matrix with fixed-size storage and fixed width template class DenseStorage { internal::plain_array m_data; - DenseIndex m_rows; + Index m_rows; public: - DenseStorage() : m_rows(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_rows(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_rows(0) {} - DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows) {} - DenseStorage& operator=(const DenseStorage& other) + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_rows(other.m_rows) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) { if (this != &other) { m_data = other.m_data; m_rows = other.m_rows; } - return *this; + return *this; } - DenseStorage(DenseIndex, DenseIndex nbRows, DenseIndex) : m_rows(nbRows) {} - void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - DenseIndex rows(void) const {return m_rows;} - DenseIndex cols(void) const {return _Cols;} - void conservativeResize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - void resize(DenseIndex, DenseIndex nbRows, DenseIndex) { m_rows = nbRows; } - const T *data() const { return m_data.array; } - T *data() { return m_data.array; } + EIGEN_DEVICE_FUNC DenseStorage(Index, Index rows, Index) : m_rows(rows) {} + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return _Cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index, Index rows, Index) { m_rows = rows; } + EIGEN_DEVICE_FUNC void resize(Index, Index rows, Index) { m_rows = rows; } + EIGEN_DEVICE_FUNC const T *data() const { return m_data.array; } + EIGEN_DEVICE_FUNC T *data() { return m_data.array; } }; // dynamic-size matrix with fixed-size storage and fixed height template class DenseStorage { internal::plain_array m_data; - DenseIndex m_cols; + Index m_cols; public: - DenseStorage() : m_cols(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(internal::constructor_without_unaligned_array_assert()), m_cols(0) {} - DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_cols(other.m_cols) {} - DenseStorage& operator=(const DenseStorage& other) + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) : m_data(other.m_data), m_cols(other.m_cols) {} + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) { if (this != &other) { @@ -249,38 +324,62 @@ template class DenseStorage class DenseStorage { T *m_data; - DenseIndex m_rows; - DenseIndex m_cols; + Index m_rows; + Index m_cols; public: - DenseStorage() : m_data(0), m_rows(0), m_cols(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_rows(0), m_cols(0) {} + EIGEN_DEVICE_FUNC explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0), m_cols(0) {} - DenseStorage(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) - : m_data(internal::conditional_aligned_new_auto(size)), m_rows(nbRows), m_cols(nbCols) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - DenseStorage(DenseStorage&& other) + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) + : m_data(internal::conditional_aligned_new_auto(size)), m_rows(rows), m_cols(cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows>=0 && cols >=0); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(other.m_rows*other.m_cols)) + , m_rows(other.m_rows) + , m_cols(other.m_cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_rows*m_cols) + internal::smart_copy(other.m_data, other.m_data+other.m_rows*other.m_cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT : m_data(std::move(other.m_data)) , m_rows(std::move(other.m_rows)) , m_cols(std::move(other.m_cols)) { other.m_data = nullptr; + other.m_rows = 0; + other.m_cols = 0; } - DenseStorage& operator=(DenseStorage&& other) + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT { using std::swap; swap(m_data, other.m_data); @@ -289,18 +388,18 @@ template class DenseStorage(m_data, m_rows*m_cols); } - void swap(DenseStorage& other) + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, m_rows*m_cols); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); std::swap(m_cols,other.m_cols); } - DenseIndex rows(void) const {return m_rows;} - DenseIndex cols(void) const {return m_cols;} - void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + void conservativeResize(Index size, Index rows, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*m_cols); - m_rows = nbRows; - m_cols = nbCols; + m_rows = rows; + m_cols = cols; } - void resize(DenseIndex size, DenseIndex nbRows, DenseIndex nbCols) + EIGEN_DEVICE_FUNC void resize(Index size, Index rows, Index cols) { if(size != m_rows*m_cols) { @@ -309,36 +408,56 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_rows = nbRows; - m_cols = nbCols; + m_rows = rows; + m_cols = cols; } - const T *data() const { return m_data; } - T *data() { return m_data; } - private: - DenseStorage(const DenseStorage&); - DenseStorage& operator=(const DenseStorage&); + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; // matrix with dynamic width and fixed height (so that matrix has dynamic size). template class DenseStorage { T *m_data; - DenseIndex m_cols; + Index m_cols; public: - DenseStorage() : m_data(0), m_cols(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_cols(0) {} - DenseStorage(DenseIndex size, DenseIndex, DenseIndex nbCols) : m_data(internal::conditional_aligned_new_auto(size)), m_cols(nbCols) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - DenseStorage(DenseStorage&& other) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_cols(0) {} + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_cols(0) {} + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) : m_data(internal::conditional_aligned_new_auto(size)), m_cols(cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows==_Rows && cols >=0); + EIGEN_UNUSED_VARIABLE(rows); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(_Rows*other.m_cols)) + , m_cols(other.m_cols) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_cols*_Rows) + internal::smart_copy(other.m_data, other.m_data+_Rows*m_cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT : m_data(std::move(other.m_data)) , m_cols(std::move(other.m_cols)) { other.m_data = nullptr; + other.m_cols = 0; } - DenseStorage& operator=(DenseStorage&& other) + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT { using std::swap; swap(m_data, other.m_data); @@ -346,16 +465,16 @@ template class DenseStorage(m_data, _Rows*m_cols); } - void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } - static DenseIndex rows(void) {return _Rows;} - DenseIndex cols(void) const {return m_cols;} - void conservativeResize(DenseIndex size, DenseIndex, DenseIndex nbCols) + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Rows*m_cols); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_cols,other.m_cols); } + EIGEN_DEVICE_FUNC static Index rows(void) {return _Rows;} + EIGEN_DEVICE_FUNC Index cols(void) const {return m_cols;} + EIGEN_DEVICE_FUNC void conservativeResize(Index size, Index, Index cols) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, _Rows*m_cols); - m_cols = nbCols; + m_cols = cols; } - EIGEN_STRONG_INLINE void resize(DenseIndex size, DenseIndex, DenseIndex nbCols) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index size, Index, Index cols) { if(size != _Rows*m_cols) { @@ -364,35 +483,55 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_cols = nbCols; + m_cols = cols; } - const T *data() const { return m_data; } - T *data() { return m_data; } - private: - DenseStorage(const DenseStorage&); - DenseStorage& operator=(const DenseStorage&); + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; // matrix with dynamic height and fixed width (so that matrix has dynamic size). template class DenseStorage { T *m_data; - DenseIndex m_rows; + Index m_rows; public: - DenseStorage() : m_data(0), m_rows(0) {} - DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0) {} - DenseStorage(DenseIndex size, DenseIndex nbRows, DenseIndex) : m_data(internal::conditional_aligned_new_auto(size)), m_rows(nbRows) - { EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN } -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - DenseStorage(DenseStorage&& other) + EIGEN_DEVICE_FUNC DenseStorage() : m_data(0), m_rows(0) {} + explicit DenseStorage(internal::constructor_without_unaligned_array_assert) : m_data(0), m_rows(0) {} + EIGEN_DEVICE_FUNC DenseStorage(Index size, Index rows, Index cols) : m_data(internal::conditional_aligned_new_auto(size)), m_rows(rows) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) + eigen_internal_assert(size==rows*cols && rows>=0 && cols == _Cols); + EIGEN_UNUSED_VARIABLE(cols); + } + EIGEN_DEVICE_FUNC DenseStorage(const DenseStorage& other) + : m_data(internal::conditional_aligned_new_auto(other.m_rows*_Cols)) + , m_rows(other.m_rows) + { + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN(Index size = m_rows*_Cols) + internal::smart_copy(other.m_data, other.m_data+other.m_rows*_Cols, m_data); + } + EIGEN_DEVICE_FUNC DenseStorage& operator=(const DenseStorage& other) + { + if (this != &other) + { + DenseStorage tmp(other); + this->swap(tmp); + } + return *this; + } +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + DenseStorage(DenseStorage&& other) EIGEN_NOEXCEPT : m_data(std::move(other.m_data)) , m_rows(std::move(other.m_rows)) { other.m_data = nullptr; + other.m_rows = 0; } - DenseStorage& operator=(DenseStorage&& other) + EIGEN_DEVICE_FUNC + DenseStorage& operator=(DenseStorage&& other) EIGEN_NOEXCEPT { using std::swap; swap(m_data, other.m_data); @@ -400,16 +539,16 @@ template class DenseStorage(m_data, _Cols*m_rows); } - void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } - DenseIndex rows(void) const {return m_rows;} - static DenseIndex cols(void) {return _Cols;} - void conservativeResize(DenseIndex size, DenseIndex nbRows, DenseIndex) + EIGEN_DEVICE_FUNC ~DenseStorage() { internal::conditional_aligned_delete_auto(m_data, _Cols*m_rows); } + EIGEN_DEVICE_FUNC void swap(DenseStorage& other) { std::swap(m_data,other.m_data); std::swap(m_rows,other.m_rows); } + EIGEN_DEVICE_FUNC Index rows(void) const {return m_rows;} + EIGEN_DEVICE_FUNC static Index cols(void) {return _Cols;} + void conservativeResize(Index size, Index rows, Index) { m_data = internal::conditional_aligned_realloc_new_auto(m_data, size, m_rows*_Cols); - m_rows = nbRows; + m_rows = rows; } - EIGEN_STRONG_INLINE void resize(DenseIndex size, DenseIndex nbRows, DenseIndex) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index size, Index rows, Index) { if(size != m_rows*_Cols) { @@ -418,15 +557,12 @@ template class DenseStorage(size); else m_data = 0; - EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN + EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({}) } - m_rows = nbRows; + m_rows = rows; } - const T *data() const { return m_data; } - T *data() { return m_data; } - private: - DenseStorage(const DenseStorage&); - DenseStorage& operator=(const DenseStorage&); + EIGEN_DEVICE_FUNC const T *data() const { return m_data; } + EIGEN_DEVICE_FUNC T *data() { return m_data; } }; } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Diagonal.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Diagonal.h index 68cf6d4b0..49e711257 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Diagonal.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Diagonal.h @@ -21,7 +21,7 @@ namespace Eigen { * \param MatrixType the type of the object in which we are taking a sub/main/super diagonal * \param DiagIndex the index of the sub/super diagonal. The default is 0 and it means the main diagonal. * A positive value means a superdiagonal, a negative value means a subdiagonal. - * You can also use Dynamic so the index can be set at runtime. + * You can also use DynamicIndex so the index can be set at runtime. * * The matrix is not required to be square. * @@ -37,7 +37,7 @@ template struct traits > : traits { - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; typedef typename MatrixType::StorageKind StorageKind; enum { @@ -52,8 +52,7 @@ struct traits > MatrixType::MaxColsAtCompileTime - EIGEN_PLAIN_ENUM_MAX( DiagIndex, 0))), MaxColsAtCompileTime = 1, MaskLvalueBit = is_lvalue::value ? LvalueBit : 0, - Flags = (unsigned int)_MatrixTypeNested::Flags & (HereditaryBits | LinearAccessBit | MaskLvalueBit | DirectAccessBit) & ~RowMajorBit, - CoeffReadCost = _MatrixTypeNested::CoeffReadCost, + Flags = (unsigned int)_MatrixTypeNested::Flags & (RowMajorBit | MaskLvalueBit | DirectAccessBit) & ~RowMajorBit, // FIXME DirectAccessBit should not be handled by expressions MatrixTypeOuterStride = outer_stride_at_compile_time::ret, InnerStrideAtCompileTime = MatrixTypeOuterStride == Dynamic ? Dynamic : MatrixTypeOuterStride+1, OuterStrideAtCompileTime = 0 @@ -70,20 +69,28 @@ template class Diagonal typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Diagonal) - inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) {} + EIGEN_DEVICE_FUNC + explicit inline Diagonal(MatrixType& matrix, Index a_index = DiagIndex) : m_matrix(matrix), m_index(a_index) {} EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Diagonal) + EIGEN_DEVICE_FUNC inline Index rows() const - { return m_index.value()<0 ? (std::min)(m_matrix.cols(),m_matrix.rows()+m_index.value()) : (std::min)(m_matrix.rows(),m_matrix.cols()-m_index.value()); } + { + return m_index.value()<0 ? numext::mini(m_matrix.cols(),m_matrix.rows()+m_index.value()) + : numext::mini(m_matrix.rows(),m_matrix.cols()-m_index.value()); + } + EIGEN_DEVICE_FUNC inline Index cols() const { return 1; } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_matrix.outerStride() + 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return 0; @@ -95,62 +102,75 @@ template class Diagonal const Scalar >::type ScalarWithConstIfNotLvalue; - inline ScalarWithConstIfNotLvalue* data() { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } - inline const Scalar* data() const { return &(m_matrix.const_cast_derived().coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC + inline ScalarWithConstIfNotLvalue* data() { return &(m_matrix.coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC + inline const Scalar* data() const { return &(m_matrix.coeffRef(rowOffset(), colOffset())); } + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index) { EIGEN_STATIC_ASSERT_LVALUE(MatrixType) - return m_matrix.const_cast_derived().coeffRef(row+rowOffset(), row+colOffset()); + return m_matrix.coeffRef(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index row, Index) const { - return m_matrix.const_cast_derived().coeffRef(row+rowOffset(), row+colOffset()); + return m_matrix.coeffRef(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline CoeffReturnType coeff(Index row, Index) const { return m_matrix.coeff(row+rowOffset(), row+colOffset()); } + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index idx) { EIGEN_STATIC_ASSERT_LVALUE(MatrixType) - return m_matrix.const_cast_derived().coeffRef(idx+rowOffset(), idx+colOffset()); + return m_matrix.coeffRef(idx+rowOffset(), idx+colOffset()); } + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index idx) const { - return m_matrix.const_cast_derived().coeffRef(idx+rowOffset(), idx+colOffset()); + return m_matrix.coeffRef(idx+rowOffset(), idx+colOffset()); } + EIGEN_DEVICE_FUNC inline CoeffReturnType coeff(Index idx) const { return m_matrix.coeff(idx+rowOffset(), idx+colOffset()); } - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC + inline const typename internal::remove_all::type& nestedExpression() const { return m_matrix; } - int index() const + EIGEN_DEVICE_FUNC + inline Index index() const { return m_index.value(); } protected: - typename MatrixType::Nested m_matrix; + typename internal::ref_selector::non_const_type m_matrix; const internal::variable_if_dynamicindex m_index; private: // some compilers may fail to optimize std::max etc in case of compile-time constants... + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index absDiagIndex() const { return m_index.value()>0 ? m_index.value() : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowOffset() const { return m_index.value()>0 ? 0 : -m_index.value(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colOffset() const { return m_index.value()>0 ? m_index.value() : 0; } - // triger a compile time error is someone try to call packet + // trigger a compile-time error if someone try to call packet template typename MatrixType::PacketReturnType packet(Index) const; template typename MatrixType::PacketReturnType packet(Index,Index) const; }; @@ -167,7 +187,7 @@ template inline typename MatrixBase::DiagonalReturnType MatrixBase::diagonal() { - return derived(); + return DiagonalReturnType(derived()); } /** This is the const version of diagonal(). */ @@ -216,20 +236,20 @@ MatrixBase::diagonal(Index index) const * * \sa MatrixBase::diagonal(), class Diagonal */ template -template -inline typename MatrixBase::template DiagonalIndexReturnType::Type +template +inline typename MatrixBase::template DiagonalIndexReturnType::Type MatrixBase::diagonal() { - return derived(); + return typename DiagonalIndexReturnType::Type(derived()); } /** This is the const version of diagonal(). */ template -template -inline typename MatrixBase::template ConstDiagonalIndexReturnType::Type +template +inline typename MatrixBase::template ConstDiagonalIndexReturnType::Type MatrixBase::diagonal() const { - return derived(); + return typename ConstDiagonalIndexReturnType::Type(derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h index 53c757bef..ecfdce8ef 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalMatrix.h @@ -22,7 +22,7 @@ class DiagonalBase : public EigenBase typedef typename DiagonalVectorType::Scalar Scalar; typedef typename DiagonalVectorType::RealScalar RealScalar; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; enum { RowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, @@ -30,79 +30,61 @@ class DiagonalBase : public EigenBase MaxRowsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, MaxColsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, IsVectorAtCompileTime = 0, - Flags = 0 + Flags = NoPreferredStorageOrderBit }; typedef Matrix DenseMatrixType; typedef DenseMatrixType DenseType; typedef DiagonalMatrix PlainObject; + EIGEN_DEVICE_FUNC inline const Derived& derived() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC inline Derived& derived() { return *static_cast(this); } + EIGEN_DEVICE_FUNC DenseMatrixType toDenseMatrix() const { return derived(); } - template - void evalTo(MatrixBase &other) const; - template - inline void addTo(MatrixBase &other) const - { other.diagonal() += diagonal(); } - template - inline void subTo(MatrixBase &other) const - { other.diagonal() -= diagonal(); } - + + EIGEN_DEVICE_FUNC inline const DiagonalVectorType& diagonal() const { return derived().diagonal(); } + EIGEN_DEVICE_FUNC inline DiagonalVectorType& diagonal() { return derived().diagonal(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return diagonal().size(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return diagonal().size(); } - /** \returns the diagonal matrix product of \c *this by the matrix \a matrix. - */ template - const DiagonalProduct + EIGEN_DEVICE_FUNC + const Product operator*(const MatrixBase &matrix) const { - return DiagonalProduct(matrix.derived(), derived()); + return Product(derived(),matrix.derived()); } - inline const DiagonalWrapper, const DiagonalVectorType> > + typedef DiagonalWrapper, const DiagonalVectorType> > InverseReturnType; + EIGEN_DEVICE_FUNC + inline const InverseReturnType inverse() const { - return diagonal().cwiseInverse(); + return InverseReturnType(diagonal().cwiseInverse()); } - inline const DiagonalWrapper, const DiagonalVectorType> > + EIGEN_DEVICE_FUNC + inline const DiagonalWrapper operator*(const Scalar& scalar) const { - return diagonal() * scalar; + return DiagonalWrapper(diagonal() * scalar); } - friend inline const DiagonalWrapper, const DiagonalVectorType> > + EIGEN_DEVICE_FUNC + friend inline const DiagonalWrapper operator*(const Scalar& scalar, const DiagonalBase& other) { - return other.diagonal() * scalar; + return DiagonalWrapper(scalar * other.diagonal()); } - - #ifdef EIGEN2_SUPPORT - template - bool isApprox(const DiagonalBase& other, typename NumTraits::Real precision = NumTraits::dummy_precision()) const - { - return diagonal().isApprox(other.diagonal(), precision); - } - template - bool isApprox(const MatrixBase& other, typename NumTraits::Real precision = NumTraits::dummy_precision()) const - { - return toDenseMatrix().isApprox(other, precision); - } - #endif }; -template -template -inline void DiagonalBase::evalTo(MatrixBase &other) const -{ - other.setZero(); - other.diagonal() = diagonal(); -} #endif /** \class DiagonalMatrix @@ -124,10 +106,9 @@ struct traits > : traits > { typedef Matrix<_Scalar,SizeAtCompileTime,1,0,MaxSizeAtCompileTime,1> DiagonalVectorType; - typedef Dense StorageKind; - typedef DenseIndex Index; + typedef DiagonalShape StorageKind; enum { - Flags = LvalueBit + Flags = LvalueBit | NoPreferredStorageOrderBit }; }; } @@ -141,7 +122,7 @@ class DiagonalMatrix typedef const DiagonalMatrix& Nested; typedef _Scalar Scalar; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; #endif protected: @@ -151,24 +132,31 @@ class DiagonalMatrix public: /** const version of diagonal(). */ + EIGEN_DEVICE_FUNC inline const DiagonalVectorType& diagonal() const { return m_diagonal; } /** \returns a reference to the stored vector of diagonal coefficients. */ + EIGEN_DEVICE_FUNC inline DiagonalVectorType& diagonal() { return m_diagonal; } /** Default constructor without initialization */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix() {} /** Constructs a diagonal matrix with given dimension */ - inline DiagonalMatrix(Index dim) : m_diagonal(dim) {} + EIGEN_DEVICE_FUNC + explicit inline DiagonalMatrix(Index dim) : m_diagonal(dim) {} /** 2D constructor. */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const Scalar& x, const Scalar& y) : m_diagonal(x,y) {} /** 3D constructor. */ + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const Scalar& x, const Scalar& y, const Scalar& z) : m_diagonal(x,y,z) {} /** Copy constructor. */ template + EIGEN_DEVICE_FUNC inline DiagonalMatrix(const DiagonalBase& other) : m_diagonal(other.diagonal()) {} #ifndef EIGEN_PARSED_BY_DOXYGEN @@ -178,11 +166,13 @@ class DiagonalMatrix /** generic constructor from expression of the diagonal coefficients */ template + EIGEN_DEVICE_FUNC explicit inline DiagonalMatrix(const MatrixBase& other) : m_diagonal(other) {} /** Copy operator. */ template + EIGEN_DEVICE_FUNC DiagonalMatrix& operator=(const DiagonalBase& other) { m_diagonal = other.diagonal(); @@ -193,6 +183,7 @@ class DiagonalMatrix /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC DiagonalMatrix& operator=(const DiagonalMatrix& other) { m_diagonal = other.diagonal(); @@ -201,14 +192,19 @@ class DiagonalMatrix #endif /** Resizes to given size. */ + EIGEN_DEVICE_FUNC inline void resize(Index size) { m_diagonal.resize(size); } /** Sets all coefficients to zero. */ + EIGEN_DEVICE_FUNC inline void setZero() { m_diagonal.setZero(); } /** Resizes and sets all coefficients to zero. */ + EIGEN_DEVICE_FUNC inline void setZero(Index size) { m_diagonal.setZero(size); } /** Sets this matrix to be the identity matrix of the current size. */ + EIGEN_DEVICE_FUNC inline void setIdentity() { m_diagonal.setOnes(); } /** Sets this matrix to be the identity matrix of the given size. */ + EIGEN_DEVICE_FUNC inline void setIdentity(Index size) { m_diagonal.setOnes(size); } }; @@ -232,14 +228,15 @@ struct traits > { typedef _DiagonalVectorType DiagonalVectorType; typedef typename DiagonalVectorType::Scalar Scalar; - typedef typename DiagonalVectorType::Index Index; - typedef typename DiagonalVectorType::StorageKind StorageKind; + typedef typename DiagonalVectorType::StorageIndex StorageIndex; + typedef DiagonalShape StorageKind; + typedef typename traits::XprKind XprKind; enum { RowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, ColsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - MaxRowsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - MaxColsAtCompileTime = DiagonalVectorType::SizeAtCompileTime, - Flags = traits::Flags & LvalueBit + MaxRowsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, + MaxColsAtCompileTime = DiagonalVectorType::MaxSizeAtCompileTime, + Flags = (traits::Flags & LvalueBit) | NoPreferredStorageOrderBit }; }; } @@ -255,9 +252,11 @@ class DiagonalWrapper #endif /** Constructor from expression of diagonal coefficients to wrap. */ - inline DiagonalWrapper(DiagonalVectorType& a_diagonal) : m_diagonal(a_diagonal) {} + EIGEN_DEVICE_FUNC + explicit inline DiagonalWrapper(DiagonalVectorType& a_diagonal) : m_diagonal(a_diagonal) {} /** \returns a const reference to the wrapped expression of diagonal coefficients. */ + EIGEN_DEVICE_FUNC const DiagonalVectorType& diagonal() const { return m_diagonal; } protected: @@ -277,7 +276,7 @@ template inline const DiagonalWrapper MatrixBase::asDiagonal() const { - return derived(); + return DiagonalWrapper(derived()); } /** \returns true if *this is approximately equal to a diagonal matrix, @@ -291,12 +290,11 @@ MatrixBase::asDiagonal() const template bool MatrixBase::isDiagonal(const RealScalar& prec) const { - using std::abs; if(cols() != rows()) return false; RealScalar maxAbsOnDiagonal = static_cast(-1); for(Index j = 0; j < cols(); ++j) { - RealScalar absOnDiagonal = abs(coeff(j,j)); + RealScalar absOnDiagonal = numext::abs(coeff(j,j)); if(absOnDiagonal > maxAbsOnDiagonal) maxAbsOnDiagonal = absOnDiagonal; } for(Index j = 0; j < cols(); ++j) @@ -308,6 +306,38 @@ bool MatrixBase::isDiagonal(const RealScalar& prec) const return true; } +namespace internal { + +template<> struct storage_kind_to_shape { typedef DiagonalShape Shape; }; + +struct Diagonal2Dense {}; + +template<> struct AssignmentKind { typedef Diagonal2Dense Kind; }; + +// Diagonal matrix to Dense assignment +template< typename DstXprType, typename SrcXprType, typename Functor> +struct Assignment +{ + static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &/*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + + dst.setZero(); + dst.diagonal() = src.diagonal(); + } + + static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &/*func*/) + { dst.diagonal() += src.diagonal(); } + + static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &/*func*/) + { dst.diagonal() -= src.diagonal(); } +}; + +} // namespace internal + } // end namespace Eigen #endif // EIGEN_DIAGONALMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h index cc6b536e1..d372b938f 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/DiagonalProduct.h @@ -13,117 +13,14 @@ namespace Eigen { -namespace internal { -template -struct traits > - : traits -{ - typedef typename scalar_product_traits::ReturnType Scalar; - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime, - MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, - MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, - - _StorageOrder = MatrixType::Flags & RowMajorBit ? RowMajor : ColMajor, - _ScalarAccessOnDiag = !((int(_StorageOrder) == ColMajor && int(ProductOrder) == OnTheLeft) - ||(int(_StorageOrder) == RowMajor && int(ProductOrder) == OnTheRight)), - _SameTypes = is_same::value, - // FIXME currently we need same types, but in the future the next rule should be the one - //_Vectorizable = bool(int(MatrixType::Flags)&PacketAccessBit) && ((!_PacketOnDiag) || (_SameTypes && bool(int(DiagonalType::DiagonalVectorType::Flags)&PacketAccessBit))), - _Vectorizable = bool(int(MatrixType::Flags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagonalType::DiagonalVectorType::Flags)&PacketAccessBit))), - _LinearAccessMask = (RowsAtCompileTime==1 || ColsAtCompileTime==1) ? LinearAccessBit : 0, - - Flags = ((HereditaryBits|_LinearAccessMask|AlignedBit) & (unsigned int)(MatrixType::Flags)) | (_Vectorizable ? PacketAccessBit : 0),//(int(MatrixType::Flags)&int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit), - Cost0 = EIGEN_ADD_COST(NumTraits::MulCost, MatrixType::CoeffReadCost), - CoeffReadCost = EIGEN_ADD_COST(Cost0,DiagonalType::DiagonalVectorType::CoeffReadCost) - }; -}; -} - -template -class DiagonalProduct : internal::no_assignment_operator, - public MatrixBase > -{ - public: - - typedef MatrixBase Base; - EIGEN_DENSE_PUBLIC_INTERFACE(DiagonalProduct) - - inline DiagonalProduct(const MatrixType& matrix, const DiagonalType& diagonal) - : m_matrix(matrix), m_diagonal(diagonal) - { - eigen_assert(diagonal.diagonal().size() == (ProductOrder == OnTheLeft ? matrix.rows() : matrix.cols())); - } - - EIGEN_STRONG_INLINE Index rows() const { return m_matrix.rows(); } - EIGEN_STRONG_INLINE Index cols() const { return m_matrix.cols(); } - - EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const - { - return m_diagonal.diagonal().coeff(ProductOrder == OnTheLeft ? row : col) * m_matrix.coeff(row, col); - } - - EIGEN_STRONG_INLINE const Scalar coeff(Index idx) const - { - enum { - StorageOrder = int(MatrixType::Flags) & RowMajorBit ? RowMajor : ColMajor - }; - return coeff(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index row, Index col) const - { - enum { - StorageOrder = Flags & RowMajorBit ? RowMajor : ColMajor - }; - const Index indexInDiagonalVector = ProductOrder == OnTheLeft ? row : col; - return packet_impl(row,col,indexInDiagonalVector,typename internal::conditional< - ((int(StorageOrder) == RowMajor && int(ProductOrder) == OnTheLeft) - ||(int(StorageOrder) == ColMajor && int(ProductOrder) == OnTheRight)), internal::true_type, internal::false_type>::type()); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet(Index idx) const - { - enum { - StorageOrder = int(MatrixType::Flags) & RowMajorBit ? RowMajor : ColMajor - }; - return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); - } - - protected: - template - EIGEN_STRONG_INLINE PacketScalar packet_impl(Index row, Index col, Index id, internal::true_type) const - { - return internal::pmul(m_matrix.template packet(row, col), - internal::pset1(m_diagonal.diagonal().coeff(id))); - } - - template - EIGEN_STRONG_INLINE PacketScalar packet_impl(Index row, Index col, Index id, internal::false_type) const - { - enum { - InnerSize = (MatrixType::Flags & RowMajorBit) ? MatrixType::ColsAtCompileTime : MatrixType::RowsAtCompileTime, - DiagonalVectorPacketLoadMode = (LoadMode == Aligned && (((InnerSize%16) == 0) || (int(DiagonalType::DiagonalVectorType::Flags)&AlignedBit)==AlignedBit) ? Aligned : Unaligned) - }; - return internal::pmul(m_matrix.template packet(row, col), - m_diagonal.diagonal().template packet(id)); - } - - typename MatrixType::Nested m_matrix; - typename DiagonalType::Nested m_diagonal; -}; - /** \returns the diagonal matrix product of \c *this by the diagonal matrix \a diagonal. */ template template -inline const DiagonalProduct +inline const Product MatrixBase::operator*(const DiagonalBase &a_diagonal) const { - return DiagonalProduct(derived(), a_diagonal.derived()); + return Product(derived(),a_diagonal.derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h index 23aab831b..06ef18b8b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Dot.h @@ -28,26 +28,31 @@ template struct dot_nocheck { - typedef typename scalar_product_traits::Scalar,typename traits::Scalar>::ReturnType ResScalar; + typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; + typedef typename conj_prod::result_type ResScalar; + EIGEN_DEVICE_FUNC static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) { - return a.template binaryExpr::Scalar,typename traits::Scalar> >(b).sum(); + return a.template binaryExpr(b).sum(); } }; template struct dot_nocheck { - typedef typename scalar_product_traits::Scalar,typename traits::Scalar>::ReturnType ResScalar; + typedef scalar_conj_product_op::Scalar,typename traits::Scalar> conj_prod; + typedef typename conj_prod::result_type ResScalar; + EIGEN_DEVICE_FUNC static inline ResScalar run(const MatrixBase& a, const MatrixBase& b) { - return a.transpose().template binaryExpr::Scalar,typename traits::Scalar> >(b).sum(); + return a.transpose().template binaryExpr(b).sum(); } }; } // end namespace internal -/** \returns the dot product of *this with other. +/** \fn MatrixBase::dot + * \returns the dot product of *this with other. * * \only_for_vectors * @@ -59,55 +64,30 @@ struct dot_nocheck */ template template -inline typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType +EIGEN_DEVICE_FUNC +typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType MatrixBase::dot(const MatrixBase& other) const { EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived) +#if !(defined(EIGEN_NO_STATIC_ASSERT) && defined(EIGEN_NO_DEBUG)) typedef internal::scalar_conj_product_op func; EIGEN_CHECK_BINARY_COMPATIBILIY(func,Scalar,typename OtherDerived::Scalar); - +#endif + eigen_assert(size() == other.size()); return internal::dot_nocheck::run(*this, other); } -#ifdef EIGEN2_SUPPORT -/** \returns the dot product of *this with other, with the Eigen2 convention that the dot product is linear in the first variable - * (conjugating the second variable). Of course this only makes a difference in the complex case. - * - * This method is only available in EIGEN2_SUPPORT mode. - * - * \only_for_vectors - * - * \sa dot() - */ -template -template -typename internal::traits::Scalar -MatrixBase::eigen2_dot(const MatrixBase& other) const -{ - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) - EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived) - EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived) - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - eigen_assert(size() == other.size()); - - return internal::dot_nocheck::run(other,*this); -} -#endif - - //---------- implementation of L2 norm and related functions ---------- /** \returns, for vectors, the squared \em l2 norm of \c *this, and for matrices the Frobenius norm. * In both cases, it consists in the sum of the square of all the matrix entries. * For vectors, this is also equals to the dot product of \c *this with itself. * - * \sa dot(), norm() + * \sa dot(), norm(), lpNorm() */ template EIGEN_STRONG_INLINE typename NumTraits::Scalar>::Real MatrixBase::squaredNorm() const @@ -119,16 +99,18 @@ EIGEN_STRONG_INLINE typename NumTraits::Scala * In both cases, it consists in the square root of the sum of the square of all the matrix entries. * For vectors, this is also equals to the square root of the dot product of \c *this with itself. * - * \sa dot(), squaredNorm() + * \sa lpNorm(), dot(), squaredNorm() */ template inline typename NumTraits::Scalar>::Real MatrixBase::norm() const { - using std::sqrt; - return sqrt(squaredNorm()); + return numext::sqrt(squaredNorm()); } -/** \returns an expression of the quotient of *this by its own norm. +/** \returns an expression of the quotient of \c *this by its own norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), + * then this function returns a copy of the input. * * \only_for_vectors * @@ -138,22 +120,77 @@ template inline const typename MatrixBase::PlainObject MatrixBase::normalized() const { - typedef typename internal::nested::type Nested; - typedef typename internal::remove_reference::type _Nested; + typedef typename internal::nested_eval::type _Nested; _Nested n(derived()); - return n / n.norm(); + RealScalar z = n.squaredNorm(); + // NOTE: after extensive benchmarking, this conditional does not impact performance, at least on recent x86 CPU + if(z>RealScalar(0)) + return n / numext::sqrt(z); + else + return n; } /** Normalizes the vector, i.e. divides it by its own norm. * * \only_for_vectors * + * \warning If the input vector is too small (i.e., this->norm()==0), then \c *this is left unchanged. + * * \sa norm(), normalized() */ template inline void MatrixBase::normalize() { - *this /= norm(); + RealScalar z = squaredNorm(); + // NOTE: after extensive benchmarking, this conditional does not impact performance, at least on recent x86 CPU + if(z>RealScalar(0)) + derived() /= numext::sqrt(z); +} + +/** \returns an expression of the quotient of \c *this by its own norm while avoiding underflow and overflow. + * + * \only_for_vectors + * + * This method is analogue to the normalized() method, but it reduces the risk of + * underflow and overflow when computing the norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), + * then this function returns a copy of the input. + * + * \sa stableNorm(), stableNormalize(), normalized() + */ +template +inline const typename MatrixBase::PlainObject +MatrixBase::stableNormalized() const +{ + typedef typename internal::nested_eval::type _Nested; + _Nested n(derived()); + RealScalar w = n.cwiseAbs().maxCoeff(); + RealScalar z = (n/w).squaredNorm(); + if(z>RealScalar(0)) + return n / (numext::sqrt(z)*w); + else + return n; +} + +/** Normalizes the vector while avoid underflow and overflow + * + * \only_for_vectors + * + * This method is analogue to the normalize() method, but it reduces the risk of + * underflow and overflow when computing the norm. + * + * \warning If the input vector is too small (i.e., this->norm()==0), then \c *this is left unchanged. + * + * \sa stableNorm(), stableNormalized(), normalize() + */ +template +inline void MatrixBase::stableNormalize() +{ + RealScalar w = cwiseAbs().maxCoeff(); + RealScalar z = (derived()/w).squaredNorm(); + if(z>RealScalar(0)) + derived() /= numext::sqrt(z)*w; } //---------- implementation of other norms ---------- @@ -164,9 +201,10 @@ template struct lpNorm_selector { typedef typename NumTraits::Scalar>::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const MatrixBase& m) { - using std::pow; + EIGEN_USING_STD_MATH(pow) return pow(m.cwiseAbs().array().pow(p).sum(), RealScalar(1)/p); } }; @@ -174,6 +212,7 @@ struct lpNorm_selector template struct lpNorm_selector { + EIGEN_DEVICE_FUNC static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.cwiseAbs().sum(); @@ -183,6 +222,7 @@ struct lpNorm_selector template struct lpNorm_selector { + EIGEN_DEVICE_FUNC static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) { return m.norm(); @@ -192,23 +232,35 @@ struct lpNorm_selector template struct lpNorm_selector { - static inline typename NumTraits::Scalar>::Real run(const MatrixBase& m) + typedef typename NumTraits::Scalar>::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const MatrixBase& m) { + if(Derived::SizeAtCompileTime==0 || (Derived::SizeAtCompileTime==Dynamic && m.size()==0)) + return RealScalar(0); return m.cwiseAbs().maxCoeff(); } }; } // end namespace internal -/** \returns the \f$ \ell^p \f$ norm of *this, that is, returns the p-th root of the sum of the p-th powers of the absolute values - * of the coefficients of *this. If \a p is the special value \a Eigen::Infinity, this function returns the \f$ \ell^\infty \f$ - * norm, that is the maximum of the absolute values of the coefficients of *this. +/** \returns the \b coefficient-wise \f$ \ell^p \f$ norm of \c *this, that is, returns the p-th root of the sum of the p-th powers of the absolute values + * of the coefficients of \c *this. If \a p is the special value \a Eigen::Infinity, this function returns the \f$ \ell^\infty \f$ + * norm, that is the maximum of the absolute values of the coefficients of \c *this. + * + * In all cases, if \c *this is empty, then the value 0 is returned. + * + * \note For matrices, this function does not compute the
operator-norm. That is, if \c *this is a matrix, then its coefficients are interpreted as a 1D vector. Nonetheless, you can easily compute the 1-norm and \f$\infty\f$-norm matrix operator norms using \link TutorialReductionsVisitorsBroadcastingReductionsNorm partial reductions \endlink. * * \sa norm() */ template template +#ifndef EIGEN_PARSED_BY_DOXYGEN inline typename NumTraits::Scalar>::Real +#else +MatrixBase::RealScalar +#endif MatrixBase::lpNorm() const { return internal::lpNorm_selector::run(*this); @@ -227,8 +279,8 @@ template bool MatrixBase::isOrthogonal (const MatrixBase& other, const RealScalar& prec) const { - typename internal::nested::type nested(derived()); - typename internal::nested::type otherNested(other.derived()); + typename internal::nested_eval::type nested(derived()); + typename internal::nested_eval::type otherNested(other.derived()); return numext::abs2(nested.dot(otherNested)) <= prec * prec * nested.squaredNorm() * otherNested.squaredNorm(); } @@ -246,13 +298,13 @@ bool MatrixBase::isOrthogonal template bool MatrixBase::isUnitary(const RealScalar& prec) const { - typename Derived::Nested nested(derived()); + typename internal::nested_eval::type self(derived()); for(Index i = 0; i < cols(); ++i) { - if(!internal::isApprox(nested.col(i).squaredNorm(), static_cast(1), prec)) + if(!internal::isApprox(self.col(i).squaredNorm(), static_cast(1), prec)) return false; for(Index j = 0; j < i; ++j) - if(!internal::isMuchSmallerThan(nested.col(i).dot(nested.col(j)), static_cast(1), prec)) + if(!internal::isMuchSmallerThan(self.col(i).dot(self.col(j)), static_cast(1), prec)) return false; } return true; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h index fadb45852..b195506a9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/EigenBase.h @@ -13,7 +13,10 @@ namespace Eigen { -/** Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). +/** \class EigenBase + * \ingroup Core_Module + * + * Common base class for all classes T such that MatrixBase has an operator=(T) and a constructor MatrixBase(T). * * In other words, an EigenBase object is an object that can be copied into a MatrixBase. * @@ -21,39 +24,57 @@ namespace Eigen { * * Notice that this class is trivial, it is only used to disambiguate overloaded functions. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template struct EigenBase { // typedef typename internal::plain_matrix_type::type PlainObject; + + /** \brief The interface type of indices + * \details To change this, \c \#define the preprocessor symbol \c EIGEN_DEFAULT_DENSE_INDEX_TYPE. + * \deprecated Since Eigen 3.3, its usage is deprecated. Use Eigen::Index instead. + * \sa StorageIndex, \ref TopicPreprocessorDirectives. + */ + typedef Eigen::Index Index; + // FIXME is it needed? typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; /** \returns a reference to the derived object */ + EIGEN_DEVICE_FUNC Derived& derived() { return *static_cast(this); } /** \returns a const reference to the derived object */ + EIGEN_DEVICE_FUNC const Derived& derived() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC inline Derived& const_cast_derived() const { return *static_cast(const_cast(this)); } + EIGEN_DEVICE_FUNC inline const Derived& const_derived() const { return *static_cast(this); } /** \returns the number of rows. \sa cols(), RowsAtCompileTime */ + EIGEN_DEVICE_FUNC inline Index rows() const { return derived().rows(); } /** \returns the number of columns. \sa rows(), ColsAtCompileTime*/ + EIGEN_DEVICE_FUNC inline Index cols() const { return derived().cols(); } /** \returns the number of coefficients, which is rows()*cols(). * \sa rows(), cols(), SizeAtCompileTime. */ + EIGEN_DEVICE_FUNC inline Index size() const { return rows() * cols(); } /** \internal Don't use it, but do the equivalent: \code dst = *this; \endcode */ - template inline void evalTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void evalTo(Dest& dst) const { derived().evalTo(dst); } /** \internal Don't use it, but do the equivalent: \code dst += *this; \endcode */ - template inline void addTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void addTo(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -63,7 +84,9 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst -= *this; \endcode */ - template inline void subTo(Dest& dst) const + template + EIGEN_DEVICE_FUNC + inline void subTo(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -73,7 +96,8 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst.applyOnTheRight(*this); \endcode */ - template inline void applyThisOnTheRight(Dest& dst) const + template + EIGEN_DEVICE_FUNC inline void applyThisOnTheRight(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -81,7 +105,8 @@ template struct EigenBase } /** \internal Don't use it, but do the equivalent: \code dst.applyOnTheLeft(*this); \endcode */ - template inline void applyThisOnTheLeft(Dest& dst) const + template + EIGEN_DEVICE_FUNC inline void applyThisOnTheLeft(Dest& dst) const { // This is the default implementation, // derived class can reimplement it in a more optimized way. @@ -104,25 +129,28 @@ template struct EigenBase */ template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator=(const EigenBase &other) { - other.derived().evalTo(derived()); + call_assignment(derived(), other.derived()); return derived(); } template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator+=(const EigenBase &other) { - other.derived().addTo(derived()); + call_assignment(derived(), other.derived(), internal::add_assign_op()); return derived(); } template template +EIGEN_DEVICE_FUNC Derived& DenseBase::operator-=(const EigenBase &other) { - other.derived().subTo(derived()); + call_assignment(derived(), other.derived(), internal::sub_assign_op()); return derived(); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h deleted file mode 100644 index 1f2955fc1..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Flagged.h +++ /dev/null @@ -1,140 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_FLAGGED_H -#define EIGEN_FLAGGED_H - -namespace Eigen { - -/** \class Flagged - * \ingroup Core_Module - * - * \brief Expression with modified flags - * - * \param ExpressionType the type of the object of which we are modifying the flags - * \param Added the flags added to the expression - * \param Removed the flags removed from the expression (has priority over Added). - * - * This class represents an expression whose flags have been modified. - * It is the return type of MatrixBase::flagged() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::flagged() - */ - -namespace internal { -template -struct traits > : traits -{ - enum { Flags = (ExpressionType::Flags | Added) & ~Removed }; -}; -} - -template class Flagged - : public MatrixBase > -{ - public: - - typedef MatrixBase Base; - - EIGEN_DENSE_PUBLIC_INTERFACE(Flagged) - typedef typename internal::conditional::ret, - ExpressionType, const ExpressionType&>::type ExpressionTypeNested; - typedef typename ExpressionType::InnerIterator InnerIterator; - - inline Flagged(const ExpressionType& matrix) : m_matrix(matrix) {} - - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } - inline Index outerStride() const { return m_matrix.outerStride(); } - inline Index innerStride() const { return m_matrix.innerStride(); } - - inline CoeffReturnType coeff(Index row, Index col) const - { - return m_matrix.coeff(row, col); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_matrix.coeff(index); - } - - inline const Scalar& coeffRef(Index row, Index col) const - { - return m_matrix.const_cast_derived().coeffRef(row, col); - } - - inline const Scalar& coeffRef(Index index) const - { - return m_matrix.const_cast_derived().coeffRef(index); - } - - inline Scalar& coeffRef(Index row, Index col) - { - return m_matrix.const_cast_derived().coeffRef(row, col); - } - - inline Scalar& coeffRef(Index index) - { - return m_matrix.const_cast_derived().coeffRef(index); - } - - template - inline const PacketScalar packet(Index row, Index col) const - { - return m_matrix.template packet(row, col); - } - - template - inline void writePacket(Index row, Index col, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(row, col, x); - } - - template - inline const PacketScalar packet(Index index) const - { - return m_matrix.template packet(index); - } - - template - inline void writePacket(Index index, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(index, x); - } - - const ExpressionType& _expression() const { return m_matrix; } - - template - typename ExpressionType::PlainObject solveTriangular(const MatrixBase& other) const; - - template - void solveTriangularInPlace(const MatrixBase& other) const; - - protected: - ExpressionTypeNested m_matrix; -}; - -/** \returns an expression of *this with added and removed flags - * - * This is mostly for internal use. - * - * \sa class Flagged - */ -template -template -inline const Flagged -DenseBase::flagged() const -{ - return derived(); -} - -} // end namespace Eigen - -#endif // EIGEN_FLAGGED_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h index 807c7a293..7b08b45e6 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ForceAlignedAccess.h @@ -39,29 +39,29 @@ template class ForceAlignedAccess typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(ForceAlignedAccess) - inline ForceAlignedAccess(const ExpressionType& matrix) : m_expression(matrix) {} + EIGEN_DEVICE_FUNC explicit inline ForceAlignedAccess(const ExpressionType& matrix) : m_expression(matrix) {} - inline Index rows() const { return m_expression.rows(); } - inline Index cols() const { return m_expression.cols(); } - inline Index outerStride() const { return m_expression.outerStride(); } - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline const CoeffReturnType coeff(Index row, Index col) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } - inline Scalar& coeffRef(Index row, Index col) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index col) { return m_expression.const_cast_derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } - inline Scalar& coeffRef(Index index) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index index) { return m_expression.const_cast_derived().coeffRef(index); } @@ -90,7 +90,7 @@ template class ForceAlignedAccess m_expression.const_cast_derived().template writePacket(index, x); } - operator const ExpressionType&() const { return m_expression; } + EIGEN_DEVICE_FUNC operator const ExpressionType&() const { return m_expression; } protected: const ExpressionType& m_expression; @@ -127,7 +127,7 @@ template inline typename internal::add_const_on_value_type,Derived&>::type>::type MatrixBase::forceAlignedAccessIf() const { - return derived(); + return derived(); // FIXME This should not work but apparently is never used } /** \returns an expression of *this with forced aligned access if \a Enable is true. @@ -138,7 +138,7 @@ template inline typename internal::conditional,Derived&>::type MatrixBase::forceAlignedAccessIf() { - return derived(); + return derived(); // FIXME This should not work but apparently is never used } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h deleted file mode 100644 index 5a1b2f28a..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Functors.h +++ /dev/null @@ -1,1029 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008-2010 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_FUNCTORS_H -#define EIGEN_FUNCTORS_H - -namespace Eigen { - -namespace internal { - -// associative functors: - -/** \internal - * \brief Template functor to compute the sum of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::operator+, class VectorwiseOp, MatrixBase::sum() - */ -template struct scalar_sum_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sum_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { return a + b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::padd(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasAdd - }; -}; - -/** \internal - * \brief Template functor to compute the product of two scalars - * - * \sa class CwiseBinaryOp, Cwise::operator*(), class VectorwiseOp, MatrixBase::redux() - */ -template struct scalar_product_op { - enum { - // TODO vectorize mixed product - Vectorizable = is_same::value && packet_traits::HasMul && packet_traits::HasMul - }; - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_EMPTY_STRUCT_CTOR(scalar_product_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a * b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmul(a,b); } - template - EIGEN_STRONG_INLINE const result_type predux(const Packet& a) const - { return internal::predux_mul(a); } -}; -template -struct functor_traits > { - enum { - Cost = (NumTraits::MulCost + NumTraits::MulCost)/2, // rough estimate! - PacketAccess = scalar_product_op::Vectorizable - }; -}; - -/** \internal - * \brief Template functor to compute the conjugate product of two scalars - * - * This is a short cut for conj(x) * y which is needed for optimization purpose; in Eigen2 support mode, this becomes x * conj(y) - */ -template struct scalar_conj_product_op { - - enum { - Conj = NumTraits::IsComplex - }; - - typedef typename scalar_product_traits::ReturnType result_type; - - EIGEN_EMPTY_STRUCT_CTOR(scalar_conj_product_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const - { return conj_helper().pmul(a,b); } - - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return conj_helper().pmul(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::MulCost, - PacketAccess = internal::is_same::value && packet_traits::HasMul - }; -}; - -/** \internal - * \brief Template functor to compute the min of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::cwiseMin, class VectorwiseOp, MatrixBase::minCoeff() - */ -template struct scalar_min_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_min_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { using std::min; return (min)(a, b); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmin(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux_min(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasMin - }; -}; - -/** \internal - * \brief Template functor to compute the max of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::cwiseMax, class VectorwiseOp, MatrixBase::maxCoeff() - */ -template struct scalar_max_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_max_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { using std::max; return (max)(a, b); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pmax(a,b); } - template - EIGEN_STRONG_INLINE const Scalar predux(const Packet& a) const - { return internal::predux_max(a); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasMax - }; -}; - -/** \internal - * \brief Template functor to compute the hypot of two scalars - * - * \sa MatrixBase::stableNorm(), class Redux - */ -template struct scalar_hypot_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_hypot_op) -// typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& _x, const Scalar& _y) const - { - using std::max; - using std::min; - using std::sqrt; - Scalar p = (max)(_x, _y); - Scalar q = (min)(_x, _y); - Scalar qp = q/p; - return p * sqrt(Scalar(1) + qp*qp); - } -}; -template -struct functor_traits > { - enum { Cost = 5 * NumTraits::MulCost, PacketAccess=0 }; -}; - -/** \internal - * \brief Template functor to compute the pow of two scalars - */ -template struct scalar_binary_pow_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_binary_pow_op) - inline Scalar operator() (const Scalar& a, const OtherScalar& b) const { return numext::pow(a, b); } -}; -template -struct functor_traits > { - enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; -}; - -// other binary functors: - -/** \internal - * \brief Template functor to compute the difference of two scalars - * - * \sa class CwiseBinaryOp, MatrixBase::operator- - */ -template struct scalar_difference_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_difference_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& b) const { return a - b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::psub(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasSub - }; -}; - -/** \internal - * \brief Template functor to compute the quotient of two scalars - * - * \sa class CwiseBinaryOp, Cwise::operator/() - */ -template struct scalar_quotient_op { - enum { - // TODO vectorize mixed product - Vectorizable = is_same::value && packet_traits::HasDiv && packet_traits::HasDiv - }; - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_EMPTY_STRUCT_CTOR(scalar_quotient_op) - EIGEN_STRONG_INLINE const result_type operator() (const LhsScalar& a, const RhsScalar& b) const { return a / b; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& b) const - { return internal::pdiv(a,b); } -}; -template -struct functor_traits > { - enum { - Cost = (NumTraits::MulCost + NumTraits::MulCost), // rough estimate! - PacketAccess = scalar_quotient_op::Vectorizable - }; -}; - - - -/** \internal - * \brief Template functor to compute the and of two booleans - * - * \sa class CwiseBinaryOp, ArrayBase::operator&& - */ -struct scalar_boolean_and_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_and_op) - EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a && b; } -}; -template<> struct functor_traits { - enum { - Cost = NumTraits::AddCost, - PacketAccess = false - }; -}; - -/** \internal - * \brief Template functor to compute the or of two booleans - * - * \sa class CwiseBinaryOp, ArrayBase::operator|| - */ -struct scalar_boolean_or_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_boolean_or_op) - EIGEN_STRONG_INLINE bool operator() (const bool& a, const bool& b) const { return a || b; } -}; -template<> struct functor_traits { - enum { - Cost = NumTraits::AddCost, - PacketAccess = false - }; -}; - -/** \internal - * \brief Template functors for comparison of two scalars - * \todo Implement packet-comparisons - */ -template struct scalar_cmp_op; - -template -struct functor_traits > { - enum { - Cost = NumTraits::AddCost, - PacketAccess = false - }; -}; - -template -struct result_of(Scalar,Scalar)> { - typedef bool type; -}; - - -template struct scalar_cmp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) - EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a==b;} -}; -template struct scalar_cmp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) - EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a struct scalar_cmp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) - EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a<=b;} -}; -template struct scalar_cmp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) - EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return !(a<=b || b<=a);} -}; -template struct scalar_cmp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cmp_op) - EIGEN_STRONG_INLINE bool operator()(const Scalar& a, const Scalar& b) const {return a!=b;} -}; - -// unary functors: - -/** \internal - * \brief Template functor to compute the opposite of a scalar - * - * \sa class CwiseUnaryOp, MatrixBase::operator- - */ -template struct scalar_opposite_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_opposite_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { return -a; } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pnegate(a); } -}; -template -struct functor_traits > -{ enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasNegate }; -}; - -/** \internal - * \brief Template functor to compute the absolute value of a scalar - * - * \sa class CwiseUnaryOp, Cwise::abs - */ -template struct scalar_abs_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_abs_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { using std::abs; return abs(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pabs(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = NumTraits::AddCost, - PacketAccess = packet_traits::HasAbs - }; -}; - -/** \internal - * \brief Template functor to compute the squared absolute value of a scalar - * - * \sa class CwiseUnaryOp, Cwise::abs2 - */ -template struct scalar_abs2_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_abs2_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE const result_type operator() (const Scalar& a) const { return numext::abs2(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pmul(a,a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasAbs2 }; }; - -/** \internal - * \brief Template functor to compute the conjugate of a complex value - * - * \sa class CwiseUnaryOp, MatrixBase::conjugate() - */ -template struct scalar_conjugate_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_conjugate_op) - EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const { using numext::conj; return conj(a); } - template - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const { return internal::pconj(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = NumTraits::IsComplex ? NumTraits::AddCost : 0, - PacketAccess = packet_traits::HasConj - }; -}; - -/** \internal - * \brief Template functor to cast a scalar to another type - * - * \sa class CwiseUnaryOp, MatrixBase::cast() - */ -template -struct scalar_cast_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cast_op) - typedef NewType result_type; - EIGEN_STRONG_INLINE const NewType operator() (const Scalar& a) const { return cast(a); } -}; -template -struct functor_traits > -{ enum { Cost = is_same::value ? 0 : NumTraits::AddCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the real part of a complex - * - * \sa class CwiseUnaryOp, MatrixBase::real() - */ -template -struct scalar_real_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_real_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return numext::real(a); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the imaginary part of a complex - * - * \sa class CwiseUnaryOp, MatrixBase::imag() - */ -template -struct scalar_imag_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type operator() (const Scalar& a) const { return numext::imag(a); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the real part of a complex as a reference - * - * \sa class CwiseUnaryOp, MatrixBase::real() - */ -template -struct scalar_real_ref_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_real_ref_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return numext::real_ref(*const_cast(&a)); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to extract the imaginary part of a complex as a reference - * - * \sa class CwiseUnaryOp, MatrixBase::imag() - */ -template -struct scalar_imag_ref_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_imag_ref_op) - typedef typename NumTraits::Real result_type; - EIGEN_STRONG_INLINE result_type& operator() (const Scalar& a) const { return numext::imag_ref(*const_cast(&a)); } -}; -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -/** \internal - * - * \brief Template functor to compute the exponential of a scalar - * - * \sa class CwiseUnaryOp, Cwise::exp() - */ -template struct scalar_exp_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_exp_op) - inline const Scalar operator() (const Scalar& a) const { using std::exp; return exp(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pexp(a); } -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasExp }; }; - -/** \internal - * - * \brief Template functor to compute the logarithm of a scalar - * - * \sa class CwiseUnaryOp, Cwise::log() - */ -template struct scalar_log_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_log_op) - inline const Scalar operator() (const Scalar& a) const { using std::log; return log(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::plog(a); } -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = packet_traits::HasLog }; }; - -/** \internal - * \brief Template functor to multiply a scalar by a fixed other one - * - * \sa class CwiseUnaryOp, MatrixBase::operator*, MatrixBase::operator/ - */ -/* NOTE why doing the pset1() in packetOp *is* an optimization ? - * indeed it seems better to declare m_other as a Packet and do the pset1() once - * in the constructor. However, in practice: - * - GCC does not like m_other as a Packet and generate a load every time it needs it - * - on the other hand GCC is able to moves the pset1() outside the loop :) - * - simpler code ;) - * (ICC and gcc 4.4 seems to perform well in both cases, the issue is visible with y = a*x + b*y) - */ -template -struct scalar_multiple_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - EIGEN_STRONG_INLINE scalar_multiple_op(const scalar_multiple_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_multiple_op(const Scalar& other) : m_other(other) { } - EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a * m_other; } - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pmul(a, pset1(m_other)); } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -template -struct scalar_multiple2_op { - typedef typename scalar_product_traits::ReturnType result_type; - EIGEN_STRONG_INLINE scalar_multiple2_op(const scalar_multiple2_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_multiple2_op(const Scalar2& other) : m_other(other) { } - EIGEN_STRONG_INLINE result_type operator() (const Scalar1& a) const { return a * m_other; } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to divide a scalar by a fixed other one - * - * This functor is used to implement the quotient of a matrix by - * a scalar where the scalar type is not necessarily a floating point type. - * - * \sa class CwiseUnaryOp, MatrixBase::operator/ - */ -template -struct scalar_quotient1_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - EIGEN_STRONG_INLINE scalar_quotient1_op(const scalar_quotient1_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_quotient1_op(const Scalar& other) : m_other(other) {} - EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a / m_other; } - EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a) const - { return internal::pdiv(a, pset1(m_other)); } - typename add_const_on_value_type::Nested>::type m_other; -}; -template -struct functor_traits > -{ enum { Cost = 2 * NumTraits::MulCost, PacketAccess = packet_traits::HasDiv }; }; - -// nullary functors - -template -struct scalar_constant_op { - typedef typename packet_traits::type Packet; - EIGEN_STRONG_INLINE scalar_constant_op(const scalar_constant_op& other) : m_other(other.m_other) { } - EIGEN_STRONG_INLINE scalar_constant_op(const Scalar& other) : m_other(other) { } - template - EIGEN_STRONG_INLINE const Scalar operator() (Index, Index = 0) const { return m_other; } - template - EIGEN_STRONG_INLINE const Packet packetOp(Index, Index = 0) const { return internal::pset1(m_other); } - const Scalar m_other; -}; -template -struct functor_traits > -// FIXME replace this packet test by a safe one -{ enum { Cost = 1, PacketAccess = packet_traits::Vectorizable, IsRepeatable = true }; }; - -template struct scalar_identity_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_identity_op) - template - EIGEN_STRONG_INLINE const Scalar operator() (Index row, Index col) const { return row==col ? Scalar(1) : Scalar(0); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false, IsRepeatable = true }; }; - -template struct linspaced_op_impl; - -// linear access for packet ops: -// 1) initialization -// base = [low, ..., low] + ([step, ..., step] * [-size, ..., 0]) -// 2) each step (where size is 1 for coeff access or PacketSize for packet access) -// base += [size*step, ..., size*step] -// -// TODO: Perhaps it's better to initialize lazily (so not in the constructor but in packetOp) -// in order to avoid the padd() in operator() ? -template -struct linspaced_op_impl -{ - typedef typename packet_traits::type Packet; - - linspaced_op_impl(const Scalar& low, const Scalar& step) : - m_low(low), m_step(step), - m_packetStep(pset1(packet_traits::size*step)), - m_base(padd(pset1(low), pmul(pset1(step),plset(-packet_traits::size)))) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const - { - m_base = padd(m_base, pset1(m_step)); - return m_low+Scalar(i)*m_step; - } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index) const { return m_base = padd(m_base,m_packetStep); } - - const Scalar m_low; - const Scalar m_step; - const Packet m_packetStep; - mutable Packet m_base; -}; - -// random access for packet ops: -// 1) each step -// [low, ..., low] + ( [step, ..., step] * ( [i, ..., i] + [0, ..., size] ) ) -template -struct linspaced_op_impl -{ - typedef typename packet_traits::type Packet; - - linspaced_op_impl(const Scalar& low, const Scalar& step) : - m_low(low), m_step(step), - m_lowPacket(pset1(m_low)), m_stepPacket(pset1(m_step)), m_interPacket(plset(0)) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return m_low+i*m_step; } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index i) const - { return internal::padd(m_lowPacket, pmul(m_stepPacket, padd(pset1(Scalar(i)),m_interPacket))); } - - const Scalar m_low; - const Scalar m_step; - const Packet m_lowPacket; - const Packet m_stepPacket; - const Packet m_interPacket; -}; - -// ----- Linspace functor ---------------------------------------------------------------- - -// Forward declaration (we default to random access which does not really give -// us a speed gain when using packet access but it allows to use the functor in -// nested expressions). -template struct linspaced_op; -template struct functor_traits< linspaced_op > -{ enum { Cost = 1, PacketAccess = packet_traits::HasSetLinear, IsRepeatable = true }; }; -template struct linspaced_op -{ - typedef typename packet_traits::type Packet; - linspaced_op(const Scalar& low, const Scalar& high, DenseIndex num_steps) : impl((num_steps==1 ? high : low), (num_steps==1 ? Scalar() : (high-low)/Scalar(num_steps-1))) {} - - template - EIGEN_STRONG_INLINE const Scalar operator() (Index i) const { return impl(i); } - - // We need this function when assigning e.g. a RowVectorXd to a MatrixXd since - // there row==0 and col is used for the actual iteration. - template - EIGEN_STRONG_INLINE const Scalar operator() (Index row, Index col) const - { - eigen_assert(col==0 || row==0); - return impl(col + row); - } - - template - EIGEN_STRONG_INLINE const Packet packetOp(Index i) const { return impl.packetOp(i); } - - // We need this function when assigning e.g. a RowVectorXd to a MatrixXd since - // there row==0 and col is used for the actual iteration. - template - EIGEN_STRONG_INLINE const Packet packetOp(Index row, Index col) const - { - eigen_assert(col==0 || row==0); - return impl.packetOp(col + row); - } - - // This proxy object handles the actual required temporaries, the different - // implementations (random vs. sequential access) as well as the - // correct piping to size 2/4 packet operations. - const linspaced_op_impl impl; -}; - -// all functors allow linear access, except scalar_identity_op. So we fix here a quick meta -// to indicate whether a functor allows linear access, just always answering 'yes' except for -// scalar_identity_op. -// FIXME move this to functor_traits adding a functor_default -template struct functor_has_linear_access { enum { ret = 1 }; }; -template struct functor_has_linear_access > { enum { ret = 0 }; }; - -// In Eigen, any binary op (Product, CwiseBinaryOp) require the Lhs and Rhs to have the same scalar type, except for multiplication -// where the mixing of different types is handled by scalar_product_traits -// In particular, real * complex is allowed. -// FIXME move this to functor_traits adding a functor_default -template struct functor_is_product_like { enum { ret = 0 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; -template struct functor_is_product_like > { enum { ret = 1 }; }; - - -/** \internal - * \brief Template functor to add a scalar to a fixed other one - * \sa class CwiseUnaryOp, Array::operator+ - */ -/* If you wonder why doing the pset1() in packetOp() is an optimization check scalar_multiple_op */ -template -struct scalar_add_op { - typedef typename packet_traits::type Packet; - // FIXME default copy constructors seems bugged with std::complex<> - inline scalar_add_op(const scalar_add_op& other) : m_other(other.m_other) { } - inline scalar_add_op(const Scalar& other) : m_other(other) { } - inline Scalar operator() (const Scalar& a) const { return a + m_other; } - inline const Packet packetOp(const Packet& a) const - { return internal::padd(a, pset1(m_other)); } - const Scalar m_other; -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = packet_traits::HasAdd }; }; - -/** \internal - * \brief Template functor to compute the square root of a scalar - * \sa class CwiseUnaryOp, Cwise::sqrt() - */ -template struct scalar_sqrt_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sqrt_op) - inline const Scalar operator() (const Scalar& a) const { using std::sqrt; return sqrt(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::psqrt(a); } -}; -template -struct functor_traits > -{ enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasSqrt - }; -}; - -/** \internal - * \brief Template functor to compute the cosine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::cos() - */ -template struct scalar_cos_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cos_op) - inline Scalar operator() (const Scalar& a) const { using std::cos; return cos(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pcos(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasCos - }; -}; - -/** \internal - * \brief Template functor to compute the sine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::sin() - */ -template struct scalar_sin_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_sin_op) - inline const Scalar operator() (const Scalar& a) const { using std::sin; return sin(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::psin(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasSin - }; -}; - - -/** \internal - * \brief Template functor to compute the tan of a scalar - * \sa class CwiseUnaryOp, ArrayBase::tan() - */ -template struct scalar_tan_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_tan_op) - inline const Scalar operator() (const Scalar& a) const { using std::tan; return tan(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::ptan(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasTan - }; -}; - -/** \internal - * \brief Template functor to compute the arc cosine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::acos() - */ -template struct scalar_acos_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_acos_op) - inline const Scalar operator() (const Scalar& a) const { using std::acos; return acos(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pacos(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasACos - }; -}; - -/** \internal - * \brief Template functor to compute the arc sine of a scalar - * \sa class CwiseUnaryOp, ArrayBase::asin() - */ -template struct scalar_asin_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_asin_op) - inline const Scalar operator() (const Scalar& a) const { using std::asin; return asin(a); } - typedef typename packet_traits::type Packet; - inline Packet packetOp(const Packet& a) const { return internal::pasin(a); } -}; -template -struct functor_traits > -{ - enum { - Cost = 5 * NumTraits::MulCost, - PacketAccess = packet_traits::HasASin - }; -}; - -/** \internal - * \brief Template functor to raise a scalar to a power - * \sa class CwiseUnaryOp, Cwise::pow - */ -template -struct scalar_pow_op { - // FIXME default copy constructors seems bugged with std::complex<> - inline scalar_pow_op(const scalar_pow_op& other) : m_exponent(other.m_exponent) { } - inline scalar_pow_op(const Scalar& exponent) : m_exponent(exponent) {} - inline Scalar operator() (const Scalar& a) const { return numext::pow(a, m_exponent); } - const Scalar m_exponent; -}; -template -struct functor_traits > -{ enum { Cost = 5 * NumTraits::MulCost, PacketAccess = false }; }; - -/** \internal - * \brief Template functor to compute the quotient between a scalar and array entries. - * \sa class CwiseUnaryOp, Cwise::inverse() - */ -template -struct scalar_inverse_mult_op { - scalar_inverse_mult_op(const Scalar& other) : m_other(other) {} - inline Scalar operator() (const Scalar& a) const { return m_other / a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pdiv(pset1(m_other),a); } - Scalar m_other; -}; - -/** \internal - * \brief Template functor to compute the inverse of a scalar - * \sa class CwiseUnaryOp, Cwise::inverse() - */ -template -struct scalar_inverse_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_inverse_op) - inline Scalar operator() (const Scalar& a) const { return Scalar(1)/a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pdiv(pset1(Scalar(1)),a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasDiv }; }; - -/** \internal - * \brief Template functor to compute the square of a scalar - * \sa class CwiseUnaryOp, Cwise::square() - */ -template -struct scalar_square_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_square_op) - inline Scalar operator() (const Scalar& a) const { return a*a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pmul(a,a); } -}; -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -/** \internal - * \brief Template functor to compute the cube of a scalar - * \sa class CwiseUnaryOp, Cwise::cube() - */ -template -struct scalar_cube_op { - EIGEN_EMPTY_STRUCT_CTOR(scalar_cube_op) - inline Scalar operator() (const Scalar& a) const { return a*a*a; } - template - inline const Packet packetOp(const Packet& a) const - { return internal::pmul(a,pmul(a,a)); } -}; -template -struct functor_traits > -{ enum { Cost = 2*NumTraits::MulCost, PacketAccess = packet_traits::HasMul }; }; - -// default functor traits for STL functors: - -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::MulCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = NumTraits::AddCost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1, PacketAccess = false }; }; - -#if(__cplusplus < 201103L) -// std::binder* are deprecated since c++11 and will be removed in c++17 -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost, PacketAccess = false }; }; -#endif - -template -struct functor_traits > -{ enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 1 + functor_traits::Cost, PacketAccess = false }; }; - -#ifdef EIGEN_STDEXT_SUPPORT - -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > > -{ enum { Cost = 0, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost + functor_traits::Cost, PacketAccess = false }; }; - -template -struct functor_traits > -{ enum { Cost = functor_traits::Cost + functor_traits::Cost + functor_traits::Cost, PacketAccess = false }; }; - -#endif // EIGEN_STDEXT_SUPPORT - -// allow to add new functors and specializations of functor_traits from outside Eigen. -// this macro is really needed because functor_traits must be specialized after it is declared but before it is used... -#ifdef EIGEN_FUNCTORS_PLUGIN -#include EIGEN_FUNCTORS_PLUGIN -#endif - -} // end namespace internal - -} // end namespace Eigen - -#endif // EIGEN_FUNCTORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h index fe63bd298..3e403a09d 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Fuzzy.h @@ -19,18 +19,19 @@ namespace internal template::IsInteger> struct isApprox_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar& prec) { - using std::min; - typename internal::nested::type nested(x); - typename internal::nested::type otherNested(y); - return (nested - otherNested).cwiseAbs2().sum() <= prec * prec * (min)(nested.cwiseAbs2().sum(), otherNested.cwiseAbs2().sum()); + typename internal::nested_eval::type nested(x); + typename internal::nested_eval::type otherNested(y); + return (nested - otherNested).cwiseAbs2().sum() <= prec * prec * numext::mini(nested.cwiseAbs2().sum(), otherNested.cwiseAbs2().sum()); } }; template struct isApprox_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar&) { return x.matrix() == y.matrix(); @@ -40,6 +41,7 @@ struct isApprox_selector template::IsInteger> struct isMuchSmallerThan_object_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived& y, const typename Derived::RealScalar& prec) { return x.cwiseAbs2().sum() <= numext::abs2(prec) * y.cwiseAbs2().sum(); @@ -49,6 +51,7 @@ struct isMuchSmallerThan_object_selector template struct isMuchSmallerThan_object_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const OtherDerived&, const typename Derived::RealScalar&) { return x.matrix() == Derived::Zero(x.rows(), x.cols()).matrix(); @@ -58,6 +61,7 @@ struct isMuchSmallerThan_object_selector template::IsInteger> struct isMuchSmallerThan_scalar_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const typename Derived::RealScalar& y, const typename Derived::RealScalar& prec) { return x.cwiseAbs2().sum() <= numext::abs2(prec * y); @@ -67,6 +71,7 @@ struct isMuchSmallerThan_scalar_selector template struct isMuchSmallerThan_scalar_selector { + EIGEN_DEVICE_FUNC static bool run(const Derived& x, const typename Derived::RealScalar&, const typename Derived::RealScalar&) { return x.matrix() == Derived::Zero(x.rows(), x.cols()).matrix(); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h index 5744eb71e..0f16cd8e3 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GeneralProduct.h @@ -11,29 +11,7 @@ #ifndef EIGEN_GENERAL_PRODUCT_H #define EIGEN_GENERAL_PRODUCT_H -namespace Eigen { - -/** \class GeneralProduct - * \ingroup Core_Module - * - * \brief Expression of the product of two general matrices or vectors - * - * \param LhsNested the type used to store the left-hand side - * \param RhsNested the type used to store the right-hand side - * \param ProductMode the type of the product - * - * This class represents an expression of the product of two general matrices. - * We call a general matrix, a dense matrix with full storage. For instance, - * This excludes triangular, selfadjoint, and sparse matrices. - * It is the return type of the operator* between general matrices. Its template - * arguments are determined automatically by ProductReturnType. Therefore, - * GeneralProduct should never be used direclty. To determine the result type of a - * function which involves a matrix product, use ProductReturnType::Type. - * - * \sa ProductReturnType, MatrixBase::operator*(const MatrixBase&) - */ -template::value> -class GeneralProduct; +namespace Eigen { enum { Large = 2, @@ -47,7 +25,8 @@ template struct product_type_selector; template struct product_size_category { enum { is_large = MaxSize == Dynamic || - Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD, + Size >= EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD || + (Size==Dynamic && MaxSize>=EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD), value = is_large ? Large : Size == 1 ? 1 : Small @@ -59,15 +38,14 @@ template struct product_type typedef typename remove_all::type _Lhs; typedef typename remove_all::type _Rhs; enum { - MaxRows = _Lhs::MaxRowsAtCompileTime, - Rows = _Lhs::RowsAtCompileTime, - MaxCols = _Rhs::MaxColsAtCompileTime, - Cols = _Rhs::ColsAtCompileTime, - MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::MaxColsAtCompileTime, - _Rhs::MaxRowsAtCompileTime), - Depth = EIGEN_SIZE_MIN_PREFER_FIXED(_Lhs::ColsAtCompileTime, - _Rhs::RowsAtCompileTime), - LargeThreshold = EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD + MaxRows = traits<_Lhs>::MaxRowsAtCompileTime, + Rows = traits<_Lhs>::RowsAtCompileTime, + MaxCols = traits<_Rhs>::MaxColsAtCompileTime, + Cols = traits<_Rhs>::ColsAtCompileTime, + MaxDepth = EIGEN_SIZE_MIN_PREFER_FIXED(traits<_Lhs>::MaxColsAtCompileTime, + traits<_Rhs>::MaxRowsAtCompileTime), + Depth = EIGEN_SIZE_MIN_PREFER_FIXED(traits<_Lhs>::ColsAtCompileTime, + traits<_Rhs>::RowsAtCompileTime) }; // the splitting into different lines of code here, introducing the _select enums and the typedef below, @@ -82,7 +60,8 @@ private: public: enum { - value = selector::ret + value = selector::ret, + ret = selector::ret }; #ifdef EIGEN_DEBUG_PRODUCT static void debug() @@ -98,12 +77,13 @@ public: #endif }; - /* The following allows to select the kind of product at compile time * based on the three dimensions of the product. * This is a compile time mapping from {1,Small,Large}^3 -> {product types} */ // FIXME I'm not sure the current mapping is the ideal one. template struct product_type_selector { enum { ret = OuterProduct }; }; +template struct product_type_selector { enum { ret = LazyCoeffBasedProductMode }; }; +template struct product_type_selector<1, N, 1> { enum { ret = LazyCoeffBasedProductMode }; }; template struct product_type_selector<1, 1, Depth> { enum { ret = InnerProduct }; }; template<> struct product_type_selector<1, 1, 1> { enum { ret = InnerProduct }; }; template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; @@ -122,60 +102,12 @@ template<> struct product_type_selector { enum template<> struct product_type_selector { enum { ret = GemmProduct }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; -template<> struct product_type_selector { enum { ret = GemmProduct }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; +template<> struct product_type_selector { enum { ret = CoeffBasedProductMode }; }; template<> struct product_type_selector { enum { ret = GemmProduct }; }; } // end namespace internal -/** \class ProductReturnType - * \ingroup Core_Module - * - * \brief Helper class to get the correct and optimized returned type of operator* - * - * \param Lhs the type of the left-hand side - * \param Rhs the type of the right-hand side - * \param ProductMode the type of the product (determined automatically by internal::product_mode) - * - * This class defines the typename Type representing the optimized product expression - * between two matrix expressions. In practice, using ProductReturnType::Type - * is the recommended way to define the result type of a function returning an expression - * which involve a matrix product. The class Product should never be - * used directly. - * - * \sa class Product, MatrixBase::operator*(const MatrixBase&) - */ -template -struct ProductReturnType -{ - // TODO use the nested type to reduce instanciations ???? -// typedef typename internal::nested::type LhsNested; -// typedef typename internal::nested::type RhsNested; - - typedef GeneralProduct Type; -}; - -template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -template -struct ProductReturnType -{ - typedef typename internal::nested::type >::type LhsNested; - typedef typename internal::nested::type >::type RhsNested; - typedef CoeffBasedProduct Type; -}; - -// this is a workaround for sun CC -template -struct LazyProductReturnType : public ProductReturnType -{}; - /*********************************************************************** * Implementation of Inner Vector Vector Product ***********************************************************************/ @@ -187,114 +119,10 @@ struct LazyProductReturnType : public ProductReturnType with: operator=(Scalar x); -namespace internal { - -template -struct traits > - : traits::ReturnType,1,1> > -{}; - -} - -template -class GeneralProduct - : internal::no_assignment_operator, - public Matrix::ReturnType,1,1> -{ - typedef Matrix::ReturnType,1,1> Base; - public: - GeneralProduct(const Lhs& lhs, const Rhs& rhs) - { - Base::coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); - } - - /** Convertion to scalar */ - operator const typename Base::Scalar() const { - return Base::coeff(0,0); - } -}; - /*********************************************************************** * Implementation of Outer Vector Vector Product ***********************************************************************/ -namespace internal { - -// Column major -template -EIGEN_DONT_INLINE void outer_product_selector_run(const ProductType& prod, Dest& dest, const Func& func, const false_type&) -{ - typedef typename Dest::Index Index; - // FIXME make sure lhs is sequentially stored - // FIXME not very good if rhs is real and lhs complex while alpha is real too - const Index cols = dest.cols(); - for (Index j=0; j -EIGEN_DONT_INLINE void outer_product_selector_run(const ProductType& prod, Dest& dest, const Func& func, const true_type&) { - typedef typename Dest::Index Index; - // FIXME make sure rhs is sequentially stored - // FIXME not very good if lhs is real and rhs complex while alpha is real too - const Index rows = dest.rows(); - for (Index i=0; i -struct traits > - : traits, Lhs, Rhs> > -{}; - -} - -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> -{ - template struct is_row_major : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; - - public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - GeneralProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs) - { - } - - struct set { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; - struct add { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; - struct sub { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; - struct adds { - Scalar m_scale; - adds(const Scalar& s) : m_scale(s) {} - template void operator()(const Dst& dst, const Src& src) const { - dst.const_cast_derived() += m_scale * src; - } - }; - - template - inline void evalTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, set(), is_row_major()); - } - - template - inline void addTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, add(), is_row_major()); - } - - template - inline void subTo(Dest& dest) const { - internal::outer_product_selector_run(*this, dest, sub(), is_row_major()); - } - - template void scaleAndAddTo(Dest& dest, const Scalar& alpha) const - { - internal::outer_product_selector_run(*this, dest, adds(alpha), is_row_major()); - } -}; - /*********************************************************************** * Implementation of General Matrix Vector Product ***********************************************************************/ @@ -308,60 +136,13 @@ class GeneralProduct */ namespace internal { -template -struct traits > - : traits, Lhs, Rhs> > -{}; - template -struct gemv_selector; +struct gemv_dense_selector; } // end namespace internal -template -class GeneralProduct - : public ProductBase, Lhs, Rhs> -{ - public: - EIGEN_PRODUCT_PUBLIC_INTERFACE(GeneralProduct) - - typedef typename Lhs::Scalar LhsScalar; - typedef typename Rhs::Scalar RhsScalar; - - GeneralProduct(const Lhs& a_lhs, const Rhs& a_rhs) : Base(a_lhs,a_rhs) - { -// EIGEN_STATIC_ASSERT((internal::is_same::value), -// YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - } - - enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; - typedef typename internal::conditional::type MatrixType; - - template void scaleAndAddTo(Dest& dst, const Scalar& alpha) const - { - eigen_assert(m_lhs.rows() == dst.rows() && m_rhs.cols() == dst.cols()); - internal::gemv_selector::HasUsableDirectAccess)>::run(*this, dst, alpha); - } -}; - namespace internal { -// The vector is on the left => transposition -template -struct gemv_selector -{ - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) - { - Transpose destT(dest); - enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; - gemv_selector - ::run(GeneralProduct,Transpose, GemvProduct> - (prod.rhs().transpose(), prod.lhs().transpose()), destT, alpha); - } -}; - template struct gemv_static_vector_if; template @@ -379,46 +160,61 @@ struct gemv_static_vector_if template struct gemv_static_vector_if { - #if EIGEN_ALIGN_STATICALLY - internal::plain_array m_data; - EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } - #else - // Some architectures cannot align on the stack, - // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. enum { ForceAlignment = internal::packet_traits::Vectorizable, PacketSize = internal::packet_traits::size }; - internal::plain_array m_data; + #if EIGEN_MAX_STATIC_ALIGN_BYTES!=0 + internal::plain_array m_data; + EIGEN_STRONG_INLINE Scalar* data() { return m_data.array; } + #else + // Some architectures cannot align on the stack, + // => let's manually enforce alignment by allocating more data and return the address of the first aligned element. + internal::plain_array m_data; EIGEN_STRONG_INLINE Scalar* data() { return ForceAlignment - ? reinterpret_cast((reinterpret_cast(m_data.array) & ~(size_t(15))) + 16) + ? reinterpret_cast((internal::UIntPtr(m_data.array) & ~(std::size_t(EIGEN_MAX_ALIGN_BYTES-1))) + EIGEN_MAX_ALIGN_BYTES) : m_data.array; } #endif }; -template<> struct gemv_selector +// The vector is on the left => transposition +template +struct gemv_dense_selector { - template - static inline void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename ProductType::Index Index; - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::RealScalar RealScalar; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; - typedef Map, Aligned> MappedDest; + Transpose destT(dest); + enum { OtherStorageOrder = StorageOrder == RowMajor ? ColMajor : RowMajor }; + gemv_dense_selector + ::run(rhs.transpose(), lhs.transpose(), destT, alpha); + } +}; - ActualLhsType actualLhs = LhsBlasTraits::extract(prod.lhs()); - ActualRhsType actualRhs = RhsBlasTraits::extract(prod.rhs()); +template<> struct gemv_dense_selector +{ + template + static inline void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) + { + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + typedef typename Dest::Scalar ResScalar; + typedef typename Dest::RealScalar RealScalar; + + typedef internal::blas_traits LhsBlasTraits; + typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; + typedef internal::blas_traits RhsBlasTraits; + typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; + + typedef Map, EIGEN_PLAIN_ENUM_MIN(AlignedMax,internal::packet_traits::size)> MappedDest; - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); + ActualLhsType actualLhs = LhsBlasTraits::extract(lhs); + ActualRhsType actualRhs = RhsBlasTraits::extract(rhs); + + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) + * RhsBlasTraits::extractScalarFactor(rhs); // make sure Dest is a compile-time vector type (bug 1166) typedef typename conditional::type ActualDest; @@ -428,80 +224,97 @@ template<> struct gemv_selector // on, the other hand it is good for the cache to pack the vector anyways... EvalToDestAtCompileTime = (ActualDest::InnerStrideAtCompileTime==1), ComplexByReal = (NumTraits::IsComplex) && (!NumTraits::IsComplex), - MightCannotUseDest = (ActualDest::InnerStrideAtCompileTime!=1) || ComplexByReal + MightCannotUseDest = (!EvalToDestAtCompileTime) || ComplexByReal }; - gemv_static_vector_if static_dest; - - bool alphaIsCompatible = (!ComplexByReal) || (numext::imag(actualAlpha)==RealScalar(0)); - bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; - + typedef const_blas_data_mapper LhsMapper; + typedef const_blas_data_mapper RhsMapper; RhsScalar compatibleAlpha = get_factor::run(actualAlpha); - ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), - evalToDest ? dest.data() : static_dest.data()); - - if(!evalToDest) + if(!MightCannotUseDest) { - #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = dest.size(); - EIGEN_DENSE_STORAGE_CTOR_PLUGIN - #endif - if(!alphaIsCompatible) - { - MappedDest(actualDestPtr, dest.size()).setZero(); - compatibleAlpha = RhsScalar(1); - } - else - MappedDest(actualDestPtr, dest.size()) = dest; + // shortcut if we are sure to be able to use dest directly, + // this ease the compiler to generate cleaner and more optimzized code for most common cases + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhs.data(), actualRhs.innerStride()), + dest.data(), 1, + compatibleAlpha); } - - general_matrix_vector_product - ::run( - actualLhs.rows(), actualLhs.cols(), - actualLhs.data(), actualLhs.outerStride(), - actualRhs.data(), actualRhs.innerStride(), - actualDestPtr, 1, - compatibleAlpha); - - if (!evalToDest) + else { - if(!alphaIsCompatible) - dest += actualAlpha * MappedDest(actualDestPtr, dest.size()); - else - dest = MappedDest(actualDestPtr, dest.size()); + gemv_static_vector_if static_dest; + + const bool alphaIsCompatible = (!ComplexByReal) || (numext::imag(actualAlpha)==RealScalar(0)); + const bool evalToDest = EvalToDestAtCompileTime && alphaIsCompatible; + + ei_declare_aligned_stack_constructed_variable(ResScalar,actualDestPtr,dest.size(), + evalToDest ? dest.data() : static_dest.data()); + + if(!evalToDest) + { + #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN + Index size = dest.size(); + EIGEN_DENSE_STORAGE_CTOR_PLUGIN + #endif + if(!alphaIsCompatible) + { + MappedDest(actualDestPtr, dest.size()).setZero(); + compatibleAlpha = RhsScalar(1); + } + else + MappedDest(actualDestPtr, dest.size()) = dest; + } + + general_matrix_vector_product + ::run( + actualLhs.rows(), actualLhs.cols(), + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhs.data(), actualRhs.innerStride()), + actualDestPtr, 1, + compatibleAlpha); + + if (!evalToDest) + { + if(!alphaIsCompatible) + dest.matrix() += actualAlpha * MappedDest(actualDestPtr, dest.size()); + else + dest = MappedDest(actualDestPtr, dest.size()); + } } } }; -template<> struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename ProductType::LhsScalar LhsScalar; - typedef typename ProductType::RhsScalar RhsScalar; - typedef typename ProductType::Scalar ResScalar; - typedef typename ProductType::Index Index; - typedef typename ProductType::ActualLhsType ActualLhsType; - typedef typename ProductType::ActualRhsType ActualRhsType; - typedef typename ProductType::_ActualRhsType _ActualRhsType; - typedef typename ProductType::LhsBlasTraits LhsBlasTraits; - typedef typename ProductType::RhsBlasTraits RhsBlasTraits; + typedef typename Lhs::Scalar LhsScalar; + typedef typename Rhs::Scalar RhsScalar; + typedef typename Dest::Scalar ResScalar; + + typedef internal::blas_traits LhsBlasTraits; + typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; + typedef internal::blas_traits RhsBlasTraits; + typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; + typedef typename internal::remove_all::type ActualRhsTypeCleaned; - typename add_const::type actualLhs = LhsBlasTraits::extract(prod.lhs()); - typename add_const::type actualRhs = RhsBlasTraits::extract(prod.rhs()); + typename add_const::type actualLhs = LhsBlasTraits::extract(lhs); + typename add_const::type actualRhs = RhsBlasTraits::extract(rhs); - ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(prod.lhs()) - * RhsBlasTraits::extractScalarFactor(prod.rhs()); + ResScalar actualAlpha = alpha * LhsBlasTraits::extractScalarFactor(lhs) + * RhsBlasTraits::extractScalarFactor(rhs); enum { // FIXME find a way to allow an inner stride on the result if packet_traits::size==1 // on, the other hand it is good for the cache to pack the vector anyways... - DirectlyUseRhs = _ActualRhsType::InnerStrideAtCompileTime==1 + DirectlyUseRhs = ActualRhsTypeCleaned::InnerStrideAtCompileTime==1 }; - gemv_static_vector_if static_rhs; + gemv_static_vector_if static_rhs; ei_declare_aligned_stack_constructed_variable(RhsScalar,actualRhsPtr,actualRhs.size(), DirectlyUseRhs ? const_cast(actualRhs.data()) : static_rhs.data()); @@ -509,45 +322,48 @@ template<> struct gemv_selector if(!DirectlyUseRhs) { #ifdef EIGEN_DENSE_STORAGE_CTOR_PLUGIN - int size = actualRhs.size(); + Index size = actualRhs.size(); EIGEN_DENSE_STORAGE_CTOR_PLUGIN #endif - Map(actualRhsPtr, actualRhs.size()) = actualRhs; + Map(actualRhsPtr, actualRhs.size()) = actualRhs; } + typedef const_blas_data_mapper LhsMapper; + typedef const_blas_data_mapper RhsMapper; general_matrix_vector_product - ::run( + ::run( actualLhs.rows(), actualLhs.cols(), - actualLhs.data(), actualLhs.outerStride(), - actualRhsPtr, 1, + LhsMapper(actualLhs.data(), actualLhs.outerStride()), + RhsMapper(actualRhsPtr, 1), dest.data(), dest.col(0).innerStride(), //NOTE if dest is not a vector at compile-time, then dest.innerStride() might be wrong. (bug 1166) actualAlpha); } }; -template<> struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename Dest::Index Index; - // TODO makes sure dest is sequentially stored in memory, otherwise use a temp - const Index size = prod.rhs().rows(); + EIGEN_STATIC_ASSERT((!nested_eval::Evaluate),EIGEN_INTERNAL_COMPILATION_ERROR_OR_YOU_MADE_A_PROGRAMMING_MISTAKE); + // TODO if rhs is large enough it might be beneficial to make sure that dest is sequentially stored in memory, otherwise use a temp + typename nested_eval::type actual_rhs(rhs); + const Index size = rhs.rows(); for(Index k=0; k struct gemv_selector +template<> struct gemv_dense_selector { - template - static void run(const ProductType& prod, Dest& dest, const typename ProductType::Scalar& alpha) + template + static void run(const Lhs &lhs, const Rhs &rhs, Dest& dest, const typename Dest::Scalar& alpha) { - typedef typename Dest::Index Index; - // TODO makes sure rhs is sequentially stored in memory, otherwise use a temp - const Index rows = prod.rows(); + EIGEN_STATIC_ASSERT((!nested_eval::Evaluate),EIGEN_INTERNAL_COMPILATION_ERROR_OR_YOU_MADE_A_PROGRAMMING_MISTAKE); + typename nested_eval::type actual_rhs(rhs); + const Index rows = dest.rows(); for(Index i=0; i struct gemv_selector * * \sa lazyProduct(), operator*=(const MatrixBase&), Cwise::operator*() */ +#ifndef __CUDACC__ + template template -inline const typename ProductReturnType::Type +inline const Product MatrixBase::operator*(const MatrixBase &other) const { // A note regarding the function declaration: In MSVC, this function will sometimes @@ -590,9 +408,12 @@ MatrixBase::operator*(const MatrixBase &other) const #ifdef EIGEN_DEBUG_PRODUCT internal::product_type::debug(); #endif - return typename ProductReturnType::Type(derived(), other.derived()); + + return Product(derived(), other.derived()); } +#endif // __CUDACC__ + /** \returns an expression of the matrix product of \c *this and \a other without implicit evaluation. * * The returned product will behave like any other expressions: the coefficients of the product will be @@ -606,7 +427,7 @@ MatrixBase::operator*(const MatrixBase &other) const */ template template -const typename LazyProductReturnType::Type +const Product MatrixBase::lazyProduct(const MatrixBase &other) const { enum { @@ -625,7 +446,7 @@ MatrixBase::lazyProduct(const MatrixBase &other) const INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION) EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT) - return typename LazyProductReturnType::Type(derived(), other.derived()); + return Product(derived(), other.derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h index c6e93bbb0..029f8ac36 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GenericPacketMath.h @@ -42,21 +42,28 @@ namespace internal { struct default_packet_traits { enum { + HasHalfPacket = 0, + HasAdd = 1, HasSub = 1, HasMul = 1, HasNegate = 1, HasAbs = 1, + HasArg = 0, HasAbs2 = 1, HasMin = 1, HasMax = 1, HasConj = 1, HasSetLinear = 1, + HasBlend = 0, HasDiv = 0, HasSqrt = 0, + HasRsqrt = 0, HasExp = 0, HasLog = 0, + HasLog1p = 0, + HasLog10 = 0, HasPow = 0, HasSin = 0, @@ -64,17 +71,37 @@ struct default_packet_traits HasTan = 0, HasASin = 0, HasACos = 0, - HasATan = 0 + HasATan = 0, + HasSinh = 0, + HasCosh = 0, + HasTanh = 0, + HasLGamma = 0, + HasDiGamma = 0, + HasZeta = 0, + HasPolygamma = 0, + HasErf = 0, + HasErfc = 0, + HasIGamma = 0, + HasIGammac = 0, + HasBetaInc = 0, + + HasRound = 0, + HasFloor = 0, + HasCeil = 0, + + HasSign = 0 }; }; template struct packet_traits : default_packet_traits { typedef T type; + typedef T half; enum { Vectorizable = 0, size = 1, - AlignedOnScalar = 0 + AlignedOnScalar = 0, + HasHalfPacket = 0 }; enum { HasAdd = 0, @@ -90,135 +117,239 @@ template struct packet_traits : default_packet_traits }; }; +template struct packet_traits : packet_traits { }; + +template struct type_casting_traits { + enum { + VectorizedCast = 0, + SrcCoeffRatio = 1, + TgtCoeffRatio = 1 + }; +}; + + +/** \internal \returns static_cast(a) (coeff-wise) */ +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a) { + return static_cast(a); +} +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a, const SrcPacket& /*b*/) { + return static_cast(a); +} + +template +EIGEN_DEVICE_FUNC inline TgtPacket +pcast(const SrcPacket& a, const SrcPacket& /*b*/, const SrcPacket& /*c*/, const SrcPacket& /*d*/) { + return static_cast(a); +} + /** \internal \returns a + b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet padd(const Packet& a, const Packet& b) { return a+b; } /** \internal \returns a - b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet psub(const Packet& a, const Packet& b) { return a-b; } /** \internal \returns -a (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pnegate(const Packet& a) { return -a; } /** \internal \returns conj(a) (coeff-wise) */ -template inline Packet + +template EIGEN_DEVICE_FUNC inline Packet pconj(const Packet& a) { return numext::conj(a); } /** \internal \returns a * b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmul(const Packet& a, const Packet& b) { return a*b; } /** \internal \returns a / b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pdiv(const Packet& a, const Packet& b) { return a/b; } /** \internal \returns the min of \a a and \a b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmin(const Packet& a, - const Packet& b) { using std::min; return (min)(a, b); } + const Packet& b) { return numext::mini(a, b); } /** \internal \returns the max of \a a and \a b (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmax(const Packet& a, - const Packet& b) { using std::max; return (max)(a, b); } + const Packet& b) { return numext::maxi(a, b); } /** \internal \returns the absolute value of \a a */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pabs(const Packet& a) { using std::abs; return abs(a); } +/** \internal \returns the phase angle of \a a */ +template EIGEN_DEVICE_FUNC inline Packet +parg(const Packet& a) { using numext::arg; return arg(a); } + /** \internal \returns the bitwise and of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pand(const Packet& a, const Packet& b) { return a & b; } /** \internal \returns the bitwise or of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet por(const Packet& a, const Packet& b) { return a | b; } /** \internal \returns the bitwise xor of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pxor(const Packet& a, const Packet& b) { return a ^ b; } /** \internal \returns the bitwise andnot of \a a and \a b */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pandnot(const Packet& a, const Packet& b) { return a & (!b); } /** \internal \returns a packet version of \a *from, from must be 16 bytes aligned */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pload(const typename unpacket_traits::type* from) { return *from; } /** \internal \returns a packet version of \a *from, (un-aligned load) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet ploadu(const typename unpacket_traits::type* from) { return *from; } -/** \internal \returns a packet with elements of \a *from duplicated. - * For instance, for a packet of 8 elements, 4 scalar will be read from \a *from and - * duplicated to form: {from[0],from[0],from[1],from[1],,from[2],from[2],,from[3],from[3]} - * Currently, this function is only used for scalar * complex products. - */ -template inline Packet -ploaddup(const typename unpacket_traits::type* from) { return *from; } - /** \internal \returns a packet with constant coefficients \a a, e.g.: (a,a,a,a) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pset1(const typename unpacket_traits::type& a) { return a; } +/** \internal \returns a packet with constant coefficients \a a[0], e.g.: (a[0],a[0],a[0],a[0]) */ +template EIGEN_DEVICE_FUNC inline Packet +pload1(const typename unpacket_traits::type *a) { return pset1(*a); } + +/** \internal \returns a packet with elements of \a *from duplicated. + * For instance, for a packet of 8 elements, 4 scalars will be read from \a *from and + * duplicated to form: {from[0],from[0],from[1],from[1],from[2],from[2],from[3],from[3]} + * Currently, this function is only used for scalar * complex products. + */ +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet +ploaddup(const typename unpacket_traits::type* from) { return *from; } + +/** \internal \returns a packet with elements of \a *from quadrupled. + * For instance, for a packet of 8 elements, 2 scalars will be read from \a *from and + * replicated to form: {from[0],from[0],from[0],from[0],from[1],from[1],from[1],from[1]} + * Currently, this function is only used in matrix products. + * For packet-size smaller or equal to 4, this function is equivalent to pload1 + */ +template EIGEN_DEVICE_FUNC inline Packet +ploadquad(const typename unpacket_traits::type* from) +{ return pload1(from); } + +/** \internal equivalent to + * \code + * a0 = pload1(a+0); + * a1 = pload1(a+1); + * a2 = pload1(a+2); + * a3 = pload1(a+3); + * \endcode + * \sa pset1, pload1, ploaddup, pbroadcast2 + */ +template EIGEN_DEVICE_FUNC +inline void pbroadcast4(const typename unpacket_traits::type *a, + Packet& a0, Packet& a1, Packet& a2, Packet& a3) +{ + a0 = pload1(a+0); + a1 = pload1(a+1); + a2 = pload1(a+2); + a3 = pload1(a+3); +} + +/** \internal equivalent to + * \code + * a0 = pload1(a+0); + * a1 = pload1(a+1); + * \endcode + * \sa pset1, pload1, ploaddup, pbroadcast4 + */ +template EIGEN_DEVICE_FUNC +inline void pbroadcast2(const typename unpacket_traits::type *a, + Packet& a0, Packet& a1) +{ + a0 = pload1(a+0); + a1 = pload1(a+1); +} + /** \internal \brief Returns a packet with coefficients (a,a+1,...,a+packet_size-1). */ -template inline typename packet_traits::type -plset(const Scalar& a) { return a; } +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet +plset(const typename unpacket_traits::type& a) { return a; } /** \internal copy the packet \a from to \a *to, \a to must be 16 bytes aligned */ -template inline void pstore(Scalar* to, const Packet& from) +template EIGEN_DEVICE_FUNC inline void pstore(Scalar* to, const Packet& from) { (*to) = from; } /** \internal copy the packet \a from to \a *to, (un-aligned store) */ -template inline void pstoreu(Scalar* to, const Packet& from) -{ (*to) = from; } +template EIGEN_DEVICE_FUNC inline void pstoreu(Scalar* to, const Packet& from) +{ (*to) = from; } + + template EIGEN_DEVICE_FUNC inline Packet pgather(const Scalar* from, Index /*stride*/) + { return ploadu(from); } + + template EIGEN_DEVICE_FUNC inline void pscatter(Scalar* to, const Packet& from, Index /*stride*/) + { pstore(to, from); } /** \internal tries to do cache prefetching of \a addr */ -template inline void prefetch(const Scalar* addr) +template EIGEN_DEVICE_FUNC inline void prefetch(const Scalar* addr) { -#if (!EIGEN_COMP_MSVC) && (EIGEN_COMP_GNUC || EIGEN_COMP_CLANG || EIGEN_COMP_ICC) +#ifdef __CUDA_ARCH__ +#if defined(__LP64__) + // 64-bit pointer operand constraint for inlined asm + asm(" prefetch.L1 [ %1 ];" : "=l"(addr) : "l"(addr)); +#else + // 32-bit pointer operand constraint for inlined asm + asm(" prefetch.L1 [ %1 ];" : "=r"(addr) : "r"(addr)); +#endif +#elif (!EIGEN_COMP_MSVC) && (EIGEN_COMP_GNUC || EIGEN_COMP_CLANG || EIGEN_COMP_ICC) __builtin_prefetch(addr); #endif } /** \internal \returns the first element of a packet */ -template inline typename unpacket_traits::type pfirst(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type pfirst(const Packet& a) { return a; } /** \internal \returns a packet where the element i contains the sum of the packet of \a vec[i] */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet preduxp(const Packet* vecs) { return vecs[0]; } /** \internal \returns the sum of the elements of \a a*/ -template inline typename unpacket_traits::type predux(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux(const Packet& a) +{ return a; } + +/** \internal \returns the sum of the elements of \a a by block of 4 elements. + * For a packet {a0, a1, a2, a3, a4, a5, a6, a7}, it returns a half packet {a0+a4, a1+a5, a2+a6, a3+a7} + * For packet-size smaller or equal to 4, this boils down to a noop. + */ +template EIGEN_DEVICE_FUNC inline +typename conditional<(unpacket_traits::size%8)==0,typename unpacket_traits::half,Packet>::type +predux_downto4(const Packet& a) { return a; } /** \internal \returns the product of the elements of \a a*/ -template inline typename unpacket_traits::type predux_mul(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_mul(const Packet& a) { return a; } /** \internal \returns the min of the elements of \a a*/ -template inline typename unpacket_traits::type predux_min(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_min(const Packet& a) { return a; } /** \internal \returns the max of the elements of \a a*/ -template inline typename unpacket_traits::type predux_max(const Packet& a) +template EIGEN_DEVICE_FUNC inline typename unpacket_traits::type predux_max(const Packet& a) { return a; } /** \internal \returns the reversed elements of \a a*/ -template inline Packet preverse(const Packet& a) +template EIGEN_DEVICE_FUNC inline Packet preverse(const Packet& a) { return a; } - /** \internal \returns \a a with real and imaginary part flipped (for complex type only) */ -template inline Packet pcplxflip(const Packet& a) +template EIGEN_DEVICE_FUNC inline Packet pcplxflip(const Packet& a) { // FIXME: uncomment the following in case we drop the internal imag and real functions. // using std::imag; @@ -250,6 +381,22 @@ Packet pasin(const Packet& a) { using std::asin; return asin(a); } template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pacos(const Packet& a) { using std::acos; return acos(a); } +/** \internal \returns the arc tangent of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet patan(const Packet& a) { using std::atan; return atan(a); } + +/** \internal \returns the hyperbolic sine of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet psinh(const Packet& a) { using std::sinh; return sinh(a); } + +/** \internal \returns the hyperbolic cosine of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pcosh(const Packet& a) { using std::cosh; return cosh(a); } + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet ptanh(const Packet& a) { using std::tanh; return tanh(a); } + /** \internal \returns the exp of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet pexp(const Packet& a) { using std::exp; return exp(a); } @@ -258,10 +405,36 @@ Packet pexp(const Packet& a) { using std::exp; return exp(a); } template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet plog(const Packet& a) { using std::log; return log(a); } +/** \internal \returns the log1p of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet plog1p(const Packet& a) { return numext::log1p(a); } + +/** \internal \returns the log10 of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet plog10(const Packet& a) { using std::log10; return log10(a); } + /** \internal \returns the square-root of \a a (coeff-wise) */ template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS Packet psqrt(const Packet& a) { using std::sqrt; return sqrt(a); } +/** \internal \returns the reciprocal square-root of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet prsqrt(const Packet& a) { + return pdiv(pset1(1), psqrt(a)); +} + +/** \internal \returns the rounded value of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pround(const Packet& a) { using numext::round; return round(a); } + +/** \internal \returns the floor of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pfloor(const Packet& a) { using numext::floor; return floor(a); } + +/** \internal \returns the ceil of \a a (coeff-wise) */ +template EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS +Packet pceil(const Packet& a) { using numext::ceil; return ceil(a); } + /*************************************************************************** * The following functions might not have to be overwritten for vectorized types ***************************************************************************/ @@ -275,34 +448,45 @@ inline void pstore1(typename unpacket_traits::type* to, const typename u } /** \internal \returns a * b + c (coeff-wise) */ -template inline Packet +template EIGEN_DEVICE_FUNC inline Packet pmadd(const Packet& a, const Packet& b, const Packet& c) { return padd(pmul(a, b),c); } /** \internal \returns a packet version of \a *from. - * If LoadMode equals #Aligned, \a from must be 16 bytes aligned */ -template -inline Packet ploadt(const typename unpacket_traits::type* from) + * The pointer \a from must be aligned on a \a Alignment bytes boundary. */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet ploadt(const typename unpacket_traits::type* from) { - if(LoadMode == Aligned) + if(Alignment >= unpacket_traits::alignment) return pload(from); else return ploadu(from); } /** \internal copy the packet \a from to \a *to. - * If StoreMode equals #Aligned, \a to must be 16 bytes aligned */ -template -inline void pstoret(Scalar* to, const Packet& from) + * The pointer \a from must be aligned on a \a Alignment bytes boundary. */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void pstoret(Scalar* to, const Packet& from) { - if(LoadMode == Aligned) + if(Alignment >= unpacket_traits::alignment) pstore(to, from); else pstoreu(to, from); } +/** \internal \returns a packet version of \a *from. + * Unlike ploadt, ploadt_ro takes advantage of the read-only memory path on the + * hardware if available to speedup the loading of data that won't be modified + * by the current computation. + */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet ploadt_ro(const typename unpacket_traits::type* from) +{ + return ploadt(from); +} + /** \internal default implementation of palign() allowing partial specialization */ template struct palign_impl @@ -336,15 +520,74 @@ inline void palign(PacketType& first, const PacketType& second) * Fast complex products (GCC generates a function call which is very slow) ***************************************************************************/ +// Eigen+CUDA does not support complexes. +#ifndef __CUDACC__ + template<> inline std::complex pmul(const std::complex& a, const std::complex& b) { return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } template<> inline std::complex pmul(const std::complex& a, const std::complex& b) { return std::complex(real(a)*real(b) - imag(a)*imag(b), imag(a)*real(b) + real(a)*imag(b)); } +#endif + + +/*************************************************************************** + * PacketBlock, that is a collection of N packets where the number of words + * in the packet is a multiple of N. +***************************************************************************/ +template ::size> struct PacketBlock { + Packet packet[N]; +}; + +template EIGEN_DEVICE_FUNC inline void +ptranspose(PacketBlock& /*kernel*/) { + // Nothing to do in the scalar case, i.e. a 1x1 matrix. +} + +/*************************************************************************** + * Selector, i.e. vector of N boolean values used to select (i.e. blend) + * words from 2 packets. +***************************************************************************/ +template struct Selector { + bool select[N]; +}; + +template EIGEN_DEVICE_FUNC inline Packet +pblend(const Selector::size>& ifPacket, const Packet& thenPacket, const Packet& elsePacket) { + return ifPacket.select[0] ? thenPacket : elsePacket; +} + +/** \internal \returns \a a with the first coefficient replaced by the scalar b */ +template EIGEN_DEVICE_FUNC inline Packet +pinsertfirst(const Packet& a, typename unpacket_traits::type b) +{ + // Default implementation based on pblend. + // It must be specialized for higher performance. + Selector::size> mask; + mask.select[0] = true; + // This for loop should be optimized away by the compiler. + for(Index i=1; i::size; ++i) + mask.select[i] = false; + return pblend(mask, pset1(b), a); +} + +/** \internal \returns \a a with the last coefficient replaced by the scalar b */ +template EIGEN_DEVICE_FUNC inline Packet +pinsertlast(const Packet& a, typename unpacket_traits::type b) +{ + // Default implementation based on pblend. + // It must be specialized for higher performance. + Selector::size> mask; + // This for loop should be optimized away by the compiler. + for(Index i=0; i::size-1; ++i) + mask.select[i] = false; + mask.select[unpacket_traits::size-1] = true; + return pblend(mask, pset1(b), a); +} + } // end namespace internal } // end namespace Eigen #endif // EIGEN_GENERIC_PACKET_MATH_H - diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h index 2acf97723..769dc255c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/GlobalFunctions.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2010-2012 Gael Guennebaud +// Copyright (C) 2010-2016 Gael Guennebaud // Copyright (C) 2010 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -11,13 +11,30 @@ #ifndef EIGEN_GLOBAL_FUNCTIONS_H #define EIGEN_GLOBAL_FUNCTIONS_H -#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR) \ +#ifdef EIGEN_PARSED_BY_DOXYGEN + +#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR,DOC_OP,DOC_DETAILS) \ + /** \returns an expression of the coefficient-wise DOC_OP of \a x + + DOC_DETAILS + + \sa Math functions, class CwiseUnaryOp + */ \ template \ inline const Eigen::CwiseUnaryOp, const Derived> \ - NAME(const Eigen::ArrayBase& x) { \ - return x.derived(); \ + NAME(const Eigen::ArrayBase& x); + +#else + +#define EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(NAME,FUNCTOR,DOC_OP,DOC_DETAILS) \ + template \ + inline const Eigen::CwiseUnaryOp, const Derived> \ + (NAME)(const Eigen::ArrayBase& x) { \ + return Eigen::CwiseUnaryOp, const Derived>(x.derived()); \ } +#endif // EIGEN_PARSED_BY_DOXYGEN + #define EIGEN_ARRAY_DECLARE_GLOBAL_EIGEN_UNARY(NAME,FUNCTOR) \ \ template \ @@ -30,55 +47,133 @@ { \ static inline typename NAME##_retval >::type run(const Eigen::ArrayBase& x) \ { \ - return x.derived(); \ + return typename NAME##_retval >::type(x.derived()); \ } \ }; - namespace Eigen { - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(real,scalar_real_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(imag,scalar_imag_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(conj,scalar_conjugate_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sin,scalar_sin_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cos,scalar_cos_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(asin,scalar_asin_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(acos,scalar_acos_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tan,scalar_tan_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(exp,scalar_exp_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log,scalar_log_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op) - EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sqrt,scalar_sqrt_op) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(real,scalar_real_op,real part,\sa ArrayBase::real) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(imag,scalar_imag_op,imaginary part,\sa ArrayBase::imag) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(conj,scalar_conjugate_op,complex conjugate,\sa ArrayBase::conjugate) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(inverse,scalar_inverse_op,inverse,\sa ArrayBase::inverse) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sin,scalar_sin_op,sine,\sa ArrayBase::sin) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cos,scalar_cos_op,cosine,\sa ArrayBase::cos) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tan,scalar_tan_op,tangent,\sa ArrayBase::tan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(atan,scalar_atan_op,arc-tangent,\sa ArrayBase::atan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(asin,scalar_asin_op,arc-sine,\sa ArrayBase::asin) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(acos,scalar_acos_op,arc-consine,\sa ArrayBase::acos) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sinh,scalar_sinh_op,hyperbolic sine,\sa ArrayBase::sinh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cosh,scalar_cosh_op,hyperbolic cosine,\sa ArrayBase::cosh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(tanh,scalar_tanh_op,hyperbolic tangent,\sa ArrayBase::tanh) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(lgamma,scalar_lgamma_op,natural logarithm of the gamma function,\sa ArrayBase::lgamma) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(digamma,scalar_digamma_op,derivative of lgamma,\sa ArrayBase::digamma) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erf,scalar_erf_op,error function,\sa ArrayBase::erf) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(erfc,scalar_erfc_op,complement error function,\sa ArrayBase::erfc) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(exp,scalar_exp_op,exponential,\sa ArrayBase::exp) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log,scalar_log_op,natural logarithm,\sa Eigen::log10 DOXCOMMA ArrayBase::log) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log1p,scalar_log1p_op,natural logarithm of 1 plus the value,\sa ArrayBase::log1p) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(log10,scalar_log10_op,base 10 logarithm,\sa Eigen::log DOXCOMMA ArrayBase::log) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs,scalar_abs_op,absolute value,\sa ArrayBase::abs DOXCOMMA MatrixBase::cwiseAbs) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(abs2,scalar_abs2_op,squared absolute value,\sa ArrayBase::abs2 DOXCOMMA MatrixBase::cwiseAbs2) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(arg,scalar_arg_op,complex argument,\sa ArrayBase::arg) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sqrt,scalar_sqrt_op,square root,\sa ArrayBase::sqrt DOXCOMMA MatrixBase::cwiseSqrt) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(rsqrt,scalar_rsqrt_op,reciprocal square root,\sa ArrayBase::rsqrt) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(square,scalar_square_op,square (power 2),\sa Eigen::abs2 DOXCOMMA Eigen::pow DOXCOMMA ArrayBase::square) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(cube,scalar_cube_op,cube (power 3),\sa Eigen::pow DOXCOMMA ArrayBase::cube) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(round,scalar_round_op,nearest integer,\sa Eigen::floor DOXCOMMA Eigen::ceil DOXCOMMA ArrayBase::round) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(floor,scalar_floor_op,nearest integer not greater than the giben value,\sa Eigen::ceil DOXCOMMA ArrayBase::floor) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(ceil,scalar_ceil_op,nearest integer not less than the giben value,\sa Eigen::floor DOXCOMMA ArrayBase::ceil) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isnan,scalar_isnan_op,not-a-number test,\sa Eigen::isinf DOXCOMMA Eigen::isfinite DOXCOMMA ArrayBase::isnan) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isinf,scalar_isinf_op,infinite value test,\sa Eigen::isnan DOXCOMMA Eigen::isfinite DOXCOMMA ArrayBase::isinf) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(isfinite,scalar_isfinite_op,finite value test,\sa Eigen::isinf DOXCOMMA Eigen::isnan DOXCOMMA ArrayBase::isfinite) + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY(sign,scalar_sign_op,sign (or 0),\sa ArrayBase::sign) - template - inline const Eigen::CwiseUnaryOp, const Derived> - pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { + /** \returns an expression of the coefficient-wise power of \a x to the given constant \a exponent. + * + * \tparam ScalarExponent is the scalar type of \a exponent. It must be compatible with the scalar type of the given expression (\c Derived::Scalar). + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ +#ifdef EIGEN_PARSED_BY_DOXYGEN + template + inline const CwiseBinaryOp,Derived,Constant > + pow(const Eigen::ArrayBase& x, const ScalarExponent& exponent); +#else + template + inline typename internal::enable_if< !(internal::is_same::value) && EIGEN_SCALAR_BINARY_SUPPORTED(pow,typename Derived::Scalar,ScalarExponent), + const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,ScalarExponent,pow) >::type + pow(const Eigen::ArrayBase& x, const ScalarExponent& exponent) { return x.derived().pow(exponent); } template - inline const Eigen::CwiseBinaryOp, const Derived, const Derived> - pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) + inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,typename Derived::Scalar,pow) + pow(const Eigen::ArrayBase& x, const typename Derived::Scalar& exponent) { + return x.derived().pow(exponent); + } +#endif + + /** \returns an expression of the coefficient-wise power of \a x to the given array of \a exponents. + * + * This function computes the coefficient-wise power. + * + * Example: \include Cwise_array_power_array.cpp + * Output: \verbinclude Cwise_array_power_array.out + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ + template + inline const Eigen::CwiseBinaryOp, const Derived, const ExponentDerived> + pow(const Eigen::ArrayBase& x, const Eigen::ArrayBase& exponents) { - return Eigen::CwiseBinaryOp, const Derived, const Derived>( + return Eigen::CwiseBinaryOp, const Derived, const ExponentDerived>( x.derived(), exponents.derived() ); } - /** - * \brief Component-wise division of a scalar by array elements. - **/ - template - inline const Eigen::CwiseUnaryOp, const Derived> - operator/(const typename Derived::Scalar& s, const Eigen::ArrayBase& a) + /** \returns an expression of the coefficient-wise power of the scalar \a x to the given array of \a exponents. + * + * This function computes the coefficient-wise power between a scalar and an array of exponents. + * + * \tparam Scalar is the scalar type of \a x. It must be compatible with the scalar type of the given array expression (\c Derived::Scalar). + * + * Example: \include Cwise_scalar_power_array.cpp + * Output: \verbinclude Cwise_scalar_power_array.out + * + * \sa ArrayBase::pow() + * + * \relates ArrayBase + */ +#ifdef EIGEN_PARSED_BY_DOXYGEN + template + inline const CwiseBinaryOp,Constant,Derived> + pow(const Scalar& x,const Eigen::ArrayBase& x); +#else + template + inline typename internal::enable_if< !(internal::is_same::value) && EIGEN_SCALAR_BINARY_SUPPORTED(pow,Scalar,typename Derived::Scalar), + const EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(Scalar,Derived,pow) >::type + pow(const Scalar& x, const Eigen::ArrayBase& exponents) { - return Eigen::CwiseUnaryOp, const Derived>( - a.derived(), - Eigen::internal::scalar_inverse_mult_op(s) - ); + return EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(Scalar,Derived,pow)( + typename internal::plain_constant_type::type(exponents.rows(), exponents.cols(), x), exponents.derived() ); } + template + inline const EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(typename Derived::Scalar,Derived,pow) + pow(const typename Derived::Scalar& x, const Eigen::ArrayBase& exponents) + { + return EIGEN_SCALAR_BINARYOP_EXPR_RETURN_TYPE(typename Derived::Scalar,Derived,pow)( + typename internal::plain_constant_type::type(exponents.rows(), exponents.cols(), x), exponents.derived() ); + } +#endif + + namespace internal { EIGEN_ARRAY_DECLARE_GLOBAL_EIGEN_UNARY(real,scalar_real_op) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h index 8d4bc59e9..da7fd6cce 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/IO.h @@ -49,7 +49,7 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& */ struct IOFormat { - /** Default contructor, see class IOFormat for the meaning of the parameters */ + /** Default constructor, see class IOFormat for the meaning of the parameters */ IOFormat(int _precision = StreamPrecision, int _flags = 0, const std::string& _coeffSeparator = " ", const std::string& _rowSeparator = "\n", const std::string& _rowPrefix="", const std::string& _rowSuffix="", @@ -57,6 +57,10 @@ struct IOFormat : matPrefix(_matPrefix), matSuffix(_matSuffix), rowPrefix(_rowPrefix), rowSuffix(_rowSuffix), rowSeparator(_rowSeparator), rowSpacer(""), coeffSeparator(_coeffSeparator), precision(_precision), flags(_flags) { + // TODO check if rowPrefix, rowSuffix or rowSeparator contains a newline + // don't add rowSpacer if columns are not to be aligned + if((flags & DontAlignCols)) + return; int i = int(matSuffix.length())-1; while (i>=0 && matSuffix[i]!='\n') { @@ -76,7 +80,7 @@ struct IOFormat * * \brief Pseudo expression providing matrix output with given format * - * \param ExpressionType the type of the object on which IO stream operations are performed + * \tparam ExpressionType the type of the object on which IO stream operations are performed * * This class represents an expression with stream operators controlled by a given IOFormat. * It is the return type of DenseBase::format() @@ -101,51 +105,23 @@ class WithFormat } protected: - const typename ExpressionType::Nested m_matrix; + typename ExpressionType::Nested m_matrix; IOFormat m_format; }; -/** \returns a WithFormat proxy object allowing to print a matrix the with given - * format \a fmt. - * - * See class IOFormat for some examples. - * - * \sa class IOFormat, class WithFormat - */ -template -inline const WithFormat -DenseBase::format(const IOFormat& fmt) const -{ - return WithFormat(derived(), fmt); -} - namespace internal { -template -struct significant_decimals_default_impl -{ - typedef typename NumTraits::Real RealScalar; - static inline int run() - { - using std::ceil; - using std::log; - return cast(ceil(-log(NumTraits::epsilon())/log(RealScalar(10)))); - } -}; - -template -struct significant_decimals_default_impl -{ - static inline int run() - { - return 0; - } -}; - +// NOTE: This helper is kept for backward compatibility with previous code specializing +// this internal::significant_decimals_impl structure. In the future we should directly +// call digits10() which has been introduced in July 2016 in 3.3. template struct significant_decimals_impl - : significant_decimals_default_impl::IsInteger> -{}; +{ + static inline int run() + { + return NumTraits::digits10(); + } +}; /** \internal * print the matrix \a _m to the output stream \a s using the output format \a fmt */ @@ -160,7 +136,6 @@ std::ostream & print_matrix(std::ostream & s, const Derived& _m, const IOFormat& typename Derived::Nested m = _m; typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; Index width = 0; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Inverse.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Inverse.h new file mode 100644 index 000000000..b76f0439d --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Inverse.h @@ -0,0 +1,118 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_INVERSE_H +#define EIGEN_INVERSE_H + +namespace Eigen { + +template class InverseImpl; + +namespace internal { + +template +struct traits > + : traits +{ + typedef typename XprType::PlainObject PlainObject; + typedef traits BaseTraits; + enum { + Flags = BaseTraits::Flags & RowMajorBit + }; +}; + +} // end namespace internal + +/** \class Inverse + * + * \brief Expression of the inverse of another expression + * + * \tparam XprType the type of the expression we are taking the inverse + * + * This class represents an abstract expression of A.inverse() + * and most of the time this is the only way it is used. + * + */ +template +class Inverse : public InverseImpl::StorageKind> +{ +public: + typedef typename XprType::StorageIndex StorageIndex; + typedef typename XprType::PlainObject PlainObject; + typedef typename XprType::Scalar Scalar; + typedef typename internal::ref_selector::type XprTypeNested; + typedef typename internal::remove_all::type XprTypeNestedCleaned; + typedef typename internal::ref_selector::type Nested; + typedef typename internal::remove_all::type NestedExpression; + + explicit EIGEN_DEVICE_FUNC Inverse(const XprType &xpr) + : m_xpr(xpr) + {} + + EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } + + EIGEN_DEVICE_FUNC const XprTypeNestedCleaned& nestedExpression() const { return m_xpr; } + +protected: + XprTypeNested m_xpr; +}; + +// Generic API dispatcher +template +class InverseImpl + : public internal::generic_xpr_base >::type +{ +public: + typedef typename internal::generic_xpr_base >::type Base; + typedef typename XprType::Scalar Scalar; +private: + + Scalar coeff(Index row, Index col) const; + Scalar coeff(Index i) const; +}; + +namespace internal { + +/** \internal + * \brief Default evaluator for Inverse expression. + * + * This default evaluator for Inverse expression simply evaluate the inverse into a temporary + * by a call to internal::call_assignment_no_alias. + * Therefore, inverse implementers only have to specialize Assignment, ...> for + * there own nested expression. + * + * \sa class Inverse + */ +template +struct unary_evaluator > + : public evaluator::PlainObject> +{ + typedef Inverse InverseType; + typedef typename InverseType::PlainObject PlainObject; + typedef evaluator Base; + + enum { Flags = Base::Flags | EvalBeforeNestingBit }; + + unary_evaluator(const InverseType& inv_xpr) + : m_result(inv_xpr.rows(), inv_xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + internal::call_assignment_no_alias(m_result, inv_xpr); + } + +protected: + PlainObject m_result; +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_INVERSE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h index f804c89d6..06d196702 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Map.h @@ -13,13 +13,35 @@ namespace Eigen { +namespace internal { +template +struct traits > + : public traits +{ + typedef traits TraitsBase; + enum { + InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 + ? int(PlainObjectType::InnerStrideAtCompileTime) + : int(StrideType::InnerStrideAtCompileTime), + OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 + ? int(PlainObjectType::OuterStrideAtCompileTime) + : int(StrideType::OuterStrideAtCompileTime), + Alignment = int(MapOptions)&int(AlignedMask), + Flags0 = TraitsBase::Flags & (~NestByRefBit), + Flags = is_lvalue::value ? int(Flags0) : (int(Flags0) & ~LvalueBit) + }; +private: + enum { Options }; // Expressions don't have Options +}; +} + /** \class Map * \ingroup Core_Module * * \brief A matrix or vector expression mapping an existing array of data. * * \tparam PlainObjectType the equivalent matrix type of the mapped data - * \tparam MapOptions specifies whether the pointer is \c #Aligned, or \c #Unaligned. + * \tparam MapOptions specifies the pointer alignment in bytes. It can be: \c #Aligned128, , \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. * The default is \c #Unaligned. * \tparam StrideType optionally specifies strides. By default, Map assumes the memory layout * of an ordinary, contiguous array. This can be overridden by specifying strides. @@ -63,44 +85,6 @@ namespace Eigen { * * \sa PlainObjectBase::Map(), \ref TopicStorageOrders */ - -namespace internal { -template -struct traits > - : public traits -{ - typedef traits TraitsBase; - typedef typename PlainObjectType::Index Index; - typedef typename PlainObjectType::Scalar Scalar; - enum { - InnerStrideAtCompileTime = StrideType::InnerStrideAtCompileTime == 0 - ? int(PlainObjectType::InnerStrideAtCompileTime) - : int(StrideType::InnerStrideAtCompileTime), - OuterStrideAtCompileTime = StrideType::OuterStrideAtCompileTime == 0 - ? int(PlainObjectType::OuterStrideAtCompileTime) - : int(StrideType::OuterStrideAtCompileTime), - HasNoInnerStride = InnerStrideAtCompileTime == 1, - HasNoOuterStride = StrideType::OuterStrideAtCompileTime == 0, - HasNoStride = HasNoInnerStride && HasNoOuterStride, - IsAligned = bool(EIGEN_ALIGN) && ((int(MapOptions)&Aligned)==Aligned), - IsDynamicSize = PlainObjectType::SizeAtCompileTime==Dynamic, - KeepsPacketAccess = bool(HasNoInnerStride) - && ( bool(IsDynamicSize) - || HasNoOuterStride - || ( OuterStrideAtCompileTime!=Dynamic - && ((static_cast(sizeof(Scalar))*OuterStrideAtCompileTime)%16)==0 ) ), - Flags0 = TraitsBase::Flags & (~NestByRefBit), - Flags1 = IsAligned ? (int(Flags0) | AlignedBit) : (int(Flags0) & ~AlignedBit), - Flags2 = (bool(HasNoStride) || bool(PlainObjectType::IsVectorAtCompileTime)) - ? int(Flags1) : int(Flags1 & ~LinearAccessBit), - Flags3 = is_lvalue::value ? int(Flags2) : (int(Flags2) & ~LvalueBit), - Flags = KeepsPacketAccess ? int(Flags3) : (int(Flags3) & ~PacketAccessBit) - }; -private: - enum { Options }; // Expressions don't have Options -}; -} - template class Map : public MapBase > { @@ -110,19 +94,17 @@ template class Ma EIGEN_DENSE_PUBLIC_INTERFACE(Map) typedef typename Base::PointerType PointerType; -#if EIGEN2_SUPPORT_STAGE <= STAGE30_FULL_EIGEN3_API - typedef const Scalar* PointerArgType; - inline PointerType cast_to_pointer_type(PointerArgType ptr) { return const_cast(ptr); } -#else typedef PointerType PointerArgType; + EIGEN_DEVICE_FUNC inline PointerType cast_to_pointer_type(PointerArgType ptr) { return ptr; } -#endif + EIGEN_DEVICE_FUNC inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() @@ -134,10 +116,11 @@ template class Ma /** Constructor in the fixed-size case. * * \param dataPtr pointer to the array to map - * \param a_stride optional Stride object, passing the strides. + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr)), m_stride(a_stride) + EIGEN_DEVICE_FUNC + explicit inline Map(PointerArgType dataPtr, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr)), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -145,11 +128,12 @@ template class Ma /** Constructor in the dynamic-size vector case. * * \param dataPtr pointer to the array to map - * \param a_size the size of the vector expression - * \param a_stride optional Stride object, passing the strides. + * \param size the size of the vector expression + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, Index a_size, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr), a_size), m_stride(a_stride) + EIGEN_DEVICE_FUNC + inline Map(PointerArgType dataPtr, Index size, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr), size), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -157,12 +141,13 @@ template class Ma /** Constructor in the dynamic-size matrix case. * * \param dataPtr pointer to the array to map - * \param nbRows the number of rows of the matrix expression - * \param nbCols the number of columns of the matrix expression - * \param a_stride optional Stride object, passing the strides. + * \param rows the number of rows of the matrix expression + * \param cols the number of columns of the matrix expression + * \param stride optional Stride object, passing the strides. */ - inline Map(PointerArgType dataPtr, Index nbRows, Index nbCols, const StrideType& a_stride = StrideType()) - : Base(cast_to_pointer_type(dataPtr), nbRows, nbCols), m_stride(a_stride) + EIGEN_DEVICE_FUNC + inline Map(PointerArgType dataPtr, Index rows, Index cols, const StrideType& stride = StrideType()) + : Base(cast_to_pointer_type(dataPtr), rows, cols), m_stride(stride) { PlainObjectType::Base::_check_template_params(); } @@ -173,19 +158,6 @@ template class Ma StrideType m_stride; }; -template -inline Array<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> - ::Array(const Scalar *data) -{ - this->_set_noalias(Eigen::Map(data)); -} - -template -inline Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> - ::Matrix(const Scalar *data) -{ - this->_set_noalias(Eigen::Map(data)); -} } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h index 81efc4a6d..020f939ad 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MapBase.h @@ -12,15 +12,25 @@ #define EIGEN_MAPBASE_H #define EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) \ - EIGEN_STATIC_ASSERT((int(internal::traits::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ + EIGEN_STATIC_ASSERT((int(internal::evaluator::Flags) & LinearAccessBit) || Derived::IsVectorAtCompileTime, \ YOU_ARE_TRYING_TO_USE_AN_INDEX_BASED_ACCESSOR_ON_AN_EXPRESSION_THAT_DOES_NOT_SUPPORT_THAT) namespace Eigen { -/** \class MapBase - * \ingroup Core_Module +/** \ingroup Core_Module * - * \brief Base class for Map and Block expression with direct access + * \brief Base class for dense Map and Block expression with direct access + * + * This base class provides the const low-level accessors (e.g. coeff, coeffRef) of dense + * Map and Block objects with direct access. + * Typical users do not have to directly deal with this class. + * + * This class can be extended by through the macro plugin \c EIGEN_MAPBASE_PLUGIN. + * See \link TopicCustomizing_Plugins customizing Eigen \endlink for details. + * + * The \c Derived class has to provide the following two methods describing the memory layout: + * \code Index innerStride() const; \endcode + * \code Index outerStride() const; \endcode * * \sa class Map, class Block */ @@ -37,7 +47,6 @@ template class MapBase }; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -76,8 +85,10 @@ template class MapBase typedef typename Base::CoeffReturnType CoeffReturnType; - inline Index rows() const { return m_rows.value(); } - inline Index cols() const { return m_cols.value(); } + /** \copydoc DenseBase::rows() */ + EIGEN_DEVICE_FUNC inline Index rows() const { return m_rows.value(); } + /** \copydoc DenseBase::cols() */ + EIGEN_DEVICE_FUNC inline Index cols() const { return m_cols.value(); } /** Returns a pointer to the first coefficient of the matrix or vector. * @@ -85,30 +96,39 @@ template class MapBase * * \sa innerStride(), outerStride() */ - inline const Scalar* data() const { return m_data; } + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return m_data; } + /** \copydoc PlainObjectBase::coeff(Index,Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index rowId, Index colId) const { return m_data[colId * colStride() + rowId * rowStride()]; } + /** \copydoc PlainObjectBase::coeff(Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index index) const { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) return m_data[index * innerStride()]; } + /** \copydoc PlainObjectBase::coeffRef(Index,Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index rowId, Index colId) const { return this->m_data[colId * colStride() + rowId * rowStride()]; } + /** \copydoc PlainObjectBase::coeffRef(Index) const */ + EIGEN_DEVICE_FUNC inline const Scalar& coeffRef(Index index) const { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) return this->m_data[index * innerStride()]; } + /** \internal */ template inline PacketScalar packet(Index rowId, Index colId) const { @@ -116,6 +136,7 @@ template class MapBase (m_data + (colId * colStride() + rowId * rowStride())); } + /** \internal */ template inline PacketScalar packet(Index index) const { @@ -123,12 +144,16 @@ template class MapBase return internal::ploadt(m_data + index * innerStride()); } + /** \internal Constructor for fixed size matrices or vectors */ + EIGEN_DEVICE_FUNC explicit inline MapBase(PointerType dataPtr) : m_data(dataPtr), m_rows(RowsAtCompileTime), m_cols(ColsAtCompileTime) { EIGEN_STATIC_ASSERT_FIXED_SIZE(Derived) - checkSanity(); + checkSanity(); } + /** \internal Constructor for dynamically sized vectors */ + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index vecSize) : m_data(dataPtr), m_rows(RowsAtCompileTime == Dynamic ? vecSize : Index(RowsAtCompileTime)), @@ -137,16 +162,18 @@ template class MapBase EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived) eigen_assert(vecSize >= 0); eigen_assert(dataPtr == 0 || SizeAtCompileTime == Dynamic || SizeAtCompileTime == vecSize); - checkSanity(); + checkSanity(); } - inline MapBase(PointerType dataPtr, Index nbRows, Index nbCols) - : m_data(dataPtr), m_rows(nbRows), m_cols(nbCols) + /** \internal Constructor for dynamically sized matrices */ + EIGEN_DEVICE_FUNC + inline MapBase(PointerType dataPtr, Index rows, Index cols) + : m_data(dataPtr), m_rows(rows), m_cols(cols) { eigen_assert( (dataPtr == 0) - || ( nbRows >= 0 && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == nbRows) - && nbCols >= 0 && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == nbCols))); - checkSanity(); + || ( rows >= 0 && (RowsAtCompileTime == Dynamic || RowsAtCompileTime == rows) + && cols >= 0 && (ColsAtCompileTime == Dynamic || ColsAtCompileTime == cols))); + checkSanity(); } #ifdef EIGEN_MAPBASE_PLUGIN @@ -155,20 +182,36 @@ template class MapBase protected: - void checkSanity() const + template + EIGEN_DEVICE_FUNC + void checkSanity(typename internal::enable_if<(internal::traits::Alignment>0),void*>::type = 0) const { - EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(internal::traits::Flags&PacketAccessBit, - internal::inner_stride_at_compile_time::ret==1), - PACKET_ACCESS_REQUIRES_TO_HAVE_INNER_STRIDE_FIXED_TO_1); - eigen_assert(EIGEN_IMPLIES(internal::traits::Flags&AlignedBit, (size_t(m_data) % 16) == 0) - && "input pointer is not aligned on a 16 byte boundary"); +#if EIGEN_MAX_ALIGN_BYTES>0 + eigen_assert(( ((internal::UIntPtr(m_data) % internal::traits::Alignment) == 0) + || (cols() * rows() * innerStride() * sizeof(Scalar)) < internal::traits::Alignment ) && "data is not aligned"); +#endif } + template + EIGEN_DEVICE_FUNC + void checkSanity(typename internal::enable_if::Alignment==0,void*>::type = 0) const + {} + PointerType m_data; const internal::variable_if_dynamic m_rows; const internal::variable_if_dynamic m_cols; }; +/** \ingroup Core_Module + * + * \brief Base class for non-const dense Map and Block expression with direct access + * + * This base class provides the non-const low-level accessors (e.g. coeff and coeffRef) of + * dense Map and Block objects with direct access. + * It inherits MapBase which defines the const variant for reading specific entries. + * + * \sa class Map, class Block + */ template class MapBase : public MapBase { @@ -179,7 +222,7 @@ template class MapBase typedef typename Base::Scalar Scalar; typedef typename Base::PacketScalar PacketScalar; - typedef typename Base::Index Index; + typedef typename Base::StorageIndex StorageIndex; typedef typename Base::PointerType PointerType; using Base::derived; @@ -200,14 +243,18 @@ template class MapBase const Scalar >::type ScalarWithConstIfNotLvalue; + EIGEN_DEVICE_FUNC inline const Scalar* data() const { return this->m_data; } + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue* data() { return this->m_data; } // no const-cast here so non-const-correct code will give a compile error + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue& coeffRef(Index row, Index col) { return this->m_data[col * colStride() + row * rowStride()]; } + EIGEN_DEVICE_FUNC inline ScalarWithConstIfNotLvalue& coeffRef(Index index) { EIGEN_STATIC_ASSERT_INDEX_BASED_ACCESS(Derived) @@ -229,10 +276,11 @@ template class MapBase (this->m_data + index * innerStride(), val); } - explicit inline MapBase(PointerType dataPtr) : Base(dataPtr) {} - inline MapBase(PointerType dataPtr, Index vecSize) : Base(dataPtr, vecSize) {} - inline MapBase(PointerType dataPtr, Index nbRows, Index nbCols) : Base(dataPtr, nbRows, nbCols) {} + EIGEN_DEVICE_FUNC explicit inline MapBase(PointerType dataPtr) : Base(dataPtr) {} + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index vecSize) : Base(dataPtr, vecSize) {} + EIGEN_DEVICE_FUNC inline MapBase(PointerType dataPtr, Index rows, Index cols) : Base(dataPtr, rows, cols) {} + EIGEN_DEVICE_FUNC Derived& operator=(const MapBase& other) { ReadOnlyMapBase::Base::operator=(other); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h index f707aa41e..a648aa0fa 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctions.h @@ -10,11 +10,25 @@ #ifndef EIGEN_MATHFUNCTIONS_H #define EIGEN_MATHFUNCTIONS_H +// source: http://www.geom.uiuc.edu/~huberty/math5337/groupe/digits.html +// TODO this should better be moved to NumTraits +#define EIGEN_PI 3.141592653589793238462643383279502884197169399375105820974944592307816406L + + namespace Eigen { +// On WINCE, std::abs is defined for int only, so let's defined our own overloads: +// This issue has been confirmed with MSVC 2008 only, but the issue might exist for more recent versions too. +#if EIGEN_OS_WINCE && EIGEN_COMP_MSVC && EIGEN_COMP_MSVC<=1500 +long abs(long x) { return (labs(x)); } +double abs(double x) { return (fabs(x)); } +float abs(float x) { return (fabsf(x)); } +long double abs(long double x) { return (fabsl(x)); } +#endif + namespace internal { -/** \internal \struct global_math_functions_filtering_base +/** \internal \class global_math_functions_filtering_base * * What it does: * Defines a typedef 'type' as follows: @@ -62,6 +76,7 @@ template::IsComplex> struct real_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return x; @@ -72,6 +87,7 @@ template struct real_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { using std::real; @@ -81,13 +97,25 @@ struct real_default_impl template struct real_impl : real_default_impl {}; +#ifdef __CUDA_ARCH__ +template +struct real_impl > +{ + typedef T RealScalar; + EIGEN_DEVICE_FUNC + static inline T run(const std::complex& x) + { + return x.real(); + } +}; +#endif + template struct real_retval { typedef typename NumTraits::Real type; }; - /**************************************************************************** * Implementation of imag * ****************************************************************************/ @@ -96,6 +124,7 @@ template::IsComplex> struct imag_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar&) { return RealScalar(0); @@ -106,6 +135,7 @@ template struct imag_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { using std::imag; @@ -115,6 +145,19 @@ struct imag_default_impl template struct imag_impl : imag_default_impl {}; +#ifdef __CUDA_ARCH__ +template +struct imag_impl > +{ + typedef T RealScalar; + EIGEN_DEVICE_FUNC + static inline T run(const std::complex& x) + { + return x.imag(); + } +}; +#endif + template struct imag_retval { @@ -129,10 +172,12 @@ template struct real_ref_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar& run(Scalar& x) { return reinterpret_cast(&x)[0]; } + EIGEN_DEVICE_FUNC static inline const RealScalar& run(const Scalar& x) { return reinterpret_cast(&x)[0]; @@ -153,10 +198,12 @@ template struct imag_ref_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar& run(Scalar& x) { return reinterpret_cast(&x)[1]; } + EIGEN_DEVICE_FUNC static inline const RealScalar& run(const Scalar& x) { return reinterpret_cast(&x)[1]; @@ -166,10 +213,12 @@ struct imag_ref_default_impl template struct imag_ref_default_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(Scalar&) { return Scalar(0); } + EIGEN_DEVICE_FUNC static inline const Scalar run(const Scalar&) { return Scalar(0); @@ -192,6 +241,7 @@ struct imag_ref_retval template::IsComplex> struct conj_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { return x; @@ -201,6 +251,7 @@ struct conj_impl template struct conj_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { using std::conj; @@ -222,6 +273,7 @@ template struct abs2_impl_default { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return x*x; @@ -232,6 +284,7 @@ template struct abs2_impl_default // IsComplex { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return real(x)*real(x) + imag(x)*imag(x); @@ -242,6 +295,7 @@ template struct abs2_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { return abs2_impl_default::IsComplex>::run(x); @@ -262,9 +316,10 @@ template struct norm1_default_impl { typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC static inline RealScalar run(const Scalar& x) { - using std::abs; + EIGEN_USING_STD_MATH(abs); return abs(real(x)) + abs(imag(x)); } }; @@ -272,9 +327,10 @@ struct norm1_default_impl template struct norm1_default_impl { + EIGEN_DEVICE_FUNC static inline Scalar run(const Scalar& x) { - using std::abs; + EIGEN_USING_STD_MATH(abs); return abs(x); } }; @@ -298,16 +354,22 @@ struct hypot_impl typedef typename NumTraits::Real RealScalar; static inline RealScalar run(const Scalar& x, const Scalar& y) { - using std::max; - using std::min; - using std::abs; - using std::sqrt; + EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD_MATH(sqrt); RealScalar _x = abs(x); RealScalar _y = abs(y); - RealScalar p = (max)(_x, _y); + Scalar p, qp; + if(_x>_y) + { + p = _x; + qp = _y / p; + } + else + { + p = _y; + qp = _x / p; + } if(p==RealScalar(0)) return RealScalar(0); - RealScalar q = (min)(_x, _y); - RealScalar qp = q/p; return p * sqrt(RealScalar(1) + qp*qp); } }; @@ -325,6 +387,7 @@ struct hypot_retval template struct cast_impl { + EIGEN_DEVICE_FUNC static inline NewType run(const OldType& x) { return static_cast(x); @@ -334,48 +397,124 @@ struct cast_impl // here, for once, we're plainly returning NewType: we don't want cast to do weird things. template +EIGEN_DEVICE_FUNC inline NewType cast(const OldType& x) { return cast_impl::run(x); } /**************************************************************************** -* Implementation of atanh2 * +* Implementation of round * ****************************************************************************/ -template -struct atanh2_default_impl -{ - typedef Scalar retval; - typedef typename NumTraits::Real RealScalar; - static inline Scalar run(const Scalar& x, const Scalar& y) +#if EIGEN_HAS_CXX11_MATH + template + struct round_impl { + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) + using std::round; + return round(x); + } + }; +#else + template + struct round_impl { - using std::abs; - using std::log; - using std::sqrt; - Scalar z = x / y; - if (y == Scalar(0) || abs(z) > sqrt(NumTraits::epsilon())) - return RealScalar(0.5) * log((y + x) / (y - x)); - else - return z + z*z*z / RealScalar(3); - } -}; + static inline Scalar run(const Scalar& x) + { + EIGEN_STATIC_ASSERT((!NumTraits::IsComplex), NUMERIC_TYPE_MUST_BE_REAL) + EIGEN_USING_STD_MATH(floor); + EIGEN_USING_STD_MATH(ceil); + return (x > Scalar(0)) ? floor(x + Scalar(0.5)) : ceil(x - Scalar(0.5)); + } + }; +#endif template -struct atanh2_default_impl +struct round_retval { - static inline Scalar run(const Scalar&, const Scalar&) + typedef Scalar type; +}; + +/**************************************************************************** +* Implementation of arg * +****************************************************************************/ + +#if EIGEN_HAS_CXX11_MATH + template + struct arg_impl { + static inline Scalar run(const Scalar& x) + { + EIGEN_USING_STD_MATH(arg); + return arg(x); + } + }; +#else + template::IsComplex> + struct arg_default_impl + { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + return (x < Scalar(0)) ? Scalar(EIGEN_PI) : Scalar(0); } + }; + + template + struct arg_default_impl + { + typedef typename NumTraits::Real RealScalar; + EIGEN_DEVICE_FUNC + static inline RealScalar run(const Scalar& x) + { + EIGEN_USING_STD_MATH(arg); + return arg(x); + } + }; + + template struct arg_impl : arg_default_impl {}; +#endif + +template +struct arg_retval +{ + typedef typename NumTraits::Real type; +}; + +/**************************************************************************** +* Implementation of log1p * +****************************************************************************/ + +namespace std_fallback { + // fallback log1p implementation in case there is no log1p(Scalar) function in namespace of Scalar, + // or that there is no suitable std::log1p function available + template + EIGEN_DEVICE_FUNC inline Scalar log1p(const Scalar& x) { + EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) + typedef typename NumTraits::Real RealScalar; + EIGEN_USING_STD_MATH(log); + Scalar x1p = RealScalar(1) + x; + return ( x1p == Scalar(1) ) ? x : x * ( log(x1p) / (x1p - RealScalar(1)) ); + } +} + +template +struct log1p_impl { + static inline Scalar run(const Scalar& x) { EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar) - return Scalar(0); + #if EIGEN_HAS_CXX11_MATH + using std::log1p; + #endif + using std_fallback::log1p; + return log1p(x); } }; -template -struct atanh2_impl : atanh2_default_impl::IsInteger> {}; template -struct atanh2_retval +struct log1p_retval { typedef Scalar type; }; @@ -384,24 +523,26 @@ struct atanh2_retval * Implementation of pow * ****************************************************************************/ -template -struct pow_default_impl +template::IsInteger&&NumTraits::IsInteger> +struct pow_impl { - typedef Scalar retval; - static inline Scalar run(const Scalar& x, const Scalar& y) + //typedef Scalar retval; + typedef typename ScalarBinaryOpTraits >::ReturnType result_type; + static EIGEN_DEVICE_FUNC inline result_type run(const ScalarX& x, const ScalarY& y) { - using std::pow; + EIGEN_USING_STD_MATH(pow); return pow(x, y); } }; -template -struct pow_default_impl +template +struct pow_impl { - static inline Scalar run(Scalar x, Scalar y) + typedef ScalarX result_type; + static EIGEN_DEVICE_FUNC inline ScalarX run(ScalarX x, ScalarY y) { - Scalar res(1); - eigen_assert(!NumTraits::IsSigned || y >= 0); + ScalarX res(1); + eigen_assert(!NumTraits::IsSigned || y >= 0); if(y & 1) res *= x; y >>= 1; while(y) @@ -414,15 +555,6 @@ struct pow_default_impl } }; -template -struct pow_impl : pow_default_impl::IsInteger> {}; - -template -struct pow_retval -{ - typedef Scalar type; -}; - /**************************************************************************** * Implementation of random * ****************************************************************************/ @@ -458,48 +590,48 @@ struct random_default_impl }; enum { - floor_log2_terminate, - floor_log2_move_up, - floor_log2_move_down, - floor_log2_bogus + meta_floor_log2_terminate, + meta_floor_log2_move_up, + meta_floor_log2_move_down, + meta_floor_log2_bogus }; -template struct floor_log2_selector +template struct meta_floor_log2_selector { enum { middle = (lower + upper) / 2, - value = (upper <= lower + 1) ? int(floor_log2_terminate) - : (n < (1 << middle)) ? int(floor_log2_move_down) - : (n==0) ? int(floor_log2_bogus) - : int(floor_log2_move_up) + value = (upper <= lower + 1) ? int(meta_floor_log2_terminate) + : (n < (1 << middle)) ? int(meta_floor_log2_move_down) + : (n==0) ? int(meta_floor_log2_bogus) + : int(meta_floor_log2_move_up) }; }; template::value> -struct floor_log2 {}; + int selector = meta_floor_log2_selector::value> +struct meta_floor_log2 {}; template -struct floor_log2 +struct meta_floor_log2 { - enum { value = floor_log2::middle>::value }; + enum { value = meta_floor_log2::middle>::value }; }; template -struct floor_log2 +struct meta_floor_log2 { - enum { value = floor_log2::middle, upper>::value }; + enum { value = meta_floor_log2::middle, upper>::value }; }; template -struct floor_log2 +struct meta_floor_log2 { enum { value = (n >= ((unsigned int)(1) << (lower+1))) ? lower+1 : lower }; }; template -struct floor_log2 +struct meta_floor_log2 { // no value, error at compile time }; @@ -508,7 +640,7 @@ template struct random_default_impl { static inline Scalar run(const Scalar& x, const Scalar& y) - { + { typedef typename conditional::IsSigned,std::ptrdiff_t,std::size_t>::type ScalarX; if(y #ifdef EIGEN_MAKING_DOCS return run(Scalar(NumTraits::IsSigned ? -10 : 0), Scalar(10)); #else - enum { rand_bits = floor_log2<(unsigned int)(RAND_MAX)+1>::value, + enum { rand_bits = meta_floor_log2<(unsigned int)(RAND_MAX)+1>::value, scalar_bits = sizeof(Scalar) * CHAR_BIT, shift = EIGEN_PLAIN_ENUM_MAX(0, int(rand_bits) - int(scalar_bits)), offset = NumTraits::IsSigned ? (1 << (EIGEN_PLAIN_ENUM_MIN(rand_bits,scalar_bits)-1)) : 0 @@ -569,97 +701,601 @@ inline EIGEN_MATHFUNC_RETVAL(random, Scalar) random() return EIGEN_MATHFUNC_IMPL(random, Scalar)::run(); } +// Implementatin of is* functions + +// std::is* do not work with fast-math and gcc, std::is* are available on MSVC 2013 and newer, as well as in clang. +#if (EIGEN_HAS_CXX11_MATH && !(EIGEN_COMP_GNUC_STRICT && __FINITE_MATH_ONLY__)) || (EIGEN_COMP_MSVC>=1800) || (EIGEN_COMP_CLANG) +#define EIGEN_USE_STD_FPCLASSIFY 1 +#else +#define EIGEN_USE_STD_FPCLASSIFY 0 +#endif + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isnan_impl(const T&) { return false; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isinf_impl(const T&) { return false; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if::value,bool>::type +isfinite_impl(const T&) { return true; } + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isfinite_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isfinite)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isfinite; + return isfinite EIGEN_NOT_A_MACRO (x); + #else + return x<=NumTraits::highest() && x>=NumTraits::lowest(); + #endif +} + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isinf_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isinf)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isinf; + return isinf EIGEN_NOT_A_MACRO (x); + #else + return x>NumTraits::highest() || x::lowest(); + #endif +} + +template +EIGEN_DEVICE_FUNC +typename internal::enable_if<(!internal::is_integral::value)&&(!NumTraits::IsComplex),bool>::type +isnan_impl(const T& x) +{ + #ifdef __CUDA_ARCH__ + return (::isnan)(x); + #elif EIGEN_USE_STD_FPCLASSIFY + using std::isnan; + return isnan EIGEN_NOT_A_MACRO (x); + #else + return x != x; + #endif +} + +#if (!EIGEN_USE_STD_FPCLASSIFY) + +#if EIGEN_COMP_MSVC + +template EIGEN_DEVICE_FUNC bool isinf_msvc_helper(T x) +{ + return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; +} + +//MSVC defines a _isnan builtin function, but for double only +EIGEN_DEVICE_FUNC inline bool isnan_impl(const long double& x) { return _isnan(x)!=0; } +EIGEN_DEVICE_FUNC inline bool isnan_impl(const double& x) { return _isnan(x)!=0; } +EIGEN_DEVICE_FUNC inline bool isnan_impl(const float& x) { return _isnan(x)!=0; } + +EIGEN_DEVICE_FUNC inline bool isinf_impl(const long double& x) { return isinf_msvc_helper(x); } +EIGEN_DEVICE_FUNC inline bool isinf_impl(const double& x) { return isinf_msvc_helper(x); } +EIGEN_DEVICE_FUNC inline bool isinf_impl(const float& x) { return isinf_msvc_helper(x); } + +#elif (defined __FINITE_MATH_ONLY__ && __FINITE_MATH_ONLY__ && EIGEN_COMP_GNUC) + +#if EIGEN_GNUC_AT_LEAST(5,0) + #define EIGEN_TMP_NOOPT_ATTRIB EIGEN_DEVICE_FUNC inline __attribute__((optimize("no-finite-math-only"))) +#else + // NOTE the inline qualifier and noinline attribute are both needed: the former is to avoid linking issue (duplicate symbol), + // while the second prevent too aggressive optimizations in fast-math mode: + #define EIGEN_TMP_NOOPT_ATTRIB EIGEN_DEVICE_FUNC inline __attribute__((noinline,optimize("no-finite-math-only"))) +#endif + +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const long double& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const double& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isnan_impl(const float& x) { return __builtin_isnan(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const double& x) { return __builtin_isinf(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const float& x) { return __builtin_isinf(x); } +template<> EIGEN_TMP_NOOPT_ATTRIB bool isinf_impl(const long double& x) { return __builtin_isinf(x); } + +#undef EIGEN_TMP_NOOPT_ATTRIB + +#endif + +#endif + +// The following overload are defined at the end of this file +template EIGEN_DEVICE_FUNC bool isfinite_impl(const std::complex& x); +template EIGEN_DEVICE_FUNC bool isnan_impl(const std::complex& x); +template EIGEN_DEVICE_FUNC bool isinf_impl(const std::complex& x); + +template T generic_fast_tanh_float(const T& a_x); + } // end namespace internal /**************************************************************************** -* Generic math function * +* Generic math functions * ****************************************************************************/ namespace numext { +#ifndef __CUDA_ARCH__ +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +{ + EIGEN_USING_STD_MATH(min); + return min EIGEN_NOT_A_MACRO (x,y); +} + +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +{ + EIGEN_USING_STD_MATH(max); + return max EIGEN_NOT_A_MACRO (x,y); +} +#else +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T mini(const T& x, const T& y) +{ + return y < x ? y : x; +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE float mini(const float& x, const float& y) +{ + return fminf(x, y); +} +template +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE T maxi(const T& x, const T& y) +{ + return x < y ? y : x; +} +template<> +EIGEN_DEVICE_FUNC +EIGEN_ALWAYS_INLINE float maxi(const float& x, const float& y) +{ + return fmaxf(x, y); +} +#endif + + template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(real, Scalar) real(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(real, Scalar)::run(x); -} +} template +EIGEN_DEVICE_FUNC inline typename internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) >::type real_ref(const Scalar& x) { return internal::real_ref_impl::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(real_ref, Scalar) real_ref(Scalar& x) { return EIGEN_MATHFUNC_IMPL(real_ref, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(imag, Scalar) imag(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(imag, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(arg, Scalar) arg(const Scalar& x) +{ + return EIGEN_MATHFUNC_IMPL(arg, Scalar)::run(x); +} + +template +EIGEN_DEVICE_FUNC inline typename internal::add_const_on_value_type< EIGEN_MATHFUNC_RETVAL(imag_ref, Scalar) >::type imag_ref(const Scalar& x) { return internal::imag_ref_impl::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(imag_ref, Scalar) imag_ref(Scalar& x) { return EIGEN_MATHFUNC_IMPL(imag_ref, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(conj, Scalar) conj(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(conj, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(abs2, Scalar) abs2(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(abs2, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(norm1, Scalar) norm1(const Scalar& x) { return EIGEN_MATHFUNC_IMPL(norm1, Scalar)::run(x); } template +EIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(hypot, Scalar) hypot(const Scalar& x, const Scalar& y) { return EIGEN_MATHFUNC_IMPL(hypot, Scalar)::run(x, y); } template -inline EIGEN_MATHFUNC_RETVAL(atanh2, Scalar) atanh2(const Scalar& x, const Scalar& y) +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(log1p, Scalar) log1p(const Scalar& x) { - return EIGEN_MATHFUNC_IMPL(atanh2, Scalar)::run(x, y); + return EIGEN_MATHFUNC_IMPL(log1p, Scalar)::run(x); } +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float log1p(const float &x) { return ::log1pf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double log1p(const double &x) { return ::log1p(x); } +#endif + +template +EIGEN_DEVICE_FUNC +inline typename internal::pow_impl::result_type pow(const ScalarX& x, const ScalarY& y) +{ + return internal::pow_impl::run(x, y); +} + +template EIGEN_DEVICE_FUNC bool (isnan) (const T &x) { return internal::isnan_impl(x); } +template EIGEN_DEVICE_FUNC bool (isinf) (const T &x) { return internal::isinf_impl(x); } +template EIGEN_DEVICE_FUNC bool (isfinite)(const T &x) { return internal::isfinite_impl(x); } + template -inline EIGEN_MATHFUNC_RETVAL(pow, Scalar) pow(const Scalar& x, const Scalar& y) +EIGEN_DEVICE_FUNC +inline EIGEN_MATHFUNC_RETVAL(round, Scalar) round(const Scalar& x) { - return EIGEN_MATHFUNC_IMPL(pow, Scalar)::run(x, y); + return EIGEN_MATHFUNC_IMPL(round, Scalar)::run(x); } -// std::isfinite is non standard, so let's define our own version, -// even though it is not very efficient. -template bool (isfinite)(const T& x) +template +EIGEN_DEVICE_FUNC +T (floor)(const T& x) { - return x::highest() && x>NumTraits::lowest(); + EIGEN_USING_STD_MATH(floor); + return floor(x); } +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float floor(const float &x) { return ::floorf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double floor(const double &x) { return ::floor(x); } +#endif + +template +EIGEN_DEVICE_FUNC +T (ceil)(const T& x) +{ + EIGEN_USING_STD_MATH(ceil); + return ceil(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float ceil(const float &x) { return ::ceilf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double ceil(const double &x) { return ::ceil(x); } +#endif + + +/** Log base 2 for 32 bits positive integers. + * Conveniently returns 0 for x==0. */ +inline int log2(int x) +{ + eigen_assert(x>=0); + unsigned int v(x); + static const int table[32] = { 0, 9, 1, 10, 13, 21, 2, 29, 11, 14, 16, 18, 22, 25, 3, 30, 8, 12, 20, 28, 15, 17, 24, 7, 19, 27, 23, 6, 26, 5, 4, 31 }; + v |= v >> 1; + v |= v >> 2; + v |= v >> 4; + v |= v >> 8; + v |= v >> 16; + return table[(v * 0x07C4ACDDU) >> 27]; +} + +/** \returns the square root of \a x. + * + * It is essentially equivalent to \code using std::sqrt; return sqrt(x); \endcode, + * but slightly faster for float/double and some compilers (e.g., gcc), thanks to + * specializations when SSE is enabled. + * + * It's usage is justified in performance critical functions, like norm/normalize. + */ +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sqrt(const T &x) +{ + EIGEN_USING_STD_MATH(sqrt); + return sqrt(x); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T log(const T &x) { + EIGEN_USING_STD_MATH(log); + return log(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float log(const float &x) { return ::logf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double log(const double &x) { return ::log(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +typename internal::enable_if::IsSigned || NumTraits::IsComplex,typename NumTraits::Real>::type +abs(const T &x) { + EIGEN_USING_STD_MATH(abs); + return abs(x); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +typename internal::enable_if::IsSigned || NumTraits::IsComplex),typename NumTraits::Real>::type +abs(const T &x) { + return x; +} + +#if defined(__SYCL_DEVICE_ONLY__) +EIGEN_ALWAYS_INLINE float abs(float x) { return cl::sycl::fabs(x); } +EIGEN_ALWAYS_INLINE double abs(double x) { return cl::sycl::fabs(x); } +#endif // defined(__SYCL_DEVICE_ONLY__) + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float abs(const float &x) { return ::fabsf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double abs(const double &x) { return ::fabs(x); } + +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float abs(const std::complex& x) { + return ::hypotf(x.real(), x.imag()); +} + +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double abs(const std::complex& x) { + return ::hypot(x.real(), x.imag()); +} +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T exp(const T &x) { + EIGEN_USING_STD_MATH(exp); + return exp(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float exp(const float &x) { return ::expf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double exp(const double &x) { return ::exp(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T cos(const T &x) { + EIGEN_USING_STD_MATH(cos); + return cos(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float cos(const float &x) { return ::cosf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double cos(const double &x) { return ::cos(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sin(const T &x) { + EIGEN_USING_STD_MATH(sin); + return sin(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float sin(const float &x) { return ::sinf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double sin(const double &x) { return ::sin(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T tan(const T &x) { + EIGEN_USING_STD_MATH(tan); + return tan(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tan(const float &x) { return ::tanf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double tan(const double &x) { return ::tan(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T acos(const T &x) { + EIGEN_USING_STD_MATH(acos); + return acos(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float acos(const float &x) { return ::acosf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double acos(const double &x) { return ::acos(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T asin(const T &x) { + EIGEN_USING_STD_MATH(asin); + return asin(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float asin(const float &x) { return ::asinf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double asin(const double &x) { return ::asin(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T atan(const T &x) { + EIGEN_USING_STD_MATH(atan); + return atan(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float atan(const float &x) { return ::atanf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double atan(const double &x) { return ::atan(x); } +#endif + + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T cosh(const T &x) { + EIGEN_USING_STD_MATH(cosh); + return cosh(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float cosh(const float &x) { return ::coshf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double cosh(const double &x) { return ::cosh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T sinh(const T &x) { + EIGEN_USING_STD_MATH(sinh); + return sinh(x); +} + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float sinh(const float &x) { return ::sinhf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double sinh(const double &x) { return ::sinh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T tanh(const T &x) { + EIGEN_USING_STD_MATH(tanh); + return tanh(x); +} + +#if (!defined(__CUDACC__)) && EIGEN_FAST_MATH +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tanh(float x) { return internal::generic_fast_tanh_float(x); } +#endif + +#ifdef __CUDACC__ +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float tanh(const float &x) { return ::tanhf(x); } + +template<> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double tanh(const double &x) { return ::tanh(x); } +#endif + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T fmod(const T& a, const T& b) { + EIGEN_USING_STD_MATH(fmod); + return fmod(a, b); +} + +#ifdef __CUDACC__ +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float fmod(const float& a, const float& b) { + return ::fmodf(a, b); +} + +template <> +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double fmod(const double& a, const double& b) { + return ::fmod(a, b); +} +#endif + } // end namespace numext namespace internal { +template +EIGEN_DEVICE_FUNC bool isfinite_impl(const std::complex& x) +{ + return (numext::isfinite)(numext::real(x)) && (numext::isfinite)(numext::imag(x)); +} + +template +EIGEN_DEVICE_FUNC bool isnan_impl(const std::complex& x) +{ + return (numext::isnan)(numext::real(x)) || (numext::isnan)(numext::imag(x)); +} + +template +EIGEN_DEVICE_FUNC bool isinf_impl(const std::complex& x) +{ + return ((numext::isinf)(numext::real(x)) || (numext::isinf)(numext::imag(x))) && (!(numext::isnan)(x)); +} + /**************************************************************************** * Implementation of fuzzy comparisons * ****************************************************************************/ @@ -673,18 +1309,17 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, const RealScalar& prec) { - using std::abs; - return abs(x) <= abs(y) * prec; + return numext::abs(x) <= numext::abs(y) * prec; } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar& prec) { - using std::min; - using std::abs; - return abs(x - y) <= (min)(abs(x), abs(y)) * prec; + return numext::abs(x - y) <= numext::mini(numext::abs(x), numext::abs(y)) * prec; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, const RealScalar& prec) { return x <= y || isApprox(x, y, prec); @@ -695,15 +1330,17 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const Scalar&, const RealScalar&) { return x == Scalar(0); } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar&) { return x == y; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, const RealScalar&) { return x <= y; @@ -714,36 +1351,36 @@ template struct scalar_fuzzy_default_impl { typedef typename NumTraits::Real RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, const RealScalar& prec) { return numext::abs2(x) <= numext::abs2(y) * prec * prec; } + EIGEN_DEVICE_FUNC static inline bool isApprox(const Scalar& x, const Scalar& y, const RealScalar& prec) { - using std::min; - return numext::abs2(x - y) <= (min)(numext::abs2(x), numext::abs2(y)) * prec * prec; + return numext::abs2(x - y) <= numext::mini(numext::abs2(x), numext::abs2(y)) * prec * prec; } }; template struct scalar_fuzzy_impl : scalar_fuzzy_default_impl::IsComplex, NumTraits::IsInteger> {}; -template +template EIGEN_DEVICE_FUNC inline bool isMuchSmallerThan(const Scalar& x, const OtherScalar& y, const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { return scalar_fuzzy_impl::template isMuchSmallerThan(x, y, precision); } -template +template EIGEN_DEVICE_FUNC inline bool isApprox(const Scalar& x, const Scalar& y, const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { return scalar_fuzzy_impl::isApprox(x, y, precision); } -template +template EIGEN_DEVICE_FUNC inline bool isApproxOrLessThan(const Scalar& x, const Scalar& y, const typename NumTraits::Real &precision = NumTraits::dummy_precision()) { @@ -766,17 +1403,19 @@ template<> struct scalar_fuzzy_impl { typedef bool RealScalar; - template + template EIGEN_DEVICE_FUNC static inline bool isMuchSmallerThan(const bool& x, const bool&, const bool&) { return !x; } + EIGEN_DEVICE_FUNC static inline bool isApprox(bool x, bool y, bool) { return x == y; } + EIGEN_DEVICE_FUNC static inline bool isApproxOrLessThan(const bool& x, const bool& y, const bool&) { return (!x) || y; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctionsImpl.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctionsImpl.h new file mode 100644 index 000000000..3c9ef22fa --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MathFunctionsImpl.h @@ -0,0 +1,78 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Pedro Gonnet (pedro.gonnet@gmail.com) +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_MATHFUNCTIONSIMPL_H +#define EIGEN_MATHFUNCTIONSIMPL_H + +namespace Eigen { + +namespace internal { + +/** \internal \returns the hyperbolic tan of \a a (coeff-wise) + Doesn't do anything fancy, just a 13/6-degree rational interpolant which + is accurate up to a couple of ulp in the range [-9, 9], outside of which + the tanh(x) = +/-1. + + This implementation works on both scalars and packets. +*/ +template +T generic_fast_tanh_float(const T& a_x) +{ + // Clamp the inputs to the range [-9, 9] since anything outside + // this range is +/-1.0f in single-precision. + const T plus_9 = pset1(9.f); + const T minus_9 = pset1(-9.f); + // NOTE GCC prior to 6.3 might improperly optimize this max/min + // step such that if a_x is nan, x will be either 9 or -9, + // and tanh will return 1 or -1 instead of nan. + // This is supposed to be fixed in gcc6.3, + // see: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=72867 + const T x = pmax(minus_9,pmin(plus_9,a_x)); + // The monomial coefficients of the numerator polynomial (odd). + const T alpha_1 = pset1(4.89352455891786e-03f); + const T alpha_3 = pset1(6.37261928875436e-04f); + const T alpha_5 = pset1(1.48572235717979e-05f); + const T alpha_7 = pset1(5.12229709037114e-08f); + const T alpha_9 = pset1(-8.60467152213735e-11f); + const T alpha_11 = pset1(2.00018790482477e-13f); + const T alpha_13 = pset1(-2.76076847742355e-16f); + + // The monomial coefficients of the denominator polynomial (even). + const T beta_0 = pset1(4.89352518554385e-03f); + const T beta_2 = pset1(2.26843463243900e-03f); + const T beta_4 = pset1(1.18534705686654e-04f); + const T beta_6 = pset1(1.19825839466702e-06f); + + // Since the polynomials are odd/even, we need x^2. + const T x2 = pmul(x, x); + + // Evaluate the numerator polynomial p. + T p = pmadd(x2, alpha_13, alpha_11); + p = pmadd(x2, p, alpha_9); + p = pmadd(x2, p, alpha_7); + p = pmadd(x2, p, alpha_5); + p = pmadd(x2, p, alpha_3); + p = pmadd(x2, p, alpha_1); + p = pmul(x, p); + + // Evaluate the denominator polynomial p. + T q = pmadd(x2, beta_6, beta_4); + q = pmadd(x2, q, beta_2); + q = pmadd(x2, q, beta_0); + + // Divide the numerator by the denominator. + return pdiv(p, q); +} + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_MATHFUNCTIONSIMPL_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h index 02be142d8..90c336d8c 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Matrix.h @@ -13,6 +13,45 @@ namespace Eigen { +namespace internal { +template +struct traits > +{ +private: + enum { size = internal::size_at_compile_time<_Rows,_Cols>::ret }; + typedef typename find_best_packet<_Scalar,size>::type PacketScalar; + enum { + row_major_bit = _Options&RowMajor ? RowMajorBit : 0, + is_dynamic_size_storage = _MaxRows==Dynamic || _MaxCols==Dynamic, + max_size = is_dynamic_size_storage ? Dynamic : _MaxRows*_MaxCols, + default_alignment = compute_default_alignment<_Scalar,max_size>::value, + actual_alignment = ((_Options&DontAlign)==0) ? default_alignment : 0, + required_alignment = unpacket_traits::alignment, + packet_access_bit = (packet_traits<_Scalar>::Vectorizable && (EIGEN_UNALIGNED_VECTORIZE || (actual_alignment>=required_alignment))) ? PacketAccessBit : 0 + }; + +public: + typedef _Scalar Scalar; + typedef Dense StorageKind; + typedef Eigen::Index StorageIndex; + typedef MatrixXpr XprKind; + enum { + RowsAtCompileTime = _Rows, + ColsAtCompileTime = _Cols, + MaxRowsAtCompileTime = _MaxRows, + MaxColsAtCompileTime = _MaxCols, + Flags = compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, + Options = _Options, + InnerStrideAtCompileTime = 1, + OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime, + + // FIXME, the following flag in only used to define NeedsToAlign in PlainObjectBase + EvaluatorFlags = LinearAccessBit | DirectAccessBit | packet_access_bit | row_major_bit, + Alignment = actual_alignment + }; +}; +} + /** \class Matrix * \ingroup Core_Module * @@ -24,13 +63,13 @@ namespace Eigen { * The %Matrix class encompasses \em both fixed-size and dynamic-size objects (\ref fixedsize "note"). * * The first three template parameters are required: - * \tparam _Scalar \anchor matrix_tparam_scalar Numeric type, e.g. float, double, int or std::complex. - * User defined sclar types are supported as well (see \ref user_defined_scalars "here"). + * \tparam _Scalar Numeric type, e.g. float, double, int or std::complex. + * User defined scalar types are supported as well (see \ref user_defined_scalars "here"). * \tparam _Rows Number of rows, or \b Dynamic * \tparam _Cols Number of columns, or \b Dynamic * * The remaining template parameters are optional -- in most cases you don't have to worry about them. - * \tparam _Options \anchor matrix_tparam_options A combination of either \b #RowMajor or \b #ColMajor, and of either + * \tparam _Options A combination of either \b #RowMajor or \b #ColMajor, and of either * \b #AutoAlign or \b #DontAlign. * The former controls \ref TopicStorageOrders "storage order", and defaults to column-major. The latter controls alignment, which is required * for vectorization. It defaults to aligning matrices except for fixed sizes that aren't a multiple of the packet size. @@ -67,7 +106,7 @@ namespace Eigen { * \endcode * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_MATRIX_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_MATRIX_PLUGIN. * * Some notes: * @@ -97,32 +136,44 @@ namespace Eigen { * are the dimensions of the original matrix, while _Rows and _Cols are Dynamic. * * - * \see MatrixBase for the majority of the API methods for matrices, \ref TopicClassHierarchy, - * \ref TopicStorageOrders + * ABI and storage layout + * + * The table below summarizes the ABI of some possible Matrix instances which is fixed thorough the lifetime of Eigen 3. + * + * + * + * + * + * + *
Matrix typeEquivalent C structure
\code Matrix \endcode\code + * struct { + * T *data; // with (size_t(data)%EIGEN_MAX_ALIGN_BYTES)==0 + * Eigen::Index rows, cols; + * }; + * \endcode
\code + * Matrix + * Matrix \endcode\code + * struct { + * T *data; // with (size_t(data)%EIGEN_MAX_ALIGN_BYTES)==0 + * Eigen::Index size; + * }; + * \endcode
\code Matrix \endcode\code + * struct { + * T data[Rows*Cols]; // with (size_t(data)%A(Rows*Cols*sizeof(T)))==0 + * }; + * \endcode
\code Matrix \endcode\code + * struct { + * T data[MaxRows*MaxCols]; // with (size_t(data)%A(MaxRows*MaxCols*sizeof(T)))==0 + * Eigen::Index rows, cols; + * }; + * \endcode
+ * Note that in this table Rows, Cols, MaxRows and MaxCols are all positive integers. A(S) is defined to the largest possible power-of-two + * smaller to EIGEN_MAX_STATIC_ALIGN_BYTES. + * + * \see MatrixBase for the majority of the API methods for matrices, \ref TopicClassHierarchy, + * \ref TopicStorageOrders */ -namespace internal { -template -struct traits > -{ - typedef _Scalar Scalar; - typedef Dense StorageKind; - typedef DenseIndex Index; - typedef MatrixXpr XprKind; - enum { - RowsAtCompileTime = _Rows, - ColsAtCompileTime = _Cols, - MaxRowsAtCompileTime = _MaxRows, - MaxColsAtCompileTime = _MaxCols, - Flags = compute_matrix_flags<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>::ret, - CoeffReadCost = NumTraits::ReadCost, - Options = _Options, - InnerStrideAtCompileTime = 1, - OuterStrideAtCompileTime = (Options&RowMajor) ? ColsAtCompileTime : RowsAtCompileTime - }; -}; -} - template class Matrix : public PlainObjectBase > @@ -151,6 +202,7 @@ class Matrix * * \callgraph */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const Matrix& other) { return Base::_set(other); @@ -167,7 +219,8 @@ class Matrix * remain row-vectors and vectors remain vectors. */ template - EIGEN_STRONG_INLINE Matrix& operator=(const MatrixBase& other) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Matrix& operator=(const DenseBase& other) { return Base::_set(other); } @@ -179,12 +232,14 @@ class Matrix * \copydetails DenseBase::operator=(const EigenBase &other) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const EigenBase &other) { return Base::operator=(other); } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix& operator=(const ReturnByValue& func) { return Base::operator=(func); @@ -200,6 +255,7 @@ class Matrix * * \sa resize(Index,Index) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix() : Base() { Base::_check_template_params(); @@ -207,60 +263,87 @@ class Matrix } // FIXME is it still needed - Matrix(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + explicit Matrix(internal::constructor_without_unaligned_array_assert) : Base(internal::constructor_without_unaligned_array_assert()) { Base::_check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - Matrix(Matrix&& other) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + Matrix(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible::value) : Base(std::move(other)) { Base::_check_template_params(); if (RowsAtCompileTime!=Dynamic && ColsAtCompileTime!=Dynamic) Base::_set_noalias(other); } - Matrix& operator=(Matrix&& other) + EIGEN_DEVICE_FUNC + Matrix& operator=(Matrix&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable::value) { other.swap(*this); return *this; } #endif - /** \brief Constructs a vector or row-vector with given dimension. \only_for_vectors - * - * Note that this is only useful for dynamic-size vectors. For fixed-size vectors, - * it is redundant to pass the dimension here, so it makes more sense to use the default - * constructor Matrix() instead. - */ - EIGEN_STRONG_INLINE explicit Matrix(Index dim) - : Base(dim, RowsAtCompileTime == 1 ? 1 : dim, ColsAtCompileTime == 1 ? 1 : dim) + #ifndef EIGEN_PARSED_BY_DOXYGEN + + // This constructor is for both 1x1 matrices and dynamic vectors + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit Matrix(const T& x) { Base::_check_template_params(); - EIGEN_STATIC_ASSERT_VECTOR_ONLY(Matrix) - eigen_assert(dim >= 0); - eigen_assert(SizeAtCompileTime == Dynamic || SizeAtCompileTime == dim); - EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + Base::template _init1(x); } - #ifndef EIGEN_PARSED_BY_DOXYGEN template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const T0& x, const T1& y) { Base::_check_template_params(); Base::template _init2(x, y); } #else + /** \brief Constructs a fixed-sized matrix initialized with coefficients starting at \a data */ + EIGEN_DEVICE_FUNC + explicit Matrix(const Scalar *data); + + /** \brief Constructs a vector or row-vector with given dimension. \only_for_vectors + * + * This is useful for dynamic-size vectors. For fixed-size vectors, + * it is redundant to pass these parameters, so one should use the default constructor + * Matrix() instead. + * + * \warning This constructor is disabled for fixed-size \c 1x1 matrices. For instance, + * calling Matrix(1) will call the initialization constructor: Matrix(const Scalar&). + * For fixed-size \c 1x1 matrices it is therefore recommended to use the default + * constructor Matrix() instead, especially when using one of the non standard + * \c EIGEN_INITIALIZE_MATRICES_BY_{ZERO,\c NAN} macros (see \ref TopicPreprocessorDirectives). + */ + EIGEN_STRONG_INLINE explicit Matrix(Index dim); + /** \brief Constructs an initialized 1x1 matrix with the given coefficient */ + Matrix(const Scalar& x); /** \brief Constructs an uninitialized matrix with \a rows rows and \a cols columns. * * This is useful for dynamic-size matrices. For fixed-size matrices, * it is redundant to pass these parameters, so one should use the default constructor - * Matrix() instead. */ + * Matrix() instead. + * + * \warning This constructor is disabled for fixed-size \c 1x2 and \c 2x1 vectors. For instance, + * calling Matrix2f(2,1) will call the initialization constructor: Matrix(const Scalar& x, const Scalar& y). + * For fixed-size \c 1x2 or \c 2x1 vectors it is therefore recommended to use the default + * constructor Matrix() instead, especially when using one of the non standard + * \c EIGEN_INITIALIZE_MATRICES_BY_{ZERO,\c NAN} macros (see \ref TopicPreprocessorDirectives). + */ + EIGEN_DEVICE_FUNC Matrix(Index rows, Index cols); + /** \brief Constructs an initialized 2D vector with given coefficients */ Matrix(const Scalar& x, const Scalar& y); #endif /** \brief Constructs an initialized 3D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z) { Base::_check_template_params(); @@ -270,6 +353,7 @@ class Matrix m_storage.data()[2] = z; } /** \brief Constructs an initialized 4D vector with given coefficients */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const Scalar& x, const Scalar& y, const Scalar& z, const Scalar& w) { Base::_check_template_params(); @@ -280,76 +364,33 @@ class Matrix m_storage.data()[3] = w; } - explicit Matrix(const Scalar *data); - /** \brief Constructor copying the value of the expression \a other */ - template - EIGEN_STRONG_INLINE Matrix(const MatrixBase& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - // This test resides here, to bring the error messages closer to the user. Normally, these checks - // are performed deeply within the library, thus causing long and scary error traces. - EIGEN_STATIC_ASSERT((internal::is_same::value), - YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY) - - Base::_check_template_params(); - Base::_set_noalias(other); - } /** \brief Copy constructor */ - EIGEN_STRONG_INLINE Matrix(const Matrix& other) - : Base(other.rows() * other.cols(), other.rows(), other.cols()) - { - Base::_check_template_params(); - Base::_set_noalias(other); - } - /** \brief Copy constructor with in-place evaluation */ - template - EIGEN_STRONG_INLINE Matrix(const ReturnByValue& other) - { - Base::_check_template_params(); - Base::resize(other.rows(), other.cols()); - other.evalTo(*this); - } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Matrix(const Matrix& other) : Base(other) + { } /** \brief Copy constructor for generic expressions. * \sa MatrixBase::operator=(const EigenBase&) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Matrix(const EigenBase &other) - : Base(other.derived().rows() * other.derived().cols(), other.derived().rows(), other.derived().cols()) - { - Base::_check_template_params(); - Base::_resize_to_match(other); - // FIXME/CHECK: isn't *this = other.derived() more efficient. it allows to - // go for pure _set() implementations, right? - *this = other; - } + : Base(other.derived()) + { } - /** \internal - * \brief Override MatrixBase::swap() since for dynamic-sized matrices - * of same type it is enough to swap the data pointers. - */ - template - void swap(MatrixBase const & other) - { this->_swap(other.derived()); } - - inline Index innerStride() const { return 1; } - inline Index outerStride() const { return this->innerSize(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return 1; } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return this->innerSize(); } /////////// Geometry module /////////// template + EIGEN_DEVICE_FUNC explicit Matrix(const RotationBase& r); template + EIGEN_DEVICE_FUNC Matrix& operator=(const RotationBase& r); - #ifdef EIGEN2_SUPPORT - template - explicit Matrix(const eigen2_RotationBase& r); - template - Matrix& operator=(const eigen2_RotationBase& r); - #endif - // allow to extend Matrix outside Eigen #ifdef EIGEN_MATRIX_PLUGIN #include EIGEN_MATRIX_PLUGIN diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h index e83ef4dc0..ce412180a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/MatrixBase.h @@ -41,9 +41,9 @@ namespace Eigen { * \endcode * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_MATRIXBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_MATRIXBASE_PLUGIN. * - * \sa \ref TopicClassHierarchy + * \sa \blank \ref TopicClassHierarchy */ template class MatrixBase : public DenseBase @@ -52,7 +52,7 @@ template class MatrixBase #ifndef EIGEN_PARSED_BY_DOXYGEN typedef MatrixBase StorageBaseType; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; + typedef typename internal::traits::StorageIndex StorageIndex; typedef typename internal::traits::Scalar Scalar; typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; @@ -66,7 +66,6 @@ template class MatrixBase using Base::MaxSizeAtCompileTime; using Base::IsVectorAtCompileTime; using Base::Flags; - using Base::CoeffReadCost; using Base::derived; using Base::const_cast_derived; @@ -98,25 +97,14 @@ template class MatrixBase /** \returns the size of the main diagonal, which is min(rows(),cols()). * \sa rows(), cols(), SizeAtCompileTime. */ - inline Index diagonalSize() const { return (std::min)(rows(),cols()); } + EIGEN_DEVICE_FUNC + inline Index diagonalSize() const { return (numext::mini)(rows(),cols()); } - /** \brief The plain matrix type corresponding to this expression. - * - * This is not necessarily exactly the return type of eval(). In the case of plain matrices, - * the return type of eval() is a const reference to a matrix, not a matrix! It is however guaranteed - * that the return type of eval() is either PlainObject or const PlainObject&. - */ - typedef Matrix::Scalar, - internal::traits::RowsAtCompileTime, - internal::traits::ColsAtCompileTime, - AutoAlign | (internal::traits::Flags&RowMajorBit ? RowMajor : ColMajor), - internal::traits::MaxRowsAtCompileTime, - internal::traits::MaxColsAtCompileTime - > PlainObject; + typedef typename Base::PlainObject PlainObject; #ifndef EIGEN_PARSED_BY_DOXYGEN /** \internal Represents a matrix with all coefficients equal to one another*/ - typedef CwiseNullaryOp,Derived> ConstantReturnType; + typedef CwiseNullaryOp,PlainObject> ConstantReturnType; /** \internal the return type of MatrixBase::adjoint() */ typedef typename internal::conditional::IsComplex, CwiseUnaryOp, ConstTransposeReturnType>, @@ -125,7 +113,7 @@ template class MatrixBase /** \internal Return type of eigenvalues() */ typedef Matrix, internal::traits::ColsAtCompileTime, 1, ColMajor> EigenvaluesReturnType; /** \internal the return type of identity */ - typedef CwiseNullaryOp,Derived> IdentityReturnType; + typedef CwiseNullaryOp,PlainObject> IdentityReturnType; /** \internal the return type of unit vectors */ typedef Block, SquareMatrixType>, internal::traits::RowsAtCompileTime, @@ -133,6 +121,7 @@ template class MatrixBase #endif // not EIGEN_PARSED_BY_DOXYGEN #define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::MatrixBase +#define EIGEN_DOC_UNARY_ADDONS(X,Y) # include "../plugins/CommonCwiseUnaryOps.h" # include "../plugins/CommonCwiseBinaryOps.h" # include "../plugins/MatrixCwiseUnaryOps.h" @@ -141,41 +130,53 @@ template class MatrixBase # include EIGEN_MATRIXBASE_PLUGIN # endif #undef EIGEN_CURRENT_STORAGE_BASE_CLASS +#undef EIGEN_DOC_UNARY_ADDONS /** Special case of the template operator=, in order to prevent the compiler * from generating a default operator= (issue hit with g++ 4.1) */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const MatrixBase& other); // We cannot inherit here via Base::operator= since it is causing // trouble with MSVC. template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const DenseBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const EigenBase& other); template + EIGEN_DEVICE_FUNC Derived& operator=(const ReturnByValue& other); - template - Derived& lazyAssign(const ProductBase& other); - - template - Derived& lazyAssign(const MatrixPowerProduct& other); - template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator+=(const MatrixBase& other); template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator-=(const MatrixBase& other); +#ifdef __CUDACC__ template - const typename ProductReturnType::Type - operator*(const MatrixBase &other) const; + EIGEN_DEVICE_FUNC + const Product + operator*(const MatrixBase &other) const + { return this->lazyProduct(other); } +#else template - const typename LazyProductReturnType::Type + const Product + operator*(const MatrixBase &other) const; + +#endif + + template + EIGEN_DEVICE_FUNC + const Product lazyProduct(const MatrixBase &other) const; template @@ -188,84 +189,93 @@ template class MatrixBase void applyOnTheRight(const EigenBase& other); template - const DiagonalProduct + EIGEN_DEVICE_FUNC + const Product operator*(const DiagonalBase &diagonal) const; template - typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType + EIGEN_DEVICE_FUNC + typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType dot(const MatrixBase& other) const; - #ifdef EIGEN2_SUPPORT - template - Scalar eigen2_dot(const MatrixBase& other) const; - #endif - - RealScalar squaredNorm() const; - RealScalar norm() const; + EIGEN_DEVICE_FUNC RealScalar squaredNorm() const; + EIGEN_DEVICE_FUNC RealScalar norm() const; RealScalar stableNorm() const; RealScalar blueNorm() const; RealScalar hypotNorm() const; - const PlainObject normalized() const; - void normalize(); + EIGEN_DEVICE_FUNC const PlainObject normalized() const; + EIGEN_DEVICE_FUNC const PlainObject stableNormalized() const; + EIGEN_DEVICE_FUNC void normalize(); + EIGEN_DEVICE_FUNC void stableNormalize(); - const AdjointReturnType adjoint() const; - void adjointInPlace(); + EIGEN_DEVICE_FUNC const AdjointReturnType adjoint() const; + EIGEN_DEVICE_FUNC void adjointInPlace(); typedef Diagonal DiagonalReturnType; + EIGEN_DEVICE_FUNC DiagonalReturnType diagonal(); + typedef typename internal::add_const >::type ConstDiagonalReturnType; + EIGEN_DEVICE_FUNC ConstDiagonalReturnType diagonal() const; template struct DiagonalIndexReturnType { typedef Diagonal Type; }; template struct ConstDiagonalIndexReturnType { typedef const Diagonal Type; }; - template typename DiagonalIndexReturnType::Type diagonal(); - template typename ConstDiagonalIndexReturnType::Type diagonal() const; - + template + EIGEN_DEVICE_FUNC + typename DiagonalIndexReturnType::Type diagonal(); + + template + EIGEN_DEVICE_FUNC + typename ConstDiagonalIndexReturnType::Type diagonal() const; + typedef Diagonal DiagonalDynamicIndexReturnType; typedef typename internal::add_const >::type ConstDiagonalDynamicIndexReturnType; + EIGEN_DEVICE_FUNC DiagonalDynamicIndexReturnType diagonal(Index index); + EIGEN_DEVICE_FUNC ConstDiagonalDynamicIndexReturnType diagonal(Index index) const; - #ifdef EIGEN2_SUPPORT - template typename internal::eigen2_part_return_type::type part(); - template const typename internal::eigen2_part_return_type::type part() const; - - // huuuge hack. make Eigen2's matrix.part() work in eigen3. Problem: Diagonal is now a class template instead - // of an integer constant. Solution: overload the part() method template wrt template parameters list. - template class U> - const DiagonalWrapper part() const - { return diagonal().asDiagonal(); } - #endif // EIGEN2_SUPPORT - template struct TriangularViewReturnType { typedef TriangularView Type; }; template struct ConstTriangularViewReturnType { typedef const TriangularView Type; }; - template typename TriangularViewReturnType::Type triangularView(); - template typename ConstTriangularViewReturnType::Type triangularView() const; + template + EIGEN_DEVICE_FUNC + typename TriangularViewReturnType::Type triangularView(); + template + EIGEN_DEVICE_FUNC + typename ConstTriangularViewReturnType::Type triangularView() const; template struct SelfAdjointViewReturnType { typedef SelfAdjointView Type; }; template struct ConstSelfAdjointViewReturnType { typedef const SelfAdjointView Type; }; - template typename SelfAdjointViewReturnType::Type selfadjointView(); - template typename ConstSelfAdjointViewReturnType::Type selfadjointView() const; + template + EIGEN_DEVICE_FUNC + typename SelfAdjointViewReturnType::Type selfadjointView(); + template + EIGEN_DEVICE_FUNC + typename ConstSelfAdjointViewReturnType::Type selfadjointView() const; const SparseView sparseView(const Scalar& m_reference = Scalar(0), const typename NumTraits::Real& m_epsilon = NumTraits::dummy_precision()) const; - static const IdentityReturnType Identity(); - static const IdentityReturnType Identity(Index rows, Index cols); - static const BasisReturnType Unit(Index size, Index i); - static const BasisReturnType Unit(Index i); - static const BasisReturnType UnitX(); - static const BasisReturnType UnitY(); - static const BasisReturnType UnitZ(); - static const BasisReturnType UnitW(); + EIGEN_DEVICE_FUNC static const IdentityReturnType Identity(); + EIGEN_DEVICE_FUNC static const IdentityReturnType Identity(Index rows, Index cols); + EIGEN_DEVICE_FUNC static const BasisReturnType Unit(Index size, Index i); + EIGEN_DEVICE_FUNC static const BasisReturnType Unit(Index i); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitX(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitY(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitZ(); + EIGEN_DEVICE_FUNC static const BasisReturnType UnitW(); + EIGEN_DEVICE_FUNC const DiagonalWrapper asDiagonal() const; const PermutationWrapper asPermutation() const; + EIGEN_DEVICE_FUNC Derived& setIdentity(); + EIGEN_DEVICE_FUNC Derived& setIdentity(Index rows, Index cols); bool isIdentity(const RealScalar& prec = NumTraits::dummy_precision()) const; @@ -284,7 +294,7 @@ template class MatrixBase * fuzzy comparison such as isApprox() * \sa isApprox(), operator!= */ template - inline bool operator==(const MatrixBase& other) const + EIGEN_DEVICE_FUNC inline bool operator==(const MatrixBase& other) const { return cwiseEqual(other).all(); } /** \returns true if at least one pair of coefficients of \c *this and \a other are not exactly equal to each other. @@ -292,64 +302,50 @@ template class MatrixBase * fuzzy comparison such as isApprox() * \sa isApprox(), operator== */ template - inline bool operator!=(const MatrixBase& other) const + EIGEN_DEVICE_FUNC inline bool operator!=(const MatrixBase& other) const { return cwiseNotEqual(other).any(); } NoAlias noalias(); - inline const ForceAlignedAccess forceAlignedAccess() const; - inline ForceAlignedAccess forceAlignedAccess(); - template inline typename internal::add_const_on_value_type,Derived&>::type>::type forceAlignedAccessIf() const; - template inline typename internal::conditional,Derived&>::type forceAlignedAccessIf(); + // TODO forceAlignedAccess is temporarily disabled + // Need to find a nicer workaround. + inline const Derived& forceAlignedAccess() const { return derived(); } + inline Derived& forceAlignedAccess() { return derived(); } + template inline const Derived& forceAlignedAccessIf() const { return derived(); } + template inline Derived& forceAlignedAccessIf() { return derived(); } - Scalar trace() const; + EIGEN_DEVICE_FUNC Scalar trace() const; -/////////// Array module /////////// + template EIGEN_DEVICE_FUNC RealScalar lpNorm() const; - template RealScalar lpNorm() const; - - MatrixBase& matrix() { return *this; } - const MatrixBase& matrix() const { return *this; } + EIGEN_DEVICE_FUNC MatrixBase& matrix() { return *this; } + EIGEN_DEVICE_FUNC const MatrixBase& matrix() const { return *this; } /** \returns an \link Eigen::ArrayBase Array \endlink expression of this matrix * \sa ArrayBase::matrix() */ - ArrayWrapper array() { return derived(); } - const ArrayWrapper array() const { return derived(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ArrayWrapper array() { return ArrayWrapper(derived()); } + /** \returns a const \link Eigen::ArrayBase Array \endlink expression of this matrix + * \sa ArrayBase::matrix() */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const ArrayWrapper array() const { return ArrayWrapper(derived()); } /////////// LU module /////////// - const FullPivLU fullPivLu() const; - const PartialPivLU partialPivLu() const; + inline const FullPivLU fullPivLu() const; + inline const PartialPivLU partialPivLu() const; - #if EIGEN2_SUPPORT_STAGE < STAGE20_RESOLVE_API_CONFLICTS - const LU lu() const; - #endif + inline const PartialPivLU lu() const; - #ifdef EIGEN2_SUPPORT - const LU eigen2_lu() const; - #endif + inline const Inverse inverse() const; - #if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - const PartialPivLU lu() const; - #endif - - #ifdef EIGEN2_SUPPORT template - void computeInverse(MatrixBase *result) const { - *result = this->inverse(); - } - #endif - - const internal::inverse_impl inverse() const; - template - void computeInverseAndDetWithCheck( + inline void computeInverseAndDetWithCheck( ResultType& inverse, typename ResultType::Scalar& determinant, bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() ) const; template - void computeInverseWithCheck( + inline void computeInverseWithCheck( ResultType& inverse, bool& invertible, const RealScalar& absDeterminantThreshold = NumTraits::dummy_precision() @@ -358,65 +354,70 @@ template class MatrixBase /////////// Cholesky module /////////// - const LLT llt() const; - const LDLT ldlt() const; + inline const LLT llt() const; + inline const LDLT ldlt() const; /////////// QR module /////////// - const HouseholderQR householderQr() const; - const ColPivHouseholderQR colPivHouseholderQr() const; - const FullPivHouseholderQR fullPivHouseholderQr() const; - - #ifdef EIGEN2_SUPPORT - const QR qr() const; - #endif + inline const HouseholderQR householderQr() const; + inline const ColPivHouseholderQR colPivHouseholderQr() const; + inline const FullPivHouseholderQR fullPivHouseholderQr() const; + inline const CompleteOrthogonalDecomposition completeOrthogonalDecomposition() const; - EigenvaluesReturnType eigenvalues() const; - RealScalar operatorNorm() const; +/////////// Eigenvalues module /////////// + + inline EigenvaluesReturnType eigenvalues() const; + inline RealScalar operatorNorm() const; /////////// SVD module /////////// - JacobiSVD jacobiSvd(unsigned int computationOptions = 0) const; - - #ifdef EIGEN2_SUPPORT - SVD svd() const; - #endif + inline JacobiSVD jacobiSvd(unsigned int computationOptions = 0) const; + inline BDCSVD bdcSvd(unsigned int computationOptions = 0) const; /////////// Geometry module /////////// #ifndef EIGEN_PARSED_BY_DOXYGEN /// \internal helper struct to form the return type of the cross product template struct cross_product_return_type { - typedef typename internal::scalar_product_traits::Scalar,typename internal::traits::Scalar>::ReturnType Scalar; + typedef typename ScalarBinaryOpTraits::Scalar,typename internal::traits::Scalar>::ReturnType Scalar; typedef Matrix type; }; #endif // EIGEN_PARSED_BY_DOXYGEN template - typename cross_product_return_type::type + EIGEN_DEVICE_FUNC +#ifndef EIGEN_PARSED_BY_DOXYGEN + inline typename cross_product_return_type::type +#else + inline PlainObject +#endif cross(const MatrixBase& other) const; + template - PlainObject cross3(const MatrixBase& other) const; - PlainObject unitOrthogonal(void) const; - Matrix eulerAngles(Index a0, Index a1, Index a2) const; - - #if EIGEN2_SUPPORT_STAGE > STAGE20_RESOLVE_API_CONFLICTS - ScalarMultipleReturnType operator*(const UniformScaling& s) const; + EIGEN_DEVICE_FUNC + inline PlainObject cross3(const MatrixBase& other) const; + + EIGEN_DEVICE_FUNC + inline PlainObject unitOrthogonal(void) const; + + EIGEN_DEVICE_FUNC + inline Matrix eulerAngles(Index a0, Index a1, Index a2) const; + // put this as separate enum value to work around possible GCC 4.3 bug (?) - enum { HomogeneousReturnTypeDirection = ColsAtCompileTime==1?Vertical:Horizontal }; + enum { HomogeneousReturnTypeDirection = ColsAtCompileTime==1&&RowsAtCompileTime==1 ? ((internal::traits::Flags&RowMajorBit)==RowMajorBit ? Horizontal : Vertical) + : ColsAtCompileTime==1 ? Vertical : Horizontal }; typedef Homogeneous HomogeneousReturnType; - HomogeneousReturnType homogeneous() const; - #endif - + EIGEN_DEVICE_FUNC + inline HomogeneousReturnType homogeneous() const; + enum { SizeMinusOne = SizeAtCompileTime==Dynamic ? Dynamic : SizeAtCompileTime-1 }; typedef Block::ColsAtCompileTime==1 ? SizeMinusOne : 1, internal::traits::ColsAtCompileTime==1 ? 1 : SizeMinusOne> ConstStartMinusOne; - typedef CwiseUnaryOp::Scalar>, - const ConstStartMinusOne > HNormalizedReturnType; - - const HNormalizedReturnType hnormalized() const; + typedef EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(ConstStartMinusOne,Scalar,quotient) HNormalizedReturnType; + EIGEN_DEVICE_FUNC + inline const HNormalizedReturnType hnormalized() const; ////////// Householder module /////////// @@ -461,49 +462,15 @@ template class MatrixBase const MatrixSquareRootReturnValue sqrt() const; const MatrixLogarithmReturnValue log() const; const MatrixPowerReturnValue pow(const RealScalar& p) const; - -#ifdef EIGEN2_SUPPORT - template - Derived& operator+=(const Flagged, 0, - EvalBeforeAssigningBit>& other); - - template - Derived& operator-=(const Flagged, 0, - EvalBeforeAssigningBit>& other); - - /** \deprecated because .lazy() is deprecated - * Overloaded for cache friendly product evaluation */ - template - Derived& lazyAssign(const Flagged& other) - { return lazyAssign(other._expression()); } - - template - const Flagged marked() const; - const Flagged lazy() const; - - inline const Cwise cwise() const; - inline Cwise cwise(); - - VectorBlock start(Index size); - const VectorBlock start(Index size) const; - VectorBlock end(Index size); - const VectorBlock end(Index size) const; - template VectorBlock start(); - template const VectorBlock start() const; - template VectorBlock end(); - template const VectorBlock end() const; - - Minor minor(Index row, Index col); - const Minor minor(Index row, Index col) const; -#endif + const MatrixComplexPowerReturnValue pow(const std::complex& p) const; protected: - MatrixBase() : Base() {} + EIGEN_DEVICE_FUNC MatrixBase() : Base() {} private: - explicit MatrixBase(int); - MatrixBase(int,int); - template explicit MatrixBase(const MatrixBase&); + EIGEN_DEVICE_FUNC explicit MatrixBase(int); + EIGEN_DEVICE_FUNC MatrixBase(int,int); + template EIGEN_DEVICE_FUNC explicit MatrixBase(const MatrixBase&); protected: // mixing arrays and matrices is not legal template Derived& operator+=(const ArrayBase& ) diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h index a893b1761..13adf070e 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NestByValue.h @@ -13,25 +13,24 @@ namespace Eigen { -/** \class NestByValue - * \ingroup Core_Module - * - * \brief Expression which must be nested by value - * - * \param ExpressionType the type of the object of which we are requiring nesting-by-value - * - * This class is the return type of MatrixBase::nestByValue() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::nestByValue() - */ - namespace internal { template struct traits > : public traits {}; } +/** \class NestByValue + * \ingroup Core_Module + * + * \brief Expression which must be nested by value + * + * \tparam ExpressionType the type of the object of which we are requiring nesting-by-value + * + * This class is the return type of MatrixBase::nestByValue() + * and most of the time this is the only way it is used. + * + * \sa MatrixBase::nestByValue() + */ template class NestByValue : public internal::dense_xpr_base< NestByValue >::type { @@ -40,29 +39,29 @@ template class NestByValue typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(NestByValue) - inline NestByValue(const ExpressionType& matrix) : m_expression(matrix) {} + EIGEN_DEVICE_FUNC explicit inline NestByValue(const ExpressionType& matrix) : m_expression(matrix) {} - inline Index rows() const { return m_expression.rows(); } - inline Index cols() const { return m_expression.cols(); } - inline Index outerStride() const { return m_expression.outerStride(); } - inline Index innerStride() const { return m_expression.innerStride(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_expression.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_expression.cols(); } + EIGEN_DEVICE_FUNC inline Index outerStride() const { return m_expression.outerStride(); } + EIGEN_DEVICE_FUNC inline Index innerStride() const { return m_expression.innerStride(); } - inline const CoeffReturnType coeff(Index row, Index col) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index row, Index col) const { return m_expression.coeff(row, col); } - inline Scalar& coeffRef(Index row, Index col) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index row, Index col) { return m_expression.const_cast_derived().coeffRef(row, col); } - inline const CoeffReturnType coeff(Index index) const + EIGEN_DEVICE_FUNC inline const CoeffReturnType coeff(Index index) const { return m_expression.coeff(index); } - inline Scalar& coeffRef(Index index) + EIGEN_DEVICE_FUNC inline Scalar& coeffRef(Index index) { return m_expression.const_cast_derived().coeffRef(index); } @@ -91,7 +90,7 @@ template class NestByValue m_expression.const_cast_derived().template writePacket(index, x); } - operator const ExpressionType&() const { return m_expression; } + EIGEN_DEVICE_FUNC operator const ExpressionType&() const { return m_expression; } protected: const ExpressionType m_expression; diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h index 768bfb18c..33908010b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NoAlias.h @@ -17,7 +17,7 @@ namespace Eigen { * * \brief Pseudo expression providing an operator = assuming no aliasing * - * \param ExpressionType the type of the object on which to do the lazy assignment + * \tparam ExpressionType the type of the object on which to do the lazy assignment * * This class represents an expression with special assignment operators * assuming no aliasing between the target expression and the source expression. @@ -30,62 +30,36 @@ namespace Eigen { template class StorageBase> class NoAlias { - typedef typename ExpressionType::Scalar Scalar; public: - NoAlias(ExpressionType& expression) : m_expression(expression) {} - - /** Behaves like MatrixBase::lazyAssign(other) - * \sa MatrixBase::lazyAssign() */ - template - EIGEN_STRONG_INLINE ExpressionType& operator=(const StorageBase& other) - { return internal::assign_selector::run(m_expression,other.derived()); } - - /** \sa MatrixBase::operator+= */ - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const StorageBase& other) - { - typedef SelfCwiseBinaryOp, ExpressionType, OtherDerived> SelfAdder; - SelfAdder tmp(m_expression); - typedef typename internal::nested::type OtherDerivedNested; - typedef typename internal::remove_all::type _OtherDerivedNested; - internal::assign_selector::run(tmp,OtherDerivedNested(other.derived())); - return m_expression; - } - - /** \sa MatrixBase::operator-= */ - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const StorageBase& other) - { - typedef SelfCwiseBinaryOp, ExpressionType, OtherDerived> SelfAdder; - SelfAdder tmp(m_expression); - typedef typename internal::nested::type OtherDerivedNested; - typedef typename internal::remove_all::type _OtherDerivedNested; - internal::assign_selector::run(tmp,OtherDerivedNested(other.derived())); - return m_expression; - } - -#ifndef EIGEN_PARSED_BY_DOXYGEN - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const ProductBase& other) - { other.derived().addTo(m_expression); return m_expression; } - - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const ProductBase& other) - { other.derived().subTo(m_expression); return m_expression; } - - template - EIGEN_STRONG_INLINE ExpressionType& operator+=(const CoeffBasedProduct& other) - { return m_expression.derived() += CoeffBasedProduct(other.lhs(), other.rhs()); } - - template - EIGEN_STRONG_INLINE ExpressionType& operator-=(const CoeffBasedProduct& other) - { return m_expression.derived() -= CoeffBasedProduct(other.lhs(), other.rhs()); } + typedef typename ExpressionType::Scalar Scalar; + + explicit NoAlias(ExpressionType& expression) : m_expression(expression) {} template - ExpressionType& operator=(const ReturnByValue& func) - { return m_expression = func; } -#endif + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::assign_op()); + return m_expression; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator+=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::add_assign_op()); + return m_expression; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE ExpressionType& operator-=(const StorageBase& other) + { + call_assignment_no_alias(m_expression, other.derived(), internal::sub_assign_op()); + return m_expression; + } + EIGEN_DEVICE_FUNC ExpressionType& expression() const { return m_expression; @@ -126,7 +100,7 @@ class NoAlias template NoAlias MatrixBase::noalias() { - return derived(); + return NoAlias(derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h index bac9e50b8..daf489878 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/NumTraits.h @@ -12,24 +12,57 @@ namespace Eigen { +namespace internal { + +// default implementation of digits10(), based on numeric_limits if specialized, +// 0 for integer types, and log10(epsilon()) otherwise. +template< typename T, + bool use_numeric_limits = std::numeric_limits::is_specialized, + bool is_integer = NumTraits::IsInteger> +struct default_digits10_impl +{ + static int run() { return std::numeric_limits::digits10; } +}; + +template +struct default_digits10_impl // Floating point +{ + static int run() { + using std::log10; + using std::ceil; + typedef typename NumTraits::Real Real; + return int(ceil(-log10(NumTraits::epsilon()))); + } +}; + +template +struct default_digits10_impl // Integer +{ + static int run() { return 0; } +}; + +} // end namespace internal + /** \class NumTraits * \ingroup Core_Module * * \brief Holds information about the various numeric (i.e. scalar) types allowed by Eigen. * - * \param T the numeric type at hand + * \tparam T the numeric type at hand * * This class stores enums, typedefs and static methods giving information about a numeric type. * * The provided data consists of: - * \li A typedef \a Real, giving the "real part" type of \a T. If \a T is already real, - * then \a Real is just a typedef to \a T. If \a T is \c std::complex then \a Real + * \li A typedef \c Real, giving the "real part" type of \a T. If \a T is already real, + * then \c Real is just a typedef to \a T. If \a T is \c std::complex then \c Real * is a typedef to \a U. - * \li A typedef \a NonInteger, giving the type that should be used for operations producing non-integral values, + * \li A typedef \c NonInteger, giving the type that should be used for operations producing non-integral values, * such as quotients, square roots, etc. If \a T is a floating-point type, then this typedef just gives * \a T again. Note however that many Eigen functions such as internal::sqrt simply refuse to * take integers. Outside of a few cases, Eigen doesn't do automatic type promotion. Thus, this typedef is * only intended as a helper for code that needs to explicitly promote types. + * \li A typedef \c Literal giving the type to use for numeric literals such as "2" or "0.5". For instance, for \c std::complex, Literal is defined as \c U. + * Of course, this type must be fully compatible with \a T. In doubt, just use \a T here. * \li A typedef \a Nested giving the type to use to nest a value inside of the expression tree. If you don't know what * this means, just use \a T here. * \li An enum value \a IsComplex. It is equal to 1 if \a T is a \c std::complex @@ -42,10 +75,14 @@ namespace Eigen { * \li An enum value \a IsSigned. It is equal to \c 1 if \a T is a signed type and to 0 if \a T is unsigned. * \li An enum value \a RequireInitialization. It is equal to \c 1 if the constructor of the numeric type \a T must * be called, and to 0 if it is safe not to call it. Default is 0 if \a T is an arithmetic type, and 1 otherwise. - * \li An epsilon() function which, unlike std::numeric_limits::epsilon(), returns a \a Real instead of a \a T. + * \li An epsilon() function which, unlike std::numeric_limits::epsilon(), + * it returns a \a Real instead of a \a T. * \li A dummy_precision() function returning a weak epsilon value. It is mainly used as a default * value by the fuzzy comparison operators. * \li highest() and lowest() functions returning the highest and lowest possible values respectively. + * \li digits10() function returning the number of decimal digits that can be represented without change. This is + * the analogue of std::numeric_limits::digits10 + * which is used as the default implementation if specialized. */ template struct GenericNumTraits @@ -67,22 +104,47 @@ template struct GenericNumTraits T >::type NonInteger; typedef T Nested; + typedef T Literal; - static inline Real epsilon() { return std::numeric_limits::epsilon(); } + EIGEN_DEVICE_FUNC + static inline Real epsilon() + { + return numext::numeric_limits::epsilon(); + } + + EIGEN_DEVICE_FUNC + static inline int digits10() + { + return internal::default_digits10_impl::run(); + } + + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { // make sure to override this for floating-point types return Real(0); } - static inline T highest() { return (std::numeric_limits::max)(); } - static inline T lowest() { return IsInteger ? (std::numeric_limits::min)() : (-(std::numeric_limits::max)()); } - -#ifdef EIGEN2_SUPPORT - enum { - HasFloatingPoint = !IsInteger - }; - typedef NonInteger FloatingPoint; -#endif + + + EIGEN_DEVICE_FUNC + static inline T highest() { + return (numext::numeric_limits::max)(); + } + + EIGEN_DEVICE_FUNC + static inline T lowest() { + return IsInteger ? (numext::numeric_limits::min)() : (-(numext::numeric_limits::max)()); + } + + EIGEN_DEVICE_FUNC + static inline T infinity() { + return numext::numeric_limits::infinity(); + } + + EIGEN_DEVICE_FUNC + static inline T quiet_NaN() { + return numext::numeric_limits::quiet_NaN(); + } }; template struct NumTraits : GenericNumTraits @@ -91,11 +153,13 @@ template struct NumTraits : GenericNumTraits template<> struct NumTraits : GenericNumTraits { + EIGEN_DEVICE_FUNC static inline float dummy_precision() { return 1e-5f; } }; template<> struct NumTraits : GenericNumTraits { + EIGEN_DEVICE_FUNC static inline double dummy_precision() { return 1e-12; } }; @@ -109,6 +173,7 @@ template struct NumTraits > : GenericNumTraits > { typedef _Real Real; + typedef typename NumTraits<_Real>::Literal Literal; enum { IsComplex = 1, RequireInitialization = NumTraits<_Real>::RequireInitialization, @@ -117,8 +182,12 @@ template struct NumTraits > MulCost = 4 * NumTraits::MulCost + 2 * NumTraits::AddCost }; + EIGEN_DEVICE_FUNC static inline Real epsilon() { return NumTraits::epsilon(); } + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { return NumTraits::dummy_precision(); } + EIGEN_DEVICE_FUNC + static inline int digits10() { return NumTraits::digits10(); } }; template @@ -130,21 +199,50 @@ struct NumTraits > typedef typename NumTraits::NonInteger NonIntegerScalar; typedef Array NonInteger; typedef ArrayType & Nested; - + typedef typename NumTraits::Literal Literal; + enum { IsComplex = NumTraits::IsComplex, IsInteger = NumTraits::IsInteger, IsSigned = NumTraits::IsSigned, RequireInitialization = 1, - ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::ReadCost, - AddCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::AddCost, - MulCost = ArrayType::SizeAtCompileTime==Dynamic ? Dynamic : ArrayType::SizeAtCompileTime * NumTraits::MulCost + ReadCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::ReadCost, + AddCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::AddCost, + MulCost = ArrayType::SizeAtCompileTime==Dynamic ? HugeCost : ArrayType::SizeAtCompileTime * NumTraits::MulCost }; - + + EIGEN_DEVICE_FUNC static inline RealScalar epsilon() { return NumTraits::epsilon(); } + EIGEN_DEVICE_FUNC static inline RealScalar dummy_precision() { return NumTraits::dummy_precision(); } + + static inline int digits10() { return NumTraits::digits10(); } }; +template<> struct NumTraits + : GenericNumTraits +{ + enum { + RequireInitialization = 1, + ReadCost = HugeCost, + AddCost = HugeCost, + MulCost = HugeCost + }; + + static inline int digits10() { return 0; } + +private: + static inline std::string epsilon(); + static inline std::string dummy_precision(); + static inline std::string lowest(); + static inline std::string highest(); + static inline std::string infinity(); + static inline std::string quiet_NaN(); +}; + +// Empty specialization for void to allow template specialization based on NumTraits::Real with T==void and SFINAE. +template<> struct NumTraits {}; + } // end namespace Eigen #endif // EIGEN_NUMTRAITS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h index bda79fa04..b1fb455b9 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PermutationMatrix.h @@ -2,7 +2,7 @@ // for linear algebra. // // Copyright (C) 2009 Benoit Jacob -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -13,14 +13,18 @@ namespace Eigen { -template class PermutedImpl; +namespace internal { + +enum PermPermProduct_t {PermPermProduct}; + +} // end namespace internal /** \class PermutationBase * \ingroup Core_Module * * \brief Base class for permutations * - * \param Derived the derived class + * \tparam Derived the derived class * * This class is the base class for all expressions representing a permutation matrix, * internally stored as a vector of integers. @@ -38,17 +42,6 @@ template -struct permut_matrix_product_retval; -template -struct permut_sparsematrix_product_retval; -enum PermPermProduct_t {PermPermProduct}; - -} // end namespace internal - template class PermutationBase : public EigenBase { @@ -60,19 +53,20 @@ class PermutationBase : public EigenBase typedef typename Traits::IndicesType IndicesType; enum { Flags = Traits::Flags, - CoeffReadCost = Traits::CoeffReadCost, RowsAtCompileTime = Traits::RowsAtCompileTime, ColsAtCompileTime = Traits::ColsAtCompileTime, MaxRowsAtCompileTime = Traits::MaxRowsAtCompileTime, MaxColsAtCompileTime = Traits::MaxColsAtCompileTime }; - typedef typename Traits::Scalar Scalar; - typedef typename Traits::Index Index; - typedef Matrix + typedef typename Traits::StorageIndex StorageIndex; + typedef Matrix DenseMatrixType; - typedef PermutationMatrix + typedef PermutationMatrix PlainPermutationType; + typedef PlainPermutationType PlainObject; using Base::derived; + typedef Inverse InverseReturnType; + typedef void Scalar; #endif /** Copies the other permutation into *this */ @@ -118,7 +112,7 @@ class PermutationBase : public EigenBase void evalTo(MatrixBase& other) const { other.setZero(); - for (int i=0; i /** Sets *this to be the identity permutation matrix */ void setIdentity() { - for(Index i = 0; i < size(); ++i) + StorageIndex n = StorageIndex(size()); + for(StorageIndex i = 0; i < n; ++i) indices().coeffRef(i) = i; } @@ -163,18 +158,18 @@ class PermutationBase : public EigenBase * * \returns a reference to *this. * - * \warning This is much slower than applyTranspositionOnTheRight(int,int): + * \warning This is much slower than applyTranspositionOnTheRight(Index,Index): * this has linear complexity and requires a lot of branching. * - * \sa applyTranspositionOnTheRight(int,int) + * \sa applyTranspositionOnTheRight(Index,Index) */ Derived& applyTranspositionOnTheLeft(Index i, Index j) { eigen_assert(i>=0 && j>=0 && i * * This is a fast operation, it only consists in swapping two indices. * - * \sa applyTranspositionOnTheLeft(int,int) + * \sa applyTranspositionOnTheLeft(Index,Index) */ Derived& applyTranspositionOnTheRight(Index i, Index j) { @@ -196,16 +191,16 @@ class PermutationBase : public EigenBase /** \returns the inverse permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ - inline Transpose inverse() const - { return derived(); } + inline InverseReturnType inverse() const + { return InverseReturnType(derived()); } /** \returns the tranpose permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ - inline Transpose transpose() const - { return derived(); } + inline InverseReturnType transpose() const + { return InverseReturnType(derived()); } /**** multiplication helpers to hopefully get RVO ****/ @@ -215,13 +210,13 @@ class PermutationBase : public EigenBase template void assignTranspose(const PermutationBase& other) { - for (int i=0; i void assignProduct(const Lhs& lhs, const Rhs& rhs) { eigen_assert(lhs.cols() == rhs.rows()); - for (int i=0; i /** \returns the product permutation matrix. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template inline PlainPermutationType operator*(const PermutationBase& other) const @@ -237,18 +232,18 @@ class PermutationBase : public EigenBase /** \returns the product of a permutation with another inverse permutation. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template - inline PlainPermutationType operator*(const Transpose >& other) const + inline PlainPermutationType operator*(const InverseImpl& other) const { return PlainPermutationType(internal::PermPermProduct, *this, other.eval()); } /** \returns the product of an inverse permutation with another permutation. * - * \note \note_try_to_help_rvo + * \note \blank \note_try_to_help_rvo */ template friend - inline PlainPermutationType operator*(const Transpose >& other, const PermutationBase& perm) + inline PlainPermutationType operator*(const InverseImpl& other, const PermutationBase& perm) { return PlainPermutationType(internal::PermPermProduct, other.eval(), perm); } /** \returns the determinant of the permutation matrix, which is either 1 or -1 depending on the parity of the permutation. @@ -284,39 +279,43 @@ class PermutationBase : public EigenBase }; +namespace internal { +template +struct traits > + : traits > +{ + typedef PermutationStorage StorageKind; + typedef Matrix<_StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1> IndicesType; + typedef _StorageIndex StorageIndex; + typedef void Scalar; +}; +} + /** \class PermutationMatrix * \ingroup Core_Module * * \brief Permutation matrix * - * \param SizeAtCompileTime the number of rows/cols, or Dynamic - * \param MaxSizeAtCompileTime the maximum number of rows/cols, or Dynamic. This optional parameter defaults to SizeAtCompileTime. Most of the time, you should not have to specify it. - * \param IndexType the interger type of the indices + * \tparam SizeAtCompileTime the number of rows/cols, or Dynamic + * \tparam MaxSizeAtCompileTime the maximum number of rows/cols, or Dynamic. This optional parameter defaults to SizeAtCompileTime. Most of the time, you should not have to specify it. + * \tparam _StorageIndex the integer type of the indices * * This class represents a permutation matrix, internally stored as a vector of integers. * * \sa class PermutationBase, class PermutationWrapper, class DiagonalMatrix */ - -namespace internal { -template -struct traits > - : traits > -{ - typedef IndexType Index; - typedef Matrix IndicesType; -}; -} - -template -class PermutationMatrix : public PermutationBase > +template +class PermutationMatrix : public PermutationBase > { typedef PermutationBase Base; typedef internal::traits Traits; public: + typedef const PermutationMatrix& Nested; + #ifndef EIGEN_PARSED_BY_DOXYGEN typedef typename Traits::IndicesType IndicesType; + typedef typename Traits::StorageIndex StorageIndex; #endif inline PermutationMatrix() @@ -324,8 +323,10 @@ class PermutationMatrix : public PermutationBase::highest()); + } /** Copy constructor. */ template @@ -346,7 +347,7 @@ class PermutationMatrix : public PermutationBase - explicit inline PermutationMatrix(const MatrixBase& a_indices) : m_indices(a_indices) + explicit inline PermutationMatrix(const MatrixBase& indices) : m_indices(indices) {} /** Convert the Transpositions \a tr to a permutation matrix */ @@ -393,10 +394,13 @@ class PermutationMatrix : public PermutationBase - PermutationMatrix(const Transpose >& other) - : m_indices(other.nestedPermutation().size()) + PermutationMatrix(const InverseImpl& other) + : m_indices(other.derived().nestedExpression().size()) { - for (int i=0; i::highest()); + StorageIndex end = StorageIndex(m_indices.size()); + for (StorageIndex i=0; i PermutationMatrix(internal::PermPermProduct_t, const Lhs& lhs, const Rhs& rhs) @@ -413,18 +417,20 @@ class PermutationMatrix : public PermutationBase -struct traits,_PacketAccess> > - : traits > +template +struct traits,_PacketAccess> > + : traits > { - typedef IndexType Index; - typedef Map, _PacketAccess> IndicesType; + typedef PermutationStorage StorageKind; + typedef Map, _PacketAccess> IndicesType; + typedef _StorageIndex StorageIndex; + typedef void Scalar; }; } -template -class Map,_PacketAccess> - : public PermutationBase,_PacketAccess> > +template +class Map,_PacketAccess> + : public PermutationBase,_PacketAccess> > { typedef PermutationBase Base; typedef internal::traits Traits; @@ -432,14 +438,14 @@ class Map, #ifndef EIGEN_PARSED_BY_DOXYGEN typedef typename Traits::IndicesType IndicesType; - typedef typename IndicesType::Scalar Index; + typedef typename IndicesType::Scalar StorageIndex; #endif - inline Map(const Index* indicesPtr) + inline Map(const StorageIndex* indicesPtr) : m_indices(indicesPtr) {} - inline Map(const Index* indicesPtr, Index size) + inline Map(const StorageIndex* indicesPtr, Index size) : m_indices(indicesPtr,size) {} @@ -474,40 +480,36 @@ class Map, IndicesType m_indices; }; -/** \class PermutationWrapper - * \ingroup Core_Module - * - * \brief Class to view a vector of integers as a permutation matrix - * - * \param _IndicesType the type of the vector of integer (can be any compatible expression) - * - * This class allows to view any vector expression of integers as a permutation matrix. - * - * \sa class PermutationBase, class PermutationMatrix - */ - -struct PermutationStorage {}; - template class TranspositionsWrapper; namespace internal { template struct traits > { typedef PermutationStorage StorageKind; - typedef typename _IndicesType::Scalar Scalar; - typedef typename _IndicesType::Scalar Index; + typedef void Scalar; + typedef typename _IndicesType::Scalar StorageIndex; typedef _IndicesType IndicesType; enum { RowsAtCompileTime = _IndicesType::SizeAtCompileTime, ColsAtCompileTime = _IndicesType::SizeAtCompileTime, - MaxRowsAtCompileTime = IndicesType::MaxRowsAtCompileTime, - MaxColsAtCompileTime = IndicesType::MaxColsAtCompileTime, - Flags = 0, - CoeffReadCost = _IndicesType::CoeffReadCost + MaxRowsAtCompileTime = IndicesType::MaxSizeAtCompileTime, + MaxColsAtCompileTime = IndicesType::MaxSizeAtCompileTime, + Flags = 0 }; }; } +/** \class PermutationWrapper + * \ingroup Core_Module + * + * \brief Class to view a vector of integers as a permutation matrix + * + * \tparam _IndicesType the type of the vector of integer (can be any compatible expression) + * + * This class allows to view any vector expression of integers as a permutation matrix. + * + * \sa class PermutationBase, class PermutationMatrix + */ template class PermutationWrapper : public PermutationBase > { @@ -519,8 +521,8 @@ class PermutationWrapper : public PermutationBase -inline const internal::permut_matrix_product_retval -operator*(const MatrixBase& matrix, - const PermutationBase &permutation) +template +EIGEN_DEVICE_FUNC +const Product +operator*(const MatrixBase &matrix, + const PermutationBase& permutation) { - return internal::permut_matrix_product_retval - - (permutation.derived(), matrix.derived()); + return Product + (matrix.derived(), permutation.derived()); } /** \returns the matrix with the permutation applied to the rows. */ -template -inline const internal::permut_matrix_product_retval - +template +EIGEN_DEVICE_FUNC +const Product operator*(const PermutationBase &permutation, - const MatrixBase& matrix) + const MatrixBase& matrix) { - return internal::permut_matrix_product_retval - - (permutation.derived(), matrix.derived()); + return Product + (permutation.derived(), matrix.derived()); } -namespace internal { -template -struct traits > +template +class InverseImpl + : public EigenBase > { - typedef typename MatrixType::PlainObject ReturnType; -}; - -template -struct permut_matrix_product_retval - : public ReturnByValue > -{ - typedef typename remove_all::type MatrixTypeNestedCleaned; - typedef typename MatrixType::Index Index; - - permut_matrix_product_retval(const PermutationType& perm, const MatrixType& matrix) - : m_permutation(perm), m_matrix(matrix) - {} - - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } - - template inline void evalTo(Dest& dst) const - { - const Index n = Side==OnTheLeft ? rows() : cols(); - // FIXME we need an is_same for expression that is not sensitive to constness. For instance - // is_same_xpr, Block >::value should be true. - const typename Dest::Scalar *dst_data = internal::extract_data(dst); - if( is_same::value - && blas_traits::HasUsableDirectAccess - && blas_traits::HasUsableDirectAccess - && dst_data!=0 && dst_data == extract_data(m_matrix)) - { - // apply the permutation inplace - Matrix mask(m_permutation.size()); - mask.fill(false); - Index r = 0; - while(r < m_permutation.size()) - { - // search for the next seed - while(r=m_permutation.size()) - break; - // we got one, let's follow it until we are back to the seed - Index k0 = r++; - Index kPrev = k0; - mask.coeffRef(k0) = true; - for(Index k=m_permutation.indices().coeff(k0); k!=k0; k=m_permutation.indices().coeff(k)) - { - Block(dst, k) - .swap(Block - (dst,((Side==OnTheLeft) ^ Transposed) ? k0 : kPrev)); - - mask.coeffRef(k) = true; - kPrev = k; - } - } - } - else - { - for(int i = 0; i < n; ++i) - { - Block - (dst, ((Side==OnTheLeft) ^ Transposed) ? m_permutation.indices().coeff(i) : i) - - = - - Block - (m_matrix, ((Side==OnTheRight) ^ Transposed) ? m_permutation.indices().coeff(i) : i); - } - } - } - - protected: - const PermutationType& m_permutation; - typename MatrixType::Nested m_matrix; -}; - -/* Template partial specialization for transposed/inverse permutations */ - -template -struct traits > > - : traits -{}; - -} // end namespace internal - -template -class Transpose > - : public EigenBase > > -{ - typedef Derived PermutationType; - typedef typename PermutationType::IndicesType IndicesType; typedef typename PermutationType::PlainPermutationType PlainPermutationType; + typedef internal::traits PermTraits; + protected: + InverseImpl() {} public: + typedef Inverse InverseType; + using EigenBase >::derived; #ifndef EIGEN_PARSED_BY_DOXYGEN - typedef internal::traits Traits; - typedef typename Derived::DenseMatrixType DenseMatrixType; + typedef typename PermutationType::DenseMatrixType DenseMatrixType; enum { - Flags = Traits::Flags, - CoeffReadCost = Traits::CoeffReadCost, - RowsAtCompileTime = Traits::RowsAtCompileTime, - ColsAtCompileTime = Traits::ColsAtCompileTime, - MaxRowsAtCompileTime = Traits::MaxRowsAtCompileTime, - MaxColsAtCompileTime = Traits::MaxColsAtCompileTime + RowsAtCompileTime = PermTraits::RowsAtCompileTime, + ColsAtCompileTime = PermTraits::ColsAtCompileTime, + MaxRowsAtCompileTime = PermTraits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = PermTraits::MaxColsAtCompileTime }; - typedef typename Traits::Scalar Scalar; #endif - Transpose(const PermutationType& p) : m_permutation(p) {} - - inline int rows() const { return m_permutation.rows(); } - inline int cols() const { return m_permutation.cols(); } - #ifndef EIGEN_PARSED_BY_DOXYGEN template void evalTo(MatrixBase& other) const { other.setZero(); - for (int i=0; i friend - inline const internal::permut_matrix_product_retval - operator*(const MatrixBase& matrix, const Transpose& trPerm) + const Product + operator*(const MatrixBase& matrix, const InverseType& trPerm) { - return internal::permut_matrix_product_retval(trPerm.m_permutation, matrix.derived()); + return Product(matrix.derived(), trPerm.derived()); } /** \returns the matrix with the inverse permutation applied to the rows. */ template - inline const internal::permut_matrix_product_retval + const Product operator*(const MatrixBase& matrix) const { - return internal::permut_matrix_product_retval(m_permutation, matrix.derived()); + return Product(derived(), matrix.derived()); } - - const PermutationType& nestedPermutation() const { return m_permutation; } - - protected: - const PermutationType& m_permutation; }; template @@ -717,6 +622,12 @@ const PermutationWrapper MatrixBase::asPermutation() con return derived(); } +namespace internal { + +template<> struct AssignmentKind { typedef EigenBase2EigenBase Kind; }; + +} // end namespace internal + } // end namespace Eigen #endif // EIGEN_PERMUTATIONMATRIX_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h index 9f71956ff..77f4f6066 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/PlainObjectBase.h @@ -28,6 +28,7 @@ namespace internal { template struct check_rows_cols_for_overflow { template + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE void run(Index, Index) { } @@ -35,11 +36,12 @@ template struct check_rows_cols_for_overflow { template<> struct check_rows_cols_for_overflow { template + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE void run(Index rows, Index cols) { // http://hg.mozilla.org/mozilla-central/file/6c8a909977d3/xpcom/ds/CheckedInt.h#l242 // we assume Index is signed - Index max_index = (size_t(1) << (8 * sizeof(Index) - 1)) - 1; // assume Index is signed + Index max_index = (std::size_t(1) << (8 * sizeof(Index) - 1)) - 1; // assume Index is signed bool error = (rows == 0 || cols == 0) ? false : (rows > max_index / cols); if (error) @@ -56,33 +58,41 @@ template struct m } // end namespace internal +#ifdef EIGEN_PARSED_BY_DOXYGEN +namespace doxygen { + +// This is a workaround to doxygen not being able to understand the inheritance logic +// when it is hidden by the dense_xpr_base helper struct. +// Moreover, doxygen fails to include members that are not documented in the declaration body of +// MatrixBase if we inherits MatrixBase >, +// this is why we simply inherits MatrixBase, though this does not make sense. + +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template struct dense_xpr_base_dispatcher; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher > + : public MatrixBase {}; +/** This class is just a workaround for Doxygen and it does not not actually exist. */ +template +struct dense_xpr_base_dispatcher > + : public ArrayBase {}; + +} // namespace doxygen + /** \class PlainObjectBase + * \ingroup Core_Module * \brief %Dense storage base class for matrices and arrays. * * This class can be extended with the help of the plugin mechanism described on the page - * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_PLAINOBJECTBASE_PLUGIN. + * \ref TopicCustomizing_Plugins by defining the preprocessor symbol \c EIGEN_PLAINOBJECTBASE_PLUGIN. + * + * \tparam Derived is the derived type, e.g., a Matrix or Array * * \sa \ref TopicClassHierarchy */ -#ifdef EIGEN_PARSED_BY_DOXYGEN -namespace internal { - -// this is a warkaround to doxygen not being able to understand the inheritence logic -// when it is hidden by the dense_xpr_base helper struct. -template struct dense_xpr_base_dispatcher_for_doxygen;// : public MatrixBase {}; -/** This class is just a workaround for Doxygen and it does not not actually exist. */ -template -struct dense_xpr_base_dispatcher_for_doxygen > - : public MatrixBase > {}; -/** This class is just a workaround for Doxygen and it does not not actually exist. */ -template -struct dense_xpr_base_dispatcher_for_doxygen > - : public ArrayBase > {}; - -} // namespace internal - template -class PlainObjectBase : public internal::dense_xpr_base_dispatcher_for_doxygen +class PlainObjectBase : public doxygen::dense_xpr_base_dispatcher #else template class PlainObjectBase : public internal::dense_xpr_base::type @@ -93,8 +103,8 @@ class PlainObjectBase : public internal::dense_xpr_base::type typedef typename internal::dense_xpr_base::type Base; typedef typename internal::traits::StorageKind StorageKind; - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; + typedef typename internal::packet_traits::type PacketScalar; typedef typename NumTraits::Real RealScalar; typedef Derived DenseType; @@ -113,28 +123,40 @@ class PlainObjectBase : public internal::dense_xpr_base::type typedef Eigen::Map MapType; friend class Eigen::Map; typedef const Eigen::Map ConstMapType; - friend class Eigen::Map; - typedef Eigen::Map AlignedMapType; - friend class Eigen::Map; - typedef const Eigen::Map ConstAlignedMapType; +#if EIGEN_MAX_ALIGN_BYTES>0 + // for EIGEN_MAX_ALIGN_BYTES==0, AlignedMax==Unaligned, and many compilers generate warnings for friend-ing a class twice. + friend class Eigen::Map; + friend class Eigen::Map; +#endif + typedef Eigen::Map AlignedMapType; + typedef const Eigen::Map ConstAlignedMapType; template struct StridedMapType { typedef Eigen::Map type; }; template struct StridedConstMapType { typedef Eigen::Map type; }; - template struct StridedAlignedMapType { typedef Eigen::Map type; }; - template struct StridedConstAlignedMapType { typedef Eigen::Map type; }; + template struct StridedAlignedMapType { typedef Eigen::Map type; }; + template struct StridedConstAlignedMapType { typedef Eigen::Map type; }; protected: DenseStorage m_storage; public: - enum { NeedsToAlign = SizeAtCompileTime != Dynamic && (internal::traits::Flags & AlignedBit) != 0 }; + enum { NeedsToAlign = (SizeAtCompileTime != Dynamic) && (internal::traits::Alignment>0) }; EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + EIGEN_DEVICE_FUNC Base& base() { return *static_cast(this); } + EIGEN_DEVICE_FUNC const Base& base() const { return *static_cast(this); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rows() const { return m_storage.rows(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index cols() const { return m_storage.cols(); } + /** This is an overloaded version of DenseCoeffsBase::coeff(Index,Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeff(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index rowId, Index colId) const { if(Flags & RowMajorBit) @@ -143,11 +165,21 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is an overloaded version of DenseCoeffsBase::coeff(Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeff(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const { return m_storage.data()[index]; } + /** This is an overloaded version of DenseCoeffsBase::coeffRef(Index,Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeffRef(Index,Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index rowId, Index colId) { if(Flags & RowMajorBit) @@ -156,11 +188,19 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is an overloaded version of DenseCoeffsBase::coeffRef(Index) const + * provided to by-pass the creation of an evaluator of the expression, thus saving compilation efforts. + * + * See DenseCoeffsBase::coeffRef(Index) const for details. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) { return m_storage.data()[index]; } + /** This is the const version of coeffRef(Index,Index) which is thus synonym of coeff(Index,Index). + * It is provided for convenience. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeffRef(Index rowId, Index colId) const { if(Flags & RowMajorBit) @@ -169,6 +209,9 @@ class PlainObjectBase : public internal::dense_xpr_base::type return m_storage.data()[rowId + colId * m_storage.rows()]; } + /** This is the const version of coeffRef(Index) which is thus synonym of coeff(Index). + * It is provided for convenience. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeffRef(Index index) const { return m_storage.data()[index]; @@ -209,11 +252,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type } /** \returns a const pointer to the data array of this matrix */ - EIGEN_STRONG_INLINE const Scalar *data() const + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } /** \returns a pointer to the data array of this matrix */ - EIGEN_STRONG_INLINE Scalar *data() + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } /** Resizes \c *this to a \a rows x \a cols matrix. @@ -232,22 +275,22 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index) for vectors, resize(NoChange_t, Index), resize(Index, NoChange_t) */ - EIGEN_STRONG_INLINE void resize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void resize(Index rows, Index cols) { - eigen_assert( EIGEN_IMPLIES(RowsAtCompileTime!=Dynamic,nbRows==RowsAtCompileTime) - && EIGEN_IMPLIES(ColsAtCompileTime!=Dynamic,nbCols==ColsAtCompileTime) - && EIGEN_IMPLIES(RowsAtCompileTime==Dynamic && MaxRowsAtCompileTime!=Dynamic,nbRows<=MaxRowsAtCompileTime) - && EIGEN_IMPLIES(ColsAtCompileTime==Dynamic && MaxColsAtCompileTime!=Dynamic,nbCols<=MaxColsAtCompileTime) - && nbRows>=0 && nbCols>=0 && "Invalid sizes when resizing a matrix or array."); - internal::check_rows_cols_for_overflow::run(nbRows, nbCols); + eigen_assert( EIGEN_IMPLIES(RowsAtCompileTime!=Dynamic,rows==RowsAtCompileTime) + && EIGEN_IMPLIES(ColsAtCompileTime!=Dynamic,cols==ColsAtCompileTime) + && EIGEN_IMPLIES(RowsAtCompileTime==Dynamic && MaxRowsAtCompileTime!=Dynamic,rows<=MaxRowsAtCompileTime) + && EIGEN_IMPLIES(ColsAtCompileTime==Dynamic && MaxColsAtCompileTime!=Dynamic,cols<=MaxColsAtCompileTime) + && rows>=0 && cols>=0 && "Invalid sizes when resizing a matrix or array."); + internal::check_rows_cols_for_overflow::run(rows, cols); #ifdef EIGEN_INITIALIZE_COEFFS - Index size = nbRows*nbCols; + Index size = rows*cols; bool size_changed = size != this->size(); - m_storage.resize(size, nbRows, nbCols); + m_storage.resize(size, rows, cols); if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED #else - internal::check_rows_cols_for_overflow::run(nbRows, nbCols); - m_storage.resize(nbRows*nbCols, nbRows, nbCols); + m_storage.resize(rows*cols, rows, cols); #endif } @@ -262,6 +305,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index), resize(NoChange_t, Index), resize(Index, NoChange_t) */ + EIGEN_DEVICE_FUNC inline void resize(Index size) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(PlainObjectBase) @@ -286,9 +330,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index) */ - inline void resize(NoChange_t, Index nbCols) + EIGEN_DEVICE_FUNC + inline void resize(NoChange_t, Index cols) { - resize(rows(), nbCols); + resize(rows(), cols); } /** Resizes the matrix, changing only the number of rows. For the parameter of type NoChange_t, just pass the special value \c NoChange @@ -299,9 +344,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \sa resize(Index,Index) */ - inline void resize(Index nbRows, NoChange_t) + EIGEN_DEVICE_FUNC + inline void resize(Index rows, NoChange_t) { - resize(nbRows, cols()); + resize(rows, cols()); } /** Resizes \c *this to have the same dimensions as \a other. @@ -312,11 +358,12 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resizeLike(const EigenBase& _other) { const OtherDerived& other = _other.derived(); - internal::check_rows_cols_for_overflow::run(Index(other.rows()), Index(other.cols())); - const Index othersize = Index(other.rows())*Index(other.cols()); + internal::check_rows_cols_for_overflow::run(other.rows(), other.cols()); + const Index othersize = other.rows()*other.cols(); if(RowsAtCompileTime == 1) { eigen_assert(other.rows() == 1 || other.cols() == 1); @@ -339,9 +386,10 @@ class PlainObjectBase : public internal::dense_xpr_base::type * Matrices are resized relative to the top-left element. In case values need to be * appended to the matrix they will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(Index nbRows, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(Index rows, Index cols) { - internal::conservative_resize_like_impl::run(*this, nbRows, nbCols); + internal::conservative_resize_like_impl::run(*this, rows, cols); } /** Resizes the matrix to \a rows x \a cols while leaving old values untouched. @@ -351,10 +399,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * In case the matrix is growing, new rows will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(Index nbRows, NoChange_t) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(Index rows, NoChange_t) { // Note: see the comment in conservativeResize(Index,Index) - conservativeResize(nbRows, cols()); + conservativeResize(rows, cols()); } /** Resizes the matrix to \a rows x \a cols while leaving old values untouched. @@ -364,10 +413,11 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * In case the matrix is growing, new columns will be uninitialized. */ - EIGEN_STRONG_INLINE void conservativeResize(NoChange_t, Index nbCols) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void conservativeResize(NoChange_t, Index cols) { // Note: see the comment in conservativeResize(Index,Index) - conservativeResize(rows(), nbCols); + conservativeResize(rows(), cols); } /** Resizes the vector to \a size while retaining old values. @@ -378,6 +428,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * When values are appended, they will be uninitialized. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResize(Index size) { internal::conservative_resize_like_impl::run(*this, size); @@ -393,6 +444,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * appended to the matrix they will copied from \c other. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void conservativeResizeLike(const DenseBase& other) { internal::conservative_resize_like_impl::run(*this, other); @@ -401,6 +453,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type /** This is a special case of the templated operator=. Its purpose is to * prevent a default operator= from hiding the templated operator=. */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const PlainObjectBase& other) { return _set(other); @@ -408,6 +461,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type /** \sa MatrixBase::lazyAssign() */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& lazyAssign(const DenseBase& other) { _resize_to_match(other); @@ -415,12 +469,18 @@ class PlainObjectBase : public internal::dense_xpr_base::type } template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const ReturnByValue& func) { resize(func.rows(), func.cols()); return Base::operator=(func); } + // Prevent user from trying to instantiate PlainObjectBase objects + // by making all its constructor protected. See bug 1074. + protected: + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase() : m_storage() { // _check_template_params(); @@ -430,20 +490,23 @@ class PlainObjectBase : public internal::dense_xpr_base::type #ifndef EIGEN_PARSED_BY_DOXYGEN // FIXME is it still needed ? /** \internal */ - PlainObjectBase(internal::constructor_without_unaligned_array_assert) + EIGEN_DEVICE_FUNC + explicit PlainObjectBase(internal::constructor_without_unaligned_array_assert) : m_storage(internal::constructor_without_unaligned_array_assert()) { // _check_template_params(); EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } #endif -#ifdef EIGEN_HAVE_RVALUE_REFERENCES - PlainObjectBase(PlainObjectBase&& other) +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC + PlainObjectBase(PlainObjectBase&& other) EIGEN_NOEXCEPT : m_storage( std::move(other.m_storage) ) { } - PlainObjectBase& operator=(PlainObjectBase&& other) + EIGEN_DEVICE_FUNC + PlainObjectBase& operator=(PlainObjectBase&& other) EIGEN_NOEXCEPT { using std::swap; swap(m_storage, other.m_storage); @@ -452,31 +515,56 @@ class PlainObjectBase : public internal::dense_xpr_base::type #endif /** Copy constructor */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PlainObjectBase(const PlainObjectBase& other) - : m_storage() - { - _check_template_params(); - lazyAssign(other); - } - - template - EIGEN_STRONG_INLINE PlainObjectBase(const DenseBase &other) - : m_storage() - { - _check_template_params(); - lazyAssign(other); - } - - EIGEN_STRONG_INLINE PlainObjectBase(Index a_size, Index nbRows, Index nbCols) - : m_storage(a_size, nbRows, nbCols) + : Base(), m_storage(other.m_storage) { } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(Index size, Index rows, Index cols) + : m_storage(size, rows, cols) { // _check_template_params(); // EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED } - /** \copydoc MatrixBase::operator=(const EigenBase&) + /** \sa PlainObjectBase::operator=(const EigenBase&) */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const DenseBase &other) + : m_storage() + { + _check_template_params(); + resizeLike(other); + _set_noalias(other); + } + + /** \sa PlainObjectBase::operator=(const EigenBase&) */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const EigenBase &other) + : m_storage() + { + _check_template_params(); + resizeLike(other); + *this = other.derived(); + } + /** \brief Copy constructor with in-place evaluation */ + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PlainObjectBase(const ReturnByValue& other) + { + _check_template_params(); + // FIXME this does not automatically transpose vectors if necessary + resize(other.rows(), other.cols()); + other.evalTo(this->derived()); + } + + public: + + /** \brief Copies the generic expression \a other into *this. + * \copydetails DenseBase::operator=(const EigenBase &other) */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const EigenBase &other) { _resize_to_match(other); @@ -484,16 +572,6 @@ class PlainObjectBase : public internal::dense_xpr_base::type return this->derived(); } - /** \sa MatrixBase::operator=(const EigenBase&) */ - template - EIGEN_STRONG_INLINE PlainObjectBase(const EigenBase &other) - : m_storage(Index(other.derived().rows()) * Index(other.derived().cols()), other.derived().rows(), other.derived().cols()) - { - _check_template_params(); - internal::check_rows_cols_for_overflow::run(other.derived().rows(), other.derived().cols()); - Base::operator=(other.derived()); - } - /** \name Map * These are convenience functions returning Map objects. The Map() static functions return unaligned Map objects, * while the AlignedMap() functions return aligned Map objects and thus should be called only with 16-byte-aligned @@ -568,16 +646,16 @@ class PlainObjectBase : public internal::dense_xpr_base::type //@} using Base::setConstant; - Derived& setConstant(Index size, const Scalar& value); - Derived& setConstant(Index rows, Index cols, const Scalar& value); + EIGEN_DEVICE_FUNC Derived& setConstant(Index size, const Scalar& val); + EIGEN_DEVICE_FUNC Derived& setConstant(Index rows, Index cols, const Scalar& val); using Base::setZero; - Derived& setZero(Index size); - Derived& setZero(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setZero(Index size); + EIGEN_DEVICE_FUNC Derived& setZero(Index rows, Index cols); using Base::setOnes; - Derived& setOnes(Index size); - Derived& setOnes(Index rows, Index cols); + EIGEN_DEVICE_FUNC Derived& setOnes(Index size); + EIGEN_DEVICE_FUNC Derived& setOnes(Index rows, Index cols); using Base::setRandom; Derived& setRandom(Index size); @@ -596,6 +674,7 @@ class PlainObjectBase : public internal::dense_xpr_base::type * remain row-vectors and vectors remain vectors. */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void _resize_to_match(const EigenBase& other) { #ifdef EIGEN_NO_AUTOMATIC_RESIZING @@ -603,8 +682,6 @@ class PlainObjectBase : public internal::dense_xpr_base::type : (rows() == other.rows() && cols() == other.cols()))) && "Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined"); EIGEN_ONLY_USED_FOR_DEBUG(other); - if(this->size()==0) - resizeLike(other); #else resizeLike(other); #endif @@ -624,25 +701,23 @@ class PlainObjectBase : public internal::dense_xpr_base::type * * \internal */ + // aliasing is dealt once in internall::call_assignment + // so at this stage we have to assume aliasing... and resising has to be done later. template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set(const DenseBase& other) { - _set_selector(other.derived(), typename internal::conditional(int(OtherDerived::Flags) & EvalBeforeAssigningBit), internal::true_type, internal::false_type>::type()); + internal::call_assignment(this->derived(), other.derived()); return this->derived(); } - template - EIGEN_STRONG_INLINE void _set_selector(const OtherDerived& other, const internal::true_type&) { _set_noalias(other.eval()); } - - template - EIGEN_STRONG_INLINE void _set_selector(const OtherDerived& other, const internal::false_type&) { _set_noalias(other); } - /** \internal Like _set() but additionally makes the assumption that no aliasing effect can happen (which * is the case when creating a new matrix) so one can enforce lazy evaluation. * * \sa operator=(const MatrixBase&), _set() */ template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& _set_noalias(const DenseBase& other) { // I don't think we need this resize call since the lazyAssign will anyways resize @@ -650,40 +725,175 @@ class PlainObjectBase : public internal::dense_xpr_base::type //_resize_to_match(other); // the 'false' below means to enforce lazy evaluation. We don't use lazyAssign() because // it wouldn't allow to copy a row-vector into a column-vector. - return internal::assign_selector::run(this->derived(), other.derived()); + internal::call_assignment_no_alias(this->derived(), other.derived(), internal::assign_op()); + return this->derived(); } template - EIGEN_STRONG_INLINE void _init2(Index nbRows, Index nbCols, typename internal::enable_if::type* = 0) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(Index rows, Index cols, typename internal::enable_if::type* = 0) { EIGEN_STATIC_ASSERT(bool(NumTraits::IsInteger) && bool(NumTraits::IsInteger), FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) - resize(nbRows,nbCols); + resize(rows,cols); } + template - EIGEN_STRONG_INLINE void _init2(const Scalar& val0, const Scalar& val1, typename internal::enable_if::type* = 0) + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(const T0& val0, const T1& val1, typename internal::enable_if::type* = 0) { EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 2) - m_storage.data()[0] = val0; - m_storage.data()[1] = val1; + m_storage.data()[0] = Scalar(val0); + m_storage.data()[1] = Scalar(val1); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init2(const Index& val0, const Index& val1, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime==2,T1>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 2) + m_storage.data()[0] = Scalar(val0); + m_storage.data()[1] = Scalar(val1); } + // The argument is convertible to the Index type and we either have a non 1x1 Matrix, or a dynamic-sized Array, + // then the argument is meant to be the size of the object. + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(Index size, typename internal::enable_if< (Base::SizeAtCompileTime!=1 || !internal::is_convertible::value) + && ((!internal::is_same::XprKind,ArrayXpr>::value || Base::SizeAtCompileTime==Dynamic)),T>::type* = 0) + { + // NOTE MSVC 2008 complains if we directly put bool(NumTraits::IsInteger) as the EIGEN_STATIC_ASSERT argument. + const bool is_integer = NumTraits::IsInteger; + EIGEN_UNUSED_VARIABLE(is_integer); + EIGEN_STATIC_ASSERT(is_integer, + FLOATING_POINT_ARGUMENT_PASSED__INTEGER_WAS_EXPECTED) + resize(size); + } + + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type can be implicitely converted) + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar& val0, typename internal::enable_if::value,T>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 1) + m_storage.data()[0] = val0; + } + + // We have a 1x1 matrix/array => the argument is interpreted as the value of the unique coefficient (case where scalar type match the index type) + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Index& val0, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime==1 + && internal::is_convertible::value,T*>::type* = 0) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(PlainObjectBase, 1) + m_storage.data()[0] = Scalar(val0); + } + + // Initialize a fixed size matrix from a pointer to raw data + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar* data){ + this->_set_noalias(ConstMapType(data)); + } + + // Initialize an arbitrary matrix from a dense expression + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const DenseBase& other){ + this->_set_noalias(other); + } + + // Initialize an arbitrary matrix from an object convertible to the Derived type. + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Derived& other){ + this->_set_noalias(other); + } + + // Initialize an arbitrary matrix from a generic Eigen expression + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const EigenBase& other){ + this->derived() = other; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const ReturnByValue& other) + { + resize(other.rows(), other.cols()); + other.evalTo(this->derived()); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const RotationBase& r) + { + this->derived() = r; + } + + // For fixed-size Array + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Scalar& val0, + typename internal::enable_if< Base::SizeAtCompileTime!=Dynamic + && Base::SizeAtCompileTime!=1 + && internal::is_convertible::value + && internal::is_same::XprKind,ArrayXpr>::value,T>::type* = 0) + { + Base::setConstant(val0); + } + + // For fixed-size Array + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void _init1(const Index& val0, + typename internal::enable_if< (!internal::is_same::value) + && (internal::is_same::value) + && Base::SizeAtCompileTime!=Dynamic + && Base::SizeAtCompileTime!=1 + && internal::is_convertible::value + && internal::is_same::XprKind,ArrayXpr>::value,T*>::type* = 0) + { + Base::setConstant(val0); + } + template friend struct internal::matrix_swap_impl; - /** \internal generic implementation of swap for dense storage since for dynamic-sized matrices of same type it is enough to swap the - * data pointers. + public: + +#ifndef EIGEN_PARSED_BY_DOXYGEN + /** \internal + * \brief Override DenseBase::swap() since for dynamic-sized matrices + * of same type it is enough to swap the data pointers. */ template - void _swap(DenseBase const & other) + EIGEN_DEVICE_FUNC + void swap(DenseBase & other) { enum { SwapPointers = internal::is_same::value && Base::SizeAtCompileTime==Dynamic }; - internal::matrix_swap_impl::run(this->derived(), other.const_cast_derived()); + internal::matrix_swap_impl::run(this->derived(), other.derived()); } - - public: -#ifndef EIGEN_PARSED_BY_DOXYGEN + + /** \internal + * \brief const version forwarded to DenseBase::swap + */ + template + EIGEN_DEVICE_FUNC + void swap(DenseBase const & other) + { Base::swap(other.derived()); } + + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void _check_template_params() { EIGEN_STATIC_ASSERT((EIGEN_IMPLIES(MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1, (Options&RowMajor)==RowMajor) @@ -697,10 +907,9 @@ class PlainObjectBase : public internal::dense_xpr_base::type && (Options & (DontAlign|RowMajor)) == Options), INVALID_MATRIX_TEMPLATE_PARAMETERS) } -#endif -private: - enum { ThisConstantIsPrivateInPlainObjectBase }; + enum { IsPlainObjectBase = 1 }; +#endif }; namespace internal { @@ -708,7 +917,6 @@ namespace internal { template struct conservative_resize_like_impl { - typedef typename Derived::Index Index; static void run(DenseBase& _this, Index rows, Index cols) { if (_this.rows() == rows && _this.cols() == cols) return; @@ -724,8 +932,8 @@ struct conservative_resize_like_impl { // The storage order does not allow us to use reallocation. typename Derived::PlainObject tmp(rows,cols); - const Index common_rows = (std::min)(rows, _this.rows()); - const Index common_cols = (std::min)(cols, _this.cols()); + const Index common_rows = numext::mini(rows, _this.rows()); + const Index common_cols = numext::mini(cols, _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); _this.derived().swap(tmp); } @@ -758,8 +966,8 @@ struct conservative_resize_like_impl { // The storage order does not allow us to use reallocation. typename Derived::PlainObject tmp(other); - const Index common_rows = (std::min)(tmp.rows(), _this.rows()); - const Index common_cols = (std::min)(tmp.cols(), _this.cols()); + const Index common_rows = numext::mini(tmp.rows(), _this.rows()); + const Index common_cols = numext::mini(tmp.cols(), _this.cols()); tmp.block(0,0,common_rows,common_cols) = _this.block(0,0,common_rows,common_cols); _this.derived().swap(tmp); } @@ -774,7 +982,6 @@ struct conservative_resize_like_impl { using conservative_resize_like_impl::run; - typedef typename Derived::Index Index; static void run(DenseBase& _this, Index size) { const Index new_rows = Derived::RowsAtCompileTime==1 ? 1 : size; @@ -800,6 +1007,7 @@ struct conservative_resize_like_impl template struct matrix_swap_impl { + EIGEN_DEVICE_FUNC static inline void run(MatrixTypeA& a, MatrixTypeB& b) { a.base().swap(b); @@ -809,6 +1017,7 @@ struct matrix_swap_impl template struct matrix_swap_impl { + EIGEN_DEVICE_FUNC static inline void run(MatrixTypeA& a, MatrixTypeB& b) { static_cast(a).m_storage.swap(static_cast(b).m_storage); diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h new file mode 100644 index 000000000..ae0c94b38 --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Product.h @@ -0,0 +1,186 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2011 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_PRODUCT_H +#define EIGEN_PRODUCT_H + +namespace Eigen { + +template class ProductImpl; + +namespace internal { + +template +struct traits > +{ + typedef typename remove_all::type LhsCleaned; + typedef typename remove_all::type RhsCleaned; + typedef traits LhsTraits; + typedef traits RhsTraits; + + typedef MatrixXpr XprKind; + + typedef typename ScalarBinaryOpTraits::Scalar, typename traits::Scalar>::ReturnType Scalar; + typedef typename product_promote_storage_type::ret>::ret StorageKind; + typedef typename promote_index_type::type StorageIndex; + + enum { + RowsAtCompileTime = LhsTraits::RowsAtCompileTime, + ColsAtCompileTime = RhsTraits::ColsAtCompileTime, + MaxRowsAtCompileTime = LhsTraits::MaxRowsAtCompileTime, + MaxColsAtCompileTime = RhsTraits::MaxColsAtCompileTime, + + // FIXME: only needed by GeneralMatrixMatrixTriangular + InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(LhsTraits::ColsAtCompileTime, RhsTraits::RowsAtCompileTime), + + // The storage order is somewhat arbitrary here. The correct one will be determined through the evaluator. + Flags = (MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1) ? RowMajorBit + : (MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1) ? 0 + : ( ((LhsTraits::Flags&NoPreferredStorageOrderBit) && (RhsTraits::Flags&RowMajorBit)) + || ((RhsTraits::Flags&NoPreferredStorageOrderBit) && (LhsTraits::Flags&RowMajorBit)) ) ? RowMajorBit + : NoPreferredStorageOrderBit + }; +}; + +} // end namespace internal + +/** \class Product + * \ingroup Core_Module + * + * \brief Expression of the product of two arbitrary matrices or vectors + * + * \tparam _Lhs the type of the left-hand side expression + * \tparam _Rhs the type of the right-hand side expression + * + * This class represents an expression of the product of two arbitrary matrices. + * + * The other template parameters are: + * \tparam Option can be DefaultProduct, AliasFreeProduct, or LazyProduct + * + */ +template +class Product : public ProductImpl<_Lhs,_Rhs,Option, + typename internal::product_promote_storage_type::StorageKind, + typename internal::traits<_Rhs>::StorageKind, + internal::product_type<_Lhs,_Rhs>::ret>::ret> +{ + public: + + typedef _Lhs Lhs; + typedef _Rhs Rhs; + + typedef typename ProductImpl< + Lhs, Rhs, Option, + typename internal::product_promote_storage_type::StorageKind, + typename internal::traits::StorageKind, + internal::product_type::ret>::ret>::Base Base; + EIGEN_GENERIC_PUBLIC_INTERFACE(Product) + + typedef typename internal::ref_selector::type LhsNested; + typedef typename internal::ref_selector::type RhsNested; + typedef typename internal::remove_all::type LhsNestedCleaned; + typedef typename internal::remove_all::type RhsNestedCleaned; + + EIGEN_DEVICE_FUNC Product(const Lhs& lhs, const Rhs& rhs) : m_lhs(lhs), m_rhs(rhs) + { + eigen_assert(lhs.cols() == rhs.rows() + && "invalid matrix product" + && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); + } + + EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); } + + EIGEN_DEVICE_FUNC const LhsNestedCleaned& lhs() const { return m_lhs; } + EIGEN_DEVICE_FUNC const RhsNestedCleaned& rhs() const { return m_rhs; } + + protected: + + LhsNested m_lhs; + RhsNested m_rhs; +}; + +namespace internal { + +template::ret> +class dense_product_base + : public internal::dense_xpr_base >::type +{}; + +/** Convertion to scalar for inner-products */ +template +class dense_product_base + : public internal::dense_xpr_base >::type +{ + typedef Product ProductXpr; + typedef typename internal::dense_xpr_base::type Base; +public: + using Base::derived; + typedef typename Base::Scalar Scalar; + + operator const Scalar() const + { + return internal::evaluator(derived()).coeff(0,0); + } +}; + +} // namespace internal + +// Generic API dispatcher +template +class ProductImpl : public internal::generic_xpr_base, MatrixXpr, StorageKind>::type +{ + public: + typedef typename internal::generic_xpr_base, MatrixXpr, StorageKind>::type Base; +}; + +template +class ProductImpl + : public internal::dense_product_base +{ + typedef Product Derived; + + public: + + typedef typename internal::dense_product_base Base; + EIGEN_DENSE_PUBLIC_INTERFACE(Derived) + protected: + enum { + IsOneByOne = (RowsAtCompileTime == 1 || RowsAtCompileTime == Dynamic) && + (ColsAtCompileTime == 1 || ColsAtCompileTime == Dynamic), + EnableCoeff = IsOneByOne || Option==LazyProduct + }; + + public: + + EIGEN_DEVICE_FUNC Scalar coeff(Index row, Index col) const + { + EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); + eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); + + return internal::evaluator(derived()).coeff(row,col); + } + + EIGEN_DEVICE_FUNC Scalar coeff(Index i) const + { + EIGEN_STATIC_ASSERT(EnableCoeff, THIS_METHOD_IS_ONLY_FOR_INNER_OR_LAZY_PRODUCTS); + eigen_assert( (Option==LazyProduct) || (this->rows() == 1 && this->cols() == 1) ); + + return internal::evaluator(derived()).coeff(i); + } + + +}; + +} // end namespace Eigen + +#endif // EIGEN_PRODUCT_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h deleted file mode 100644 index cf74470a9..000000000 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductBase.h +++ /dev/null @@ -1,290 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009-2010 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_PRODUCTBASE_H -#define EIGEN_PRODUCTBASE_H - -namespace Eigen { - -/** \class ProductBase - * \ingroup Core_Module - * - */ - -namespace internal { -template -struct traits > -{ - typedef MatrixXpr XprKind; - typedef typename remove_all<_Lhs>::type Lhs; - typedef typename remove_all<_Rhs>::type Rhs; - typedef typename scalar_product_traits::ReturnType Scalar; - typedef typename promote_storage_type::StorageKind, - typename traits::StorageKind>::ret StorageKind; - typedef typename promote_index_type::Index, - typename traits::Index>::type Index; - enum { - RowsAtCompileTime = traits::RowsAtCompileTime, - ColsAtCompileTime = traits::ColsAtCompileTime, - MaxRowsAtCompileTime = traits::MaxRowsAtCompileTime, - MaxColsAtCompileTime = traits::MaxColsAtCompileTime, - Flags = (MaxRowsAtCompileTime==1 ? RowMajorBit : 0) - | EvalBeforeNestingBit | EvalBeforeAssigningBit | NestByRefBit, - // Note that EvalBeforeNestingBit and NestByRefBit - // are not used in practice because nested is overloaded for products - CoeffReadCost = 0 // FIXME why is it needed ? - }; -}; -} - -#define EIGEN_PRODUCT_PUBLIC_INTERFACE(Derived) \ - typedef ProductBase Base; \ - EIGEN_DENSE_PUBLIC_INTERFACE(Derived) \ - typedef typename Base::LhsNested LhsNested; \ - typedef typename Base::_LhsNested _LhsNested; \ - typedef typename Base::LhsBlasTraits LhsBlasTraits; \ - typedef typename Base::ActualLhsType ActualLhsType; \ - typedef typename Base::_ActualLhsType _ActualLhsType; \ - typedef typename Base::RhsNested RhsNested; \ - typedef typename Base::_RhsNested _RhsNested; \ - typedef typename Base::RhsBlasTraits RhsBlasTraits; \ - typedef typename Base::ActualRhsType ActualRhsType; \ - typedef typename Base::_ActualRhsType _ActualRhsType; \ - using Base::m_lhs; \ - using Base::m_rhs; - -template -class ProductBase : public MatrixBase -{ - public: - typedef MatrixBase Base; - EIGEN_DENSE_PUBLIC_INTERFACE(ProductBase) - - typedef typename Lhs::Nested LhsNested; - typedef typename internal::remove_all::type _LhsNested; - typedef internal::blas_traits<_LhsNested> LhsBlasTraits; - typedef typename LhsBlasTraits::DirectLinearAccessType ActualLhsType; - typedef typename internal::remove_all::type _ActualLhsType; - typedef typename internal::traits::Scalar LhsScalar; - - typedef typename Rhs::Nested RhsNested; - typedef typename internal::remove_all::type _RhsNested; - typedef internal::blas_traits<_RhsNested> RhsBlasTraits; - typedef typename RhsBlasTraits::DirectLinearAccessType ActualRhsType; - typedef typename internal::remove_all::type _ActualRhsType; - typedef typename internal::traits::Scalar RhsScalar; - - // Diagonal of a product: no need to evaluate the arguments because they are going to be evaluated only once - typedef CoeffBasedProduct FullyLazyCoeffBaseProductType; - - public: - -#ifndef EIGEN_NO_MALLOC - typedef typename Base::PlainObject BasePlainObject; - typedef Matrix DynPlainObject; - typedef typename internal::conditional<(BasePlainObject::SizeAtCompileTime==Dynamic) || (BasePlainObject::SizeAtCompileTime*int(sizeof(Scalar)) < int(EIGEN_STACK_ALLOCATION_LIMIT)), - BasePlainObject, DynPlainObject>::type PlainObject; -#else - typedef typename Base::PlainObject PlainObject; -#endif - - ProductBase(const Lhs& a_lhs, const Rhs& a_rhs) - : m_lhs(a_lhs), m_rhs(a_rhs) - { - eigen_assert(a_lhs.cols() == a_rhs.rows() - && "invalid matrix product" - && "if you wanted a coeff-wise or a dot product use the respective explicit functions"); - } - - inline Index rows() const { return m_lhs.rows(); } - inline Index cols() const { return m_rhs.cols(); } - - template - inline void evalTo(Dest& dst) const { dst.setZero(); scaleAndAddTo(dst,Scalar(1)); } - - template - inline void addTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(1)); } - - template - inline void subTo(Dest& dst) const { scaleAndAddTo(dst,Scalar(-1)); } - - template - inline void scaleAndAddTo(Dest& dst, const Scalar& alpha) const { derived().scaleAndAddTo(dst,alpha); } - - const _LhsNested& lhs() const { return m_lhs; } - const _RhsNested& rhs() const { return m_rhs; } - - // Implicit conversion to the nested type (trigger the evaluation of the product) - operator const PlainObject& () const - { - m_result.resize(m_lhs.rows(), m_rhs.cols()); - derived().evalTo(m_result); - return m_result; - } - - const Diagonal diagonal() const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs); } - - template - const Diagonal diagonal() const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs); } - - const Diagonal diagonal(Index index) const - { return FullyLazyCoeffBaseProductType(m_lhs, m_rhs).diagonal(index); } - - // restrict coeff accessors to 1x1 expressions. No need to care about mutators here since this isnt a Lvalue expression - typename Base::CoeffReturnType coeff(Index row, Index col) const - { -#ifdef EIGEN2_SUPPORT - return lhs().row(row).cwiseProduct(rhs().col(col).transpose()).sum(); -#else - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - Matrix result = *this; - return result.coeff(row,col); -#endif - } - - typename Base::CoeffReturnType coeff(Index i) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - Matrix result = *this; - return result.coeff(i); - } - - const Scalar& coeffRef(Index row, Index col) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeffRef(row,col); - } - - const Scalar& coeffRef(Index i) const - { - EIGEN_STATIC_ASSERT_SIZE_1x1(Derived) - eigen_assert(this->rows() == 1 && this->cols() == 1); - return derived().coeffRef(i); - } - - protected: - - LhsNested m_lhs; - RhsNested m_rhs; - - mutable PlainObject m_result; -}; - -// here we need to overload the nested rule for products -// such that the nested type is a const reference to a plain matrix -namespace internal { -template -struct nested, N, PlainObject> -{ - typedef typename GeneralProduct::PlainObject const& type; -}; -template -struct nested, N, PlainObject> -{ - typedef typename GeneralProduct::PlainObject const& type; -}; -} - -template -class ScaledProduct; - -// Note that these two operator* functions are not defined as member -// functions of ProductBase, because, otherwise we would have to -// define all overloads defined in MatrixBase. Furthermore, Using -// "using Base::operator*" would not work with MSVC. -// -// Also note that here we accept any compatible scalar types -template -const ScaledProduct -operator*(const ProductBase& prod, const typename Derived::Scalar& x) -{ return ScaledProduct(prod.derived(), x); } - -template -typename internal::enable_if::value, - const ScaledProduct >::type -operator*(const ProductBase& prod, const typename Derived::RealScalar& x) -{ return ScaledProduct(prod.derived(), x); } - - -template -const ScaledProduct -operator*(const typename Derived::Scalar& x,const ProductBase& prod) -{ return ScaledProduct(prod.derived(), x); } - -template -typename internal::enable_if::value, - const ScaledProduct >::type -operator*(const typename Derived::RealScalar& x,const ProductBase& prod) -{ return ScaledProduct(prod.derived(), x); } - -namespace internal { -template -struct traits > - : traits, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> > -{ - typedef typename traits::StorageKind StorageKind; -}; -} - -template -class ScaledProduct - : public ProductBase, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> -{ - public: - typedef ProductBase, - typename NestedProduct::_LhsNested, - typename NestedProduct::_RhsNested> Base; - typedef typename Base::Scalar Scalar; - typedef typename Base::PlainObject PlainObject; -// EIGEN_PRODUCT_PUBLIC_INTERFACE(ScaledProduct) - - ScaledProduct(const NestedProduct& prod, const Scalar& x) - : Base(prod.lhs(),prod.rhs()), m_prod(prod), m_alpha(x) {} - - template - inline void evalTo(Dest& dst) const { dst.setZero(); scaleAndAddTo(dst, Scalar(1)); } - - template - inline void addTo(Dest& dst) const { scaleAndAddTo(dst, Scalar(1)); } - - template - inline void subTo(Dest& dst) const { scaleAndAddTo(dst, Scalar(-1)); } - - template - inline void scaleAndAddTo(Dest& dst, const Scalar& a_alpha) const { m_prod.derived().scaleAndAddTo(dst,a_alpha * m_alpha); } - - const Scalar& alpha() const { return m_alpha; } - - protected: - const NestedProduct& m_prod; - Scalar m_alpha; -}; - -/** \internal - * Overloaded to perform an efficient C = (A*B).lazy() */ -template -template -Derived& MatrixBase::lazyAssign(const ProductBase& other) -{ - other.derived().evalTo(derived()); - return derived(); -} - -} // end namespace Eigen - -#endif // EIGEN_PRODUCTBASE_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductEvaluators.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductEvaluators.h new file mode 100644 index 000000000..c42725dbd --- /dev/null +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ProductEvaluators.h @@ -0,0 +1,1105 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2008-2010 Gael Guennebaud +// Copyright (C) 2011 Jitse Niesen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#ifndef EIGEN_PRODUCTEVALUATORS_H +#define EIGEN_PRODUCTEVALUATORS_H + +namespace Eigen { + +namespace internal { + +/** \internal + * Evaluator of a product expression. + * Since products require special treatments to handle all possible cases, + * we simply deffer the evaluation logic to a product_evaluator class + * which offers more partial specialization possibilities. + * + * \sa class product_evaluator + */ +template +struct evaluator > + : public product_evaluator > +{ + typedef Product XprType; + typedef product_evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) : Base(xpr) {} +}; + +// Catch "scalar * ( A * B )" and transform it to "(A*scalar) * B" +// TODO we should apply that rule only if that's really helpful +template +struct evaluator_assume_aliasing, + const CwiseNullaryOp, Plain1>, + const Product > > +{ + static const bool value = true; +}; +template +struct evaluator, + const CwiseNullaryOp, Plain1>, + const Product > > + : public evaluator > +{ + typedef CwiseBinaryOp, + const CwiseNullaryOp, Plain1>, + const Product > XprType; + typedef evaluator > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : Base(xpr.lhs().functor().m_other * xpr.rhs().lhs() * xpr.rhs().rhs()) + {} +}; + + +template +struct evaluator, DiagIndex> > + : public evaluator, DiagIndex> > +{ + typedef Diagonal, DiagIndex> XprType; + typedef evaluator, DiagIndex> > Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : Base(Diagonal, DiagIndex>( + Product(xpr.nestedExpression().lhs(), xpr.nestedExpression().rhs()), + xpr.index() )) + {} +}; + + +// Helper class to perform a matrix product with the destination at hand. +// Depending on the sizes of the factors, there are different evaluation strategies +// as controlled by internal::product_type. +template< typename Lhs, typename Rhs, + typename LhsShape = typename evaluator_traits::Shape, + typename RhsShape = typename evaluator_traits::Shape, + int ProductType = internal::product_type::value> +struct generic_product_impl; + +template +struct evaluator_assume_aliasing > { + static const bool value = true; +}; + +// This is the default evaluator implementation for products: +// It creates a temporary and call generic_product_impl +template +struct product_evaluator, ProductTag, LhsShape, RhsShape> + : public evaluator::PlainObject> +{ + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + typedef evaluator Base; + enum { + Flags = Base::Flags | EvalBeforeNestingBit + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit product_evaluator(const XprType& xpr) + : m_result(xpr.rows(), xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + +// FIXME shall we handle nested_eval here?, +// if so, then we must take care at removing the call to nested_eval in the specializations (e.g., in permutation_matrix_product, transposition_matrix_product, etc.) +// typedef typename internal::nested_eval::type LhsNested; +// typedef typename internal::nested_eval::type RhsNested; +// typedef typename internal::remove_all::type LhsNestedCleaned; +// typedef typename internal::remove_all::type RhsNestedCleaned; +// +// const LhsNested lhs(xpr.lhs()); +// const RhsNested rhs(xpr.rhs()); +// +// generic_product_impl::evalTo(m_result, lhs, rhs); + + generic_product_impl::evalTo(m_result, xpr.lhs(), xpr.rhs()); + } + +protected: + PlainObject m_result; +}; + +// The following three shortcuts are enabled only if the scalar types match excatly. +// TODO: we could enable them for different scalar types when the product is not vectorized. + +// Dense = Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op &) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if((dst.rows()!=dstRows) || (dst.cols()!=dstCols)) + dst.resize(dstRows, dstCols); + // FIXME shall we handle nested_eval here? + generic_product_impl::evalTo(dst, src.lhs(), src.rhs()); + } +}; + +// Dense += Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::add_assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op &) + { + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + // FIXME shall we handle nested_eval here? + generic_product_impl::addTo(dst, src.lhs(), src.rhs()); + } +}; + +// Dense -= Product +template< typename DstXprType, typename Lhs, typename Rhs, int Options, typename Scalar> +struct Assignment, internal::sub_assign_op, Dense2Dense, + typename enable_if<(Options==DefaultProduct || Options==AliasFreeProduct)>::type> +{ + typedef Product SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op &) + { + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + // FIXME shall we handle nested_eval here? + generic_product_impl::subTo(dst, src.lhs(), src.rhs()); + } +}; + + +// Dense ?= scalar * Product +// TODO we should apply that rule if that's really helpful +// for instance, this is not good for inner products +template< typename DstXprType, typename Lhs, typename Rhs, typename AssignFunc, typename Scalar, typename ScalarBis, typename Plain> +struct Assignment, const CwiseNullaryOp,Plain>, + const Product >, AssignFunc, Dense2Dense> +{ + typedef CwiseBinaryOp, + const CwiseNullaryOp,Plain>, + const Product > SrcXprType; + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const AssignFunc& func) + { + call_assignment_no_alias(dst, (src.lhs().functor().m_other * src.rhs().lhs())*src.rhs().rhs(), func); + } +}; + +//---------------------------------------- +// Catch "Dense ?= xpr + Product<>" expression to save one temporary +// FIXME we could probably enable these rules for any product, i.e., not only Dense and DefaultProduct + +template +struct evaluator_assume_aliasing::Scalar>, const OtherXpr, + const Product >, DenseShape > { + static const bool value = true; +}; + +template +struct evaluator_assume_aliasing::Scalar>, const OtherXpr, + const Product >, DenseShape > { + static const bool value = true; +}; + +template +struct assignment_from_xpr_op_product +{ + template + static EIGEN_STRONG_INLINE + void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/) + { + call_assignment_no_alias(dst, src.lhs(), Func1()); + call_assignment_no_alias(dst, src.rhs(), Func2()); + } +}; + +#define EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(ASSIGN_OP,BINOP,ASSIGN_OP2) \ + template< typename DstXprType, typename OtherXpr, typename Lhs, typename Rhs, typename DstScalar, typename SrcScalar, typename OtherScalar,typename ProdScalar> \ + struct Assignment, const OtherXpr, \ + const Product >, internal::ASSIGN_OP, Dense2Dense> \ + : assignment_from_xpr_op_product, internal::ASSIGN_OP, internal::ASSIGN_OP2 > \ + {} + +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(assign_op, scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(add_assign_op,scalar_sum_op,add_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(sub_assign_op,scalar_sum_op,sub_assign_op); + +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(assign_op, scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(add_assign_op,scalar_difference_op,sub_assign_op); +EIGEN_CATCH_ASSIGN_XPR_OP_PRODUCT(sub_assign_op,scalar_difference_op,add_assign_op); + +//---------------------------------------- + +template +struct generic_product_impl +{ + template + static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + dst.coeffRef(0,0) = (lhs.transpose().cwiseProduct(rhs)).sum(); + } + + template + static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + dst.coeffRef(0,0) += (lhs.transpose().cwiseProduct(rhs)).sum(); + } + + template + static void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { dst.coeffRef(0,0) -= (lhs.transpose().cwiseProduct(rhs)).sum(); } +}; + + +/*********************************************************************** +* Implementation of outer dense * dense vector product +***********************************************************************/ + +// Column major result +template +void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const false_type&) +{ + evaluator rhsEval(rhs); + typename nested_eval::type actual_lhs(lhs); + // FIXME if cols is large enough, then it might be useful to make sure that lhs is sequentially stored + // FIXME not very good if rhs is real and lhs complex while alpha is real too + const Index cols = dst.cols(); + for (Index j=0; j +void outer_product_selector_run(Dst& dst, const Lhs &lhs, const Rhs &rhs, const Func& func, const true_type&) +{ + evaluator lhsEval(lhs); + typename nested_eval::type actual_rhs(rhs); + // FIXME if rows is large enough, then it might be useful to make sure that rhs is sequentially stored + // FIXME not very good if lhs is real and rhs complex while alpha is real too + const Index rows = dst.rows(); + for (Index i=0; i +struct generic_product_impl +{ + template struct is_row_major : internal::conditional<(int(T::Flags)&RowMajorBit), internal::true_type, internal::false_type>::type {}; + typedef typename Product::Scalar Scalar; + + // TODO it would be nice to be able to exploit our *_assign_op functors for that purpose + struct set { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() = src; } }; + struct add { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() += src; } }; + struct sub { template void operator()(const Dst& dst, const Src& src) const { dst.const_cast_derived() -= src; } }; + struct adds { + Scalar m_scale; + explicit adds(const Scalar& s) : m_scale(s) {} + template void operator()(const Dst& dst, const Src& src) const { + dst.const_cast_derived() += m_scale * src; + } + }; + + template + static inline void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, set(), is_row_major()); + } + + template + static inline void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, add(), is_row_major()); + } + + template + static inline void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + internal::outer_product_selector_run(dst, lhs, rhs, sub(), is_row_major()); + } + + template + static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + internal::outer_product_selector_run(dst, lhs, rhs, adds(alpha), is_row_major()); + } + +}; + + +// This base class provides default implementations for evalTo, addTo, subTo, in terms of scaleAndAddTo +template +struct generic_product_impl_base +{ + typedef typename Product::Scalar Scalar; + + template + static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { dst.setZero(); scaleAndAddTo(dst, lhs, rhs, Scalar(1)); } + + template + static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { scaleAndAddTo(dst,lhs, rhs, Scalar(1)); } + + template + static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { scaleAndAddTo(dst, lhs, rhs, Scalar(-1)); } + + template + static EIGEN_STRONG_INLINE void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { Derived::scaleAndAddTo(dst,lhs,rhs,alpha); } + +}; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename nested_eval::type LhsNested; + typedef typename nested_eval::type RhsNested; + typedef typename Product::Scalar Scalar; + enum { Side = Lhs::IsVectorAtCompileTime ? OnTheLeft : OnTheRight }; + typedef typename internal::remove_all::type>::type MatrixType; + + template + static EIGEN_STRONG_INLINE void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + LhsNested actual_lhs(lhs); + RhsNested actual_rhs(rhs); + internal::gemv_dense_selector::HasUsableDirectAccess) + >::run(actual_lhs, actual_rhs, dst, alpha); + } +}; + +template +struct generic_product_impl +{ + typedef typename Product::Scalar Scalar; + + template + static EIGEN_STRONG_INLINE void evalTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // Same as: dst.noalias() = lhs.lazyProduct(rhs); + // but easier on the compiler side + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::assign_op()); + } + + template + static EIGEN_STRONG_INLINE void addTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // dst.noalias() += lhs.lazyProduct(rhs); + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::add_assign_op()); + } + + template + static EIGEN_STRONG_INLINE void subTo(Dst& dst, const Lhs& lhs, const Rhs& rhs) + { + // dst.noalias() -= lhs.lazyProduct(rhs); + call_assignment_no_alias(dst, lhs.lazyProduct(rhs), internal::sub_assign_op()); + } + +// template +// static inline void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) +// { dst.noalias() += alpha * lhs.lazyProduct(rhs); } +}; + +// This specialization enforces the use of a coefficient-based evaluation strategy +template +struct generic_product_impl + : generic_product_impl {}; + +// Case 2: Evaluate coeff by coeff +// +// This is mostly taken from CoeffBasedProduct.h +// The main difference is that we add an extra argument to the etor_product_*_impl::run() function +// for the inner dimension of the product, because evaluator object do not know their size. + +template +struct etor_product_coeff_impl; + +template +struct etor_product_packet_impl; + +template +struct product_evaluator, ProductTag, DenseShape, DenseShape> + : evaluator_base > +{ + typedef Product XprType; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + explicit product_evaluator(const XprType& xpr) + : m_lhs(xpr.lhs()), + m_rhs(xpr.rhs()), + m_lhsImpl(m_lhs), // FIXME the creation of the evaluator objects should result in a no-op, but check that! + m_rhsImpl(m_rhs), // Moreover, they are only useful for the packet path, so we could completely disable them when not needed, + // or perhaps declare them on the fly on the packet method... We have experiment to check what's best. + m_innerDim(xpr.lhs().cols()) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::MulCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::AddCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); +#if 0 + std::cerr << "LhsOuterStrideBytes= " << LhsOuterStrideBytes << "\n"; + std::cerr << "RhsOuterStrideBytes= " << RhsOuterStrideBytes << "\n"; + std::cerr << "LhsAlignment= " << LhsAlignment << "\n"; + std::cerr << "RhsAlignment= " << RhsAlignment << "\n"; + std::cerr << "CanVectorizeLhs= " << CanVectorizeLhs << "\n"; + std::cerr << "CanVectorizeRhs= " << CanVectorizeRhs << "\n"; + std::cerr << "CanVectorizeInner= " << CanVectorizeInner << "\n"; + std::cerr << "EvalToRowMajor= " << EvalToRowMajor << "\n"; + std::cerr << "Alignment= " << Alignment << "\n"; + std::cerr << "Flags= " << Flags << "\n"; +#endif + } + + // Everything below here is taken from CoeffBasedProduct.h + + typedef typename internal::nested_eval::type LhsNested; + typedef typename internal::nested_eval::type RhsNested; + + typedef typename internal::remove_all::type LhsNestedCleaned; + typedef typename internal::remove_all::type RhsNestedCleaned; + + typedef evaluator LhsEtorType; + typedef evaluator RhsEtorType; + + enum { + RowsAtCompileTime = LhsNestedCleaned::RowsAtCompileTime, + ColsAtCompileTime = RhsNestedCleaned::ColsAtCompileTime, + InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(LhsNestedCleaned::ColsAtCompileTime, RhsNestedCleaned::RowsAtCompileTime), + MaxRowsAtCompileTime = LhsNestedCleaned::MaxRowsAtCompileTime, + MaxColsAtCompileTime = RhsNestedCleaned::MaxColsAtCompileTime + }; + + typedef typename find_best_packet::type LhsVecPacketType; + typedef typename find_best_packet::type RhsVecPacketType; + + enum { + + LhsCoeffReadCost = LhsEtorType::CoeffReadCost, + RhsCoeffReadCost = RhsEtorType::CoeffReadCost, + CoeffReadCost = InnerSize==0 ? NumTraits::ReadCost + : InnerSize == Dynamic ? HugeCost + : InnerSize * (NumTraits::MulCost + LhsCoeffReadCost + RhsCoeffReadCost) + + (InnerSize - 1) * NumTraits::AddCost, + + Unroll = CoeffReadCost <= EIGEN_UNROLLING_LIMIT, + + LhsFlags = LhsEtorType::Flags, + RhsFlags = RhsEtorType::Flags, + + LhsRowMajor = LhsFlags & RowMajorBit, + RhsRowMajor = RhsFlags & RowMajorBit, + + LhsVecPacketSize = unpacket_traits::size, + RhsVecPacketSize = unpacket_traits::size, + + // Here, we don't care about alignment larger than the usable packet size. + LhsAlignment = EIGEN_PLAIN_ENUM_MIN(LhsEtorType::Alignment,LhsVecPacketSize*int(sizeof(typename LhsNestedCleaned::Scalar))), + RhsAlignment = EIGEN_PLAIN_ENUM_MIN(RhsEtorType::Alignment,RhsVecPacketSize*int(sizeof(typename RhsNestedCleaned::Scalar))), + + SameType = is_same::value, + + CanVectorizeRhs = bool(RhsRowMajor) && (RhsFlags & PacketAccessBit) && (ColsAtCompileTime!=1), + CanVectorizeLhs = (!LhsRowMajor) && (LhsFlags & PacketAccessBit) && (RowsAtCompileTime!=1), + + EvalToRowMajor = (MaxRowsAtCompileTime==1&&MaxColsAtCompileTime!=1) ? 1 + : (MaxColsAtCompileTime==1&&MaxRowsAtCompileTime!=1) ? 0 + : (bool(RhsRowMajor) && !CanVectorizeLhs), + + Flags = ((unsigned int)(LhsFlags | RhsFlags) & HereditaryBits & ~RowMajorBit) + | (EvalToRowMajor ? RowMajorBit : 0) + // TODO enable vectorization for mixed types + | (SameType && (CanVectorizeLhs || CanVectorizeRhs) ? PacketAccessBit : 0) + | (XprType::IsVectorAtCompileTime ? LinearAccessBit : 0), + + LhsOuterStrideBytes = int(LhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename LhsNestedCleaned::Scalar)), + RhsOuterStrideBytes = int(RhsNestedCleaned::OuterStrideAtCompileTime) * int(sizeof(typename RhsNestedCleaned::Scalar)), + + Alignment = bool(CanVectorizeLhs) ? (LhsOuterStrideBytes<=0 || (int(LhsOuterStrideBytes) % EIGEN_PLAIN_ENUM_MAX(1,LhsAlignment))!=0 ? 0 : LhsAlignment) + : bool(CanVectorizeRhs) ? (RhsOuterStrideBytes<=0 || (int(RhsOuterStrideBytes) % EIGEN_PLAIN_ENUM_MAX(1,RhsAlignment))!=0 ? 0 : RhsAlignment) + : 0, + + /* CanVectorizeInner deserves special explanation. It does not affect the product flags. It is not used outside + * of Product. If the Product itself is not a packet-access expression, there is still a chance that the inner + * loop of the product might be vectorized. This is the meaning of CanVectorizeInner. Since it doesn't affect + * the Flags, it is safe to make this value depend on ActualPacketAccessBit, that doesn't affect the ABI. + */ + CanVectorizeInner = SameType + && LhsRowMajor + && (!RhsRowMajor) + && (LhsFlags & RhsFlags & ActualPacketAccessBit) + && (InnerSize % packet_traits::size == 0) + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CoeffReturnType coeff(Index row, Index col) const + { + return (m_lhs.row(row).transpose().cwiseProduct( m_rhs.col(col) )).sum(); + } + + /* Allow index-based non-packet access. It is impossible though to allow index-based packed access, + * which is why we don't set the LinearAccessBit. + * TODO: this seems possible when the result is a vector + */ + EIGEN_DEVICE_FUNC const CoeffReturnType coeff(Index index) const + { + const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; + const Index col = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? index : 0; + return (m_lhs.row(row).transpose().cwiseProduct( m_rhs.col(col) )).sum(); + } + + template + const PacketType packet(Index row, Index col) const + { + PacketType res; + typedef etor_product_packet_impl PacketImpl; + PacketImpl::run(row, col, m_lhsImpl, m_rhsImpl, m_innerDim, res); + return res; + } + + template + const PacketType packet(Index index) const + { + const Index row = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? 0 : index; + const Index col = (RowsAtCompileTime == 1 || MaxRowsAtCompileTime==1) ? index : 0; + return packet(row,col); + } + +protected: + typename internal::add_const_on_value_type::type m_lhs; + typename internal::add_const_on_value_type::type m_rhs; + + LhsEtorType m_lhsImpl; + RhsEtorType m_rhsImpl; + + // TODO: Get rid of m_innerDim if known at compile time + Index m_innerDim; +}; + +template +struct product_evaluator, LazyCoeffBasedProductMode, DenseShape, DenseShape> + : product_evaluator, CoeffBasedProductMode, DenseShape, DenseShape> +{ + typedef Product XprType; + typedef Product BaseProduct; + typedef product_evaluator Base; + enum { + Flags = Base::Flags | EvalBeforeNestingBit + }; + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(BaseProduct(xpr.lhs(),xpr.rhs())) + {} +}; + +/**************************************** +*** Coeff based product, Packet path *** +****************************************/ + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + { + etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); + res = pmadd(pset1(lhs.coeff(row, Index(UnrollingIndex-1))), rhs.template packet(Index(UnrollingIndex-1), col), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet &res) + { + etor_product_packet_impl::run(row, col, lhs, rhs, innerDim, res); + res = pmadd(lhs.template packet(row, Index(UnrollingIndex-1)), pset1(rhs.coeff(Index(UnrollingIndex-1), col)), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + { + res = pmul(pset1(lhs.coeff(row, Index(0))),rhs.template packet(Index(0), col)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index /*innerDim*/, Packet &res) + { + res = pmul(lhs.template packet(row, Index(0)), pset1(rhs.coeff(Index(0), col))); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + { + res = pset1(typename unpacket_traits::type(0)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index /*row*/, Index /*col*/, const Lhs& /*lhs*/, const Rhs& /*rhs*/, Index /*innerDim*/, Packet &res) + { + res = pset1(typename unpacket_traits::type(0)); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + { + res = pset1(typename unpacket_traits::type(0)); + for(Index i = 0; i < innerDim; ++i) + res = pmadd(pset1(lhs.coeff(row, i)), rhs.template packet(i, col), res); + } +}; + +template +struct etor_product_packet_impl +{ + static EIGEN_STRONG_INLINE void run(Index row, Index col, const Lhs& lhs, const Rhs& rhs, Index innerDim, Packet& res) + { + res = pset1(typename unpacket_traits::type(0)); + for(Index i = 0; i < innerDim; ++i) + res = pmadd(lhs.template packet(row, i), pset1(rhs.coeff(i, col)), res); + } +}; + + +/*************************************************************************** +* Triangular products +***************************************************************************/ +template +struct triangular_product_impl; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + triangular_product_impl + ::run(dst, lhs.nestedExpression(), rhs, alpha); + } +}; + +template +struct generic_product_impl +: generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + triangular_product_impl::run(dst, lhs, rhs.nestedExpression(), alpha); + } +}; + + +/*************************************************************************** +* SelfAdjoint products +***************************************************************************/ +template +struct selfadjoint_product_impl; + +template +struct generic_product_impl + : generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + selfadjoint_product_impl::run(dst, lhs.nestedExpression(), rhs, alpha); + } +}; + +template +struct generic_product_impl +: generic_product_impl_base > +{ + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha) + { + selfadjoint_product_impl::run(dst, lhs, rhs.nestedExpression(), alpha); + } +}; + + +/*************************************************************************** +* Diagonal products +***************************************************************************/ + +template +struct diagonal_product_evaluator_base + : evaluator_base +{ + typedef typename ScalarBinaryOpTraits::ReturnType Scalar; +public: + enum { + CoeffReadCost = NumTraits::MulCost + evaluator::CoeffReadCost + evaluator::CoeffReadCost, + + MatrixFlags = evaluator::Flags, + DiagFlags = evaluator::Flags, + _StorageOrder = MatrixFlags & RowMajorBit ? RowMajor : ColMajor, + _ScalarAccessOnDiag = !((int(_StorageOrder) == ColMajor && int(ProductOrder) == OnTheLeft) + ||(int(_StorageOrder) == RowMajor && int(ProductOrder) == OnTheRight)), + _SameTypes = is_same::value, + // FIXME currently we need same types, but in the future the next rule should be the one + //_Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && ((!_PacketOnDiag) || (_SameTypes && bool(int(DiagFlags)&PacketAccessBit))), + _Vectorizable = bool(int(MatrixFlags)&PacketAccessBit) && _SameTypes && (_ScalarAccessOnDiag || (bool(int(DiagFlags)&PacketAccessBit))), + _LinearAccessMask = (MatrixType::RowsAtCompileTime==1 || MatrixType::ColsAtCompileTime==1) ? LinearAccessBit : 0, + Flags = ((HereditaryBits|_LinearAccessMask) & (unsigned int)(MatrixFlags)) | (_Vectorizable ? PacketAccessBit : 0), + Alignment = evaluator::Alignment + }; + + diagonal_product_evaluator_base(const MatrixType &mat, const DiagonalType &diag) + : m_diagImpl(diag), m_matImpl(mat) + { + EIGEN_INTERNAL_CHECK_COST_VALUE(NumTraits::MulCost); + EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index idx) const + { + return m_diagImpl.coeff(idx) * m_matImpl.coeff(idx); + } + +protected: + template + EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::true_type) const + { + return internal::pmul(m_matImpl.template packet(row, col), + internal::pset1(m_diagImpl.coeff(id))); + } + + template + EIGEN_STRONG_INLINE PacketType packet_impl(Index row, Index col, Index id, internal::false_type) const + { + enum { + InnerSize = (MatrixType::Flags & RowMajorBit) ? MatrixType::ColsAtCompileTime : MatrixType::RowsAtCompileTime, + DiagonalPacketLoadMode = EIGEN_PLAIN_ENUM_MIN(LoadMode,((InnerSize%16) == 0) ? int(Aligned16) : int(evaluator::Alignment)) // FIXME hardcoded 16!! + }; + return internal::pmul(m_matImpl.template packet(row, col), + m_diagImpl.template packet(id)); + } + + evaluator m_diagImpl; + evaluator m_matImpl; +}; + +// diagonal * dense +template +struct product_evaluator, ProductTag, DiagonalShape, DenseShape> + : diagonal_product_evaluator_base, OnTheLeft> +{ + typedef diagonal_product_evaluator_base, OnTheLeft> Base; + using Base::m_diagImpl; + using Base::m_matImpl; + using Base::coeff; + typedef typename Base::Scalar Scalar; + + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + + enum { + StorageOrder = int(Rhs::Flags) & RowMajorBit ? RowMajor : ColMajor + }; + + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(xpr.rhs(), xpr.lhs().diagonal()) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const + { + return m_diagImpl.coeff(row) * m_matImpl.coeff(row, col); + } + +#ifndef __CUDACC__ + template + EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const + { + // FIXME: NVCC used to complain about the template keyword, but we have to check whether this is still the case. + // See also similar calls below. + return this->template packet_impl(row,col, row, + typename internal::conditional::type()); + } + + template + EIGEN_STRONG_INLINE PacketType packet(Index idx) const + { + return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); + } +#endif +}; + +// dense * diagonal +template +struct product_evaluator, ProductTag, DenseShape, DiagonalShape> + : diagonal_product_evaluator_base, OnTheRight> +{ + typedef diagonal_product_evaluator_base, OnTheRight> Base; + using Base::m_diagImpl; + using Base::m_matImpl; + using Base::coeff; + typedef typename Base::Scalar Scalar; + + typedef Product XprType; + typedef typename XprType::PlainObject PlainObject; + + enum { StorageOrder = int(Lhs::Flags) & RowMajorBit ? RowMajor : ColMajor }; + + EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr) + : Base(xpr.lhs(), xpr.rhs().diagonal()) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar coeff(Index row, Index col) const + { + return m_matImpl.coeff(row, col) * m_diagImpl.coeff(col); + } + +#ifndef __CUDACC__ + template + EIGEN_STRONG_INLINE PacketType packet(Index row, Index col) const + { + return this->template packet_impl(row,col, col, + typename internal::conditional::type()); + } + + template + EIGEN_STRONG_INLINE PacketType packet(Index idx) const + { + return packet(int(StorageOrder)==ColMajor?idx:0,int(StorageOrder)==ColMajor?0:idx); + } +#endif +}; + +/*************************************************************************** +* Products with permutation matrices +***************************************************************************/ + +/** \internal + * \class permutation_matrix_product + * Internal helper class implementing the product between a permutation matrix and a matrix. + * This class is specialized for DenseShape below and for SparseShape in SparseCore/SparsePermutation.h + */ +template +struct permutation_matrix_product; + +template +struct permutation_matrix_product +{ + typedef typename nested_eval::type MatrixType; + typedef typename remove_all::type MatrixTypeCleaned; + + template + static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr) + { + MatrixType mat(xpr); + const Index n = Side==OnTheLeft ? mat.rows() : mat.cols(); + // FIXME we need an is_same for expression that is not sensitive to constness. For instance + // is_same_xpr, Block >::value should be true. + //if(is_same::value && extract_data(dst) == extract_data(mat)) + if(is_same_dense(dst, mat)) + { + // apply the permutation inplace + Matrix mask(perm.size()); + mask.fill(false); + Index r = 0; + while(r < perm.size()) + { + // search for the next seed + while(r=perm.size()) + break; + // we got one, let's follow it until we are back to the seed + Index k0 = r++; + Index kPrev = k0; + mask.coeffRef(k0) = true; + for(Index k=perm.indices().coeff(k0); k!=k0; k=perm.indices().coeff(k)) + { + Block(dst, k) + .swap(Block + (dst,((Side==OnTheLeft) ^ Transposed) ? k0 : kPrev)); + + mask.coeffRef(k) = true; + kPrev = k; + } + } + } + else + { + for(Index i = 0; i < n; ++i) + { + Block + (dst, ((Side==OnTheLeft) ^ Transposed) ? perm.indices().coeff(i) : i) + + = + + Block + (mat, ((Side==OnTheRight) ^ Transposed) ? perm.indices().coeff(i) : i); + } + } + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, lhs, rhs); + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, rhs, lhs); + } +}; + +template +struct generic_product_impl, Rhs, PermutationShape, MatrixShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Inverse& lhs, const Rhs& rhs) + { + permutation_matrix_product::run(dst, lhs.nestedExpression(), rhs); + } +}; + +template +struct generic_product_impl, MatrixShape, PermutationShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Inverse& rhs) + { + permutation_matrix_product::run(dst, rhs.nestedExpression(), lhs); + } +}; + + +/*************************************************************************** +* Products with transpositions matrices +***************************************************************************/ + +// FIXME could we unify Transpositions and Permutation into a single "shape"?? + +/** \internal + * \class transposition_matrix_product + * Internal helper class implementing the product between a permutation matrix and a matrix. + */ +template +struct transposition_matrix_product +{ + typedef typename nested_eval::type MatrixType; + typedef typename remove_all::type MatrixTypeCleaned; + + template + static inline void run(Dest& dst, const TranspositionType& tr, const ExpressionType& xpr) + { + MatrixType mat(xpr); + typedef typename TranspositionType::StorageIndex StorageIndex; + const Index size = tr.size(); + StorageIndex j = 0; + + if(!is_same_dense(dst,mat)) + dst = mat; + + for(Index k=(Transposed?size-1:0) ; Transposed?k>=0:k +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, lhs, rhs); + } +}; + +template +struct generic_product_impl +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, rhs, lhs); + } +}; + + +template +struct generic_product_impl, Rhs, TranspositionsShape, MatrixShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Transpose& lhs, const Rhs& rhs) + { + transposition_matrix_product::run(dst, lhs.nestedExpression(), rhs); + } +}; + +template +struct generic_product_impl, MatrixShape, TranspositionsShape, ProductTag> +{ + template + static void evalTo(Dest& dst, const Lhs& lhs, const Transpose& rhs) + { + transposition_matrix_product::run(dst, rhs.nestedExpression(), lhs); + } +}; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_PRODUCT_EVALUATORS_H diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Random.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Random.h index 480fea408..6faf789c7 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Random.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Random.h @@ -16,8 +16,7 @@ namespace internal { template struct scalar_random_op { EIGEN_EMPTY_STRUCT_CTOR(scalar_random_op) - template - inline const Scalar operator() (Index, Index = 0) const { return random(); } + inline const Scalar operator() () const { return random(); } }; template @@ -28,12 +27,18 @@ struct functor_traits > /** \returns a random matrix expression * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * The parameters \a rows and \a cols are the number of rows and of columns of * the returned matrix. Must be compatible with this MatrixBase type. * + * \not_reentrant + * * This variant is meant to be used for dynamic-size matrix types. For fixed-size types, * it is redundant to pass \a rows and \a cols as arguments, so Random() should be used * instead. + * * * Example: \include MatrixBase_random_int_int.cpp * Output: \verbinclude MatrixBase_random_int_int.out @@ -41,22 +46,28 @@ struct functor_traits > * This expression has the "evaluate before nesting" flag so that it will be evaluated into * a temporary matrix whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. + * + * See DenseBase::NullaryExpr(Index, const CustomNullaryOp&) for an example using C++11 random generators. * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index), MatrixBase::Random() + * \sa DenseBase::setRandom(), DenseBase::Random(Index), DenseBase::Random() */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random(Index rows, Index cols) { return NullaryExpr(rows, cols, internal::scalar_random_op()); } /** \returns a random vector expression + * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. * * The parameter \a size is the size of the returned vector. * Must be compatible with this MatrixBase type. * * \only_for_vectors + * \not_reentrant * * This variant is meant to be used for dynamic-size vector types. For fixed-size types, * it is redundant to pass \a size as argument, so Random() should be used @@ -69,10 +80,10 @@ DenseBase::Random(Index rows, Index cols) * a temporary vector whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index,Index), MatrixBase::Random() + * \sa DenseBase::setRandom(), DenseBase::Random(Index,Index), DenseBase::Random() */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random(Index size) { return NullaryExpr(size, internal::scalar_random_op()); @@ -80,6 +91,9 @@ DenseBase::Random(Index size) /** \returns a fixed-size random matrix or vector expression * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * This variant is only for fixed-size MatrixBase types. For dynamic-size types, you * need to use the variants taking size arguments. * @@ -89,11 +103,13 @@ DenseBase::Random(Index size) * This expression has the "evaluate before nesting" flag so that it will be evaluated into * a temporary matrix whenever it is nested in a larger expression. This prevents unexpected * behavior with expressions involving random matrices. + * + * \not_reentrant * - * \sa MatrixBase::setRandom(), MatrixBase::Random(Index,Index), MatrixBase::Random(Index) + * \sa DenseBase::setRandom(), DenseBase::Random(Index,Index), DenseBase::Random(Index) */ template -inline const CwiseNullaryOp::Scalar>, Derived> +inline const typename DenseBase::RandomReturnType DenseBase::Random() { return NullaryExpr(RowsAtCompileTime, ColsAtCompileTime, internal::scalar_random_op()); @@ -101,6 +117,11 @@ DenseBase::Random() /** Sets all coefficients in this expression to random values. * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * * Example: \include MatrixBase_setRandom.cpp * Output: \verbinclude MatrixBase_setRandom.out * @@ -114,12 +135,16 @@ inline Derived& DenseBase::setRandom() /** Resizes to the given \a newSize, and sets all coefficients in this expression to random values. * + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * * \only_for_vectors + * \not_reentrant * * Example: \include Matrix_setRandom_int.cpp * Output: \verbinclude Matrix_setRandom_int.out * - * \sa MatrixBase::setRandom(), setRandom(Index,Index), class CwiseNullaryOp, MatrixBase::Random() + * \sa DenseBase::setRandom(), setRandom(Index,Index), class CwiseNullaryOp, DenseBase::Random() */ template EIGEN_STRONG_INLINE Derived& @@ -131,19 +156,24 @@ PlainObjectBase::setRandom(Index newSize) /** Resizes to the given size, and sets all coefficients in this expression to random values. * - * \param nbRows the new number of rows - * \param nbCols the new number of columns + * Numbers are uniformly spread through their whole definition range for integer types, + * and in the [-1:1] range for floating point scalar types. + * + * \not_reentrant + * + * \param rows the new number of rows + * \param cols the new number of columns * * Example: \include Matrix_setRandom_int_int.cpp * Output: \verbinclude Matrix_setRandom_int_int.out * - * \sa MatrixBase::setRandom(), setRandom(Index), class CwiseNullaryOp, MatrixBase::Random() + * \sa DenseBase::setRandom(), setRandom(Index), class CwiseNullaryOp, DenseBase::Random() */ template EIGEN_STRONG_INLINE Derived& -PlainObjectBase::setRandom(Index nbRows, Index nbCols) +PlainObjectBase::setRandom(Index rows, Index cols) { - resize(nbRows, nbCols); + resize(rows, cols); return setRandom(); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h index 9b8662a6f..b6e8f8887 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Redux.h @@ -27,8 +27,9 @@ template struct redux_traits { public: + typedef typename find_best_packet::type PacketType; enum { - PacketSize = packet_traits::size, + PacketSize = unpacket_traits::size, InnerMaxSize = int(Derived::IsRowMajor) ? Derived::MaxColsAtCompileTime : Derived::MaxRowsAtCompileTime @@ -37,8 +38,8 @@ public: enum { MightVectorize = (int(Derived::Flags)&ActualPacketAccessBit) && (functor_traits::PacketAccess), - MayLinearVectorize = MightVectorize && (int(Derived::Flags)&LinearAccessBit), - MaySliceVectorize = MightVectorize && int(InnerMaxSize)>=3*PacketSize + MayLinearVectorize = bool(MightVectorize) && (int(Derived::Flags)&LinearAccessBit), + MaySliceVectorize = bool(MightVectorize) && int(InnerMaxSize)>=3*PacketSize }; public: @@ -50,21 +51,34 @@ public: public: enum { - Cost = ( Derived::SizeAtCompileTime == Dynamic - || Derived::CoeffReadCost == Dynamic - || (Derived::SizeAtCompileTime!=1 && functor_traits::Cost == Dynamic) - ) ? Dynamic - : Derived::SizeAtCompileTime * Derived::CoeffReadCost - + (Derived::SizeAtCompileTime-1) * functor_traits::Cost, + Cost = Derived::SizeAtCompileTime == Dynamic ? HugeCost + : Derived::SizeAtCompileTime * Derived::CoeffReadCost + (Derived::SizeAtCompileTime-1) * functor_traits::Cost, UnrollingLimit = EIGEN_UNROLLING_LIMIT * (int(Traversal) == int(DefaultTraversal) ? 1 : int(PacketSize)) }; public: enum { - Unrolling = Cost != Dynamic && Cost <= UnrollingLimit - ? CompleteUnrolling - : NoUnrolling + Unrolling = Cost <= UnrollingLimit ? CompleteUnrolling : NoUnrolling }; + +#ifdef EIGEN_DEBUG_ASSIGN + static void debug() + { + std::cerr << "Xpr: " << typeid(typename Derived::XprType).name() << std::endl; + std::cerr.setf(std::ios::hex, std::ios::basefield); + EIGEN_DEBUG_VAR(Derived::Flags) + std::cerr.unsetf(std::ios::hex); + EIGEN_DEBUG_VAR(InnerMaxSize) + EIGEN_DEBUG_VAR(PacketSize) + EIGEN_DEBUG_VAR(MightVectorize) + EIGEN_DEBUG_VAR(MayLinearVectorize) + EIGEN_DEBUG_VAR(MaySliceVectorize) + EIGEN_DEBUG_VAR(Traversal) + EIGEN_DEBUG_VAR(UnrollingLimit) + EIGEN_DEBUG_VAR(Unrolling) + std::cerr << std::endl; + } +#endif }; /*************************************************************************** @@ -82,6 +96,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { return func(redux_novec_unroller::run(mat,func), @@ -99,6 +114,7 @@ struct redux_novec_unroller typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func&) { return mat.coeffByOuterInner(outer, inner); @@ -112,6 +128,7 @@ template struct redux_novec_unroller { typedef typename Derived::Scalar Scalar; + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived&, const Func&) { return Scalar(); } }; @@ -121,12 +138,12 @@ template struct redux_vec_unroller { enum { - PacketSize = packet_traits::size, + PacketSize = redux_traits::PacketSize, HalfLength = Length/2 }; typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + typedef typename redux_traits::PacketType PacketScalar; static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func& func) { @@ -140,18 +157,18 @@ template struct redux_vec_unroller { enum { - index = Start * packet_traits::size, + index = Start * redux_traits::PacketSize, outer = index / int(Derived::InnerSizeAtCompileTime), inner = index % int(Derived::InnerSizeAtCompileTime), - alignment = (Derived::Flags & AlignedBit) ? Aligned : Unaligned + alignment = Derived::Alignment }; typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + typedef typename redux_traits::PacketType PacketScalar; static EIGEN_STRONG_INLINE PacketScalar run(const Derived &mat, const Func&) { - return mat.template packetByOuterInner(outer, inner); + return mat.template packetByOuterInner(outer, inner); } }; @@ -169,8 +186,8 @@ template struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename Derived::Index Index; - static EIGEN_STRONG_INLINE Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); Scalar res; @@ -193,19 +210,19 @@ template struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; - typedef typename Derived::Index Index; + typedef typename redux_traits::PacketType PacketScalar; - static Scalar run(const Derived& mat, const Func& func) + static Scalar run(const Derived &mat, const Func& func) { const Index size = mat.size(); - eigen_assert(size && "you are using an empty matrix"); - const Index packetSize = packet_traits::size; - const Index alignedStart = internal::first_aligned(mat); + + const Index packetSize = redux_traits::PacketSize; + const int packetAlignment = unpacket_traits::alignment; enum { - alignment = bool(Derived::Flags & DirectAccessBit) || bool(Derived::Flags & AlignedBit) - ? Aligned : Unaligned + alignment0 = (bool(Derived::Flags & DirectAccessBit) && bool(packet_traits::AlignedOnScalar)) ? int(packetAlignment) : int(Unaligned), + alignment = EIGEN_PLAIN_ENUM_MAX(alignment0, Derived::Alignment) }; + const Index alignedStart = internal::first_default_aligned(mat.nestedExpression()); const Index alignedSize2 = ((size-alignedStart)/(2*packetSize))*(2*packetSize); const Index alignedSize = ((size-alignedStart)/(packetSize))*(packetSize); const Index alignedEnd2 = alignedStart + alignedSize2; @@ -213,19 +230,19 @@ struct redux_impl Scalar res; if(alignedSize) { - PacketScalar packet_res0 = mat.template packet(alignedStart); + PacketScalar packet_res0 = mat.template packet(alignedStart); if(alignedSize>packetSize) // we have at least two packets to partly unroll the loop { - PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); + PacketScalar packet_res1 = mat.template packet(alignedStart+packetSize); for(Index index = alignedStart + 2*packetSize; index < alignedEnd2; index += 2*packetSize) { - packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); - packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); + packet_res0 = func.packetOp(packet_res0, mat.template packet(index)); + packet_res1 = func.packetOp(packet_res1, mat.template packet(index+packetSize)); } packet_res0 = func.packetOp(packet_res0,packet_res1); if(alignedEnd>alignedEnd2) - packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); + packet_res0 = func.packetOp(packet_res0, mat.template packet(alignedEnd2)); } res = func.predux(packet_res0); @@ -252,25 +269,24 @@ template struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; - typedef typename Derived::Index Index; + typedef typename redux_traits::PacketType PacketType; - static Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC static Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); const Index innerSize = mat.innerSize(); const Index outerSize = mat.outerSize(); enum { - packetSize = packet_traits::size + packetSize = redux_traits::PacketSize }; const Index packetedInnerSize = ((innerSize)/packetSize)*packetSize; Scalar res; if(packetedInnerSize) { - PacketScalar packet_res = mat.template packet(0,0); + PacketType packet_res = mat.template packet(0,0); for(Index j=0; j(j,i)); + packet_res = func.packetOp(packet_res, mat.template packetByOuterInner(j,i)); res = func.predux(packet_res); for(Index j=0; j struct redux_impl { typedef typename Derived::Scalar Scalar; - typedef typename packet_traits::type PacketScalar; + + typedef typename redux_traits::PacketType PacketScalar; enum { - PacketSize = packet_traits::size, + PacketSize = redux_traits::PacketSize, Size = Derived::SizeAtCompileTime, VectorizedSize = (Size / PacketSize) * PacketSize }; - static EIGEN_STRONG_INLINE Scalar run(const Derived& mat, const Func& func) + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Scalar run(const Derived &mat, const Func& func) { eigen_assert(mat.rows()>0 && mat.cols()>0 && "you are using an empty matrix"); - Scalar res = func.predux(redux_vec_unroller::run(mat,func)); - if (VectorizedSize != Size) - res = func(res,redux_novec_unroller::run(mat,func)); - return res; + if (VectorizedSize > 0) { + Scalar res = func.predux(redux_vec_unroller::run(mat,func)); + if (VectorizedSize != Size) + res = func(res,redux_novec_unroller::run(mat,func)); + return res; + } + else { + return redux_novec_unroller::run(mat,func); + } } }; +// evaluator adaptor +template +class redux_evaluator +{ +public: + typedef _XprType XprType; + EIGEN_DEVICE_FUNC explicit redux_evaluator(const XprType &xpr) : m_evaluator(xpr), m_xpr(xpr) {} + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename XprType::PacketScalar PacketScalar; + typedef typename XprType::PacketReturnType PacketReturnType; + + enum { + MaxRowsAtCompileTime = XprType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = XprType::MaxColsAtCompileTime, + // TODO we should not remove DirectAccessBit and rather find an elegant way to query the alignment offset at runtime from the evaluator + Flags = evaluator::Flags & ~DirectAccessBit, + IsRowMajor = XprType::IsRowMajor, + SizeAtCompileTime = XprType::SizeAtCompileTime, + InnerSizeAtCompileTime = XprType::InnerSizeAtCompileTime, + CoeffReadCost = evaluator::CoeffReadCost, + Alignment = evaluator::Alignment + }; + + EIGEN_DEVICE_FUNC Index rows() const { return m_xpr.rows(); } + EIGEN_DEVICE_FUNC Index cols() const { return m_xpr.cols(); } + EIGEN_DEVICE_FUNC Index size() const { return m_xpr.size(); } + EIGEN_DEVICE_FUNC Index innerSize() const { return m_xpr.innerSize(); } + EIGEN_DEVICE_FUNC Index outerSize() const { return m_xpr.outerSize(); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeff(Index row, Index col) const + { return m_evaluator.coeff(row, col); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeff(Index index) const + { return m_evaluator.coeff(index); } + + template + PacketType packet(Index row, Index col) const + { return m_evaluator.template packet(row, col); } + + template + PacketType packet(Index index) const + { return m_evaluator.template packet(index); } + + EIGEN_DEVICE_FUNC + CoeffReturnType coeffByOuterInner(Index outer, Index inner) const + { return m_evaluator.coeff(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } + + template + PacketType packetByOuterInner(Index outer, Index inner) const + { return m_evaluator.template packet(IsRowMajor ? outer : inner, IsRowMajor ? inner : outer); } + + const XprType & nestedExpression() const { return m_xpr; } + +protected: + internal::evaluator m_evaluator; + const XprType &m_xpr; +}; + } // end namespace internal /*************************************************************************** @@ -317,18 +401,21 @@ struct redux_impl /** \returns the result of a full redux operation on the whole matrix or vector using \a func * * The template parameter \a BinaryOp is the type of the functor \a func which must be - * an associative operator. Both current STL and TR1 functor styles are handled. + * an associative operator. Both current C++98 and C++11 functor styles are handled. * * \sa DenseBase::sum(), DenseBase::minCoeff(), DenseBase::maxCoeff(), MatrixBase::colwise(), MatrixBase::rowwise() */ template template -EIGEN_STRONG_INLINE typename internal::result_of::Scalar)>::type +typename internal::traits::Scalar DenseBase::redux(const Func& func) const { - typedef typename internal::remove_all::type ThisNested; - return internal::redux_impl - ::run(derived(), func); + eigen_assert(this->rows()>0 && this->cols()>0 && "you are using an empty matrix"); + + typedef typename internal::redux_evaluator ThisEvaluator; + ThisEvaluator thisEval(derived()); + + return internal::redux_impl::run(thisEval, func); } /** \returns the minimum of all coefficients of \c *this. @@ -338,7 +425,7 @@ template EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::minCoeff() const { - return this->redux(Eigen::internal::scalar_min_op()); + return derived().redux(Eigen::internal::scalar_min_op()); } /** \returns the maximum of all coefficients of \c *this. @@ -348,10 +435,12 @@ template EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::maxCoeff() const { - return this->redux(Eigen::internal::scalar_max_op()); + return derived().redux(Eigen::internal::scalar_max_op()); } -/** \returns the sum of all coefficients of *this +/** \returns the sum of all coefficients of \c *this + * + * If \c *this is empty, then the value 0 is returned. * * \sa trace(), prod(), mean() */ @@ -361,7 +450,7 @@ DenseBase::sum() const { if(SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) return Scalar(0); - return this->redux(Eigen::internal::scalar_sum_op()); + return derived().redux(Eigen::internal::scalar_sum_op()); } /** \returns the mean of all coefficients of *this @@ -372,7 +461,14 @@ template EIGEN_STRONG_INLINE typename internal::traits::Scalar DenseBase::mean() const { - return Scalar(this->redux(Eigen::internal::scalar_sum_op())) / Scalar(this->size()); +#ifdef __INTEL_COMPILER + #pragma warning push + #pragma warning ( disable : 2259 ) +#endif + return Scalar(derived().redux(Eigen::internal::scalar_sum_op())) / Scalar(this->size()); +#ifdef __INTEL_COMPILER + #pragma warning pop +#endif } /** \returns the product of all coefficients of *this @@ -388,7 +484,7 @@ DenseBase::prod() const { if(SizeAtCompileTime==0 || (SizeAtCompileTime==Dynamic && size()==0)) return Scalar(1); - return this->redux(Eigen::internal::scalar_product_op()); + return derived().redux(Eigen::internal::scalar_product_op()); } /** \returns the trace of \c *this, i.e. the sum of the coefficients on the main diagonal. diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h index 7a3becaf8..bdf24f52a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Ref.h @@ -12,79 +12,6 @@ namespace Eigen { -template class RefBase; -template,OuterStride<> >::type > class Ref; - -/** \class Ref - * \ingroup Core_Module - * - * \brief A matrix or vector expression mapping an existing expressions - * - * \tparam PlainObjectType the equivalent matrix type of the mapped data - * \tparam Options specifies whether the pointer is \c #Aligned, or \c #Unaligned. - * The default is \c #Unaligned. - * \tparam StrideType optionally specifies strides. By default, Ref implies a contiguous storage along the inner dimension (inner stride==1), - * but accept a variable outer stride (leading dimension). - * This can be overridden by specifying strides. - * The type passed here must be a specialization of the Stride template, see examples below. - * - * This class permits to write non template functions taking Eigen's object as parameters while limiting the number of copies. - * A Ref<> object can represent either a const expression or a l-value: - * \code - * // in-out argument: - * void foo1(Ref x); - * - * // read-only const argument: - * void foo2(const Ref& x); - * \endcode - * - * In the in-out case, the input argument must satisfies the constraints of the actual Ref<> type, otherwise a compilation issue will be triggered. - * By default, a Ref can reference any dense vector expression of float having a contiguous memory layout. - * Likewise, a Ref can reference any column major dense matrix expression of float whose column's elements are contiguously stored with - * the possibility to have a constant space inbetween each column, i.e.: the inner stride mmust be equal to 1, but the outer-stride (or leading dimension), - * can be greater than the number of rows. - * - * In the const case, if the input expression does not match the above requirement, then it is evaluated into a temporary before being passed to the function. - * Here are some examples: - * \code - * MatrixXf A; - * VectorXf a; - * foo1(a.head()); // OK - * foo1(A.col()); // OK - * foo1(A.row()); // compilation error because here innerstride!=1 - * foo2(A.row()); // The row is copied into a contiguous temporary - * foo2(2*a); // The expression is evaluated into a temporary - * foo2(A.col().segment(2,4)); // No temporary - * \endcode - * - * The range of inputs that can be referenced without temporary can be enlarged using the last two template parameter. - * Here is an example accepting an innerstride!=1: - * \code - * // in-out argument: - * void foo3(Ref > x); - * foo3(A.row()); // OK - * \endcode - * The downside here is that the function foo3 might be significantly slower than foo1 because it won't be able to exploit vectorization, and will involved more - * expensive address computations even if the input is contiguously stored in memory. To overcome this issue, one might propose to overloads internally calling a - * template function, e.g.: - * \code - * // in the .h: - * void foo(const Ref& A); - * void foo(const Ref >& A); - * - * // in the .cpp: - * template void foo_impl(const TypeOfA& A) { - * ... // crazy code goes here - * } - * void foo(const Ref& A) { foo_impl(A); } - * void foo(const Ref >& A) { foo_impl(A); } - * \endcode - * - * - * \sa PlainObjectBase::Map(), \ref TopicStorageOrders - */ - namespace internal { template @@ -95,7 +22,8 @@ struct traits > typedef _StrideType StrideType; enum { Options = _Options, - Flags = traits >::Flags | NestByRefBit + Flags = traits >::Flags | NestByRefBit, + Alignment = traits >::Alignment }; template struct match { @@ -107,7 +35,13 @@ struct traits > || (int(StrideType::InnerStrideAtCompileTime)==0 && int(Derived::InnerStrideAtCompileTime)==1), OuterStrideMatch = Derived::IsVectorAtCompileTime || int(StrideType::OuterStrideAtCompileTime)==int(Dynamic) || int(StrideType::OuterStrideAtCompileTime)==int(Derived::OuterStrideAtCompileTime), - AlignmentMatch = (_Options!=Aligned) || ((PlainObjectType::Flags&AlignedBit)==0) || ((traits::Flags&AlignedBit)==AlignedBit), + // NOTE, this indirection of evaluator::Alignment is needed + // to workaround a very strange bug in MSVC related to the instantiation + // of has_*ary_operator in evaluator. + // This line is surprisingly very sensitive. For instance, simply adding parenthesis + // as "DerivedAlignment = (int(evaluator::Alignment))," will make MSVC fail... + DerivedAlignment = int(evaluator::Alignment), + AlignmentMatch = (int(traits::Alignment)==int(Unaligned)) || (DerivedAlignment >= int(Alignment)), // FIXME the first condition is not very clear, it should be replaced by the required alignment ScalarTypeMatch = internal::is_same::value, MatchAtCompileTime = HasDirectAccess && StorageOrderMatch && InnerStrideMatch && OuterStrideMatch && AlignmentMatch && ScalarTypeMatch }; @@ -132,12 +66,12 @@ public: typedef MapBase Base; EIGEN_DENSE_PUBLIC_INTERFACE(RefBase) - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return StrideType::InnerStrideAtCompileTime != 0 ? m_stride.inner() : 1; } - inline Index outerStride() const + EIGEN_DEVICE_FUNC inline Index outerStride() const { return StrideType::OuterStrideAtCompileTime != 0 ? m_stride.outer() : IsVectorAtCompileTime ? this->size() @@ -145,7 +79,7 @@ public: : this->rows(); } - RefBase() + EIGEN_DEVICE_FUNC RefBase() : Base(0,RowsAtCompileTime==Dynamic?0:RowsAtCompileTime,ColsAtCompileTime==Dynamic?0:ColsAtCompileTime), // Stride<> does not allow default ctor for Dynamic strides, so let' initialize it with dummy values: m_stride(StrideType::OuterStrideAtCompileTime==Dynamic?0:StrideType::OuterStrideAtCompileTime, @@ -159,7 +93,7 @@ protected: typedef Stride StrideBase; template - void construct(Expression& expr) + EIGEN_DEVICE_FUNC void construct(Expression& expr) { if(PlainObjectType::RowsAtCompileTime==1) { @@ -184,15 +118,83 @@ protected: StrideBase m_stride; }; - +/** \class Ref + * \ingroup Core_Module + * + * \brief A matrix or vector expression mapping an existing expression + * + * \tparam PlainObjectType the equivalent matrix type of the mapped data + * \tparam Options specifies the pointer alignment in bytes. It can be: \c #Aligned128, , \c #Aligned64, \c #Aligned32, \c #Aligned16, \c #Aligned8 or \c #Unaligned. + * The default is \c #Unaligned. + * \tparam StrideType optionally specifies strides. By default, Ref implies a contiguous storage along the inner dimension (inner stride==1), + * but accepts a variable outer stride (leading dimension). + * This can be overridden by specifying strides. + * The type passed here must be a specialization of the Stride template, see examples below. + * + * This class provides a way to write non-template functions taking Eigen objects as parameters while limiting the number of copies. + * A Ref<> object can represent either a const expression or a l-value: + * \code + * // in-out argument: + * void foo1(Ref x); + * + * // read-only const argument: + * void foo2(const Ref& x); + * \endcode + * + * In the in-out case, the input argument must satisfy the constraints of the actual Ref<> type, otherwise a compilation issue will be triggered. + * By default, a Ref can reference any dense vector expression of float having a contiguous memory layout. + * Likewise, a Ref can reference any column-major dense matrix expression of float whose column's elements are contiguously stored with + * the possibility to have a constant space in-between each column, i.e. the inner stride must be equal to 1, but the outer stride (or leading dimension) + * can be greater than the number of rows. + * + * In the const case, if the input expression does not match the above requirement, then it is evaluated into a temporary before being passed to the function. + * Here are some examples: + * \code + * MatrixXf A; + * VectorXf a; + * foo1(a.head()); // OK + * foo1(A.col()); // OK + * foo1(A.row()); // Compilation error because here innerstride!=1 + * foo2(A.row()); // Compilation error because A.row() is a 1xN object while foo2 is expecting a Nx1 object + * foo2(A.row().transpose()); // The row is copied into a contiguous temporary + * foo2(2*a); // The expression is evaluated into a temporary + * foo2(A.col().segment(2,4)); // No temporary + * \endcode + * + * The range of inputs that can be referenced without temporary can be enlarged using the last two template parameters. + * Here is an example accepting an innerstride!=1: + * \code + * // in-out argument: + * void foo3(Ref > x); + * foo3(A.row()); // OK + * \endcode + * The downside here is that the function foo3 might be significantly slower than foo1 because it won't be able to exploit vectorization, and will involve more + * expensive address computations even if the input is contiguously stored in memory. To overcome this issue, one might propose to overload internally calling a + * template function, e.g.: + * \code + * // in the .h: + * void foo(const Ref& A); + * void foo(const Ref >& A); + * + * // in the .cpp: + * template void foo_impl(const TypeOfA& A) { + * ... // crazy code goes here + * } + * void foo(const Ref& A) { foo_impl(A); } + * void foo(const Ref >& A) { foo_impl(A); } + * \endcode + * + * + * \sa PlainObjectBase::Map(), \ref TopicStorageOrders + */ template class Ref : public RefBase > { private: typedef internal::traits Traits; template - inline Ref(const PlainObjectBase& expr, - typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0); + EIGEN_DEVICE_FUNC inline Ref(const PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0); public: typedef RefBase Base; @@ -201,23 +203,24 @@ template class Ref #ifndef EIGEN_PARSED_BY_DOXYGEN template - inline Ref(PlainObjectBase& expr, - typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) + EIGEN_DEVICE_FUNC inline Ref(PlainObjectBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) { - EIGEN_STATIC_ASSERT(static_cast(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); + EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); Base::construct(expr.derived()); } template - inline Ref(const DenseBase& expr, - typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) + EIGEN_DEVICE_FUNC inline Ref(const DenseBase& expr, + typename internal::enable_if::MatchAtCompileTime),Derived>::type* = 0) #else + /** Implicit constructor from any dense expression */ template inline Ref(DenseBase& expr) #endif { - EIGEN_STATIC_ASSERT(static_cast(internal::is_lvalue::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); - EIGEN_STATIC_ASSERT(static_cast(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); - enum { THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY = Derived::ThisConstantIsPrivateInPlainObjectBase}; + EIGEN_STATIC_ASSERT(bool(internal::is_lvalue::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); + EIGEN_STATIC_ASSERT(bool(Traits::template match::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH); + EIGEN_STATIC_ASSERT(!Derived::IsPlainObjectBase,THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY); Base::construct(expr.const_cast_derived()); } @@ -236,36 +239,36 @@ template class Ref< EIGEN_DENSE_PUBLIC_INTERFACE(Ref) template - inline Ref(const DenseBase& expr, - typename internal::enable_if::ScalarTypeMatch),Derived>::type* = 0) + EIGEN_DEVICE_FUNC inline Ref(const DenseBase& expr, + typename internal::enable_if::ScalarTypeMatch),Derived>::type* = 0) { // std::cout << match_helper::HasDirectAccess << "," << match_helper::OuterStrideMatch << "," << match_helper::InnerStrideMatch << "\n"; // std::cout << int(StrideType::OuterStrideAtCompileTime) << " - " << int(Derived::OuterStrideAtCompileTime) << "\n"; // std::cout << int(StrideType::InnerStrideAtCompileTime) << " - " << int(Derived::InnerStrideAtCompileTime) << "\n"; construct(expr.derived(), typename Traits::template match::type()); } - - inline Ref(const Ref& other) : Base(other) { + + EIGEN_DEVICE_FUNC inline Ref(const Ref& other) : Base(other) { // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy } template - inline Ref(const RefBase& other) { + EIGEN_DEVICE_FUNC inline Ref(const RefBase& other) { construct(other.derived(), typename Traits::template match::type()); } protected: template - void construct(const Expression& expr,internal::true_type) + EIGEN_DEVICE_FUNC void construct(const Expression& expr,internal::true_type) { Base::construct(expr); } template - void construct(const Expression& expr, internal::false_type) + EIGEN_DEVICE_FUNC void construct(const Expression& expr, internal::false_type) { - m_object.lazyAssign(expr); + internal::call_assignment_no_alias(m_object,expr,internal::assign_op()); Base::construct(m_object); } diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h index ac4537c14..9960ef884 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Replicate.h @@ -12,21 +12,6 @@ namespace Eigen { -/** - * \class Replicate - * \ingroup Core_Module - * - * \brief Expression of the multiple replication of a matrix or vector - * - * \param MatrixType the type of the object we are replicating - * - * This class represents an expression of the multiple replication of a matrix or vector. - * It is the return type of DenseBase::replicate() and most of the time - * this is the only way it is used. - * - * \sa DenseBase::replicate() - */ - namespace internal { template struct traits > @@ -35,10 +20,7 @@ struct traits > typedef typename MatrixType::Scalar Scalar; typedef typename traits::StorageKind StorageKind; typedef typename traits::XprKind XprKind; - enum { - Factor = (RowFactor==Dynamic || ColFactor==Dynamic) ? Dynamic : RowFactor*ColFactor - }; - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; enum { RowsAtCompileTime = RowFactor==Dynamic || int(MatrixType::RowsAtCompileTime)==Dynamic @@ -53,12 +35,29 @@ struct traits > IsRowMajor = MaxRowsAtCompileTime==1 && MaxColsAtCompileTime!=1 ? 1 : MaxColsAtCompileTime==1 && MaxRowsAtCompileTime!=1 ? 0 : (MatrixType::Flags & RowMajorBit) ? 1 : 0, - Flags = (_MatrixTypeNested::Flags & HereditaryBits & ~RowMajorBit) | (IsRowMajor ? RowMajorBit : 0), - CoeffReadCost = _MatrixTypeNested::CoeffReadCost + + // FIXME enable DirectAccess with negative strides? + Flags = IsRowMajor ? RowMajorBit : 0 }; }; } +/** + * \class Replicate + * \ingroup Core_Module + * + * \brief Expression of the multiple replication of a matrix or vector + * + * \tparam MatrixType the type of the object we are replicating + * \tparam RowFactor number of repetitions at compile time along the vertical direction, can be Dynamic. + * \tparam ColFactor number of repetitions at compile time along the horizontal direction, can be Dynamic. + * + * This class represents an expression of the multiple replication of a matrix or vector. + * It is the return type of DenseBase::replicate() and most of the time + * this is the only way it is used. + * + * \sa DenseBase::replicate() + */ template class Replicate : public internal::dense_xpr_base< Replicate >::type { @@ -68,10 +67,12 @@ template class Replicate typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Replicate) + typedef typename internal::remove_all::type NestedExpression; template - inline explicit Replicate(const OriginalMatrixType& a_matrix) - : m_matrix(a_matrix), m_rowFactor(RowFactor), m_colFactor(ColFactor) + EIGEN_DEVICE_FUNC + inline explicit Replicate(const OriginalMatrixType& matrix) + : m_matrix(matrix), m_rowFactor(RowFactor), m_colFactor(ColFactor) { EIGEN_STATIC_ASSERT((internal::is_same::type,OriginalMatrixType>::value), THE_MATRIX_OR_EXPRESSION_THAT_YOU_PASSED_DOES_NOT_HAVE_THE_EXPECTED_TYPE) @@ -79,41 +80,20 @@ template class Replicate } template - inline Replicate(const OriginalMatrixType& a_matrix, Index rowFactor, Index colFactor) - : m_matrix(a_matrix), m_rowFactor(rowFactor), m_colFactor(colFactor) + EIGEN_DEVICE_FUNC + inline Replicate(const OriginalMatrixType& matrix, Index rowFactor, Index colFactor) + : m_matrix(matrix), m_rowFactor(rowFactor), m_colFactor(colFactor) { EIGEN_STATIC_ASSERT((internal::is_same::type,OriginalMatrixType>::value), THE_MATRIX_OR_EXPRESSION_THAT_YOU_PASSED_DOES_NOT_HAVE_THE_EXPECTED_TYPE) } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows() * m_rowFactor.value(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols() * m_colFactor.value(); } - inline Scalar coeff(Index rowId, Index colId) const - { - // try to avoid using modulo; this is a pure optimization strategy - const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 - : RowFactor==1 ? rowId - : rowId%m_matrix.rows(); - const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 - : ColFactor==1 ? colId - : colId%m_matrix.cols(); - - return m_matrix.coeff(actual_row, actual_col); - } - template - inline PacketScalar packet(Index rowId, Index colId) const - { - const Index actual_row = internal::traits::RowsAtCompileTime==1 ? 0 - : RowFactor==1 ? rowId - : rowId%m_matrix.rows(); - const Index actual_col = internal::traits::ColsAtCompileTime==1 ? 0 - : ColFactor==1 ? colId - : colId%m_matrix.cols(); - - return m_matrix.template packet(actual_row, actual_col); - } - + EIGEN_DEVICE_FUNC const _MatrixTypeNested& nestedExpression() const { return m_matrix; @@ -141,21 +121,6 @@ DenseBase::replicate() const return Replicate(derived()); } -/** - * \return an expression of the replication of \c *this - * - * Example: \include MatrixBase_replicate_int_int.cpp - * Output: \verbinclude MatrixBase_replicate_int_int.out - * - * \sa VectorwiseOp::replicate(), DenseBase::replicate(), class Replicate - */ -template -const typename DenseBase::ReplicateReturnType -DenseBase::replicate(Index rowFactor,Index colFactor) const -{ - return Replicate(derived(),rowFactor,colFactor); -} - /** * \return an expression of the replication of each column (or row) of \c *this * diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h index f635598dc..c44b7673b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/ReturnByValue.h @@ -13,11 +13,6 @@ namespace Eigen { -/** \class ReturnByValue - * \ingroup Core_Module - * - */ - namespace internal { template @@ -38,17 +33,22 @@ struct traits > * So internal::nested always gives the plain return matrix type. * * FIXME: I don't understand why we need this specialization: isn't this taken care of by the EvalBeforeNestingBit ?? + * Answer: EvalBeforeNestingBit should be deprecated since we have the evaluators */ template -struct nested, n, PlainObject> +struct nested_eval, n, PlainObject> { typedef typename traits::ReturnType type; }; } // end namespace internal +/** \class ReturnByValue + * \ingroup Core_Module + * + */ template class ReturnByValue - : internal::no_assignment_operator, public internal::dense_xpr_base< ReturnByValue >::type + : public internal::dense_xpr_base< ReturnByValue >::type, internal::no_assignment_operator { public: typedef typename internal::traits::ReturnType ReturnType; @@ -57,10 +57,11 @@ template class ReturnByValue EIGEN_DENSE_PUBLIC_INTERFACE(ReturnByValue) template + EIGEN_DEVICE_FUNC inline void evalTo(Dest& dst) const { static_cast(this)->evalTo(dst); } - inline Index rows() const { return static_cast(this)->rows(); } - inline Index cols() const { return static_cast(this)->cols(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return static_cast(this)->rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return static_cast(this)->cols(); } #ifndef EIGEN_PARSED_BY_DOXYGEN #define Unusable YOU_ARE_TRYING_TO_ACCESS_A_SINGLE_COEFFICIENT_IN_A_SPECIAL_EXPRESSION_WHERE_THAT_IS_NOT_ALLOWED_BECAUSE_THAT_WOULD_BE_INEFFICIENT @@ -72,8 +73,7 @@ template class ReturnByValue const Unusable& coeff(Index,Index) const { return *reinterpret_cast(this); } Unusable& coeffRef(Index) { return *reinterpret_cast(this); } Unusable& coeffRef(Index,Index) { return *reinterpret_cast(this); } - template Unusable& packet(Index) const; - template Unusable& packet(Index, Index) const; +#undef Unusable #endif }; @@ -85,14 +85,32 @@ Derived& DenseBase::operator=(const ReturnByValue& other) return derived(); } -template -template -Derived& DenseBase::lazyAssign(const ReturnByValue& other) -{ - other.evalTo(derived()); - return derived(); -} +namespace internal { +// Expression is evaluated in a temporary; default implementation of Assignment is bypassed so that +// when a ReturnByValue expression is assigned, the evaluator is not constructed. +// TODO: Finalize port to new regime; ReturnByValue should not exist in the expression world + +template +struct evaluator > + : public evaluator::ReturnType> +{ + typedef ReturnByValue XprType; + typedef typename internal::traits::ReturnType PlainObject; + typedef evaluator Base; + + EIGEN_DEVICE_FUNC explicit evaluator(const XprType& xpr) + : m_result(xpr.rows(), xpr.cols()) + { + ::new (static_cast(this)) Base(m_result); + xpr.evalTo(m_result); + } + +protected: + PlainObject m_result; +}; + +} // end namespace internal } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h index 041f8222a..0640cda2a 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Reverse.h @@ -14,20 +14,6 @@ namespace Eigen { -/** \class Reverse - * \ingroup Core_Module - * - * \brief Expression of the reverse of a vector or matrix - * - * \param MatrixType the type of the object of which we are taking the reverse - * - * This class represents an expression of the reverse of a vector. - * It is the return type of MatrixBase::reverse() and VectorwiseOp::reverse() - * and most of the time this is the only way it is used. - * - * \sa MatrixBase::reverse(), VectorwiseOp::reverse() - */ - namespace internal { template @@ -37,36 +23,43 @@ struct traits > typedef typename MatrixType::Scalar Scalar; typedef typename traits::StorageKind StorageKind; typedef typename traits::XprKind XprKind; - typedef typename nested::type MatrixTypeNested; + typedef typename ref_selector::type MatrixTypeNested; typedef typename remove_reference::type _MatrixTypeNested; enum { RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, - - // let's enable LinearAccess only with vectorization because of the product overhead - LinearAccess = ( (Direction==BothDirections) && (int(_MatrixTypeNested::Flags)&PacketAccessBit) ) - ? LinearAccessBit : 0, - - Flags = int(_MatrixTypeNested::Flags) & (HereditaryBits | LvalueBit | PacketAccessBit | LinearAccess), - - CoeffReadCost = _MatrixTypeNested::CoeffReadCost + Flags = _MatrixTypeNested::Flags & (RowMajorBit | LvalueBit) }; }; -template struct reverse_packet_cond +template struct reverse_packet_cond { - static inline PacketScalar run(const PacketScalar& x) { return preverse(x); } + static inline PacketType run(const PacketType& x) { return preverse(x); } }; -template struct reverse_packet_cond +template struct reverse_packet_cond { - static inline PacketScalar run(const PacketScalar& x) { return x; } + static inline PacketType run(const PacketType& x) { return x; } }; } // end namespace internal +/** \class Reverse + * \ingroup Core_Module + * + * \brief Expression of the reverse of a vector or matrix + * + * \tparam MatrixType the type of the object of which we are taking the reverse + * \tparam Direction defines the direction of the reverse operation, can be Vertical, Horizontal, or BothDirections + * + * This class represents an expression of the reverse of a vector. + * It is the return type of MatrixBase::reverse() and VectorwiseOp::reverse() + * and most of the time this is the only way it is used. + * + * \sa MatrixBase::reverse(), VectorwiseOp::reverse() + */ template class Reverse : public internal::dense_xpr_base< Reverse >::type { @@ -74,26 +67,9 @@ template class Reverse typedef typename internal::dense_xpr_base::type Base; EIGEN_DENSE_PUBLIC_INTERFACE(Reverse) + typedef typename internal::remove_all::type NestedExpression; using Base::IsRowMajor; - // The following two operators are provided to worarkound - // a MSVC 2013 issue. In theory, we could simply do: - // using Base::operator(); - // to make const version of operator() visible. - // Otheriwse, they would be hidden by the non-const versions defined in this file - - inline CoeffReturnType operator()(Index row, Index col) const - { - eigen_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); - return coeff(row, col); - } - - inline CoeffReturnType operator()(Index index) const - { - eigen_assert(index >= 0 && index < m_matrix.size()); - return coeff(index); - } - protected: enum { PacketSize = internal::packet_traits::size, @@ -109,82 +85,19 @@ template class Reverse typedef internal::reverse_packet_cond reverse_packet; public: - inline Reverse(const MatrixType& matrix) : m_matrix(matrix) { } + EIGEN_DEVICE_FUNC explicit inline Reverse(const MatrixType& matrix) : m_matrix(matrix) { } EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Reverse) - inline Index rows() const { return m_matrix.rows(); } - inline Index cols() const { return m_matrix.cols(); } + EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows(); } + EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols(); } - inline Index innerStride() const + EIGEN_DEVICE_FUNC inline Index innerStride() const { return -m_matrix.innerStride(); } - inline Scalar& operator()(Index row, Index col) - { - eigen_assert(row >= 0 && row < rows() && col >= 0 && col < cols()); - return coeffRef(row, col); - } - - inline Scalar& coeffRef(Index row, Index col) - { - return m_matrix.const_cast_derived().coeffRef(ReverseRow ? m_matrix.rows() - row - 1 : row, - ReverseCol ? m_matrix.cols() - col - 1 : col); - } - - inline CoeffReturnType coeff(Index row, Index col) const - { - return m_matrix.coeff(ReverseRow ? m_matrix.rows() - row - 1 : row, - ReverseCol ? m_matrix.cols() - col - 1 : col); - } - - inline CoeffReturnType coeff(Index index) const - { - return m_matrix.coeff(m_matrix.size() - index - 1); - } - - inline Scalar& coeffRef(Index index) - { - return m_matrix.const_cast_derived().coeffRef(m_matrix.size() - index - 1); - } - - inline Scalar& operator()(Index index) - { - eigen_assert(index >= 0 && index < m_matrix.size()); - return coeffRef(index); - } - - template - inline const PacketScalar packet(Index row, Index col) const - { - return reverse_packet::run(m_matrix.template packet( - ReverseRow ? m_matrix.rows() - row - OffsetRow : row, - ReverseCol ? m_matrix.cols() - col - OffsetCol : col)); - } - - template - inline void writePacket(Index row, Index col, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket( - ReverseRow ? m_matrix.rows() - row - OffsetRow : row, - ReverseCol ? m_matrix.cols() - col - OffsetCol : col, - reverse_packet::run(x)); - } - - template - inline const PacketScalar packet(Index index) const - { - return internal::preverse(m_matrix.template packet( m_matrix.size() - index - PacketSize )); - } - - template - inline void writePacket(Index index, const PacketScalar& x) - { - m_matrix.const_cast_derived().template writePacket(m_matrix.size() - index - PacketSize, internal::preverse(x)); - } - - const typename internal::remove_all::type& + EIGEN_DEVICE_FUNC const typename internal::remove_all::type& nestedExpression() const { return m_matrix; @@ -204,33 +117,93 @@ template inline typename DenseBase::ReverseReturnType DenseBase::reverse() { - return derived(); + return ReverseReturnType(derived()); } -/** This is the const version of reverse(). */ -template -inline const typename DenseBase::ConstReverseReturnType -DenseBase::reverse() const -{ - return derived(); -} + +//reverse const overload moved DenseBase.h due to a CUDA compiler bug /** This is the "in place" version of reverse: it reverses \c *this. * * In most cases it is probably better to simply use the reversed expression * of a matrix. However, when reversing the matrix data itself is really needed, * then this "in-place" version is probably the right choice because it provides - * the following additional features: + * the following additional benefits: * - less error prone: doing the same operation with .reverse() requires special care: * \code m = m.reverse().eval(); \endcode - * - this API allows to avoid creating a temporary (the current implementation creates a temporary, but that could be avoided using swap) + * - this API enables reverse operations without the need for a temporary * - it allows future optimizations (cache friendliness, etc.) * - * \sa reverse() */ + * \sa VectorwiseOp::reverseInPlace(), reverse() */ template inline void DenseBase::reverseInPlace() { - derived() = derived().reverse().eval(); + if(cols()>rows()) + { + Index half = cols()/2; + leftCols(half).swap(rightCols(half).reverse()); + if((cols()%2)==1) + { + Index half2 = rows()/2; + col(half).head(half2).swap(col(half).tail(half2).reverse()); + } + } + else + { + Index half = rows()/2; + topRows(half).swap(bottomRows(half).reverse()); + if((rows()%2)==1) + { + Index half2 = cols()/2; + row(half).head(half2).swap(row(half).tail(half2).reverse()); + } + } +} + +namespace internal { + +template +struct vectorwise_reverse_inplace_impl; + +template<> +struct vectorwise_reverse_inplace_impl +{ + template + static void run(ExpressionType &xpr) + { + Index half = xpr.rows()/2; + xpr.topRows(half).swap(xpr.bottomRows(half).colwise().reverse()); + } +}; + +template<> +struct vectorwise_reverse_inplace_impl +{ + template + static void run(ExpressionType &xpr) + { + Index half = xpr.cols()/2; + xpr.leftCols(half).swap(xpr.rightCols(half).rowwise().reverse()); + } +}; + +} // end namespace internal + +/** This is the "in place" version of VectorwiseOp::reverse: it reverses each column or row of \c *this. + * + * In most cases it is probably better to simply use the reversed expression + * of a matrix. However, when reversing the matrix data itself is really needed, + * then this "in-place" version is probably the right choice because it provides + * the following additional benefits: + * - less error prone: doing the same operation with .reverse() requires special care: + * \code m = m.reverse().eval(); \endcode + * - this API enables reverse operations without the need for a temporary + * + * \sa DenseBase::reverseInPlace(), reverse() */ +template +void VectorwiseOp::reverseInPlace() +{ + internal::vectorwise_reverse_inplace_impl::run(_expression().const_cast_derived()); } } // end namespace Eigen diff --git a/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h b/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h index 87993bbb5..79eec1b5b 100644 --- a/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h +++ b/gtsam/3rdparty/Eigen/Eigen/src/Core/Select.h @@ -43,23 +43,21 @@ struct traits > ColsAtCompileTime = ConditionMatrixType::ColsAtCompileTime, MaxRowsAtCompileTime = ConditionMatrixType::MaxRowsAtCompileTime, MaxColsAtCompileTime = ConditionMatrixType::MaxColsAtCompileTime, - Flags = (unsigned int)ThenMatrixType::Flags & ElseMatrixType::Flags & HereditaryBits, - CoeffReadCost = traits::type>::CoeffReadCost - + EIGEN_SIZE_MAX(traits::type>::CoeffReadCost, - traits::type>::CoeffReadCost) + Flags = (unsigned int)ThenMatrixType::Flags & ElseMatrixType::Flags & RowMajorBit }; }; } template -class Select : internal::no_assignment_operator, - public internal::dense_xpr_base< Select >::type +class Select : public internal::dense_xpr_base< Select >::type, + internal::no_assignment_operator { public: typedef typename internal::dense_xpr_base" << endl; + cerr << "available actions:" << endl; + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + cerr << " " << (*it)->invokation_name() << endl; + } + cerr << "the input files should each contain an output of benchmark-blocking-sizes" << endl; + exit(1); +} + +int main(int argc, char* argv[]) +{ + cout.precision(default_precision); + cerr.precision(default_precision); + + vector> available_actions; + available_actions.emplace_back(new partition_action_t); + available_actions.emplace_back(new evaluate_defaults_action_t); + + vector input_filenames; + + action_t* action = nullptr; + + if (argc < 2) { + show_usage_and_exit(argc, argv, available_actions); + } + for (int i = 1; i < argc; i++) { + bool arg_handled = false; + // Step 1. Try to match action invokation names. + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + if (!strcmp(argv[i], (*it)->invokation_name())) { + if (!action) { + action = it->get(); + arg_handled = true; + break; + } else { + cerr << "can't specify more than one action!" << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + } + if (arg_handled) { + continue; + } + // Step 2. Try to match option names. + if (argv[i][0] == '-') { + if (!strcmp(argv[i], "--only-cubic-sizes")) { + only_cubic_sizes = true; + arg_handled = true; + } + if (!strcmp(argv[i], "--dump-tables")) { + dump_tables = true; + arg_handled = true; + } + if (!arg_handled) { + cerr << "Unrecognized option: " << argv[i] << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + if (arg_handled) { + continue; + } + // Step 3. Default to interpreting args as input filenames. + input_filenames.emplace_back(argv[i]); + } + + if (dump_tables && only_cubic_sizes) { + cerr << "Incompatible options: --only-cubic-sizes and --dump-tables." << endl; + show_usage_and_exit(argc, argv, available_actions); + } + + if (!action) { + show_usage_and_exit(argc, argv, available_actions); + } + + action->run(input_filenames); +} diff --git a/gtsam/3rdparty/Eigen/bench/benchCholesky.cpp b/gtsam/3rdparty/Eigen/bench/benchCholesky.cpp index 42b3e1285..9a8e7cf63 100644 --- a/gtsam/3rdparty/Eigen/bench/benchCholesky.cpp +++ b/gtsam/3rdparty/Eigen/bench/benchCholesky.cpp @@ -31,7 +31,7 @@ __attribute__ ((noinline)) void benchLLT(const MatrixType& m) int rows = m.rows(); int cols = m.cols(); - int cost = 0; + double cost = 0; for (int j=0; j0; ++i) + for (int i=0; dynsizes[i]>0; ++i) benchLLT(Matrix(dynsizes[i],dynsizes[i])); benchLLT(Matrix()); diff --git a/gtsam/3rdparty/Eigen/bench/bench_gemm.cpp b/gtsam/3rdparty/Eigen/bench/bench_gemm.cpp index 41ca8b3b6..8528c5587 100644 --- a/gtsam/3rdparty/Eigen/bench/bench_gemm.cpp +++ b/gtsam/3rdparty/Eigen/bench/bench_gemm.cpp @@ -2,6 +2,14 @@ // g++-4.4 bench_gemm.cpp -I .. -O2 -DNDEBUG -lrt -fopenmp && OMP_NUM_THREADS=2 ./a.out // icpc bench_gemm.cpp -I .. -O3 -DNDEBUG -lrt -openmp && OMP_NUM_THREADS=2 ./a.out +// Compilation options: +// +// -DSCALAR=std::complex +// -DSCALARA=double or -DSCALARB=double +// -DHAVE_BLAS +// -DDECOUPLED +// + #include #include #include @@ -14,10 +22,18 @@ using namespace Eigen; #define SCALAR float #endif +#ifndef SCALARA +#define SCALARA SCALAR +#endif + +#ifndef SCALARB +#define SCALARB SCALAR +#endif + typedef SCALAR Scalar; typedef NumTraits::Real RealScalar; -typedef Matrix A; -typedef Matrix B; +typedef Matrix A; +typedef Matrix B; typedef Matrix C; typedef Matrix M; @@ -129,35 +145,69 @@ int main(int argc, char ** argv) int tries = 2; // number of tries, we keep the best int s = 2048; - int cache_size = -1; + int m = s; + int n = s; + int p = s; + int cache_size1=-1, cache_size2=l2, cache_size3 = 0; bool need_help = false; - for (int i=1; i c t p\n"; + std::cout << argv[0] << " -s -c -t -p \n"; + std::cout << " : size\n"; + std::cout << " : rows columns depth\n"; return 1; } - if(cache_size>0) - setCpuCacheSizes(cache_size,96*cache_size); - - int m = s; - int n = s; - int p = s; +#if EIGEN_VERSION_AT_LEAST(3,2,90) + if(cache_size1>0) + setCpuCacheSizes(cache_size1,cache_size2,cache_size3); +#endif + A a(m,p); a.setRandom(); B b(p,n); b.setRandom(); C c(m,n); c.setOnes(); @@ -172,6 +222,7 @@ int main(int argc, char ** argv) // check the parallel product is correct #if defined EIGEN_HAS_OPENMP + Eigen::initParallel(); int procs = omp_get_max_threads(); if(procs>1) { @@ -188,11 +239,20 @@ int main(int argc, char ** argv) #elif defined HAVE_BLAS blas_gemm(a,b,r); c.noalias() += a * b; - if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; + if(!r.isApprox(c)) { + std::cout << r - c << "\n"; + std::cerr << "Warning, your product is crap!\n\n"; + } #else - gemm(a,b,c); - r.noalias() += a.cast() * b.cast(); - if(!r.isApprox(c)) std::cerr << "Warning, your product is crap!\n\n"; + if(1.*m*n*p<2000.*2000*2000) + { + gemm(a,b,c); + r.noalias() += a.cast() .lazyProduct( b.cast() ); + if(!r.isApprox(c)) { + std::cout << r - c << "\n"; + std::cerr << "Warning, your product is crap!\n\n"; + } + } #endif #ifdef HAVE_BLAS @@ -214,7 +274,7 @@ int main(int argc, char ** argv) { BenchTimer tmono; omp_set_num_threads(1); - Eigen::internal::setNbThreads(1); + Eigen::setNbThreads(1); c = rc; BENCH(tmono, tries, rep, gemm(a,b,c)); std::cout << "eigen mono cpu " << tmono.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmono.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmono.total(CPU_TIMER) << "s)\n"; @@ -223,6 +283,15 @@ int main(int argc, char ** argv) } #endif + if(1.*m*n*p<30*30*30) + { + BenchTimer tmt; + c = rc; + BENCH(tmt, tries, rep, c.noalias()+=a.lazyProduct(b)); + std::cout << "lazy cpu " << tmt.best(CPU_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(CPU_TIMER) << "s)\n"; + std::cout << "lazy real " << tmt.best(REAL_TIMER)/rep << "s \t" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 << " GFLOPS \t(" << tmt.total(REAL_TIMER) << "s)\n"; + } + #ifdef DECOUPLED if((NumTraits::IsComplex) && (NumTraits::IsComplex)) { diff --git a/gtsam/3rdparty/Eigen/bench/bench_norm.cpp b/gtsam/3rdparty/Eigen/bench/bench_norm.cpp index 806db292c..129afcfb2 100644 --- a/gtsam/3rdparty/Eigen/bench/bench_norm.cpp +++ b/gtsam/3rdparty/Eigen/bench/bench_norm.cpp @@ -6,19 +6,25 @@ using namespace Eigen; using namespace std; template -EIGEN_DONT_INLINE typename T::Scalar sqsumNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar sqsumNorm(T& v) { return v.norm(); } template -EIGEN_DONT_INLINE typename T::Scalar hypotNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar stableNorm(T& v) +{ + return v.stableNorm(); +} + +template +EIGEN_DONT_INLINE typename T::Scalar hypotNorm(T& v) { return v.hypotNorm(); } template -EIGEN_DONT_INLINE typename T::Scalar blueNorm(const T& v) +EIGEN_DONT_INLINE typename T::Scalar blueNorm(T& v) { return v.blueNorm(); } @@ -32,25 +38,25 @@ EIGEN_DONT_INLINE typename T::Scalar lapackNorm(T& v) Scalar ssq = 1; for (int i=0;i= ax) { - ssq += internal::abs2(ax/scale); + ssq += numext::abs2(ax/scale); } else { - ssq = Scalar(1) + ssq * internal::abs2(scale/ax); + ssq = Scalar(1) + ssq * numext::abs2(scale/ax); scale = ax; } } - return scale * internal::sqrt(ssq); + return scale * std::sqrt(ssq); } template EIGEN_DONT_INLINE typename T::Scalar twopassNorm(T& v) { typedef typename T::Scalar Scalar; - Scalar s = v.cwise().abs().maxCoeff(); + Scalar s = v.array().abs().maxCoeff(); return s*(v/s).norm(); } @@ -73,16 +79,20 @@ EIGEN_DONT_INLINE typename T::Scalar divacNorm(T& v) v(i) = v(2*i) + v(2*i+1); n = n/2; } - return internal::sqrt(v(0)); + return std::sqrt(v(0)); } +namespace Eigen { +namespace internal { #ifdef EIGEN_VECTORIZE -Packet4f internal::plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); } -Packet2d internal::plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); } +Packet4f plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); } +Packet2d plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); } -Packet4f internal::pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); } -Packet2d internal::pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); } +Packet4f pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); } +Packet2d pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); } #endif +} +} template EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) @@ -126,7 +136,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) overfl = rbig*s2m; // overfow boundary for abig eps = std::pow(ibeta, 1-it); - relerr = internal::sqrt(eps); // tolerance for neglecting asml + relerr = std::sqrt(eps); // tolerance for neglecting asml abig = 1.0/eps - 1.0; if (Scalar(nbig)>abig) nmax = abig; // largest safe n else nmax = nbig; @@ -134,13 +144,13 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) typedef typename internal::packet_traits::type Packet; const int ps = internal::packet_traits::size; - Packet pasml = internal::pset1(Scalar(0)); - Packet pamed = internal::pset1(Scalar(0)); - Packet pabig = internal::pset1(Scalar(0)); - Packet ps2m = internal::pset1(s2m); - Packet ps1m = internal::pset1(s1m); - Packet pb2 = internal::pset1(b2); - Packet pb1 = internal::pset1(b1); + Packet pasml = internal::pset1(Scalar(0)); + Packet pamed = internal::pset1(Scalar(0)); + Packet pabig = internal::pset1(Scalar(0)); + Packet ps2m = internal::pset1(s2m); + Packet ps1m = internal::pset1(s1m); + Packet pb2 = internal::pset1(b2); + Packet pb1 = internal::pset1(b1); for(int j=0; j(j)); @@ -170,7 +180,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) Scalar amed = internal::predux(pamed); if(abig > Scalar(0)) { - abig = internal::sqrt(abig); + abig = std::sqrt(abig); if(abig > overfl) { eigen_assert(false && "overflow"); @@ -179,7 +189,7 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) if(amed > Scalar(0)) { abig = abig/s2m; - amed = internal::sqrt(amed); + amed = std::sqrt(amed); } else { @@ -191,55 +201,56 @@ EIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v) { if (amed > Scalar(0)) { - abig = internal::sqrt(amed); - amed = internal::sqrt(asml) / s1m; + abig = std::sqrt(amed); + amed = std::sqrt(asml) / s1m; } else { - return internal::sqrt(asml)/s1m; + return std::sqrt(asml)/s1m; } } else { - return internal::sqrt(amed); + return std::sqrt(amed); } asml = std::min(abig, amed); abig = std::max(abig, amed); if(asml <= abig*relerr) return abig; else - return abig * internal::sqrt(Scalar(1) + internal::abs2(asml/abig)); + return abig * std::sqrt(Scalar(1) + numext::abs2(asml/abig)); #endif } #define BENCH_PERF(NRM) { \ + float af = 0; double ad = 0; std::complex ac = 0; \ Eigen::BenchTimer tf, td, tcf; tf.reset(); td.reset(); tcf.reset();\ for (int k=0; k()); - double yd = based * internal::abs(internal::random()); + double yf = basef * std::abs(internal::random()); + double yd = based * std::abs(internal::random()); VectorXf vf = VectorXf::Ones(s) * yf; VectorXd vd = VectorXd::Ones(s) * yd; - std::cout << "reference\t" << internal::sqrt(double(s))*yf << "\t" << internal::sqrt(double(s))*yd << "\n"; + std::cout << "reference\t" << std::sqrt(double(s))*yf << "\t" << std::sqrt(double(s))*yd << "\n"; std::cout << "sqsumNorm\t" << sqsumNorm(vf) << "\t" << sqsumNorm(vd) << "\n"; std::cout << "hypotNorm\t" << hypotNorm(vf) << "\t" << hypotNorm(vd) << "\n"; std::cout << "blueNorm\t" << blueNorm(vf) << "\t" << blueNorm(vd) << "\n"; @@ -255,8 +266,8 @@ void check_accuracy_var(int ef0, int ef1, int ed0, int ed1, int s) VectorXd vd(s); for (int i=0; i()) * std::pow(double(10), internal::random(ef0,ef1)); - vd[i] = internal::abs(internal::random()) * std::pow(double(10), internal::random(ed0,ed1)); + vf[i] = std::abs(internal::random()) * std::pow(double(10), internal::random(ef0,ef1)); + vd[i] = std::abs(internal::random()) * std::pow(double(10), internal::random(ed0,ed1)); } //std::cout << "reference\t" << internal::sqrt(double(s))*yf << "\t" << internal::sqrt(double(s))*yd << "\n"; @@ -312,34 +323,38 @@ int main(int argc, char** argv) std::cout << "\n"; } + y = 1; std::cout.precision(4); - std::cerr << "Performance (out of cache):\n"; + int s1 = 1024*1024*32; + std::cerr << "Performance (out of cache, " << s1 << "):\n"; { int iters = 1; - VectorXf vf = VectorXf::Random(1024*1024*32) * y; - VectorXd vd = VectorXd::Random(1024*1024*32) * y; - VectorXcf vcf = VectorXcf::Random(1024*1024*32) * y; + VectorXf vf = VectorXf::Random(s1) * y; + VectorXd vd = VectorXd::Random(s1) * y; + VectorXcf vcf = VectorXcf::Random(s1) * y; BENCH_PERF(sqsumNorm); + BENCH_PERF(stableNorm); BENCH_PERF(blueNorm); -// BENCH_PERF(pblueNorm); -// BENCH_PERF(lapackNorm); -// BENCH_PERF(hypotNorm); -// BENCH_PERF(twopassNorm); + BENCH_PERF(pblueNorm); + BENCH_PERF(lapackNorm); + BENCH_PERF(hypotNorm); + BENCH_PERF(twopassNorm); BENCH_PERF(bl2passNorm); } - std::cerr << "\nPerformance (in cache):\n"; + std::cerr << "\nPerformance (in cache, " << 512 << "):\n"; { int iters = 100000; VectorXf vf = VectorXf::Random(512) * y; VectorXd vd = VectorXd::Random(512) * y; VectorXcf vcf = VectorXcf::Random(512) * y; BENCH_PERF(sqsumNorm); + BENCH_PERF(stableNorm); BENCH_PERF(blueNorm); -// BENCH_PERF(pblueNorm); -// BENCH_PERF(lapackNorm); -// BENCH_PERF(hypotNorm); -// BENCH_PERF(twopassNorm); + BENCH_PERF(pblueNorm); + BENCH_PERF(lapackNorm); + BENCH_PERF(hypotNorm); + BENCH_PERF(twopassNorm); BENCH_PERF(bl2passNorm); } } diff --git a/gtsam/3rdparty/Eigen/bench/benchmark-blocking-sizes.cpp b/gtsam/3rdparty/Eigen/bench/benchmark-blocking-sizes.cpp new file mode 100644 index 000000000..827be2880 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/benchmark-blocking-sizes.cpp @@ -0,0 +1,677 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Jacob +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include +#include +#include +#include +#include +#include +#include + +bool eigen_use_specific_block_size; +int eigen_block_size_k, eigen_block_size_m, eigen_block_size_n; +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZES eigen_use_specific_block_size +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_K eigen_block_size_k +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_M eigen_block_size_m +#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_N eigen_block_size_n +#include + +#include + +using namespace Eigen; +using namespace std; + +static BenchTimer timer; + +// how many times we repeat each measurement. +// measurements are randomly shuffled - we're not doing +// all N identical measurements in a row. +const int measurement_repetitions = 3; + +// Timings below this value are too short to be accurate, +// we'll repeat measurements with more iterations until +// we get a timing above that threshold. +const float min_accurate_time = 1e-2f; + +// See --min-working-set-size command line parameter. +size_t min_working_set_size = 0; + +float max_clock_speed = 0.0f; + +// range of sizes that we will benchmark (in all 3 K,M,N dimensions) +const size_t maxsize = 2048; +const size_t minsize = 16; + +typedef MatrixXf MatrixType; +typedef MatrixType::Scalar Scalar; +typedef internal::packet_traits::type Packet; + +static_assert((maxsize & (maxsize - 1)) == 0, "maxsize must be a power of two"); +static_assert((minsize & (minsize - 1)) == 0, "minsize must be a power of two"); +static_assert(maxsize > minsize, "maxsize must be larger than minsize"); +static_assert(maxsize < (minsize << 16), "maxsize must be less than (minsize<<16)"); + +// just a helper to store a triple of K,M,N sizes for matrix product +struct size_triple_t +{ + size_t k, m, n; + size_triple_t() : k(0), m(0), n(0) {} + size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {} + size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {} + size_triple_t(uint16_t compact) + { + k = 1 << ((compact & 0xf00) >> 8); + m = 1 << ((compact & 0x0f0) >> 4); + n = 1 << ((compact & 0x00f) >> 0); + } +}; + +uint8_t log2_pot(size_t x) { + size_t l = 0; + while (x >>= 1) l++; + return l; +} + +// Convert between size tripes and a compact form fitting in 12 bits +// where each size, which must be a POT, is encoded as its log2, on 4 bits +// so the largest representable size is 2^15 == 32k ... big enough. +uint16_t compact_size_triple(size_t k, size_t m, size_t n) +{ + return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n); +} + +uint16_t compact_size_triple(const size_triple_t& t) +{ + return compact_size_triple(t.k, t.m, t.n); +} + +// A single benchmark. Initially only contains benchmark params. +// Then call run(), which stores the result in the gflops field. +struct benchmark_t +{ + uint16_t compact_product_size; + uint16_t compact_block_size; + bool use_default_block_size; + float gflops; + benchmark_t() + : compact_product_size(0) + , compact_block_size(0) + , use_default_block_size(false) + , gflops(0) + { + } + benchmark_t(size_t pk, size_t pm, size_t pn, + size_t bk, size_t bm, size_t bn) + : compact_product_size(compact_size_triple(pk, pm, pn)) + , compact_block_size(compact_size_triple(bk, bm, bn)) + , use_default_block_size(false) + , gflops(0) + {} + benchmark_t(size_t pk, size_t pm, size_t pn) + : compact_product_size(compact_size_triple(pk, pm, pn)) + , compact_block_size(0) + , use_default_block_size(true) + , gflops(0) + {} + + void run(); +}; + +ostream& operator<<(ostream& s, const benchmark_t& b) +{ + s << hex << b.compact_product_size << dec; + if (b.use_default_block_size) { + size_triple_t t(b.compact_product_size); + Index k = t.k, m = t.m, n = t.n; + internal::computeProductBlockingSizes(k, m, n); + s << " default(" << k << ", " << m << ", " << n << ")"; + } else { + s << " " << hex << b.compact_block_size << dec; + } + s << " " << b.gflops; + return s; +} + +// We sort first by increasing benchmark parameters, +// then by decreasing performance. +bool operator<(const benchmark_t& b1, const benchmark_t& b2) +{ + return b1.compact_product_size < b2.compact_product_size || + (b1.compact_product_size == b2.compact_product_size && ( + (b1.compact_block_size < b2.compact_block_size || ( + b1.compact_block_size == b2.compact_block_size && + b1.gflops > b2.gflops)))); +} + +void benchmark_t::run() +{ + size_triple_t productsizes(compact_product_size); + + if (use_default_block_size) { + eigen_use_specific_block_size = false; + } else { + // feed eigen with our custom blocking params + eigen_use_specific_block_size = true; + size_triple_t blocksizes(compact_block_size); + eigen_block_size_k = blocksizes.k; + eigen_block_size_m = blocksizes.m; + eigen_block_size_n = blocksizes.n; + } + + // set up the matrix pool + + const size_t combined_three_matrices_sizes = + sizeof(Scalar) * + (productsizes.k * productsizes.m + + productsizes.k * productsizes.n + + productsizes.m * productsizes.n); + + // 64 M is large enough that nobody has a cache bigger than that, + // while still being small enough that everybody has this much RAM, + // so conveniently we don't need to special-case platforms here. + const size_t unlikely_large_cache_size = 64 << 20; + + const size_t working_set_size = + min_working_set_size ? min_working_set_size : unlikely_large_cache_size; + + const size_t matrix_pool_size = + 1 + working_set_size / combined_three_matrices_sizes; + + MatrixType *lhs = new MatrixType[matrix_pool_size]; + MatrixType *rhs = new MatrixType[matrix_pool_size]; + MatrixType *dst = new MatrixType[matrix_pool_size]; + + for (size_t i = 0; i < matrix_pool_size; i++) { + lhs[i] = MatrixType::Zero(productsizes.m, productsizes.k); + rhs[i] = MatrixType::Zero(productsizes.k, productsizes.n); + dst[i] = MatrixType::Zero(productsizes.m, productsizes.n); + } + + // main benchmark loop + + int iters_at_a_time = 1; + float time_per_iter = 0.0f; + size_t matrix_index = 0; + while (true) { + + double starttime = timer.getCpuTime(); + for (int i = 0; i < iters_at_a_time; i++) { + dst[matrix_index].noalias() = lhs[matrix_index] * rhs[matrix_index]; + matrix_index++; + if (matrix_index == matrix_pool_size) { + matrix_index = 0; + } + } + double endtime = timer.getCpuTime(); + + const float timing = float(endtime - starttime); + + if (timing >= min_accurate_time) { + time_per_iter = timing / iters_at_a_time; + break; + } + + iters_at_a_time *= 2; + } + + delete[] lhs; + delete[] rhs; + delete[] dst; + + gflops = 2e-9 * productsizes.k * productsizes.m * productsizes.n / time_per_iter; +} + +void print_cpuinfo() +{ +#ifdef __linux__ + cout << "contents of /proc/cpuinfo:" << endl; + string line; + ifstream cpuinfo("/proc/cpuinfo"); + if (cpuinfo.is_open()) { + while (getline(cpuinfo, line)) { + cout << line << endl; + } + cpuinfo.close(); + } + cout << endl; +#elif defined __APPLE__ + cout << "output of sysctl hw:" << endl; + system("sysctl hw"); + cout << endl; +#endif +} + +template +string type_name() +{ + return "unknown"; +} + +template<> +string type_name() +{ + return "float"; +} + +template<> +string type_name() +{ + return "double"; +} + +struct action_t +{ + virtual const char* invokation_name() const { abort(); return nullptr; } + virtual void run() const { abort(); } + virtual ~action_t() {} +}; + +void show_usage_and_exit(int /*argc*/, char* argv[], + const vector>& available_actions) +{ + cerr << "usage: " << argv[0] << " [options...]" << endl << endl; + cerr << "available actions:" << endl << endl; + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + cerr << " " << (*it)->invokation_name() << endl; + } + cerr << endl; + cerr << "options:" << endl << endl; + cerr << " --min-working-set-size=N:" << endl; + cerr << " Set the minimum working set size to N bytes." << endl; + cerr << " This is rounded up as needed to a multiple of matrix size." << endl; + cerr << " A larger working set lowers the chance of a warm cache." << endl; + cerr << " The default value 0 means use a large enough working" << endl; + cerr << " set to likely outsize caches." << endl; + cerr << " A value of 1 (that is, 1 byte) would mean don't do anything to" << endl; + cerr << " avoid warm caches." << endl; + exit(1); +} + +float measure_clock_speed() +{ + cerr << "Measuring clock speed... \r" << flush; + + vector all_gflops; + for (int i = 0; i < 8; i++) { + benchmark_t b(1024, 1024, 1024); + b.run(); + all_gflops.push_back(b.gflops); + } + + sort(all_gflops.begin(), all_gflops.end()); + float stable_estimate = all_gflops[2] + all_gflops[3] + all_gflops[4] + all_gflops[5]; + + // multiply by an arbitrary constant to discourage trying doing anything with the + // returned values besides just comparing them with each other. + float result = stable_estimate * 123.456f; + + return result; +} + +struct human_duration_t +{ + int seconds; + human_duration_t(int s) : seconds(s) {} +}; + +ostream& operator<<(ostream& s, const human_duration_t& d) +{ + int remainder = d.seconds; + if (remainder > 3600) { + int hours = remainder / 3600; + s << hours << " h "; + remainder -= hours * 3600; + } + if (remainder > 60) { + int minutes = remainder / 60; + s << minutes << " min "; + remainder -= minutes * 60; + } + if (d.seconds < 600) { + s << remainder << " s"; + } + return s; +} + +const char session_filename[] = "/data/local/tmp/benchmark-blocking-sizes-session.data"; + +void serialize_benchmarks(const char* filename, const vector& benchmarks, size_t first_benchmark_to_run) +{ + FILE* file = fopen(filename, "w"); + if (!file) { + cerr << "Could not open file " << filename << " for writing." << endl; + cerr << "Do you have write permissions on the current working directory?" << endl; + exit(1); + } + size_t benchmarks_vector_size = benchmarks.size(); + fwrite(&max_clock_speed, sizeof(max_clock_speed), 1, file); + fwrite(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file); + fwrite(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file); + fwrite(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file); + fclose(file); +} + +bool deserialize_benchmarks(const char* filename, vector& benchmarks, size_t& first_benchmark_to_run) +{ + FILE* file = fopen(filename, "r"); + if (!file) { + return false; + } + if (1 != fread(&max_clock_speed, sizeof(max_clock_speed), 1, file)) { + return false; + } + size_t benchmarks_vector_size = 0; + if (1 != fread(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file)) { + return false; + } + if (1 != fread(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file)) { + return false; + } + benchmarks.resize(benchmarks_vector_size); + if (benchmarks.size() != fread(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file)) { + return false; + } + unlink(filename); + return true; +} + +void try_run_some_benchmarks( + vector& benchmarks, + double time_start, + size_t& first_benchmark_to_run) +{ + if (first_benchmark_to_run == benchmarks.size()) { + return; + } + + double time_last_progress_update = 0; + double time_last_clock_speed_measurement = 0; + double time_now = 0; + + size_t benchmark_index = first_benchmark_to_run; + + while (true) { + float ratio_done = float(benchmark_index) / benchmarks.size(); + time_now = timer.getRealTime(); + + // We check clock speed every minute and at the end. + if (benchmark_index == benchmarks.size() || + time_now > time_last_clock_speed_measurement + 60.0f) + { + time_last_clock_speed_measurement = time_now; + + // Ensure that clock speed is as expected + float current_clock_speed = measure_clock_speed(); + + // The tolerance needs to be smaller than the relative difference between + // clock speeds that a device could operate under. + // It seems unlikely that a device would be throttling clock speeds by + // amounts smaller than 2%. + // With a value of 1%, I was getting within noise on a Sandy Bridge. + const float clock_speed_tolerance = 0.02f; + + if (current_clock_speed > (1 + clock_speed_tolerance) * max_clock_speed) { + // Clock speed is now higher than we previously measured. + // Either our initial measurement was inaccurate, which won't happen + // too many times as we are keeping the best clock speed value and + // and allowing some tolerance; or something really weird happened, + // which invalidates all benchmark results collected so far. + // Either way, we better restart all over again now. + if (benchmark_index) { + cerr << "Restarting at " << 100.0f * ratio_done + << " % because clock speed increased. " << endl; + } + max_clock_speed = current_clock_speed; + first_benchmark_to_run = 0; + return; + } + + bool rerun_last_tests = false; + + if (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) { + cerr << "Measurements completed so far: " + << 100.0f * ratio_done + << " % " << endl; + cerr << "Clock speed seems to be only " + << current_clock_speed/max_clock_speed + << " times what it used to be." << endl; + + unsigned int seconds_to_sleep_if_lower_clock_speed = 1; + + while (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) { + if (seconds_to_sleep_if_lower_clock_speed > 32) { + cerr << "Sleeping longer probably won't make a difference." << endl; + cerr << "Serializing benchmarks to " << session_filename << endl; + serialize_benchmarks(session_filename, benchmarks, first_benchmark_to_run); + cerr << "Now restart this benchmark, and it should pick up where we left." << endl; + exit(2); + } + rerun_last_tests = true; + cerr << "Sleeping " + << seconds_to_sleep_if_lower_clock_speed + << " s... \r" << endl; + sleep(seconds_to_sleep_if_lower_clock_speed); + current_clock_speed = measure_clock_speed(); + seconds_to_sleep_if_lower_clock_speed *= 2; + } + } + + if (rerun_last_tests) { + cerr << "Redoing the last " + << 100.0f * float(benchmark_index - first_benchmark_to_run) / benchmarks.size() + << " % because clock speed had been low. " << endl; + return; + } + + // nothing wrong with the clock speed so far, so there won't be a need to rerun + // benchmarks run so far in case we later encounter a lower clock speed. + first_benchmark_to_run = benchmark_index; + } + + if (benchmark_index == benchmarks.size()) { + // We're done! + first_benchmark_to_run = benchmarks.size(); + // Erase progress info + cerr << " " << endl; + return; + } + + // Display progress info on stderr + if (time_now > time_last_progress_update + 1.0f) { + time_last_progress_update = time_now; + cerr << "Measurements... " << 100.0f * ratio_done + << " %, ETA " + << human_duration_t(float(time_now - time_start) * (1.0f - ratio_done) / ratio_done) + << " \r" << flush; + } + + // This is where we actually run a benchmark! + benchmarks[benchmark_index].run(); + benchmark_index++; + } +} + +void run_benchmarks(vector& benchmarks) +{ + size_t first_benchmark_to_run; + vector deserialized_benchmarks; + bool use_deserialized_benchmarks = false; + if (deserialize_benchmarks(session_filename, deserialized_benchmarks, first_benchmark_to_run)) { + cerr << "Found serialized session with " + << 100.0f * first_benchmark_to_run / deserialized_benchmarks.size() + << " % already done" << endl; + if (deserialized_benchmarks.size() == benchmarks.size() && + first_benchmark_to_run > 0 && + first_benchmark_to_run < benchmarks.size()) + { + use_deserialized_benchmarks = true; + } + } + + if (use_deserialized_benchmarks) { + benchmarks = deserialized_benchmarks; + } else { + // not using deserialized benchmarks, starting from scratch + first_benchmark_to_run = 0; + + // Randomly shuffling benchmarks allows us to get accurate enough progress info, + // as now the cheap/expensive benchmarks are randomly mixed so they average out. + // It also means that if data is corrupted for some time span, the odds are that + // not all repetitions of a given benchmark will be corrupted. + random_shuffle(benchmarks.begin(), benchmarks.end()); + } + + for (int i = 0; i < 4; i++) { + max_clock_speed = max(max_clock_speed, measure_clock_speed()); + } + + double time_start = 0.0; + while (first_benchmark_to_run < benchmarks.size()) { + if (first_benchmark_to_run == 0) { + time_start = timer.getRealTime(); + } + try_run_some_benchmarks(benchmarks, + time_start, + first_benchmark_to_run); + } + + // Sort timings by increasing benchmark parameters, and decreasing gflops. + // The latter is very important. It means that we can ignore all but the first + // benchmark with given parameters. + sort(benchmarks.begin(), benchmarks.end()); + + // Collect best (i.e. now first) results for each parameter values. + vector best_benchmarks; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + if (best_benchmarks.empty() || + best_benchmarks.back().compact_product_size != it->compact_product_size || + best_benchmarks.back().compact_block_size != it->compact_block_size) + { + best_benchmarks.push_back(*it); + } + } + + // keep and return only the best benchmarks + benchmarks = best_benchmarks; +} + +struct measure_all_pot_sizes_action_t : action_t +{ + virtual const char* invokation_name() const { return "all-pot-sizes"; } + virtual void run() const + { + vector benchmarks; + for (int repetition = 0; repetition < measurement_repetitions; repetition++) { + for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) { + for (size_t msize = minsize; msize <= maxsize; msize *= 2) { + for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) { + for (size_t kblock = minsize; kblock <= ksize; kblock *= 2) { + for (size_t mblock = minsize; mblock <= msize; mblock *= 2) { + for (size_t nblock = minsize; nblock <= nsize; nblock *= 2) { + benchmarks.emplace_back(ksize, msize, nsize, kblock, mblock, nblock); + } + } + } + } + } + } + } + + run_benchmarks(benchmarks); + + cout << "BEGIN MEASUREMENTS ALL POT SIZES" << endl; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + cout << *it << endl; + } + } +}; + +struct measure_default_sizes_action_t : action_t +{ + virtual const char* invokation_name() const { return "default-sizes"; } + virtual void run() const + { + vector benchmarks; + for (int repetition = 0; repetition < measurement_repetitions; repetition++) { + for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) { + for (size_t msize = minsize; msize <= maxsize; msize *= 2) { + for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) { + benchmarks.emplace_back(ksize, msize, nsize); + } + } + } + } + + run_benchmarks(benchmarks); + + cout << "BEGIN MEASUREMENTS DEFAULT SIZES" << endl; + for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) { + cout << *it << endl; + } + } +}; + +int main(int argc, char* argv[]) +{ + double time_start = timer.getRealTime(); + cout.precision(4); + cerr.precision(4); + + vector> available_actions; + available_actions.emplace_back(new measure_all_pot_sizes_action_t); + available_actions.emplace_back(new measure_default_sizes_action_t); + + auto action = available_actions.end(); + + if (argc <= 1) { + show_usage_and_exit(argc, argv, available_actions); + } + for (auto it = available_actions.begin(); it != available_actions.end(); ++it) { + if (!strcmp(argv[1], (*it)->invokation_name())) { + action = it; + break; + } + } + + if (action == available_actions.end()) { + show_usage_and_exit(argc, argv, available_actions); + } + + for (int i = 2; i < argc; i++) { + if (argv[i] == strstr(argv[i], "--min-working-set-size=")) { + const char* equals_sign = strchr(argv[i], '='); + min_working_set_size = strtoul(equals_sign+1, nullptr, 10); + } else { + cerr << "unrecognized option: " << argv[i] << endl << endl; + show_usage_and_exit(argc, argv, available_actions); + } + } + + print_cpuinfo(); + + cout << "benchmark parameters:" << endl; + cout << "pointer size: " << 8*sizeof(void*) << " bits" << endl; + cout << "scalar type: " << type_name() << endl; + cout << "packet size: " << internal::packet_traits::size << endl; + cout << "minsize = " << minsize << endl; + cout << "maxsize = " << maxsize << endl; + cout << "measurement_repetitions = " << measurement_repetitions << endl; + cout << "min_accurate_time = " << min_accurate_time << endl; + cout << "min_working_set_size = " << min_working_set_size; + if (min_working_set_size == 0) { + cout << " (try to outsize caches)"; + } + cout << endl << endl; + + (*action)->run(); + + double time_end = timer.getRealTime(); + cerr << "Finished in " << human_duration_t(time_end - time_start) << endl; +} diff --git a/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt index 119b470d9..38ff9f483 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/CMakeLists.txt @@ -11,29 +11,24 @@ SET(CMAKE_INCLUDE_CURRENT_DIR ON) string(REGEX MATCH icpc IS_ICPC ${CMAKE_CXX_COMPILER}) IF(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC) - SET(CMAKE_CXX_FLAGS "-g0 -O3 -DNDEBUG") - SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG") - IF(NOT BTL_NOVEC) - SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -msse2") - SET(CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} -msse2") - ELSE(NOT BTL_NOVEC) + SET(CMAKE_CXX_FLAGS "-g0 -O3 -DNDEBUG ${CMAKE_CXX_FLAGS}") + SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG ${CMAKE_Fortran_FLAGS}") + IF(BTL_NOVEC) SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE") - ENDIF(NOT BTL_NOVEC) + ENDIF(BTL_NOVEC) ENDIF(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC) IF(MSVC) SET(CMAKE_CXX_FLAGS " /O2 /Ot /GL /fp:fast -DNDEBUG") # SET(CMAKE_Fortran_FLAGS "-g0 -O3 -DNDEBUG") - IF(NOT BTL_NOVEC) - SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /arch:SSE2") - ELSE(NOT BTL_NOVEC) + IF(BTL_NOVEC) SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE") - ENDIF(NOT BTL_NOVEC) + ENDIF(BTL_NOVEC) ENDIF(MSVC) if(IS_ICPC) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fast") - set(CMAKE_Fortran_FLAGS "${CMAKE_Fortran_FLAGS} -fast") + set(CMAKE_CXX_FLAGS "-fast ${CMAKE_CXX_FLAGS}") + set(CMAKE_Fortran_FLAGS "-fast ${CMAKE_Fortran_FLAGS}") endif(IS_ICPC) include_directories( @@ -48,6 +43,12 @@ include_directories( # set(DEFAULT_LIBRARIES ${MKL_LIBRARIES}) # endif (MKL_FOUND) +find_library(EIGEN_BTL_RT_LIBRARY rt) +# if we cannot find it easily, then we don't need it! +if(NOT EIGEN_BTL_RT_LIBRARY) + set(EIGEN_BTL_RT_LIBRARY "") +endif() + MACRO(BTL_ADD_BENCH targetname) foreach(_current_var ${ARGN}) @@ -70,7 +71,7 @@ MACRO(BTL_ADD_BENCH targetname) IF(BUILD_${targetname}) ADD_EXECUTABLE(${targetname} ${_sources}) ADD_TEST(${targetname} "${targetname}") - target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} rt) + target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} ${EIGEN_BTL_RT_LIBRARY}) ENDIF(BUILD_${targetname}) ENDMACRO(BTL_ADD_BENCH) @@ -91,6 +92,7 @@ ENABLE_TESTING() add_subdirectory(libs/eigen3) add_subdirectory(libs/eigen2) +add_subdirectory(libs/tensors) add_subdirectory(libs/BLAS) add_subdirectory(libs/ublas) add_subdirectory(libs/gmm) @@ -98,6 +100,7 @@ add_subdirectory(libs/mtl4) add_subdirectory(libs/blitz) add_subdirectory(libs/tvmet) add_subdirectory(libs/STL) +add_subdirectory(libs/blaze) add_subdirectory(data) diff --git a/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpby.hh b/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpby.hh index 98511ab6a..dadd0ccf3 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpby.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpby.hh @@ -33,7 +33,7 @@ class Action_axpby { public : // Ctor - Action_axpby( int size ):_size(size),_alpha(0.5),_beta(0.95) + Action_axpby( int size ):_alpha(0.5),_beta(0.95),_size(size) { MESSAGE("Action_axpby Ctor"); diff --git a/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpy.hh b/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpy.hh index e4cb3a5bd..261be4cb8 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpy.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/actions/action_axpy.hh @@ -35,7 +35,7 @@ public : // Ctor - Action_axpy( int size ):_size(size),_coef(1.0) + Action_axpy( int size ):_coef(1.0),_size(size) { MESSAGE("Action_axpy Ctor"); diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindACML.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindACML.cmake index f45ae1b0d..4989fa2f4 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindACML.cmake +++ b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindACML.cmake @@ -17,6 +17,7 @@ find_file(ACML_LIBRARIES libacml_mp.so PATHS /usr/lib + /usr/lib64 $ENV{ACMLDIR}/lib ${LIB_INSTALL_DIR} ) @@ -35,6 +36,7 @@ if(NOT ACML_LIBRARIES) libacml.so libacml_mv.so PATHS /usr/lib + /usr/lib64 $ENV{ACMLDIR}/lib ${LIB_INSTALL_DIR} ) diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindATLAS.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindATLAS.cmake index 6b9065206..4136a989d 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindATLAS.cmake +++ b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindATLAS.cmake @@ -3,33 +3,25 @@ if (ATLAS_LIBRARIES) set(ATLAS_FIND_QUIETLY TRUE) endif (ATLAS_LIBRARIES) -find_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_LIB atlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_library(ATLAS_LIB satlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_file(ATLAS_CBLAS libcblas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_CBLAS cblas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_LAPACK NAMES liblapack_atlas.so.3 liblapack.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_library(ATLAS_LAPACK NAMES lapack_atlas lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_file(ATLAS_LAPACK liblapack_atlas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -find_library(ATLAS_LAPACK lapack_atlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) - -if(NOT ATLAS_LAPACK) - find_file(ATLAS_LAPACK liblapack.so.3 PATHS /usr/lib/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) - find_library(ATLAS_LAPACK lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) -endif(NOT ATLAS_LAPACK) - -find_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) +find_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) find_library(ATLAS_F77BLAS f77blas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR}) if(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS) - set(ATLAS_LIBRARIES ${ATLAS_LAPACK} ${ATLAS_CBLAS} ${ATLAS_F77BLAS} ${ATLAS_LIB}) + set(ATLAS_LIBRARIES ${ATLAS_LAPACK} ${ATLAS_LIB}) # search the default lapack lib link to it find_file(ATLAS_REFERENCE_LAPACK liblapack.so.3 PATHS /usr/lib /usr/lib64) find_library(ATLAS_REFERENCE_LAPACK NAMES lapack) - if(ATLAS_REFERENCE_LAPACK) - set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK}) - endif() +# if(ATLAS_REFERENCE_LAPACK) +# set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK}) +# endif() endif(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS) diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindBLAZE.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindBLAZE.cmake new file mode 100644 index 000000000..dba4c89f2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindBLAZE.cmake @@ -0,0 +1,31 @@ +# - Try to find eigen2 headers +# Once done this will define +# +# BLAZE_FOUND - system has blaze lib +# BLAZE_INCLUDE_DIR - the blaze include directory +# +# Copyright (C) 2008 Gael Guennebaud +# Adapted from FindEigen.cmake: +# Copyright (c) 2006, 2007 Montel Laurent, +# Redistribution and use is allowed according to the terms of the BSD license. +# For details see the accompanying COPYING-CMAKE-SCRIPTS file. + +if (BLAZE_INCLUDE_DIR) + + # in cache already + set(BLAZE_FOUND TRUE) + +else (BLAZE_INCLUDE_DIR) + +find_path(BLAZE_INCLUDE_DIR NAMES blaze/Blaze.h + PATHS + ${INCLUDE_INSTALL_DIR} + ) + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(BLAZE DEFAULT_MSG BLAZE_INCLUDE_DIR) + +mark_as_advanced(BLAZE_INCLUDE_DIR) + +endif(BLAZE_INCLUDE_DIR) + diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindCBLAS.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindCBLAS.cmake index 554f0291b..ce0f2f2b2 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindCBLAS.cmake +++ b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindCBLAS.cmake @@ -23,6 +23,7 @@ find_file(CBLAS_LIBRARIES libcblas.so.3 PATHS /usr/lib + /usr/lib64 $ENV{CBLASDIR}/lib ${LIB_INSTALL_DIR} ) diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO.cmake deleted file mode 100644 index 67ea0934a..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO.cmake +++ /dev/null @@ -1,15 +0,0 @@ - -if (GOTO_LIBRARIES) - set(GOTO_FIND_QUIETLY TRUE) -endif (GOTO_LIBRARIES) - -find_library(GOTO_LIBRARIES goto PATHS $ENV{GOTODIR} ${LIB_INSTALL_DIR}) - -if(GOTO_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) - set(GOTO_LIBRARIES ${GOTO_LIBRARIES} "-lpthread -lgfortran") -endif() - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GOTO DEFAULT_MSG GOTO_LIBRARIES) - -mark_as_advanced(GOTO_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO2.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO2.cmake deleted file mode 100644 index baa68d213..000000000 --- a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindGOTO2.cmake +++ /dev/null @@ -1,25 +0,0 @@ - -if (GOTO2_LIBRARIES) - set(GOTO2_FIND_QUIETLY TRUE) -endif (GOTO2_LIBRARIES) -# -# find_path(GOTO_INCLUDES -# NAMES -# cblas.h -# PATHS -# $ENV{GOTODIR}/include -# ${INCLUDE_INSTALL_DIR} -# ) - -find_file(GOTO2_LIBRARIES libgoto2.so PATHS /usr/lib $ENV{GOTO2DIR} ${LIB_INSTALL_DIR}) -find_library(GOTO2_LIBRARIES goto2 PATHS $ENV{GOTO2DIR} ${LIB_INSTALL_DIR}) - -if(GOTO2_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) - set(GOTO2_LIBRARIES ${GOTO2_LIBRARIES} "-lpthread -lgfortran") -endif() - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(GOTO2 DEFAULT_MSG - GOTO2_LIBRARIES) - -mark_as_advanced(GOTO2_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/bench/btl/cmake/FindOPENBLAS.cmake b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindOPENBLAS.cmake new file mode 100644 index 000000000..2a0919436 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/cmake/FindOPENBLAS.cmake @@ -0,0 +1,17 @@ + +if (OPENBLAS_LIBRARIES) + set(OPENBLAS_FIND_QUIETLY TRUE) +endif (OPENBLAS_LIBRARIES) + +find_file(OPENBLAS_LIBRARIES NAMES libopenblas.so libopenblas.so.0 PATHS /usr/lib /usr/lib64 $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR}) +find_library(OPENBLAS_LIBRARIES openblas PATHS $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR}) + +if(OPENBLAS_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX) + set(OPENBLAS_LIBRARIES ${OPENBLAS_LIBRARIES} "-lpthread -lgfortran") +endif() + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(OPENBLAS DEFAULT_MSG + OPENBLAS_LIBRARIES) + +mark_as_advanced(OPENBLAS_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt b/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt index e32213e22..39d2b5dc4 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/data/action_settings.txt @@ -1,19 +1,19 @@ -aat ; "{/*1.5 A x A^T}" ; "matrix size" ; 4:3000 -ata ; "{/*1.5 A^T x A}" ; "matrix size" ; 4:3000 -atv ; "{/*1.5 matrix^T x vector}" ; "matrix size" ; 4:3000 +aat ; "{/*1.5 A x A^T}" ; "matrix size" ; 4:5000 +ata ; "{/*1.5 A^T x A}" ; "matrix size" ; 4:5000 +atv ; "{/*1.5 matrix^T x vector}" ; "matrix size" ; 4:5000 axpby ; "{/*1.5 Y = alpha X + beta Y}" ; "vector size" ; 5:1000000 axpy ; "{/*1.5 Y += alpha X}" ; "vector size" ; 5:1000000 -matrix_matrix ; "{/*1.5 matrix matrix product}" ; "matrix size" ; 4:3000 -matrix_vector ; "{/*1.5 matrix vector product}" ; "matrix size" ; 4:3000 -trmm ; "{/*1.5 triangular matrix matrix product}" ; "matrix size" ; 4:3000 -trisolve_vector ; "{/*1.5 triangular solver - vector (X = inv(L) X)}" ; "size" ; 4:3000 -trisolve_matrix ; "{/*1.5 triangular solver - matrix (M = inv(L) M)}" ; "size" ; 4:3000 -cholesky ; "{/*1.5 Cholesky decomposition}" ; "matrix size" ; 4:3000 -complete_lu_decomp ; "{/*1.5 Complete LU decomposition}" ; "matrix size" ; 4:3000 -partial_lu_decomp ; "{/*1.5 Partial LU decomposition}" ; "matrix size" ; 4:3000 -tridiagonalization ; "{/*1.5 Tridiagonalization}" ; "matrix size" ; 4:3000 -hessenberg ; "{/*1.5 Hessenberg decomposition}" ; "matrix size" ; 4:3000 -symv ; "{/*1.5 symmetric matrix vector product}" ; "matrix size" ; 4:3000 -syr2 ; "{/*1.5 symmretric rank-2 update (A += u^T v + u v^T)}" ; "matrix size" ; 4:3000 -ger ; "{/*1.5 general rank-1 update (A += u v^T)}" ; "matrix size" ; 4:3000 -rot ; "{/*1.5 apply rotation in the plane}" ; "vector size" ; 4:1000000 \ No newline at end of file +matrix_matrix ; "{/*1.5 matrix matrix product}" ; "matrix size" ; 4:5000 +matrix_vector ; "{/*1.5 matrix vector product}" ; "matrix size" ; 4:5000 +trmm ; "{/*1.5 triangular matrix matrix product}" ; "matrix size" ; 4:5000 +trisolve_vector ; "{/*1.5 triangular solver - vector (X = inv(L) X)}" ; "size" ; 4:5000 +trisolve_matrix ; "{/*1.5 triangular solver - matrix (M = inv(L) M)}" ; "size" ; 4:5000 +cholesky ; "{/*1.5 Cholesky decomposition}" ; "matrix size" ; 4:5000 +complete_lu_decomp ; "{/*1.5 Complete LU decomposition}" ; "matrix size" ; 4:5000 +partial_lu_decomp ; "{/*1.5 Partial LU decomposition}" ; "matrix size" ; 4:5000 +tridiagonalization ; "{/*1.5 Tridiagonalization}" ; "matrix size" ; 4:5000 +hessenberg ; "{/*1.5 Hessenberg decomposition}" ; "matrix size" ; 4:5000 +symv ; "{/*1.5 symmetric matrix vector product}" ; "matrix size" ; 4:5000 +syr2 ; "{/*1.5 symmretric rank-2 update (A += u^T v + u v^T)}" ; "matrix size" ; 4:5000 +ger ; "{/*1.5 general rank-1 update (A += u v^T)}" ; "matrix size" ; 4:5000 +rot ; "{/*1.5 apply rotation in the plane}" ; "vector size" ; 4:1000000 diff --git a/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt b/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt index 6844bab28..f023cfe02 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/data/perlib_plot_settings.txt @@ -10,7 +10,7 @@ ublas ; with lines lw 3 lt 1 lc rgbcolor "#00b7ff" mtl4 ; with lines lw 3 lt 1 lc rgbcolor "#d18847" blitz ; with lines lw 3 lt 1 lc rgbcolor "#ff00ff" F77 ; with lines lw 3 lt 3 lc rgbcolor "#e6e64c" -GOTO ; with lines lw 3 lt 3 lc rgbcolor "#C05600" -GOTO2 ; with lines lw 3 lt 1 lc rgbcolor "#C05600" +OPENBLAS ; with lines lw 3 lt 1 lc rgbcolor "#C05600" C ; with lines lw 3 lt 3 lc rgbcolor "#e6bd96" ACML ; with lines lw 2 lt 3 lc rgbcolor "#e6e64c" +blaze ; with lines lw 3 lt 1 lc rgbcolor "#ff00ff" diff --git a/gtsam/3rdparty/Eigen/bench/btl/generic_bench/bench.hh b/gtsam/3rdparty/Eigen/bench/btl/generic_bench/bench.hh index 005c36395..7b7b951b5 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/generic_bench/bench.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/generic_bench/bench.hh @@ -102,8 +102,8 @@ BTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point ) // merge the two data std::vector newSizes; std::vector newFlops; - int i=0; - int j=0; + unsigned int i=0; + unsigned int j=0; while (i config = BtlString(_config).split(" \t\n"); - for (int i = 0; i BTL_DONT_INLINE void init_matrix(Vector & A, int size){ A.resize(size); - for (int row=0; row(A[row],size,row); } } @@ -50,11 +50,11 @@ BTL_DONT_INLINE void init_matrix(Vector & A, int size){ template BTL_DONT_INLINE void init_matrix_symm(Matrix& A, int size){ A.resize(size); - for (int row=0; row @@ -87,6 +87,48 @@ }; // Portable_Timer +#elif defined(__APPLE__) +#include +#include + + +class Portable_Timer +{ + public: + + Portable_Timer() + { + } + + void start() + { + m_start_time = double(mach_absolute_time())*1e-9;; + + } + + void stop() + { + m_stop_time = double(mach_absolute_time())*1e-9;; + + } + + double elapsed() + { + return user_time(); + } + + double user_time() + { + return m_stop_time - m_start_time; + } + + +private: + + double m_stop_time, m_start_time; + +}; // Portable_Timer (Apple) + #else #include @@ -138,7 +180,7 @@ private: int m_clkid; double m_stop_time, m_start_time; -}; // Portable_Timer +}; // Portable_Timer (Linux) #endif diff --git a/gtsam/3rdparty/Eigen/bench/btl/generic_bench/utils/size_lin_log.hh b/gtsam/3rdparty/Eigen/bench/btl/generic_bench/utils/size_lin_log.hh index bca3932ae..bbc9f543d 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/generic_bench/utils/size_lin_log.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/generic_bench/utils/size_lin_log.hh @@ -23,7 +23,7 @@ #include "size_log.hh" template -void size_lin_log(const int nb_point, const int size_min, const int size_max, Vector & X) +void size_lin_log(const int nb_point, const int /*size_min*/, const int size_max, Vector & X) { int ten=10; int nine=9; diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt index de42fe047..0272ccad0 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/CMakeLists.txt @@ -18,27 +18,14 @@ if (MKL_FOUND) endif (MKL_FOUND) -find_package(GOTO2) -if (GOTO2_FOUND) - btl_add_bench(btl_goto2 main.cpp) - if(BUILD_btl_goto2) - target_link_libraries(btl_goto2 ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto2 PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO2") - endif(BUILD_btl_goto2) -endif (GOTO2_FOUND) - -find_package(GOTO) -if (GOTO_FOUND) - if(GOTO2_FOUND) - btl_add_bench(btl_goto main.cpp OFF) - else() - btl_add_bench(btl_goto main.cpp) - endif() - if(BUILD_btl_goto) - target_link_libraries(btl_goto ${GOTO_LIBRARIES} ) - set_target_properties(btl_goto PROPERTIES COMPILE_FLAGS "-DCBLASNAME=GOTO") - endif(BUILD_btl_goto) -endif (GOTO_FOUND) +find_package(OPENBLAS) +if (OPENBLAS_FOUND) + btl_add_bench(btl_openblas main.cpp) + if(BUILD_btl_openblas) + target_link_libraries(btl_openblas ${OPENBLAS_LIBRARIES} ) + set_target_properties(btl_openblas PROPERTIES COMPILE_FLAGS "-DCBLASNAME=OPENBLAS") + endif(BUILD_btl_openblas) +endif (OPENBLAS_FOUND) find_package(ACML) if (ACML_FOUND) diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh index 0e84df038..fc4ba2a1f 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/blas_interface_impl.hh @@ -75,7 +75,6 @@ public : static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ int N2 = N*N; BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); - char uplo = 'L'; int info = 0; int * ipiv = (int*)alloca(sizeof(int)*N); BLAS_FUNC(getrf)(&N, &N, C, &N, ipiv, &info); @@ -92,7 +91,7 @@ public : BLAS_FUNC(trsm)(&right, &lower, ¬rans, &nonunit, &N, &N, &fone, L, &N, X, &N); } - static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){ + static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & /*X*/, int N){ BLAS_FUNC(trmm)(&left, &lower, ¬rans,&nonunit, &N,&N,&fone,A,&N,B,&N); } @@ -101,7 +100,6 @@ public : static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ int N2 = N*N; BLAS_FUNC(copy)(&N2, X, &intone, C, &intone); - char uplo = 'L'; int info = 0; int * ipiv = (int*)alloca(sizeof(int)*N); int * jpiv = (int*)alloca(sizeof(int)*N); @@ -134,8 +132,6 @@ public : } char uplo = 'U'; int info = 0; - int ilo = 1; - int ihi = N; int bsize = 64; int worksize = N*bsize; SCALAR* d = new SCALAR[3*N+worksize]; diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h index 515d8dcfc..de613803b 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/c_interface_base.h @@ -17,12 +17,12 @@ public: typedef real* gene_matrix; typedef real* gene_vector; - static void free_matrix(gene_matrix & A, int N){ - delete A; + static void free_matrix(gene_matrix & A, int /*N*/){ + delete[] A; } static void free_vector(gene_vector & B){ - delete B; + delete[] B; } static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp index 8347c9f0b..564d55ef2 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/BLAS/main.cpp @@ -56,13 +56,13 @@ int main() bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); #ifdef HAS_LAPACK - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); #endif //bench > >(MIN_LU,MAX_LU,NB_POINT); diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh index 93e76bd55..ef4cc9233 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/STL/STL_interface.hh @@ -44,9 +44,9 @@ public : return "STL"; } - static void free_matrix(gene_matrix & A, int N){} + static void free_matrix(gene_matrix & /*A*/, int /*N*/){} - static void free_vector(gene_vector & B){} + static void free_vector(gene_vector & /*B*/){} static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ A = A_stl; diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/CMakeLists.txt new file mode 100644 index 000000000..e99a0855c --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/CMakeLists.txt @@ -0,0 +1,13 @@ + +find_package(BLAZE) +find_package(Boost COMPONENTS system) +if (BLAZE_FOUND AND Boost_FOUND) + include_directories(${BLAZE_INCLUDE_DIR} ${Boost_INCLUDE_DIRS}) + btl_add_bench(btl_blaze main.cpp) + # Note: The newest blaze version requires C++14. + # Ideally, we should set this depending on the version of Blaze we found + set_property(TARGET btl_blaze PROPERTY CXX_STANDARD 14) + if(BUILD_btl_blaze) + target_link_libraries(btl_blaze ${Boost_LIBRARIES}) + endif() +endif () diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/blaze_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/blaze_interface.hh new file mode 100644 index 000000000..ee1523944 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/blaze_interface.hh @@ -0,0 +1,140 @@ +//===================================================== +// Copyright (C) 2008 Gael Guennebaud +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#ifndef BLAZE_INTERFACE_HH +#define BLAZE_INTERFACE_HH + +#include +#include +// using namespace blaze; + +#include + +template +class blaze_interface { + +public : + + typedef real real_type ; + + typedef std::vector stl_vector; + typedef std::vector stl_matrix; + + typedef blaze::DynamicMatrix gene_matrix; + typedef blaze::DynamicVector gene_vector; + + static inline std::string name() { return "blaze"; } + + static void free_matrix(gene_matrix & A, int N){ + return ; + } + + static void free_vector(gene_vector & B){ + return ; + } + + static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ + A.resize(A_stl[0].size(), A_stl.size()); + + for (int j=0; j ipvt(N); +// lu_factor(R, ipvt); +// } + +// static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){ +// X = lower_trisolve(L, B); +// } + + static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){ + cible = source; + } + + static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){ + cible = source; + } + +}; + +#endif diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/main.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/main.cpp new file mode 100644 index 000000000..80e8f4eaa --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/blaze/main.cpp @@ -0,0 +1,40 @@ +//===================================================== +// Copyright (C) 2008 Gael Guennebaud +//===================================================== +// +// This program is free software; you can redistribute it and/or +// modify it under the terms of the GNU General Public License +// as published by the Free Software Foundation; either version 2 +// of the License, or (at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// You should have received a copy of the GNU General Public License +// along with this program; if not, write to the Free Software +// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. +// +#include "utilities.h" +#include "blaze_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + bench > >(MIN_MV,MAX_MV,NB_POINT); + bench > >(MIN_MV,MAX_MV,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_MM,MAX_MM,NB_POINT); + + return 0; +} + + diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh index 47fe58135..1deabdae2 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen2/eigen2_interface.hh @@ -47,7 +47,7 @@ public : { #if defined(EIGEN_VECTORIZE_SSE) if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; - #elif defined(EIGEN_VECTORIZE_ALTIVEC) + #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) if (SIZE==Dynamic) return "eigen2"; else return "tiny_eigen2"; #else if (SIZE==Dynamic) return "eigen2_novec"; else return "tiny_eigen2_novec"; diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh index 31bcc1f93..b821fd721 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/eigen3_interface.hh @@ -45,15 +45,15 @@ public : return EIGEN_MAKESTRING(BTL_PREFIX); } - static void free_matrix(gene_matrix & A, int N) {} + static void free_matrix(gene_matrix & /*A*/, int /*N*/) {} - static void free_vector(gene_vector & B) {} + static void free_vector(gene_vector & /*B*/) {} static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ A.resize(A_stl[0].size(), A_stl.size()); - for (int j=0; j().setZero(); X.template selfadjointView().rankUpdate(A); } - static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){ + static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = A*B; } - static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){ + static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = (A.template selfadjointView() * B); // internal::product_selfadjoint_vector(N,A.data(),N, B.data(), 1, X.data(), 1); } @@ -155,54 +155,54 @@ public : } } - static EIGEN_DONT_INLINE void syr2(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ + static EIGEN_DONT_INLINE void syr2(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){ // internal::product_selfadjoint_rank2_update(N,A.data(),N, X.data(), 1, Y.data(), 1, -1); for(int j=0; j(c,s)); } - static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){ + static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int /*N*/){ X.noalias() = (A.transpose()*B); } - static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){ + static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int /*N*/){ Y += coef * X; } - static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){ + static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int /*N*/){ Y = a*X + b*Y; } - static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){ + static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int /*N*/){ cible = source; } - static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int N){ + static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int /*N*/){ cible = source; } - static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int N){ + static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int /*N*/){ X = L.template triangularView().solve(B); } - static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ + static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){ X = L.template triangularView().solve(B); } - static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){ + static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){ X.noalias() = L.template triangularView() * B; } - static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){ + static inline void cholesky(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = X; internal::llt_inplace::blocked(C); //C = X.llt().matrixL(); @@ -211,11 +211,11 @@ public : // Cholesky::computeInPlaceBlock(C); } - static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = X.fullPivLu().matrixLU(); } - static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ + static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){ Matrix piv(N); DenseIndex nb; C = X; @@ -223,13 +223,13 @@ public : // C = X.partialPivLu().matrixLU(); } - static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ + static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){ typename Tridiagonalization::CoeffVectorType aux(N-1); C = X; internal::tridiagonalization_inplace(C, aux); } - static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){ + static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int /*N*/){ C = HessenbergDecomposition(X).packedMatrix(); } diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_adv.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_adv.cpp index efe5857e4..95865357e 100644 --- a/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_adv.cpp +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/eigen3/main_adv.cpp @@ -29,14 +29,14 @@ BTL_MAIN; int main() { - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); - bench > >(MIN_MM,MAX_MM,NB_POINT); +// bench > >(MIN_LU,MAX_LU,NB_POINT); + bench > >(MIN_LU,MAX_LU,NB_POINT); return 0; } diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/CMakeLists.txt new file mode 100644 index 000000000..09d6d8e43 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/CMakeLists.txt @@ -0,0 +1,44 @@ + + +if((NOT TENSOR_INCLUDE_DIR) AND Eigen_SOURCE_DIR) + # unless TENSOR_INCLUDE_DIR is defined, let's use current Eigen version + set(TENSOR_INCLUDE_DIR ${Eigen_SOURCE_DIR}) + set(TENSOR_FOUND TRUE) +else() + find_package(Tensor) +endif() + +if (TENSOR_FOUND) + + include_directories(${TENSOR_INCLUDE_DIR}) + btl_add_bench(btl_tensor_linear main_linear.cpp) + btl_add_bench(btl_tensor_vecmat main_vecmat.cpp) + btl_add_bench(btl_tensor_matmat main_matmat.cpp) + + btl_add_target_property(btl_tensor_linear COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + btl_add_target_property(btl_tensor_vecmat COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + btl_add_target_property(btl_tensor_matmat COMPILE_FLAGS "-fno-exceptions -DBTL_PREFIX=tensor") + + option(BTL_BENCH_NOGCCVEC "also bench Eigen explicit vec without GCC's auto vec" OFF) + if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC) + btl_add_bench(btl_tensor_nogccvec_linear main_linear.cpp) + btl_add_bench(btl_tensor_nogccvec_vecmat main_vecmat.cpp) + btl_add_bench(btl_tensor_nogccvec_matmat main_matmat.cpp) + + btl_add_target_property(btl_tensor_nogccvec_linear COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + btl_add_target_property(btl_tensor_nogccvec_vecmat COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + btl_add_target_property(btl_tensor_nogccvec_matmat COMPILE_FLAGS "-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec") + endif() + + + if(NOT BTL_NOVEC) + btl_add_bench(btl_tensor_novec_linear main_linear.cpp OFF) + btl_add_bench(btl_tensor_novec_vecmat main_vecmat.cpp OFF) + btl_add_bench(btl_tensor_novec_matmat main_matmat.cpp OFF) + btl_add_target_property(btl_tensor_novec_linear COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + btl_add_target_property(btl_tensor_novec_vecmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + btl_add_target_property(btl_tensor_novec_matmat COMPILE_FLAGS "-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec") + + endif(NOT BTL_NOVEC) + +endif (TENSOR_FOUND) diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_linear.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_linear.cpp new file mode 100644 index 000000000..e257f1e72 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_linear.cpp @@ -0,0 +1,23 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + bench > >(MIN_AXPY,MAX_AXPY,NB_POINT); + + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_matmat.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_matmat.cpp new file mode 100644 index 000000000..675fcfc6d --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_matmat.cpp @@ -0,0 +1,21 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_MM,MAX_MM,NB_POINT); + + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_vecmat.cpp b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_vecmat.cpp new file mode 100644 index 000000000..1af00c81b --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/main_vecmat.cpp @@ -0,0 +1,21 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#include "utilities.h" +#include "tensor_interface.hh" +#include "bench.hh" +#include "basic_actions.hh" + +BTL_MAIN; + +int main() +{ + bench > >(MIN_MV,MAX_MV,NB_POINT); + + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/tensor_interface.hh b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/tensor_interface.hh new file mode 100644 index 000000000..97b8e0f0b --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/btl/libs/tensors/tensor_interface.hh @@ -0,0 +1,105 @@ +//===================================================== +// Copyright (C) 2014 Benoit Steiner +//===================================================== +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// +#ifndef TENSOR_INTERFACE_HH +#define TENSOR_INTERFACE_HH + +#include +#include +#include "btl.hh" + +using namespace Eigen; + +template +class tensor_interface +{ +public : + typedef real real_type; + typedef typename Eigen::Tensor::Index Index; + + typedef std::vector stl_vector; + typedef std::vector stl_matrix; + + typedef Eigen::Tensor gene_matrix; + typedef Eigen::Tensor gene_vector; + + + static inline std::string name( void ) + { + return EIGEN_MAKESTRING(BTL_PREFIX); + } + + static void free_matrix(gene_matrix & /*A*/, int /*N*/) {} + + static void free_vector(gene_vector & /*B*/) {} + + static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){ + A.resize(Eigen::array(A_stl[0].size(), A_stl.size())); + + for (unsigned int j=0; j(i,j)) = A_stl[j][i]; + } + } + } + + static BTL_DONT_INLINE void vector_from_stl(gene_vector & B, stl_vector & B_stl){ + B.resize(B_stl.size()); + + for (unsigned int i=0; i(i,j)); + } + } + } + + static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int /*N*/){ + typedef typename Eigen::Tensor::DimensionPair DimPair; + const Eigen::array dims(DimPair(1, 0)); + X/*.noalias()*/ = A.contract(B, dims); + } + + static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){ + typedef typename Eigen::Tensor::DimensionPair DimPair; + const Eigen::array dims(DimPair(1, 0)); + X/*.noalias()*/ = A.contract(B, dims); + } + + static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int /*N*/){ + Y += X.constant(coef) * X; + } + + static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int /*N*/){ + Y = X.constant(a)*X + Y.constant(b)*Y; + } + + static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int /*N*/){ + cible = source; + } + + static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int /*N*/){ + cible = source; + } +}; + +#endif diff --git a/gtsam/3rdparty/Eigen/bench/dense_solvers.cpp b/gtsam/3rdparty/Eigen/bench/dense_solvers.cpp new file mode 100644 index 000000000..24343dcd8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/dense_solvers.cpp @@ -0,0 +1,186 @@ +#include +#include "BenchTimer.h" +#include +#include +#include +#include +#include +using namespace Eigen; + +std::map > results; +std::vector labels; +std::vector sizes; + +template +EIGEN_DONT_INLINE +void compute_norm_equation(Solver &solver, const MatrixType &A) { + if(A.rows()!=A.cols()) + solver.compute(A.transpose()*A); + else + solver.compute(A); +} + +template +EIGEN_DONT_INLINE +void compute(Solver &solver, const MatrixType &A) { + solver.compute(A); +} + +template +void bench(int id, int rows, int size = Size) +{ + typedef Matrix Mat; + typedef Matrix MatDyn; + typedef Matrix MatSquare; + Mat A(rows,size); + A.setRandom(); + if(rows==size) + A = A*A.adjoint(); + BenchTimer t_llt, t_ldlt, t_lu, t_fplu, t_qr, t_cpqr, t_cod, t_fpqr, t_jsvd, t_bdcsvd; + + int svd_opt = ComputeThinU|ComputeThinV; + + int tries = 5; + int rep = 1000/size; + if(rep==0) rep = 1; +// rep = rep*rep; + + LLT llt(size); + LDLT ldlt(size); + PartialPivLU lu(size); + FullPivLU fplu(size,size); + HouseholderQR qr(A.rows(),A.cols()); + ColPivHouseholderQR cpqr(A.rows(),A.cols()); + CompleteOrthogonalDecomposition cod(A.rows(),A.cols()); + FullPivHouseholderQR fpqr(A.rows(),A.cols()); + JacobiSVD jsvd(A.rows(),A.cols()); + BDCSVD bdcsvd(A.rows(),A.cols()); + + BENCH(t_llt, tries, rep, compute_norm_equation(llt,A)); + BENCH(t_ldlt, tries, rep, compute_norm_equation(ldlt,A)); + BENCH(t_lu, tries, rep, compute_norm_equation(lu,A)); + if(size<=1000) + BENCH(t_fplu, tries, rep, compute_norm_equation(fplu,A)); + BENCH(t_qr, tries, rep, compute(qr,A)); + BENCH(t_cpqr, tries, rep, compute(cpqr,A)); + BENCH(t_cod, tries, rep, compute(cod,A)); + if(size*rows<=10000000) + BENCH(t_fpqr, tries, rep, compute(fpqr,A)); + if(size<500) // JacobiSVD is really too slow for too large matrices + BENCH(t_jsvd, tries, rep, jsvd.compute(A,svd_opt)); +// if(size*rows<=20000000) + BENCH(t_bdcsvd, tries, rep, bdcsvd.compute(A,svd_opt)); + + results["LLT"][id] = t_llt.best(); + results["LDLT"][id] = t_ldlt.best(); + results["PartialPivLU"][id] = t_lu.best(); + results["FullPivLU"][id] = t_fplu.best(); + results["HouseholderQR"][id] = t_qr.best(); + results["ColPivHouseholderQR"][id] = t_cpqr.best(); + results["CompleteOrthogonalDecomposition"][id] = t_cod.best(); + results["FullPivHouseholderQR"][id] = t_fpqr.best(); + results["JacobiSVD"][id] = t_jsvd.best(); + results["BDCSVD"][id] = t_bdcsvd.best(); +} + + +int main() +{ + labels.push_back("LLT"); + labels.push_back("LDLT"); + labels.push_back("PartialPivLU"); + labels.push_back("FullPivLU"); + labels.push_back("HouseholderQR"); + labels.push_back("ColPivHouseholderQR"); + labels.push_back("CompleteOrthogonalDecomposition"); + labels.push_back("FullPivHouseholderQR"); + labels.push_back("JacobiSVD"); + labels.push_back("BDCSVD"); + + for(int i=0; i(k,sizes[k](0),sizes[k](1)); + } + + cout.width(32); + cout << "solver/size"; + cout << " "; + for(int k=0; k=1e6) cout << "-"; + else cout << r(k); + cout << " "; + } + cout << endl; + } + + // HTML output + cout << "" << endl; + cout << "" << endl; + for(int k=0; k" << sizes[k](0) << "x" << sizes[k](1) << ""; + cout << "" << endl; + for(int i=0; i"; + ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f; + for(int k=0; k=1e6) cout << ""; + else + { + cout << ""; + } + } + cout << "" << endl; + } + cout << "
solver/size
" << labels[i] << "-" << r(k); + if(i>0) + cout << " (x" << numext::round(10.f*results[labels[i]](k)/results["LLT"](k))/10.f << ")"; + if(i<4 && sizes[k](0)!=sizes[k](1)) + cout << " *"; + cout << "
" << endl; + +// cout << "LLT (ms) " << (results["LLT"]*1000.).format(fmt) << "\n"; +// cout << "LDLT (%) " << (results["LDLT"]/results["LLT"]).format(fmt) << "\n"; +// cout << "PartialPivLU (%) " << (results["PartialPivLU"]/results["LLT"]).format(fmt) << "\n"; +// cout << "FullPivLU (%) " << (results["FullPivLU"]/results["LLT"]).format(fmt) << "\n"; +// cout << "HouseholderQR (%) " << (results["HouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "ColPivHouseholderQR (%) " << (results["ColPivHouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "CompleteOrthogonalDecomposition (%) " << (results["CompleteOrthogonalDecomposition"]/results["LLT"]).format(fmt) << "\n"; +// cout << "FullPivHouseholderQR (%) " << (results["FullPivHouseholderQR"]/results["LLT"]).format(fmt) << "\n"; +// cout << "JacobiSVD (%) " << (results["JacobiSVD"]/results["LLT"]).format(fmt) << "\n"; +// cout << "BDCSVD (%) " << (results["BDCSVD"]/results["LLT"]).format(fmt) << "\n"; +} diff --git a/gtsam/3rdparty/Eigen/bench/eig33.cpp b/gtsam/3rdparty/Eigen/bench/eig33.cpp index 1608b999d..47947a9be 100644 --- a/gtsam/3rdparty/Eigen/bench/eig33.cpp +++ b/gtsam/3rdparty/Eigen/bench/eig33.cpp @@ -50,7 +50,7 @@ inline void computeRoots(const Matrix& m, Roots& roots) { typedef typename Matrix::Scalar Scalar; const Scalar s_inv3 = 1.0/3.0; - const Scalar s_sqrt3 = internal::sqrt(Scalar(3.0)); + const Scalar s_sqrt3 = std::sqrt(Scalar(3.0)); // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0. The // eigenvalues are the roots to this equation, all guaranteed to be @@ -73,23 +73,13 @@ inline void computeRoots(const Matrix& m, Roots& roots) q = Scalar(0); // Compute the eigenvalues by solving for the roots of the polynomial. - Scalar rho = internal::sqrt(-a_over_3); - Scalar theta = std::atan2(internal::sqrt(-q),half_b)*s_inv3; - Scalar cos_theta = internal::cos(theta); - Scalar sin_theta = internal::sin(theta); - roots(0) = c2_over_3 + Scalar(2)*rho*cos_theta; - roots(1) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); - roots(2) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); - - // Sort in increasing order. - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - if (roots(1) >= roots(2)) - { - std::swap(roots(1),roots(2)); - if (roots(0) >= roots(1)) - std::swap(roots(0),roots(1)); - } + Scalar rho = std::sqrt(-a_over_3); + Scalar theta = std::atan2(std::sqrt(-q),half_b)*s_inv3; + Scalar cos_theta = std::cos(theta); + Scalar sin_theta = std::sin(theta); + roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta; + roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); + roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); } template @@ -99,9 +89,12 @@ void eigen33(const Matrix& mat, Matrix& evecs, Vector& evals) // Scale the matrix so its entries are in [-1,1]. The scaling is applied // only when at least one matrix entry has magnitude larger than 1. - Scalar scale = mat.cwiseAbs()/*.template triangularView()*/.maxCoeff(); + Scalar shift = mat.trace()/3; + Matrix scaledMat = mat; + scaledMat.diagonal().array() -= shift; + Scalar scale = scaledMat.cwiseAbs()/*.template triangularView()*/.maxCoeff(); scale = std::max(scale,Scalar(1)); - Matrix scaledMat = mat / scale; + scaledMat/=scale; // Compute the eigenvalues // scaledMat.setZero(); @@ -166,6 +159,7 @@ void eigen33(const Matrix& mat, Matrix& evecs, Vector& evals) // Rescale back to the original size. evals *= scale; + evals.array()+=shift; } int main() @@ -173,24 +167,29 @@ int main() BenchTimer t; int tries = 10; int rep = 400000; - typedef Matrix3f Mat; - typedef Vector3f Vec; + typedef Matrix3d Mat; + typedef Vector3d Vec; Mat A = Mat::Random(3,3); A = A.adjoint() * A; +// Mat Q = A.householderQr().householderQ(); +// A = Q * Vec(2.2424567,2.2424566,7.454353).asDiagonal() * Q.transpose(); SelfAdjointEigenSolver eig(A); BENCH(t, tries, rep, eig.compute(A)); - std::cout << "Eigen: " << t.best() << "s\n"; + std::cout << "Eigen iterative: " << t.best() << "s\n"; + + BENCH(t, tries, rep, eig.computeDirect(A)); + std::cout << "Eigen direct : " << t.best() << "s\n"; Mat evecs; Vec evals; BENCH(t, tries, rep, eigen33(A,evecs,evals)); std::cout << "Direct: " << t.best() << "s\n\n"; - std::cerr << "Eigenvalue/eigenvector diffs:\n"; - std::cerr << (evals - eig.eigenvalues()).transpose() << "\n"; - for(int k=0;k<3;++k) - if(evecs.col(k).dot(eig.eigenvectors().col(k))<0) - evecs.col(k) = -evecs.col(k); - std::cerr << evecs - eig.eigenvectors() << "\n\n"; +// std::cerr << "Eigenvalue/eigenvector diffs:\n"; +// std::cerr << (evals - eig.eigenvalues()).transpose() << "\n"; +// for(int k=0;k<3;++k) +// if(evecs.col(k).dot(eig.eigenvectors().col(k))<0) +// evecs.col(k) = -evecs.col(k); +// std::cerr << evecs - eig.eigenvectors() << "\n\n"; } diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/changesets.txt b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/changesets.txt new file mode 100644 index 000000000..af8eb9b8f --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/changesets.txt @@ -0,0 +1,61 @@ +#3.0.1 +#3.1.1 +#3.2.0 +3.2.4 +#5745:37f59e65eb6c +5891:d8652709345d # introduce AVX +#5893:24b4dc92c6d3 # merge +5895:997c2ef9fc8b # introduce FMA +#5904:e1eafd14eaa1 # complex and AVX +5908:f8ee3c721251 # improve packing with ptranspose +#5921:ca808bb456b0 # merge +#5927:8b1001f9e3ac +5937:5a4ca1ad8c53 # New gebp kernel handling up to 3 packets x 4 register-level blocks +#5949:f3488f4e45b2 # merge +#5969:e09031dccfd9 # Disable 3pX4 kernel on Altivec +#5992:4a429f5e0483 # merge +before-evaluators +#6334:f6a45e5b8b7c # Implement evaluator for sparse outer products +#6639:c9121c60b5c7 +#6655:06f163b5221f # Properly detect FMA support on ARM +#6677:700e023044e7 # FMA has been wrongly disabled +#6681:11d31dafb0e3 +#6699:5e6e8e10aad1 # merge default to tensors +#6726:ff2d2388e7b9 # merge default to tensors +#6742:0cbd6195e829 # merge default to tensors +#6747:853d2bafeb8f # Generalized the gebp apis +6765:71584fd55762 # Made the blocking computation aware of the l3 cache; Also optimized the blocking parameters to take into account the number of threads used for a computation +#6781:9cc5a931b2c6 # generalized gemv +#6792:f6e1daab600a # ensured that contractions that can be reduced to a matrix vector product +#6844:039efd86b75c # merge tensor +6845:7333ed40c6ef # change prefetching in gebp +#6856:b5be5e10eb7f # merge index conversion +#6893:c3a64aba7c70 # clean blocking size computation +#6898:6fb31ebe6492 # rotating kernel for ARM +6899:877facace746 # rotating kernel for ARM only +#6904:c250623ae9fa # result_of +6921:915f1b1fc158 # fix prefetching change for ARM +6923:9ff25f6dacc6 # prefetching +6933:52572e60b5d3 # blocking size strategy +6937:c8c042f286b2 # avoid redundant pack_rhs +6981:7e5d6f78da59 # dynamic loop swapping +6984:45f26866c091 # rm dynamic loop swapping, adjust lhs's micro panel height to fully exploit L1 cache +6986:a675d05b6f8f # blocking heuristic: block on the rhs in L1 if the lhs fit in L1. +7013:f875e75f07e5 # organize a little our default cache sizes, and use a saner default L1 outside of x86 (10% faster on Nexus 5) +7015:8aad8f35c955 # Refactor computeProductBlockingSizes to make room for the possibility of using lookup tables +7016:a58d253e8c91 # Polish lookup tables generation +7018:9b27294a8186 # actual_panel_rows computation should always be resilient to parameters not consistent with the known L1 cache size, see comment +7019:c758b1e2c073 # Provide a empirical lookup table for blocking sizes measured on a Nexus 5. Only for float, only for Android on ARM 32bit for now. +7085:627e039fba68 # Bug 986: add support for coefficient-based product with 0 depth. +7098:b6f1db9cf9ec # Bug 992: don't select a 3p GEMM path with non-vectorizable scalar types, this hits unsupported paths in symm/triangular products code +7591:09a8e2186610 # 3.3-alpha1 +7650:b0f3c8f43025 # help clang inlining +#8744:74b789ada92a # Improved the matrix multiplication blocking in the case where mr is not a power of 2 (e.g on Haswell CPUs) +8789:efcb912e4356 # Made the index type a template parameter to evaluateProductBlockingSizes. Use numext::mini and numext::maxi instead of std::min/std::max to compute blocking sizes +8972:81d53c711775 # Don't optimize the processing of the last rows of a matrix matrix product in cases that violate the assumptions made by the optimized code path +8985:d935df21a082 # Remove the rotating kernel. +8988:6c2dc56e73b3 # Bug 256: enable vectorization with unaligned loads/stores. +9148:b8b8c421e36c # Relax mixing-type constraints for binary coefficient-wise operators +9174:d228bc282ac9 # merge +9212:c90098affa7b # Fix performance regression introduced in changeset 8aad8f35c955 +9213:9f1c14e4694b # Fix performance regression in dgemm introduced by changeset 81d53c711775 diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm.cpp b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm.cpp new file mode 100644 index 000000000..614bd4737 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm.cpp @@ -0,0 +1,67 @@ +#include +#include +#include +#include +#include "../../BenchTimer.h" +using namespace Eigen; + +#ifndef SCALAR +#error SCALAR must be defined +#endif + +typedef SCALAR Scalar; + +typedef Matrix Mat; + +EIGEN_DONT_INLINE +void gemm(const Mat &A, const Mat &B, Mat &C) +{ + C.noalias() += A * B; +} + +EIGEN_DONT_INLINE +double bench(long m, long n, long k) +{ + Mat A(m,k); + Mat B(k,n); + Mat C(m,n); + A.setRandom(); + B.setRandom(); + C.setZero(); + + BenchTimer t; + + double up = 1e8*4/sizeof(Scalar); + double tm0 = 4, tm1 = 10; + if(NumTraits::IsComplex) + { + up /= 4; + tm0 = 2; + tm1 = 4; + } + + double flops = 2. * m * n * k; + long rep = std::max(1., std::min(100., up/flops) ); + long tries = std::max(tm0, std::min(tm1, up/flops) ); + + BENCH(t, tries, rep, gemm(A,B,C)); + + return 1e-9 * rep * flops / t.best(); +} + +int main(int argc, char **argv) +{ + std::vector results; + + std::ifstream settings("gemm_settings.txt"); + long m, n, k; + while(settings >> m >> n >> k) + { + //std::cerr << " Testing " << m << " " << n << " " << k << std::endl; + results.push_back( bench(m, n, k) ); + } + + std::cout << RowVectorXd::Map(results.data(), results.size()); + + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm_settings.txt b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm_settings.txt new file mode 100644 index 000000000..5c43e1c7d --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/gemm_settings.txt @@ -0,0 +1,15 @@ +8 8 8 +9 9 9 +24 24 24 +239 239 239 +240 240 240 +2400 24 24 +24 2400 24 +24 24 2400 +24 2400 2400 +2400 24 2400 +2400 2400 24 +2400 2400 64 +4800 23 160 +23 4800 160 +2400 2400 2400 diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm.cpp b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm.cpp new file mode 100644 index 000000000..6dc370155 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm.cpp @@ -0,0 +1,98 @@ +#include +#include +#include +#include +#include "../../BenchTimer.h" +using namespace Eigen; + +#ifndef SCALAR +#error SCALAR must be defined +#endif + +typedef SCALAR Scalar; + +template +EIGEN_DONT_INLINE +void lazy_gemm(const MatA &A, const MatB &B, MatC &C) +{ +// escape((void*)A.data()); +// escape((void*)B.data()); + C.noalias() += A.lazyProduct(B); +// escape((void*)C.data()); +} + +template +EIGEN_DONT_INLINE +double bench() +{ + typedef Matrix MatA; + typedef Matrix MatB; + typedef Matrix MatC; + + MatA A(m,k); + MatB B(k,n); + MatC C(m,n); + A.setRandom(); + B.setRandom(); + C.setZero(); + + BenchTimer t; + + double up = 1e7*4/sizeof(Scalar); + double tm0 = 10, tm1 = 20; + + double flops = 2. * m * n * k; + long rep = std::max(10., std::min(10000., up/flops) ); + long tries = std::max(tm0, std::min(tm1, up/flops) ); + + BENCH(t, tries, rep, lazy_gemm(A,B,C)); + + return 1e-9 * rep * flops / t.best(); +} + +template +double bench_t(int t) +{ + if(t) + return bench(); + else + return bench(); +} + +EIGEN_DONT_INLINE +double bench_mnk(int m, int n, int k, int t) +{ + int id = m*10000 + n*100 + k; + switch(id) { + case 10101 : return bench_t< 1, 1, 1>(t); break; + case 20202 : return bench_t< 2, 2, 2>(t); break; + case 30303 : return bench_t< 3, 3, 3>(t); break; + case 40404 : return bench_t< 4, 4, 4>(t); break; + case 50505 : return bench_t< 5, 5, 5>(t); break; + case 60606 : return bench_t< 6, 6, 6>(t); break; + case 70707 : return bench_t< 7, 7, 7>(t); break; + case 80808 : return bench_t< 8, 8, 8>(t); break; + case 90909 : return bench_t< 9, 9, 9>(t); break; + case 101010 : return bench_t<10,10,10>(t); break; + case 111111 : return bench_t<11,11,11>(t); break; + case 121212 : return bench_t<12,12,12>(t); break; + } + return 0; +} + +int main(int argc, char **argv) +{ + std::vector results; + + std::ifstream settings("lazy_gemm_settings.txt"); + long m, n, k, t; + while(settings >> m >> n >> k >> t) + { + //std::cerr << " Testing " << m << " " << n << " " << k << std::endl; + results.push_back( bench_mnk(m, n, k, t) ); + } + + std::cout << RowVectorXd::Map(results.data(), results.size()); + + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm_settings.txt b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm_settings.txt new file mode 100644 index 000000000..407d5d4fa --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/lazy_gemm_settings.txt @@ -0,0 +1,15 @@ +1 1 1 0 +2 2 2 0 +3 3 3 0 +4 4 4 0 +4 4 4 1 +5 5 5 0 +6 6 6 0 +7 7 7 0 +7 7 7 1 +8 8 8 0 +9 9 9 0 +10 10 10 0 +11 11 11 0 +12 12 12 0 +12 12 12 1 diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/make_plot.sh b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/make_plot.sh new file mode 100755 index 000000000..cd3214ac9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/make_plot.sh @@ -0,0 +1,38 @@ +#!/bin/bash + +# base name of the bench +# it reads $1.out +# and generates $1.pdf +WHAT=$1 +bench=$2 + +header="rev " +while read line +do + if [ ! -z '$line' ]; then + header="$header \"$line\"" + fi +done < $bench"_settings.txt" + +echo $header > $WHAT.out.header +cat $WHAT.out >> $WHAT.out.header + + +echo "set title '$WHAT'" > $WHAT.gnuplot +echo "set key autotitle columnhead outside " >> $WHAT.gnuplot +echo "set xtics rotate 1" >> $WHAT.gnuplot + +echo "set term pdf color rounded enhanced fontscale 0.35 size 7in,5in" >> $WHAT.gnuplot +echo set output "'"$WHAT.pdf"'" >> $WHAT.gnuplot + +col=`cat $bench"_settings.txt" | wc -l` +echo "plot for [col=2:$col+1] '$WHAT.out.header' using 0:col:xticlabels(1) with lines" >> $WHAT.gnuplot +echo " " >> $WHAT.gnuplot + +gnuplot -persist < $WHAT.gnuplot + +# generate a png file +# convert -background white -density 120 -rotate 90 -resize 800 +dither -colors 256 -quality 0 $WHAT.ps -background white -flatten .$WHAT.png + +# clean +rm $WHAT.out.header $WHAT.gnuplot \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/run.sh b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/run.sh new file mode 100755 index 000000000..9d6ee40bc --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/perf_monitoring/gemm/run.sh @@ -0,0 +1,156 @@ +#!/bin/bash + +# ./run.sh gemm +# ./run.sh lazy_gemm + +# Examples of environment variables to be set: +# PREFIX="haswell-fma-" +# CXX_FLAGS="-mfma" + +# Options: +# -up : enforce the recomputation of existing data, and keep best results as a merging strategy +# -s : recompute selected changesets only and keep bests + +bench=$1 + +if echo "$*" | grep '\-up' > /dev/null; then + update=true +else + update=false +fi + +if echo "$*" | grep '\-s' > /dev/null; then + selected=true +else + selected=false +fi + +global_args="$*" + +if [ $selected == true ]; then + echo "Recompute selected changesets only and keep bests" +elif [ $update == true ]; then + echo "(Re-)Compute all changesets and keep bests" +else + echo "Skip previously computed changesets" +fi + + + +if [ ! -d "eigen_src" ]; then + hg clone https://bitbucket.org/eigen/eigen eigen_src +else + cd eigen_src + hg pull -u + cd .. +fi + +if [ ! -z '$CXX' ]; then + CXX=g++ +fi + +function make_backup +{ + if [ -f "$1.out" ]; then + mv "$1.out" "$1.backup" + fi +} + +function merge +{ + count1=`echo $1 | wc -w` + count2=`echo $2 | wc -w` + + if [ $count1 == $count2 ]; then + a=( $1 ); b=( $2 ) + res="" + for (( i=0 ; i<$count1 ; i++ )); do + ai=${a[$i]}; bi=${b[$i]} + tmp=`echo "if ($ai > $bi) $ai else $bi " | bc -l` + res="$res $tmp" + done + echo $res + + else + echo $1 + fi +} + +function test_current +{ + rev=$1 + scalar=$2 + name=$3 + + prev="" + if [ -e "$name.backup" ]; then + prev=`grep $rev "$name.backup" | cut -c 14-` + fi + res=$prev + count_rev=`echo $prev | wc -w` + count_ref=`cat $bench"_settings.txt" | wc -l` + if echo "$global_args" | grep "$rev" > /dev/null; then + rev_found=true + else + rev_found=false + fi +# echo $update et $selected et $rev_found because $rev et "$global_args" +# echo $count_rev et $count_ref + if [ $update == true ] || [ $count_rev != $count_ref ] || ([ $selected == true ] && [ $rev_found == true ]); then + if $CXX -O2 -DNDEBUG -march=native $CXX_FLAGS -I eigen_src $bench.cpp -DSCALAR=$scalar -o $name; then + curr=`./$name` + if [ $count_rev == $count_ref ]; then + echo "merge previous $prev" + echo "with new $curr" + else + echo "got $curr" + fi + res=`merge "$curr" "$prev"` +# echo $res + echo "$rev $res" >> $name.out + else + echo "Compilation failed, skip rev $rev" + fi + else + echo "Skip existing results for $rev / $name" + echo "$rev $res" >> $name.out + fi +} + +make_backup $PREFIX"s"$bench +make_backup $PREFIX"d"$bench +make_backup $PREFIX"c"$bench + +cut -f1 -d"#" < changesets.txt | grep -E '[[:alnum:]]' | while read rev +do + if [ ! -z '$rev' ]; then + echo "Testing rev $rev" + cd eigen_src + hg up -C $rev > /dev/null + actual_rev=`hg identify | cut -f1 -d' '` + cd .. + + test_current $actual_rev float $PREFIX"s"$bench + test_current $actual_rev double $PREFIX"d"$bench + test_current $actual_rev "std::complex" $PREFIX"c"$bench + fi + +done + +echo "Float:" +cat $PREFIX"s""$bench.out" +echo " " + +echo "Double:" +cat $PREFIX"d""$bench.out" +echo "" + +echo "Complex:" +cat $PREFIX"c""$bench.out" +echo "" + +./make_plot.sh $PREFIX"s"$bench $bench +./make_plot.sh $PREFIX"d"$bench $bench +./make_plot.sh $PREFIX"c"$bench $bench + + diff --git a/gtsam/3rdparty/Eigen/bench/spbench/CMakeLists.txt b/gtsam/3rdparty/Eigen/bench/spbench/CMakeLists.txt index 6e0e1b103..932735698 100644 --- a/gtsam/3rdparty/Eigen/bench/spbench/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/bench/spbench/CMakeLists.txt @@ -29,7 +29,7 @@ if(UMFPACK_FOUND AND BLAS_FOUND) set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) endif() -find_package(SuperLU) +find_package(SuperLU 4.0) if(SUPERLU_FOUND AND BLAS_FOUND) add_definitions("-DEIGEN_SUPERLU_SUPPORT") include_directories(${SUPERLU_INCLUDES}) @@ -38,25 +38,32 @@ if(SUPERLU_FOUND AND BLAS_FOUND) endif() -find_package(Pastix) -find_package(Scotch) -find_package(Metis) -if(PASTIX_FOUND AND BLAS_FOUND) +find_package(PASTIX QUIET COMPONENTS METIS SCOTCH) +# check that the PASTIX found is a version without MPI +find_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS + NAMES pastix_nompi.h + HINTS ${PASTIX_INCLUDE_DIRS} +) +if (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS) + message(STATUS "A version of Pastix has been found but pastix_nompi.h does not exist in the include directory." + " Because Eigen tests require a version without MPI, we disable the Pastix backend.") +endif() +if(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS AND BLAS_FOUND) add_definitions("-DEIGEN_PASTIX_SUPPORT") - include_directories(${PASTIX_INCLUDES}) + include_directories(${PASTIX_INCLUDE_DIRS_DEP}) if(SCOTCH_FOUND) - include_directories(${SCOTCH_INCLUDES}) + include_directories(${SCOTCH_INCLUDE_DIRS}) set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES}) elseif(METIS_FOUND) - include_directories(${METIS_INCLUDES}) + include_directories(${METIS_INCLUDE_DIRS}) set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES}) endif(SCOTCH_FOUND) - set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES} ${ORDERING_LIBRARIES} ${BLAS_LIBRARIES}) - set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES}) + set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP}) endif(PASTIX_FOUND AND BLAS_FOUND) if(METIS_FOUND) - include_directories(${METIS_INCLUDES}) + include_directories(${METIS_INCLUDE_DIRS}) set (SPARSE_LIBS ${SPARSE_LIBS} ${METIS_LIBRARIES}) add_definitions("-DEIGEN_METIS_SUPPORT") endif(METIS_FOUND) diff --git a/gtsam/3rdparty/Eigen/bench/spbench/spbenchstyle.h b/gtsam/3rdparty/Eigen/bench/spbench/spbenchstyle.h index 17a05ce71..f6a981778 100644 --- a/gtsam/3rdparty/Eigen/bench/spbench/spbenchstyle.h +++ b/gtsam/3rdparty/Eigen/bench/spbench/spbenchstyle.h @@ -91,4 +91,5 @@ void printBenchStyle(std::ofstream& out) \n\n"; } -#endif \ No newline at end of file + +#endif diff --git a/gtsam/3rdparty/Eigen/bench/tensors/README b/gtsam/3rdparty/Eigen/bench/tensors/README new file mode 100644 index 000000000..3a5fdbe17 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/README @@ -0,0 +1,21 @@ +The tensor benchmark suite is made of several parts. + +The first part is a generic suite, in which each benchmark comes in 2 flavors: one that runs on CPU, and one that runs on GPU. + +To compile the floating point CPU benchmarks, simply call: +g++ tensor_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu + +To compile the floating point GPU benchmarks, simply call: +nvcc tensor_benchmarks_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_35 -o benchmarks_gpu + +We also provide a version of the generic GPU tensor benchmarks that uses half floats (aka fp16) instead of regular floats. To compile these benchmarks, simply call the command line below. You'll need a recent GPU that supports compute capability 5.3 or higher to run them and nvcc 7.5 or higher to compile the code. +nvcc tensor_benchmarks_fp16_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_53 -o benchmarks_fp16_gpu + +last but not least, we also provide a suite of benchmarks to measure the scalability of the contraction code on CPU. To compile these benchmarks, call +g++ contraction_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu + +To compile the benchmark for SYCL, using ComputeCpp you currently need 2 passes (only for translation units containing device code): +1. The device compilation pass that generates the device code (SYCL kernels and referenced device functions) and glue code needed by the host compiler to reference the device code from host code. +{ComputeCpp_ROOT}/bin/compute++ -I ../../ -I {ComputeCpp_ROOT}/include/ -std=c++11 -mllvm -inline-threshold=1000 -Wno-ignored-attributes -sycl -intelspirmetadata -emit-llvm -no-serial-memop -sycl-compress-name -DBUILD_PLATFORM_SPIR -DNDBUG -O3 -c tensor_benchmarks_sycl.cc +2. The host compilation pass that generates the final host binary. +clang++-3.7 -include tensor_benchmarks_sycl.sycl benchmark_main.cc tensor_benchmarks_sycl.cc -pthread -I ../../ -I {ComputeCpp_ROOT}/include/ -L {ComputeCpp_ROOT}/lib/ -lComputeCpp -lOpenCL -D_GLIBCXX_USE_CXX11_ABI=0 -std=c++11 -o tensor_benchmark_sycl diff --git a/gtsam/3rdparty/Eigen/bench/tensors/benchmark.h b/gtsam/3rdparty/Eigen/bench/tensors/benchmark.h new file mode 100644 index 000000000..f115b54ad --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/benchmark.h @@ -0,0 +1,49 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include +#include +#include + +namespace testing { +class Benchmark { + public: + Benchmark(const char* name, void (*fn)(int)) { + Register(name, fn, NULL); + } + Benchmark(const char* name, void (*fn_range)(int, int)) { + Register(name, NULL, fn_range); + } + Benchmark* Arg(int x); + Benchmark* Range(int lo, int hi); + const char* Name(); + bool ShouldRun(int argc, char* argv[]); + void Run(); + private: + const char* name_; + void (*fn_)(int); + void (*fn_range_)(int, int); + std::vector args_; + void Register(const char* name, void (*fn)(int), void (*fn_range)(int, int)); + void RunRepeatedlyWithArg(int iterations, int arg); + void RunWithArg(int arg); +}; +} // namespace testing +void SetBenchmarkFlopsProcessed(int64_t); +void StopBenchmarkTiming(); +void StartBenchmarkTiming(); +#define BENCHMARK(f) \ + static ::testing::Benchmark* _benchmark_##f __attribute__((unused)) = \ + (new ::testing::Benchmark(#f, f)) diff --git a/gtsam/3rdparty/Eigen/bench/tensors/benchmark_main.cc b/gtsam/3rdparty/Eigen/bench/tensors/benchmark_main.cc new file mode 100644 index 000000000..1efa0dbad --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/benchmark_main.cc @@ -0,0 +1,237 @@ +/* + * Copyright (C) 2012 The Android Open Source Project + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "benchmark.h" +#include +#include +#include +#include +#include +#include +#include +#include + +static int64_t g_flops_processed; +static int64_t g_benchmark_total_time_ns; +static int64_t g_benchmark_start_time_ns; +typedef std::map BenchmarkMap; +typedef BenchmarkMap::iterator BenchmarkMapIt; + +BenchmarkMap& gBenchmarks() { + static BenchmarkMap g_benchmarks; + return g_benchmarks; +} + +static int g_name_column_width = 20; + +static int Round(int n) { + int base = 1; + while (base*10 < n) { + base *= 10; + } + if (n < 2*base) { + return 2*base; + } + if (n < 5*base) { + return 5*base; + } + return 10*base; +} + +#ifdef __APPLE__ + #include + static mach_timebase_info_data_t g_time_info; + static void __attribute__((constructor)) init_info() { + mach_timebase_info(&g_time_info); + } +#endif + +static int64_t NanoTime() { +#if defined(__APPLE__) + uint64_t t = mach_absolute_time(); + return t * g_time_info.numer / g_time_info.denom; +#else + struct timespec t; + t.tv_sec = t.tv_nsec = 0; + clock_gettime(CLOCK_MONOTONIC, &t); + return static_cast(t.tv_sec) * 1000000000LL + t.tv_nsec; +#endif +} + +namespace testing { +Benchmark* Benchmark::Arg(int arg) { + args_.push_back(arg); + return this; +} + +Benchmark* Benchmark::Range(int lo, int hi) { + const int kRangeMultiplier = 8; + if (hi < lo) { + int temp = hi; + hi = lo; + lo = temp; + } + while (lo < hi) { + args_.push_back(lo); + lo *= kRangeMultiplier; + } + // We always run the hi number. + args_.push_back(hi); + return this; +} + +const char* Benchmark::Name() { + return name_; +} +bool Benchmark::ShouldRun(int argc, char* argv[]) { + if (argc == 1) { + return true; // With no arguments, we run all benchmarks. + } + // Otherwise, we interpret each argument as a regular expression and + // see if any of our benchmarks match. + for (int i = 1; i < argc; i++) { + regex_t re; + if (regcomp(&re, argv[i], 0) != 0) { + fprintf(stderr, "couldn't compile \"%s\" as a regular expression!\n", argv[i]); + exit(EXIT_FAILURE); + } + int match = regexec(&re, name_, 0, NULL, 0); + regfree(&re); + if (match != REG_NOMATCH) { + return true; + } + } + return false; +} +void Benchmark::Register(const char* name, void (*fn)(int), void (*fn_range)(int, int)) { + name_ = name; + fn_ = fn; + fn_range_ = fn_range; + if (fn_ == NULL && fn_range_ == NULL) { + fprintf(stderr, "%s: missing function\n", name_); + exit(EXIT_FAILURE); + } + gBenchmarks().insert(std::make_pair(name, this)); +} +void Benchmark::Run() { + if (fn_ != NULL) { + RunWithArg(0); + } else { + if (args_.empty()) { + fprintf(stderr, "%s: no args!\n", name_); + exit(EXIT_FAILURE); + } + for (size_t i = 0; i < args_.size(); ++i) { + RunWithArg(args_[i]); + } + } +} +void Benchmark::RunRepeatedlyWithArg(int iterations, int arg) { + g_flops_processed = 0; + g_benchmark_total_time_ns = 0; + g_benchmark_start_time_ns = NanoTime(); + if (fn_ != NULL) { + fn_(iterations); + } else { + fn_range_(iterations, arg); + } + if (g_benchmark_start_time_ns != 0) { + g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns; + } +} +void Benchmark::RunWithArg(int arg) { + // run once in case it's expensive + int iterations = 1; + RunRepeatedlyWithArg(iterations, arg); + while (g_benchmark_total_time_ns < 1e9 && iterations < 1e9) { + int last = iterations; + if (g_benchmark_total_time_ns/iterations == 0) { + iterations = 1e9; + } else { + iterations = 1e9 / (g_benchmark_total_time_ns/iterations); + } + iterations = std::max(last + 1, std::min(iterations + iterations/2, 100*last)); + iterations = Round(iterations); + RunRepeatedlyWithArg(iterations, arg); + } + char throughput[100]; + throughput[0] = '\0'; + if (g_benchmark_total_time_ns > 0 && g_flops_processed > 0) { + double mflops_processed = static_cast(g_flops_processed)/1e6; + double seconds = static_cast(g_benchmark_total_time_ns)/1e9; + snprintf(throughput, sizeof(throughput), " %8.2f MFlops/s", mflops_processed/seconds); + } + char full_name[100]; + if (fn_range_ != NULL) { + if (arg >= (1<<20)) { + snprintf(full_name, sizeof(full_name), "%s/%dM", name_, arg/(1<<20)); + } else if (arg >= (1<<10)) { + snprintf(full_name, sizeof(full_name), "%s/%dK", name_, arg/(1<<10)); + } else { + snprintf(full_name, sizeof(full_name), "%s/%d", name_, arg); + } + } else { + snprintf(full_name, sizeof(full_name), "%s", name_); + } + printf("%-*s %10d %10" PRId64 "%s\n", g_name_column_width, full_name, + iterations, g_benchmark_total_time_ns/iterations, throughput); + fflush(stdout); +} +} // namespace testing +void SetBenchmarkFlopsProcessed(int64_t x) { + g_flops_processed = x; +} +void StopBenchmarkTiming() { + if (g_benchmark_start_time_ns != 0) { + g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns; + } + g_benchmark_start_time_ns = 0; +} +void StartBenchmarkTiming() { + if (g_benchmark_start_time_ns == 0) { + g_benchmark_start_time_ns = NanoTime(); + } +} +int main(int argc, char* argv[]) { + if (gBenchmarks().empty()) { + fprintf(stderr, "No benchmarks registered!\n"); + exit(EXIT_FAILURE); + } + for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) { + int name_width = static_cast(strlen(it->second->Name())); + g_name_column_width = std::max(g_name_column_width, name_width); + } + bool need_header = true; + for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) { + ::testing::Benchmark* b = it->second; + if (b->ShouldRun(argc, argv)) { + if (need_header) { + printf("%-*s %10s %10s\n", g_name_column_width, "", "iterations", "ns/op"); + fflush(stdout); + need_header = false; + } + b->Run(); + } + } + if (need_header) { + fprintf(stderr, "No matching benchmarks!\n"); + fprintf(stderr, "Available benchmarks:\n"); + for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) { + fprintf(stderr, " %s\n", it->second->Name()); + } + exit(EXIT_FAILURE); + } + return 0; +} diff --git a/gtsam/3rdparty/Eigen/bench/tensors/contraction_benchmarks_cpu.cc b/gtsam/3rdparty/Eigen/bench/tensors/contraction_benchmarks_cpu.cc new file mode 100644 index 000000000..f9e57ad47 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/contraction_benchmarks_cpu.cc @@ -0,0 +1,39 @@ +#define EIGEN_USE_THREADS + +#include + +#include "tensor_benchmarks.h" + +#define CREATE_THREAD_POOL(threads) \ +Eigen::ThreadPool pool(threads); \ +Eigen::ThreadPoolDevice device(&pool, threads); + + +// Contractions for number of threads ranging from 1 to 32 +// Dimensions are Rows, Cols, Depth +#define BM_ContractionCPU(D1, D2, D3) \ + static void BM_##Contraction##_##D1##x##D2##x##D3(int iters, int Threads) { \ + StopBenchmarkTiming(); \ + CREATE_THREAD_POOL(Threads); \ + BenchmarkSuite suite(device, D1, D2, D3); \ + suite.contraction(iters); \ + } \ + BENCHMARK_RANGE(BM_##Contraction##_##D1##x##D2##x##D3, 1, 32); + + +// Vector Matrix and Matrix Vector products +BM_ContractionCPU(1, 2000, 500); +BM_ContractionCPU(2000, 1, 500); + +// Various skinny matrices +BM_ContractionCPU(250, 3, 512); +BM_ContractionCPU(1500, 3, 512); + +BM_ContractionCPU(512, 800, 4); +BM_ContractionCPU(512, 80, 800); +BM_ContractionCPU(512, 80, 13522); +BM_ContractionCPU(1, 80, 13522); + +BM_ContractionCPU(3200, 512, 4); +BM_ContractionCPU(3200, 512, 80); +BM_ContractionCPU(3200, 80, 512); diff --git a/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks.h b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks.h new file mode 100644 index 000000000..c2fb3dede --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks.h @@ -0,0 +1,478 @@ +#ifndef THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_ +#define THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_ + +typedef int TensorIndex; +#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int + +#include "unsupported/Eigen/CXX11/Tensor" +#include "benchmark.h" + +#define BENCHMARK_RANGE(bench, lo, hi) \ + BENCHMARK(bench)->Range(lo, hi) + +using Eigen::Tensor; +using Eigen::TensorMap; + +// TODO(bsteiner): also templatize on the input type since we have users +// for int8 as well as floats. +template class BenchmarkSuite { + public: + BenchmarkSuite(const Device& device, size_t m, size_t k, size_t n) + : m_(m), k_(k), n_(n), device_(device) { + initialize(); + } + + BenchmarkSuite(const Device& device, size_t m) + : m_(m), k_(m), n_(m), device_(device) { + initialize(); + } + + ~BenchmarkSuite() { + device_.deallocate(a_); + device_.deallocate(b_); + device_.deallocate(c_); + } + + void memcpy(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + device_.memcpy(c_, a_, m_ * m_ * sizeof(T)); + } + // Record the number of values copied per second + finalizeBenchmark(static_cast(m_) * m_ * num_iters); + } + + void typeCasting(int num_iters) { + eigen_assert(m_ == n_); + Eigen::array sizes; + if (sizeof(T) >= sizeof(int)) { + sizes[0] = m_; + sizes[1] = k_; + } else { + sizes[0] = m_ * sizeof(T) / sizeof(int); + sizes[1] = k_ * sizeof(T) / sizeof(int); + } + const TensorMap, Eigen::Aligned> A((int*)a_, sizes); + TensorMap, Eigen::Aligned> B(b_, sizes); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + B.device(device_) = A.template cast(); + } + // Record the number of values copied per second + finalizeBenchmark(static_cast(m_) * k_ * num_iters); + } + + void random(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + Eigen::array sizes; + sizes[0] = m_; + sizes[1] = m_; + TensorMap, Eigen::Aligned> C(c_, sizes); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = C.random(); + } + // Record the number of random numbers generated per second + finalizeBenchmark(static_cast(m_) * m_ * num_iters); + } + + void slicing(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + Eigen::array sizes; + sizes[0] = m_; + sizes[1] = m_; + const TensorMap, Eigen::Aligned> A(a_, sizes); + const TensorMap, Eigen::Aligned> B(b_, sizes); + TensorMap, Eigen::Aligned> C(c_, sizes); + + const Eigen::DSizes quarter_sizes(m_/2, m_/2); + const Eigen::DSizes first_quadrant(0, 0); + const Eigen::DSizes second_quadrant(0, m_/2); + const Eigen::DSizes third_quadrant(m_/2, 0); + const Eigen::DSizes fourth_quadrant(m_/2, m_/2); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.slice(first_quadrant, quarter_sizes).device(device_) = + A.slice(first_quadrant, quarter_sizes); + C.slice(second_quadrant, quarter_sizes).device(device_) = + B.slice(second_quadrant, quarter_sizes); + C.slice(third_quadrant, quarter_sizes).device(device_) = + A.slice(third_quadrant, quarter_sizes); + C.slice(fourth_quadrant, quarter_sizes).device(device_) = + B.slice(fourth_quadrant, quarter_sizes); + } + // Record the number of values copied from the rhs slice to the lhs slice + // each second + finalizeBenchmark(static_cast(m_) * m_ * num_iters); + } + + void rowChip(int num_iters) { + Eigen::array input_size; + input_size[0] = k_; + input_size[1] = n_; + const TensorMap, Eigen::Aligned> B(b_, input_size); + Eigen::array output_size; + output_size[0] = n_; + TensorMap, Eigen::Aligned> C(c_, output_size); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = B.chip(iter % k_, 0); + } + // Record the number of values copied from the rhs chip to the lhs. + finalizeBenchmark(static_cast(n_) * num_iters); + } + + void colChip(int num_iters) { + Eigen::array input_size; + input_size[0] = k_; + input_size[1] = n_; + const TensorMap, Eigen::Aligned> B(b_, input_size); + Eigen::array output_size; + output_size[0] = n_; + TensorMap, Eigen::Aligned> C(c_, output_size); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = B.chip(iter % n_, 1); + } + // Record the number of values copied from the rhs chip to the lhs. + finalizeBenchmark(static_cast(n_) * num_iters); + } + + void shuffling(int num_iters) { + eigen_assert(m_ == n_); + Eigen::array size_a; + size_a[0] = m_; + size_a[1] = k_; + const TensorMap, Eigen::Aligned> A(a_, size_a); + Eigen::array size_b; + size_b[0] = k_; + size_b[1] = m_; + TensorMap, Eigen::Aligned> B(b_, size_b); + + Eigen::array shuffle; + shuffle[0] = 1; + shuffle[1] = 0; + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + B.device(device_) = A.shuffle(shuffle); + } + // Record the number of values shuffled from A and copied to B each second + finalizeBenchmark(static_cast(m_) * k_ * num_iters); + } + + void padding(int num_iters) { + eigen_assert(m_ == k_); + Eigen::array size_a; + size_a[0] = m_; + size_a[1] = k_-3; + const TensorMap, Eigen::Aligned> A(a_, size_a); + Eigen::array size_b; + size_b[0] = k_; + size_b[1] = m_; + TensorMap, Eigen::Aligned> B(b_, size_b); + +#if defined(EIGEN_HAS_INDEX_LIST) + Eigen::IndexPairList, + Eigen::type2indexpair<2, 1> > paddings; +#else + Eigen::array, 2> paddings; + paddings[0] = Eigen::IndexPair(0, 0); + paddings[1] = Eigen::IndexPair(2, 1); +#endif + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + B.device(device_) = A.pad(paddings); + } + // Record the number of values copied from the padded tensor A each second + finalizeBenchmark(static_cast(m_) * k_ * num_iters); + } + + void striding(int num_iters) { + eigen_assert(m_ == k_); + Eigen::array size_a; + size_a[0] = m_; + size_a[1] = k_; + const TensorMap, Eigen::Aligned> A(a_, size_a); + Eigen::array size_b; + size_b[0] = m_; + size_b[1] = k_/2; + TensorMap, Eigen::Aligned> B(b_, size_b); + +#ifndef EIGEN_HAS_INDEX_LIST + Eigen::array strides; + strides[0] = 1; + strides[1] = 2; +#else + // Take advantage of cxx11 to give the compiler information it can use to + // optimize the code. + Eigen::IndexList, Eigen::type2index<2> > strides; +#endif + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + B.device(device_) = A.stride(strides); + } + // Record the number of values copied from the padded tensor A each second + finalizeBenchmark(static_cast(m_) * k_ * num_iters); + } + + void broadcasting(int num_iters) { + Eigen::array size_a; + size_a[0] = m_; + size_a[1] = 1; + const TensorMap, Eigen::Aligned> A(a_, size_a); + Eigen::array size_c; + size_c[0] = m_; + size_c[1] = n_; + TensorMap, Eigen::Aligned> C(c_, size_c); + +#ifndef EIGEN_HAS_INDEX_LIST + Eigen::array broadcast; + broadcast[0] = 1; + broadcast[1] = n_; +#else + // Take advantage of cxx11 to give the compiler information it can use to + // optimize the code. + Eigen::IndexList, int> broadcast; + broadcast.set(1, n_); +#endif + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A.broadcast(broadcast); + } + // Record the number of values broadcasted from A and copied to C each second + finalizeBenchmark(static_cast(m_) * n_ * num_iters); + } + + void coeffWiseOp(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + Eigen::array sizes; + sizes[0] = m_; + sizes[1] = m_; + const TensorMap, Eigen::Aligned> A(a_, sizes); + const TensorMap, Eigen::Aligned> B(b_, sizes); + TensorMap, Eigen::Aligned> C(c_, sizes); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A * A.constant(static_cast(3.14)) + B * B.constant(static_cast(2.7)); + } + // Record the number of FLOP executed per second (2 multiplications and + // 1 addition per value) + finalizeBenchmark(static_cast(3) * m_ * m_ * num_iters); + } + + void algebraicFunc(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + Eigen::array sizes; + sizes[0] = m_; + sizes[1] = m_; + const TensorMap, Eigen::Aligned> A(a_, sizes); + const TensorMap, Eigen::Aligned> B(b_, sizes); + TensorMap, Eigen::Aligned> C(c_, sizes); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A.rsqrt() + B.sqrt() * B.square(); + } + // Record the number of FLOP executed per second (assuming one operation + // per value) + finalizeBenchmark(static_cast(m_) * m_ * num_iters); + } + + void transcendentalFunc(int num_iters) { + eigen_assert(m_ == k_ && k_ == n_); + Eigen::array sizes; + sizes[0] = m_; + sizes[1] = m_; + const TensorMap, Eigen::Aligned> A(a_, sizes); + const TensorMap, Eigen::Aligned> B(b_, sizes); + TensorMap, Eigen::Aligned> C(c_, sizes); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A.exp() + B.log(); + } + // Record the number of FLOP executed per second (assuming one operation + // per value) + finalizeBenchmark(static_cast(m_) * m_ * num_iters); + } + + // Row reduction + void rowReduction(int num_iters) { + Eigen::array input_size; + input_size[0] = k_; + input_size[1] = n_; + const TensorMap, Eigen::Aligned> B(b_, input_size); + Eigen::array output_size; + output_size[0] = n_; + TensorMap, Eigen::Aligned> C(c_, output_size); + +#ifndef EIGEN_HAS_INDEX_LIST + Eigen::array sum_along_dim; + sum_along_dim[0] = 0; +#else + // Take advantage of cxx11 to give the compiler information it can use to + // optimize the code. + Eigen::IndexList> sum_along_dim; +#endif + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = B.sum(sum_along_dim); + } + // Record the number of FLOP executed per second (assuming one operation + // per value) + finalizeBenchmark(static_cast(k_) * n_ * num_iters); + } + + // Column reduction + void colReduction(int num_iters) { + Eigen::array input_size; + input_size[0] = k_; + input_size[1] = n_; + const TensorMap, Eigen::Aligned> B( + b_, input_size); + Eigen::array output_size; + output_size[0] = k_; + TensorMap, Eigen::Aligned> C( + c_, output_size); + +#ifndef EIGEN_HAS_INDEX_LIST + Eigen::array sum_along_dim; + sum_along_dim[0] = 1; +#else + // Take advantage of cxx11 to give the compiler information it can use to + // optimize the code. + Eigen::IndexList> sum_along_dim; +#endif + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = B.sum(sum_along_dim); + } + // Record the number of FLOP executed per second (assuming one operation + // per value) + finalizeBenchmark(static_cast(k_) * n_ * num_iters); + } + + // Full reduction + void fullReduction(int num_iters) { + Eigen::array input_size; + input_size[0] = k_; + input_size[1] = n_; + const TensorMap, Eigen::Aligned> B( + b_, input_size); + Eigen::array output_size; + TensorMap, Eigen::Aligned> C( + c_, output_size); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = B.sum(); + } + // Record the number of FLOP executed per second (assuming one operation + // per value) + finalizeBenchmark(static_cast(k_) * n_ * num_iters); + } + + // do a contraction which is equivalent to a matrix multiplication + void contraction(int num_iters) { + Eigen::array sizeA; + sizeA[0] = m_; + sizeA[1] = k_; + Eigen::array sizeB; + sizeB[0] = k_; + sizeB[1] = n_; + Eigen::array sizeC; + sizeC[0] = m_; + sizeC[1] = n_; + + const TensorMap, Eigen::Aligned> A(a_, sizeA); + const TensorMap, Eigen::Aligned> B(b_, sizeB); + TensorMap, Eigen::Aligned> C(c_, sizeC); + + typedef typename Tensor::DimensionPair DimPair; + Eigen::array dims; + dims[0] = DimPair(1, 0); + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A.contract(B, dims); + } + // Record the number of FLOP executed per second (size_ multiplications and + // additions for each value in the resulting tensor) + finalizeBenchmark(static_cast(2) * m_ * n_ * k_ * num_iters); + } + + void convolution(int num_iters, int kernel_x, int kernel_y) { + Eigen::array input_sizes; + input_sizes[0] = m_; + input_sizes[1] = n_; + TensorMap, Eigen::Aligned> A(a_, input_sizes); + Eigen::array kernel_sizes; + kernel_sizes[0] = kernel_x; + kernel_sizes[1] = kernel_y; + TensorMap, Eigen::Aligned> B(b_, kernel_sizes); + Eigen::array result_sizes; + result_sizes[0] = m_ - kernel_x + 1; + result_sizes[1] = n_ - kernel_y + 1; + TensorMap, Eigen::Aligned> C(c_, result_sizes); + Eigen::array dims; + dims[0] = 0; + dims[1] = 1; + + StartBenchmarkTiming(); + for (int iter = 0; iter < num_iters; ++iter) { + C.device(device_) = A.convolve(B, dims); + } + // Record the number of FLOP executed per second (kernel_size + // multiplications and additions for each value in the resulting tensor) + finalizeBenchmark(static_cast(2) * + (m_ - kernel_x + 1) * (n_ - kernel_y + 1) * kernel_x * kernel_y * num_iters); + } + + private: + void initialize() { + a_ = (T *) device_.allocate(m_ * k_ * sizeof(T)); + b_ = (T *) device_.allocate(k_ * n_ * sizeof(T)); + c_ = (T *) device_.allocate(m_ * n_ * sizeof(T)); + + // Initialize the content of the memory pools to prevent asan from + // complaining. + device_.memset(a_, 12, m_ * k_ * sizeof(T)); + device_.memset(b_, 23, k_ * n_ * sizeof(T)); + device_.memset(c_, 31, m_ * n_ * sizeof(T)); + + //BenchmarkUseRealTime(); + } + + inline void finalizeBenchmark(int64_t num_items) { +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + if (Eigen::internal::is_same::value) { + device_.synchronize(); + } +#endif + StopBenchmarkTiming(); + SetBenchmarkFlopsProcessed(num_items); + } + + + TensorIndex m_; + TensorIndex k_; + TensorIndex n_; + T* a_; + T* b_; + T* c_; + Device device_; +}; +#endif // THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_ diff --git a/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_cpu.cc b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_cpu.cc new file mode 100644 index 000000000..8947f4b7f --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_cpu.cc @@ -0,0 +1,168 @@ +#define EIGEN_USE_THREADS + +#include + +#include "tensor_benchmarks.h" + +#define CREATE_THREAD_POOL(threads) \ +Eigen::ThreadPool pool(threads); \ +Eigen::ThreadPoolDevice device(&pool, threads); + +// Simple functions +#define BM_FuncCPU(FUNC, THREADS) \ + static void BM_##FUNC##_##THREADS##T(int iters, int N) { \ + StopBenchmarkTiming(); \ + CREATE_THREAD_POOL(THREADS); \ + BenchmarkSuite suite(device, N); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##THREADS##T, 10, 5000); + +BM_FuncCPU(memcpy, 4); +BM_FuncCPU(memcpy, 8); +BM_FuncCPU(memcpy, 12); + +BM_FuncCPU(typeCasting, 4); +BM_FuncCPU(typeCasting, 8); +BM_FuncCPU(typeCasting, 12); + +BM_FuncCPU(random, 4); +BM_FuncCPU(random, 8); +BM_FuncCPU(random, 12); + +BM_FuncCPU(slicing, 4); +BM_FuncCPU(slicing, 8); +BM_FuncCPU(slicing, 12); + +BM_FuncCPU(rowChip, 4); +BM_FuncCPU(rowChip, 8); +BM_FuncCPU(rowChip, 12); + +BM_FuncCPU(colChip, 4); +BM_FuncCPU(colChip, 8); +BM_FuncCPU(colChip, 12); + +BM_FuncCPU(shuffling, 4); +BM_FuncCPU(shuffling, 8); +BM_FuncCPU(shuffling, 12); + +BM_FuncCPU(padding, 4); +BM_FuncCPU(padding, 8); +BM_FuncCPU(padding, 12); + +BM_FuncCPU(striding, 4); +BM_FuncCPU(striding, 8); +BM_FuncCPU(striding, 12); + +BM_FuncCPU(broadcasting, 4); +BM_FuncCPU(broadcasting, 8); +BM_FuncCPU(broadcasting, 12); + +BM_FuncCPU(coeffWiseOp, 4); +BM_FuncCPU(coeffWiseOp, 8); +BM_FuncCPU(coeffWiseOp, 12); + +BM_FuncCPU(algebraicFunc, 4); +BM_FuncCPU(algebraicFunc, 8); +BM_FuncCPU(algebraicFunc, 12); + +BM_FuncCPU(transcendentalFunc, 4); +BM_FuncCPU(transcendentalFunc, 8); +BM_FuncCPU(transcendentalFunc, 12); + +BM_FuncCPU(rowReduction, 4); +BM_FuncCPU(rowReduction, 8); +BM_FuncCPU(rowReduction, 12); + +BM_FuncCPU(colReduction, 4); +BM_FuncCPU(colReduction, 8); +BM_FuncCPU(colReduction, 12); + + +// Contractions +#define BM_FuncWithInputDimsCPU(FUNC, D1, D2, D3, THREADS) \ + static void BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T(int iters, int N) { \ + StopBenchmarkTiming(); \ + if (THREADS == 1) { \ + Eigen::DefaultDevice device; \ + BenchmarkSuite suite(device, D1, D2, D3); \ + suite.FUNC(iters); \ + } else { \ + CREATE_THREAD_POOL(THREADS); \ + BenchmarkSuite suite(device, D1, D2, D3); \ + suite.FUNC(iters); \ + } \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T, 10, 5000); + + +BM_FuncWithInputDimsCPU(contraction, N, N, N, 1); +BM_FuncWithInputDimsCPU(contraction, N, N, N, 4); +BM_FuncWithInputDimsCPU(contraction, N, N, N, 8); +BM_FuncWithInputDimsCPU(contraction, N, N, N, 12); +BM_FuncWithInputDimsCPU(contraction, N, N, N, 16); + +BM_FuncWithInputDimsCPU(contraction, 64, N, N, 1); +BM_FuncWithInputDimsCPU(contraction, 64, N, N, 4); +BM_FuncWithInputDimsCPU(contraction, 64, N, N, 8); +BM_FuncWithInputDimsCPU(contraction, 64, N, N, 12); +BM_FuncWithInputDimsCPU(contraction, 64, N, N, 16); + +BM_FuncWithInputDimsCPU(contraction, N, 64, N, 1); +BM_FuncWithInputDimsCPU(contraction, N, 64, N, 4); +BM_FuncWithInputDimsCPU(contraction, N, 64, N, 8); +BM_FuncWithInputDimsCPU(contraction, N, 64, N, 12); +BM_FuncWithInputDimsCPU(contraction, N, 64, N, 16); + +BM_FuncWithInputDimsCPU(contraction, N, N, 64, 1); +BM_FuncWithInputDimsCPU(contraction, N, N, 64, 4); +BM_FuncWithInputDimsCPU(contraction, N, N, 64, 8); +BM_FuncWithInputDimsCPU(contraction, N, N, 64, 12); +BM_FuncWithInputDimsCPU(contraction, N, N, 64, 16); + +BM_FuncWithInputDimsCPU(contraction, 1, N, N, 1); +BM_FuncWithInputDimsCPU(contraction, 1, N, N, 4); +BM_FuncWithInputDimsCPU(contraction, 1, N, N, 8); +BM_FuncWithInputDimsCPU(contraction, 1, N, N, 12); +BM_FuncWithInputDimsCPU(contraction, 1, N, N, 16); + +BM_FuncWithInputDimsCPU(contraction, N, N, 1, 1); +BM_FuncWithInputDimsCPU(contraction, N, N, 1, 4); +BM_FuncWithInputDimsCPU(contraction, N, N, 1, 8); +BM_FuncWithInputDimsCPU(contraction, N, N, 1, 12); +BM_FuncWithInputDimsCPU(contraction, N, N, 1, 16); + + +// Convolutions +#define BM_FuncWithKernelDimsCPU(FUNC, DIM1, DIM2, THREADS) \ + static void BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T(int iters, int N) { \ + StopBenchmarkTiming(); \ + CREATE_THREAD_POOL(THREADS); \ + BenchmarkSuite suite(device, N); \ + suite.FUNC(iters, DIM1, DIM2); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T, 128, 5000); + +BM_FuncWithKernelDimsCPU(convolution, 7, 1, 4); +BM_FuncWithKernelDimsCPU(convolution, 7, 1, 8); +BM_FuncWithKernelDimsCPU(convolution, 7, 1, 12); + +BM_FuncWithKernelDimsCPU(convolution, 1, 7, 4); +BM_FuncWithKernelDimsCPU(convolution, 1, 7, 8); +BM_FuncWithKernelDimsCPU(convolution, 1, 7, 12); + +BM_FuncWithKernelDimsCPU(convolution, 7, 4, 4); +BM_FuncWithKernelDimsCPU(convolution, 7, 4, 8); +BM_FuncWithKernelDimsCPU(convolution, 7, 4, 12); + +BM_FuncWithKernelDimsCPU(convolution, 4, 7, 4); +BM_FuncWithKernelDimsCPU(convolution, 4, 7, 8); +BM_FuncWithKernelDimsCPU(convolution, 4, 7, 12); + +BM_FuncWithKernelDimsCPU(convolution, 7, 64, 4); +BM_FuncWithKernelDimsCPU(convolution, 7, 64, 8); +BM_FuncWithKernelDimsCPU(convolution, 7, 64, 12); + +BM_FuncWithKernelDimsCPU(convolution, 64, 7, 4); +BM_FuncWithKernelDimsCPU(convolution, 64, 7, 8); +BM_FuncWithKernelDimsCPU(convolution, 64, 7, 12); diff --git a/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu new file mode 100644 index 000000000..65784d0d6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu @@ -0,0 +1,77 @@ +#define EIGEN_USE_GPU + +#include +#include +#include + +#include "tensor_benchmarks.h" + +// Simple functions +#define BM_FuncGPU(FUNC) \ + static void BM_##FUNC(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, N); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC, 10, 5000); + +BM_FuncGPU(memcpy); +BM_FuncGPU(typeCasting); +//BM_FuncGPU(random); +BM_FuncGPU(slicing); +BM_FuncGPU(rowChip); +BM_FuncGPU(colChip); +BM_FuncGPU(shuffling); +BM_FuncGPU(padding); +BM_FuncGPU(striding); +BM_FuncGPU(broadcasting); +BM_FuncGPU(coeffWiseOp); +BM_FuncGPU(algebraicFunc); +BM_FuncGPU(transcendentalFunc); +BM_FuncGPU(rowReduction); +BM_FuncGPU(colReduction); +BM_FuncGPU(fullReduction); + + +// Contractions +#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3) \ + static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, D1, D2, D3); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000); + + +BM_FuncWithInputDimsGPU(contraction, N, N, N); +BM_FuncWithInputDimsGPU(contraction, 64, N, N); +BM_FuncWithInputDimsGPU(contraction, N, 64, N); +BM_FuncWithInputDimsGPU(contraction, N, N, 64); + + +// Convolutions +#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2) \ + static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, N); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters, DIM1, DIM2); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000); + +/* +BM_FuncWithKernelDimsGPU(convolution, 7, 1); +BM_FuncWithKernelDimsGPU(convolution, 1, 7); +BM_FuncWithKernelDimsGPU(convolution, 7, 4); +BM_FuncWithKernelDimsGPU(convolution, 4, 7); +BM_FuncWithKernelDimsGPU(convolution, 7, 64); +BM_FuncWithKernelDimsGPU(convolution, 64, 7); +*/ diff --git a/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_gpu.cu b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_gpu.cu new file mode 100644 index 000000000..76d68c5c1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_gpu.cu @@ -0,0 +1,75 @@ +#define EIGEN_USE_GPU + +#include +#include +#include + +#include "tensor_benchmarks.h" + +// Simple functions +#define BM_FuncGPU(FUNC) \ + static void BM_##FUNC(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, N); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC, 10, 5000); + +BM_FuncGPU(memcpy); +BM_FuncGPU(typeCasting); +BM_FuncGPU(random); +BM_FuncGPU(slicing); +BM_FuncGPU(rowChip); +BM_FuncGPU(colChip); +BM_FuncGPU(shuffling); +BM_FuncGPU(padding); +BM_FuncGPU(striding); +BM_FuncGPU(broadcasting); +BM_FuncGPU(coeffWiseOp); +BM_FuncGPU(algebraicFunc); +BM_FuncGPU(transcendentalFunc); +BM_FuncGPU(rowReduction); +BM_FuncGPU(colReduction); +BM_FuncGPU(fullReduction); + + +// Contractions +#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3) \ + static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, D1, D2, D3); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000); + + +BM_FuncWithInputDimsGPU(contraction, N, N, N); +BM_FuncWithInputDimsGPU(contraction, 64, N, N); +BM_FuncWithInputDimsGPU(contraction, N, 64, N); +BM_FuncWithInputDimsGPU(contraction, N, N, 64); + + +// Convolutions +#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2) \ + static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) { \ + StopBenchmarkTiming(); \ + Eigen::CudaStreamDevice stream; \ + Eigen::GpuDevice device(&stream); \ + BenchmarkSuite suite(device, N); \ + cudaDeviceSynchronize(); \ + suite.FUNC(iters, DIM1, DIM2); \ + } \ + BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000); + +BM_FuncWithKernelDimsGPU(convolution, 7, 1); +BM_FuncWithKernelDimsGPU(convolution, 1, 7); +BM_FuncWithKernelDimsGPU(convolution, 7, 4); +BM_FuncWithKernelDimsGPU(convolution, 4, 7); +BM_FuncWithKernelDimsGPU(convolution, 7, 64); +BM_FuncWithKernelDimsGPU(convolution, 64, 7); diff --git a/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_sycl.cc b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_sycl.cc new file mode 100644 index 000000000..7eca4d966 --- /dev/null +++ b/gtsam/3rdparty/Eigen/bench/tensors/tensor_benchmarks_sycl.cc @@ -0,0 +1,37 @@ +#define EIGEN_USE_SYCL + +#include +#include + +#include "tensor_benchmarks.h" + +using Eigen::array; +using Eigen::SyclDevice; +using Eigen::Tensor; +using Eigen::TensorMap; +// Simple functions +template +cl::sycl::queue sycl_queue() { + return cl::sycl::queue(device_selector(), [=](cl::sycl::exception_list l) { + for (const auto& e : l) { + try { + std::rethrow_exception(e); + } catch (cl::sycl::exception e) { + std::cout << e.what() << std::endl; + } + } + }); +} + +#define BM_FuncGPU(FUNC) \ + static void BM_##FUNC(int iters, int N) { \ + StopBenchmarkTiming(); \ + cl::sycl::queue q = sycl_queue(); \ + Eigen::SyclDevice device(q); \ + BenchmarkSuite suite(device, N); \ + suite.FUNC(iters); \ + } \ + BENCHMARK_RANGE(BM_##FUNC, 10, 5000); + +BM_FuncGPU(broadcasting); +BM_FuncGPU(coeffWiseOp); diff --git a/gtsam/3rdparty/Eigen/blas/CMakeLists.txt b/gtsam/3rdparty/Eigen/blas/CMakeLists.txt index a9bc05137..d0efb4188 100644 --- a/gtsam/3rdparty/Eigen/blas/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/blas/CMakeLists.txt @@ -14,23 +14,18 @@ endif() add_custom_target(blas) -set(EigenBlas_SRCS single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp) +set(EigenBlas_SRCS single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp + f2c/srotm.c f2c/srotmg.c f2c/drotm.c f2c/drotmg.c + f2c/lsame.c f2c/dspmv.c f2c/ssbmv.c f2c/chbmv.c + f2c/sspmv.c f2c/zhbmv.c f2c/chpmv.c f2c/dsbmv.c + f2c/zhpmv.c f2c/dtbmv.c f2c/stbmv.c f2c/ctbmv.c + f2c/ztbmv.c f2c/d_cnjg.c f2c/r_cnjg.c + ) -if(EIGEN_Fortran_COMPILER_WORKS) - -set(EigenBlas_SRCS ${EigenBlas_SRCS} - complexdots.f - srotm.f srotmg.f drotm.f drotmg.f - lsame.f dspmv.f ssbmv.f - chbmv.f sspmv.f - zhbmv.f chpmv.f dsbmv.f - zhpmv.f - dtbmv.f stbmv.f ctbmv.f ztbmv.f -) +if (EIGEN_Fortran_COMPILER_WORKS) + set(EigenBlas_SRCS ${EigenBlas_SRCS} fortran/complexdots.f) else() - -message(WARNING " No fortran compiler has been detected, the blas build will be incomplete.") - + set(EigenBlas_SRCS ${EigenBlas_SRCS} f2c/complexdots.c) endif() add_library(eigen_blas_static ${EigenBlas_SRCS}) diff --git a/gtsam/3rdparty/Eigen/blas/PackedTriangularMatrixVector.h b/gtsam/3rdparty/Eigen/blas/PackedTriangularMatrixVector.h index e9886d56f..0039536a8 100644 --- a/gtsam/3rdparty/Eigen/blas/PackedTriangularMatrixVector.h +++ b/gtsam/3rdparty/Eigen/blas/PackedTriangularMatrixVector.h @@ -18,7 +18,7 @@ struct packed_triangular_matrix_vector_product; template struct packed_triangular_matrix_vector_product { - typedef typename scalar_product_traits::ReturnType ResScalar; + typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; enum { IsLower = (Mode & Lower) ==Lower, HasUnitDiag = (Mode & UnitDiag)==UnitDiag, @@ -47,7 +47,7 @@ struct packed_triangular_matrix_vector_product struct packed_triangular_matrix_vector_product { - typedef typename scalar_product_traits::ReturnType ResScalar; + typedef typename ScalarBinaryOpTraits::ReturnType ResScalar; enum { IsLower = (Mode & Lower) ==Lower, HasUnitDiag = (Mode & UnitDiag)==UnitDiag, diff --git a/gtsam/3rdparty/Eigen/blas/chbmv.f b/gtsam/3rdparty/Eigen/blas/chbmv.f deleted file mode 100644 index 1b1c330ea..000000000 --- a/gtsam/3rdparty/Eigen/blas/chbmv.f +++ /dev/null @@ -1,310 +0,0 @@ - SUBROUTINE CHBMV(UPLO,N,K,ALPHA,A,LDA,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - COMPLEX ALPHA,BETA - INTEGER INCX,INCY,K,LDA,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - COMPLEX A(LDA,*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* CHBMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n hermitian band matrix, with k super-diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the band matrix A is being supplied as -* follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* being supplied. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* being supplied. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry, K specifies the number of super-diagonals of the -* matrix A. K must satisfy 0 .le. K. -* Unchanged on exit. -* -* ALPHA - COMPLEX . -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* A - COMPLEX array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the hermitian matrix, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer the upper -* triangular part of a hermitian band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the hermitian matrix, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer the lower -* triangular part of a hermitian band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that the imaginary parts of the diagonal elements need -* not be set and are assumed to be zero. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the -* vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - COMPLEX . -* On entry, BETA specifies the scalar beta. -* Unchanged on exit. -* -* Y - COMPLEX array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the -* vector y. On exit, Y is overwritten by the updated vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - COMPLEX ONE - PARAMETER (ONE= (1.0E+0,0.0E+0)) - COMPLEX ZERO - PARAMETER (ZERO= (0.0E+0,0.0E+0)) -* .. -* .. Local Scalars .. - COMPLEX TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,KPLUS1,KX,KY,L -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC CONJG,MAX,MIN,REAL -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (K.LT.0) THEN - INFO = 3 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 6 - ELSE IF (INCX.EQ.0) THEN - INFO = 8 - ELSE IF (INCY.EQ.0) THEN - INFO = 11 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('CHBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array A -* are accessed sequentially with one pass through A. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - IF (LSAME(UPLO,'U')) THEN -* -* Form y when upper triangle of A is stored. -* - KPLUS1 = K + 1 - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - L = KPLUS1 - J - DO 50 I = MAX(1,J-K),J - 1 - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + CONJG(A(L+I,J))*X(I) - 50 CONTINUE - Y(J) = Y(J) + TEMP1*REAL(A(KPLUS1,J)) + ALPHA*TEMP2 - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - L = KPLUS1 - J - DO 70 I = MAX(1,J-K),J - 1 - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + CONJG(A(L+I,J))*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*REAL(A(KPLUS1,J)) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - IF (J.GT.K) THEN - KX = KX + INCX - KY = KY + INCY - END IF - 80 CONTINUE - END IF - ELSE -* -* Form y when lower triangle of A is stored. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*REAL(A(1,J)) - L = 1 - J - DO 90 I = J + 1,MIN(N,J+K) - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + CONJG(A(L+I,J))*X(I) - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*REAL(A(1,J)) - L = 1 - J - IX = JX - IY = JY - DO 110 I = J + 1,MIN(N,J+K) - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + CONJG(A(L+I,J))*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of CHBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/chpmv.f b/gtsam/3rdparty/Eigen/blas/chpmv.f deleted file mode 100644 index 158be5a7b..000000000 --- a/gtsam/3rdparty/Eigen/blas/chpmv.f +++ /dev/null @@ -1,272 +0,0 @@ - SUBROUTINE CHPMV(UPLO,N,ALPHA,AP,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - COMPLEX ALPHA,BETA - INTEGER INCX,INCY,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - COMPLEX AP(*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* CHPMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n hermitian matrix, supplied in packed form. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the matrix A is supplied in the packed -* array AP as follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* supplied in AP. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* supplied in AP. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* ALPHA - COMPLEX . -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* AP - COMPLEX array of DIMENSION at least -* ( ( n*( n + 1 ) )/2 ). -* Before entry with UPLO = 'U' or 'u', the array AP must -* contain the upper triangular part of the hermitian matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) -* and a( 2, 2 ) respectively, and so on. -* Before entry with UPLO = 'L' or 'l', the array AP must -* contain the lower triangular part of the hermitian matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) -* and a( 3, 1 ) respectively, and so on. -* Note that the imaginary parts of the diagonal elements need -* not be set and are assumed to be zero. -* Unchanged on exit. -* -* X - COMPLEX array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - COMPLEX . -* On entry, BETA specifies the scalar beta. When BETA is -* supplied as zero then Y need not be set on input. -* Unchanged on exit. -* -* Y - COMPLEX array of dimension at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the n -* element vector y. On exit, Y is overwritten by the updated -* vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - COMPLEX ONE - PARAMETER (ONE= (1.0E+0,0.0E+0)) - COMPLEX ZERO - PARAMETER (ZERO= (0.0E+0,0.0E+0)) -* .. -* .. Local Scalars .. - COMPLEX TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,K,KK,KX,KY -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC CONJG,REAL -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (INCX.EQ.0) THEN - INFO = 6 - ELSE IF (INCY.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('CHPMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array AP -* are accessed sequentially with one pass through AP. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - KK = 1 - IF (LSAME(UPLO,'U')) THEN -* -* Form y when AP contains the upper triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - K = KK - DO 50 I = 1,J - 1 - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + CONJG(AP(K))*X(I) - K = K + 1 - 50 CONTINUE - Y(J) = Y(J) + TEMP1*REAL(AP(KK+J-1)) + ALPHA*TEMP2 - KK = KK + J - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - DO 70 K = KK,KK + J - 2 - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + CONJG(AP(K))*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*REAL(AP(KK+J-1)) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + J - 80 CONTINUE - END IF - ELSE -* -* Form y when AP contains the lower triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*REAL(AP(KK)) - K = KK + 1 - DO 90 I = J + 1,N - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + CONJG(AP(K))*X(I) - K = K + 1 - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - KK = KK + (N-J+1) - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*REAL(AP(KK)) - IX = JX - IY = JY - DO 110 K = KK + 1,KK + N - J - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + CONJG(AP(K))*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + (N-J+1) - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of CHPMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/common.h b/gtsam/3rdparty/Eigen/blas/common.h index 2bf642c6b..61d8344d9 100644 --- a/gtsam/3rdparty/Eigen/blas/common.h +++ b/gtsam/3rdparty/Eigen/blas/common.h @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2010 Gael Guennebaud +// Copyright (C) 2009-2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -10,18 +10,16 @@ #ifndef EIGEN_BLAS_COMMON_H #define EIGEN_BLAS_COMMON_H -#include -#include +#include "../Eigen/Core" +#include "../Eigen/Jacobi" -#include #include #ifndef SCALAR #error the token SCALAR must be defined to compile this file #endif -#include - +#include "../Eigen/src/misc/blas.h" #define NOTR 0 #define TR 1 @@ -95,6 +93,7 @@ enum typedef Matrix PlainMatrixType; typedef Map, 0, OuterStride<> > MatrixType; +typedef Map, 0, OuterStride<> > ConstMatrixType; typedef Map, 0, InnerStride > StridedVectorType; typedef Map > CompactVectorType; @@ -106,26 +105,45 @@ matrix(T* data, int rows, int cols, int stride) } template -Map, 0, InnerStride > vector(T* data, int size, int incr) +Map, 0, OuterStride<> > +matrix(const T* data, int rows, int cols, int stride) +{ + return Map, 0, OuterStride<> >(data, rows, cols, OuterStride<>(stride)); +} + +template +Map, 0, InnerStride > make_vector(T* data, int size, int incr) { return Map, 0, InnerStride >(data, size, InnerStride(incr)); } template -Map > vector(T* data, int size) +Map, 0, InnerStride > make_vector(const T* data, int size, int incr) +{ + return Map, 0, InnerStride >(data, size, InnerStride(incr)); +} + +template +Map > make_vector(T* data, int size) { return Map >(data, size); } +template +Map > make_vector(const T* data, int size) +{ + return Map >(data, size); +} + template T* get_compact_vector(T* x, int n, int incx) { if(incx==1) return x; - T* ret = new Scalar[n]; - if(incx<0) vector(ret,n) = vector(x,n,-incx).reverse(); - else vector(ret,n) = vector(x,n, incx); + typename Eigen::internal::remove_const::type* ret = new Scalar[n]; + if(incx<0) make_vector(ret,n) = make_vector(x,n,-incx).reverse(); + else make_vector(ret,n) = make_vector(x,n, incx); return ret; } @@ -135,8 +153,8 @@ T* copy_back(T* x_cpy, T* x, int n, int incx) if(x_cpy==x) return 0; - if(incx<0) vector(x,n,-incx).reverse() = vector(x_cpy,n); - else vector(x,n, incx) = vector(x_cpy,n); + if(incx<0) make_vector(x,n,-incx).reverse() = make_vector(x_cpy,n); + else make_vector(x,n, incx) = make_vector(x_cpy,n); return x_cpy; } diff --git a/gtsam/3rdparty/Eigen/blas/ctbmv.f b/gtsam/3rdparty/Eigen/blas/ctbmv.f deleted file mode 100644 index 5a879fa01..000000000 --- a/gtsam/3rdparty/Eigen/blas/ctbmv.f +++ /dev/null @@ -1,366 +0,0 @@ - SUBROUTINE CTBMV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - COMPLEX A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* CTBMV performs one of the matrix-vector operations -* -* x := A*x, or x := A'*x, or x := conjg( A' )*x, -* -* where x is an n element vector and A is an n by n unit, or non-unit, -* upper or lower triangular band matrix, with ( k + 1 ) diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the operation to be performed as -* follows: -* -* TRANS = 'N' or 'n' x := A*x. -* -* TRANS = 'T' or 't' x := A'*x. -* -* TRANS = 'C' or 'c' x := conjg( A' )*x. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - COMPLEX array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. On exit, X is overwritten with the -* tranformed vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - COMPLEX ZERO - PARAMETER (ZERO= (0.0E+0,0.0E+0)) -* .. -* .. Local Scalars .. - COMPLEX TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOCONJ,NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC CONJG,MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('CTBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOCONJ = LSAME(TRANS,'T') - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := A*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = 1,N - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = KPLUS1 - J - DO 10 I = MAX(1,J-K),J - 1 - X(I) = X(I) + TEMP*A(L+I,J) - 10 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(KPLUS1,J) - END IF - 20 CONTINUE - ELSE - JX = KX - DO 40 J = 1,N - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - DO 30 I = MAX(1,J-K),J - 1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX + INCX - 30 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(KPLUS1,J) - END IF - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = 1 - J - DO 50 I = MIN(N,J+K),J + 1,-1 - X(I) = X(I) + TEMP*A(L+I,J) - 50 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(1,J) - END IF - 60 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 80 J = N,1,-1 - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = 1 - J - DO 70 I = MIN(N,J+K),J + 1,-1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX - INCX - 70 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(1,J) - END IF - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := A'*x or x := conjg( A' )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 110 J = N,1,-1 - TEMP = X(J) - L = KPLUS1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 90 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(I) - 90 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*CONJG(A(KPLUS1,J)) - DO 100 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + CONJG(A(L+I,J))*X(I) - 100 CONTINUE - END IF - X(J) = TEMP - 110 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 140 J = N,1,-1 - TEMP = X(JX) - KX = KX - INCX - IX = KX - L = KPLUS1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 120 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX - INCX - 120 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*CONJG(A(KPLUS1,J)) - DO 130 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + CONJG(A(L+I,J))*X(IX) - IX = IX - INCX - 130 CONTINUE - END IF - X(JX) = TEMP - JX = JX - INCX - 140 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 170 J = 1,N - TEMP = X(J) - L = 1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 150 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(I) - 150 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*CONJG(A(1,J)) - DO 160 I = J + 1,MIN(N,J+K) - TEMP = TEMP + CONJG(A(L+I,J))*X(I) - 160 CONTINUE - END IF - X(J) = TEMP - 170 CONTINUE - ELSE - JX = KX - DO 200 J = 1,N - TEMP = X(JX) - KX = KX + INCX - IX = KX - L = 1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 180 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX + INCX - 180 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*CONJG(A(1,J)) - DO 190 I = J + 1,MIN(N,J+K) - TEMP = TEMP + CONJG(A(L+I,J))*X(IX) - IX = IX + INCX - 190 CONTINUE - END IF - X(JX) = TEMP - JX = JX + INCX - 200 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of CTBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/double.cpp b/gtsam/3rdparty/Eigen/blas/double.cpp index 8fd0709ba..295b1d1f2 100644 --- a/gtsam/3rdparty/Eigen/blas/double.cpp +++ b/gtsam/3rdparty/Eigen/blas/double.cpp @@ -23,11 +23,10 @@ double BLASFUNC(dsdot)(int* n, float* x, int* incx, float* y, int* incy) { if(*n<=0) return 0; - if(*incx==1 && *incy==1) return (vector(x,*n).cast().cwiseProduct(vector(y,*n).cast())).sum(); - else if(*incx>0 && *incy>0) return (vector(x,*n,*incx).cast().cwiseProduct(vector(y,*n,*incy).cast())).sum(); - else if(*incx<0 && *incy>0) return (vector(x,*n,-*incx).reverse().cast().cwiseProduct(vector(y,*n,*incy).cast())).sum(); - else if(*incx>0 && *incy<0) return (vector(x,*n,*incx).cast().cwiseProduct(vector(y,*n,-*incy).reverse().cast())).sum(); - else if(*incx<0 && *incy<0) return (vector(x,*n,-*incx).reverse().cast().cwiseProduct(vector(y,*n,-*incy).reverse().cast())).sum(); + if(*incx==1 && *incy==1) return (make_vector(x,*n).cast().cwiseProduct(make_vector(y,*n).cast())).sum(); + else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cast().cwiseProduct(make_vector(y,*n,*incy).cast())).sum(); + else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cast().cwiseProduct(make_vector(y,*n,*incy).cast())).sum(); + else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cast().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast())).sum(); + else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cast().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast())).sum(); else return 0; } - diff --git a/gtsam/3rdparty/Eigen/blas/drotm.f b/gtsam/3rdparty/Eigen/blas/drotm.f deleted file mode 100644 index 63a3b1134..000000000 --- a/gtsam/3rdparty/Eigen/blas/drotm.f +++ /dev/null @@ -1,147 +0,0 @@ - SUBROUTINE DROTM(N,DX,INCX,DY,INCY,DPARAM) -* .. Scalar Arguments .. - INTEGER INCX,INCY,N -* .. -* .. Array Arguments .. - DOUBLE PRECISION DPARAM(5),DX(*),DY(*) -* .. -* -* Purpose -* ======= -* -* APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX -* -* (DX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF DX ARE IN -* (DY**T) -* -* DX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE -* LX = (-INCX)*N, AND SIMILARLY FOR SY USING LY AND INCY. -* WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. -* -* DFLAG=-1.D0 DFLAG=0.D0 DFLAG=1.D0 DFLAG=-2.D0 -* -* (DH11 DH12) (1.D0 DH12) (DH11 1.D0) (1.D0 0.D0) -* H=( ) ( ) ( ) ( ) -* (DH21 DH22), (DH21 1.D0), (-1.D0 DH22), (0.D0 1.D0). -* SEE DROTMG FOR A DESCRIPTION OF DATA STORAGE IN DPARAM. -* -* Arguments -* ========= -* -* N (input) INTEGER -* number of elements in input vector(s) -* -* DX (input/output) DOUBLE PRECISION array, dimension N -* double precision vector with N elements -* -* INCX (input) INTEGER -* storage spacing between elements of DX -* -* DY (input/output) DOUBLE PRECISION array, dimension N -* double precision vector with N elements -* -* INCY (input) INTEGER -* storage spacing between elements of DY -* -* DPARAM (input/output) DOUBLE PRECISION array, dimension 5 -* DPARAM(1)=DFLAG -* DPARAM(2)=DH11 -* DPARAM(3)=DH21 -* DPARAM(4)=DH12 -* DPARAM(5)=DH22 -* -* ===================================================================== -* -* .. Local Scalars .. - DOUBLE PRECISION DFLAG,DH11,DH12,DH21,DH22,TWO,W,Z,ZERO - INTEGER I,KX,KY,NSTEPS -* .. -* .. Data statements .. - DATA ZERO,TWO/0.D0,2.D0/ -* .. -* - DFLAG = DPARAM(1) - IF (N.LE.0 .OR. (DFLAG+TWO.EQ.ZERO)) GO TO 140 - IF (.NOT. (INCX.EQ.INCY.AND.INCX.GT.0)) GO TO 70 -* - NSTEPS = N*INCX - IF (DFLAG) 50,10,30 - 10 CONTINUE - DH12 = DPARAM(4) - DH21 = DPARAM(3) - DO 20 I = 1,NSTEPS,INCX - W = DX(I) - Z = DY(I) - DX(I) = W + Z*DH12 - DY(I) = W*DH21 + Z - 20 CONTINUE - GO TO 140 - 30 CONTINUE - DH11 = DPARAM(2) - DH22 = DPARAM(5) - DO 40 I = 1,NSTEPS,INCX - W = DX(I) - Z = DY(I) - DX(I) = W*DH11 + Z - DY(I) = -W + DH22*Z - 40 CONTINUE - GO TO 140 - 50 CONTINUE - DH11 = DPARAM(2) - DH12 = DPARAM(4) - DH21 = DPARAM(3) - DH22 = DPARAM(5) - DO 60 I = 1,NSTEPS,INCX - W = DX(I) - Z = DY(I) - DX(I) = W*DH11 + Z*DH12 - DY(I) = W*DH21 + Z*DH22 - 60 CONTINUE - GO TO 140 - 70 CONTINUE - KX = 1 - KY = 1 - IF (INCX.LT.0) KX = 1 + (1-N)*INCX - IF (INCY.LT.0) KY = 1 + (1-N)*INCY -* - IF (DFLAG) 120,80,100 - 80 CONTINUE - DH12 = DPARAM(4) - DH21 = DPARAM(3) - DO 90 I = 1,N - W = DX(KX) - Z = DY(KY) - DX(KX) = W + Z*DH12 - DY(KY) = W*DH21 + Z - KX = KX + INCX - KY = KY + INCY - 90 CONTINUE - GO TO 140 - 100 CONTINUE - DH11 = DPARAM(2) - DH22 = DPARAM(5) - DO 110 I = 1,N - W = DX(KX) - Z = DY(KY) - DX(KX) = W*DH11 + Z - DY(KY) = -W + DH22*Z - KX = KX + INCX - KY = KY + INCY - 110 CONTINUE - GO TO 140 - 120 CONTINUE - DH11 = DPARAM(2) - DH12 = DPARAM(4) - DH21 = DPARAM(3) - DH22 = DPARAM(5) - DO 130 I = 1,N - W = DX(KX) - Z = DY(KY) - DX(KX) = W*DH11 + Z*DH12 - DY(KY) = W*DH21 + Z*DH22 - KX = KX + INCX - KY = KY + INCY - 130 CONTINUE - 140 CONTINUE - RETURN - END diff --git a/gtsam/3rdparty/Eigen/blas/drotmg.f b/gtsam/3rdparty/Eigen/blas/drotmg.f deleted file mode 100644 index 3ae647b08..000000000 --- a/gtsam/3rdparty/Eigen/blas/drotmg.f +++ /dev/null @@ -1,206 +0,0 @@ - SUBROUTINE DROTMG(DD1,DD2,DX1,DY1,DPARAM) -* .. Scalar Arguments .. - DOUBLE PRECISION DD1,DD2,DX1,DY1 -* .. -* .. Array Arguments .. - DOUBLE PRECISION DPARAM(5) -* .. -* -* Purpose -* ======= -* -* CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS -* THE SECOND COMPONENT OF THE 2-VECTOR (DSQRT(DD1)*DX1,DSQRT(DD2)* -* DY2)**T. -* WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. -* -* DFLAG=-1.D0 DFLAG=0.D0 DFLAG=1.D0 DFLAG=-2.D0 -* -* (DH11 DH12) (1.D0 DH12) (DH11 1.D0) (1.D0 0.D0) -* H=( ) ( ) ( ) ( ) -* (DH21 DH22), (DH21 1.D0), (-1.D0 DH22), (0.D0 1.D0). -* LOCATIONS 2-4 OF DPARAM CONTAIN DH11, DH21, DH12, AND DH22 -* RESPECTIVELY. (VALUES OF 1.D0, -1.D0, OR 0.D0 IMPLIED BY THE -* VALUE OF DPARAM(1) ARE NOT STORED IN DPARAM.) -* -* THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE -* INEXACT. THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE -* OF DD1 AND DD2. ALL ACTUAL SCALING OF DATA IS DONE USING GAM. -* -* -* Arguments -* ========= -* -* DD1 (input/output) DOUBLE PRECISION -* -* DD2 (input/output) DOUBLE PRECISION -* -* DX1 (input/output) DOUBLE PRECISION -* -* DY1 (input) DOUBLE PRECISION -* -* DPARAM (input/output) DOUBLE PRECISION array, dimension 5 -* DPARAM(1)=DFLAG -* DPARAM(2)=DH11 -* DPARAM(3)=DH21 -* DPARAM(4)=DH12 -* DPARAM(5)=DH22 -* -* ===================================================================== -* -* .. Local Scalars .. - DOUBLE PRECISION DFLAG,DH11,DH12,DH21,DH22,DP1,DP2,DQ1,DQ2,DTEMP, - + DU,GAM,GAMSQ,ONE,RGAMSQ,TWO,ZERO - INTEGER IGO -* .. -* .. Intrinsic Functions .. - INTRINSIC DABS -* .. -* .. Data statements .. -* - DATA ZERO,ONE,TWO/0.D0,1.D0,2.D0/ - DATA GAM,GAMSQ,RGAMSQ/4096.D0,16777216.D0,5.9604645D-8/ -* .. - - IF (.NOT.DD1.LT.ZERO) GO TO 10 -* GO ZERO-H-D-AND-DX1.. - GO TO 60 - 10 CONTINUE -* CASE-DD1-NONNEGATIVE - DP2 = DD2*DY1 - IF (.NOT.DP2.EQ.ZERO) GO TO 20 - DFLAG = -TWO - GO TO 260 -* REGULAR-CASE.. - 20 CONTINUE - DP1 = DD1*DX1 - DQ2 = DP2*DY1 - DQ1 = DP1*DX1 -* - IF (.NOT.DABS(DQ1).GT.DABS(DQ2)) GO TO 40 - DH21 = -DY1/DX1 - DH12 = DP2/DP1 -* - DU = ONE - DH12*DH21 -* - IF (.NOT.DU.LE.ZERO) GO TO 30 -* GO ZERO-H-D-AND-DX1.. - GO TO 60 - 30 CONTINUE - DFLAG = ZERO - DD1 = DD1/DU - DD2 = DD2/DU - DX1 = DX1*DU -* GO SCALE-CHECK.. - GO TO 100 - 40 CONTINUE - IF (.NOT.DQ2.LT.ZERO) GO TO 50 -* GO ZERO-H-D-AND-DX1.. - GO TO 60 - 50 CONTINUE - DFLAG = ONE - DH11 = DP1/DP2 - DH22 = DX1/DY1 - DU = ONE + DH11*DH22 - DTEMP = DD2/DU - DD2 = DD1/DU - DD1 = DTEMP - DX1 = DY1*DU -* GO SCALE-CHECK - GO TO 100 -* PROCEDURE..ZERO-H-D-AND-DX1.. - 60 CONTINUE - DFLAG = -ONE - DH11 = ZERO - DH12 = ZERO - DH21 = ZERO - DH22 = ZERO -* - DD1 = ZERO - DD2 = ZERO - DX1 = ZERO -* RETURN.. - GO TO 220 -* PROCEDURE..FIX-H.. - 70 CONTINUE - IF (.NOT.DFLAG.GE.ZERO) GO TO 90 -* - IF (.NOT.DFLAG.EQ.ZERO) GO TO 80 - DH11 = ONE - DH22 = ONE - DFLAG = -ONE - GO TO 90 - 80 CONTINUE - DH21 = -ONE - DH12 = ONE - DFLAG = -ONE - 90 CONTINUE - GO TO IGO(120,150,180,210) -* PROCEDURE..SCALE-CHECK - 100 CONTINUE - 110 CONTINUE - IF (.NOT.DD1.LE.RGAMSQ) GO TO 130 - IF (DD1.EQ.ZERO) GO TO 160 - ASSIGN 120 TO IGO -* FIX-H.. - GO TO 70 - 120 CONTINUE - DD1 = DD1*GAM**2 - DX1 = DX1/GAM - DH11 = DH11/GAM - DH12 = DH12/GAM - GO TO 110 - 130 CONTINUE - 140 CONTINUE - IF (.NOT.DD1.GE.GAMSQ) GO TO 160 - ASSIGN 150 TO IGO -* FIX-H.. - GO TO 70 - 150 CONTINUE - DD1 = DD1/GAM**2 - DX1 = DX1*GAM - DH11 = DH11*GAM - DH12 = DH12*GAM - GO TO 140 - 160 CONTINUE - 170 CONTINUE - IF (.NOT.DABS(DD2).LE.RGAMSQ) GO TO 190 - IF (DD2.EQ.ZERO) GO TO 220 - ASSIGN 180 TO IGO -* FIX-H.. - GO TO 70 - 180 CONTINUE - DD2 = DD2*GAM**2 - DH21 = DH21/GAM - DH22 = DH22/GAM - GO TO 170 - 190 CONTINUE - 200 CONTINUE - IF (.NOT.DABS(DD2).GE.GAMSQ) GO TO 220 - ASSIGN 210 TO IGO -* FIX-H.. - GO TO 70 - 210 CONTINUE - DD2 = DD2/GAM**2 - DH21 = DH21*GAM - DH22 = DH22*GAM - GO TO 200 - 220 CONTINUE - IF (DFLAG) 250,230,240 - 230 CONTINUE - DPARAM(3) = DH21 - DPARAM(4) = DH12 - GO TO 260 - 240 CONTINUE - DPARAM(2) = DH11 - DPARAM(5) = DH22 - GO TO 260 - 250 CONTINUE - DPARAM(2) = DH11 - DPARAM(3) = DH21 - DPARAM(4) = DH12 - DPARAM(5) = DH22 - 260 CONTINUE - DPARAM(1) = DFLAG - RETURN - END diff --git a/gtsam/3rdparty/Eigen/blas/dsbmv.f b/gtsam/3rdparty/Eigen/blas/dsbmv.f deleted file mode 100644 index 8c82d1fa1..000000000 --- a/gtsam/3rdparty/Eigen/blas/dsbmv.f +++ /dev/null @@ -1,304 +0,0 @@ - SUBROUTINE DSBMV(UPLO,N,K,ALPHA,A,LDA,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - DOUBLE PRECISION ALPHA,BETA - INTEGER INCX,INCY,K,LDA,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - DOUBLE PRECISION A(LDA,*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* DSBMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n symmetric band matrix, with k super-diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the band matrix A is being supplied as -* follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* being supplied. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* being supplied. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry, K specifies the number of super-diagonals of the -* matrix A. K must satisfy 0 .le. K. -* Unchanged on exit. -* -* ALPHA - DOUBLE PRECISION. -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* A - DOUBLE PRECISION array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the symmetric matrix, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer the upper -* triangular part of a symmetric band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the symmetric matrix, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer the lower -* triangular part of a symmetric band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - DOUBLE PRECISION array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the -* vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - DOUBLE PRECISION. -* On entry, BETA specifies the scalar beta. -* Unchanged on exit. -* -* Y - DOUBLE PRECISION array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the -* vector y. On exit, Y is overwritten by the updated vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE PRECISION ONE,ZERO - PARAMETER (ONE=1.0D+0,ZERO=0.0D+0) -* .. -* .. Local Scalars .. - DOUBLE PRECISION TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,KPLUS1,KX,KY,L -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (K.LT.0) THEN - INFO = 3 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 6 - ELSE IF (INCX.EQ.0) THEN - INFO = 8 - ELSE IF (INCY.EQ.0) THEN - INFO = 11 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('DSBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array A -* are accessed sequentially with one pass through A. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - IF (LSAME(UPLO,'U')) THEN -* -* Form y when upper triangle of A is stored. -* - KPLUS1 = K + 1 - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - L = KPLUS1 - J - DO 50 I = MAX(1,J-K),J - 1 - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + A(L+I,J)*X(I) - 50 CONTINUE - Y(J) = Y(J) + TEMP1*A(KPLUS1,J) + ALPHA*TEMP2 - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - L = KPLUS1 - J - DO 70 I = MAX(1,J-K),J - 1 - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + A(L+I,J)*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*A(KPLUS1,J) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - IF (J.GT.K) THEN - KX = KX + INCX - KY = KY + INCY - END IF - 80 CONTINUE - END IF - ELSE -* -* Form y when lower triangle of A is stored. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*A(1,J) - L = 1 - J - DO 90 I = J + 1,MIN(N,J+K) - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + A(L+I,J)*X(I) - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*A(1,J) - L = 1 - J - IX = JX - IY = JY - DO 110 I = J + 1,MIN(N,J+K) - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + A(L+I,J)*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of DSBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/dspmv.f b/gtsam/3rdparty/Eigen/blas/dspmv.f deleted file mode 100644 index f6e121e76..000000000 --- a/gtsam/3rdparty/Eigen/blas/dspmv.f +++ /dev/null @@ -1,265 +0,0 @@ - SUBROUTINE DSPMV(UPLO,N,ALPHA,AP,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - DOUBLE PRECISION ALPHA,BETA - INTEGER INCX,INCY,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - DOUBLE PRECISION AP(*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* DSPMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n symmetric matrix, supplied in packed form. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the matrix A is supplied in the packed -* array AP as follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* supplied in AP. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* supplied in AP. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* ALPHA - DOUBLE PRECISION. -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* AP - DOUBLE PRECISION array of DIMENSION at least -* ( ( n*( n + 1 ) )/2 ). -* Before entry with UPLO = 'U' or 'u', the array AP must -* contain the upper triangular part of the symmetric matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) -* and a( 2, 2 ) respectively, and so on. -* Before entry with UPLO = 'L' or 'l', the array AP must -* contain the lower triangular part of the symmetric matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) -* and a( 3, 1 ) respectively, and so on. -* Unchanged on exit. -* -* X - DOUBLE PRECISION array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - DOUBLE PRECISION. -* On entry, BETA specifies the scalar beta. When BETA is -* supplied as zero then Y need not be set on input. -* Unchanged on exit. -* -* Y - DOUBLE PRECISION array of dimension at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the n -* element vector y. On exit, Y is overwritten by the updated -* vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE PRECISION ONE,ZERO - PARAMETER (ONE=1.0D+0,ZERO=0.0D+0) -* .. -* .. Local Scalars .. - DOUBLE PRECISION TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,K,KK,KX,KY -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (INCX.EQ.0) THEN - INFO = 6 - ELSE IF (INCY.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('DSPMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array AP -* are accessed sequentially with one pass through AP. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - KK = 1 - IF (LSAME(UPLO,'U')) THEN -* -* Form y when AP contains the upper triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - K = KK - DO 50 I = 1,J - 1 - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + AP(K)*X(I) - K = K + 1 - 50 CONTINUE - Y(J) = Y(J) + TEMP1*AP(KK+J-1) + ALPHA*TEMP2 - KK = KK + J - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - DO 70 K = KK,KK + J - 2 - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + AP(K)*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*AP(KK+J-1) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + J - 80 CONTINUE - END IF - ELSE -* -* Form y when AP contains the lower triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*AP(KK) - K = KK + 1 - DO 90 I = J + 1,N - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + AP(K)*X(I) - K = K + 1 - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - KK = KK + (N-J+1) - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*AP(KK) - IX = JX - IY = JY - DO 110 K = KK + 1,KK + N - J - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + AP(K)*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + (N-J+1) - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of DSPMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/dtbmv.f b/gtsam/3rdparty/Eigen/blas/dtbmv.f deleted file mode 100644 index a87ffdeae..000000000 --- a/gtsam/3rdparty/Eigen/blas/dtbmv.f +++ /dev/null @@ -1,335 +0,0 @@ - SUBROUTINE DTBMV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - DOUBLE PRECISION A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* DTBMV performs one of the matrix-vector operations -* -* x := A*x, or x := A'*x, -* -* where x is an n element vector and A is an n by n unit, or non-unit, -* upper or lower triangular band matrix, with ( k + 1 ) diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the operation to be performed as -* follows: -* -* TRANS = 'N' or 'n' x := A*x. -* -* TRANS = 'T' or 't' x := A'*x. -* -* TRANS = 'C' or 'c' x := A'*x. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - DOUBLE PRECISION array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - DOUBLE PRECISION array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. On exit, X is overwritten with the -* tranformed vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE PRECISION ZERO - PARAMETER (ZERO=0.0D+0) -* .. -* .. Local Scalars .. - DOUBLE PRECISION TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('DTBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := A*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = 1,N - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = KPLUS1 - J - DO 10 I = MAX(1,J-K),J - 1 - X(I) = X(I) + TEMP*A(L+I,J) - 10 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(KPLUS1,J) - END IF - 20 CONTINUE - ELSE - JX = KX - DO 40 J = 1,N - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - DO 30 I = MAX(1,J-K),J - 1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX + INCX - 30 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(KPLUS1,J) - END IF - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = 1 - J - DO 50 I = MIN(N,J+K),J + 1,-1 - X(I) = X(I) + TEMP*A(L+I,J) - 50 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(1,J) - END IF - 60 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 80 J = N,1,-1 - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = 1 - J - DO 70 I = MIN(N,J+K),J + 1,-1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX - INCX - 70 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(1,J) - END IF - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := A'*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 100 J = N,1,-1 - TEMP = X(J) - L = KPLUS1 - J - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 90 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(I) - 90 CONTINUE - X(J) = TEMP - 100 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 120 J = N,1,-1 - TEMP = X(JX) - KX = KX - INCX - IX = KX - L = KPLUS1 - J - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 110 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX - INCX - 110 CONTINUE - X(JX) = TEMP - JX = JX - INCX - 120 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 140 J = 1,N - TEMP = X(J) - L = 1 - J - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 130 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(I) - 130 CONTINUE - X(J) = TEMP - 140 CONTINUE - ELSE - JX = KX - DO 160 J = 1,N - TEMP = X(JX) - KX = KX + INCX - IX = KX - L = 1 - J - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 150 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX + INCX - 150 CONTINUE - X(JX) = TEMP - JX = JX + INCX - 160 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of DTBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/f2c/chbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/chbmv.c new file mode 100644 index 000000000..f218fe3f5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/chbmv.c @@ -0,0 +1,487 @@ +/* chbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int chbmv_(char *uplo, integer *n, integer *k, complex * + alpha, complex *a, integer *lda, complex *x, integer *incx, complex * + beta, complex *y, integer *incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5; + real r__1; + complex q__1, q__2, q__3, q__4; + + /* Builtin functions */ + void r_cnjg(complex *, complex *); + + /* Local variables */ + integer i__, j, l, ix, iy, jx, jy, kx, ky, info; + complex temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* CHBMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n hermitian band matrix, with k super-diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the band matrix A is being supplied as */ +/* follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* being supplied. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* being supplied. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry, K specifies the number of super-diagonals of the */ +/* matrix A. K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* ALPHA - COMPLEX . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* A - COMPLEX array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the hermitian matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer the upper */ +/* triangular part of a hermitian band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the hermitian matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer the lower */ +/* triangular part of a hermitian band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that the imaginary parts of the diagonal elements need */ +/* not be set and are assumed to be zero. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - COMPLEX array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the */ +/* vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - COMPLEX . */ +/* On entry, BETA specifies the scalar beta. */ +/* Unchanged on exit. */ + +/* Y - COMPLEX array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the */ +/* vector y. On exit, Y is overwritten by the updated vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + --y; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*k < 0) { + info = 3; + } else if (*lda < *k + 1) { + info = 6; + } else if (*incx == 0) { + info = 8; + } else if (*incy == 0) { + info = 11; + } + if (info != 0) { + xerbla_("CHBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && + beta->i == 0.f))) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array A */ +/* are accessed sequentially with one pass through A. */ + +/* First form y := beta*y. */ + + if (beta->r != 1.f || beta->i != 0.f) { + if (*incy == 1) { + if (beta->r == 0.f && beta->i == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + y[i__2].r = 0.f, y[i__2].i = 0.f; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + i__3 = i__; + q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + q__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; +/* L20: */ + } + } + } else { + iy = ky; + if (beta->r == 0.f && beta->i == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + y[i__2].r = 0.f, y[i__2].i = 0.f; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + i__3 = iy; + q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + q__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + iy += *incy; +/* L40: */ + } + } + } + } + if (alpha->r == 0.f && alpha->i == 0.f) { + return 0; + } + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when upper triangle of A is stored. */ + + kplus1 = *k + 1; + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + q__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + i__2 = i__; + i__3 = i__; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__2 = i__; + q__2.r = q__3.r * x[i__2].r - q__3.i * x[i__2].i, q__2.i = + q__3.r * x[i__2].i + q__3.i * x[i__2].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; +/* L50: */ + } + i__4 = j; + i__2 = j; + i__3 = kplus1 + j * a_dim1; + r__1 = a[i__3].r; + q__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i; + q__2.r = y[i__2].r + q__3.r, q__2.i = y[i__2].i + q__3.i; + q__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i; + y[i__4].r = q__1.r, y[i__4].i = q__1.i; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__4 = jx; + q__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, q__1.i = + alpha->r * x[i__4].i + alpha->i * x[i__4].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + ix = kx; + iy = ky; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + i__4 = iy; + i__2 = iy; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i; + y[i__4].r = q__1.r, y[i__4].i = q__1.i; + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i = + q__3.r * x[i__4].i + q__3.i * x[i__4].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; + ix += *incx; + iy += *incy; +/* L70: */ + } + i__3 = jy; + i__4 = jy; + i__2 = kplus1 + j * a_dim1; + r__1 = a[i__2].r; + q__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i; + q__2.r = y[i__4].r + q__3.r, q__2.i = y[i__4].i + q__3.i; + q__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + jx += *incx; + jy += *incy; + if (j > *k) { + kx += *incx; + ky += *incy; + } +/* L80: */ + } + } + } else { + +/* Form y when lower triangle of A is stored. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__3 = j; + q__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i = + alpha->r * x[i__3].i + alpha->i * x[i__3].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + i__3 = j; + i__4 = j; + i__2 = j * a_dim1 + 1; + r__1 = a[i__2].r; + q__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + i__4 = i__; + i__2 = i__; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i; + y[i__4].r = q__1.r, y[i__4].i = q__1.i; + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__4 = i__; + q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i = + q__3.r * x[i__4].i + q__3.i * x[i__4].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; +/* L90: */ + } + i__3 = j; + i__4 = j; + q__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__3 = jx; + q__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i = + alpha->r * x[i__3].i + alpha->i * x[i__3].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + i__3 = jy; + i__4 = jy; + i__2 = j * a_dim1 + 1; + r__1 = a[i__2].r; + q__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + l = 1 - j; + ix = jx; + iy = jy; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + ix += *incx; + iy += *incy; + i__4 = iy; + i__2 = iy; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i; + y[i__4].r = q__1.r, y[i__4].i = q__1.i; + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i = + q__3.r * x[i__4].i + q__3.i * x[i__4].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; +/* L110: */ + } + i__3 = jy; + i__4 = jy; + q__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + jx += *incx; + jy += *incy; +/* L120: */ + } + } + } + + return 0; + +/* End of CHBMV . */ + +} /* chbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/chpmv.c b/gtsam/3rdparty/Eigen/blas/f2c/chpmv.c new file mode 100644 index 000000000..65bab1c7f --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/chpmv.c @@ -0,0 +1,438 @@ +/* chpmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int chpmv_(char *uplo, integer *n, complex *alpha, complex * + ap, complex *x, integer *incx, complex *beta, complex *y, integer * + incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer i__1, i__2, i__3, i__4, i__5; + real r__1; + complex q__1, q__2, q__3, q__4; + + /* Builtin functions */ + void r_cnjg(complex *, complex *); + + /* Local variables */ + integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info; + complex temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* CHPMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n hermitian matrix, supplied in packed form. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the matrix A is supplied in the packed */ +/* array AP as follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* supplied in AP. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* supplied in AP. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* ALPHA - COMPLEX . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* AP - COMPLEX array of DIMENSION at least */ +/* ( ( n*( n + 1 ) )/2 ). */ +/* Before entry with UPLO = 'U' or 'u', the array AP must */ +/* contain the upper triangular part of the hermitian matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */ +/* and a( 2, 2 ) respectively, and so on. */ +/* Before entry with UPLO = 'L' or 'l', the array AP must */ +/* contain the lower triangular part of the hermitian matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */ +/* and a( 3, 1 ) respectively, and so on. */ +/* Note that the imaginary parts of the diagonal elements need */ +/* not be set and are assumed to be zero. */ +/* Unchanged on exit. */ + +/* X - COMPLEX array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - COMPLEX . */ +/* On entry, BETA specifies the scalar beta. When BETA is */ +/* supplied as zero then Y need not be set on input. */ +/* Unchanged on exit. */ + +/* Y - COMPLEX array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the n */ +/* element vector y. On exit, Y is overwritten by the updated */ +/* vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + --y; + --x; + --ap; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*incx == 0) { + info = 6; + } else if (*incy == 0) { + info = 9; + } + if (info != 0) { + xerbla_("CHPMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && + beta->i == 0.f))) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array AP */ +/* are accessed sequentially with one pass through AP. */ + +/* First form y := beta*y. */ + + if (beta->r != 1.f || beta->i != 0.f) { + if (*incy == 1) { + if (beta->r == 0.f && beta->i == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + y[i__2].r = 0.f, y[i__2].i = 0.f; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + i__3 = i__; + q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + q__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; +/* L20: */ + } + } + } else { + iy = ky; + if (beta->r == 0.f && beta->i == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + y[i__2].r = 0.f, y[i__2].i = 0.f; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + i__3 = iy; + q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + q__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + iy += *incy; +/* L40: */ + } + } + } + } + if (alpha->r == 0.f && alpha->i == 0.f) { + return 0; + } + kk = 1; + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when AP contains the upper triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + q__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + k = kk; + i__2 = j - 1; + for (i__ = 1; i__ <= i__2; ++i__) { + i__3 = i__; + i__4 = i__; + i__5 = k; + q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + r_cnjg(&q__3, &ap[k]); + i__3 = i__; + q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i = + q__3.r * x[i__3].i + q__3.i * x[i__3].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; + ++k; +/* L50: */ + } + i__2 = j; + i__3 = j; + i__4 = kk + j - 1; + r__1 = ap[i__4].r; + q__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i; + q__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i; + q__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + kk += j; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = jx; + q__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + ix = kx; + iy = ky; + i__2 = kk + j - 2; + for (k = kk; k <= i__2; ++k) { + i__3 = iy; + i__4 = iy; + i__5 = k; + q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + r_cnjg(&q__3, &ap[k]); + i__3 = ix; + q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i = + q__3.r * x[i__3].i + q__3.i * x[i__3].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; + ix += *incx; + iy += *incy; +/* L70: */ + } + i__2 = jy; + i__3 = jy; + i__4 = kk + j - 1; + r__1 = ap[i__4].r; + q__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i; + q__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i; + q__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + jx += *incx; + jy += *incy; + kk += j; +/* L80: */ + } + } + } else { + +/* Form y when AP contains the lower triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + q__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + i__2 = j; + i__3 = j; + i__4 = kk; + r__1 = ap[i__4].r; + q__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i; + q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + k = kk + 1; + i__2 = *n; + for (i__ = j + 1; i__ <= i__2; ++i__) { + i__3 = i__; + i__4 = i__; + i__5 = k; + q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + r_cnjg(&q__3, &ap[k]); + i__3 = i__; + q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i = + q__3.r * x[i__3].i + q__3.i * x[i__3].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; + ++k; +/* L90: */ + } + i__2 = j; + i__3 = j; + q__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + kk += *n - j + 1; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = jx; + q__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = q__1.r, temp1.i = q__1.i; + temp2.r = 0.f, temp2.i = 0.f; + i__2 = jy; + i__3 = jy; + i__4 = kk; + r__1 = ap[i__4].r; + q__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i; + q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + ix = jx; + iy = jy; + i__2 = kk + *n - j; + for (k = kk + 1; k <= i__2; ++k) { + ix += *incx; + iy += *incy; + i__3 = iy; + i__4 = iy; + i__5 = k; + q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i; + y[i__3].r = q__1.r, y[i__3].i = q__1.i; + r_cnjg(&q__3, &ap[k]); + i__3 = ix; + q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i = + q__3.r * x[i__3].i + q__3.i * x[i__3].r; + q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i; + temp2.r = q__1.r, temp2.i = q__1.i; +/* L110: */ + } + i__2 = jy; + i__3 = jy; + q__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i; + y[i__2].r = q__1.r, y[i__2].i = q__1.i; + jx += *incx; + jy += *incy; + kk += *n - j + 1; +/* L120: */ + } + } + } + + return 0; + +/* End of CHPMV . */ + +} /* chpmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/complexdots.c b/gtsam/3rdparty/Eigen/blas/f2c/complexdots.c new file mode 100644 index 000000000..a856a231c --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/complexdots.c @@ -0,0 +1,84 @@ +/* This file has been modified to use the standard gfortran calling + convention, rather than the f2c calling convention. + + It does not require -ff2c when compiled with gfortran. +*/ + +/* complexdots.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +complex cdotc_(integer *n, complex *cx, integer + *incx, complex *cy, integer *incy) +{ + complex res; + extern /* Subroutine */ int cdotcw_(integer *, complex *, integer *, + complex *, integer *, complex *); + + /* Parameter adjustments */ + --cy; + --cx; + + /* Function Body */ + cdotcw_(n, &cx[1], incx, &cy[1], incy, &res); + return res; +} /* cdotc_ */ + +complex cdotu_(integer *n, complex *cx, integer + *incx, complex *cy, integer *incy) +{ + complex res; + extern /* Subroutine */ int cdotuw_(integer *, complex *, integer *, + complex *, integer *, complex *); + + /* Parameter adjustments */ + --cy; + --cx; + + /* Function Body */ + cdotuw_(n, &cx[1], incx, &cy[1], incy, &res); + return res; +} /* cdotu_ */ + +doublecomplex zdotc_(integer *n, doublecomplex *cx, integer *incx, + doublecomplex *cy, integer *incy) +{ + doublecomplex res; + extern /* Subroutine */ int zdotcw_(integer *, doublecomplex *, integer *, + doublecomplex *, integer *, doublecomplex *); + + /* Parameter adjustments */ + --cy; + --cx; + + /* Function Body */ + zdotcw_(n, &cx[1], incx, &cy[1], incy, &res); + return res; +} /* zdotc_ */ + +doublecomplex zdotu_(integer *n, doublecomplex *cx, integer *incx, + doublecomplex *cy, integer *incy) +{ + doublecomplex res; + extern /* Subroutine */ int zdotuw_(integer *, doublecomplex *, integer *, + doublecomplex *, integer *, doublecomplex *); + + /* Parameter adjustments */ + --cy; + --cx; + + /* Function Body */ + zdotuw_(n, &cx[1], incx, &cy[1], incy, &res); + return res; +} /* zdotu_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/ctbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/ctbmv.c new file mode 100644 index 000000000..790fd581f --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/ctbmv.c @@ -0,0 +1,647 @@ +/* ctbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int ctbmv_(char *uplo, char *trans, char *diag, integer *n, + integer *k, complex *a, integer *lda, complex *x, integer *incx, + ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5; + complex q__1, q__2, q__3; + + /* Builtin functions */ + void r_cnjg(complex *, complex *); + + /* Local variables */ + integer i__, j, l, ix, jx, kx, info; + complex temp; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + logical noconj, nounit; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* CTBMV performs one of the matrix-vector operations */ + +/* x := A*x, or x := A'*x, or x := conjg( A' )*x, */ + +/* where x is an n element vector and A is an n by n unit, or non-unit, */ +/* upper or lower triangular band matrix, with ( k + 1 ) diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the matrix is an upper or */ +/* lower triangular matrix as follows: */ + +/* UPLO = 'U' or 'u' A is an upper triangular matrix. */ + +/* UPLO = 'L' or 'l' A is a lower triangular matrix. */ + +/* Unchanged on exit. */ + +/* TRANS - CHARACTER*1. */ +/* On entry, TRANS specifies the operation to be performed as */ +/* follows: */ + +/* TRANS = 'N' or 'n' x := A*x. */ + +/* TRANS = 'T' or 't' x := A'*x. */ + +/* TRANS = 'C' or 'c' x := conjg( A' )*x. */ + +/* Unchanged on exit. */ + +/* DIAG - CHARACTER*1. */ +/* On entry, DIAG specifies whether or not A is unit */ +/* triangular as follows: */ + +/* DIAG = 'U' or 'u' A is assumed to be unit triangular. */ + +/* DIAG = 'N' or 'n' A is not assumed to be unit */ +/* triangular. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry with UPLO = 'U' or 'u', K specifies the number of */ +/* super-diagonals of the matrix A. */ +/* On entry with UPLO = 'L' or 'l', K specifies the number of */ +/* sub-diagonals of the matrix A. */ +/* K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* A - COMPLEX array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer an upper */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer a lower */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that when DIAG = 'U' or 'u' the elements of the array A */ +/* corresponding to the diagonal elements of the matrix are not */ +/* referenced, but are assumed to be unity. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - COMPLEX array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. On exit, X is overwritten with the */ +/* tranformed vector x. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (! lsame_(trans, "N", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, + "T", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, "C", (ftnlen)1, ( + ftnlen)1)) { + info = 2; + } else if (! lsame_(diag, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, + "N", (ftnlen)1, (ftnlen)1)) { + info = 3; + } else if (*n < 0) { + info = 4; + } else if (*k < 0) { + info = 5; + } else if (*lda < *k + 1) { + info = 7; + } else if (*incx == 0) { + info = 9; + } + if (info != 0) { + xerbla_("CTBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0) { + return 0; + } + + noconj = lsame_(trans, "T", (ftnlen)1, (ftnlen)1); + nounit = lsame_(diag, "N", (ftnlen)1, (ftnlen)1); + +/* Set up the start point in X if the increment is not unity. This */ +/* will be ( N - 1 )*INCX too small for descending loops. */ + + if (*incx <= 0) { + kx = 1 - (*n - 1) * *incx; + } else if (*incx != 1) { + kx = 1; + } + +/* Start the operations. In this version the elements of A are */ +/* accessed sequentially with one pass through A. */ + + if (lsame_(trans, "N", (ftnlen)1, (ftnlen)1)) { + +/* Form x := A*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + if (x[i__2].r != 0.f || x[i__2].i != 0.f) { + i__2 = j; + temp.r = x[i__2].r, temp.i = x[i__2].i; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + i__2 = i__; + i__3 = i__; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, + q__2.i = temp.r * a[i__5].i + temp.i * a[ + i__5].r; + q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + + q__2.i; + x[i__2].r = q__1.r, x[i__2].i = q__1.i; +/* L10: */ + } + if (nounit) { + i__4 = j; + i__2 = j; + i__3 = kplus1 + j * a_dim1; + q__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[ + i__3].i, q__1.i = x[i__2].r * a[i__3].i + + x[i__2].i * a[i__3].r; + x[i__4].r = q__1.r, x[i__4].i = q__1.i; + } + } +/* L20: */ + } + } else { + jx = kx; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__4 = jx; + if (x[i__4].r != 0.f || x[i__4].i != 0.f) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + ix = kx; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + i__4 = ix; + i__2 = ix; + i__5 = l + i__ + j * a_dim1; + q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, + q__2.i = temp.r * a[i__5].i + temp.i * a[ + i__5].r; + q__1.r = x[i__2].r + q__2.r, q__1.i = x[i__2].i + + q__2.i; + x[i__4].r = q__1.r, x[i__4].i = q__1.i; + ix += *incx; +/* L30: */ + } + if (nounit) { + i__3 = jx; + i__4 = jx; + i__2 = kplus1 + j * a_dim1; + q__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[ + i__2].i, q__1.i = x[i__4].r * a[i__2].i + + x[i__4].i * a[i__2].r; + x[i__3].r = q__1.r, x[i__3].i = q__1.i; + } + } + jx += *incx; + if (j > *k) { + kx += *incx; + } +/* L40: */ + } + } + } else { + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + i__1 = j; + if (x[i__1].r != 0.f || x[i__1].i != 0.f) { + i__1 = j; + temp.r = x[i__1].r, temp.i = x[i__1].i; + l = 1 - j; +/* Computing MIN */ + i__1 = *n, i__3 = j + *k; + i__4 = j + 1; + for (i__ = min(i__1,i__3); i__ >= i__4; --i__) { + i__1 = i__; + i__3 = i__; + i__2 = l + i__ + j * a_dim1; + q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, + q__2.i = temp.r * a[i__2].i + temp.i * a[ + i__2].r; + q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + + q__2.i; + x[i__1].r = q__1.r, x[i__1].i = q__1.i; +/* L50: */ + } + if (nounit) { + i__4 = j; + i__1 = j; + i__3 = j * a_dim1 + 1; + q__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[ + i__3].i, q__1.i = x[i__1].r * a[i__3].i + + x[i__1].i * a[i__3].r; + x[i__4].r = q__1.r, x[i__4].i = q__1.i; + } + } +/* L60: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + i__4 = jx; + if (x[i__4].r != 0.f || x[i__4].i != 0.f) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + ix = kx; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__1 = j + *k; + i__3 = j + 1; + for (i__ = min(i__4,i__1); i__ >= i__3; --i__) { + i__4 = ix; + i__1 = ix; + i__2 = l + i__ + j * a_dim1; + q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, + q__2.i = temp.r * a[i__2].i + temp.i * a[ + i__2].r; + q__1.r = x[i__1].r + q__2.r, q__1.i = x[i__1].i + + q__2.i; + x[i__4].r = q__1.r, x[i__4].i = q__1.i; + ix -= *incx; +/* L70: */ + } + if (nounit) { + i__3 = jx; + i__4 = jx; + i__1 = j * a_dim1 + 1; + q__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[ + i__1].i, q__1.i = x[i__4].r * a[i__1].i + + x[i__4].i * a[i__1].r; + x[i__3].r = q__1.r, x[i__3].i = q__1.i; + } + } + jx -= *incx; + if (*n - j >= *k) { + kx -= *incx; + } +/* L80: */ + } + } + } + } else { + +/* Form x := A'*x or x := conjg( A' )*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + i__3 = j; + temp.r = x[i__3].r, temp.i = x[i__3].i; + l = kplus1 - j; + if (noconj) { + if (nounit) { + i__3 = kplus1 + j * a_dim1; + q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, + q__1.i = temp.r * a[i__3].i + temp.i * a[ + i__3].r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + i__4 = l + i__ + j * a_dim1; + i__1 = i__; + q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[ + i__1].i, q__2.i = a[i__4].r * x[i__1].i + + a[i__4].i * x[i__1].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; +/* L90: */ + } + } else { + if (nounit) { + r_cnjg(&q__2, &a[kplus1 + j * a_dim1]); + q__1.r = temp.r * q__2.r - temp.i * q__2.i, + q__1.i = temp.r * q__2.i + temp.i * + q__2.r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__4 = i__; + q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, + q__2.i = q__3.r * x[i__4].i + q__3.i * x[ + i__4].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; +/* L100: */ + } + } + i__3 = j; + x[i__3].r = temp.r, x[i__3].i = temp.i; +/* L110: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + i__3 = jx; + temp.r = x[i__3].r, temp.i = x[i__3].i; + kx -= *incx; + ix = kx; + l = kplus1 - j; + if (noconj) { + if (nounit) { + i__3 = kplus1 + j * a_dim1; + q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, + q__1.i = temp.r * a[i__3].i + temp.i * a[ + i__3].r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + i__4 = l + i__ + j * a_dim1; + i__1 = ix; + q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[ + i__1].i, q__2.i = a[i__4].r * x[i__1].i + + a[i__4].i * x[i__1].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; + ix -= *incx; +/* L120: */ + } + } else { + if (nounit) { + r_cnjg(&q__2, &a[kplus1 + j * a_dim1]); + q__1.r = temp.r * q__2.r - temp.i * q__2.i, + q__1.i = temp.r * q__2.i + temp.i * + q__2.r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, + q__2.i = q__3.r * x[i__4].i + q__3.i * x[ + i__4].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; + ix -= *incx; +/* L130: */ + } + } + i__3 = jx; + x[i__3].r = temp.r, x[i__3].i = temp.i; + jx -= *incx; +/* L140: */ + } + } + } else { + if (*incx == 1) { + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + i__4 = j; + temp.r = x[i__4].r, temp.i = x[i__4].i; + l = 1 - j; + if (noconj) { + if (nounit) { + i__4 = j * a_dim1 + 1; + q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, + q__1.i = temp.r * a[i__4].i + temp.i * a[ + i__4].r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + i__1 = l + i__ + j * a_dim1; + i__2 = i__; + q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[ + i__2].i, q__2.i = a[i__1].r * x[i__2].i + + a[i__1].i * x[i__2].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; +/* L150: */ + } + } else { + if (nounit) { + r_cnjg(&q__2, &a[j * a_dim1 + 1]); + q__1.r = temp.r * q__2.r - temp.i * q__2.i, + q__1.i = temp.r * q__2.i + temp.i * + q__2.r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__1 = i__; + q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, + q__2.i = q__3.r * x[i__1].i + q__3.i * x[ + i__1].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; +/* L160: */ + } + } + i__4 = j; + x[i__4].r = temp.r, x[i__4].i = temp.i; +/* L170: */ + } + } else { + jx = kx; + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + kx += *incx; + ix = kx; + l = 1 - j; + if (noconj) { + if (nounit) { + i__4 = j * a_dim1 + 1; + q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, + q__1.i = temp.r * a[i__4].i + temp.i * a[ + i__4].r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + i__1 = l + i__ + j * a_dim1; + i__2 = ix; + q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[ + i__2].i, q__2.i = a[i__1].r * x[i__2].i + + a[i__1].i * x[i__2].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; + ix += *incx; +/* L180: */ + } + } else { + if (nounit) { + r_cnjg(&q__2, &a[j * a_dim1 + 1]); + q__1.r = temp.r * q__2.r - temp.i * q__2.i, + q__1.i = temp.r * q__2.i + temp.i * + q__2.r; + temp.r = q__1.r, temp.i = q__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + r_cnjg(&q__3, &a[l + i__ + j * a_dim1]); + i__1 = ix; + q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, + q__2.i = q__3.r * x[i__1].i + q__3.i * x[ + i__1].r; + q__1.r = temp.r + q__2.r, q__1.i = temp.i + + q__2.i; + temp.r = q__1.r, temp.i = q__1.i; + ix += *incx; +/* L190: */ + } + } + i__4 = jx; + x[i__4].r = temp.r, x[i__4].i = temp.i; + jx += *incx; +/* L200: */ + } + } + } + } + + return 0; + +/* End of CTBMV . */ + +} /* ctbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/d_cnjg.c b/gtsam/3rdparty/Eigen/blas/f2c/d_cnjg.c new file mode 100644 index 000000000..623090c6b --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/d_cnjg.c @@ -0,0 +1,6 @@ +#include "datatypes.h" + +void d_cnjg(doublecomplex *r, doublecomplex *z) { + r->r = z->r; + r->i = -(z->i); +} diff --git a/gtsam/3rdparty/Eigen/blas/f2c/datatypes.h b/gtsam/3rdparty/Eigen/blas/f2c/datatypes.h new file mode 100644 index 000000000..63232b246 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/datatypes.h @@ -0,0 +1,24 @@ +/* This contains a limited subset of the typedefs exposed by f2c + for use by the Eigen BLAS C-only implementation. +*/ + +#ifndef __EIGEN_DATATYPES_H__ +#define __EIGEN_DATATYPES_H__ + +typedef int integer; +typedef unsigned int uinteger; +typedef float real; +typedef double doublereal; +typedef struct { real r, i; } complex; +typedef struct { doublereal r, i; } doublecomplex; +typedef int ftnlen; +typedef int logical; + +#define abs(x) ((x) >= 0 ? (x) : -(x)) +#define dabs(x) (doublereal)abs(x) +#define min(a,b) ((a) <= (b) ? (a) : (b)) +#define max(a,b) ((a) >= (b) ? (a) : (b)) +#define dmin(a,b) (doublereal)min(a,b) +#define dmax(a,b) (doublereal)max(a,b) + +#endif diff --git a/gtsam/3rdparty/Eigen/blas/f2c/drotm.c b/gtsam/3rdparty/Eigen/blas/f2c/drotm.c new file mode 100644 index 000000000..17a779b74 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/drotm.c @@ -0,0 +1,215 @@ +/* drotm.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int drotm_(integer *n, doublereal *dx, integer *incx, + doublereal *dy, integer *incy, doublereal *dparam) +{ + /* Initialized data */ + + static doublereal zero = 0.; + static doublereal two = 2.; + + /* System generated locals */ + integer i__1, i__2; + + /* Local variables */ + integer i__; + doublereal w, z__; + integer kx, ky; + doublereal dh11, dh12, dh21, dh22, dflag; + integer nsteps; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */ + +/* (DX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF DX ARE IN */ +/* (DY**T) */ + +/* DX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */ +/* LX = (-INCX)*N, AND SIMILARLY FOR SY USING LY AND INCY. */ +/* WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */ + +/* DFLAG=-1.D0 DFLAG=0.D0 DFLAG=1.D0 DFLAG=-2.D0 */ + +/* (DH11 DH12) (1.D0 DH12) (DH11 1.D0) (1.D0 0.D0) */ +/* H=( ) ( ) ( ) ( ) */ +/* (DH21 DH22), (DH21 1.D0), (-1.D0 DH22), (0.D0 1.D0). */ +/* SEE DROTMG FOR A DESCRIPTION OF DATA STORAGE IN DPARAM. */ + +/* Arguments */ +/* ========= */ + +/* N (input) INTEGER */ +/* number of elements in input vector(s) */ + +/* DX (input/output) DOUBLE PRECISION array, dimension N */ +/* double precision vector with N elements */ + +/* INCX (input) INTEGER */ +/* storage spacing between elements of DX */ + +/* DY (input/output) DOUBLE PRECISION array, dimension N */ +/* double precision vector with N elements */ + +/* INCY (input) INTEGER */ +/* storage spacing between elements of DY */ + +/* DPARAM (input/output) DOUBLE PRECISION array, dimension 5 */ +/* DPARAM(1)=DFLAG */ +/* DPARAM(2)=DH11 */ +/* DPARAM(3)=DH21 */ +/* DPARAM(4)=DH12 */ +/* DPARAM(5)=DH22 */ + +/* ===================================================================== */ + +/* .. Local Scalars .. */ +/* .. */ +/* .. Data statements .. */ + /* Parameter adjustments */ + --dparam; + --dy; + --dx; + + /* Function Body */ +/* .. */ + + dflag = dparam[1]; + if (*n <= 0 || dflag + two == zero) { + goto L140; + } + if (! (*incx == *incy && *incx > 0)) { + goto L70; + } + + nsteps = *n * *incx; + if (dflag < 0.) { + goto L50; + } else if (dflag == 0) { + goto L10; + } else { + goto L30; + } +L10: + dh12 = dparam[4]; + dh21 = dparam[3]; + i__1 = nsteps; + i__2 = *incx; + for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) { + w = dx[i__]; + z__ = dy[i__]; + dx[i__] = w + z__ * dh12; + dy[i__] = w * dh21 + z__; +/* L20: */ + } + goto L140; +L30: + dh11 = dparam[2]; + dh22 = dparam[5]; + i__2 = nsteps; + i__1 = *incx; + for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) { + w = dx[i__]; + z__ = dy[i__]; + dx[i__] = w * dh11 + z__; + dy[i__] = -w + dh22 * z__; +/* L40: */ + } + goto L140; +L50: + dh11 = dparam[2]; + dh12 = dparam[4]; + dh21 = dparam[3]; + dh22 = dparam[5]; + i__1 = nsteps; + i__2 = *incx; + for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) { + w = dx[i__]; + z__ = dy[i__]; + dx[i__] = w * dh11 + z__ * dh12; + dy[i__] = w * dh21 + z__ * dh22; +/* L60: */ + } + goto L140; +L70: + kx = 1; + ky = 1; + if (*incx < 0) { + kx = (1 - *n) * *incx + 1; + } + if (*incy < 0) { + ky = (1 - *n) * *incy + 1; + } + + if (dflag < 0.) { + goto L120; + } else if (dflag == 0) { + goto L80; + } else { + goto L100; + } +L80: + dh12 = dparam[4]; + dh21 = dparam[3]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = dx[kx]; + z__ = dy[ky]; + dx[kx] = w + z__ * dh12; + dy[ky] = w * dh21 + z__; + kx += *incx; + ky += *incy; +/* L90: */ + } + goto L140; +L100: + dh11 = dparam[2]; + dh22 = dparam[5]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = dx[kx]; + z__ = dy[ky]; + dx[kx] = w * dh11 + z__; + dy[ky] = -w + dh22 * z__; + kx += *incx; + ky += *incy; +/* L110: */ + } + goto L140; +L120: + dh11 = dparam[2]; + dh12 = dparam[4]; + dh21 = dparam[3]; + dh22 = dparam[5]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = dx[kx]; + z__ = dy[ky]; + dx[kx] = w * dh11 + z__ * dh12; + dy[ky] = w * dh21 + z__ * dh22; + kx += *incx; + ky += *incy; +/* L130: */ + } +L140: + return 0; +} /* drotm_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/drotmg.c b/gtsam/3rdparty/Eigen/blas/f2c/drotmg.c new file mode 100644 index 000000000..a63eb1083 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/drotmg.c @@ -0,0 +1,293 @@ +/* drotmg.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int drotmg_(doublereal *dd1, doublereal *dd2, doublereal * + dx1, doublereal *dy1, doublereal *dparam) +{ + /* Initialized data */ + + static doublereal zero = 0.; + static doublereal one = 1.; + static doublereal two = 2.; + static doublereal gam = 4096.; + static doublereal gamsq = 16777216.; + static doublereal rgamsq = 5.9604645e-8; + + /* Format strings */ + static char fmt_120[] = ""; + static char fmt_150[] = ""; + static char fmt_180[] = ""; + static char fmt_210[] = ""; + + /* System generated locals */ + doublereal d__1; + + /* Local variables */ + doublereal du, dp1, dp2, dq1, dq2, dh11, dh12, dh21, dh22; + integer igo; + doublereal dflag, dtemp; + + /* Assigned format variables */ + static char *igo_fmt; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */ +/* THE SECOND COMPONENT OF THE 2-VECTOR (DSQRT(DD1)*DX1,DSQRT(DD2)* */ +/* DY2)**T. */ +/* WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */ + +/* DFLAG=-1.D0 DFLAG=0.D0 DFLAG=1.D0 DFLAG=-2.D0 */ + +/* (DH11 DH12) (1.D0 DH12) (DH11 1.D0) (1.D0 0.D0) */ +/* H=( ) ( ) ( ) ( ) */ +/* (DH21 DH22), (DH21 1.D0), (-1.D0 DH22), (0.D0 1.D0). */ +/* LOCATIONS 2-4 OF DPARAM CONTAIN DH11, DH21, DH12, AND DH22 */ +/* RESPECTIVELY. (VALUES OF 1.D0, -1.D0, OR 0.D0 IMPLIED BY THE */ +/* VALUE OF DPARAM(1) ARE NOT STORED IN DPARAM.) */ + +/* THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */ +/* INEXACT. THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */ +/* OF DD1 AND DD2. ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */ + + +/* Arguments */ +/* ========= */ + +/* DD1 (input/output) DOUBLE PRECISION */ + +/* DD2 (input/output) DOUBLE PRECISION */ + +/* DX1 (input/output) DOUBLE PRECISION */ + +/* DY1 (input) DOUBLE PRECISION */ + +/* DPARAM (input/output) DOUBLE PRECISION array, dimension 5 */ +/* DPARAM(1)=DFLAG */ +/* DPARAM(2)=DH11 */ +/* DPARAM(3)=DH21 */ +/* DPARAM(4)=DH12 */ +/* DPARAM(5)=DH22 */ + +/* ===================================================================== */ + +/* .. Local Scalars .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ +/* .. Data statements .. */ + + /* Parameter adjustments */ + --dparam; + + /* Function Body */ +/* .. */ + if (! (*dd1 < zero)) { + goto L10; + } +/* GO ZERO-H-D-AND-DX1.. */ + goto L60; +L10: +/* CASE-DD1-NONNEGATIVE */ + dp2 = *dd2 * *dy1; + if (! (dp2 == zero)) { + goto L20; + } + dflag = -two; + goto L260; +/* REGULAR-CASE.. */ +L20: + dp1 = *dd1 * *dx1; + dq2 = dp2 * *dy1; + dq1 = dp1 * *dx1; + + if (! (abs(dq1) > abs(dq2))) { + goto L40; + } + dh21 = -(*dy1) / *dx1; + dh12 = dp2 / dp1; + + du = one - dh12 * dh21; + + if (! (du <= zero)) { + goto L30; + } +/* GO ZERO-H-D-AND-DX1.. */ + goto L60; +L30: + dflag = zero; + *dd1 /= du; + *dd2 /= du; + *dx1 *= du; +/* GO SCALE-CHECK.. */ + goto L100; +L40: + if (! (dq2 < zero)) { + goto L50; + } +/* GO ZERO-H-D-AND-DX1.. */ + goto L60; +L50: + dflag = one; + dh11 = dp1 / dp2; + dh22 = *dx1 / *dy1; + du = one + dh11 * dh22; + dtemp = *dd2 / du; + *dd2 = *dd1 / du; + *dd1 = dtemp; + *dx1 = *dy1 * du; +/* GO SCALE-CHECK */ + goto L100; +/* PROCEDURE..ZERO-H-D-AND-DX1.. */ +L60: + dflag = -one; + dh11 = zero; + dh12 = zero; + dh21 = zero; + dh22 = zero; + + *dd1 = zero; + *dd2 = zero; + *dx1 = zero; +/* RETURN.. */ + goto L220; +/* PROCEDURE..FIX-H.. */ +L70: + if (! (dflag >= zero)) { + goto L90; + } + + if (! (dflag == zero)) { + goto L80; + } + dh11 = one; + dh22 = one; + dflag = -one; + goto L90; +L80: + dh21 = -one; + dh12 = one; + dflag = -one; +L90: + switch (igo) { + case 0: goto L120; + case 1: goto L150; + case 2: goto L180; + case 3: goto L210; + } +/* PROCEDURE..SCALE-CHECK */ +L100: +L110: + if (! (*dd1 <= rgamsq)) { + goto L130; + } + if (*dd1 == zero) { + goto L160; + } + igo = 0; + igo_fmt = fmt_120; +/* FIX-H.. */ + goto L70; +L120: +/* Computing 2nd power */ + d__1 = gam; + *dd1 *= d__1 * d__1; + *dx1 /= gam; + dh11 /= gam; + dh12 /= gam; + goto L110; +L130: +L140: + if (! (*dd1 >= gamsq)) { + goto L160; + } + igo = 1; + igo_fmt = fmt_150; +/* FIX-H.. */ + goto L70; +L150: +/* Computing 2nd power */ + d__1 = gam; + *dd1 /= d__1 * d__1; + *dx1 *= gam; + dh11 *= gam; + dh12 *= gam; + goto L140; +L160: +L170: + if (! (abs(*dd2) <= rgamsq)) { + goto L190; + } + if (*dd2 == zero) { + goto L220; + } + igo = 2; + igo_fmt = fmt_180; +/* FIX-H.. */ + goto L70; +L180: +/* Computing 2nd power */ + d__1 = gam; + *dd2 *= d__1 * d__1; + dh21 /= gam; + dh22 /= gam; + goto L170; +L190: +L200: + if (! (abs(*dd2) >= gamsq)) { + goto L220; + } + igo = 3; + igo_fmt = fmt_210; +/* FIX-H.. */ + goto L70; +L210: +/* Computing 2nd power */ + d__1 = gam; + *dd2 /= d__1 * d__1; + dh21 *= gam; + dh22 *= gam; + goto L200; +L220: + if (dflag < 0.) { + goto L250; + } else if (dflag == 0) { + goto L230; + } else { + goto L240; + } +L230: + dparam[3] = dh21; + dparam[4] = dh12; + goto L260; +L240: + dparam[2] = dh11; + dparam[5] = dh22; + goto L260; +L250: + dparam[2] = dh11; + dparam[3] = dh21; + dparam[4] = dh12; + dparam[5] = dh22; +L260: + dparam[1] = dflag; + return 0; +} /* drotmg_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/dsbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/dsbmv.c new file mode 100644 index 000000000..c6b4b21d6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/dsbmv.c @@ -0,0 +1,366 @@ +/* dsbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int dsbmv_(char *uplo, integer *n, integer *k, doublereal * + alpha, doublereal *a, integer *lda, doublereal *x, integer *incx, + doublereal *beta, doublereal *y, integer *incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4; + + /* Local variables */ + integer i__, j, l, ix, iy, jx, jy, kx, ky, info; + doublereal temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* DSBMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n symmetric band matrix, with k super-diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the band matrix A is being supplied as */ +/* follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* being supplied. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* being supplied. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry, K specifies the number of super-diagonals of the */ +/* matrix A. K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* ALPHA - DOUBLE PRECISION. */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* A - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the symmetric matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer the upper */ +/* triangular part of a symmetric band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the symmetric matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer the lower */ +/* triangular part of a symmetric band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - DOUBLE PRECISION array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the */ +/* vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - DOUBLE PRECISION. */ +/* On entry, BETA specifies the scalar beta. */ +/* Unchanged on exit. */ + +/* Y - DOUBLE PRECISION array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the */ +/* vector y. On exit, Y is overwritten by the updated vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + --y; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*k < 0) { + info = 3; + } else if (*lda < *k + 1) { + info = 6; + } else if (*incx == 0) { + info = 8; + } else if (*incy == 0) { + info = 11; + } + if (info != 0) { + xerbla_("DSBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (*alpha == 0. && *beta == 1.)) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array A */ +/* are accessed sequentially with one pass through A. */ + +/* First form y := beta*y. */ + + if (*beta != 1.) { + if (*incy == 1) { + if (*beta == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = 0.; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = *beta * y[i__]; +/* L20: */ + } + } + } else { + iy = ky; + if (*beta == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = 0.; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = *beta * y[iy]; + iy += *incy; +/* L40: */ + } + } + } + } + if (*alpha == 0.) { + return 0; + } + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when upper triangle of A is stored. */ + + kplus1 = *k + 1; + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + y[i__] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[i__]; +/* L50: */ + } + y[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.; + ix = kx; + iy = ky; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + y[iy] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[ix]; + ix += *incx; + iy += *incy; +/* L70: */ + } + y[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * + temp2; + jx += *incx; + jy += *incy; + if (j > *k) { + kx += *incx; + ky += *incy; + } +/* L80: */ + } + } + } else { + +/* Form y when lower triangle of A is stored. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.; + y[j] += temp1 * a[j * a_dim1 + 1]; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + y[i__] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[i__]; +/* L90: */ + } + y[j] += *alpha * temp2; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.; + y[jy] += temp1 * a[j * a_dim1 + 1]; + l = 1 - j; + ix = jx; + iy = jy; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + ix += *incx; + iy += *incy; + y[iy] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[ix]; +/* L110: */ + } + y[jy] += *alpha * temp2; + jx += *incx; + jy += *incy; +/* L120: */ + } + } + } + + return 0; + +/* End of DSBMV . */ + +} /* dsbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/dspmv.c b/gtsam/3rdparty/Eigen/blas/f2c/dspmv.c new file mode 100644 index 000000000..0b4e92d5c --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/dspmv.c @@ -0,0 +1,316 @@ +/* dspmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int dspmv_(char *uplo, integer *n, doublereal *alpha, + doublereal *ap, doublereal *x, integer *incx, doublereal *beta, + doublereal *y, integer *incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer i__1, i__2; + + /* Local variables */ + integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info; + doublereal temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* DSPMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n symmetric matrix, supplied in packed form. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the matrix A is supplied in the packed */ +/* array AP as follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* supplied in AP. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* supplied in AP. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* ALPHA - DOUBLE PRECISION. */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* AP - DOUBLE PRECISION array of DIMENSION at least */ +/* ( ( n*( n + 1 ) )/2 ). */ +/* Before entry with UPLO = 'U' or 'u', the array AP must */ +/* contain the upper triangular part of the symmetric matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */ +/* and a( 2, 2 ) respectively, and so on. */ +/* Before entry with UPLO = 'L' or 'l', the array AP must */ +/* contain the lower triangular part of the symmetric matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */ +/* and a( 3, 1 ) respectively, and so on. */ +/* Unchanged on exit. */ + +/* X - DOUBLE PRECISION array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - DOUBLE PRECISION. */ +/* On entry, BETA specifies the scalar beta. When BETA is */ +/* supplied as zero then Y need not be set on input. */ +/* Unchanged on exit. */ + +/* Y - DOUBLE PRECISION array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the n */ +/* element vector y. On exit, Y is overwritten by the updated */ +/* vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + --y; + --x; + --ap; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*incx == 0) { + info = 6; + } else if (*incy == 0) { + info = 9; + } + if (info != 0) { + xerbla_("DSPMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (*alpha == 0. && *beta == 1.)) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array AP */ +/* are accessed sequentially with one pass through AP. */ + +/* First form y := beta*y. */ + + if (*beta != 1.) { + if (*incy == 1) { + if (*beta == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = 0.; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = *beta * y[i__]; +/* L20: */ + } + } + } else { + iy = ky; + if (*beta == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = 0.; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = *beta * y[iy]; + iy += *incy; +/* L40: */ + } + } + } + } + if (*alpha == 0.) { + return 0; + } + kk = 1; + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when AP contains the upper triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.; + k = kk; + i__2 = j - 1; + for (i__ = 1; i__ <= i__2; ++i__) { + y[i__] += temp1 * ap[k]; + temp2 += ap[k] * x[i__]; + ++k; +/* L50: */ + } + y[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2; + kk += j; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.; + ix = kx; + iy = ky; + i__2 = kk + j - 2; + for (k = kk; k <= i__2; ++k) { + y[iy] += temp1 * ap[k]; + temp2 += ap[k] * x[ix]; + ix += *incx; + iy += *incy; +/* L70: */ + } + y[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2; + jx += *incx; + jy += *incy; + kk += j; +/* L80: */ + } + } + } else { + +/* Form y when AP contains the lower triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.; + y[j] += temp1 * ap[kk]; + k = kk + 1; + i__2 = *n; + for (i__ = j + 1; i__ <= i__2; ++i__) { + y[i__] += temp1 * ap[k]; + temp2 += ap[k] * x[i__]; + ++k; +/* L90: */ + } + y[j] += *alpha * temp2; + kk += *n - j + 1; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.; + y[jy] += temp1 * ap[kk]; + ix = jx; + iy = jy; + i__2 = kk + *n - j; + for (k = kk + 1; k <= i__2; ++k) { + ix += *incx; + iy += *incy; + y[iy] += temp1 * ap[k]; + temp2 += ap[k] * x[ix]; +/* L110: */ + } + y[jy] += *alpha * temp2; + jx += *incx; + jy += *incy; + kk += *n - j + 1; +/* L120: */ + } + } + } + + return 0; + +/* End of DSPMV . */ + +} /* dspmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/dtbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/dtbmv.c new file mode 100644 index 000000000..fdf73ebb5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/dtbmv.c @@ -0,0 +1,428 @@ +/* dtbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int dtbmv_(char *uplo, char *trans, char *diag, integer *n, + integer *k, doublereal *a, integer *lda, doublereal *x, integer *incx, + ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4; + + /* Local variables */ + integer i__, j, l, ix, jx, kx, info; + doublereal temp; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + logical nounit; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* DTBMV performs one of the matrix-vector operations */ + +/* x := A*x, or x := A'*x, */ + +/* where x is an n element vector and A is an n by n unit, or non-unit, */ +/* upper or lower triangular band matrix, with ( k + 1 ) diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the matrix is an upper or */ +/* lower triangular matrix as follows: */ + +/* UPLO = 'U' or 'u' A is an upper triangular matrix. */ + +/* UPLO = 'L' or 'l' A is a lower triangular matrix. */ + +/* Unchanged on exit. */ + +/* TRANS - CHARACTER*1. */ +/* On entry, TRANS specifies the operation to be performed as */ +/* follows: */ + +/* TRANS = 'N' or 'n' x := A*x. */ + +/* TRANS = 'T' or 't' x := A'*x. */ + +/* TRANS = 'C' or 'c' x := A'*x. */ + +/* Unchanged on exit. */ + +/* DIAG - CHARACTER*1. */ +/* On entry, DIAG specifies whether or not A is unit */ +/* triangular as follows: */ + +/* DIAG = 'U' or 'u' A is assumed to be unit triangular. */ + +/* DIAG = 'N' or 'n' A is not assumed to be unit */ +/* triangular. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry with UPLO = 'U' or 'u', K specifies the number of */ +/* super-diagonals of the matrix A. */ +/* On entry with UPLO = 'L' or 'l', K specifies the number of */ +/* sub-diagonals of the matrix A. */ +/* K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* A - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer an upper */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer a lower */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that when DIAG = 'U' or 'u' the elements of the array A */ +/* corresponding to the diagonal elements of the matrix are not */ +/* referenced, but are assumed to be unity. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - DOUBLE PRECISION array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. On exit, X is overwritten with the */ +/* tranformed vector x. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (! lsame_(trans, "N", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, + "T", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, "C", (ftnlen)1, ( + ftnlen)1)) { + info = 2; + } else if (! lsame_(diag, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, + "N", (ftnlen)1, (ftnlen)1)) { + info = 3; + } else if (*n < 0) { + info = 4; + } else if (*k < 0) { + info = 5; + } else if (*lda < *k + 1) { + info = 7; + } else if (*incx == 0) { + info = 9; + } + if (info != 0) { + xerbla_("DTBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0) { + return 0; + } + + nounit = lsame_(diag, "N", (ftnlen)1, (ftnlen)1); + +/* Set up the start point in X if the increment is not unity. This */ +/* will be ( N - 1 )*INCX too small for descending loops. */ + + if (*incx <= 0) { + kx = 1 - (*n - 1) * *incx; + } else if (*incx != 1) { + kx = 1; + } + +/* Start the operations. In this version the elements of A are */ +/* accessed sequentially with one pass through A. */ + + if (lsame_(trans, "N", (ftnlen)1, (ftnlen)1)) { + +/* Form x := A*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + if (x[j] != 0.) { + temp = x[j]; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + x[i__] += temp * a[l + i__ + j * a_dim1]; +/* L10: */ + } + if (nounit) { + x[j] *= a[kplus1 + j * a_dim1]; + } + } +/* L20: */ + } + } else { + jx = kx; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + if (x[jx] != 0.) { + temp = x[jx]; + ix = kx; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + x[ix] += temp * a[l + i__ + j * a_dim1]; + ix += *incx; +/* L30: */ + } + if (nounit) { + x[jx] *= a[kplus1 + j * a_dim1]; + } + } + jx += *incx; + if (j > *k) { + kx += *incx; + } +/* L40: */ + } + } + } else { + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + if (x[j] != 0.) { + temp = x[j]; + l = 1 - j; +/* Computing MIN */ + i__1 = *n, i__3 = j + *k; + i__4 = j + 1; + for (i__ = min(i__1,i__3); i__ >= i__4; --i__) { + x[i__] += temp * a[l + i__ + j * a_dim1]; +/* L50: */ + } + if (nounit) { + x[j] *= a[j * a_dim1 + 1]; + } + } +/* L60: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + if (x[jx] != 0.) { + temp = x[jx]; + ix = kx; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__1 = j + *k; + i__3 = j + 1; + for (i__ = min(i__4,i__1); i__ >= i__3; --i__) { + x[ix] += temp * a[l + i__ + j * a_dim1]; + ix -= *incx; +/* L70: */ + } + if (nounit) { + x[jx] *= a[j * a_dim1 + 1]; + } + } + jx -= *incx; + if (*n - j >= *k) { + kx -= *incx; + } +/* L80: */ + } + } + } + } else { + +/* Form x := A'*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + temp = x[j]; + l = kplus1 - j; + if (nounit) { + temp *= a[kplus1 + j * a_dim1]; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + temp += a[l + i__ + j * a_dim1] * x[i__]; +/* L90: */ + } + x[j] = temp; +/* L100: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + temp = x[jx]; + kx -= *incx; + ix = kx; + l = kplus1 - j; + if (nounit) { + temp *= a[kplus1 + j * a_dim1]; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + temp += a[l + i__ + j * a_dim1] * x[ix]; + ix -= *incx; +/* L110: */ + } + x[jx] = temp; + jx -= *incx; +/* L120: */ + } + } + } else { + if (*incx == 1) { + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + temp = x[j]; + l = 1 - j; + if (nounit) { + temp *= a[j * a_dim1 + 1]; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + temp += a[l + i__ + j * a_dim1] * x[i__]; +/* L130: */ + } + x[j] = temp; +/* L140: */ + } + } else { + jx = kx; + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + temp = x[jx]; + kx += *incx; + ix = kx; + l = 1 - j; + if (nounit) { + temp *= a[j * a_dim1 + 1]; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + temp += a[l + i__ + j * a_dim1] * x[ix]; + ix += *incx; +/* L150: */ + } + x[jx] = temp; + jx += *incx; +/* L160: */ + } + } + } + } + + return 0; + +/* End of DTBMV . */ + +} /* dtbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/lsame.c b/gtsam/3rdparty/Eigen/blas/f2c/lsame.c new file mode 100644 index 000000000..46324d916 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/lsame.c @@ -0,0 +1,117 @@ +/* lsame.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +logical lsame_(char *ca, char *cb, ftnlen ca_len, ftnlen cb_len) +{ + /* System generated locals */ + logical ret_val; + + /* Local variables */ + integer inta, intb, zcode; + + +/* -- LAPACK auxiliary routine (version 3.1) -- */ +/* Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd.. */ +/* November 2006 */ + +/* .. Scalar Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* LSAME returns .TRUE. if CA is the same letter as CB regardless of */ +/* case. */ + +/* Arguments */ +/* ========= */ + +/* CA (input) CHARACTER*1 */ + +/* CB (input) CHARACTER*1 */ +/* CA and CB specify the single characters to be compared. */ + +/* ===================================================================== */ + +/* .. Intrinsic Functions .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ + +/* Test if the characters are equal */ + + ret_val = *(unsigned char *)ca == *(unsigned char *)cb; + if (ret_val) { + return ret_val; + } + +/* Now test for equivalence if both characters are alphabetic. */ + + zcode = 'Z'; + +/* Use 'Z' rather than 'A' so that ASCII can be detected on Prime */ +/* machines, on which ICHAR returns a value with bit 8 set. */ +/* ICHAR('A') on Prime machines returns 193 which is the same as */ +/* ICHAR('A') on an EBCDIC machine. */ + + inta = *(unsigned char *)ca; + intb = *(unsigned char *)cb; + + if (zcode == 90 || zcode == 122) { + +/* ASCII is assumed - ZCODE is the ASCII code of either lower or */ +/* upper case 'Z'. */ + + if (inta >= 97 && inta <= 122) { + inta += -32; + } + if (intb >= 97 && intb <= 122) { + intb += -32; + } + + } else if (zcode == 233 || zcode == 169) { + +/* EBCDIC is assumed - ZCODE is the EBCDIC code of either lower or */ +/* upper case 'Z'. */ + + if ((inta >= 129 && inta <= 137) || (inta >= 145 && inta <= 153) || + (inta >= 162 && inta <= 169)) { + inta += 64; + } + if ((intb >= 129 && intb <= 137) || (intb >= 145 && intb <= 153) || + (intb >= 162 && intb <= 169)) { + intb += 64; + } + + } else if (zcode == 218 || zcode == 250) { + +/* ASCII is assumed, on Prime machines - ZCODE is the ASCII code */ +/* plus 128 of either lower or upper case 'Z'. */ + + if (inta >= 225 && inta <= 250) { + inta += -32; + } + if (intb >= 225 && intb <= 250) { + intb += -32; + } + } + ret_val = inta == intb; + +/* RETURN */ + +/* End of LSAME */ + + return ret_val; +} /* lsame_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/r_cnjg.c b/gtsam/3rdparty/Eigen/blas/f2c/r_cnjg.c new file mode 100644 index 000000000..c08182f88 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/r_cnjg.c @@ -0,0 +1,6 @@ +#include "datatypes.h" + +void r_cnjg(complex *r, complex *z) { + r->r = z->r; + r->i = -(z->i); +} diff --git a/gtsam/3rdparty/Eigen/blas/f2c/srotm.c b/gtsam/3rdparty/Eigen/blas/f2c/srotm.c new file mode 100644 index 000000000..bd5944a99 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/srotm.c @@ -0,0 +1,216 @@ +/* srotm.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int srotm_(integer *n, real *sx, integer *incx, real *sy, + integer *incy, real *sparam) +{ + /* Initialized data */ + + static real zero = 0.f; + static real two = 2.f; + + /* System generated locals */ + integer i__1, i__2; + + /* Local variables */ + integer i__; + real w, z__; + integer kx, ky; + real sh11, sh12, sh21, sh22, sflag; + integer nsteps; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */ + +/* (SX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF SX ARE IN */ +/* (DX**T) */ + +/* SX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */ +/* LX = (-INCX)*N, AND SIMILARLY FOR SY USING USING LY AND INCY. */ +/* WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */ + +/* SFLAG=-1.E0 SFLAG=0.E0 SFLAG=1.E0 SFLAG=-2.E0 */ + +/* (SH11 SH12) (1.E0 SH12) (SH11 1.E0) (1.E0 0.E0) */ +/* H=( ) ( ) ( ) ( ) */ +/* (SH21 SH22), (SH21 1.E0), (-1.E0 SH22), (0.E0 1.E0). */ +/* SEE SROTMG FOR A DESCRIPTION OF DATA STORAGE IN SPARAM. */ + + +/* Arguments */ +/* ========= */ + +/* N (input) INTEGER */ +/* number of elements in input vector(s) */ + +/* SX (input/output) REAL array, dimension N */ +/* double precision vector with N elements */ + +/* INCX (input) INTEGER */ +/* storage spacing between elements of SX */ + +/* SY (input/output) REAL array, dimension N */ +/* double precision vector with N elements */ + +/* INCY (input) INTEGER */ +/* storage spacing between elements of SY */ + +/* SPARAM (input/output) REAL array, dimension 5 */ +/* SPARAM(1)=SFLAG */ +/* SPARAM(2)=SH11 */ +/* SPARAM(3)=SH21 */ +/* SPARAM(4)=SH12 */ +/* SPARAM(5)=SH22 */ + +/* ===================================================================== */ + +/* .. Local Scalars .. */ +/* .. */ +/* .. Data statements .. */ + /* Parameter adjustments */ + --sparam; + --sy; + --sx; + + /* Function Body */ +/* .. */ + + sflag = sparam[1]; + if (*n <= 0 || sflag + two == zero) { + goto L140; + } + if (! (*incx == *incy && *incx > 0)) { + goto L70; + } + + nsteps = *n * *incx; + if (sflag < 0.f) { + goto L50; + } else if (sflag == 0) { + goto L10; + } else { + goto L30; + } +L10: + sh12 = sparam[4]; + sh21 = sparam[3]; + i__1 = nsteps; + i__2 = *incx; + for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) { + w = sx[i__]; + z__ = sy[i__]; + sx[i__] = w + z__ * sh12; + sy[i__] = w * sh21 + z__; +/* L20: */ + } + goto L140; +L30: + sh11 = sparam[2]; + sh22 = sparam[5]; + i__2 = nsteps; + i__1 = *incx; + for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) { + w = sx[i__]; + z__ = sy[i__]; + sx[i__] = w * sh11 + z__; + sy[i__] = -w + sh22 * z__; +/* L40: */ + } + goto L140; +L50: + sh11 = sparam[2]; + sh12 = sparam[4]; + sh21 = sparam[3]; + sh22 = sparam[5]; + i__1 = nsteps; + i__2 = *incx; + for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) { + w = sx[i__]; + z__ = sy[i__]; + sx[i__] = w * sh11 + z__ * sh12; + sy[i__] = w * sh21 + z__ * sh22; +/* L60: */ + } + goto L140; +L70: + kx = 1; + ky = 1; + if (*incx < 0) { + kx = (1 - *n) * *incx + 1; + } + if (*incy < 0) { + ky = (1 - *n) * *incy + 1; + } + + if (sflag < 0.f) { + goto L120; + } else if (sflag == 0) { + goto L80; + } else { + goto L100; + } +L80: + sh12 = sparam[4]; + sh21 = sparam[3]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = sx[kx]; + z__ = sy[ky]; + sx[kx] = w + z__ * sh12; + sy[ky] = w * sh21 + z__; + kx += *incx; + ky += *incy; +/* L90: */ + } + goto L140; +L100: + sh11 = sparam[2]; + sh22 = sparam[5]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = sx[kx]; + z__ = sy[ky]; + sx[kx] = w * sh11 + z__; + sy[ky] = -w + sh22 * z__; + kx += *incx; + ky += *incy; +/* L110: */ + } + goto L140; +L120: + sh11 = sparam[2]; + sh12 = sparam[4]; + sh21 = sparam[3]; + sh22 = sparam[5]; + i__2 = *n; + for (i__ = 1; i__ <= i__2; ++i__) { + w = sx[kx]; + z__ = sy[ky]; + sx[kx] = w * sh11 + z__ * sh12; + sy[ky] = w * sh21 + z__ * sh22; + kx += *incx; + ky += *incy; +/* L130: */ + } +L140: + return 0; +} /* srotm_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/srotmg.c b/gtsam/3rdparty/Eigen/blas/f2c/srotmg.c new file mode 100644 index 000000000..75f789fe2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/srotmg.c @@ -0,0 +1,295 @@ +/* srotmg.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int srotmg_(real *sd1, real *sd2, real *sx1, real *sy1, real + *sparam) +{ + /* Initialized data */ + + static real zero = 0.f; + static real one = 1.f; + static real two = 2.f; + static real gam = 4096.f; + static real gamsq = 16777200.f; + static real rgamsq = 5.96046e-8f; + + /* Format strings */ + static char fmt_120[] = ""; + static char fmt_150[] = ""; + static char fmt_180[] = ""; + static char fmt_210[] = ""; + + /* System generated locals */ + real r__1; + + /* Local variables */ + real su, sp1, sp2, sq1, sq2, sh11, sh12, sh21, sh22; + integer igo; + real sflag, stemp; + + /* Assigned format variables */ + static char *igo_fmt; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */ +/* THE SECOND COMPONENT OF THE 2-VECTOR (SQRT(SD1)*SX1,SQRT(SD2)* */ +/* SY2)**T. */ +/* WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */ + +/* SFLAG=-1.E0 SFLAG=0.E0 SFLAG=1.E0 SFLAG=-2.E0 */ + +/* (SH11 SH12) (1.E0 SH12) (SH11 1.E0) (1.E0 0.E0) */ +/* H=( ) ( ) ( ) ( ) */ +/* (SH21 SH22), (SH21 1.E0), (-1.E0 SH22), (0.E0 1.E0). */ +/* LOCATIONS 2-4 OF SPARAM CONTAIN SH11,SH21,SH12, AND SH22 */ +/* RESPECTIVELY. (VALUES OF 1.E0, -1.E0, OR 0.E0 IMPLIED BY THE */ +/* VALUE OF SPARAM(1) ARE NOT STORED IN SPARAM.) */ + +/* THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */ +/* INEXACT. THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */ +/* OF SD1 AND SD2. ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */ + + +/* Arguments */ +/* ========= */ + + +/* SD1 (input/output) REAL */ + +/* SD2 (input/output) REAL */ + +/* SX1 (input/output) REAL */ + +/* SY1 (input) REAL */ + + +/* SPARAM (input/output) REAL array, dimension 5 */ +/* SPARAM(1)=SFLAG */ +/* SPARAM(2)=SH11 */ +/* SPARAM(3)=SH21 */ +/* SPARAM(4)=SH12 */ +/* SPARAM(5)=SH22 */ + +/* ===================================================================== */ + +/* .. Local Scalars .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ +/* .. Data statements .. */ + + /* Parameter adjustments */ + --sparam; + + /* Function Body */ +/* .. */ + if (! (*sd1 < zero)) { + goto L10; + } +/* GO ZERO-H-D-AND-SX1.. */ + goto L60; +L10: +/* CASE-SD1-NONNEGATIVE */ + sp2 = *sd2 * *sy1; + if (! (sp2 == zero)) { + goto L20; + } + sflag = -two; + goto L260; +/* REGULAR-CASE.. */ +L20: + sp1 = *sd1 * *sx1; + sq2 = sp2 * *sy1; + sq1 = sp1 * *sx1; + + if (! (dabs(sq1) > dabs(sq2))) { + goto L40; + } + sh21 = -(*sy1) / *sx1; + sh12 = sp2 / sp1; + + su = one - sh12 * sh21; + + if (! (su <= zero)) { + goto L30; + } +/* GO ZERO-H-D-AND-SX1.. */ + goto L60; +L30: + sflag = zero; + *sd1 /= su; + *sd2 /= su; + *sx1 *= su; +/* GO SCALE-CHECK.. */ + goto L100; +L40: + if (! (sq2 < zero)) { + goto L50; + } +/* GO ZERO-H-D-AND-SX1.. */ + goto L60; +L50: + sflag = one; + sh11 = sp1 / sp2; + sh22 = *sx1 / *sy1; + su = one + sh11 * sh22; + stemp = *sd2 / su; + *sd2 = *sd1 / su; + *sd1 = stemp; + *sx1 = *sy1 * su; +/* GO SCALE-CHECK */ + goto L100; +/* PROCEDURE..ZERO-H-D-AND-SX1.. */ +L60: + sflag = -one; + sh11 = zero; + sh12 = zero; + sh21 = zero; + sh22 = zero; + + *sd1 = zero; + *sd2 = zero; + *sx1 = zero; +/* RETURN.. */ + goto L220; +/* PROCEDURE..FIX-H.. */ +L70: + if (! (sflag >= zero)) { + goto L90; + } + + if (! (sflag == zero)) { + goto L80; + } + sh11 = one; + sh22 = one; + sflag = -one; + goto L90; +L80: + sh21 = -one; + sh12 = one; + sflag = -one; +L90: + switch (igo) { + case 0: goto L120; + case 1: goto L150; + case 2: goto L180; + case 3: goto L210; + } +/* PROCEDURE..SCALE-CHECK */ +L100: +L110: + if (! (*sd1 <= rgamsq)) { + goto L130; + } + if (*sd1 == zero) { + goto L160; + } + igo = 0; + igo_fmt = fmt_120; +/* FIX-H.. */ + goto L70; +L120: +/* Computing 2nd power */ + r__1 = gam; + *sd1 *= r__1 * r__1; + *sx1 /= gam; + sh11 /= gam; + sh12 /= gam; + goto L110; +L130: +L140: + if (! (*sd1 >= gamsq)) { + goto L160; + } + igo = 1; + igo_fmt = fmt_150; +/* FIX-H.. */ + goto L70; +L150: +/* Computing 2nd power */ + r__1 = gam; + *sd1 /= r__1 * r__1; + *sx1 *= gam; + sh11 *= gam; + sh12 *= gam; + goto L140; +L160: +L170: + if (! (dabs(*sd2) <= rgamsq)) { + goto L190; + } + if (*sd2 == zero) { + goto L220; + } + igo = 2; + igo_fmt = fmt_180; +/* FIX-H.. */ + goto L70; +L180: +/* Computing 2nd power */ + r__1 = gam; + *sd2 *= r__1 * r__1; + sh21 /= gam; + sh22 /= gam; + goto L170; +L190: +L200: + if (! (dabs(*sd2) >= gamsq)) { + goto L220; + } + igo = 3; + igo_fmt = fmt_210; +/* FIX-H.. */ + goto L70; +L210: +/* Computing 2nd power */ + r__1 = gam; + *sd2 /= r__1 * r__1; + sh21 *= gam; + sh22 *= gam; + goto L200; +L220: + if (sflag < 0.f) { + goto L250; + } else if (sflag == 0) { + goto L230; + } else { + goto L240; + } +L230: + sparam[3] = sh21; + sparam[4] = sh12; + goto L260; +L240: + sparam[2] = sh11; + sparam[5] = sh22; + goto L260; +L250: + sparam[2] = sh11; + sparam[3] = sh21; + sparam[4] = sh12; + sparam[5] = sh22; +L260: + sparam[1] = sflag; + return 0; +} /* srotmg_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/ssbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/ssbmv.c new file mode 100644 index 000000000..8599325f2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/ssbmv.c @@ -0,0 +1,368 @@ +/* ssbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int ssbmv_(char *uplo, integer *n, integer *k, real *alpha, + real *a, integer *lda, real *x, integer *incx, real *beta, real *y, + integer *incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4; + + /* Local variables */ + integer i__, j, l, ix, iy, jx, jy, kx, ky, info; + real temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* SSBMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n symmetric band matrix, with k super-diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the band matrix A is being supplied as */ +/* follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* being supplied. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* being supplied. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry, K specifies the number of super-diagonals of the */ +/* matrix A. K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* ALPHA - REAL . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* A - REAL array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the symmetric matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer the upper */ +/* triangular part of a symmetric band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the symmetric matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer the lower */ +/* triangular part of a symmetric band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - REAL array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the */ +/* vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - REAL . */ +/* On entry, BETA specifies the scalar beta. */ +/* Unchanged on exit. */ + +/* Y - REAL array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the */ +/* vector y. On exit, Y is overwritten by the updated vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + --y; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*k < 0) { + info = 3; + } else if (*lda < *k + 1) { + info = 6; + } else if (*incx == 0) { + info = 8; + } else if (*incy == 0) { + info = 11; + } + if (info != 0) { + xerbla_("SSBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array A */ +/* are accessed sequentially with one pass through A. */ + +/* First form y := beta*y. */ + + if (*beta != 1.f) { + if (*incy == 1) { + if (*beta == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = 0.f; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = *beta * y[i__]; +/* L20: */ + } + } + } else { + iy = ky; + if (*beta == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = 0.f; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = *beta * y[iy]; + iy += *incy; +/* L40: */ + } + } + } + } + if (*alpha == 0.f) { + return 0; + } + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when upper triangle of A is stored. */ + + kplus1 = *k + 1; + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.f; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + y[i__] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[i__]; +/* L50: */ + } + y[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.f; + ix = kx; + iy = ky; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + y[iy] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[ix]; + ix += *incx; + iy += *incy; +/* L70: */ + } + y[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * + temp2; + jx += *incx; + jy += *incy; + if (j > *k) { + kx += *incx; + ky += *incy; + } +/* L80: */ + } + } + } else { + +/* Form y when lower triangle of A is stored. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.f; + y[j] += temp1 * a[j * a_dim1 + 1]; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + y[i__] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[i__]; +/* L90: */ + } + y[j] += *alpha * temp2; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.f; + y[jy] += temp1 * a[j * a_dim1 + 1]; + l = 1 - j; + ix = jx; + iy = jy; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + ix += *incx; + iy += *incy; + y[iy] += temp1 * a[l + i__ + j * a_dim1]; + temp2 += a[l + i__ + j * a_dim1] * x[ix]; +/* L110: */ + } + y[jy] += *alpha * temp2; + jx += *incx; + jy += *incy; +/* L120: */ + } + } + } + + return 0; + +/* End of SSBMV . */ + +} /* ssbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/sspmv.c b/gtsam/3rdparty/Eigen/blas/f2c/sspmv.c new file mode 100644 index 000000000..47858ec6c --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/sspmv.c @@ -0,0 +1,316 @@ +/* sspmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int sspmv_(char *uplo, integer *n, real *alpha, real *ap, + real *x, integer *incx, real *beta, real *y, integer *incy, ftnlen + uplo_len) +{ + /* System generated locals */ + integer i__1, i__2; + + /* Local variables */ + integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info; + real temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* SSPMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n symmetric matrix, supplied in packed form. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the matrix A is supplied in the packed */ +/* array AP as follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* supplied in AP. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* supplied in AP. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* ALPHA - REAL . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* AP - REAL array of DIMENSION at least */ +/* ( ( n*( n + 1 ) )/2 ). */ +/* Before entry with UPLO = 'U' or 'u', the array AP must */ +/* contain the upper triangular part of the symmetric matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */ +/* and a( 2, 2 ) respectively, and so on. */ +/* Before entry with UPLO = 'L' or 'l', the array AP must */ +/* contain the lower triangular part of the symmetric matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */ +/* and a( 3, 1 ) respectively, and so on. */ +/* Unchanged on exit. */ + +/* X - REAL array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - REAL . */ +/* On entry, BETA specifies the scalar beta. When BETA is */ +/* supplied as zero then Y need not be set on input. */ +/* Unchanged on exit. */ + +/* Y - REAL array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the n */ +/* element vector y. On exit, Y is overwritten by the updated */ +/* vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + --y; + --x; + --ap; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*incx == 0) { + info = 6; + } else if (*incy == 0) { + info = 9; + } + if (info != 0) { + xerbla_("SSPMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array AP */ +/* are accessed sequentially with one pass through AP. */ + +/* First form y := beta*y. */ + + if (*beta != 1.f) { + if (*incy == 1) { + if (*beta == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = 0.f; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[i__] = *beta * y[i__]; +/* L20: */ + } + } + } else { + iy = ky; + if (*beta == 0.f) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = 0.f; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + y[iy] = *beta * y[iy]; + iy += *incy; +/* L40: */ + } + } + } + } + if (*alpha == 0.f) { + return 0; + } + kk = 1; + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when AP contains the upper triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.f; + k = kk; + i__2 = j - 1; + for (i__ = 1; i__ <= i__2; ++i__) { + y[i__] += temp1 * ap[k]; + temp2 += ap[k] * x[i__]; + ++k; +/* L50: */ + } + y[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2; + kk += j; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.f; + ix = kx; + iy = ky; + i__2 = kk + j - 2; + for (k = kk; k <= i__2; ++k) { + y[iy] += temp1 * ap[k]; + temp2 += ap[k] * x[ix]; + ix += *incx; + iy += *incy; +/* L70: */ + } + y[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2; + jx += *incx; + jy += *incy; + kk += j; +/* L80: */ + } + } + } else { + +/* Form y when AP contains the lower triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[j]; + temp2 = 0.f; + y[j] += temp1 * ap[kk]; + k = kk + 1; + i__2 = *n; + for (i__ = j + 1; i__ <= i__2; ++i__) { + y[i__] += temp1 * ap[k]; + temp2 += ap[k] * x[i__]; + ++k; +/* L90: */ + } + y[j] += *alpha * temp2; + kk += *n - j + 1; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + temp1 = *alpha * x[jx]; + temp2 = 0.f; + y[jy] += temp1 * ap[kk]; + ix = jx; + iy = jy; + i__2 = kk + *n - j; + for (k = kk + 1; k <= i__2; ++k) { + ix += *incx; + iy += *incy; + y[iy] += temp1 * ap[k]; + temp2 += ap[k] * x[ix]; +/* L110: */ + } + y[jy] += *alpha * temp2; + jx += *incx; + jy += *incy; + kk += *n - j + 1; +/* L120: */ + } + } + } + + return 0; + +/* End of SSPMV . */ + +} /* sspmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/stbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/stbmv.c new file mode 100644 index 000000000..fcf9ce336 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/stbmv.c @@ -0,0 +1,428 @@ +/* stbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int stbmv_(char *uplo, char *trans, char *diag, integer *n, + integer *k, real *a, integer *lda, real *x, integer *incx, ftnlen + uplo_len, ftnlen trans_len, ftnlen diag_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4; + + /* Local variables */ + integer i__, j, l, ix, jx, kx, info; + real temp; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + logical nounit; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* STBMV performs one of the matrix-vector operations */ + +/* x := A*x, or x := A'*x, */ + +/* where x is an n element vector and A is an n by n unit, or non-unit, */ +/* upper or lower triangular band matrix, with ( k + 1 ) diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the matrix is an upper or */ +/* lower triangular matrix as follows: */ + +/* UPLO = 'U' or 'u' A is an upper triangular matrix. */ + +/* UPLO = 'L' or 'l' A is a lower triangular matrix. */ + +/* Unchanged on exit. */ + +/* TRANS - CHARACTER*1. */ +/* On entry, TRANS specifies the operation to be performed as */ +/* follows: */ + +/* TRANS = 'N' or 'n' x := A*x. */ + +/* TRANS = 'T' or 't' x := A'*x. */ + +/* TRANS = 'C' or 'c' x := A'*x. */ + +/* Unchanged on exit. */ + +/* DIAG - CHARACTER*1. */ +/* On entry, DIAG specifies whether or not A is unit */ +/* triangular as follows: */ + +/* DIAG = 'U' or 'u' A is assumed to be unit triangular. */ + +/* DIAG = 'N' or 'n' A is not assumed to be unit */ +/* triangular. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry with UPLO = 'U' or 'u', K specifies the number of */ +/* super-diagonals of the matrix A. */ +/* On entry with UPLO = 'L' or 'l', K specifies the number of */ +/* sub-diagonals of the matrix A. */ +/* K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* A - REAL array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer an upper */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer a lower */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that when DIAG = 'U' or 'u' the elements of the array A */ +/* corresponding to the diagonal elements of the matrix are not */ +/* referenced, but are assumed to be unity. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - REAL array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. On exit, X is overwritten with the */ +/* tranformed vector x. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (! lsame_(trans, "N", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, + "T", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, "C", (ftnlen)1, ( + ftnlen)1)) { + info = 2; + } else if (! lsame_(diag, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, + "N", (ftnlen)1, (ftnlen)1)) { + info = 3; + } else if (*n < 0) { + info = 4; + } else if (*k < 0) { + info = 5; + } else if (*lda < *k + 1) { + info = 7; + } else if (*incx == 0) { + info = 9; + } + if (info != 0) { + xerbla_("STBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0) { + return 0; + } + + nounit = lsame_(diag, "N", (ftnlen)1, (ftnlen)1); + +/* Set up the start point in X if the increment is not unity. This */ +/* will be ( N - 1 )*INCX too small for descending loops. */ + + if (*incx <= 0) { + kx = 1 - (*n - 1) * *incx; + } else if (*incx != 1) { + kx = 1; + } + +/* Start the operations. In this version the elements of A are */ +/* accessed sequentially with one pass through A. */ + + if (lsame_(trans, "N", (ftnlen)1, (ftnlen)1)) { + +/* Form x := A*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + if (x[j] != 0.f) { + temp = x[j]; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + x[i__] += temp * a[l + i__ + j * a_dim1]; +/* L10: */ + } + if (nounit) { + x[j] *= a[kplus1 + j * a_dim1]; + } + } +/* L20: */ + } + } else { + jx = kx; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + if (x[jx] != 0.f) { + temp = x[jx]; + ix = kx; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + x[ix] += temp * a[l + i__ + j * a_dim1]; + ix += *incx; +/* L30: */ + } + if (nounit) { + x[jx] *= a[kplus1 + j * a_dim1]; + } + } + jx += *incx; + if (j > *k) { + kx += *incx; + } +/* L40: */ + } + } + } else { + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + if (x[j] != 0.f) { + temp = x[j]; + l = 1 - j; +/* Computing MIN */ + i__1 = *n, i__3 = j + *k; + i__4 = j + 1; + for (i__ = min(i__1,i__3); i__ >= i__4; --i__) { + x[i__] += temp * a[l + i__ + j * a_dim1]; +/* L50: */ + } + if (nounit) { + x[j] *= a[j * a_dim1 + 1]; + } + } +/* L60: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + if (x[jx] != 0.f) { + temp = x[jx]; + ix = kx; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__1 = j + *k; + i__3 = j + 1; + for (i__ = min(i__4,i__1); i__ >= i__3; --i__) { + x[ix] += temp * a[l + i__ + j * a_dim1]; + ix -= *incx; +/* L70: */ + } + if (nounit) { + x[jx] *= a[j * a_dim1 + 1]; + } + } + jx -= *incx; + if (*n - j >= *k) { + kx -= *incx; + } +/* L80: */ + } + } + } + } else { + +/* Form x := A'*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + temp = x[j]; + l = kplus1 - j; + if (nounit) { + temp *= a[kplus1 + j * a_dim1]; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + temp += a[l + i__ + j * a_dim1] * x[i__]; +/* L90: */ + } + x[j] = temp; +/* L100: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + temp = x[jx]; + kx -= *incx; + ix = kx; + l = kplus1 - j; + if (nounit) { + temp *= a[kplus1 + j * a_dim1]; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + temp += a[l + i__ + j * a_dim1] * x[ix]; + ix -= *incx; +/* L110: */ + } + x[jx] = temp; + jx -= *incx; +/* L120: */ + } + } + } else { + if (*incx == 1) { + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + temp = x[j]; + l = 1 - j; + if (nounit) { + temp *= a[j * a_dim1 + 1]; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + temp += a[l + i__ + j * a_dim1] * x[i__]; +/* L130: */ + } + x[j] = temp; +/* L140: */ + } + } else { + jx = kx; + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + temp = x[jx]; + kx += *incx; + ix = kx; + l = 1 - j; + if (nounit) { + temp *= a[j * a_dim1 + 1]; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + temp += a[l + i__ + j * a_dim1] * x[ix]; + ix += *incx; +/* L150: */ + } + x[jx] = temp; + jx += *incx; +/* L160: */ + } + } + } + } + + return 0; + +/* End of STBMV . */ + +} /* stbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/zhbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/zhbmv.c new file mode 100644 index 000000000..42da13dbb --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/zhbmv.c @@ -0,0 +1,488 @@ +/* zhbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int zhbmv_(char *uplo, integer *n, integer *k, doublecomplex + *alpha, doublecomplex *a, integer *lda, doublecomplex *x, integer * + incx, doublecomplex *beta, doublecomplex *y, integer *incy, ftnlen + uplo_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5; + doublereal d__1; + doublecomplex z__1, z__2, z__3, z__4; + + /* Builtin functions */ + void d_cnjg(doublecomplex *, doublecomplex *); + + /* Local variables */ + integer i__, j, l, ix, iy, jx, jy, kx, ky, info; + doublecomplex temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* ZHBMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n hermitian band matrix, with k super-diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the band matrix A is being supplied as */ +/* follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* being supplied. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* being supplied. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry, K specifies the number of super-diagonals of the */ +/* matrix A. K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* ALPHA - COMPLEX*16 . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* A - COMPLEX*16 array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the hermitian matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer the upper */ +/* triangular part of a hermitian band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the hermitian matrix, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer the lower */ +/* triangular part of a hermitian band matrix from conventional */ +/* full matrix storage to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that the imaginary parts of the diagonal elements need */ +/* not be set and are assumed to be zero. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - COMPLEX*16 array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the */ +/* vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - COMPLEX*16 . */ +/* On entry, BETA specifies the scalar beta. */ +/* Unchanged on exit. */ + +/* Y - COMPLEX*16 array of DIMENSION at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the */ +/* vector y. On exit, Y is overwritten by the updated vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + --y; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*k < 0) { + info = 3; + } else if (*lda < *k + 1) { + info = 6; + } else if (*incx == 0) { + info = 8; + } else if (*incy == 0) { + info = 11; + } + if (info != 0) { + xerbla_("ZHBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && + beta->i == 0.))) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array A */ +/* are accessed sequentially with one pass through A. */ + +/* First form y := beta*y. */ + + if (beta->r != 1. || beta->i != 0.) { + if (*incy == 1) { + if (beta->r == 0. && beta->i == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + y[i__2].r = 0., y[i__2].i = 0.; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + i__3 = i__; + z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + z__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; +/* L20: */ + } + } + } else { + iy = ky; + if (beta->r == 0. && beta->i == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + y[i__2].r = 0., y[i__2].i = 0.; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + i__3 = iy; + z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + z__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + iy += *incy; +/* L40: */ + } + } + } + } + if (alpha->r == 0. && alpha->i == 0.) { + return 0; + } + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when upper triangle of A is stored. */ + + kplus1 = *k + 1; + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + z__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + i__2 = i__; + i__3 = i__; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__2 = i__; + z__2.r = z__3.r * x[i__2].r - z__3.i * x[i__2].i, z__2.i = + z__3.r * x[i__2].i + z__3.i * x[i__2].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; +/* L50: */ + } + i__4 = j; + i__2 = j; + i__3 = kplus1 + j * a_dim1; + d__1 = a[i__3].r; + z__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i; + z__2.r = y[i__2].r + z__3.r, z__2.i = y[i__2].i + z__3.i; + z__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i; + y[i__4].r = z__1.r, y[i__4].i = z__1.i; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__4 = jx; + z__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, z__1.i = + alpha->r * x[i__4].i + alpha->i * x[i__4].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + ix = kx; + iy = ky; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + i__4 = iy; + i__2 = iy; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i; + y[i__4].r = z__1.r, y[i__4].i = z__1.i; + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i = + z__3.r * x[i__4].i + z__3.i * x[i__4].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; + ix += *incx; + iy += *incy; +/* L70: */ + } + i__3 = jy; + i__4 = jy; + i__2 = kplus1 + j * a_dim1; + d__1 = a[i__2].r; + z__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i; + z__2.r = y[i__4].r + z__3.r, z__2.i = y[i__4].i + z__3.i; + z__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + jx += *incx; + jy += *incy; + if (j > *k) { + kx += *incx; + ky += *incy; + } +/* L80: */ + } + } + } else { + +/* Form y when lower triangle of A is stored. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__3 = j; + z__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i = + alpha->r * x[i__3].i + alpha->i * x[i__3].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + i__3 = j; + i__4 = j; + i__2 = j * a_dim1 + 1; + d__1 = a[i__2].r; + z__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + i__4 = i__; + i__2 = i__; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i; + y[i__4].r = z__1.r, y[i__4].i = z__1.i; + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__4 = i__; + z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i = + z__3.r * x[i__4].i + z__3.i * x[i__4].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; +/* L90: */ + } + i__3 = j; + i__4 = j; + z__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__3 = jx; + z__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i = + alpha->r * x[i__3].i + alpha->i * x[i__3].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + i__3 = jy; + i__4 = jy; + i__2 = j * a_dim1 + 1; + d__1 = a[i__2].r; + z__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + l = 1 - j; + ix = jx; + iy = jy; +/* Computing MIN */ + i__4 = *n, i__2 = j + *k; + i__3 = min(i__4,i__2); + for (i__ = j + 1; i__ <= i__3; ++i__) { + ix += *incx; + iy += *incy; + i__4 = iy; + i__2 = iy; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, + z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5] + .r; + z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i; + y[i__4].r = z__1.r, y[i__4].i = z__1.i; + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i = + z__3.r * x[i__4].i + z__3.i * x[i__4].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; +/* L110: */ + } + i__3 = jy; + i__4 = jy; + z__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + jx += *incx; + jy += *incy; +/* L120: */ + } + } + } + + return 0; + +/* End of ZHBMV . */ + +} /* zhbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/zhpmv.c b/gtsam/3rdparty/Eigen/blas/f2c/zhpmv.c new file mode 100644 index 000000000..fbe2f42b3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/zhpmv.c @@ -0,0 +1,438 @@ +/* zhpmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int zhpmv_(char *uplo, integer *n, doublecomplex *alpha, + doublecomplex *ap, doublecomplex *x, integer *incx, doublecomplex * + beta, doublecomplex *y, integer *incy, ftnlen uplo_len) +{ + /* System generated locals */ + integer i__1, i__2, i__3, i__4, i__5; + doublereal d__1; + doublecomplex z__1, z__2, z__3, z__4; + + /* Builtin functions */ + void d_cnjg(doublecomplex *, doublecomplex *); + + /* Local variables */ + integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info; + doublecomplex temp1, temp2; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* ZHPMV performs the matrix-vector operation */ + +/* y := alpha*A*x + beta*y, */ + +/* where alpha and beta are scalars, x and y are n element vectors and */ +/* A is an n by n hermitian matrix, supplied in packed form. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the upper or lower */ +/* triangular part of the matrix A is supplied in the packed */ +/* array AP as follows: */ + +/* UPLO = 'U' or 'u' The upper triangular part of A is */ +/* supplied in AP. */ + +/* UPLO = 'L' or 'l' The lower triangular part of A is */ +/* supplied in AP. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* ALPHA - COMPLEX*16 . */ +/* On entry, ALPHA specifies the scalar alpha. */ +/* Unchanged on exit. */ + +/* AP - COMPLEX*16 array of DIMENSION at least */ +/* ( ( n*( n + 1 ) )/2 ). */ +/* Before entry with UPLO = 'U' or 'u', the array AP must */ +/* contain the upper triangular part of the hermitian matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */ +/* and a( 2, 2 ) respectively, and so on. */ +/* Before entry with UPLO = 'L' or 'l', the array AP must */ +/* contain the lower triangular part of the hermitian matrix */ +/* packed sequentially, column by column, so that AP( 1 ) */ +/* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */ +/* and a( 3, 1 ) respectively, and so on. */ +/* Note that the imaginary parts of the diagonal elements need */ +/* not be set and are assumed to be zero. */ +/* Unchanged on exit. */ + +/* X - COMPLEX*16 array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. */ +/* Unchanged on exit. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* BETA - COMPLEX*16 . */ +/* On entry, BETA specifies the scalar beta. When BETA is */ +/* supplied as zero then Y need not be set on input. */ +/* Unchanged on exit. */ + +/* Y - COMPLEX*16 array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCY ) ). */ +/* Before entry, the incremented array Y must contain the n */ +/* element vector y. On exit, Y is overwritten by the updated */ +/* vector y. */ + +/* INCY - INTEGER. */ +/* On entry, INCY specifies the increment for the elements of */ +/* Y. INCY must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + --y; + --x; + --ap; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (*n < 0) { + info = 2; + } else if (*incx == 0) { + info = 6; + } else if (*incy == 0) { + info = 9; + } + if (info != 0) { + xerbla_("ZHPMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && + beta->i == 0.))) { + return 0; + } + +/* Set up the start points in X and Y. */ + + if (*incx > 0) { + kx = 1; + } else { + kx = 1 - (*n - 1) * *incx; + } + if (*incy > 0) { + ky = 1; + } else { + ky = 1 - (*n - 1) * *incy; + } + +/* Start the operations. In this version the elements of the array AP */ +/* are accessed sequentially with one pass through AP. */ + +/* First form y := beta*y. */ + + if (beta->r != 1. || beta->i != 0.) { + if (*incy == 1) { + if (beta->r == 0. && beta->i == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + y[i__2].r = 0., y[i__2].i = 0.; +/* L10: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = i__; + i__3 = i__; + z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + z__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; +/* L20: */ + } + } + } else { + iy = ky; + if (beta->r == 0. && beta->i == 0.) { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + y[i__2].r = 0., y[i__2].i = 0.; + iy += *incy; +/* L30: */ + } + } else { + i__1 = *n; + for (i__ = 1; i__ <= i__1; ++i__) { + i__2 = iy; + i__3 = iy; + z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, + z__1.i = beta->r * y[i__3].i + beta->i * y[i__3] + .r; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + iy += *incy; +/* L40: */ + } + } + } + } + if (alpha->r == 0. && alpha->i == 0.) { + return 0; + } + kk = 1; + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + +/* Form y when AP contains the upper triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + z__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + k = kk; + i__2 = j - 1; + for (i__ = 1; i__ <= i__2; ++i__) { + i__3 = i__; + i__4 = i__; + i__5 = k; + z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + d_cnjg(&z__3, &ap[k]); + i__3 = i__; + z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i = + z__3.r * x[i__3].i + z__3.i * x[i__3].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; + ++k; +/* L50: */ + } + i__2 = j; + i__3 = j; + i__4 = kk + j - 1; + d__1 = ap[i__4].r; + z__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i; + z__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i; + z__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + kk += j; +/* L60: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = jx; + z__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + ix = kx; + iy = ky; + i__2 = kk + j - 2; + for (k = kk; k <= i__2; ++k) { + i__3 = iy; + i__4 = iy; + i__5 = k; + z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + d_cnjg(&z__3, &ap[k]); + i__3 = ix; + z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i = + z__3.r * x[i__3].i + z__3.i * x[i__3].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; + ix += *incx; + iy += *incy; +/* L70: */ + } + i__2 = jy; + i__3 = jy; + i__4 = kk + j - 1; + d__1 = ap[i__4].r; + z__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i; + z__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i; + z__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + jx += *incx; + jy += *incy; + kk += j; +/* L80: */ + } + } + } else { + +/* Form y when AP contains the lower triangle. */ + + if (*incx == 1 && *incy == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + z__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + i__2 = j; + i__3 = j; + i__4 = kk; + d__1 = ap[i__4].r; + z__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i; + z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + k = kk + 1; + i__2 = *n; + for (i__ = j + 1; i__ <= i__2; ++i__) { + i__3 = i__; + i__4 = i__; + i__5 = k; + z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + d_cnjg(&z__3, &ap[k]); + i__3 = i__; + z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i = + z__3.r * x[i__3].i + z__3.i * x[i__3].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; + ++k; +/* L90: */ + } + i__2 = j; + i__3 = j; + z__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + kk += *n - j + 1; +/* L100: */ + } + } else { + jx = kx; + jy = ky; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = jx; + z__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i = + alpha->r * x[i__2].i + alpha->i * x[i__2].r; + temp1.r = z__1.r, temp1.i = z__1.i; + temp2.r = 0., temp2.i = 0.; + i__2 = jy; + i__3 = jy; + i__4 = kk; + d__1 = ap[i__4].r; + z__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i; + z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + ix = jx; + iy = jy; + i__2 = kk + *n - j; + for (k = kk + 1; k <= i__2; ++k) { + ix += *incx; + iy += *incy; + i__3 = iy; + i__4 = iy; + i__5 = k; + z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, + z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5] + .r; + z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i; + y[i__3].r = z__1.r, y[i__3].i = z__1.i; + d_cnjg(&z__3, &ap[k]); + i__3 = ix; + z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i = + z__3.r * x[i__3].i + z__3.i * x[i__3].r; + z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i; + temp2.r = z__1.r, temp2.i = z__1.i; +/* L110: */ + } + i__2 = jy; + i__3 = jy; + z__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = + alpha->r * temp2.i + alpha->i * temp2.r; + z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i; + y[i__2].r = z__1.r, y[i__2].i = z__1.i; + jx += *incx; + jy += *incy; + kk += *n - j + 1; +/* L120: */ + } + } + } + + return 0; + +/* End of ZHPMV . */ + +} /* zhpmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/f2c/ztbmv.c b/gtsam/3rdparty/Eigen/blas/f2c/ztbmv.c new file mode 100644 index 000000000..4cdcd7f88 --- /dev/null +++ b/gtsam/3rdparty/Eigen/blas/f2c/ztbmv.c @@ -0,0 +1,647 @@ +/* ztbmv.f -- translated by f2c (version 20100827). + You must link the resulting object file with libf2c: + on Microsoft Windows system, link with libf2c.lib; + on Linux or Unix systems, link with .../path/to/libf2c.a -lm + or, if you install libf2c.a in a standard place, with -lf2c -lm + -- in that order, at the end of the command line, as in + cc *.o -lf2c -lm + Source for libf2c is in /netlib/f2c/libf2c.zip, e.g., + + http://www.netlib.org/f2c/libf2c.zip +*/ + +#include "datatypes.h" + +/* Subroutine */ int ztbmv_(char *uplo, char *trans, char *diag, integer *n, + integer *k, doublecomplex *a, integer *lda, doublecomplex *x, integer + *incx, ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len) +{ + /* System generated locals */ + integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5; + doublecomplex z__1, z__2, z__3; + + /* Builtin functions */ + void d_cnjg(doublecomplex *, doublecomplex *); + + /* Local variables */ + integer i__, j, l, ix, jx, kx, info; + doublecomplex temp; + extern logical lsame_(char *, char *, ftnlen, ftnlen); + integer kplus1; + extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen); + logical noconj, nounit; + +/* .. Scalar Arguments .. */ +/* .. */ +/* .. Array Arguments .. */ +/* .. */ + +/* Purpose */ +/* ======= */ + +/* ZTBMV performs one of the matrix-vector operations */ + +/* x := A*x, or x := A'*x, or x := conjg( A' )*x, */ + +/* where x is an n element vector and A is an n by n unit, or non-unit, */ +/* upper or lower triangular band matrix, with ( k + 1 ) diagonals. */ + +/* Arguments */ +/* ========== */ + +/* UPLO - CHARACTER*1. */ +/* On entry, UPLO specifies whether the matrix is an upper or */ +/* lower triangular matrix as follows: */ + +/* UPLO = 'U' or 'u' A is an upper triangular matrix. */ + +/* UPLO = 'L' or 'l' A is a lower triangular matrix. */ + +/* Unchanged on exit. */ + +/* TRANS - CHARACTER*1. */ +/* On entry, TRANS specifies the operation to be performed as */ +/* follows: */ + +/* TRANS = 'N' or 'n' x := A*x. */ + +/* TRANS = 'T' or 't' x := A'*x. */ + +/* TRANS = 'C' or 'c' x := conjg( A' )*x. */ + +/* Unchanged on exit. */ + +/* DIAG - CHARACTER*1. */ +/* On entry, DIAG specifies whether or not A is unit */ +/* triangular as follows: */ + +/* DIAG = 'U' or 'u' A is assumed to be unit triangular. */ + +/* DIAG = 'N' or 'n' A is not assumed to be unit */ +/* triangular. */ + +/* Unchanged on exit. */ + +/* N - INTEGER. */ +/* On entry, N specifies the order of the matrix A. */ +/* N must be at least zero. */ +/* Unchanged on exit. */ + +/* K - INTEGER. */ +/* On entry with UPLO = 'U' or 'u', K specifies the number of */ +/* super-diagonals of the matrix A. */ +/* On entry with UPLO = 'L' or 'l', K specifies the number of */ +/* sub-diagonals of the matrix A. */ +/* K must satisfy 0 .le. K. */ +/* Unchanged on exit. */ + +/* A - COMPLEX*16 array of DIMENSION ( LDA, n ). */ +/* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */ +/* by n part of the array A must contain the upper triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row */ +/* ( k + 1 ) of the array, the first super-diagonal starting at */ +/* position 2 in row k, and so on. The top left k by k triangle */ +/* of the array A is not referenced. */ +/* The following program segment will transfer an upper */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = K + 1 - J */ +/* DO 10, I = MAX( 1, J - K ), J */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */ +/* by n part of the array A must contain the lower triangular */ +/* band part of the matrix of coefficients, supplied column by */ +/* column, with the leading diagonal of the matrix in row 1 of */ +/* the array, the first sub-diagonal starting at position 1 in */ +/* row 2, and so on. The bottom right k by k triangle of the */ +/* array A is not referenced. */ +/* The following program segment will transfer a lower */ +/* triangular band matrix from conventional full matrix storage */ +/* to band storage: */ + +/* DO 20, J = 1, N */ +/* M = 1 - J */ +/* DO 10, I = J, MIN( N, J + K ) */ +/* A( M + I, J ) = matrix( I, J ) */ +/* 10 CONTINUE */ +/* 20 CONTINUE */ + +/* Note that when DIAG = 'U' or 'u' the elements of the array A */ +/* corresponding to the diagonal elements of the matrix are not */ +/* referenced, but are assumed to be unity. */ +/* Unchanged on exit. */ + +/* LDA - INTEGER. */ +/* On entry, LDA specifies the first dimension of A as declared */ +/* in the calling (sub) program. LDA must be at least */ +/* ( k + 1 ). */ +/* Unchanged on exit. */ + +/* X - COMPLEX*16 array of dimension at least */ +/* ( 1 + ( n - 1 )*abs( INCX ) ). */ +/* Before entry, the incremented array X must contain the n */ +/* element vector x. On exit, X is overwritten with the */ +/* tranformed vector x. */ + +/* INCX - INTEGER. */ +/* On entry, INCX specifies the increment for the elements of */ +/* X. INCX must not be zero. */ +/* Unchanged on exit. */ + +/* Further Details */ +/* =============== */ + +/* Level 2 Blas routine. */ + +/* -- Written on 22-October-1986. */ +/* Jack Dongarra, Argonne National Lab. */ +/* Jeremy Du Croz, Nag Central Office. */ +/* Sven Hammarling, Nag Central Office. */ +/* Richard Hanson, Sandia National Labs. */ + +/* ===================================================================== */ + +/* .. Parameters .. */ +/* .. */ +/* .. Local Scalars .. */ +/* .. */ +/* .. External Functions .. */ +/* .. */ +/* .. External Subroutines .. */ +/* .. */ +/* .. Intrinsic Functions .. */ +/* .. */ + +/* Test the input parameters. */ + + /* Parameter adjustments */ + a_dim1 = *lda; + a_offset = 1 + a_dim1; + a -= a_offset; + --x; + + /* Function Body */ + info = 0; + if (! lsame_(uplo, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, "L", ( + ftnlen)1, (ftnlen)1)) { + info = 1; + } else if (! lsame_(trans, "N", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, + "T", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, "C", (ftnlen)1, ( + ftnlen)1)) { + info = 2; + } else if (! lsame_(diag, "U", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, + "N", (ftnlen)1, (ftnlen)1)) { + info = 3; + } else if (*n < 0) { + info = 4; + } else if (*k < 0) { + info = 5; + } else if (*lda < *k + 1) { + info = 7; + } else if (*incx == 0) { + info = 9; + } + if (info != 0) { + xerbla_("ZTBMV ", &info, (ftnlen)6); + return 0; + } + +/* Quick return if possible. */ + + if (*n == 0) { + return 0; + } + + noconj = lsame_(trans, "T", (ftnlen)1, (ftnlen)1); + nounit = lsame_(diag, "N", (ftnlen)1, (ftnlen)1); + +/* Set up the start point in X if the increment is not unity. This */ +/* will be ( N - 1 )*INCX too small for descending loops. */ + + if (*incx <= 0) { + kx = 1 - (*n - 1) * *incx; + } else if (*incx != 1) { + kx = 1; + } + +/* Start the operations. In this version the elements of A are */ +/* accessed sequentially with one pass through A. */ + + if (lsame_(trans, "N", (ftnlen)1, (ftnlen)1)) { + +/* Form x := A*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__2 = j; + if (x[i__2].r != 0. || x[i__2].i != 0.) { + i__2 = j; + temp.r = x[i__2].r, temp.i = x[i__2].i; + l = kplus1 - j; +/* Computing MAX */ + i__2 = 1, i__3 = j - *k; + i__4 = j - 1; + for (i__ = max(i__2,i__3); i__ <= i__4; ++i__) { + i__2 = i__; + i__3 = i__; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, + z__2.i = temp.r * a[i__5].i + temp.i * a[ + i__5].r; + z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + + z__2.i; + x[i__2].r = z__1.r, x[i__2].i = z__1.i; +/* L10: */ + } + if (nounit) { + i__4 = j; + i__2 = j; + i__3 = kplus1 + j * a_dim1; + z__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[ + i__3].i, z__1.i = x[i__2].r * a[i__3].i + + x[i__2].i * a[i__3].r; + x[i__4].r = z__1.r, x[i__4].i = z__1.i; + } + } +/* L20: */ + } + } else { + jx = kx; + i__1 = *n; + for (j = 1; j <= i__1; ++j) { + i__4 = jx; + if (x[i__4].r != 0. || x[i__4].i != 0.) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + ix = kx; + l = kplus1 - j; +/* Computing MAX */ + i__4 = 1, i__2 = j - *k; + i__3 = j - 1; + for (i__ = max(i__4,i__2); i__ <= i__3; ++i__) { + i__4 = ix; + i__2 = ix; + i__5 = l + i__ + j * a_dim1; + z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, + z__2.i = temp.r * a[i__5].i + temp.i * a[ + i__5].r; + z__1.r = x[i__2].r + z__2.r, z__1.i = x[i__2].i + + z__2.i; + x[i__4].r = z__1.r, x[i__4].i = z__1.i; + ix += *incx; +/* L30: */ + } + if (nounit) { + i__3 = jx; + i__4 = jx; + i__2 = kplus1 + j * a_dim1; + z__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[ + i__2].i, z__1.i = x[i__4].r * a[i__2].i + + x[i__4].i * a[i__2].r; + x[i__3].r = z__1.r, x[i__3].i = z__1.i; + } + } + jx += *incx; + if (j > *k) { + kx += *incx; + } +/* L40: */ + } + } + } else { + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + i__1 = j; + if (x[i__1].r != 0. || x[i__1].i != 0.) { + i__1 = j; + temp.r = x[i__1].r, temp.i = x[i__1].i; + l = 1 - j; +/* Computing MIN */ + i__1 = *n, i__3 = j + *k; + i__4 = j + 1; + for (i__ = min(i__1,i__3); i__ >= i__4; --i__) { + i__1 = i__; + i__3 = i__; + i__2 = l + i__ + j * a_dim1; + z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, + z__2.i = temp.r * a[i__2].i + temp.i * a[ + i__2].r; + z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + + z__2.i; + x[i__1].r = z__1.r, x[i__1].i = z__1.i; +/* L50: */ + } + if (nounit) { + i__4 = j; + i__1 = j; + i__3 = j * a_dim1 + 1; + z__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[ + i__3].i, z__1.i = x[i__1].r * a[i__3].i + + x[i__1].i * a[i__3].r; + x[i__4].r = z__1.r, x[i__4].i = z__1.i; + } + } +/* L60: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + i__4 = jx; + if (x[i__4].r != 0. || x[i__4].i != 0.) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + ix = kx; + l = 1 - j; +/* Computing MIN */ + i__4 = *n, i__1 = j + *k; + i__3 = j + 1; + for (i__ = min(i__4,i__1); i__ >= i__3; --i__) { + i__4 = ix; + i__1 = ix; + i__2 = l + i__ + j * a_dim1; + z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, + z__2.i = temp.r * a[i__2].i + temp.i * a[ + i__2].r; + z__1.r = x[i__1].r + z__2.r, z__1.i = x[i__1].i + + z__2.i; + x[i__4].r = z__1.r, x[i__4].i = z__1.i; + ix -= *incx; +/* L70: */ + } + if (nounit) { + i__3 = jx; + i__4 = jx; + i__1 = j * a_dim1 + 1; + z__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[ + i__1].i, z__1.i = x[i__4].r * a[i__1].i + + x[i__4].i * a[i__1].r; + x[i__3].r = z__1.r, x[i__3].i = z__1.i; + } + } + jx -= *incx; + if (*n - j >= *k) { + kx -= *incx; + } +/* L80: */ + } + } + } + } else { + +/* Form x := A'*x or x := conjg( A' )*x. */ + + if (lsame_(uplo, "U", (ftnlen)1, (ftnlen)1)) { + kplus1 = *k + 1; + if (*incx == 1) { + for (j = *n; j >= 1; --j) { + i__3 = j; + temp.r = x[i__3].r, temp.i = x[i__3].i; + l = kplus1 - j; + if (noconj) { + if (nounit) { + i__3 = kplus1 + j * a_dim1; + z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, + z__1.i = temp.r * a[i__3].i + temp.i * a[ + i__3].r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + i__4 = l + i__ + j * a_dim1; + i__1 = i__; + z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[ + i__1].i, z__2.i = a[i__4].r * x[i__1].i + + a[i__4].i * x[i__1].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; +/* L90: */ + } + } else { + if (nounit) { + d_cnjg(&z__2, &a[kplus1 + j * a_dim1]); + z__1.r = temp.r * z__2.r - temp.i * z__2.i, + z__1.i = temp.r * z__2.i + temp.i * + z__2.r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__4 = i__; + z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, + z__2.i = z__3.r * x[i__4].i + z__3.i * x[ + i__4].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; +/* L100: */ + } + } + i__3 = j; + x[i__3].r = temp.r, x[i__3].i = temp.i; +/* L110: */ + } + } else { + kx += (*n - 1) * *incx; + jx = kx; + for (j = *n; j >= 1; --j) { + i__3 = jx; + temp.r = x[i__3].r, temp.i = x[i__3].i; + kx -= *incx; + ix = kx; + l = kplus1 - j; + if (noconj) { + if (nounit) { + i__3 = kplus1 + j * a_dim1; + z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, + z__1.i = temp.r * a[i__3].i + temp.i * a[ + i__3].r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + i__4 = l + i__ + j * a_dim1; + i__1 = ix; + z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[ + i__1].i, z__2.i = a[i__4].r * x[i__1].i + + a[i__4].i * x[i__1].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; + ix -= *incx; +/* L120: */ + } + } else { + if (nounit) { + d_cnjg(&z__2, &a[kplus1 + j * a_dim1]); + z__1.r = temp.r * z__2.r - temp.i * z__2.i, + z__1.i = temp.r * z__2.i + temp.i * + z__2.r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MAX */ + i__4 = 1, i__1 = j - *k; + i__3 = max(i__4,i__1); + for (i__ = j - 1; i__ >= i__3; --i__) { + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__4 = ix; + z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, + z__2.i = z__3.r * x[i__4].i + z__3.i * x[ + i__4].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; + ix -= *incx; +/* L130: */ + } + } + i__3 = jx; + x[i__3].r = temp.r, x[i__3].i = temp.i; + jx -= *incx; +/* L140: */ + } + } + } else { + if (*incx == 1) { + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + i__4 = j; + temp.r = x[i__4].r, temp.i = x[i__4].i; + l = 1 - j; + if (noconj) { + if (nounit) { + i__4 = j * a_dim1 + 1; + z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, + z__1.i = temp.r * a[i__4].i + temp.i * a[ + i__4].r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + i__1 = l + i__ + j * a_dim1; + i__2 = i__; + z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[ + i__2].i, z__2.i = a[i__1].r * x[i__2].i + + a[i__1].i * x[i__2].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; +/* L150: */ + } + } else { + if (nounit) { + d_cnjg(&z__2, &a[j * a_dim1 + 1]); + z__1.r = temp.r * z__2.r - temp.i * z__2.i, + z__1.i = temp.r * z__2.i + temp.i * + z__2.r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__1 = i__; + z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, + z__2.i = z__3.r * x[i__1].i + z__3.i * x[ + i__1].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; +/* L160: */ + } + } + i__4 = j; + x[i__4].r = temp.r, x[i__4].i = temp.i; +/* L170: */ + } + } else { + jx = kx; + i__3 = *n; + for (j = 1; j <= i__3; ++j) { + i__4 = jx; + temp.r = x[i__4].r, temp.i = x[i__4].i; + kx += *incx; + ix = kx; + l = 1 - j; + if (noconj) { + if (nounit) { + i__4 = j * a_dim1 + 1; + z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, + z__1.i = temp.r * a[i__4].i + temp.i * a[ + i__4].r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + i__1 = l + i__ + j * a_dim1; + i__2 = ix; + z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[ + i__2].i, z__2.i = a[i__1].r * x[i__2].i + + a[i__1].i * x[i__2].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; + ix += *incx; +/* L180: */ + } + } else { + if (nounit) { + d_cnjg(&z__2, &a[j * a_dim1 + 1]); + z__1.r = temp.r * z__2.r - temp.i * z__2.i, + z__1.i = temp.r * z__2.i + temp.i * + z__2.r; + temp.r = z__1.r, temp.i = z__1.i; + } +/* Computing MIN */ + i__1 = *n, i__2 = j + *k; + i__4 = min(i__1,i__2); + for (i__ = j + 1; i__ <= i__4; ++i__) { + d_cnjg(&z__3, &a[l + i__ + j * a_dim1]); + i__1 = ix; + z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, + z__2.i = z__3.r * x[i__1].i + z__3.i * x[ + i__1].r; + z__1.r = temp.r + z__2.r, z__1.i = temp.i + + z__2.i; + temp.r = z__1.r, temp.i = z__1.i; + ix += *incx; +/* L190: */ + } + } + i__4 = jx; + x[i__4].r = temp.r, x[i__4].i = temp.i; + jx += *incx; +/* L200: */ + } + } + } + } + + return 0; + +/* End of ZTBMV . */ + +} /* ztbmv_ */ + diff --git a/gtsam/3rdparty/Eigen/blas/complexdots.f b/gtsam/3rdparty/Eigen/blas/fortran/complexdots.f similarity index 100% rename from gtsam/3rdparty/Eigen/blas/complexdots.f rename to gtsam/3rdparty/Eigen/blas/fortran/complexdots.f diff --git a/gtsam/3rdparty/Eigen/blas/level1_cplx_impl.h b/gtsam/3rdparty/Eigen/blas/level1_cplx_impl.h index 283b9f827..719f5bac9 100644 --- a/gtsam/3rdparty/Eigen/blas/level1_cplx_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level1_cplx_impl.h @@ -32,45 +32,52 @@ RealScalar EIGEN_CAT(EIGEN_CAT(REAL_SCALAR_SUFFIX,SCALAR_SUFFIX),asum_)(int *n, if(*n<=0) return 0; - if(*incx==1) return vector(x,*n).unaryExpr().sum(); - else return vector(x,*n,std::abs(*incx)).unaryExpr().sum(); + if(*incx==1) return make_vector(x,*n).unaryExpr().sum(); + else return make_vector(x,*n,std::abs(*incx)).unaryExpr().sum(); } // computes a dot product of a conjugated vector with another vector. int EIGEN_BLAS_FUNC(dotcw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres) { // std::cerr << "_dotc " << *n << " " << *incx << " " << *incy << "\n"; + Scalar* res = reinterpret_cast(pres); - if(*n<=0) return 0; + if(*n<=0) + { + *res = Scalar(0); + return 0; + } Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar* res = reinterpret_cast(pres); - if(*incx==1 && *incy==1) *res = (vector(x,*n).dot(vector(y,*n))); - else if(*incx>0 && *incy>0) *res = (vector(x,*n,*incx).dot(vector(y,*n,*incy))); - else if(*incx<0 && *incy>0) *res = (vector(x,*n,-*incx).reverse().dot(vector(y,*n,*incy))); - else if(*incx>0 && *incy<0) *res = (vector(x,*n,*incx).dot(vector(y,*n,-*incy).reverse())); - else if(*incx<0 && *incy<0) *res = (vector(x,*n,-*incx).reverse().dot(vector(y,*n,-*incy).reverse())); + if(*incx==1 && *incy==1) *res = (make_vector(x,*n).dot(make_vector(y,*n))); + else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,*incy))); + else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,*incy))); + else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,-*incy).reverse())); + else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,-*incy).reverse())); return 0; } // computes a vector-vector dot product without complex conjugation. int EIGEN_BLAS_FUNC(dotuw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres) { -// std::cerr << "_dotu " << *n << " " << *incx << " " << *incy << "\n"; + Scalar* res = reinterpret_cast(pres); - if(*n<=0) return 0; + if(*n<=0) + { + *res = Scalar(0); + return 0; + } Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar* res = reinterpret_cast(pres); - if(*incx==1 && *incy==1) *res = (vector(x,*n).cwiseProduct(vector(y,*n))).sum(); - else if(*incx>0 && *incy>0) *res = (vector(x,*n,*incx).cwiseProduct(vector(y,*n,*incy))).sum(); - else if(*incx<0 && *incy>0) *res = (vector(x,*n,-*incx).reverse().cwiseProduct(vector(y,*n,*incy))).sum(); - else if(*incx>0 && *incy<0) *res = (vector(x,*n,*incx).cwiseProduct(vector(y,*n,-*incy).reverse())).sum(); - else if(*incx<0 && *incy<0) *res = (vector(x,*n,-*incx).reverse().cwiseProduct(vector(y,*n,-*incy).reverse())).sum(); + if(*incx==1 && *incy==1) *res = (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum(); + else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum(); + else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum(); + else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum(); + else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum(); return 0; } @@ -82,9 +89,9 @@ RealScalar EIGEN_CAT(EIGEN_CAT(REAL_SCALAR_SUFFIX,SCALAR_SUFFIX),nrm2_)(int *n, Scalar* x = reinterpret_cast(px); if(*incx==1) - return vector(x,*n).stableNorm(); + return make_vector(x,*n).stableNorm(); - return vector(x,*n,*incx).stableNorm(); + return make_vector(x,*n,*incx).stableNorm(); } int EIGEN_CAT(EIGEN_CAT(SCALAR_SUFFIX,REAL_SCALAR_SUFFIX),rot_)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps) @@ -96,8 +103,8 @@ int EIGEN_CAT(EIGEN_CAT(SCALAR_SUFFIX,REAL_SCALAR_SUFFIX),rot_)(int *n, RealScal RealScalar c = *pc; RealScalar s = *ps; - StridedVectorType vx(vector(x,*n,std::abs(*incx))); - StridedVectorType vy(vector(y,*n,std::abs(*incy))); + StridedVectorType vx(make_vector(x,*n,std::abs(*incx))); + StridedVectorType vy(make_vector(y,*n,std::abs(*incy))); Reverse rvx(vx); Reverse rvy(vy); @@ -119,9 +126,8 @@ int EIGEN_CAT(EIGEN_CAT(SCALAR_SUFFIX,REAL_SCALAR_SUFFIX),scal_)(int *n, RealSca // std::cerr << "__scal " << *n << " " << alpha << " " << *incx << "\n"; - if(*incx==1) vector(x,*n) *= alpha; - else vector(x,*n,std::abs(*incx)) *= alpha; + if(*incx==1) make_vector(x,*n) *= alpha; + else make_vector(x,*n,std::abs(*incx)) *= alpha; return 0; } - diff --git a/gtsam/3rdparty/Eigen/blas/level1_impl.h b/gtsam/3rdparty/Eigen/blas/level1_impl.h index b08c2f6be..f857bfa20 100644 --- a/gtsam/3rdparty/Eigen/blas/level1_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level1_impl.h @@ -9,19 +9,19 @@ #include "common.h" -int EIGEN_BLAS_FUNC(axpy)(int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy) +int EIGEN_BLAS_FUNC(axpy)(const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *py, const int *incy) { - Scalar* x = reinterpret_cast(px); + const Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); if(*n<=0) return 0; - if(*incx==1 && *incy==1) vector(y,*n) += alpha * vector(x,*n); - else if(*incx>0 && *incy>0) vector(y,*n,*incy) += alpha * vector(x,*n,*incx); - else if(*incx>0 && *incy<0) vector(y,*n,-*incy).reverse() += alpha * vector(x,*n,*incx); - else if(*incx<0 && *incy>0) vector(y,*n,*incy) += alpha * vector(x,*n,-*incx).reverse(); - else if(*incx<0 && *incy<0) vector(y,*n,-*incy).reverse() += alpha * vector(x,*n,-*incx).reverse(); + if(*incx==1 && *incy==1) make_vector(y,*n) += alpha * make_vector(x,*n); + else if(*incx>0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,*incx); + else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,*incx); + else if(*incx<0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,-*incx).reverse(); + else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,-*incx).reverse(); return 0; } @@ -35,7 +35,7 @@ int EIGEN_BLAS_FUNC(copy)(int *n, RealScalar *px, int *incx, RealScalar *py, int // be carefull, *incx==0 is allowed !! if(*incx==1 && *incy==1) - vector(y,*n) = vector(x,*n); + make_vector(y,*n) = make_vector(x,*n); else { if(*incx<0) x = x - (*n-1)*(*incx); @@ -57,27 +57,27 @@ int EIGEN_CAT(EIGEN_CAT(i,SCALAR_SUFFIX),amax_)(int *n, RealScalar *px, int *inc Scalar* x = reinterpret_cast(px); DenseIndex ret; - if(*incx==1) vector(x,*n).cwiseAbs().maxCoeff(&ret); - else vector(x,*n,std::abs(*incx)).cwiseAbs().maxCoeff(&ret); - return ret+1; + if(*incx==1) make_vector(x,*n).cwiseAbs().maxCoeff(&ret); + else make_vector(x,*n,std::abs(*incx)).cwiseAbs().maxCoeff(&ret); + return int(ret)+1; } int EIGEN_CAT(EIGEN_CAT(i,SCALAR_SUFFIX),amin_)(int *n, RealScalar *px, int *incx) { if(*n<=0) return 0; Scalar* x = reinterpret_cast(px); - + DenseIndex ret; - if(*incx==1) vector(x,*n).cwiseAbs().minCoeff(&ret); - else vector(x,*n,std::abs(*incx)).cwiseAbs().minCoeff(&ret); - return ret+1; + if(*incx==1) make_vector(x,*n).cwiseAbs().minCoeff(&ret); + else make_vector(x,*n,std::abs(*incx)).cwiseAbs().minCoeff(&ret); + return int(ret)+1; } int EIGEN_BLAS_FUNC(rotg)(RealScalar *pa, RealScalar *pb, RealScalar *pc, RealScalar *ps) { using std::sqrt; using std::abs; - + Scalar& a = *reinterpret_cast(pa); Scalar& b = *reinterpret_cast(pb); RealScalar* c = pc; @@ -143,8 +143,8 @@ int EIGEN_BLAS_FUNC(scal)(int *n, RealScalar *palpha, RealScalar *px, int *incx) Scalar* x = reinterpret_cast(px); Scalar alpha = *reinterpret_cast(palpha); - if(*incx==1) vector(x,*n) *= alpha; - else vector(x,*n,std::abs(*incx)) *= alpha; + if(*incx==1) make_vector(x,*n) *= alpha; + else make_vector(x,*n,std::abs(*incx)) *= alpha; return 0; } @@ -156,12 +156,11 @@ int EIGEN_BLAS_FUNC(swap)(int *n, RealScalar *px, int *incx, RealScalar *py, int Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - if(*incx==1 && *incy==1) vector(y,*n).swap(vector(x,*n)); - else if(*incx>0 && *incy>0) vector(y,*n,*incy).swap(vector(x,*n,*incx)); - else if(*incx>0 && *incy<0) vector(y,*n,-*incy).reverse().swap(vector(x,*n,*incx)); - else if(*incx<0 && *incy>0) vector(y,*n,*incy).swap(vector(x,*n,-*incx).reverse()); - else if(*incx<0 && *incy<0) vector(y,*n,-*incy).reverse().swap(vector(x,*n,-*incx).reverse()); + if(*incx==1 && *incy==1) make_vector(y,*n).swap(make_vector(x,*n)); + else if(*incx>0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,*incx)); + else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,*incx)); + else if(*incx<0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,-*incx).reverse()); + else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,-*incx).reverse()); return 1; } - diff --git a/gtsam/3rdparty/Eigen/blas/level1_real_impl.h b/gtsam/3rdparty/Eigen/blas/level1_real_impl.h index 8acecdfc6..02586d519 100644 --- a/gtsam/3rdparty/Eigen/blas/level1_real_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level1_real_impl.h @@ -19,8 +19,8 @@ RealScalar EIGEN_BLAS_FUNC(asum)(int *n, RealScalar *px, int *incx) if(*n<=0) return 0; - if(*incx==1) return vector(x,*n).cwiseAbs().sum(); - else return vector(x,*n,std::abs(*incx)).cwiseAbs().sum(); + if(*incx==1) return make_vector(x,*n).cwiseAbs().sum(); + else return make_vector(x,*n,std::abs(*incx)).cwiseAbs().sum(); } // computes a vector-vector dot product. @@ -33,11 +33,11 @@ Scalar EIGEN_BLAS_FUNC(dot)(int *n, RealScalar *px, int *incx, RealScalar *py, i Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - if(*incx==1 && *incy==1) return (vector(x,*n).cwiseProduct(vector(y,*n))).sum(); - else if(*incx>0 && *incy>0) return (vector(x,*n,*incx).cwiseProduct(vector(y,*n,*incy))).sum(); - else if(*incx<0 && *incy>0) return (vector(x,*n,-*incx).reverse().cwiseProduct(vector(y,*n,*incy))).sum(); - else if(*incx>0 && *incy<0) return (vector(x,*n,*incx).cwiseProduct(vector(y,*n,-*incy).reverse())).sum(); - else if(*incx<0 && *incy<0) return (vector(x,*n,-*incx).reverse().cwiseProduct(vector(y,*n,-*incy).reverse())).sum(); + if(*incx==1 && *incy==1) return (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum(); + else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum(); + else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum(); + else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum(); + else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum(); else return 0; } @@ -50,8 +50,8 @@ Scalar EIGEN_BLAS_FUNC(nrm2)(int *n, RealScalar *px, int *incx) Scalar* x = reinterpret_cast(px); - if(*incx==1) return vector(x,*n).stableNorm(); - else return vector(x,*n,std::abs(*incx)).stableNorm(); + if(*incx==1) return make_vector(x,*n).stableNorm(); + else return make_vector(x,*n,std::abs(*incx)).stableNorm(); } int EIGEN_BLAS_FUNC(rot)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps) @@ -64,8 +64,8 @@ int EIGEN_BLAS_FUNC(rot)(int *n, RealScalar *px, int *incx, RealScalar *py, int Scalar c = *reinterpret_cast(pc); Scalar s = *reinterpret_cast(ps); - StridedVectorType vx(vector(x,*n,std::abs(*incx))); - StridedVectorType vy(vector(y,*n,std::abs(*incy))); + StridedVectorType vx(make_vector(x,*n,std::abs(*incx))); + StridedVectorType vy(make_vector(y,*n,std::abs(*incy))); Reverse rvx(vx); Reverse rvy(vy); diff --git a/gtsam/3rdparty/Eigen/blas/level2_cplx_impl.h b/gtsam/3rdparty/Eigen/blas/level2_cplx_impl.h index b850b6cd1..e3ce61435 100644 --- a/gtsam/3rdparty/Eigen/blas/level2_cplx_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level2_cplx_impl.h @@ -16,28 +16,22 @@ * where alpha and beta are scalars, x and y are n element vectors and * A is an n by n hermitian matrix. */ -int EIGEN_BLAS_FUNC(hemv)(char *uplo, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *px, int *incx, RealScalar *pbeta, RealScalar *py, int *incy) +int EIGEN_BLAS_FUNC(hemv)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda, + const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy) { - typedef void (*functype)(int, const Scalar*, int, const Scalar*, int, Scalar*, Scalar); - static functype func[2]; + typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar); + static const functype func[2] = { + // array index: UP + (internal::selfadjoint_matrix_vector_product::run), + // array index: LO + (internal::selfadjoint_matrix_vector_product::run), + }; - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::selfadjoint_matrix_vector_product::run); - func[LO] = (internal::selfadjoint_matrix_vector_product::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); - Scalar* x = reinterpret_cast(px); + const Scalar* a = reinterpret_cast(pa); + const Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); // check arguments int info = 0; @@ -52,13 +46,13 @@ int EIGEN_BLAS_FUNC(hemv)(char *uplo, int *n, RealScalar *palpha, RealScalar *pa if(*n==0) return 1; - Scalar* actual_x = get_compact_vector(x,*n,*incx); + const Scalar* actual_x = get_compact_vector(x,*n,*incx); Scalar* actual_y = get_compact_vector(y,*n,*incy); if(beta!=Scalar(1)) { - if(beta==Scalar(0)) vector(actual_y, *n).setZero(); - else vector(actual_y, *n) *= beta; + if(beta==Scalar(0)) make_vector(actual_y, *n).setZero(); + else make_vector(actual_y, *n) *= beta; } if(alpha!=Scalar(0)) @@ -67,7 +61,7 @@ int EIGEN_BLAS_FUNC(hemv)(char *uplo, int *n, RealScalar *palpha, RealScalar *pa if(code>=2 || func[code]==0) return 0; - func[code](*n, a, *lda, actual_x, 1, actual_y, alpha); + func[code](*n, a, *lda, actual_x, actual_y, alpha); } if(actual_x!=x) delete[] actual_x; @@ -111,19 +105,12 @@ int EIGEN_BLAS_FUNC(hemv)(char *uplo, int *n, RealScalar *palpha, RealScalar *pa int EIGEN_BLAS_FUNC(hpr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pap) { typedef void (*functype)(int, Scalar*, const Scalar*, RealScalar); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::selfadjoint_packed_rank1_update::run); - func[LO] = (internal::selfadjoint_packed_rank1_update::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (internal::selfadjoint_packed_rank1_update::run), + // array index: LO + (internal::selfadjoint_packed_rank1_update::run), + }; Scalar* x = reinterpret_cast(px); Scalar* ap = reinterpret_cast(pap); @@ -162,19 +149,12 @@ int EIGEN_BLAS_FUNC(hpr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int EIGEN_BLAS_FUNC(hpr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap) { typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::packed_rank2_update_selector::run); - func[LO] = (internal::packed_rank2_update_selector::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (internal::packed_rank2_update_selector::run), + // array index: LO + (internal::packed_rank2_update_selector::run), + }; Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); @@ -217,19 +197,12 @@ int EIGEN_BLAS_FUNC(hpr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px int EIGEN_BLAS_FUNC(her)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pa, int *lda) { typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (selfadjoint_rank1_update::run); - func[LO] = (selfadjoint_rank1_update::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (selfadjoint_rank1_update::run), + // array index: LO + (selfadjoint_rank1_update::run), + }; Scalar* x = reinterpret_cast(px); Scalar* a = reinterpret_cast(pa); @@ -271,19 +244,12 @@ int EIGEN_BLAS_FUNC(her)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int EIGEN_BLAS_FUNC(her2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda) { typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::rank2_update_selector::run); - func[LO] = (internal::rank2_update_selector::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (internal::rank2_update_selector::run), + // array index: LO + (internal::rank2_update_selector::run), + }; Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); diff --git a/gtsam/3rdparty/Eigen/blas/level2_impl.h b/gtsam/3rdparty/Eigen/blas/level2_impl.h index 5f3941975..173f40b44 100644 --- a/gtsam/3rdparty/Eigen/blas/level2_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level2_impl.h @@ -9,29 +9,39 @@ #include "common.h" -int EIGEN_BLAS_FUNC(gemv)(char *opa, int *m, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *incb, RealScalar *pbeta, RealScalar *pc, int *incc) +template +struct general_matrix_vector_product_wrapper +{ + static void run(Index rows, Index cols,const Scalar *lhs, Index lhsStride, const Scalar *rhs, Index rhsIncr, Scalar* res, Index resIncr, Scalar alpha) + { + typedef internal::const_blas_data_mapper LhsMapper; + typedef internal::const_blas_data_mapper RhsMapper; + + internal::general_matrix_vector_product + ::run( + rows, cols, LhsMapper(lhs, lhsStride), RhsMapper(rhs, rhsIncr), res, resIncr, alpha); + } +}; + +int EIGEN_BLAS_FUNC(gemv)(const char *opa, const int *m, const int *n, const RealScalar *palpha, + const RealScalar *pa, const int *lda, const RealScalar *pb, const int *incb, const RealScalar *pbeta, RealScalar *pc, const int *incc) { typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int , Scalar *, int, Scalar); - static functype func[4]; + static const functype func[4] = { + // array index: NOTR + (general_matrix_vector_product_wrapper::run), + // array index: TR + (general_matrix_vector_product_wrapper::run), + // array index: ADJ + (general_matrix_vector_product_wrapper::run), + 0 + }; - static bool init = false; - if(!init) - { - for(int k=0; k<4; ++k) - func[k] = 0; - - func[NOTR] = (internal::general_matrix_vector_product::run); - func[TR ] = (internal::general_matrix_vector_product::run); - func[ADJ ] = (internal::general_matrix_vector_product::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); // check arguments int info = 0; @@ -53,13 +63,13 @@ int EIGEN_BLAS_FUNC(gemv)(char *opa, int *m, int *n, RealScalar *palpha, RealSca if(code!=NOTR) std::swap(actual_m,actual_n); - Scalar* actual_b = get_compact_vector(b,actual_n,*incb); + const Scalar* actual_b = get_compact_vector(b,actual_n,*incb); Scalar* actual_c = get_compact_vector(c,actual_m,*incc); if(beta!=Scalar(1)) { - if(beta==Scalar(0)) vector(actual_c, actual_m).setZero(); - else vector(actual_c, actual_m) *= beta; + if(beta==Scalar(0)) make_vector(actual_c, actual_m).setZero(); + else make_vector(actual_c, actual_m) *= beta; } if(code>=4 || func[code]==0) @@ -73,37 +83,41 @@ int EIGEN_BLAS_FUNC(gemv)(char *opa, int *m, int *n, RealScalar *palpha, RealSca return 1; } -int EIGEN_BLAS_FUNC(trsv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pa, int *lda, RealScalar *pb, int *incb) +int EIGEN_BLAS_FUNC(trsv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb) { typedef void (*functype)(int, const Scalar *, int, Scalar *); - static functype func[16]; + static const functype func[16] = { + // array index: NOTR | (UP << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + // array index: TR | (UP << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + // array index: ADJ | (UP << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + 0, + // array index: NOTR | (LO << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + // array index: TR | (LO << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + // array index: ADJ | (LO << 2) | (NUNIT << 3) + (internal::triangular_solve_vector::run), + 0, + // array index: NOTR | (UP << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + // array index: TR | (UP << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + // array index: ADJ | (UP << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + 0, + // array index: NOTR | (LO << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + // array index: TR | (LO << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + // array index: ADJ | (LO << 2) | (UNIT << 3) + (internal::triangular_solve_vector::run), + 0 + }; - static bool init = false; - if(!init) - { - for(int k=0; k<16; ++k) - func[k] = 0; - - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::triangular_solve_vector::run); - - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::triangular_solve_vector::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* b = reinterpret_cast(pb); int info = 0; @@ -128,37 +142,41 @@ int EIGEN_BLAS_FUNC(trsv)(char *uplo, char *opa, char *diag, int *n, RealScalar -int EIGEN_BLAS_FUNC(trmv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pa, int *lda, RealScalar *pb, int *incb) +int EIGEN_BLAS_FUNC(trmv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb) { typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int, Scalar *, int, const Scalar&); - static functype func[16]; + static const functype func[16] = { + // array index: NOTR | (UP << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: TR | (UP << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: ADJ | (UP << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (LO << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: TR | (LO << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: ADJ | (LO << 2) | (NUNIT << 3) + (internal::triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (UP << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: TR | (UP << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: ADJ | (UP << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (LO << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: TR | (LO << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + // array index: ADJ | (LO << 2) | (UNIT << 3) + (internal::triangular_matrix_vector_product::run), + 0 + }; - static bool init = false; - if(!init) - { - for(int k=0; k<16; ++k) - func[k] = 0; - - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::triangular_matrix_vector_product::run); - - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::triangular_matrix_vector_product::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* b = reinterpret_cast(pb); int info = 0; @@ -200,13 +218,13 @@ int EIGEN_BLAS_FUNC(trmv)(char *uplo, char *opa, char *diag, int *n, RealScalar int EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *px, int *incx, RealScalar *pbeta, RealScalar *py, int *incy) { - Scalar* a = reinterpret_cast(pa); - Scalar* x = reinterpret_cast(px); + const Scalar* a = reinterpret_cast(pa); + const Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); int coeff_rows = *kl+*ku+1; - + int info = 0; if(OP(*trans)==INVALID) info = 1; else if(*m<0) info = 2; @@ -218,26 +236,26 @@ int EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealSca else if(*incy==0) info = 13; if(info) return xerbla_(SCALAR_SUFFIX_UP"GBMV ",&info,6); - + if(*m==0 || *n==0 || (alpha==Scalar(0) && beta==Scalar(1))) return 0; - + int actual_m = *m; int actual_n = *n; if(OP(*trans)!=NOTR) std::swap(actual_m,actual_n); - - Scalar* actual_x = get_compact_vector(x,actual_n,*incx); + + const Scalar* actual_x = get_compact_vector(x,actual_n,*incx); Scalar* actual_y = get_compact_vector(y,actual_m,*incy); - + if(beta!=Scalar(1)) { - if(beta==Scalar(0)) vector(actual_y, actual_m).setZero(); - else vector(actual_y, actual_m) *= beta; + if(beta==Scalar(0)) make_vector(actual_y, actual_m).setZero(); + else make_vector(actual_y, actual_m) *= beta; } - - MatrixType mat_coeffs(a,coeff_rows,*n,*lda); - + + ConstMatrixType mat_coeffs(a,coeff_rows,*n,*lda); + int nb = std::min(*n,(*m)+(*ku)); for(int j=0; j(pa); Scalar* x = reinterpret_cast(px); int coeff_rows = *k + 1; - + int info = 0; if(UPLO(*uplo)==INVALID) info = 1; else if(OP(*opa)==INVALID) info = 2; @@ -283,37 +301,37 @@ int EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *opa, char *diag, int *n, int *k, Rea else if(*incx==0) info = 9; if(info) return xerbla_(SCALAR_SUFFIX_UP"TBMV ",&info,6); - + if(*n==0) return 0; - + int actual_n = *n; - + Scalar* actual_x = get_compact_vector(x,actual_n,*incx); - + MatrixType mat_coeffs(a,coeff_rows,*n,*lda); - + int ku = UPLO(*uplo)==UPPER ? *k : 0; int kl = UPLO(*uplo)==LOWER ? *k : 0; - + for(int j=0; j<*n; ++j) { int start = std::max(0,j - ku); int end = std::min((*m)-1,j + kl); int len = end - start + 1; int offset = (ku) - j + start; - + if(OP(*trans)==NOTR) - vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len); + make_vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len); else if(OP(*trans)==TR) - actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * vector(actual_x+start,len) ).value(); + actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * make_vector(actual_x+start,len) ).value(); else - actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint() * vector(actual_x+start,len) ).value(); - } - + actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint() * make_vector(actual_x+start,len) ).value(); + } + if(actual_x!=x) delete[] actual_x; if(actual_y!=y) delete[] copy_back(actual_y,y,actual_m,*incy); - + return 0; } #endif @@ -332,37 +350,41 @@ int EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *opa, char *diag, int *n, int *k, Rea int EIGEN_BLAS_FUNC(tbsv)(char *uplo, char *op, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx) { typedef void (*functype)(int, int, const Scalar *, int, Scalar *); - static functype func[16]; - - static bool init = false; - if(!init) - { - for(int k=0; k<16; ++k) - func[k] = 0; - - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::band_solve_triangular_selector::run); - - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::band_solve_triangular_selector::run); - - init = true; - } + static const functype func[16] = { + // array index: NOTR | (UP << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: TR | (UP << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: ADJ | (UP << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + 0, + // array index: NOTR | (LO << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: TR | (LO << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: ADJ | (LO << 2) | (NUNIT << 3) + (internal::band_solve_triangular_selector::run), + 0, + // array index: NOTR | (UP << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: TR | (UP << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: ADJ | (UP << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + 0, + // array index: NOTR | (LO << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: TR | (LO << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + // array index: ADJ | (LO << 2) | (UNIT << 3) + (internal::band_solve_triangular_selector::run), + 0, + }; Scalar* a = reinterpret_cast(pa); Scalar* x = reinterpret_cast(px); int coeff_rows = *k+1; - + int info = 0; if(UPLO(*uplo)==INVALID) info = 1; else if(OP(*op)==INVALID) info = 2; @@ -373,22 +395,22 @@ int EIGEN_BLAS_FUNC(tbsv)(char *uplo, char *op, char *diag, int *n, int *k, Real else if(*incx==0) info = 9; if(info) return xerbla_(SCALAR_SUFFIX_UP"TBSV ",&info,6); - + if(*n==0 || (*k==0 && DIAG(*diag)==UNIT)) return 0; - + int actual_n = *n; - + Scalar* actual_x = get_compact_vector(x,actual_n,*incx); - + int code = OP(*op) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3); if(code>=16 || func[code]==0) return 0; func[code](*n, *k, a, *lda, actual_x); - + if(actual_x!=x) delete[] copy_back(actual_x,x,actual_n,*incx); - + return 0; } @@ -402,32 +424,36 @@ int EIGEN_BLAS_FUNC(tbsv)(char *uplo, char *op, char *diag, int *n, int *k, Real int EIGEN_BLAS_FUNC(tpmv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx) { typedef void (*functype)(int, const Scalar*, const Scalar*, Scalar*, Scalar); - static functype func[16]; - - static bool init = false; - if(!init) - { - for(int k=0; k<16; ++k) - func[k] = 0; - - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_matrix_vector_product::run); - - init = true; - } + static const functype func[16] = { + // array index: NOTR | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: TR | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: ADJ | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: TR | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: ADJ | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: TR | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: ADJ | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + 0, + // array index: NOTR | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: TR | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + // array index: ADJ | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_matrix_vector_product::run), + 0 + }; Scalar* ap = reinterpret_cast(pap); Scalar* x = reinterpret_cast(px); @@ -473,32 +499,36 @@ int EIGEN_BLAS_FUNC(tpmv)(char *uplo, char *opa, char *diag, int *n, RealScalar int EIGEN_BLAS_FUNC(tpsv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx) { typedef void (*functype)(int, const Scalar*, Scalar*); - static functype func[16]; - - static bool init = false; - if(!init) - { - for(int k=0; k<16; ++k) - func[k] = 0; - - func[NOTR | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[TR | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[ADJ | (UP << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - - func[NOTR | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[TR | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[ADJ | (LO << 2) | (NUNIT << 3)] = (internal::packed_triangular_solve_vector::run); - - func[NOTR | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[TR | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[ADJ | (UP << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - - func[NOTR | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[TR | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - func[ADJ | (LO << 2) | (UNIT << 3)] = (internal::packed_triangular_solve_vector::run); - - init = true; - } + static const functype func[16] = { + // array index: NOTR | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: TR | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: ADJ | (UP << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + 0, + // array index: NOTR | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: TR | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: ADJ | (LO << 2) | (NUNIT << 3) + (internal::packed_triangular_solve_vector::run), + 0, + // array index: NOTR | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: TR | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: ADJ | (UP << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + 0, + // array index: NOTR | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: TR | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + // array index: ADJ | (LO << 2) | (UNIT << 3) + (internal::packed_triangular_solve_vector::run), + 0 + }; Scalar* ap = reinterpret_cast(pap); Scalar* x = reinterpret_cast(px); @@ -521,4 +551,3 @@ int EIGEN_BLAS_FUNC(tpsv)(char *uplo, char *opa, char *diag, int *n, RealScalar return 1; } - diff --git a/gtsam/3rdparty/Eigen/blas/level2_real_impl.h b/gtsam/3rdparty/Eigen/blas/level2_real_impl.h index 8d56eaaa1..7620f0a38 100644 --- a/gtsam/3rdparty/Eigen/blas/level2_real_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level2_real_impl.h @@ -10,28 +10,22 @@ #include "common.h" // y = alpha*A*x + beta*y -int EIGEN_BLAS_FUNC(symv) (char *uplo, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *px, int *incx, RealScalar *pbeta, RealScalar *py, int *incy) +int EIGEN_BLAS_FUNC(symv) (const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda, + const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy) { - typedef void (*functype)(int, const Scalar*, int, const Scalar*, int, Scalar*, Scalar); - static functype func[2]; + typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar); + static const functype func[2] = { + // array index: UP + (internal::selfadjoint_matrix_vector_product::run), + // array index: LO + (internal::selfadjoint_matrix_vector_product::run), + }; - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::selfadjoint_matrix_vector_product::run); - func[LO] = (internal::selfadjoint_matrix_vector_product::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); - Scalar* x = reinterpret_cast(px); + const Scalar* a = reinterpret_cast(pa); + const Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); // check arguments int info = 0; @@ -46,20 +40,20 @@ int EIGEN_BLAS_FUNC(symv) (char *uplo, int *n, RealScalar *palpha, RealScalar *p if(*n==0) return 0; - Scalar* actual_x = get_compact_vector(x,*n,*incx); + const Scalar* actual_x = get_compact_vector(x,*n,*incx); Scalar* actual_y = get_compact_vector(y,*n,*incy); if(beta!=Scalar(1)) { - if(beta==Scalar(0)) vector(actual_y, *n).setZero(); - else vector(actual_y, *n) *= beta; + if(beta==Scalar(0)) make_vector(actual_y, *n).setZero(); + else make_vector(actual_y, *n) *= beta; } int code = UPLO(*uplo); if(code>=2 || func[code]==0) return 0; - func[code](*n, a, *lda, actual_x, 1, actual_y, alpha); + func[code](*n, a, *lda, actual_x, actual_y, alpha); if(actual_x!=x) delete[] actual_x; if(actual_y!=y) delete[] copy_back(actual_y,y,*n,*incy); @@ -68,41 +62,20 @@ int EIGEN_BLAS_FUNC(symv) (char *uplo, int *n, RealScalar *palpha, RealScalar *p } // C := alpha*x*x' + C -int EIGEN_BLAS_FUNC(syr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(syr)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *pc, const int *ldc) { -// typedef void (*functype)(int, const Scalar *, int, Scalar *, int, Scalar); -// static functype func[2]; - -// static bool init = false; -// if(!init) -// { -// for(int k=0; k<2; ++k) -// func[k] = 0; -// -// func[UP] = (internal::selfadjoint_product::run); -// func[LO] = (internal::selfadjoint_product::run); - -// init = true; -// } typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&); - static functype func[2]; + static const functype func[2] = { + // array index: UP + (selfadjoint_rank1_update::run), + // array index: LO + (selfadjoint_rank1_update::run), + }; - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (selfadjoint_rank1_update::run); - func[LO] = (selfadjoint_rank1_update::run); - - init = true; - } - - Scalar* x = reinterpret_cast(px); + const Scalar* x = reinterpret_cast(px); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); int info = 0; if(UPLO(*uplo)==INVALID) info = 1; @@ -115,7 +88,7 @@ int EIGEN_BLAS_FUNC(syr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, if(*n==0 || alpha==Scalar(0)) return 1; // if the increment is not 1, let's copy it to a temporary vector to enable vectorization - Scalar* x_cpy = get_compact_vector(x,*n,*incx); + const Scalar* x_cpy = get_compact_vector(x,*n,*incx); int code = UPLO(*uplo); if(code>=2 || func[code]==0) @@ -129,41 +102,20 @@ int EIGEN_BLAS_FUNC(syr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, } // C := alpha*x*y' + alpha*y*x' + C -int EIGEN_BLAS_FUNC(syr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(syr2)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, const RealScalar *py, const int *incy, RealScalar *pc, const int *ldc) { -// typedef void (*functype)(int, const Scalar *, int, const Scalar *, int, Scalar *, int, Scalar); -// static functype func[2]; -// -// static bool init = false; -// if(!init) -// { -// for(int k=0; k<2; ++k) -// func[k] = 0; -// -// func[UP] = (internal::selfadjoint_product::run); -// func[LO] = (internal::selfadjoint_product::run); -// -// init = true; -// } typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar); - static functype func[2]; + static const functype func[2] = { + // array index: UP + (internal::rank2_update_selector::run), + // array index: LO + (internal::rank2_update_selector::run), + }; - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::rank2_update_selector::run); - func[LO] = (internal::rank2_update_selector::run); - - init = true; - } - - Scalar* x = reinterpret_cast(px); - Scalar* y = reinterpret_cast(py); + const Scalar* x = reinterpret_cast(px); + const Scalar* y = reinterpret_cast(py); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); int info = 0; if(UPLO(*uplo)==INVALID) info = 1; @@ -177,9 +129,9 @@ int EIGEN_BLAS_FUNC(syr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px if(alpha==Scalar(0)) return 1; - Scalar* x_cpy = get_compact_vector(x,*n,*incx); - Scalar* y_cpy = get_compact_vector(y,*n,*incy); - + const Scalar* x_cpy = get_compact_vector(x,*n,*incx); + const Scalar* y_cpy = get_compact_vector(y,*n,*incy); + int code = UPLO(*uplo); if(code>=2 || func[code]==0) return 0; @@ -234,19 +186,12 @@ int EIGEN_BLAS_FUNC(syr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px int EIGEN_BLAS_FUNC(spr)(char *uplo, int *n, Scalar *palpha, Scalar *px, int *incx, Scalar *pap) { typedef void (*functype)(int, Scalar*, const Scalar*, Scalar); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::selfadjoint_packed_rank1_update::run); - func[LO] = (internal::selfadjoint_packed_rank1_update::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (internal::selfadjoint_packed_rank1_update::run), + // array index: LO + (internal::selfadjoint_packed_rank1_update::run), + }; Scalar* x = reinterpret_cast(px); Scalar* ap = reinterpret_cast(pap); @@ -285,19 +230,12 @@ int EIGEN_BLAS_FUNC(spr)(char *uplo, int *n, Scalar *palpha, Scalar *px, int *in int EIGEN_BLAS_FUNC(spr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap) { typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar); - static functype func[2]; - - static bool init = false; - if(!init) - { - for(int k=0; k<2; ++k) - func[k] = 0; - - func[UP] = (internal::packed_rank2_update_selector::run); - func[LO] = (internal::packed_rank2_update_selector::run); - - init = true; - } + static const functype func[2] = { + // array index: UP + (internal::packed_rank2_update_selector::run), + // array index: LO + (internal::packed_rank2_update_selector::run), + }; Scalar* x = reinterpret_cast(px); Scalar* y = reinterpret_cast(py); @@ -366,5 +304,3 @@ int EIGEN_BLAS_FUNC(ger)(int *m, int *n, Scalar *palpha, Scalar *px, int *incx, return 1; } - - diff --git a/gtsam/3rdparty/Eigen/blas/level3_impl.h b/gtsam/3rdparty/Eigen/blas/level3_impl.h index 07dbc22ff..6c802cd5f 100644 --- a/gtsam/3rdparty/Eigen/blas/level3_impl.h +++ b/gtsam/3rdparty/Eigen/blas/level3_impl.h @@ -6,37 +6,43 @@ // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - +#include #include "common.h" -int EIGEN_BLAS_FUNC(gemm)(char *opa, char *opb, int *m, int *n, int *k, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(gemm)(const char *opa, const char *opb, const int *m, const int *n, const int *k, const RealScalar *palpha, + const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { // std::cerr << "in gemm " << *opa << " " << *opb << " " << *m << " " << *n << " " << *k << " " << *lda << " " << *ldb << " " << *ldc << " " << *palpha << " " << *pbeta << "\n"; typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, Scalar, internal::level3_blocking&, Eigen::internal::GemmParallelInfo*); - static functype func[12]; + static const functype func[12] = { + // array index: NOTR | (NOTR << 2) + (internal::general_matrix_matrix_product::run), + // array index: TR | (NOTR << 2) + (internal::general_matrix_matrix_product::run), + // array index: ADJ | (NOTR << 2) + (internal::general_matrix_matrix_product::run), + 0, + // array index: NOTR | (TR << 2) + (internal::general_matrix_matrix_product::run), + // array index: TR | (TR << 2) + (internal::general_matrix_matrix_product::run), + // array index: ADJ | (TR << 2) + (internal::general_matrix_matrix_product::run), + 0, + // array index: NOTR | (ADJ << 2) + (internal::general_matrix_matrix_product::run), + // array index: TR | (ADJ << 2) + (internal::general_matrix_matrix_product::run), + // array index: ADJ | (ADJ << 2) + (internal::general_matrix_matrix_product::run), + 0 + }; - static bool init = false; - if(!init) - { - for(int k=0; k<12; ++k) - func[k] = 0; - func[NOTR | (NOTR << 2)] = (internal::general_matrix_matrix_product::run); - func[TR | (NOTR << 2)] = (internal::general_matrix_matrix_product::run); - func[ADJ | (NOTR << 2)] = (internal::general_matrix_matrix_product::run); - func[NOTR | (TR << 2)] = (internal::general_matrix_matrix_product::run); - func[TR | (TR << 2)] = (internal::general_matrix_matrix_product::run); - func[ADJ | (TR << 2)] = (internal::general_matrix_matrix_product::run); - func[NOTR | (ADJ << 2)] = (internal::general_matrix_matrix_product::run); - func[TR | (ADJ << 2)] = (internal::general_matrix_matrix_product::run); - func[ADJ | (ADJ << 2)] = (internal::general_matrix_matrix_product::run); - init = true; - } - - Scalar* a = reinterpret_cast(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); int info = 0; if(OP(*opa)==INVALID) info = 1; @@ -50,70 +56,92 @@ int EIGEN_BLAS_FUNC(gemm)(char *opa, char *opb, int *m, int *n, int *k, RealScal if(info) return xerbla_(SCALAR_SUFFIX_UP"GEMM ",&info,6); + if (*m == 0 || *n == 0) + return 0; + if(beta!=Scalar(1)) { if(beta==Scalar(0)) matrix(c, *m, *n, *ldc).setZero(); else matrix(c, *m, *n, *ldc) *= beta; } - internal::gemm_blocking_space blocking(*m,*n,*k); + if(*k == 0) + return 0; + + internal::gemm_blocking_space blocking(*m,*n,*k,1,true); int code = OP(*opa) | (OP(*opb) << 2); func[code](*m, *n, *k, a, *lda, b, *ldb, c, *ldc, alpha, blocking, 0); return 0; } -int EIGEN_BLAS_FUNC(trsm)(char *side, char *uplo, char *opa, char *diag, int *m, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb) +int EIGEN_BLAS_FUNC(trsm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n, + const RealScalar *palpha, const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb) { // std::cerr << "in trsm " << *side << " " << *uplo << " " << *opa << " " << *diag << " " << *m << "," << *n << " " << *palpha << " " << *lda << " " << *ldb<< "\n"; typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, internal::level3_blocking&); - static functype func[32]; + static const functype func[32] = { + // array index: NOTR | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run),\ + 0, + // array index: NOTR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: TR | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + // array index: ADJ | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::triangular_solve_matrix::run), + 0 + }; - static bool init = false; - if(!init) - { - for(int k=0; k<32; ++k) - func[k] = 0; - - func[NOTR | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::triangular_solve_matrix::run); - - - func[NOTR | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - - func[NOTR | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[TR | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - func[ADJ | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::triangular_solve_matrix::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* b = reinterpret_cast(pb); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); int info = 0; if(SIDE(*side)==INVALID) info = 1; @@ -127,16 +155,19 @@ int EIGEN_BLAS_FUNC(trsm)(char *side, char *uplo, char *opa, char *diag, int *m, if(info) return xerbla_(SCALAR_SUFFIX_UP"TRSM ",&info,6); + if(*m==0 || *n==0) + return 0; + int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4); - + if(SIDE(*side)==LEFT) { - internal::gemm_blocking_space blocking(*m,*n,*m); + internal::gemm_blocking_space blocking(*m,*n,*m,1,false); func[code](*m, *n, a, *lda, b, *ldb, blocking); } else { - internal::gemm_blocking_space blocking(*m,*n,*n); + internal::gemm_blocking_space blocking(*m,*n,*n,1,false); func[code](*n, *m, a, *lda, b, *ldb, blocking); } @@ -149,55 +180,73 @@ int EIGEN_BLAS_FUNC(trsm)(char *side, char *uplo, char *opa, char *diag, int *m, // b = alpha*op(a)*b for side = 'L'or'l' // b = alpha*b*op(a) for side = 'R'or'r' -int EIGEN_BLAS_FUNC(trmm)(char *side, char *uplo, char *opa, char *diag, int *m, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb) +int EIGEN_BLAS_FUNC(trmm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n, + const RealScalar *palpha, const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb) { // std::cerr << "in trmm " << *side << " " << *uplo << " " << *opa << " " << *diag << " " << *m << " " << *n << " " << *lda << " " << *ldb << " " << *palpha << "\n"; typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, const Scalar&, internal::level3_blocking&); - static functype func[32]; - static bool init = false; - if(!init) - { - for(int k=0; k<32; ++k) - func[k] = 0; + static const functype func[32] = { + // array index: NOTR | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (LEFT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (RIGHT << 2) | (UP << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (LEFT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (RIGHT << 2) | (LO << 3) | (NUNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (LEFT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (RIGHT << 2) | (UP << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (LEFT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0, + // array index: NOTR | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: TR | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + // array index: ADJ | (RIGHT << 2) | (LO << 3) | (UNIT << 4) + (internal::product_triangular_matrix_matrix::run), + 0 + }; - func[NOTR | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (LEFT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (LEFT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (LEFT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (RIGHT << 2) | (UP << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (LEFT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - func[NOTR | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[TR | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - func[ADJ | (RIGHT << 2) | (LO << 3) | (UNIT << 4)] = (internal::product_triangular_matrix_matrix::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* b = reinterpret_cast(pb); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); int info = 0; if(SIDE(*side)==INVALID) info = 1; @@ -222,12 +271,12 @@ int EIGEN_BLAS_FUNC(trmm)(char *side, char *uplo, char *opa, char *diag, int *m, if(SIDE(*side)==LEFT) { - internal::gemm_blocking_space blocking(*m,*n,*m); + internal::gemm_blocking_space blocking(*m,*n,*m,1,false); func[code](*m, *n, *m, a, *lda, tmp.data(), tmp.outerStride(), b, *ldb, alpha, blocking); } else { - internal::gemm_blocking_space blocking(*m,*n,*n); + internal::gemm_blocking_space blocking(*m,*n,*n,1,false); func[code](*m, *n, *n, tmp.data(), tmp.outerStride(), a, *lda, b, *ldb, alpha, blocking); } return 1; @@ -235,14 +284,15 @@ int EIGEN_BLAS_FUNC(trmm)(char *side, char *uplo, char *opa, char *diag, int *m, // c = alpha*a*b + beta*c for side = 'L'or'l' // c = alpha*b*a + beta*c for side = 'R'or'r -int EIGEN_BLAS_FUNC(symm)(char *side, char *uplo, int *m, int *n, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(symm)(const char *side, const char *uplo, const int *m, const int *n, const RealScalar *palpha, + const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { // std::cerr << "in symm " << *side << " " << *uplo << " " << *m << "x" << *n << " lda:" << *lda << " ldb:" << *ldb << " ldc:" << *ldc << " alpha:" << *palpha << " beta:" << *pbeta << "\n"; - Scalar* a = reinterpret_cast(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); int info = 0; if(SIDE(*side)==INVALID) info = 1; @@ -266,9 +316,9 @@ int EIGEN_BLAS_FUNC(symm)(char *side, char *uplo, int *m, int *n, RealScalar *pa return 1; } + int size = (SIDE(*side)==LEFT) ? (*m) : (*n); #if ISCOMPLEX // FIXME add support for symmetric complex matrix - int size = (SIDE(*side)==LEFT) ? (*m) : (*n); Matrix matA(size,size); if(UPLO(*uplo)==UP) { @@ -285,13 +335,15 @@ int EIGEN_BLAS_FUNC(symm)(char *side, char *uplo, int *m, int *n, RealScalar *pa else if(SIDE(*side)==RIGHT) matrix(c, *m, *n, *ldc) += alpha * matrix(b, *m, *n, *ldb) * matA; #else + internal::gemm_blocking_space blocking(*m,*n,size,1,false); + if(SIDE(*side)==LEFT) - if(UPLO(*uplo)==UP) internal::product_selfadjoint_matrix::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha); - else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha); + if(UPLO(*uplo)==UP) internal::product_selfadjoint_matrix::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha, blocking); + else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha, blocking); else return 0; else if(SIDE(*side)==RIGHT) - if(UPLO(*uplo)==UP) internal::product_selfadjoint_matrix::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha); - else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha); + if(UPLO(*uplo)==UP) internal::product_selfadjoint_matrix::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha, blocking); + else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha, blocking); else return 0; else return 0; @@ -302,39 +354,38 @@ int EIGEN_BLAS_FUNC(symm)(char *side, char *uplo, int *m, int *n, RealScalar *pa // c = alpha*a*a' + beta*c for op = 'N'or'n' // c = alpha*a'*a + beta*c for op = 'T'or't','C'or'c' -int EIGEN_BLAS_FUNC(syrk)(char *uplo, char *op, int *n, int *k, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(syrk)(const char *uplo, const char *op, const int *n, const int *k, + const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { // std::cerr << "in syrk " << *uplo << " " << *op << " " << *n << " " << *k << " " << *palpha << " " << *lda << " " << *pbeta << " " << *ldc << "\n"; #if !ISCOMPLEX - typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, const Scalar&); - static functype func[8]; - - static bool init = false; - if(!init) - { - for(int k=0; k<8; ++k) - func[k] = 0; - - func[NOTR | (UP << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[TR | (UP << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[ADJ | (UP << 2)] = (internal::general_matrix_matrix_triangular_product::run); - - func[NOTR | (LO << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[TR | (LO << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[ADJ | (LO << 2)] = (internal::general_matrix_matrix_triangular_product::run); - - init = true; - } + typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, const Scalar&, internal::level3_blocking&); + static const functype func[8] = { + // array index: NOTR | (UP << 2) + (internal::general_matrix_matrix_triangular_product::run), + // array index: TR | (UP << 2) + (internal::general_matrix_matrix_triangular_product::run), + // array index: ADJ | (UP << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0, + // array index: NOTR | (LO << 2) + (internal::general_matrix_matrix_triangular_product::run), + // array index: TR | (LO << 2) + (internal::general_matrix_matrix_triangular_product::run), + // array index: ADJ | (LO << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0 + }; #endif - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); int info = 0; if(UPLO(*uplo)==INVALID) info = 1; - else if(OP(*op)==INVALID) info = 2; + else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) ) info = 2; else if(*n<0) info = 3; else if(*k<0) info = 4; else if(*lda() *= beta; } + if(*n==0 || *k==0) + return 0; + #if ISCOMPLEX // FIXME add support for symmetric complex matrix if(UPLO(*uplo)==UP) @@ -369,8 +423,10 @@ int EIGEN_BLAS_FUNC(syrk)(char *uplo, char *op, int *n, int *k, RealScalar *palp matrix(c, *n, *n, *ldc).triangularView() += alpha * matrix(a,*k,*n,*lda).transpose() * matrix(a,*k,*n,*lda); } #else + internal::gemm_blocking_space blocking(*n,*n,*k,1,false); + int code = OP(*op) | (UPLO(*uplo) << 2); - func[code](*n, *k, a, *lda, a, *lda, c, *ldc, alpha); + func[code](*n, *k, a, *lda, a, *lda, c, *ldc, alpha, blocking); #endif return 0; @@ -378,17 +434,20 @@ int EIGEN_BLAS_FUNC(syrk)(char *uplo, char *op, int *n, int *k, RealScalar *palp // c = alpha*a*b' + alpha*b*a' + beta*c for op = 'N'or'n' // c = alpha*a'*b + alpha*b'*a + beta*c for op = 'T'or't' -int EIGEN_BLAS_FUNC(syr2k)(char *uplo, char *op, int *n, int *k, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(syr2k)(const char *uplo, const char *op, const int *n, const int *k, const RealScalar *palpha, + const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { - Scalar* a = reinterpret_cast(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); + +// std::cerr << "in syr2k " << *uplo << " " << *op << " " << *n << " " << *k << " " << alpha << " " << *lda << " " << *ldb << " " << beta << " " << *ldc << "\n"; int info = 0; if(UPLO(*uplo)==INVALID) info = 1; - else if(OP(*op)==INVALID) info = 2; + else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) ) info = 2; else if(*n<0) info = 3; else if(*k<0) info = 4; else if(*lda(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); - Scalar beta = *reinterpret_cast(pbeta); + Scalar alpha = *reinterpret_cast(palpha); + Scalar beta = *reinterpret_cast(pbeta); // std::cerr << "in hemm " << *side << " " << *uplo << " " << *m << " " << *n << " " << alpha << " " << *lda << " " << beta << " " << *ldc << "\n"; @@ -472,20 +532,23 @@ int EIGEN_BLAS_FUNC(hemm)(char *side, char *uplo, int *m, int *n, RealScalar *pa return 1; } + int size = (SIDE(*side)==LEFT) ? (*m) : (*n); + internal::gemm_blocking_space blocking(*m,*n,size,1,false); + if(SIDE(*side)==LEFT) { if(UPLO(*uplo)==UP) internal::product_selfadjoint_matrix - ::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha); + ::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha, blocking); else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix - ::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha); + ::run(*m, *n, a, *lda, b, *ldb, c, *ldc, alpha, blocking); else return 0; } else if(SIDE(*side)==RIGHT) { if(UPLO(*uplo)==UP) matrix(c,*m,*n,*ldc) += alpha * matrix(b,*m,*n,*ldb) * matrix(a,*n,*n,*lda).selfadjointView();/*internal::product_selfadjoint_matrix - ::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha);*/ + ::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha, blocking);*/ else if(UPLO(*uplo)==LO) internal::product_selfadjoint_matrix - ::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha); + ::run(*m, *n, b, *ldb, a, *lda, c, *ldc, alpha, blocking); else return 0; } else @@ -498,27 +561,28 @@ int EIGEN_BLAS_FUNC(hemm)(char *side, char *uplo, int *m, int *n, RealScalar *pa // c = alpha*a*conj(a') + beta*c for op = 'N'or'n' // c = alpha*conj(a')*a + beta*c for op = 'C'or'c' -int EIGEN_BLAS_FUNC(herk)(char *uplo, char *op, int *n, int *k, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(herk)(const char *uplo, const char *op, const int *n, const int *k, + const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { - typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, const Scalar&); - static functype func[8]; +// std::cerr << "in herk " << *uplo << " " << *op << " " << *n << " " << *k << " " << *palpha << " " << *lda << " " << *pbeta << " " << *ldc << "\n"; - static bool init = false; - if(!init) - { - for(int k=0; k<8; ++k) - func[k] = 0; + typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, const Scalar&, internal::level3_blocking&); + static const functype func[8] = { + // array index: NOTR | (UP << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0, + // array index: ADJ | (UP << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0, + // array index: NOTR | (LO << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0, + // array index: ADJ | (LO << 2) + (internal::general_matrix_matrix_triangular_product::run), + 0 + }; - func[NOTR | (UP << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[ADJ | (UP << 2)] = (internal::general_matrix_matrix_triangular_product::run); - - func[NOTR | (LO << 2)] = (internal::general_matrix_matrix_triangular_product::run); - func[ADJ | (LO << 2)] = (internal::general_matrix_matrix_triangular_product::run); - - init = true; - } - - Scalar* a = reinterpret_cast(pa); + const Scalar* a = reinterpret_cast(pa); Scalar* c = reinterpret_cast(pc); RealScalar alpha = *palpha; RealScalar beta = *pbeta; @@ -545,7 +609,7 @@ int EIGEN_BLAS_FUNC(herk)(char *uplo, char *op, int *n, int *k, RealScalar *palp else if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView().setZero(); else matrix(c, *n, *n, *ldc).triangularView() *= beta; - + if(beta!=Scalar(0)) { matrix(c, *n, *n, *ldc).diagonal().real() *= beta; @@ -555,7 +619,8 @@ int EIGEN_BLAS_FUNC(herk)(char *uplo, char *op, int *n, int *k, RealScalar *palp if(*k>0 && alpha!=RealScalar(0)) { - func[code](*n, *k, a, *lda, a, *lda, c, *ldc, alpha); + internal::gemm_blocking_space blocking(*n,*n,*k,1,false); + func[code](*n, *k, a, *lda, a, *lda, c, *ldc, alpha, blocking); matrix(c, *n, *n, *ldc).diagonal().imag().setZero(); } return 0; @@ -563,21 +628,24 @@ int EIGEN_BLAS_FUNC(herk)(char *uplo, char *op, int *n, int *k, RealScalar *palp // c = alpha*a*conj(b') + conj(alpha)*b*conj(a') + beta*c, for op = 'N'or'n' // c = alpha*conj(a')*b + conj(alpha)*conj(b')*a + beta*c, for op = 'C'or'c' -int EIGEN_BLAS_FUNC(her2k)(char *uplo, char *op, int *n, int *k, RealScalar *palpha, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, RealScalar *pbeta, RealScalar *pc, int *ldc) +int EIGEN_BLAS_FUNC(her2k)(const char *uplo, const char *op, const int *n, const int *k, + const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc) { - Scalar* a = reinterpret_cast(pa); - Scalar* b = reinterpret_cast(pb); + const Scalar* a = reinterpret_cast(pa); + const Scalar* b = reinterpret_cast(pb); Scalar* c = reinterpret_cast(pc); - Scalar alpha = *reinterpret_cast(palpha); + Scalar alpha = *reinterpret_cast(palpha); RealScalar beta = *pbeta; +// std::cerr << "in her2k " << *uplo << " " << *op << " " << *n << " " << *k << " " << alpha << " " << *lda << " " << *ldb << " " << beta << " " << *ldc << "\n"; + int info = 0; if(UPLO(*uplo)==INVALID) info = 1; else if((OP(*op)==INVALID) || (OP(*op)==TR)) info = 2; else if(*n<0) info = 3; else if(*k<0) info = 4; else if(*lda \brief \b CBLAT1 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM CBLAT1 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX Level 1 BLAS. +*> Based upon the original BLAS test routine together with: +*> +*> F06GAF Example Program Text +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex_blas_testing +* +* ===================================================================== PROGRAM CBLAT1 -* Test program for the COMPLEX Level 1 BLAS. -* Based upon the original BLAS test routine together with: -* F06GAF Example Program Text +* +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 +* +* ===================================================================== +* * .. Parameters .. INTEGER NOUT PARAMETER (NOUT=6) @@ -114,8 +156,8 @@ + (5.0E0,6.0E0), (5.0E0,6.0E0), (0.1E0,0.1E0), + (-0.6E0,0.1E0), (0.1E0,-0.3E0), (7.0E0,8.0E0), + (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0), - + (7.0E0,8.0E0), (0.3E0,0.1E0), (0.1E0,0.4E0), - + (0.4E0,0.1E0), (0.1E0,0.2E0), (2.0E0,3.0E0), + + (7.0E0,8.0E0), (0.3E0,0.1E0), (0.5E0,0.0E0), + + (0.0E0,0.5E0), (0.0E0,0.2E0), (2.0E0,3.0E0), + (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/ DATA ((CV(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0), + (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0), @@ -129,10 +171,10 @@ + (3.0E0,6.0E0), (-0.6E0,0.1E0), (4.0E0,7.0E0), + (0.1E0,-0.3E0), (7.0E0,2.0E0), (7.0E0,2.0E0), + (7.0E0,2.0E0), (0.3E0,0.1E0), (5.0E0,8.0E0), - + (0.1E0,0.4E0), (6.0E0,9.0E0), (0.4E0,0.1E0), - + (8.0E0,3.0E0), (0.1E0,0.2E0), (9.0E0,4.0E0)/ - DATA STRUE2/0.0E0, 0.5E0, 0.6E0, 0.7E0, 0.7E0/ - DATA STRUE4/0.0E0, 0.7E0, 1.0E0, 1.3E0, 1.7E0/ + + (0.5E0,0.0E0), (6.0E0,9.0E0), (0.0E0,0.5E0), + + (8.0E0,3.0E0), (0.0E0,0.2E0), (9.0E0,4.0E0)/ + DATA STRUE2/0.0E0, 0.5E0, 0.6E0, 0.7E0, 0.8E0/ + DATA STRUE4/0.0E0, 0.7E0, 1.0E0, 1.3E0, 1.6E0/ DATA ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0), + (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0), + (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0), @@ -145,8 +187,8 @@ + (0.11E0,-0.03E0), (-0.17E0,0.46E0), + (-0.17E0,-0.19E0), (7.0E0,8.0E0), (7.0E0,8.0E0), + (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0), - + (0.19E0,-0.17E0), (0.32E0,0.09E0), - + (0.23E0,-0.24E0), (0.18E0,0.01E0), + + (0.19E0,-0.17E0), (0.20E0,-0.35E0), + + (0.35E0,0.20E0), (0.14E0,0.08E0), + (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0), + (2.0E0,3.0E0)/ DATA ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0), @@ -162,9 +204,9 @@ + (-0.17E0,0.46E0), (4.0E0,7.0E0), + (-0.17E0,-0.19E0), (7.0E0,2.0E0), (7.0E0,2.0E0), + (7.0E0,2.0E0), (0.19E0,-0.17E0), (5.0E0,8.0E0), - + (0.32E0,0.09E0), (6.0E0,9.0E0), - + (0.23E0,-0.24E0), (8.0E0,3.0E0), - + (0.18E0,0.01E0), (9.0E0,4.0E0)/ + + (0.20E0,-0.35E0), (6.0E0,9.0E0), + + (0.35E0,0.20E0), (8.0E0,3.0E0), + + (0.14E0,0.08E0), (9.0E0,4.0E0)/ DATA ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0), + (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0), + (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0), @@ -177,8 +219,8 @@ + (0.03E0,0.03E0), (-0.18E0,0.03E0), + (0.03E0,-0.09E0), (7.0E0,8.0E0), (7.0E0,8.0E0), + (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0), - + (0.09E0,0.03E0), (0.03E0,0.12E0), - + (0.12E0,0.03E0), (0.03E0,0.06E0), (2.0E0,3.0E0), + + (0.09E0,0.03E0), (0.15E0,0.00E0), + + (0.00E0,0.15E0), (0.00E0,0.06E0), (2.0E0,3.0E0), + (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/ DATA ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0), + (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0), @@ -193,8 +235,8 @@ + (-0.18E0,0.03E0), (4.0E0,7.0E0), + (0.03E0,-0.09E0), (7.0E0,2.0E0), (7.0E0,2.0E0), + (7.0E0,2.0E0), (0.09E0,0.03E0), (5.0E0,8.0E0), - + (0.03E0,0.12E0), (6.0E0,9.0E0), (0.12E0,0.03E0), - + (8.0E0,3.0E0), (0.03E0,0.06E0), (9.0E0,4.0E0)/ + + (0.15E0,0.00E0), (6.0E0,9.0E0), (0.00E0,0.15E0), + + (8.0E0,3.0E0), (0.00E0,0.06E0), (9.0E0,4.0E0)/ DATA ITRUE3/0, 1, 2, 2, 2/ * .. Executable Statements .. DO 60 INCX = 1, 2 @@ -529,7 +571,8 @@ * * .. Parameters .. INTEGER NOUT - PARAMETER (NOUT=6) + REAL ZERO + PARAMETER (NOUT=6, ZERO=0.0E0) * .. Scalar Arguments .. REAL SFAC INTEGER LEN @@ -552,7 +595,7 @@ * DO 40 I = 1, LEN SD = SCOMP(I) - STRUE(I) - IF (SDIFF(ABS(SSIZE(I))+ABS(SFAC*SD),ABS(SSIZE(I))).EQ.0.0E0) + IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO)) + GO TO 40 * * HERE SCOMP(I) IS NOT CLOSE TO STRUE(I). diff --git a/gtsam/3rdparty/Eigen/blas/testing/cblat2.f b/gtsam/3rdparty/Eigen/blas/testing/cblat2.f index 20f188100..5833ea81a 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/cblat2.f +++ b/gtsam/3rdparty/Eigen/blas/testing/cblat2.f @@ -1,68 +1,114 @@ +*> \brief \b CBLAT2 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM CBLAT2 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX Level 2 Blas. +*> +*> The program must be driven by a short data file. The first 18 records +*> of the file are read using list-directed input, the last 17 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 35 lines: +*> 'cblat2.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'CBLA2T.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 4 NUMBER OF VALUES OF K +*> 0 1 2 4 VALUES OF K +*> 4 NUMBER OF VALUES OF INCX AND INCY +*> 1 2 -1 -2 VALUES OF INCX AND INCY +*> 3 NUMBER OF VALUES OF ALPHA +*> (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA +*> CGEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CGBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CHEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CHBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CHPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTRMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTRSV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTBSV T PUT F FOR NO TEST. SAME COLUMNS. +*> CTPSV T PUT F FOR NO TEST. SAME COLUMNS. +*> CGERC T PUT F FOR NO TEST. SAME COLUMNS. +*> CGERU T PUT F FOR NO TEST. SAME COLUMNS. +*> CHER T PUT F FOR NO TEST. SAME COLUMNS. +*> CHPR T PUT F FOR NO TEST. SAME COLUMNS. +*> CHER2 T PUT F FOR NO TEST. SAME COLUMNS. +*> CHPR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. +*> An extended set of Fortran Basic Linear Algebra Subprograms. +*> +*> Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics +*> and Computer Science Division, Argonne National Laboratory, +*> 9700 South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> Or +*> +*> NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms +*> Group Ltd., NAG Central Office, 256 Banbury Road, Oxford +*> OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st +*> Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. +*> +*> +*> -- Written on 10-August-1987. +*> Richard Hanson, Sandia National Labs. +*> Jeremy Du Croz, NAG Central Office. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex_blas_testing +* +* ===================================================================== PROGRAM CBLAT2 * -* Test program for the COMPLEX Level 2 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 18 records -* of the file are read using list-directed input, the last 17 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 35 lines: -* 'CBLAT2.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'CBLA2T.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 4 NUMBER OF VALUES OF K -* 0 1 2 4 VALUES OF K -* 4 NUMBER OF VALUES OF INCX AND INCY -* 1 2 -1 -2 VALUES OF INCX AND INCY -* 3 NUMBER OF VALUES OF ALPHA -* (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA -* CGEMV T PUT F FOR NO TEST. SAME COLUMNS. -* CGBMV T PUT F FOR NO TEST. SAME COLUMNS. -* CHEMV T PUT F FOR NO TEST. SAME COLUMNS. -* CHBMV T PUT F FOR NO TEST. SAME COLUMNS. -* CHPMV T PUT F FOR NO TEST. SAME COLUMNS. -* CTRMV T PUT F FOR NO TEST. SAME COLUMNS. -* CTBMV T PUT F FOR NO TEST. SAME COLUMNS. -* CTPMV T PUT F FOR NO TEST. SAME COLUMNS. -* CTRSV T PUT F FOR NO TEST. SAME COLUMNS. -* CTBSV T PUT F FOR NO TEST. SAME COLUMNS. -* CTPSV T PUT F FOR NO TEST. SAME COLUMNS. -* CGERC T PUT F FOR NO TEST. SAME COLUMNS. -* CGERU T PUT F FOR NO TEST. SAME COLUMNS. -* CHER T PUT F FOR NO TEST. SAME COLUMNS. -* CHPR T PUT F FOR NO TEST. SAME COLUMNS. -* CHER2 T PUT F FOR NO TEST. SAME COLUMNS. -* CHPR2 T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. -* An extended set of Fortran Basic Linear Algebra Subprograms. -* -* Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics -* and Computer Science Division, Argonne National Laboratory, -* 9700 South Cass Avenue, Argonne, Illinois 60439, US. -* -* Or -* -* NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms -* Group Ltd., NAG Central Office, 256 Banbury Road, Oxford -* OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st -* Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. -* -* -* -- Written on 10-August-1987. -* Richard Hanson, Sandia National Labs. -* Jeremy Du Croz, NAG Central Office. +* ===================================================================== * * .. Parameters .. INTEGER NIN @@ -71,8 +117,8 @@ PARAMETER ( NSUBS = 17 ) COMPLEX ZERO, ONE PARAMETER ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) ) - REAL RZERO, RHALF, RONE - PARAMETER ( RZERO = 0.0, RHALF = 0.5, RONE = 1.0 ) + REAL RZERO + PARAMETER ( RZERO = 0.0 ) INTEGER NMAX, INCMAX PARAMETER ( NMAX = 65, INCMAX = 2 ) INTEGER NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX @@ -126,7 +172,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -135,7 +181,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -240,14 +286,7 @@ * * Compute EPS (the machine precision). * - EPS = RONE - 90 CONTINUE - IF( SDIFF( RONE + EPS, RONE ).EQ.RZERO ) - $ GO TO 100 - EPS = RHALF*EPS - GO TO 90 - 100 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(RZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of CMVCH using exact data. @@ -3079,7 +3118,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LCERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/cblat3.f b/gtsam/3rdparty/Eigen/blas/testing/cblat3.f index b26be91e6..09f2cb9c5 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/cblat3.f +++ b/gtsam/3rdparty/Eigen/blas/testing/cblat3.f @@ -1,50 +1,96 @@ +*> \brief \b CBLAT3 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM CBLAT3 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX Level 3 Blas. +*> +*> The program must be driven by a short data file. The first 14 records +*> of the file are read using list-directed input, the last 9 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 23 lines: +*> 'cblat3.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'CBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 3 NUMBER OF VALUES OF ALPHA +*> (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA +*> CGEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> CHEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> CSYMM T PUT F FOR NO TEST. SAME COLUMNS. +*> CTRMM T PUT F FOR NO TEST. SAME COLUMNS. +*> CTRSM T PUT F FOR NO TEST. SAME COLUMNS. +*> CHERK T PUT F FOR NO TEST. SAME COLUMNS. +*> CSYRK T PUT F FOR NO TEST. SAME COLUMNS. +*> CHER2K T PUT F FOR NO TEST. SAME COLUMNS. +*> CSYR2K T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. +*> A Set of Level 3 Basic Linear Algebra Subprograms. +*> +*> Technical Memorandum No.88 (Revision 1), Mathematics and +*> Computer Science Division, Argonne National Laboratory, 9700 +*> South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> -- Written on 8-February-1989. +*> Jack Dongarra, Argonne National Laboratory. +*> Iain Duff, AERE Harwell. +*> Jeremy Du Croz, Numerical Algorithms Group Ltd. +*> Sven Hammarling, Numerical Algorithms Group Ltd. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex_blas_testing +* +* ===================================================================== PROGRAM CBLAT3 * -* Test program for the COMPLEX Level 3 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 14 records -* of the file are read using list-directed input, the last 9 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 23 lines: -* 'CBLAT3.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'CBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 3 NUMBER OF VALUES OF ALPHA -* (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA -* CGEMM T PUT F FOR NO TEST. SAME COLUMNS. -* CHEMM T PUT F FOR NO TEST. SAME COLUMNS. -* CSYMM T PUT F FOR NO TEST. SAME COLUMNS. -* CTRMM T PUT F FOR NO TEST. SAME COLUMNS. -* CTRSM T PUT F FOR NO TEST. SAME COLUMNS. -* CHERK T PUT F FOR NO TEST. SAME COLUMNS. -* CSYRK T PUT F FOR NO TEST. SAME COLUMNS. -* CHER2K T PUT F FOR NO TEST. SAME COLUMNS. -* CSYR2K T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. -* A Set of Level 3 Basic Linear Algebra Subprograms. -* -* Technical Memorandum No.88 (Revision 1), Mathematics and -* Computer Science Division, Argonne National Laboratory, 9700 -* South Cass Avenue, Argonne, Illinois 60439, US. -* -* -- Written on 8-February-1989. -* Jack Dongarra, Argonne National Laboratory. -* Iain Duff, AERE Harwell. -* Jeremy Du Croz, Numerical Algorithms Group Ltd. -* Sven Hammarling, Numerical Algorithms Group Ltd. +* ===================================================================== * * .. Parameters .. INTEGER NIN @@ -53,8 +99,8 @@ PARAMETER ( NSUBS = 9 ) COMPLEX ZERO, ONE PARAMETER ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) ) - REAL RZERO, RHALF, RONE - PARAMETER ( RZERO = 0.0, RHALF = 0.5, RONE = 1.0 ) + REAL RZERO + PARAMETER ( RZERO = 0.0 ) INTEGER NMAX PARAMETER ( NMAX = 65 ) INTEGER NIDMAX, NALMAX, NBEMAX @@ -103,7 +149,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -112,7 +158,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -189,14 +235,7 @@ * * Compute EPS (the machine precision). * - EPS = RONE - 70 CONTINUE - IF( SDIFF( RONE + EPS, RONE ).EQ.RZERO ) - $ GO TO 80 - EPS = RHALF*EPS - GO TO 70 - 80 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(RZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of CMMCH using exact data. @@ -1946,7 +1985,7 @@ * * Tests the error exits from the Level 3 Blas. * Requires a special version of the error-handling routine XERBLA. -* ALPHA, RALPHA, BETA, RBETA, A, B and C should not need to be defined. +* A, B and C should not need to be defined. * * Auxiliary routine for test program for Level 3 Blas. * @@ -1956,12 +1995,19 @@ * Jeremy Du Croz, Numerical Algorithms Group Ltd. * Sven Hammarling, Numerical Algorithms Group Ltd. * +* 3-19-92: Initialize ALPHA, BETA, RALPHA, and RBETA (eca) +* 3-19-92: Fix argument 12 in calls to CSYMM and CHEMM +* with INFOT = 9 (eca) +* * .. Scalar Arguments .. INTEGER ISNUM, NOUT CHARACTER*6 SRNAMT * .. Scalars in Common .. INTEGER INFOT, NOUTC LOGICAL LERR, OK +* .. Parameters .. + REAL ONE, TWO + PARAMETER ( ONE = 1.0E0, TWO = 2.0E0 ) * .. Local Scalars .. COMPLEX ALPHA, BETA REAL RALPHA, RBETA @@ -1979,6 +2025,14 @@ * LERR is set to .TRUE. by the special version of XERBLA each time * it is called, and is then tested and re-set by CHKXER. LERR = .FALSE. +* +* Initialize ALPHA, BETA, RALPHA, and RBETA. +* + ALPHA = CMPLX( ONE, -ONE ) + BETA = CMPLX( TWO, -TWO ) + RALPHA = ONE + RBETA = TWO +* GO TO ( 10, 20, 30, 40, 50, 60, 70, 80, $ 90 )ISNUM 10 INFOT = 1 @@ -2205,16 +2259,16 @@ CALL CHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -2272,16 +2326,16 @@ CALL CSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -3268,7 +3322,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LCERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/dblat2.f b/gtsam/3rdparty/Eigen/blas/testing/dblat2.f index 4002d4368..0fa80afa4 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/dblat2.f +++ b/gtsam/3rdparty/Eigen/blas/testing/dblat2.f @@ -1,75 +1,121 @@ +*> \brief \b DBLAT2 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM DBLAT2 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the DOUBLE PRECISION Level 2 Blas. +*> +*> The program must be driven by a short data file. The first 18 records +*> of the file are read using list-directed input, the last 16 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 34 lines: +*> 'dblat2.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'DBLAT2.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 4 NUMBER OF VALUES OF K +*> 0 1 2 4 VALUES OF K +*> 4 NUMBER OF VALUES OF INCX AND INCY +*> 1 2 -1 -2 VALUES OF INCX AND INCY +*> 3 NUMBER OF VALUES OF ALPHA +*> 0.0 1.0 0.7 VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> 0.0 1.0 0.9 VALUES OF BETAC +*> DGEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DGBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DSBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DSPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTRMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTRSV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTBSV T PUT F FOR NO TEST. SAME COLUMNS. +*> DTPSV T PUT F FOR NO TEST. SAME COLUMNS. +*> DGER T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYR T PUT F FOR NO TEST. SAME COLUMNS. +*> DSPR T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> DSPR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. +*> An extended set of Fortran Basic Linear Algebra Subprograms. +*> +*> Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics +*> and Computer Science Division, Argonne National Laboratory, +*> 9700 South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> Or +*> +*> NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms +*> Group Ltd., NAG Central Office, 256 Banbury Road, Oxford +*> OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st +*> Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. +*> +*> +*> -- Written on 10-August-1987. +*> Richard Hanson, Sandia National Labs. +*> Jeremy Du Croz, NAG Central Office. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup double_blas_testing +* +* ===================================================================== PROGRAM DBLAT2 * -* Test program for the DOUBLE PRECISION Level 2 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 18 records -* of the file are read using list-directed input, the last 16 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 34 lines: -* 'DBLAT2.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'DBLAT2.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 4 NUMBER OF VALUES OF K -* 0 1 2 4 VALUES OF K -* 4 NUMBER OF VALUES OF INCX AND INCY -* 1 2 -1 -2 VALUES OF INCX AND INCY -* 3 NUMBER OF VALUES OF ALPHA -* 0.0 1.0 0.7 VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* 0.0 1.0 0.9 VALUES OF BETA -* DGEMV T PUT F FOR NO TEST. SAME COLUMNS. -* DGBMV T PUT F FOR NO TEST. SAME COLUMNS. -* DSYMV T PUT F FOR NO TEST. SAME COLUMNS. -* DSBMV T PUT F FOR NO TEST. SAME COLUMNS. -* DSPMV T PUT F FOR NO TEST. SAME COLUMNS. -* DTRMV T PUT F FOR NO TEST. SAME COLUMNS. -* DTBMV T PUT F FOR NO TEST. SAME COLUMNS. -* DTPMV T PUT F FOR NO TEST. SAME COLUMNS. -* DTRSV T PUT F FOR NO TEST. SAME COLUMNS. -* DTBSV T PUT F FOR NO TEST. SAME COLUMNS. -* DTPSV T PUT F FOR NO TEST. SAME COLUMNS. -* DGER T PUT F FOR NO TEST. SAME COLUMNS. -* DSYR T PUT F FOR NO TEST. SAME COLUMNS. -* DSPR T PUT F FOR NO TEST. SAME COLUMNS. -* DSYR2 T PUT F FOR NO TEST. SAME COLUMNS. -* DSPR2 T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. -* An extended set of Fortran Basic Linear Algebra Subprograms. -* -* Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics -* and Computer Science Division, Argonne National Laboratory, -* 9700 South Cass Avenue, Argonne, Illinois 60439, US. -* -* Or -* -* NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms -* Group Ltd., NAG Central Office, 256 Banbury Road, Oxford -* OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st -* Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. -* -* -* -- Written on 10-August-1987. -* Richard Hanson, Sandia National Labs. -* Jeremy Du Croz, NAG Central Office. +* ===================================================================== * * .. Parameters .. INTEGER NIN PARAMETER ( NIN = 5 ) INTEGER NSUBS PARAMETER ( NSUBS = 16 ) - DOUBLE PRECISION ZERO, HALF, ONE - PARAMETER ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 ) + DOUBLE PRECISION ZERO, ONE + PARAMETER ( ZERO = 0.0D0, ONE = 1.0D0 ) INTEGER NMAX, INCMAX PARAMETER ( NMAX = 65, INCMAX = 2 ) INTEGER NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX @@ -121,7 +167,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -130,7 +176,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -235,14 +281,7 @@ * * Compute EPS (the machine precision). * - EPS = ONE - 90 CONTINUE - IF( DDIFF( ONE + EPS, ONE ).EQ.ZERO ) - $ GO TO 100 - EPS = HALF*EPS - GO TO 90 - 100 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(ZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of DMVCH using exact data. @@ -2982,7 +3021,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LDERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/dblat3.f b/gtsam/3rdparty/Eigen/blas/testing/dblat3.f index 082e03e5e..8d37c7453 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/dblat3.f +++ b/gtsam/3rdparty/Eigen/blas/testing/dblat3.f @@ -1,55 +1,101 @@ +*> \brief \b DBLAT3 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM DBLAT3 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the DOUBLE PRECISION Level 3 Blas. +*> +*> The program must be driven by a short data file. The first 14 records +*> of the file are read using list-directed input, the last 6 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 20 lines: +*> 'dblat3.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'DBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 3 NUMBER OF VALUES OF ALPHA +*> 0.0 1.0 0.7 VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> 0.0 1.0 1.3 VALUES OF BETA +*> DGEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYMM T PUT F FOR NO TEST. SAME COLUMNS. +*> DTRMM T PUT F FOR NO TEST. SAME COLUMNS. +*> DTRSM T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYRK T PUT F FOR NO TEST. SAME COLUMNS. +*> DSYR2K T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. +*> A Set of Level 3 Basic Linear Algebra Subprograms. +*> +*> Technical Memorandum No.88 (Revision 1), Mathematics and +*> Computer Science Division, Argonne National Laboratory, 9700 +*> South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> -- Written on 8-February-1989. +*> Jack Dongarra, Argonne National Laboratory. +*> Iain Duff, AERE Harwell. +*> Jeremy Du Croz, Numerical Algorithms Group Ltd. +*> Sven Hammarling, Numerical Algorithms Group Ltd. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup double_blas_testing +* +* ===================================================================== PROGRAM DBLAT3 * -* Test program for the DOUBLE PRECISION Level 3 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 14 records -* of the file are read using list-directed input, the last 6 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 20 lines: -* 'DBLAT3.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'DBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 3 NUMBER OF VALUES OF ALPHA -* 0.0 1.0 0.7 VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* 0.0 1.0 1.3 VALUES OF BETA -* DGEMM T PUT F FOR NO TEST. SAME COLUMNS. -* DSYMM T PUT F FOR NO TEST. SAME COLUMNS. -* DTRMM T PUT F FOR NO TEST. SAME COLUMNS. -* DTRSM T PUT F FOR NO TEST. SAME COLUMNS. -* DSYRK T PUT F FOR NO TEST. SAME COLUMNS. -* DSYR2K T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. -* A Set of Level 3 Basic Linear Algebra Subprograms. -* -* Technical Memorandum No.88 (Revision 1), Mathematics and -* Computer Science Division, Argonne National Laboratory, 9700 -* South Cass Avenue, Argonne, Illinois 60439, US. -* -* -- Written on 8-February-1989. -* Jack Dongarra, Argonne National Laboratory. -* Iain Duff, AERE Harwell. -* Jeremy Du Croz, Numerical Algorithms Group Ltd. -* Sven Hammarling, Numerical Algorithms Group Ltd. +* ===================================================================== * * .. Parameters .. INTEGER NIN PARAMETER ( NIN = 5 ) INTEGER NSUBS PARAMETER ( NSUBS = 6 ) - DOUBLE PRECISION ZERO, HALF, ONE - PARAMETER ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 ) + DOUBLE PRECISION ZERO, ONE + PARAMETER ( ZERO = 0.0D0, ONE = 1.0D0 ) INTEGER NMAX PARAMETER ( NMAX = 65 ) INTEGER NIDMAX, NALMAX, NBEMAX @@ -96,7 +142,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -105,7 +151,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -182,14 +228,7 @@ * * Compute EPS (the machine precision). * - EPS = ONE - 70 CONTINUE - IF( DDIFF( ONE + EPS, ONE ).EQ.ZERO ) - $ GO TO 80 - EPS = HALF*EPS - GO TO 70 - 80 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(ZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of DMMCH using exact data. @@ -1802,7 +1841,7 @@ * * Tests the error exits from the Level 3 Blas. * Requires a special version of the error-handling routine XERBLA. -* ALPHA, BETA, A, B and C should not need to be defined. +* A, B and C should not need to be defined. * * Auxiliary routine for test program for Level 3 Blas. * @@ -1812,12 +1851,18 @@ * Jeremy Du Croz, Numerical Algorithms Group Ltd. * Sven Hammarling, Numerical Algorithms Group Ltd. * +* 3-19-92: Initialize ALPHA and BETA (eca) +* 3-19-92: Fix argument 12 in calls to SSYMM with INFOT = 9 (eca) +* * .. Scalar Arguments .. INTEGER ISNUM, NOUT CHARACTER*6 SRNAMT * .. Scalars in Common .. INTEGER INFOT, NOUTC LOGICAL LERR, OK +* .. Parameters .. + DOUBLE PRECISION ONE, TWO + PARAMETER ( ONE = 1.0D0, TWO = 2.0D0 ) * .. Local Scalars .. DOUBLE PRECISION ALPHA, BETA * .. Local Arrays .. @@ -1834,6 +1879,12 @@ * LERR is set to .TRUE. by the special version of XERBLA each time * it is called, and is then tested and re-set by CHKXER. LERR = .FALSE. +* +* Initialize ALPHA and BETA. +* + ALPHA = ONE + BETA = TWO +* GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM 10 INFOT = 1 CALL DGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) @@ -1963,16 +2014,16 @@ CALL DSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -2660,7 +2711,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LDERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/sblat2.f b/gtsam/3rdparty/Eigen/blas/testing/sblat2.f index 057a85429..71605ed31 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/sblat2.f +++ b/gtsam/3rdparty/Eigen/blas/testing/sblat2.f @@ -1,75 +1,121 @@ +*> \brief \b SBLAT2 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM SBLAT2 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the REAL Level 2 Blas. +*> +*> The program must be driven by a short data file. The first 18 records +*> of the file are read using list-directed input, the last 16 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 34 lines: +*> 'sblat2.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'SBLAT2.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 4 NUMBER OF VALUES OF K +*> 0 1 2 4 VALUES OF K +*> 4 NUMBER OF VALUES OF INCX AND INCY +*> 1 2 -1 -2 VALUES OF INCX AND INCY +*> 3 NUMBER OF VALUES OF ALPHA +*> 0.0 1.0 0.7 VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> 0.0 1.0 0.9 VALUES OF BETA +*> SGEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> SGBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYMV T PUT F FOR NO TEST. SAME COLUMNS. +*> SSBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> SSPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> STRMV T PUT F FOR NO TEST. SAME COLUMNS. +*> STBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> STPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> STRSV T PUT F FOR NO TEST. SAME COLUMNS. +*> STBSV T PUT F FOR NO TEST. SAME COLUMNS. +*> STPSV T PUT F FOR NO TEST. SAME COLUMNS. +*> SGER T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYR T PUT F FOR NO TEST. SAME COLUMNS. +*> SSPR T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> SSPR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. +*> An extended set of Fortran Basic Linear Algebra Subprograms. +*> +*> Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics +*> and Computer Science Division, Argonne National Laboratory, +*> 9700 South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> Or +*> +*> NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms +*> Group Ltd., NAG Central Office, 256 Banbury Road, Oxford +*> OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st +*> Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. +*> +*> +*> -- Written on 10-August-1987. +*> Richard Hanson, Sandia National Labs. +*> Jeremy Du Croz, NAG Central Office. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup single_blas_testing +* +* ===================================================================== PROGRAM SBLAT2 * -* Test program for the REAL Level 2 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 18 records -* of the file are read using list-directed input, the last 16 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 34 lines: -* 'SBLAT2.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'SBLAT2.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 4 NUMBER OF VALUES OF K -* 0 1 2 4 VALUES OF K -* 4 NUMBER OF VALUES OF INCX AND INCY -* 1 2 -1 -2 VALUES OF INCX AND INCY -* 3 NUMBER OF VALUES OF ALPHA -* 0.0 1.0 0.7 VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* 0.0 1.0 0.9 VALUES OF BETA -* SGEMV T PUT F FOR NO TEST. SAME COLUMNS. -* SGBMV T PUT F FOR NO TEST. SAME COLUMNS. -* SSYMV T PUT F FOR NO TEST. SAME COLUMNS. -* SSBMV T PUT F FOR NO TEST. SAME COLUMNS. -* SSPMV T PUT F FOR NO TEST. SAME COLUMNS. -* STRMV T PUT F FOR NO TEST. SAME COLUMNS. -* STBMV T PUT F FOR NO TEST. SAME COLUMNS. -* STPMV T PUT F FOR NO TEST. SAME COLUMNS. -* STRSV T PUT F FOR NO TEST. SAME COLUMNS. -* STBSV T PUT F FOR NO TEST. SAME COLUMNS. -* STPSV T PUT F FOR NO TEST. SAME COLUMNS. -* SGER T PUT F FOR NO TEST. SAME COLUMNS. -* SSYR T PUT F FOR NO TEST. SAME COLUMNS. -* SSPR T PUT F FOR NO TEST. SAME COLUMNS. -* SSYR2 T PUT F FOR NO TEST. SAME COLUMNS. -* SSPR2 T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. -* An extended set of Fortran Basic Linear Algebra Subprograms. -* -* Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics -* and Computer Science Division, Argonne National Laboratory, -* 9700 South Cass Avenue, Argonne, Illinois 60439, US. -* -* Or -* -* NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms -* Group Ltd., NAG Central Office, 256 Banbury Road, Oxford -* OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st -* Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. -* -* -* -- Written on 10-August-1987. -* Richard Hanson, Sandia National Labs. -* Jeremy Du Croz, NAG Central Office. +* ===================================================================== * * .. Parameters .. INTEGER NIN PARAMETER ( NIN = 5 ) INTEGER NSUBS PARAMETER ( NSUBS = 16 ) - REAL ZERO, HALF, ONE - PARAMETER ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 ) + REAL ZERO, ONE + PARAMETER ( ZERO = 0.0, ONE = 1.0 ) INTEGER NMAX, INCMAX PARAMETER ( NMAX = 65, INCMAX = 2 ) INTEGER NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX @@ -121,7 +167,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -130,7 +176,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -235,14 +281,7 @@ * * Compute EPS (the machine precision). * - EPS = ONE - 90 CONTINUE - IF( SDIFF( ONE + EPS, ONE ).EQ.ZERO ) - $ GO TO 100 - EPS = HALF*EPS - GO TO 90 - 100 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(ZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of SMVCH using exact data. @@ -2982,7 +3021,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LSERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/sblat3.f b/gtsam/3rdparty/Eigen/blas/testing/sblat3.f index 325a9eb92..879269633 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/sblat3.f +++ b/gtsam/3rdparty/Eigen/blas/testing/sblat3.f @@ -1,55 +1,101 @@ +*> \brief \b SBLAT3 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM SBLAT3 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the REAL Level 3 Blas. +*> +*> The program must be driven by a short data file. The first 14 records +*> of the file are read using list-directed input, the last 6 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 20 lines: +*> 'sblat3.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'SBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 3 NUMBER OF VALUES OF ALPHA +*> 0.0 1.0 0.7 VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> 0.0 1.0 1.3 VALUES OF BETA +*> SGEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYMM T PUT F FOR NO TEST. SAME COLUMNS. +*> STRMM T PUT F FOR NO TEST. SAME COLUMNS. +*> STRSM T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYRK T PUT F FOR NO TEST. SAME COLUMNS. +*> SSYR2K T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. +*> A Set of Level 3 Basic Linear Algebra Subprograms. +*> +*> Technical Memorandum No.88 (Revision 1), Mathematics and +*> Computer Science Division, Argonne National Laboratory, 9700 +*> South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> -- Written on 8-February-1989. +*> Jack Dongarra, Argonne National Laboratory. +*> Iain Duff, AERE Harwell. +*> Jeremy Du Croz, Numerical Algorithms Group Ltd. +*> Sven Hammarling, Numerical Algorithms Group Ltd. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup single_blas_testing +* +* ===================================================================== PROGRAM SBLAT3 * -* Test program for the REAL Level 3 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 14 records -* of the file are read using list-directed input, the last 6 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 20 lines: -* 'SBLAT3.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'SBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 3 NUMBER OF VALUES OF ALPHA -* 0.0 1.0 0.7 VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* 0.0 1.0 1.3 VALUES OF BETA -* SGEMM T PUT F FOR NO TEST. SAME COLUMNS. -* SSYMM T PUT F FOR NO TEST. SAME COLUMNS. -* STRMM T PUT F FOR NO TEST. SAME COLUMNS. -* STRSM T PUT F FOR NO TEST. SAME COLUMNS. -* SSYRK T PUT F FOR NO TEST. SAME COLUMNS. -* SSYR2K T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. -* A Set of Level 3 Basic Linear Algebra Subprograms. -* -* Technical Memorandum No.88 (Revision 1), Mathematics and -* Computer Science Division, Argonne National Laboratory, 9700 -* South Cass Avenue, Argonne, Illinois 60439, US. -* -* -- Written on 8-February-1989. -* Jack Dongarra, Argonne National Laboratory. -* Iain Duff, AERE Harwell. -* Jeremy Du Croz, Numerical Algorithms Group Ltd. -* Sven Hammarling, Numerical Algorithms Group Ltd. +* ===================================================================== * * .. Parameters .. INTEGER NIN PARAMETER ( NIN = 5 ) INTEGER NSUBS PARAMETER ( NSUBS = 6 ) - REAL ZERO, HALF, ONE - PARAMETER ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 ) + REAL ZERO, ONE + PARAMETER ( ZERO = 0.0, ONE = 1.0 ) INTEGER NMAX PARAMETER ( NMAX = 65 ) INTEGER NIDMAX, NALMAX, NBEMAX @@ -96,7 +142,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -105,7 +151,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -182,14 +228,7 @@ * * Compute EPS (the machine precision). * - EPS = ONE - 70 CONTINUE - IF( SDIFF( ONE + EPS, ONE ).EQ.ZERO ) - $ GO TO 80 - EPS = HALF*EPS - GO TO 70 - 80 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(ZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of SMMCH using exact data. @@ -1802,7 +1841,7 @@ * * Tests the error exits from the Level 3 Blas. * Requires a special version of the error-handling routine XERBLA. -* ALPHA, BETA, A, B and C should not need to be defined. +* A, B and C should not need to be defined. * * Auxiliary routine for test program for Level 3 Blas. * @@ -1812,12 +1851,18 @@ * Jeremy Du Croz, Numerical Algorithms Group Ltd. * Sven Hammarling, Numerical Algorithms Group Ltd. * +* 3-19-92: Initialize ALPHA and BETA (eca) +* 3-19-92: Fix argument 12 in calls to SSYMM with INFOT = 9 (eca) +* * .. Scalar Arguments .. INTEGER ISNUM, NOUT CHARACTER*6 SRNAMT * .. Scalars in Common .. INTEGER INFOT, NOUTC LOGICAL LERR, OK +* .. Parameters .. + REAL ONE, TWO + PARAMETER ( ONE = 1.0E0, TWO = 2.0E0 ) * .. Local Scalars .. REAL ALPHA, BETA * .. Local Arrays .. @@ -1834,6 +1879,12 @@ * LERR is set to .TRUE. by the special version of XERBLA each time * it is called, and is then tested and re-set by CHKXER. LERR = .FALSE. +* +* Initialize ALPHA and BETA. +* + ALPHA = ONE + BETA = TWO +* GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM 10 INFOT = 1 CALL SGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) @@ -1963,16 +2014,16 @@ CALL SSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -2660,7 +2711,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LSERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/zblat1.f b/gtsam/3rdparty/Eigen/blas/testing/zblat1.f index e2415e1c4..d30112c63 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/zblat1.f +++ b/gtsam/3rdparty/Eigen/blas/testing/zblat1.f @@ -1,7 +1,49 @@ +*> \brief \b ZBLAT1 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM ZBLAT1 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX*16 Level 1 BLAS. +*> +*> Based upon the original BLAS test routine together with: +*> F06GAF Example Program Text +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex16_blas_testing +* +* ===================================================================== PROGRAM ZBLAT1 -* Test program for the COMPLEX*16 Level 1 BLAS. -* Based upon the original BLAS test routine together with: -* F06GAF Example Program Text +* +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 +* +* ===================================================================== +* * .. Parameters .. INTEGER NOUT PARAMETER (NOUT=6) @@ -114,8 +156,8 @@ + (5.0D0,6.0D0), (5.0D0,6.0D0), (0.1D0,0.1D0), + (-0.6D0,0.1D0), (0.1D0,-0.3D0), (7.0D0,8.0D0), + (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0), - + (7.0D0,8.0D0), (0.3D0,0.1D0), (0.1D0,0.4D0), - + (0.4D0,0.1D0), (0.1D0,0.2D0), (2.0D0,3.0D0), + + (7.0D0,8.0D0), (0.3D0,0.1D0), (0.5D0,0.0D0), + + (0.0D0,0.5D0), (0.0D0,0.2D0), (2.0D0,3.0D0), + (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/ DATA ((CV(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0), + (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0), @@ -129,10 +171,10 @@ + (3.0D0,6.0D0), (-0.6D0,0.1D0), (4.0D0,7.0D0), + (0.1D0,-0.3D0), (7.0D0,2.0D0), (7.0D0,2.0D0), + (7.0D0,2.0D0), (0.3D0,0.1D0), (5.0D0,8.0D0), - + (0.1D0,0.4D0), (6.0D0,9.0D0), (0.4D0,0.1D0), - + (8.0D0,3.0D0), (0.1D0,0.2D0), (9.0D0,4.0D0)/ - DATA STRUE2/0.0D0, 0.5D0, 0.6D0, 0.7D0, 0.7D0/ - DATA STRUE4/0.0D0, 0.7D0, 1.0D0, 1.3D0, 1.7D0/ + + (0.5D0,0.0D0), (6.0D0,9.0D0), (0.0D0,0.5D0), + + (8.0D0,3.0D0), (0.0D0,0.2D0), (9.0D0,4.0D0)/ + DATA STRUE2/0.0D0, 0.5D0, 0.6D0, 0.7D0, 0.8D0/ + DATA STRUE4/0.0D0, 0.7D0, 1.0D0, 1.3D0, 1.6D0/ DATA ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0), + (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0), + (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0), @@ -145,8 +187,8 @@ + (0.11D0,-0.03D0), (-0.17D0,0.46D0), + (-0.17D0,-0.19D0), (7.0D0,8.0D0), (7.0D0,8.0D0), + (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0), - + (0.19D0,-0.17D0), (0.32D0,0.09D0), - + (0.23D0,-0.24D0), (0.18D0,0.01D0), + + (0.19D0,-0.17D0), (0.20D0,-0.35D0), + + (0.35D0,0.20D0), (0.14D0,0.08D0), + (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0), + (2.0D0,3.0D0)/ DATA ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0), @@ -162,9 +204,9 @@ + (-0.17D0,0.46D0), (4.0D0,7.0D0), + (-0.17D0,-0.19D0), (7.0D0,2.0D0), (7.0D0,2.0D0), + (7.0D0,2.0D0), (0.19D0,-0.17D0), (5.0D0,8.0D0), - + (0.32D0,0.09D0), (6.0D0,9.0D0), - + (0.23D0,-0.24D0), (8.0D0,3.0D0), - + (0.18D0,0.01D0), (9.0D0,4.0D0)/ + + (0.20D0,-0.35D0), (6.0D0,9.0D0), + + (0.35D0,0.20D0), (8.0D0,3.0D0), + + (0.14D0,0.08D0), (9.0D0,4.0D0)/ DATA ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0), + (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0), + (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0), @@ -177,8 +219,8 @@ + (0.03D0,0.03D0), (-0.18D0,0.03D0), + (0.03D0,-0.09D0), (7.0D0,8.0D0), (7.0D0,8.0D0), + (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0), - + (0.09D0,0.03D0), (0.03D0,0.12D0), - + (0.12D0,0.03D0), (0.03D0,0.06D0), (2.0D0,3.0D0), + + (0.09D0,0.03D0), (0.15D0,0.00D0), + + (0.00D0,0.15D0), (0.00D0,0.06D0), (2.0D0,3.0D0), + (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/ DATA ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0), + (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0), @@ -193,8 +235,8 @@ + (-0.18D0,0.03D0), (4.0D0,7.0D0), + (0.03D0,-0.09D0), (7.0D0,2.0D0), (7.0D0,2.0D0), + (7.0D0,2.0D0), (0.09D0,0.03D0), (5.0D0,8.0D0), - + (0.03D0,0.12D0), (6.0D0,9.0D0), (0.12D0,0.03D0), - + (8.0D0,3.0D0), (0.03D0,0.06D0), (9.0D0,4.0D0)/ + + (0.15D0,0.00D0), (6.0D0,9.0D0), (0.00D0,0.15D0), + + (8.0D0,3.0D0), (0.00D0,0.06D0), (9.0D0,4.0D0)/ DATA ITRUE3/0, 1, 2, 2, 2/ * .. Executable Statements .. DO 60 INCX = 1, 2 @@ -529,7 +571,8 @@ * * .. Parameters .. INTEGER NOUT - PARAMETER (NOUT=6) + DOUBLE PRECISION ZERO + PARAMETER (NOUT=6, ZERO=0.0D0) * .. Scalar Arguments .. DOUBLE PRECISION SFAC INTEGER LEN @@ -552,7 +595,7 @@ * DO 40 I = 1, LEN SD = SCOMP(I) - STRUE(I) - IF (SDIFF(ABS(SSIZE(I))+ABS(SFAC*SD),ABS(SSIZE(I))).EQ.0.0D0) + IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO)) + GO TO 40 * * HERE SCOMP(I) IS NOT CLOSE TO STRUE(I). diff --git a/gtsam/3rdparty/Eigen/blas/testing/zblat2.f b/gtsam/3rdparty/Eigen/blas/testing/zblat2.f index e65cdcc70..53129a11e 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/zblat2.f +++ b/gtsam/3rdparty/Eigen/blas/testing/zblat2.f @@ -1,68 +1,114 @@ +*> \brief \b ZBLAT2 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM ZBLAT2 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX*16 Level 2 Blas. +*> +*> The program must be driven by a short data file. The first 18 records +*> of the file are read using list-directed input, the last 17 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 35 lines: +*> 'zblat2.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'CBLA2T.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 4 NUMBER OF VALUES OF K +*> 0 1 2 4 VALUES OF K +*> 4 NUMBER OF VALUES OF INCX AND INCY +*> 1 2 -1 -2 VALUES OF INCX AND INCY +*> 3 NUMBER OF VALUES OF ALPHA +*> (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA +*> ZGEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZGBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHEMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTRMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTBMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTPMV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTRSV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTBSV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTPSV T PUT F FOR NO TEST. SAME COLUMNS. +*> ZGERC T PUT F FOR NO TEST. SAME COLUMNS. +*> ZGERU T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHER T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHPR T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHER2 T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHPR2 T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. +*> An extended set of Fortran Basic Linear Algebra Subprograms. +*> +*> Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics +*> and Computer Science Division, Argonne National Laboratory, +*> 9700 South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> Or +*> +*> NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms +*> Group Ltd., NAG Central Office, 256 Banbury Road, Oxford +*> OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st +*> Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. +*> +*> +*> -- Written on 10-August-1987. +*> Richard Hanson, Sandia National Labs. +*> Jeremy Du Croz, NAG Central Office. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex16_blas_testing +* +* ===================================================================== PROGRAM ZBLAT2 * -* Test program for the COMPLEX*16 Level 2 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 18 records -* of the file are read using list-directed input, the last 17 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 35 lines: -* 'ZBLAT2.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'CBLA2T.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 4 NUMBER OF VALUES OF K -* 0 1 2 4 VALUES OF K -* 4 NUMBER OF VALUES OF INCX AND INCY -* 1 2 -1 -2 VALUES OF INCX AND INCY -* 3 NUMBER OF VALUES OF ALPHA -* (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA -* ZGEMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZGBMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZHEMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZHBMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZHPMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTRMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTBMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTPMV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTRSV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTBSV T PUT F FOR NO TEST. SAME COLUMNS. -* ZTPSV T PUT F FOR NO TEST. SAME COLUMNS. -* ZGERC T PUT F FOR NO TEST. SAME COLUMNS. -* ZGERU T PUT F FOR NO TEST. SAME COLUMNS. -* ZHER T PUT F FOR NO TEST. SAME COLUMNS. -* ZHPR T PUT F FOR NO TEST. SAME COLUMNS. -* ZHER2 T PUT F FOR NO TEST. SAME COLUMNS. -* ZHPR2 T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Hammarling S. and Hanson R. J.. -* An extended set of Fortran Basic Linear Algebra Subprograms. -* -* Technical Memoranda Nos. 41 (revision 3) and 81, Mathematics -* and Computer Science Division, Argonne National Laboratory, -* 9700 South Cass Avenue, Argonne, Illinois 60439, US. -* -* Or -* -* NAG Technical Reports TR3/87 and TR4/87, Numerical Algorithms -* Group Ltd., NAG Central Office, 256 Banbury Road, Oxford -* OX2 7DE, UK, and Numerical Algorithms Group Inc., 1101 31st -* Street, Suite 100, Downers Grove, Illinois 60515-1263, USA. -* -* -* -- Written on 10-August-1987. -* Richard Hanson, Sandia National Labs. -* Jeremy Du Croz, NAG Central Office. +* ===================================================================== * * .. Parameters .. INTEGER NIN @@ -72,8 +118,8 @@ COMPLEX*16 ZERO, ONE PARAMETER ( ZERO = ( 0.0D0, 0.0D0 ), $ ONE = ( 1.0D0, 0.0D0 ) ) - DOUBLE PRECISION RZERO, RHALF, RONE - PARAMETER ( RZERO = 0.0D0, RHALF = 0.5D0, RONE = 1.0D0 ) + DOUBLE PRECISION RZERO + PARAMETER ( RZERO = 0.0D0 ) INTEGER NMAX, INCMAX PARAMETER ( NMAX = 65, INCMAX = 2 ) INTEGER NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX @@ -127,7 +173,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -136,7 +182,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -241,14 +287,7 @@ * * Compute EPS (the machine precision). * - EPS = RONE - 90 CONTINUE - IF( DDIFF( RONE + EPS, RONE ).EQ.RZERO ) - $ GO TO 100 - EPS = RHALF*EPS - GO TO 90 - 100 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(RZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of ZMVCH using exact data. @@ -3087,7 +3126,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LZERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/testing/zblat3.f b/gtsam/3rdparty/Eigen/blas/testing/zblat3.f index d6a522f2a..59ca24145 100644 --- a/gtsam/3rdparty/Eigen/blas/testing/zblat3.f +++ b/gtsam/3rdparty/Eigen/blas/testing/zblat3.f @@ -1,50 +1,97 @@ +*> \brief \b ZBLAT3 +* +* =========== DOCUMENTATION =========== +* +* Online html documentation available at +* http://www.netlib.org/lapack/explore-html/ +* +* Definition: +* =========== +* +* PROGRAM ZBLAT3 +* +* +*> \par Purpose: +* ============= +*> +*> \verbatim +*> +*> Test program for the COMPLEX*16 Level 3 Blas. +*> +*> The program must be driven by a short data file. The first 14 records +*> of the file are read using list-directed input, the last 9 records +*> are read using the format ( A6, L2 ). An annotated example of a data +*> file can be obtained by deleting the first 3 characters from the +*> following 23 lines: +*> 'zblat3.out' NAME OF SUMMARY OUTPUT FILE +*> 6 UNIT NUMBER OF SUMMARY FILE +*> 'ZBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE +*> -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) +*> F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. +*> F LOGICAL FLAG, T TO STOP ON FAILURES. +*> T LOGICAL FLAG, T TO TEST ERROR EXITS. +*> 16.0 THRESHOLD VALUE OF TEST RATIO +*> 6 NUMBER OF VALUES OF N +*> 0 1 2 3 5 9 VALUES OF N +*> 3 NUMBER OF VALUES OF ALPHA +*> (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA +*> 3 NUMBER OF VALUES OF BETA +*> (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA +*> ZGEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHEMM T PUT F FOR NO TEST. SAME COLUMNS. +*> ZSYMM T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTRMM T PUT F FOR NO TEST. SAME COLUMNS. +*> ZTRSM T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHERK T PUT F FOR NO TEST. SAME COLUMNS. +*> ZSYRK T PUT F FOR NO TEST. SAME COLUMNS. +*> ZHER2K T PUT F FOR NO TEST. SAME COLUMNS. +*> ZSYR2K T PUT F FOR NO TEST. SAME COLUMNS. +*> +*> +*> Further Details +*> =============== +*> +*> See: +*> +*> Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. +*> A Set of Level 3 Basic Linear Algebra Subprograms. +*> +*> Technical Memorandum No.88 (Revision 1), Mathematics and +*> Computer Science Division, Argonne National Laboratory, 9700 +*> South Cass Avenue, Argonne, Illinois 60439, US. +*> +*> -- Written on 8-February-1989. +*> Jack Dongarra, Argonne National Laboratory. +*> Iain Duff, AERE Harwell. +*> Jeremy Du Croz, Numerical Algorithms Group Ltd. +*> Sven Hammarling, Numerical Algorithms Group Ltd. +*> +*> 10-9-00: Change STATUS='NEW' to 'UNKNOWN' so that the testers +*> can be run multiple times without deleting generated +*> output files (susan) +*> \endverbatim +* +* Authors: +* ======== +* +*> \author Univ. of Tennessee +*> \author Univ. of California Berkeley +*> \author Univ. of Colorado Denver +*> \author NAG Ltd. +* +*> \date April 2012 +* +*> \ingroup complex16_blas_testing +* +* ===================================================================== PROGRAM ZBLAT3 * -* Test program for the COMPLEX*16 Level 3 Blas. +* -- Reference BLAS test routine (version 3.4.1) -- +* -- Reference BLAS is a software package provided by Univ. of Tennessee, -- +* -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..-- +* April 2012 * -* The program must be driven by a short data file. The first 14 records -* of the file are read using list-directed input, the last 9 records -* are read using the format ( A6, L2 ). An annotated example of a data -* file can be obtained by deleting the first 3 characters from the -* following 23 lines: -* 'ZBLAT3.SUMM' NAME OF SUMMARY OUTPUT FILE -* 6 UNIT NUMBER OF SUMMARY FILE -* 'ZBLAT3.SNAP' NAME OF SNAPSHOT OUTPUT FILE -* -1 UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0) -* F LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD. -* F LOGICAL FLAG, T TO STOP ON FAILURES. -* T LOGICAL FLAG, T TO TEST ERROR EXITS. -* 16.0 THRESHOLD VALUE OF TEST RATIO -* 6 NUMBER OF VALUES OF N -* 0 1 2 3 5 9 VALUES OF N -* 3 NUMBER OF VALUES OF ALPHA -* (0.0,0.0) (1.0,0.0) (0.7,-0.9) VALUES OF ALPHA -* 3 NUMBER OF VALUES OF BETA -* (0.0,0.0) (1.0,0.0) (1.3,-1.1) VALUES OF BETA -* ZGEMM T PUT F FOR NO TEST. SAME COLUMNS. -* ZHEMM T PUT F FOR NO TEST. SAME COLUMNS. -* ZSYMM T PUT F FOR NO TEST. SAME COLUMNS. -* ZTRMM T PUT F FOR NO TEST. SAME COLUMNS. -* ZTRSM T PUT F FOR NO TEST. SAME COLUMNS. -* ZHERK T PUT F FOR NO TEST. SAME COLUMNS. -* ZSYRK T PUT F FOR NO TEST. SAME COLUMNS. -* ZHER2K T PUT F FOR NO TEST. SAME COLUMNS. -* ZSYR2K T PUT F FOR NO TEST. SAME COLUMNS. -* -* See: -* -* Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S. -* A Set of Level 3 Basic Linear Algebra Subprograms. -* -* Technical Memorandum No.88 (Revision 1), Mathematics and -* Computer Science Division, Argonne National Laboratory, 9700 -* South Cass Avenue, Argonne, Illinois 60439, US. -* -* -- Written on 8-February-1989. -* Jack Dongarra, Argonne National Laboratory. -* Iain Duff, AERE Harwell. -* Jeremy Du Croz, Numerical Algorithms Group Ltd. -* Sven Hammarling, Numerical Algorithms Group Ltd. +* ===================================================================== * * .. Parameters .. INTEGER NIN @@ -54,8 +101,8 @@ COMPLEX*16 ZERO, ONE PARAMETER ( ZERO = ( 0.0D0, 0.0D0 ), $ ONE = ( 1.0D0, 0.0D0 ) ) - DOUBLE PRECISION RZERO, RHALF, RONE - PARAMETER ( RZERO = 0.0D0, RHALF = 0.5D0, RONE = 1.0D0 ) + DOUBLE PRECISION RZERO + PARAMETER ( RZERO = 0.0D0 ) INTEGER NMAX PARAMETER ( NMAX = 65 ) INTEGER NIDMAX, NALMAX, NBEMAX @@ -104,7 +151,7 @@ * READ( NIN, FMT = * )SUMMRY READ( NIN, FMT = * )NOUT - OPEN( NOUT, FILE = SUMMRY, STATUS = 'NEW' ) + OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' ) NOUTC = NOUT * * Read name and unit number for snapshot output file and open file. @@ -113,7 +160,7 @@ READ( NIN, FMT = * )NTRA TRACE = NTRA.GE.0 IF( TRACE )THEN - OPEN( NTRA, FILE = SNAPS, STATUS = 'NEW' ) + OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' ) END IF * Read the flag that directs rewinding of the snapshot file. READ( NIN, FMT = * )REWI @@ -190,14 +237,7 @@ * * Compute EPS (the machine precision). * - EPS = RONE - 70 CONTINUE - IF( DDIFF( RONE + EPS, RONE ).EQ.RZERO ) - $ GO TO 80 - EPS = RHALF*EPS - GO TO 70 - 80 CONTINUE - EPS = EPS + EPS + EPS = EPSILON(RZERO) WRITE( NOUT, FMT = 9998 )EPS * * Check the reliability of ZMMCH using exact data. @@ -1949,7 +1989,7 @@ * * Tests the error exits from the Level 3 Blas. * Requires a special version of the error-handling routine XERBLA. -* ALPHA, RALPHA, BETA, RBETA, A, B and C should not need to be defined. +* A, B and C should not need to be defined. * * Auxiliary routine for test program for Level 3 Blas. * @@ -1959,12 +1999,20 @@ * Jeremy Du Croz, Numerical Algorithms Group Ltd. * Sven Hammarling, Numerical Algorithms Group Ltd. * +* 3-19-92: Initialize ALPHA, BETA, RALPHA, and RBETA (eca) +* 3-19-92: Fix argument 12 in calls to ZSYMM and ZHEMM +* with INFOT = 9 (eca) +* 10-9-00: Declared INTRINSIC DCMPLX (susan) +* * .. Scalar Arguments .. INTEGER ISNUM, NOUT CHARACTER*6 SRNAMT * .. Scalars in Common .. INTEGER INFOT, NOUTC LOGICAL LERR, OK +* .. Parameters .. + REAL ONE, TWO + PARAMETER ( ONE = 1.0D0, TWO = 2.0D0 ) * .. Local Scalars .. COMPLEX*16 ALPHA, BETA DOUBLE PRECISION RALPHA, RBETA @@ -1973,6 +2021,8 @@ * .. External Subroutines .. EXTERNAL ZGEMM, ZHEMM, ZHER2K, ZHERK, CHKXER, ZSYMM, $ ZSYR2K, ZSYRK, ZTRMM, ZTRSM +* .. Intrinsic Functions .. + INTRINSIC DCMPLX * .. Common blocks .. COMMON /INFOC/INFOT, NOUTC, OK, LERR * .. Executable Statements .. @@ -1982,6 +2032,14 @@ * LERR is set to .TRUE. by the special version of XERBLA each time * it is called, and is then tested and re-set by CHKXER. LERR = .FALSE. +* +* Initialize ALPHA, BETA, RALPHA, and RBETA. +* + ALPHA = DCMPLX( ONE, -ONE ) + BETA = DCMPLX( TWO, -TWO ) + RALPHA = ONE + RBETA = TWO +* GO TO ( 10, 20, 30, 40, 50, 60, 70, 80, $ 90 )ISNUM 10 INFOT = 1 @@ -2208,16 +2266,16 @@ CALL ZHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -2275,16 +2333,16 @@ CALL ZSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 1 ) + CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 9 - CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 ) + CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 ) CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK ) INFOT = 12 CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 ) @@ -3274,7 +3332,6 @@ 50 CONTINUE END IF * - 60 CONTINUE LZERES = .TRUE. GO TO 80 70 CONTINUE diff --git a/gtsam/3rdparty/Eigen/blas/xerbla.cpp b/gtsam/3rdparty/Eigen/blas/xerbla.cpp index dd39a5244..c373e8699 100644 --- a/gtsam/3rdparty/Eigen/blas/xerbla.cpp +++ b/gtsam/3rdparty/Eigen/blas/xerbla.cpp @@ -1,5 +1,5 @@ -#include +#include #if (defined __GNUC__) && (!defined __MINGW32__) && (!defined __CYGWIN__) #define EIGEN_WEAK_LINKING __attribute__ ((weak)) @@ -14,7 +14,7 @@ extern "C" EIGEN_WEAK_LINKING int xerbla_(const char * msg, int *info, int) { - std::cerr << "Eigen BLAS ERROR #" << *info << ": " << msg << "\n"; + printf("Eigen BLAS ERROR #%i: %s\n", *info, msg ); return 0; } diff --git a/gtsam/3rdparty/Eigen/blas/zhbmv.f b/gtsam/3rdparty/Eigen/blas/zhbmv.f deleted file mode 100644 index bca0da5fc..000000000 --- a/gtsam/3rdparty/Eigen/blas/zhbmv.f +++ /dev/null @@ -1,310 +0,0 @@ - SUBROUTINE ZHBMV(UPLO,N,K,ALPHA,A,LDA,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - DOUBLE COMPLEX ALPHA,BETA - INTEGER INCX,INCY,K,LDA,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - DOUBLE COMPLEX A(LDA,*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* ZHBMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n hermitian band matrix, with k super-diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the band matrix A is being supplied as -* follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* being supplied. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* being supplied. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry, K specifies the number of super-diagonals of the -* matrix A. K must satisfy 0 .le. K. -* Unchanged on exit. -* -* ALPHA - COMPLEX*16 . -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* A - COMPLEX*16 array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the hermitian matrix, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer the upper -* triangular part of a hermitian band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the hermitian matrix, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer the lower -* triangular part of a hermitian band matrix from conventional -* full matrix storage to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that the imaginary parts of the diagonal elements need -* not be set and are assumed to be zero. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX*16 array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the -* vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - COMPLEX*16 . -* On entry, BETA specifies the scalar beta. -* Unchanged on exit. -* -* Y - COMPLEX*16 array of DIMENSION at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the -* vector y. On exit, Y is overwritten by the updated vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE COMPLEX ONE - PARAMETER (ONE= (1.0D+0,0.0D+0)) - DOUBLE COMPLEX ZERO - PARAMETER (ZERO= (0.0D+0,0.0D+0)) -* .. -* .. Local Scalars .. - DOUBLE COMPLEX TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,KPLUS1,KX,KY,L -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC DBLE,DCONJG,MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (K.LT.0) THEN - INFO = 3 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 6 - ELSE IF (INCX.EQ.0) THEN - INFO = 8 - ELSE IF (INCY.EQ.0) THEN - INFO = 11 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('ZHBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array A -* are accessed sequentially with one pass through A. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - IF (LSAME(UPLO,'U')) THEN -* -* Form y when upper triangle of A is stored. -* - KPLUS1 = K + 1 - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - L = KPLUS1 - J - DO 50 I = MAX(1,J-K),J - 1 - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + DCONJG(A(L+I,J))*X(I) - 50 CONTINUE - Y(J) = Y(J) + TEMP1*DBLE(A(KPLUS1,J)) + ALPHA*TEMP2 - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - L = KPLUS1 - J - DO 70 I = MAX(1,J-K),J - 1 - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + DCONJG(A(L+I,J))*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*DBLE(A(KPLUS1,J)) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - IF (J.GT.K) THEN - KX = KX + INCX - KY = KY + INCY - END IF - 80 CONTINUE - END IF - ELSE -* -* Form y when lower triangle of A is stored. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*DBLE(A(1,J)) - L = 1 - J - DO 90 I = J + 1,MIN(N,J+K) - Y(I) = Y(I) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + DCONJG(A(L+I,J))*X(I) - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*DBLE(A(1,J)) - L = 1 - J - IX = JX - IY = JY - DO 110 I = J + 1,MIN(N,J+K) - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*A(L+I,J) - TEMP2 = TEMP2 + DCONJG(A(L+I,J))*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of ZHBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/zhpmv.f b/gtsam/3rdparty/Eigen/blas/zhpmv.f deleted file mode 100644 index b686108b3..000000000 --- a/gtsam/3rdparty/Eigen/blas/zhpmv.f +++ /dev/null @@ -1,272 +0,0 @@ - SUBROUTINE ZHPMV(UPLO,N,ALPHA,AP,X,INCX,BETA,Y,INCY) -* .. Scalar Arguments .. - DOUBLE COMPLEX ALPHA,BETA - INTEGER INCX,INCY,N - CHARACTER UPLO -* .. -* .. Array Arguments .. - DOUBLE COMPLEX AP(*),X(*),Y(*) -* .. -* -* Purpose -* ======= -* -* ZHPMV performs the matrix-vector operation -* -* y := alpha*A*x + beta*y, -* -* where alpha and beta are scalars, x and y are n element vectors and -* A is an n by n hermitian matrix, supplied in packed form. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the upper or lower -* triangular part of the matrix A is supplied in the packed -* array AP as follows: -* -* UPLO = 'U' or 'u' The upper triangular part of A is -* supplied in AP. -* -* UPLO = 'L' or 'l' The lower triangular part of A is -* supplied in AP. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* ALPHA - COMPLEX*16 . -* On entry, ALPHA specifies the scalar alpha. -* Unchanged on exit. -* -* AP - COMPLEX*16 array of DIMENSION at least -* ( ( n*( n + 1 ) )/2 ). -* Before entry with UPLO = 'U' or 'u', the array AP must -* contain the upper triangular part of the hermitian matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) -* and a( 2, 2 ) respectively, and so on. -* Before entry with UPLO = 'L' or 'l', the array AP must -* contain the lower triangular part of the hermitian matrix -* packed sequentially, column by column, so that AP( 1 ) -* contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) -* and a( 3, 1 ) respectively, and so on. -* Note that the imaginary parts of the diagonal elements need -* not be set and are assumed to be zero. -* Unchanged on exit. -* -* X - COMPLEX*16 array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. -* Unchanged on exit. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* BETA - COMPLEX*16 . -* On entry, BETA specifies the scalar beta. When BETA is -* supplied as zero then Y need not be set on input. -* Unchanged on exit. -* -* Y - COMPLEX*16 array of dimension at least -* ( 1 + ( n - 1 )*abs( INCY ) ). -* Before entry, the incremented array Y must contain the n -* element vector y. On exit, Y is overwritten by the updated -* vector y. -* -* INCY - INTEGER. -* On entry, INCY specifies the increment for the elements of -* Y. INCY must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE COMPLEX ONE - PARAMETER (ONE= (1.0D+0,0.0D+0)) - DOUBLE COMPLEX ZERO - PARAMETER (ZERO= (0.0D+0,0.0D+0)) -* .. -* .. Local Scalars .. - DOUBLE COMPLEX TEMP1,TEMP2 - INTEGER I,INFO,IX,IY,J,JX,JY,K,KK,KX,KY -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC DBLE,DCONJG -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (N.LT.0) THEN - INFO = 2 - ELSE IF (INCX.EQ.0) THEN - INFO = 6 - ELSE IF (INCY.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('ZHPMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF ((N.EQ.0) .OR. ((ALPHA.EQ.ZERO).AND. (BETA.EQ.ONE))) RETURN -* -* Set up the start points in X and Y. -* - IF (INCX.GT.0) THEN - KX = 1 - ELSE - KX = 1 - (N-1)*INCX - END IF - IF (INCY.GT.0) THEN - KY = 1 - ELSE - KY = 1 - (N-1)*INCY - END IF -* -* Start the operations. In this version the elements of the array AP -* are accessed sequentially with one pass through AP. -* -* First form y := beta*y. -* - IF (BETA.NE.ONE) THEN - IF (INCY.EQ.1) THEN - IF (BETA.EQ.ZERO) THEN - DO 10 I = 1,N - Y(I) = ZERO - 10 CONTINUE - ELSE - DO 20 I = 1,N - Y(I) = BETA*Y(I) - 20 CONTINUE - END IF - ELSE - IY = KY - IF (BETA.EQ.ZERO) THEN - DO 30 I = 1,N - Y(IY) = ZERO - IY = IY + INCY - 30 CONTINUE - ELSE - DO 40 I = 1,N - Y(IY) = BETA*Y(IY) - IY = IY + INCY - 40 CONTINUE - END IF - END IF - END IF - IF (ALPHA.EQ.ZERO) RETURN - KK = 1 - IF (LSAME(UPLO,'U')) THEN -* -* Form y when AP contains the upper triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 60 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - K = KK - DO 50 I = 1,J - 1 - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + DCONJG(AP(K))*X(I) - K = K + 1 - 50 CONTINUE - Y(J) = Y(J) + TEMP1*DBLE(AP(KK+J-1)) + ALPHA*TEMP2 - KK = KK + J - 60 CONTINUE - ELSE - JX = KX - JY = KY - DO 80 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - IX = KX - IY = KY - DO 70 K = KK,KK + J - 2 - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + DCONJG(AP(K))*X(IX) - IX = IX + INCX - IY = IY + INCY - 70 CONTINUE - Y(JY) = Y(JY) + TEMP1*DBLE(AP(KK+J-1)) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + J - 80 CONTINUE - END IF - ELSE -* -* Form y when AP contains the lower triangle. -* - IF ((INCX.EQ.1) .AND. (INCY.EQ.1)) THEN - DO 100 J = 1,N - TEMP1 = ALPHA*X(J) - TEMP2 = ZERO - Y(J) = Y(J) + TEMP1*DBLE(AP(KK)) - K = KK + 1 - DO 90 I = J + 1,N - Y(I) = Y(I) + TEMP1*AP(K) - TEMP2 = TEMP2 + DCONJG(AP(K))*X(I) - K = K + 1 - 90 CONTINUE - Y(J) = Y(J) + ALPHA*TEMP2 - KK = KK + (N-J+1) - 100 CONTINUE - ELSE - JX = KX - JY = KY - DO 120 J = 1,N - TEMP1 = ALPHA*X(JX) - TEMP2 = ZERO - Y(JY) = Y(JY) + TEMP1*DBLE(AP(KK)) - IX = JX - IY = JY - DO 110 K = KK + 1,KK + N - J - IX = IX + INCX - IY = IY + INCY - Y(IY) = Y(IY) + TEMP1*AP(K) - TEMP2 = TEMP2 + DCONJG(AP(K))*X(IX) - 110 CONTINUE - Y(JY) = Y(JY) + ALPHA*TEMP2 - JX = JX + INCX - JY = JY + INCY - KK = KK + (N-J+1) - 120 CONTINUE - END IF - END IF -* - RETURN -* -* End of ZHPMV . -* - END diff --git a/gtsam/3rdparty/Eigen/blas/ztbmv.f b/gtsam/3rdparty/Eigen/blas/ztbmv.f deleted file mode 100644 index 7c85c1b55..000000000 --- a/gtsam/3rdparty/Eigen/blas/ztbmv.f +++ /dev/null @@ -1,366 +0,0 @@ - SUBROUTINE ZTBMV(UPLO,TRANS,DIAG,N,K,A,LDA,X,INCX) -* .. Scalar Arguments .. - INTEGER INCX,K,LDA,N - CHARACTER DIAG,TRANS,UPLO -* .. -* .. Array Arguments .. - DOUBLE COMPLEX A(LDA,*),X(*) -* .. -* -* Purpose -* ======= -* -* ZTBMV performs one of the matrix-vector operations -* -* x := A*x, or x := A'*x, or x := conjg( A' )*x, -* -* where x is an n element vector and A is an n by n unit, or non-unit, -* upper or lower triangular band matrix, with ( k + 1 ) diagonals. -* -* Arguments -* ========== -* -* UPLO - CHARACTER*1. -* On entry, UPLO specifies whether the matrix is an upper or -* lower triangular matrix as follows: -* -* UPLO = 'U' or 'u' A is an upper triangular matrix. -* -* UPLO = 'L' or 'l' A is a lower triangular matrix. -* -* Unchanged on exit. -* -* TRANS - CHARACTER*1. -* On entry, TRANS specifies the operation to be performed as -* follows: -* -* TRANS = 'N' or 'n' x := A*x. -* -* TRANS = 'T' or 't' x := A'*x. -* -* TRANS = 'C' or 'c' x := conjg( A' )*x. -* -* Unchanged on exit. -* -* DIAG - CHARACTER*1. -* On entry, DIAG specifies whether or not A is unit -* triangular as follows: -* -* DIAG = 'U' or 'u' A is assumed to be unit triangular. -* -* DIAG = 'N' or 'n' A is not assumed to be unit -* triangular. -* -* Unchanged on exit. -* -* N - INTEGER. -* On entry, N specifies the order of the matrix A. -* N must be at least zero. -* Unchanged on exit. -* -* K - INTEGER. -* On entry with UPLO = 'U' or 'u', K specifies the number of -* super-diagonals of the matrix A. -* On entry with UPLO = 'L' or 'l', K specifies the number of -* sub-diagonals of the matrix A. -* K must satisfy 0 .le. K. -* Unchanged on exit. -* -* A - COMPLEX*16 array of DIMENSION ( LDA, n ). -* Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) -* by n part of the array A must contain the upper triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row -* ( k + 1 ) of the array, the first super-diagonal starting at -* position 2 in row k, and so on. The top left k by k triangle -* of the array A is not referenced. -* The following program segment will transfer an upper -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = K + 1 - J -* DO 10, I = MAX( 1, J - K ), J -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) -* by n part of the array A must contain the lower triangular -* band part of the matrix of coefficients, supplied column by -* column, with the leading diagonal of the matrix in row 1 of -* the array, the first sub-diagonal starting at position 1 in -* row 2, and so on. The bottom right k by k triangle of the -* array A is not referenced. -* The following program segment will transfer a lower -* triangular band matrix from conventional full matrix storage -* to band storage: -* -* DO 20, J = 1, N -* M = 1 - J -* DO 10, I = J, MIN( N, J + K ) -* A( M + I, J ) = matrix( I, J ) -* 10 CONTINUE -* 20 CONTINUE -* -* Note that when DIAG = 'U' or 'u' the elements of the array A -* corresponding to the diagonal elements of the matrix are not -* referenced, but are assumed to be unity. -* Unchanged on exit. -* -* LDA - INTEGER. -* On entry, LDA specifies the first dimension of A as declared -* in the calling (sub) program. LDA must be at least -* ( k + 1 ). -* Unchanged on exit. -* -* X - COMPLEX*16 array of dimension at least -* ( 1 + ( n - 1 )*abs( INCX ) ). -* Before entry, the incremented array X must contain the n -* element vector x. On exit, X is overwritten with the -* tranformed vector x. -* -* INCX - INTEGER. -* On entry, INCX specifies the increment for the elements of -* X. INCX must not be zero. -* Unchanged on exit. -* -* Further Details -* =============== -* -* Level 2 Blas routine. -* -* -- Written on 22-October-1986. -* Jack Dongarra, Argonne National Lab. -* Jeremy Du Croz, Nag Central Office. -* Sven Hammarling, Nag Central Office. -* Richard Hanson, Sandia National Labs. -* -* ===================================================================== -* -* .. Parameters .. - DOUBLE COMPLEX ZERO - PARAMETER (ZERO= (0.0D+0,0.0D+0)) -* .. -* .. Local Scalars .. - DOUBLE COMPLEX TEMP - INTEGER I,INFO,IX,J,JX,KPLUS1,KX,L - LOGICAL NOCONJ,NOUNIT -* .. -* .. External Functions .. - LOGICAL LSAME - EXTERNAL LSAME -* .. -* .. External Subroutines .. - EXTERNAL XERBLA -* .. -* .. Intrinsic Functions .. - INTRINSIC DCONJG,MAX,MIN -* .. -* -* Test the input parameters. -* - INFO = 0 - IF (.NOT.LSAME(UPLO,'U') .AND. .NOT.LSAME(UPLO,'L')) THEN - INFO = 1 - ELSE IF (.NOT.LSAME(TRANS,'N') .AND. .NOT.LSAME(TRANS,'T') .AND. - + .NOT.LSAME(TRANS,'C')) THEN - INFO = 2 - ELSE IF (.NOT.LSAME(DIAG,'U') .AND. .NOT.LSAME(DIAG,'N')) THEN - INFO = 3 - ELSE IF (N.LT.0) THEN - INFO = 4 - ELSE IF (K.LT.0) THEN - INFO = 5 - ELSE IF (LDA.LT. (K+1)) THEN - INFO = 7 - ELSE IF (INCX.EQ.0) THEN - INFO = 9 - END IF - IF (INFO.NE.0) THEN - CALL XERBLA('ZTBMV ',INFO) - RETURN - END IF -* -* Quick return if possible. -* - IF (N.EQ.0) RETURN -* - NOCONJ = LSAME(TRANS,'T') - NOUNIT = LSAME(DIAG,'N') -* -* Set up the start point in X if the increment is not unity. This -* will be ( N - 1 )*INCX too small for descending loops. -* - IF (INCX.LE.0) THEN - KX = 1 - (N-1)*INCX - ELSE IF (INCX.NE.1) THEN - KX = 1 - END IF -* -* Start the operations. In this version the elements of A are -* accessed sequentially with one pass through A. -* - IF (LSAME(TRANS,'N')) THEN -* -* Form x := A*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 20 J = 1,N - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = KPLUS1 - J - DO 10 I = MAX(1,J-K),J - 1 - X(I) = X(I) + TEMP*A(L+I,J) - 10 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(KPLUS1,J) - END IF - 20 CONTINUE - ELSE - JX = KX - DO 40 J = 1,N - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = KPLUS1 - J - DO 30 I = MAX(1,J-K),J - 1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX + INCX - 30 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(KPLUS1,J) - END IF - JX = JX + INCX - IF (J.GT.K) KX = KX + INCX - 40 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 60 J = N,1,-1 - IF (X(J).NE.ZERO) THEN - TEMP = X(J) - L = 1 - J - DO 50 I = MIN(N,J+K),J + 1,-1 - X(I) = X(I) + TEMP*A(L+I,J) - 50 CONTINUE - IF (NOUNIT) X(J) = X(J)*A(1,J) - END IF - 60 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 80 J = N,1,-1 - IF (X(JX).NE.ZERO) THEN - TEMP = X(JX) - IX = KX - L = 1 - J - DO 70 I = MIN(N,J+K),J + 1,-1 - X(IX) = X(IX) + TEMP*A(L+I,J) - IX = IX - INCX - 70 CONTINUE - IF (NOUNIT) X(JX) = X(JX)*A(1,J) - END IF - JX = JX - INCX - IF ((N-J).GE.K) KX = KX - INCX - 80 CONTINUE - END IF - END IF - ELSE -* -* Form x := A'*x or x := conjg( A' )*x. -* - IF (LSAME(UPLO,'U')) THEN - KPLUS1 = K + 1 - IF (INCX.EQ.1) THEN - DO 110 J = N,1,-1 - TEMP = X(J) - L = KPLUS1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 90 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(I) - 90 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*DCONJG(A(KPLUS1,J)) - DO 100 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + DCONJG(A(L+I,J))*X(I) - 100 CONTINUE - END IF - X(J) = TEMP - 110 CONTINUE - ELSE - KX = KX + (N-1)*INCX - JX = KX - DO 140 J = N,1,-1 - TEMP = X(JX) - KX = KX - INCX - IX = KX - L = KPLUS1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(KPLUS1,J) - DO 120 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX - INCX - 120 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*DCONJG(A(KPLUS1,J)) - DO 130 I = J - 1,MAX(1,J-K),-1 - TEMP = TEMP + DCONJG(A(L+I,J))*X(IX) - IX = IX - INCX - 130 CONTINUE - END IF - X(JX) = TEMP - JX = JX - INCX - 140 CONTINUE - END IF - ELSE - IF (INCX.EQ.1) THEN - DO 170 J = 1,N - TEMP = X(J) - L = 1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 150 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(I) - 150 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*DCONJG(A(1,J)) - DO 160 I = J + 1,MIN(N,J+K) - TEMP = TEMP + DCONJG(A(L+I,J))*X(I) - 160 CONTINUE - END IF - X(J) = TEMP - 170 CONTINUE - ELSE - JX = KX - DO 200 J = 1,N - TEMP = X(JX) - KX = KX + INCX - IX = KX - L = 1 - J - IF (NOCONJ) THEN - IF (NOUNIT) TEMP = TEMP*A(1,J) - DO 180 I = J + 1,MIN(N,J+K) - TEMP = TEMP + A(L+I,J)*X(IX) - IX = IX + INCX - 180 CONTINUE - ELSE - IF (NOUNIT) TEMP = TEMP*DCONJG(A(1,J)) - DO 190 I = J + 1,MIN(N,J+K) - TEMP = TEMP + DCONJG(A(L+I,J))*X(IX) - IX = IX + INCX - 190 CONTINUE - END IF - X(JX) = TEMP - JX = JX + INCX - 200 CONTINUE - END IF - END IF - END IF -* - RETURN -* -* End of ZTBMV . -* - END diff --git a/gtsam/3rdparty/Eigen/cmake/Eigen3Config.cmake.in b/gtsam/3rdparty/Eigen/cmake/Eigen3Config.cmake.in new file mode 100644 index 000000000..c5c546887 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/Eigen3Config.cmake.in @@ -0,0 +1,21 @@ +# This file exports the Eigen3::Eigen CMake target which should be passed to the +# target_link_libraries command. + +@PACKAGE_INIT@ + +include ("${CMAKE_CURRENT_LIST_DIR}/Eigen3Targets.cmake") + +# Legacy variables, do *not* use. May be removed in the future. + +set (EIGEN3_FOUND 1) +set (EIGEN3_USE_FILE "${CMAKE_CURRENT_LIST_DIR}/UseEigen3.cmake") + +set (EIGEN3_DEFINITIONS "@EIGEN_DEFINITIONS@") +set (EIGEN3_INCLUDE_DIR "@PACKAGE_EIGEN_INCLUDE_DIR@") +set (EIGEN3_INCLUDE_DIRS "@PACKAGE_EIGEN_INCLUDE_DIR@") +set (EIGEN3_ROOT_DIR "@PACKAGE_EIGEN_ROOT_DIR@") + +set (EIGEN3_VERSION_STRING "@EIGEN_VERSION_STRING@") +set (EIGEN3_VERSION_MAJOR "@EIGEN_VERSION_MAJOR@") +set (EIGEN3_VERSION_MINOR "@EIGEN_VERSION_MINOR@") +set (EIGEN3_VERSION_PATCH "@EIGEN_VERSION_PATCH@") diff --git a/gtsam/3rdparty/Eigen/cmake/Eigen3ConfigLegacy.cmake.in b/gtsam/3rdparty/Eigen/cmake/Eigen3ConfigLegacy.cmake.in new file mode 100644 index 000000000..62d722469 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/Eigen3ConfigLegacy.cmake.in @@ -0,0 +1,30 @@ +# -*- cmake -*- +# +# Eigen3Config.cmake(.in) + +# Use the following variables to compile and link against Eigen: +# EIGEN3_FOUND - True if Eigen was found on your system +# EIGEN3_USE_FILE - The file making Eigen usable +# EIGEN3_DEFINITIONS - Definitions needed to build with Eigen +# EIGEN3_INCLUDE_DIR - Directory where signature_of_eigen3_matrix_library can be found +# EIGEN3_INCLUDE_DIRS - List of directories of Eigen and it's dependencies +# EIGEN3_ROOT_DIR - The base directory of Eigen +# EIGEN3_VERSION_STRING - A human-readable string containing the version +# EIGEN3_VERSION_MAJOR - The major version of Eigen +# EIGEN3_VERSION_MINOR - The minor version of Eigen +# EIGEN3_VERSION_PATCH - The patch version of Eigen + +@PACKAGE_INIT@ + +set ( EIGEN3_FOUND 1 ) +set ( EIGEN3_USE_FILE "${CMAKE_CURRENT_LIST_DIR}/UseEigen3.cmake" ) + +set ( EIGEN3_DEFINITIONS "@EIGEN_DEFINITIONS@" ) +set ( EIGEN3_INCLUDE_DIR "@PACKAGE_EIGEN_INCLUDE_DIR@" ) +set ( EIGEN3_INCLUDE_DIRS "@PACKAGE_EIGEN_INCLUDE_DIR@" ) +set ( EIGEN3_ROOT_DIR "@PACKAGE_EIGEN_ROOT_DIR@" ) + +set ( EIGEN3_VERSION_STRING "@EIGEN_VERSION_STRING@" ) +set ( EIGEN3_VERSION_MAJOR "@EIGEN_VERSION_MAJOR@" ) +set ( EIGEN3_VERSION_MINOR "@EIGEN_VERSION_MINOR@" ) +set ( EIGEN3_VERSION_PATCH "@EIGEN_VERSION_PATCH@" ) diff --git a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake index b5b62aee6..afc24b5e9 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenConfigureTesting.cmake @@ -1,7 +1,7 @@ include(EigenTesting) include(CheckCXXSourceCompiles) -# configure the "site" and "buildname" +# configure the "site" and "buildname" ei_set_sitename() # retrieve and store the build string @@ -46,18 +46,16 @@ if(CMAKE_COMPILER_IS_GNUCXX) if(EIGEN_COVERAGE_TESTING) set(COVERAGE_FLAGS "-fprofile-arcs -ftest-coverage") set(CTEST_CUSTOM_COVERAGE_EXCLUDE "/test/") - else(EIGEN_COVERAGE_TESTING) - set(COVERAGE_FLAGS "") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS}") endif(EIGEN_COVERAGE_TESTING) - if(EIGEN_TEST_C++0x) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=gnu++0x") - endif(EIGEN_TEST_C++0x) - if(CMAKE_SYSTEM_NAME MATCHES Linux) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS} -g2") - set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "${CMAKE_CXX_FLAGS_RELWITHDEBINFO} ${COVERAGE_FLAGS} -O2 -g2") - set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${COVERAGE_FLAGS} -fno-inline-functions") - set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${COVERAGE_FLAGS} -O0 -g3") - endif(CMAKE_SYSTEM_NAME MATCHES Linux) + elseif(MSVC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /D_CRT_SECURE_NO_WARNINGS /D_SCL_SECURE_NO_WARNINGS") endif(CMAKE_COMPILER_IS_GNUCXX) + + +check_cxx_compiler_flag("-std=c++11" EIGEN_COMPILER_SUPPORT_CXX11) + +if(EIGEN_TEST_CXX11 AND EIGEN_COMPILER_SUPPORT_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +endif() diff --git a/gtsam/3rdparty/Eigen/cmake/EigenDetermineVSServicePack.cmake b/gtsam/3rdparty/Eigen/cmake/EigenDetermineVSServicePack.cmake index 8e5546a85..fed78194d 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenDetermineVSServicePack.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenDetermineVSServicePack.cmake @@ -4,7 +4,6 @@ include(CMakeDetermineVSServicePack) # _DetermineVSServicePack_FastCheckVersionWithCompiler which lead to errors on some systems. function(EigenDetermineVSServicePack _pack) if(NOT DETERMINED_VS_SERVICE_PACK OR NOT ${_pack}) - if(NOT DETERMINED_VS_SERVICE_PACK) _DetermineVSServicePack_CheckVersionWithTryCompile(DETERMINED_VS_SERVICE_PACK _cl_version) if(NOT DETERMINED_VS_SERVICE_PACK) @@ -13,10 +12,25 @@ function(EigenDetermineVSServicePack _pack) endif() if(DETERMINED_VS_SERVICE_PACK) - if(_cl_version) # Call helper function to determine VS version _DetermineVSServicePackFromCompiler(_sp "${_cl_version}") + + # temporary fix, until CMake catches up + if (NOT _sp) + if(${_cl_version} VERSION_EQUAL "17.00.50727.1") + set(_sp "vc110") + elseif(${_cl_version} VERSION_EQUAL "17.00.51106.1") + set(_sp "vc110sp1") + elseif(${_cl_version} VERSION_EQUAL "17.00.60315.1") + set(_sp "vc110sp2") + elseif(${_cl_version} VERSION_EQUAL "17.00.60610.1") + set(_sp "vc110sp3") + else() + set(_sp ${CMAKE_CXX_COMPILER_VERSION}) + endif() + endif() + if(_sp) set(${_pack} ${_sp} CACHE INTERNAL "The Visual Studio Release with Service Pack") diff --git a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake index cbe12d51b..a92a2978b 100644 --- a/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake +++ b/gtsam/3rdparty/Eigen/cmake/EigenTesting.cmake @@ -1,19 +1,48 @@ macro(ei_add_property prop value) - get_property(previous GLOBAL PROPERTY ${prop}) + get_property(previous GLOBAL PROPERTY ${prop}) if ((NOT previous) OR (previous STREQUAL "")) set_property(GLOBAL PROPERTY ${prop} "${value}") else() set_property(GLOBAL PROPERTY ${prop} "${previous} ${value}") - endif() + endif() endmacro(ei_add_property) #internal. See documentation of ei_add_test for details. macro(ei_add_test_internal testname testname_with_suffix) set(targetname ${testname_with_suffix}) - set(filename ${testname}.cpp) - add_executable(${targetname} ${filename}) + if(EIGEN_ADD_TEST_FILENAME_EXTENSION) + set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION}) + else() + set(filename ${testname}.cpp) + endif() + + if(EIGEN_ADD_TEST_FILENAME_EXTENSION STREQUAL cu) + if(EIGEN_TEST_CUDA_CLANG) + set_source_files_properties(${filename} PROPERTIES LANGUAGE CXX) + if(CUDA_64_BIT_DEVICE_CODE) + link_directories("${CUDA_TOOLKIT_ROOT_DIR}/lib64") + else() + link_directories("${CUDA_TOOLKIT_ROOT_DIR}/lib") + endif() + if (${ARGC} GREATER 2) + add_executable(${targetname} ${filename}) + else() + add_executable(${targetname} ${filename} OPTIONS ${ARGV2}) + endif() + target_link_libraries(${targetname} "cudart_static" "cuda" "dl" "rt" "pthread") + else() + if (${ARGC} GREATER 2) + cuda_add_executable(${targetname} ${filename} OPTIONS ${ARGV2}) + else() + cuda_add_executable(${targetname} ${filename}) + endif() + endif() + else() + add_executable(${targetname} ${filename}) + endif() + if (targetname MATCHES "^eigen2_") add_dependencies(eigen2_buildtests ${targetname}) else() @@ -27,20 +56,20 @@ macro(ei_add_test_internal testname testname_with_suffix) ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_DEBUG_ASSERTS=1") endif(EIGEN_DEBUG_ASSERTS) endif(EIGEN_NO_ASSERTION_CHECKING) - + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_MAX_SIZE=${EIGEN_TEST_MAX_SIZE}") ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_FUNC=${testname}") - - if(MSVC AND NOT EIGEN_SPLIT_LARGE_TESTS) + + if(MSVC) ei_add_target_property(${targetname} COMPILE_FLAGS "/bigobj") - endif() + endif() # let the user pass flags. if(${ARGC} GREATER 2) ei_add_target_property(${targetname} COMPILE_FLAGS "${ARGV2}") endif(${ARGC} GREATER 2) - + if(EIGEN_TEST_CUSTOM_CXX_FLAGS) ei_add_target_property(${targetname} COMPILE_FLAGS "${EIGEN_TEST_CUSTOM_CXX_FLAGS}") endif() @@ -66,16 +95,12 @@ macro(ei_add_test_internal testname testname_with_suffix) # notice: no double quotes around ${libs_to_link} here. It may be a list. target_link_libraries(${targetname} ${libs_to_link}) endif() - endif() - - if(EIGEN_BIN_BASH_EXISTS) - add_test(${testname_with_suffix} "${Eigen_SOURCE_DIR}/test/runtest.sh" "${testname_with_suffix}") - else() - add_test(${testname_with_suffix} "${targetname}") endif() - + + add_test(${testname_with_suffix} "${targetname}") + # Specify target and test labels accoirding to EIGEN_CURRENT_SUBPROJECT - get_property(current_subproject GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT) + get_property(current_subproject GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT) if ((current_subproject) AND (NOT (current_subproject STREQUAL ""))) set_property(TARGET ${targetname} PROPERTY LABELS "Build${current_subproject}") add_dependencies("Build${current_subproject}" ${targetname}) @@ -84,6 +109,103 @@ macro(ei_add_test_internal testname testname_with_suffix) endmacro(ei_add_test_internal) +# SYCL +macro(ei_add_test_internal_sycl testname testname_with_suffix) + include_directories( SYSTEM ${COMPUTECPP_PACKAGE_ROOT_DIR}/include) + set(targetname ${testname_with_suffix}) + + if(EIGEN_ADD_TEST_FILENAME_EXTENSION) + set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION}) + else() + set(filename ${testname}.cpp) + endif() + + set( include_file ${CMAKE_CURRENT_BINARY_DIR}/inc_${filename}) + set( bc_file ${CMAKE_CURRENT_BINARY_DIR}/${filename}) + set( host_file ${CMAKE_CURRENT_SOURCE_DIR}/${filename}) + + ADD_CUSTOM_COMMAND( + OUTPUT ${include_file} + COMMAND ${CMAKE_COMMAND} -E echo "\\#include \\\"${host_file}\\\"" > ${include_file} + COMMAND ${CMAKE_COMMAND} -E echo "\\#include \\\"${bc_file}.sycl\\\"" >> ${include_file} + DEPENDS ${filename} ${bc_file}.sycl + COMMENT "Building ComputeCpp integration header file ${include_file}" + ) + # Add a custom target for the generated integration header + add_custom_target(${testname}_integration_header_sycl DEPENDS ${include_file}) + + add_executable(${targetname} ${include_file}) + add_dependencies(${targetname} ${testname}_integration_header_sycl) + add_sycl_to_target(${targetname} ${filename} ${CMAKE_CURRENT_BINARY_DIR}) + + if (targetname MATCHES "^eigen2_") + add_dependencies(eigen2_buildtests ${targetname}) + else() + add_dependencies(buildtests ${targetname}) + endif() + + if(EIGEN_NO_ASSERTION_CHECKING) + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_NO_ASSERTION_CHECKING=1") + else(EIGEN_NO_ASSERTION_CHECKING) + if(EIGEN_DEBUG_ASSERTS) + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_DEBUG_ASSERTS=1") + endif(EIGEN_DEBUG_ASSERTS) + endif(EIGEN_NO_ASSERTION_CHECKING) + + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_MAX_SIZE=${EIGEN_TEST_MAX_SIZE}") + + ei_add_target_property(${targetname} COMPILE_FLAGS "-DEIGEN_TEST_FUNC=${testname}") + + if(MSVC AND NOT EIGEN_SPLIT_LARGE_TESTS) + ei_add_target_property(${targetname} COMPILE_FLAGS "/bigobj") + endif() + + # let the user pass flags. + if(${ARGC} GREATER 2) + ei_add_target_property(${targetname} COMPILE_FLAGS "${ARGV2}") + endif(${ARGC} GREATER 2) + + if(EIGEN_TEST_CUSTOM_CXX_FLAGS) + ei_add_target_property(${targetname} COMPILE_FLAGS "${EIGEN_TEST_CUSTOM_CXX_FLAGS}") + endif() + + if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO) + target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) + endif() + if(EXTERNAL_LIBS) + target_link_libraries(${targetname} ${EXTERNAL_LIBS}) + endif() + if(EIGEN_TEST_CUSTOM_LINKER_FLAGS) + target_link_libraries(${targetname} ${EIGEN_TEST_CUSTOM_LINKER_FLAGS}) + endif() + + if(${ARGC} GREATER 3) + set(libs_to_link ${ARGV3}) + # it could be that some cmake module provides a bad library string " " (just spaces), + # and that severely breaks target_link_libraries ("can't link to -l-lstdc++" errors). + # so we check for strings containing only spaces. + string(STRIP "${libs_to_link}" libs_to_link_stripped) + string(LENGTH "${libs_to_link_stripped}" libs_to_link_stripped_length) + if(${libs_to_link_stripped_length} GREATER 0) + # notice: no double quotes around ${libs_to_link} here. It may be a list. + target_link_libraries(${targetname} ${libs_to_link}) + endif() + endif() + + add_test(${testname_with_suffix} "${targetname}") + + # Specify target and test labels according to EIGEN_CURRENT_SUBPROJECT + get_property(current_subproject GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT) + if ((current_subproject) AND (NOT (current_subproject STREQUAL ""))) + set_property(TARGET ${targetname} PROPERTY LABELS "Build${current_subproject}") + add_dependencies("Build${current_subproject}" ${targetname}) + set_property(TEST ${testname_with_suffix} PROPERTY LABELS "${current_subproject}") + endif() + + +endmacro(ei_add_test_internal_sycl) + + # Macro to add a test # # the unique mandatory parameter testname must correspond to a file @@ -131,7 +253,13 @@ macro(ei_add_test testname) set(EIGEN_TESTS_LIST "${EIGEN_TESTS_LIST}${testname}\n") set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST "${EIGEN_TESTS_LIST}") - file(READ "${testname}.cpp" test_source) + if(EIGEN_ADD_TEST_FILENAME_EXTENSION) + set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION}) + else() + set(filename ${testname}.cpp) + endif() + + file(READ "${filename}" test_source) set(parts 0) string(REGEX MATCHALL "CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+|EIGEN_SUFFIXES(;[0-9]+)+" occurences "${test_source}") @@ -154,6 +282,39 @@ macro(ei_add_test testname) endif(EIGEN_SPLIT_LARGE_TESTS AND suffixes) endmacro(ei_add_test) +macro(ei_add_test_sycl testname) + get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST) + set(EIGEN_TESTS_LIST "${EIGEN_TESTS_LIST}${testname}\n") + set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST "${EIGEN_TESTS_LIST}") + + if(EIGEN_ADD_TEST_FILENAME_EXTENSION) + set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION}) + else() + set(filename ${testname}.cpp) + endif() + + file(READ "${filename}" test_source) + set(parts 0) + string(REGEX MATCHALL "CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+|EIGEN_SUFFIXES(;[0-9]+)+" + occurences "${test_source}") + string(REGEX REPLACE "CALL_SUBTEST_|EIGEN_TEST_PART_|EIGEN_SUFFIXES" "" suffixes "${occurences}") + list(REMOVE_DUPLICATES suffixes) + if(EIGEN_SPLIT_LARGE_TESTS AND suffixes) + add_custom_target(${testname}) + foreach(suffix ${suffixes}) + ei_add_test_internal_sycl(${testname} ${testname}_${suffix} + "${ARGV1} -DEIGEN_TEST_PART_${suffix}=1" "${ARGV2}") + add_dependencies(${testname} ${testname}_${suffix}) + endforeach(suffix) + else(EIGEN_SPLIT_LARGE_TESTS AND suffixes) + set(symbols_to_enable_all_parts "") + foreach(suffix ${suffixes}) + set(symbols_to_enable_all_parts + "${symbols_to_enable_all_parts} -DEIGEN_TEST_PART_${suffix}=1") + endforeach(suffix) + ei_add_test_internal_sycl(${testname} ${testname} "${ARGV1} ${symbols_to_enable_all_parts}" "${ARGV2}") + endif(EIGEN_SPLIT_LARGE_TESTS AND suffixes) +endmacro(ei_add_test_sycl) # adds a failtest, i.e. a test that succeed if the program fails to compile # note that the test runner for these is CMake itself, when passed -DEIGEN_FAILTEST=ON @@ -218,7 +379,7 @@ macro(ei_testing_print_summary) elseif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION) message(STATUS "Explicit vectorization disabled (alignment kept enabled)") else() - + message(STATUS "Maximal matrix/vector size: ${EIGEN_TEST_MAX_SIZE}") if(EIGEN_TEST_SSE2) @@ -251,18 +412,75 @@ macro(ei_testing_print_summary) message(STATUS "SSE4.2: Using architecture defaults") endif() + if(EIGEN_TEST_AVX) + message(STATUS "AVX: ON") + else() + message(STATUS "AVX: Using architecture defaults") + endif() + + if(EIGEN_TEST_FMA) + message(STATUS "FMA: ON") + else() + message(STATUS "FMA: Using architecture defaults") + endif() + + if(EIGEN_TEST_AVX512) + message(STATUS "AVX512: ON") + else() + message(STATUS "AVX512: Using architecture defaults") + endif() + if(EIGEN_TEST_ALTIVEC) message(STATUS "Altivec: ON") else() message(STATUS "Altivec: Using architecture defaults") endif() + if(EIGEN_TEST_VSX) + message(STATUS "VSX: ON") + else() + message(STATUS "VSX: Using architecture defaults") + endif() + if(EIGEN_TEST_NEON) message(STATUS "ARM NEON: ON") else() message(STATUS "ARM NEON: Using architecture defaults") endif() + if(EIGEN_TEST_NEON64) + message(STATUS "ARMv8 NEON: ON") + else() + message(STATUS "ARMv8 NEON: Using architecture defaults") + endif() + + if(EIGEN_TEST_ZVECTOR) + message(STATUS "S390X ZVECTOR: ON") + else() + message(STATUS "S390X ZVECTOR: Using architecture defaults") + endif() + + if(EIGEN_TEST_CXX11) + message(STATUS "C++11: ON") + else() + message(STATUS "C++11: OFF") + endif() + + if(EIGEN_TEST_SYCL) + message(STATUS "SYCL: ON") + else() + message(STATUS "SYCL: OFF") + endif() + if(EIGEN_TEST_CUDA) + if(EIGEN_TEST_CUDA_CLANG) + message(STATUS "CUDA: ON (using clang)") + else() + message(STATUS "CUDA: ON (using nvcc)") + endif() + else() + message(STATUS "CUDA: OFF") + endif() + endif() # vectorization / alignment options message(STATUS "\n${EIGEN_TESTING_SUMMARY}") @@ -287,7 +505,7 @@ macro(ei_init_testing) set_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT "0") set_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT "0") - + # uncomment anytime you change the ei_get_compilerver_from_cxx_version_string macro # ei_test_get_compilerver_from_cxx_version_string() endmacro(ei_init_testing) @@ -296,47 +514,47 @@ macro(ei_set_sitename) # if the sitename is not yet set, try to set it if(NOT ${SITE} OR ${SITE} STREQUAL "") set(eigen_computername $ENV{COMPUTERNAME}) - set(eigen_hostname $ENV{HOSTNAME}) + set(eigen_hostname $ENV{HOSTNAME}) if(eigen_hostname) set(SITE ${eigen_hostname}) - elseif(eigen_computername) - set(SITE ${eigen_computername}) + elseif(eigen_computername) + set(SITE ${eigen_computername}) endif() endif() # in case it is already set, enforce lower case if(SITE) string(TOLOWER ${SITE} SITE) - endif() + endif() endmacro(ei_set_sitename) macro(ei_get_compilerver VAR) - if(MSVC) - # on windows system, we use a modified CMake script - include(EigenDetermineVSServicePack) - EigenDetermineVSServicePack( my_service_pack ) + if(MSVC) + # on windows system, we use a modified CMake script + include(EigenDetermineVSServicePack) + EigenDetermineVSServicePack( my_service_pack ) - if( my_service_pack ) - set(${VAR} ${my_service_pack}) + if( my_service_pack ) + set(${VAR} ${my_service_pack}) + else() + set(${VAR} "na") + endif() else() - set(${VAR} "na") - endif() - else() # on all other system we rely on ${CMAKE_CXX_COMPILER} # supporting a "--version" or "/version" flag - + if(WIN32 AND ${CMAKE_CXX_COMPILER_ID} EQUAL "Intel") set(EIGEN_CXX_FLAG_VERSION "/version") else() set(EIGEN_CXX_FLAG_VERSION "--version") endif() - - execute_process(COMMAND ${CMAKE_CXX_COMPILER} ${EIGEN_CXX_FLAG_VERSION} + + execute_process(COMMAND ${CMAKE_CXX_COMPILER} ${EIGEN_CXX_FLAG_VERSION} OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE) string(REGEX REPLACE "[\n\r].*" "" eigen_cxx_compiler_version_string ${eigen_cxx_compiler_version_string}) - + ei_get_compilerver_from_cxx_version_string("${eigen_cxx_compiler_version_string}" CNAME CVER) set(${VAR} "${CNAME}-${CVER}") - + endif() endmacro(ei_get_compilerver) @@ -345,18 +563,20 @@ endmacro(ei_get_compilerver) # the testing macro call in ei_init_testing() of the EigenTesting.cmake file. # See also the ei_test_get_compilerver_from_cxx_version_string macro at the end of the file macro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER) - # extract possible compiler names + # extract possible compiler names string(REGEX MATCH "g\\+\\+" ei_has_gpp ${VERSTRING}) string(REGEX MATCH "llvm|LLVM" ei_has_llvm ${VERSTRING}) string(REGEX MATCH "gcc|GCC" ei_has_gcc ${VERSTRING}) string(REGEX MATCH "icpc|ICC" ei_has_icpc ${VERSTRING}) string(REGEX MATCH "clang|CLANG" ei_has_clang ${VERSTRING}) - + # combine them if((ei_has_llvm) AND (ei_has_gpp OR ei_has_gcc)) set(${CNAME} "llvm-g++") elseif((ei_has_llvm) AND (ei_has_clang)) set(${CNAME} "llvm-clang++") + elseif(ei_has_clang) + set(${CNAME} "clang++") elseif(ei_has_icpc) set(${CNAME} "icpc") elseif(ei_has_gpp OR ei_has_gcc) @@ -364,7 +584,7 @@ macro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER) else() set(${CNAME} "_") endif() - + # extract possible version numbers # first try to extract 3 isolated numbers: string(REGEX MATCH " [0-9]+\\.[0-9]+\\.[0-9]+" eicver ${VERSTRING}) @@ -382,9 +602,9 @@ macro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER) endif() endif() endif() - + string(REGEX REPLACE ".(.*)" "\\1" ${CVER} ${eicver}) - + endmacro(ei_get_compilerver_from_cxx_version_string) macro(ei_get_cxxflags VAR) @@ -392,8 +612,18 @@ macro(ei_get_cxxflags VAR) ei_is_64bit_env(IS_64BIT_ENV) if(EIGEN_TEST_NEON) set(${VAR} NEON) + elseif(EIGEN_TEST_NEON64) + set(${VAR} NEON) + elseif(EIGEN_TEST_ZVECTOR) + set(${VAR} ZVECTOR) + elseif(EIGEN_TEST_VSX) + set(${VAR} VSX) elseif(EIGEN_TEST_ALTIVEC) set(${VAR} ALVEC) + elseif(EIGEN_TEST_FMA) + set(${VAR} FMA) + elseif(EIGEN_TEST_AVX) + set(${VAR} AVX) elseif(EIGEN_TEST_SSE4_2) set(${VAR} SSE42) elseif(EIGEN_TEST_SSE4_1) @@ -403,30 +633,30 @@ macro(ei_get_cxxflags VAR) elseif(EIGEN_TEST_SSE3) set(${VAR} SSE3) elseif(EIGEN_TEST_SSE2 OR IS_64BIT_ENV) - set(${VAR} SSE2) + set(${VAR} SSE2) endif() if(EIGEN_TEST_OPENMP) if (${VAR} STREQUAL "") - set(${VAR} OMP) - else() - set(${VAR} ${${VAR}}-OMP) - endif() + set(${VAR} OMP) + else() + set(${VAR} ${${VAR}}-OMP) + endif() endif() - + if(EIGEN_DEFAULT_TO_ROW_MAJOR) if (${VAR} STREQUAL "") - set(${VAR} ROW) - else() - set(${VAR} ${${VAR}}-ROWMAJ) - endif() + set(${VAR} ROW) + else() + set(${VAR} ${${VAR}}-ROWMAJ) + endif() endif() endmacro(ei_get_cxxflags) macro(ei_set_build_string) ei_get_compilerver(LOCAL_COMPILER_VERSION) ei_get_cxxflags(LOCAL_COMPILER_FLAGS) - + include(EigenDetermineOSVersion) DetermineOSVersion(OS_VERSION) @@ -442,7 +672,11 @@ macro(ei_set_build_string) else() set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-64bit) endif() - + + if(EIGEN_TEST_CXX11) + set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-cxx11) + endif() + if(EIGEN_BUILD_STRING_SUFFIX) set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${EIGEN_BUILD_STRING_SUFFIX}) endif() diff --git a/gtsam/3rdparty/Eigen/cmake/EigenUninstall.cmake b/gtsam/3rdparty/Eigen/cmake/EigenUninstall.cmake new file mode 100644 index 000000000..4dae8c85c --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/EigenUninstall.cmake @@ -0,0 +1,40 @@ +################ CMake Uninstall Template ####################### +# CMake Template file for uninstallation of files +# mentioned in 'install_manifest.txt' +# +# Used by uinstall target +################################################################# + +set(MANIFEST "${CMAKE_CURRENT_BINARY_DIR}/install_manifest.txt") + +if(EXISTS ${MANIFEST}) + message(STATUS "============== Uninstalling Eigen ===================") + + file(STRINGS ${MANIFEST} files) + foreach(file ${files}) + if(EXISTS ${file}) + message(STATUS "Removing file: '${file}'") + + execute_process( + COMMAND ${CMAKE_COMMAND} -E remove ${file} + OUTPUT_VARIABLE rm_out + RESULT_VARIABLE rm_retval + ) + + if(NOT "${rm_retval}" STREQUAL 0) + message(FATAL_ERROR "Failed to remove file: '${file}'.") + endif() + else() + message(STATUS "File '${file}' does not exist.") + endif() + endforeach(file) + + message(STATUS "========== Finished Uninstalling Eigen ==============") +else() + message(STATUS "Cannot find install manifest: '${MANIFEST}'") + message(STATUS "Probably make install has not been performed") + message(STATUS " or install_manifest.txt has been deleted.") +endif() + + + diff --git a/gtsam/3rdparty/Eigen/cmake/FindAdolc.cmake b/gtsam/3rdparty/Eigen/cmake/FindAdolc.cmake index 1a7ff3628..937e54990 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindAdolc.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindAdolc.cmake @@ -5,7 +5,7 @@ endif (ADOLC_INCLUDES AND ADOLC_LIBRARIES) find_path(ADOLC_INCLUDES NAMES - adolc/adouble.h + adolc/adtl.h PATHS $ENV{ADOLCDIR} ${INCLUDE_INSTALL_DIR} diff --git a/gtsam/3rdparty/Eigen/cmake/FindBLAS.cmake b/gtsam/3rdparty/Eigen/cmake/FindBLAS.cmake index 68c4e0724..9f74b07fe 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindBLAS.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindBLAS.cmake @@ -1,385 +1,1363 @@ -# Find BLAS library +### # -# This module finds an installed library that implements the BLAS +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2016 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find BLAS library +# This module finds an installed fortran library that implements the BLAS # linear-algebra interface (see http://www.netlib.org/blas/). -# The list of libraries searched for is mainly taken +# The list of libraries searched for is taken # from the autoconf macro file, acx_blas.m4 (distributed at # http://ac-archive.sourceforge.net/ac-archive/acx_blas.html). # # This module sets the following variables: # BLAS_FOUND - set to true if a library implementing the BLAS interface # is found -# BLAS_INCLUDE_DIR - Directories containing the BLAS header files -# BLAS_DEFINITIONS - Compilation options to use BLAS -# BLAS_LINKER_FLAGS - Linker flags to use BLAS (excluding -l +# BLAS_LINKER_FLAGS - uncached list of required linker flags (excluding -l # and -L). -# BLAS_LIBRARIES_DIR - Directories containing the BLAS libraries. -# May be null if BLAS_LIBRARIES contains libraries name using full path. -# BLAS_LIBRARIES - List of libraries to link against BLAS interface. -# May be null if the compiler supports auto-link (e.g. VC++). -# BLAS_USE_FILE - The name of the cmake module to include to compile -# applications or libraries using BLAS. +# BLAS_COMPILER_FLAGS - uncached list of required compiler flags (including -I for mkl headers). +# BLAS_LIBRARIES - uncached list of libraries (using full path name) to +# link against to use BLAS +# BLAS95_LIBRARIES - uncached list of libraries (using full path name) +# to link against to use BLAS95 interface +# BLAS95_FOUND - set to true if a library implementing the BLAS f95 interface +# is found +# BLA_STATIC if set on this determines what kind of linkage we do (static) +# BLA_VENDOR if set checks only the specified vendor, if not set checks +# all the possibilities +# BLAS_VENDOR_FOUND stores the BLAS vendor found +# BLA_F95 if set on tries to find the f95 interfaces for BLAS/LAPACK +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DBLAS_DIR=path/to/blas): +# BLAS_DIR - Where to find the base directory of blas +# BLAS_INCDIR - Where to find the header files +# BLAS_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: BLAS_DIR, BLAS_INCDIR, BLAS_LIBDIR +# For MKL case and if no paths are given as hints, we will try to use the MKLROOT +# environment variable +# BLAS_VERBOSE Print some additional information during BLAS libraries detection +########## +### List of vendors (BLA_VENDOR) valid in this module +########## List of vendors (BLA_VENDOR) valid in this module +## Open (for OpenBlas), Eigen (for EigenBlas), Goto, ATLAS PhiPACK, +##  CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT +## Intel10_32 (intel mkl v10 32 bit), Intel10_64lp (intel mkl v10 64 bit,lp thread model, lp64 model), +## Intel10_64lp_seq (intel mkl v10 64 bit,sequential code, lp64 model), +## Intel( older versions of mkl 32 and 64 bit), +##  ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic +# C/CXX should be enabled to use Intel mkl +### +# We handle different modes to find the dependency # -# This module was modified by CGAL team: -# - find libraries for a C++ compiler, instead of Fortran -# - added BLAS_INCLUDE_DIR, BLAS_DEFINITIONS and BLAS_LIBRARIES_DIR -# - removed BLAS95_LIBRARIES +# - Detection if already installed on the system +# - BLAS libraries can be detected from different ways +# Here is the order of precedence: +# 1) we look in cmake variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined +# 2) we look in environment variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined +# 3) we look in common environnment variables depending on the system (INCLUDE, C_INCLUDE_PATH, CPATH - LIB, DYLD_LIBRARY_PATH, LD_LIBRARY_PATH) +# 4) we look in common system paths depending on the system, see for example paths contained in the following cmake variables: +# - CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES +# - CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_C_IMPLICIT_LINK_DIRECTORIES +# + +#============================================================================= +# Copyright 2007-2009 Kitware, Inc. +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of CMake, substitute the full +# License text for the above reference.) + +## Some macros to print status when search for headers and libs +# This macro informs why the _lib_to_find file has not been found +macro(Print_Find_Library_Blas_Status _libname _lib_to_find) + + # save _libname upper/lower case + string(TOUPPER ${_libname} LIBNAME) + string(TOLOWER ${_libname} libname) + + # print status + #message(" ") + if(${LIBNAME}_LIBDIR) + message("${Yellow}${LIBNAME}_LIBDIR is defined but ${_lib_to_find}" + "has not been found in ${ARGN}${ColourReset}") + else() + if(${LIBNAME}_DIR) + message("${Yellow}${LIBNAME}_DIR is defined but ${_lib_to_find}" + "has not been found in ${ARGN}${ColourReset}") + else() + message("${Yellow}${_lib_to_find} not found." + "Nor ${LIBNAME}_DIR neither ${LIBNAME}_LIBDIR" + "are defined so that we look for ${_lib_to_find} in" + "system paths (Linux: LD_LIBRARY_PATH, Windows: LIB," + "Mac: DYLD_LIBRARY_PATH," + "CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES," + "CMAKE_C_IMPLICIT_LINK_DIRECTORIES)${ColourReset}") + if(_lib_env) + message("${Yellow}${_lib_to_find} has not been found in" + "${_lib_env}${ColourReset}") + endif() + endif() + endif() + message("${BoldYellow}Please indicate where to find ${_lib_to_find}. You have three options:\n" + "- Option 1: Provide the Installation directory of BLAS library with cmake option: -D${LIBNAME}_DIR=your/path/to/${libname}/\n" + "- Option 2: Provide the directory where to find the library with cmake option: -D${LIBNAME}_LIBDIR=your/path/to/${libname}/lib/\n" + "- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\n" + "- Option 4: If your library provides a PkgConfig file, make sure pkg-config finds your library${ColourReset}") + +endmacro() + +# This macro informs why the _lib_to_find file has not been found +macro(Print_Find_Library_Blas_CheckFunc_Status _name) + + # save _libname upper/lower case + string(TOUPPER ${_name} FUNCNAME) + string(TOLOWER ${_name} funcname) + + # print status + #message(" ") + message("${Red}Libs have been found but check of symbol ${_name} failed " + "with following libraries ${ARGN}${ColourReset}") + message("${BoldRed}Please open your error file CMakeFiles/CMakeError.log" + "to figure out why it fails${ColourReset}") + #message(" ") + +endmacro() + +if (NOT BLAS_FOUND) + set(BLAS_DIR "" CACHE PATH "Installation directory of BLAS library") + if (NOT BLAS_FIND_QUIETLY) + message(STATUS "A cache variable, namely BLAS_DIR, has been set to specify the install directory of BLAS") + endif() +endif() + +option(BLAS_VERBOSE "Print some additional information during BLAS libraries detection" OFF) +mark_as_advanced(BLAS_VERBOSE) include(CheckFunctionExists) +include(CheckFortranFunctionExists) +set(_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES}) -# This macro checks for the existence of the combination of fortran libraries -# given by _list. If the combination is found, this macro checks (using the -# check_function_exists macro) whether can link against that library -# combination using the name of a routine given by _name using the linker -# flags given by _flags. If the combination of libraries is found and passes -# the link test, LIBRARIES is set to the list of complete library paths that -# have been found and DEFINITIONS to the required definitions. -# Otherwise, LIBRARIES is set to FALSE. -# N.B. _prefix is the prefix applied to the names of all cached variables that -# are generated internally and marked advanced by this macro. -macro(check_fortran_libraries DEFINITIONS LIBRARIES _prefix _name _flags _list _path) - #message("DEBUG: check_fortran_libraries(${_list} in ${_path})") +# Check the language being used +get_property( _LANGUAGES_ GLOBAL PROPERTY ENABLED_LANGUAGES ) +if( _LANGUAGES_ MATCHES Fortran ) + set( _CHECK_FORTRAN TRUE ) +elseif( (_LANGUAGES_ MATCHES C) OR (_LANGUAGES_ MATCHES CXX) ) + set( _CHECK_FORTRAN FALSE ) +else() + if(BLAS_FIND_REQUIRED) + message(FATAL_ERROR "FindBLAS requires Fortran, C, or C++ to be enabled.") + else() + message(STATUS "Looking for BLAS... - NOT found (Unsupported languages)") + return() + endif() +endif() - # Check for the existence of the libraries given by _list - set(_libraries_found TRUE) - set(_libraries_work FALSE) - set(${DEFINITIONS} "") - set(${LIBRARIES} "") +macro(Check_Fortran_Libraries LIBRARIES _prefix _name _flags _list _thread) + # This macro checks for the existence of the combination of fortran libraries + # given by _list. If the combination is found, this macro checks (using the + # Check_Fortran_Function_Exists macro) whether can link against that library + # combination using the name of a routine given by _name using the linker + # flags given by _flags. If the combination of libraries is found and passes + # the link test, LIBRARIES is set to the list of complete library paths that + # have been found. Otherwise, LIBRARIES is set to FALSE. + + # N.B. _prefix is the prefix applied to the names of all cached variables that + # are generated internally and marked advanced by this macro. + + set(_libdir ${ARGN}) + + set(_libraries_work TRUE) + set(${LIBRARIES}) set(_combined_name) + set(ENV_MKLROOT "$ENV{MKLROOT}") + set(ENV_BLAS_DIR "$ENV{BLAS_DIR}") + set(ENV_BLAS_LIBDIR "$ENV{BLAS_LIBDIR}") + if (NOT _libdir) + if (BLAS_LIBDIR) + list(APPEND _libdir "${BLAS_LIBDIR}") + elseif (BLAS_DIR) + list(APPEND _libdir "${BLAS_DIR}") + list(APPEND _libdir "${BLAS_DIR}/lib") + if("${CMAKE_SIZEOF_VOID_P}" EQUAL "8") + list(APPEND _libdir "${BLAS_DIR}/lib64") + list(APPEND _libdir "${BLAS_DIR}/lib/intel64") + else() + list(APPEND _libdir "${BLAS_DIR}/lib32") + list(APPEND _libdir "${BLAS_DIR}/lib/ia32") + endif() + elseif(ENV_BLAS_LIBDIR) + list(APPEND _libdir "${ENV_BLAS_LIBDIR}") + elseif(ENV_BLAS_DIR) + list(APPEND _libdir "${ENV_BLAS_DIR}") + list(APPEND _libdir "${ENV_BLAS_DIR}/lib") + if("${CMAKE_SIZEOF_VOID_P}" EQUAL "8") + list(APPEND _libdir "${ENV_BLAS_DIR}/lib64") + list(APPEND _libdir "${ENV_BLAS_DIR}/lib/intel64") + else() + list(APPEND _libdir "${ENV_BLAS_DIR}/lib32") + list(APPEND _libdir "${ENV_BLAS_DIR}/lib/ia32") + endif() + else() + if (ENV_MKLROOT) + list(APPEND _libdir "${ENV_MKLROOT}/lib") + if("${CMAKE_SIZEOF_VOID_P}" EQUAL "8") + list(APPEND _libdir "${ENV_MKLROOT}/lib64") + list(APPEND _libdir "${ENV_MKLROOT}/lib/intel64") + else() + list(APPEND _libdir "${ENV_MKLROOT}/lib32") + list(APPEND _libdir "${ENV_MKLROOT}/lib/ia32") + endif() + endif() + if (WIN32) + string(REPLACE ":" ";" _libdir2 "$ENV{LIB}") + elseif (APPLE) + string(REPLACE ":" ";" _libdir2 "$ENV{DYLD_LIBRARY_PATH}") + else () + string(REPLACE ":" ";" _libdir2 "$ENV{LD_LIBRARY_PATH}") + endif () + list(APPEND _libdir "${_libdir2}") + list(APPEND _libdir "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _libdir "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() + endif () + + if (BLAS_VERBOSE) + message("${Cyan}Try to find BLAS libraries: ${_list}") + endif () + foreach(_library ${_list}) set(_combined_name ${_combined_name}_${_library}) - if(_libraries_found) - # search first in ${_path} - find_library(${_prefix}_${_library}_LIBRARY - NAMES ${_library} - PATHS ${_path} NO_DEFAULT_PATH - ) - # if not found, search in environment variables and system - if ( WIN32 ) - find_library(${_prefix}_${_library}_LIBRARY - NAMES ${_library} - PATHS ENV LIB - ) - elseif ( APPLE ) - find_library(${_prefix}_${_library}_LIBRARY - NAMES ${_library} - PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH - ) + if(_libraries_work) + if (BLA_STATIC) + if (WIN32) + set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES}) + endif () + if (APPLE) + set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES}) + else () + set(CMAKE_FIND_LIBRARY_SUFFIXES .a ${CMAKE_FIND_LIBRARY_SUFFIXES}) + endif () else () - find_library(${_prefix}_${_library}_LIBRARY - NAMES ${_library} - PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV LD_LIBRARY_PATH - ) - endif() + if (CMAKE_SYSTEM_NAME STREQUAL "Linux") + # for ubuntu's libblas3gf and liblapack3gf packages + set(CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES} .so.3gf) + endif () + endif () + find_library(${_prefix}_${_library}_LIBRARY + NAMES ${_library} + HINTS ${_libdir} + NO_DEFAULT_PATH + ) mark_as_advanced(${_prefix}_${_library}_LIBRARY) + # Print status if not found + # ------------------------- + if (NOT ${_prefix}_${_library}_LIBRARY AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE) + Print_Find_Library_Blas_Status(blas ${_library} ${_libdir}) + endif () set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY}) - set(_libraries_found ${${_prefix}_${_library}_LIBRARY}) - endif(_libraries_found) + set(_libraries_work ${${_prefix}_${_library}_LIBRARY}) + endif(_libraries_work) endforeach(_library ${_list}) - if(_libraries_found) - set(_libraries_found ${${LIBRARIES}}) - endif() - # Test this combination of libraries with the Fortran/f2c interface. - # We test the Fortran interface first as it is well standardized. - if(_libraries_found AND NOT _libraries_work) - set(${DEFINITIONS} "-D${_prefix}_USE_F2C") - set(${LIBRARIES} ${_libraries_found}) - # Some C++ linkers require the f2c library to link with Fortran libraries. - # I do not know which ones, thus I just add the f2c library if it is available. - find_package( F2C QUIET ) - if ( F2C_FOUND ) - set(${DEFINITIONS} ${${DEFINITIONS}} ${F2C_DEFINITIONS}) - set(${LIBRARIES} ${${LIBRARIES}} ${F2C_LIBRARIES}) + if(_libraries_work) + # Test this combination of libraries. + if (CMAKE_SYSTEM_NAME STREQUAL "Linux" AND BLA_STATIC) + list(INSERT ${LIBRARIES} 0 "-Wl,--start-group") + list(APPEND ${LIBRARIES} "-Wl,--end-group") endif() - set(CMAKE_REQUIRED_DEFINITIONS ${${DEFINITIONS}}) - set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}}) - #message("DEBUG: CMAKE_REQUIRED_DEFINITIONS = ${CMAKE_REQUIRED_DEFINITIONS}") - #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") - # Check if function exists with f2c calling convention (ie a trailing underscore) - check_function_exists(${_name}_ ${_prefix}_${_name}_${_combined_name}_f2c_WORKS) - set(CMAKE_REQUIRED_DEFINITIONS} "") - set(CMAKE_REQUIRED_LIBRARIES "") - mark_as_advanced(${_prefix}_${_name}_${_combined_name}_f2c_WORKS) - set(_libraries_work ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS}) - endif(_libraries_found AND NOT _libraries_work) - - # If not found, test this combination of libraries with a C interface. - # A few implementations (ie ACML) provide a C interface. Unfortunately, there is no standard. - if(_libraries_found AND NOT _libraries_work) - set(${DEFINITIONS} "") - set(${LIBRARIES} ${_libraries_found}) - set(CMAKE_REQUIRED_DEFINITIONS "") - set(CMAKE_REQUIRED_LIBRARIES ${_flags} ${${LIBRARIES}}) - #message("DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}") - check_function_exists(${_name} ${_prefix}_${_name}${_combined_name}_WORKS) - set(CMAKE_REQUIRED_LIBRARIES "") - mark_as_advanced(${_prefix}_${_name}${_combined_name}_WORKS) - set(_libraries_work ${${_prefix}_${_name}${_combined_name}_WORKS}) - endif(_libraries_found AND NOT _libraries_work) - - # on failure - if(NOT _libraries_work) - set(${DEFINITIONS} "") - set(${LIBRARIES} FALSE) + set(CMAKE_REQUIRED_LIBRARIES "${_flags};${${LIBRARIES}};${_thread}") + set(CMAKE_REQUIRED_FLAGS "${BLAS_COMPILER_FLAGS}") + if (BLAS_VERBOSE) + message("${Cyan}BLAS libs found for BLA_VENDOR ${BLA_VENDOR}." + "Try to compile symbol ${_name} with following libraries:" + "${CMAKE_REQUIRED_LIBRARIES}") + endif () + if(NOT BLAS_FOUND) + unset(${_prefix}${_combined_name}_WORKS CACHE) + endif() + if (_CHECK_FORTRAN) + if (CMAKE_Fortran_COMPILER_ID STREQUAL "GNU") + string(REPLACE "mkl_intel_lp64" "mkl_gf_lp64" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + string(REPLACE "mkl_intel_ilp64" "mkl_gf_ilp64" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + endif() + check_fortran_function_exists("${_name}" ${_prefix}${_combined_name}_WORKS) + else() + check_function_exists("${_name}_" ${_prefix}${_combined_name}_WORKS) + endif() + mark_as_advanced(${_prefix}${_combined_name}_WORKS) + set(_libraries_work ${${_prefix}${_combined_name}_WORKS}) + # Print status if not found + # ------------------------- + if (NOT _libraries_work AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE) + Print_Find_Library_Blas_CheckFunc_Status(${_name} ${CMAKE_REQUIRED_LIBRARIES}) + endif () + set(CMAKE_REQUIRED_LIBRARIES) endif() - #message("DEBUG: ${DEFINITIONS} = ${${DEFINITIONS}}") - #message("DEBUG: ${LIBRARIES} = ${${LIBRARIES}}") -endmacro(check_fortran_libraries) + + if(_libraries_work) + set(${LIBRARIES} ${${LIBRARIES}} ${_thread}) + else(_libraries_work) + set(${LIBRARIES} FALSE) + endif(_libraries_work) + +endmacro(Check_Fortran_Libraries) -# -# main -# +set(BLAS_LINKER_FLAGS) +set(BLAS_LIBRARIES) +set(BLAS95_LIBRARIES) +if ($ENV{BLA_VENDOR} MATCHES ".+") + set(BLA_VENDOR $ENV{BLA_VENDOR}) +else () + if(NOT BLA_VENDOR) + set(BLA_VENDOR "All") + endif() +endif () -# Is it already configured? -if (BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) +#BLAS in intel mkl 10 library? (em64t 64bit) +if (BLA_VENDOR MATCHES "Intel*" OR BLA_VENDOR STREQUAL "All") - set(BLAS_FOUND TRUE) + if(NOT BLAS_LIBRARIES OR BLA_VENDOR MATCHES "Intel*") + # Looking for include + # ------------------- -else() + # Add system include paths to search include + # ------------------------------------------ + unset(_inc_env) + set(ENV_MKLROOT "$ENV{MKLROOT}") + set(ENV_BLAS_DIR "$ENV{BLAS_DIR}") + set(ENV_BLAS_INCDIR "$ENV{BLAS_INCDIR}") + if(ENV_BLAS_INCDIR) + list(APPEND _inc_env "${ENV_BLAS_INCDIR}") + elseif(ENV_BLAS_DIR) + list(APPEND _inc_env "${ENV_BLAS_DIR}") + list(APPEND _inc_env "${ENV_BLAS_DIR}/include") + else() + if (ENV_MKLROOT) + list(APPEND _inc_env "${ENV_MKLROOT}/include") + endif() + # system variables + if(WIN32) + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() + endif() + list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") + list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") + list(REMOVE_DUPLICATES _inc_env) - # reset variables - set( BLAS_INCLUDE_DIR "" ) - set( BLAS_DEFINITIONS "" ) - set( BLAS_LINKER_FLAGS "" ) - set( BLAS_LIBRARIES "" ) - set( BLAS_LIBRARIES_DIR "" ) + # set paths where to look for + set(PATH_TO_LOOK_FOR "${_inc_env}") - # - # If Unix, search for BLAS function in possible libraries - # + # Try to find the fftw header in the given paths + # ------------------------------------------------- + # call cmake macro to find the header path + if(BLAS_INCDIR) + set(BLAS_mkl.h_DIRS "BLAS_mkl.h_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_DIRS + NAMES mkl.h + HINTS ${BLAS_INCDIR}) + else() + if(BLAS_DIR) + set(BLAS_mkl.h_DIRS "BLAS_mkl.h_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_DIRS + NAMES mkl.h + HINTS ${BLAS_DIR} + PATH_SUFFIXES "include") + else() + set(BLAS_mkl.h_DIRS "BLAS_mkl.h_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_DIRS + NAMES mkl.h + HINTS ${PATH_TO_LOOK_FOR}) + endif() + endif() + mark_as_advanced(BLAS_mkl.h_DIRS) - # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + # If found, add path to cmake variable + # ------------------------------------ + if (BLAS_mkl.h_DIRS) + set(BLAS_INCLUDE_DIRS "${BLAS_mkl.h_DIRS}") + else () + set(BLAS_INCLUDE_DIRS "BLAS_INCLUDE_DIRS-NOTFOUND") + if(NOT BLAS_FIND_QUIETLY) + message(STATUS "Looking for BLAS -- mkl.h not found") + endif() + endif() + + if (WIN32) + string(REPLACE ":" ";" _libdir "$ENV{LIB}") + elseif (APPLE) + string(REPLACE ":" ";" _libdir "$ENV{DYLD_LIBRARY_PATH}") + else () + string(REPLACE ":" ";" _libdir "$ENV{LD_LIBRARY_PATH}") + endif () + list(APPEND _libdir "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _libdir "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + # libiomp5 + # -------- + set(OMP_iomp5_LIBRARY "OMP_iomp5_LIBRARY-NOTFOUND") + find_library(OMP_iomp5_LIBRARY + NAMES iomp5 + HINTS ${_libdir} + ) + mark_as_advanced(OMP_iomp5_LIBRARY) + set(OMP_LIB "") + # libgomp + # ------- + set(OMP_gomp_LIBRARY "OMP_gomp_LIBRARY-NOTFOUND") + find_library(OMP_gomp_LIBRARY + NAMES gomp + HINTS ${_libdir} + ) + mark_as_advanced(OMP_gomp_LIBRARY) + # choose one or another depending on the compilo + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + if (OMP_gomp_LIBRARY) + set(OMP_LIB "${OMP_gomp_LIBRARY}") + endif() + else(CMAKE_C_COMPILER_ID STREQUAL "Intel") + if (OMP_iomp5_LIBRARY) + set(OMP_LIB "${OMP_iomp5_LIBRARY}") + endif() + endif() + + if (UNIX AND NOT WIN32) + # m + find_library(M_LIBRARY + NAMES m + HINTS ${_libdir}) + mark_as_advanced(M_LIBRARY) + if(M_LIBRARY) + set(LM "-lm") + else() + set(LM "") + endif() + # Fortran + set(LGFORTRAN "") + if (CMAKE_C_COMPILER_ID MATCHES "GNU") + find_library( + FORTRAN_gfortran_LIBRARY + NAMES gfortran + HINTS ${_libdir} + ) + mark_as_advanced(FORTRAN_gfortran_LIBRARY) + if (FORTRAN_gfortran_LIBRARY) + set(LGFORTRAN "${FORTRAN_gfortran_LIBRARY}") + endif() + elseif (CMAKE_C_COMPILER_ID MATCHES "Intel") + find_library( + FORTRAN_ifcore_LIBRARY + NAMES ifcore + HINTS ${_libdir} + ) + mark_as_advanced(FORTRAN_ifcore_LIBRARY) + if (FORTRAN_ifcore_LIBRARY) + set(LGFORTRAN "{FORTRAN_ifcore_LIBRARY}") + endif() + endif() + set(BLAS_COMPILER_FLAGS "") + if (NOT BLA_VENDOR STREQUAL "Intel10_64lp_seq") + if (CMAKE_C_COMPILER_ID STREQUAL "Intel") + list(APPEND BLAS_COMPILER_FLAGS "-openmp") + endif() + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + list(APPEND BLAS_COMPILER_FLAGS "-fopenmp") + endif() + endif() + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + if (BLA_VENDOR STREQUAL "Intel10_32") + list(APPEND BLAS_COMPILER_FLAGS "-m32") + else() + list(APPEND BLAS_COMPILER_FLAGS "-m64") + endif() + if (NOT BLA_VENDOR STREQUAL "Intel10_64lp_seq") + list(APPEND OMP_LIB "-ldl") + endif() + if (ENV_MKLROOT) + list(APPEND BLAS_COMPILER_FLAGS "-I${ENV_MKLROOT}/include") + endif() + endif() + + set(additional_flags "") + if (CMAKE_C_COMPILER_ID STREQUAL "GNU" AND CMAKE_SYSTEM_NAME STREQUAL "Linux") + set(additional_flags "-Wl,--no-as-needed") + endif() + endif () + + if (_LANGUAGES_ MATCHES C OR _LANGUAGES_ MATCHES CXX) + if(BLAS_FIND_QUIETLY OR NOT BLAS_FIND_REQUIRED) + find_package(Threads) + else() + find_package(Threads REQUIRED) + endif() + + set(BLAS_SEARCH_LIBS "") + + if(BLA_F95) + + set(BLAS_mkl_SEARCH_SYMBOL SGEMM) + set(_LIBRARIES BLAS95_LIBRARIES) + if (WIN32) + if (BLA_STATIC) + set(BLAS_mkl_DLL_SUFFIX "") + else() + set(BLAS_mkl_DLL_SUFFIX "_dll") + endif() + + # Find the main file (32-bit or 64-bit) + set(BLAS_SEARCH_LIBS_WIN_MAIN "") + if (BLA_VENDOR STREQUAL "Intel10_32" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN + "mkl_blas95${BLAS_mkl_DLL_SUFFIX} mkl_intel_c${BLAS_mkl_DLL_SUFFIX}") + endif() + if (BLA_VENDOR STREQUAL "Intel10_64lp*" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN + "mkl_blas95_lp64${BLAS_mkl_DLL_SUFFIX} mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}") + endif () + + # Add threading/sequential libs + set(BLAS_SEARCH_LIBS_WIN_THREAD "") + if (BLA_VENDOR STREQUAL "*_seq" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "mkl_sequential${BLAS_mkl_DLL_SUFFIX}") + endif() + if (NOT BLA_VENDOR STREQUAL "*_seq" OR BLA_VENDOR STREQUAL "All") + # old version + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}") + # mkl >= 10.3 + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}") + endif() + + # Cartesian product of the above + foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN}) + foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD}) + list(APPEND BLAS_SEARCH_LIBS + "${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}") + endforeach() + endforeach() + else (WIN32) + if (BLA_VENDOR STREQUAL "Intel10_32" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS + "mkl_blas95 mkl_intel mkl_intel_thread mkl_core guide") + endif () + if (BLA_VENDOR STREQUAL "Intel10_64lp" OR BLA_VENDOR STREQUAL "All") + # old version + list(APPEND BLAS_SEARCH_LIBS + "mkl_blas95 mkl_intel_lp64 mkl_intel_thread mkl_core guide") + # mkl >= 10.3 + if (CMAKE_C_COMPILER_ID STREQUAL "Intel") + list(APPEND BLAS_SEARCH_LIBS + "mkl_blas95_lp64 mkl_intel_lp64 mkl_intel_thread mkl_core") + endif() + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + list(APPEND BLAS_SEARCH_LIBS + "mkl_blas95_lp64 mkl_intel_lp64 mkl_gnu_thread mkl_core") + endif() + endif () + if (BLA_VENDOR STREQUAL "Intel10_64lp_seq" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel_lp64 mkl_sequential mkl_core") + if (BLA_VENDOR STREQUAL "Intel10_64lp_seq") + set(OMP_LIB "") + endif() + endif () + endif (WIN32) + + else (BLA_F95) + + set(BLAS_mkl_SEARCH_SYMBOL sgemm) + set(_LIBRARIES BLAS_LIBRARIES) + if (WIN32) + if (BLA_STATIC) + set(BLAS_mkl_DLL_SUFFIX "") + else() + set(BLAS_mkl_DLL_SUFFIX "_dll") + endif() + + # Find the main file (32-bit or 64-bit) + set(BLAS_SEARCH_LIBS_WIN_MAIN "") + if (BLA_VENDOR STREQUAL "Intel10_32" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN + "mkl_intel_c${BLAS_mkl_DLL_SUFFIX}") + endif() + if (BLA_VENDOR STREQUAL "Intel10_64lp*" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN + "mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}") + endif () + + # Add threading/sequential libs + set(BLAS_SEARCH_LIBS_WIN_THREAD "") + if (NOT BLA_VENDOR STREQUAL "*_seq" OR BLA_VENDOR STREQUAL "All") + # old version + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}") + # mkl >= 10.3 + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}") + endif() + if (BLA_VENDOR STREQUAL "*_seq" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD + "mkl_sequential${BLAS_mkl_DLL_SUFFIX}") + endif() + + # Cartesian product of the above + foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN}) + foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD}) + list(APPEND BLAS_SEARCH_LIBS + "${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}") + endforeach() + endforeach() + else (WIN32) + if (BLA_VENDOR STREQUAL "Intel10_32" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel mkl_intel_thread mkl_core guide") + endif () + if (BLA_VENDOR STREQUAL "Intel10_64lp" OR BLA_VENDOR STREQUAL "All") + # old version + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel_lp64 mkl_intel_thread mkl_core guide") + # mkl >= 10.3 + if (CMAKE_C_COMPILER_ID STREQUAL "Intel") + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel_lp64 mkl_intel_thread mkl_core") + endif() + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel_lp64 mkl_gnu_thread mkl_core") + endif() + endif () + if (BLA_VENDOR STREQUAL "Intel10_64lp_seq" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS + "mkl_intel_lp64 mkl_sequential mkl_core") + if (BLA_VENDOR STREQUAL "Intel10_64lp_seq") + set(OMP_LIB "") + endif() + endif () + #older vesions of intel mkl libs + if (BLA_VENDOR STREQUAL "Intel" OR BLA_VENDOR STREQUAL "All") + list(APPEND BLAS_SEARCH_LIBS + "mkl") + list(APPEND BLAS_SEARCH_LIBS + "mkl_ia32") + list(APPEND BLAS_SEARCH_LIBS + "mkl_em64t") + endif () + endif (WIN32) + + endif (BLA_F95) + + foreach (IT ${BLAS_SEARCH_LIBS}) + string(REPLACE " " ";" SEARCH_LIBS ${IT}) + if (${_LIBRARIES}) + else () + check_fortran_libraries( + ${_LIBRARIES} + BLAS + ${BLAS_mkl_SEARCH_SYMBOL} + "${additional_flags}" + "${SEARCH_LIBS}" + "${OMP_LIB};${CMAKE_THREAD_LIBS_INIT};${LM}" + ) + if(_LIBRARIES) + set(BLAS_LINKER_FLAGS "${additional_flags}") + endif() + endif() + endforeach () + if(NOT BLAS_FIND_QUIETLY) + if(${_LIBRARIES}) + message(STATUS "Looking for MKL BLAS: found") + else() + message(STATUS "Looking for MKL BLAS: not found") + endif() + endif() + if (${_LIBRARIES} AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Intel MKL") + endif() + endif (_LANGUAGES_ MATCHES C OR _LANGUAGES_ MATCHES CXX) + endif(NOT BLAS_LIBRARIES OR BLA_VENDOR MATCHES "Intel*") +endif (BLA_VENDOR MATCHES "Intel*" OR BLA_VENDOR STREQUAL "All") + + +if (BLA_VENDOR STREQUAL "Goto" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + # gotoblas (http://www.tacc.utexas.edu/tacc-projects/gotoblas2) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "cblas;f77blas;atlas" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "goto2" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Goto BLAS: found") + else() + message(STATUS "Looking for Goto BLAS: not found") + endif() endif() + endif() + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Goto") + endif() - # BLAS in PhiPACK libraries? (requires generic BLAS lib, too) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS +endif (BLA_VENDOR STREQUAL "Goto" OR BLA_VENDOR STREQUAL "All") + + +# OpenBlas +if (BLA_VENDOR STREQUAL "Open" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + # openblas (http://www.openblas.net/) + check_fortran_libraries( + BLAS_LIBRARIES + BLAS + sgemm + "" + "openblas" + "" + ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Open BLAS: found") + else() + message(STATUS "Looking for Open BLAS: not found") + endif() + endif() + endif() + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Openblas") + endif() + +endif (BLA_VENDOR STREQUAL "Open" OR BLA_VENDOR STREQUAL "All") + + +# EigenBlas +if (BLA_VENDOR STREQUAL "Eigen" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page) + check_fortran_libraries( + BLAS_LIBRARIES + BLAS + sgemm + "" + "eigen_blas" + "" + ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + message(STATUS "Looking for Eigen BLAS: found") + else() + message(STATUS "Looking for Eigen BLAS: not found") + endif() + endif() + endif() + + if(NOT BLAS_LIBRARIES) + # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page) + check_fortran_libraries( + BLAS_LIBRARIES + BLAS + sgemm + "" + "eigen_blas_static" + "" + ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Eigen BLAS: found") + else() + message(STATUS "Looking for Eigen BLAS: not found") + endif() + endif() + endif() + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Eigen") + endif() + +endif (BLA_VENDOR STREQUAL "Eigen" OR BLA_VENDOR STREQUAL "All") + + +if (BLA_VENDOR STREQUAL "ATLAS" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/) + check_fortran_libraries( + BLAS_LIBRARIES + BLAS + dgemm + "" + "f77blas;atlas" + "" + ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Atlas BLAS: found") + else() + message(STATUS "Looking for Atlas BLAS: not found") + endif() + endif() + endif() + + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Atlas") + endif() + +endif (BLA_VENDOR STREQUAL "ATLAS" OR BLA_VENDOR STREQUAL "All") + + +# BLAS in PhiPACK libraries? (requires generic BLAS lib, too) +if (BLA_VENDOR STREQUAL "PhiPACK" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" "sgemm;dgemm;blas" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for PhiPACK BLAS: found") + else() + message(STATUS "Looking for PhiPACK BLAS: not found") + endif() endif() + endif() - # BLAS in Alpha CXML library? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "PhiPACK") + endif() + +endif (BLA_VENDOR STREQUAL "PhiPACK" OR BLA_VENDOR STREQUAL "All") + + +# BLAS in Alpha CXML library? +if (BLA_VENDOR STREQUAL "CXML" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" "cxml" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for CXML BLAS: found") + else() + message(STATUS "Looking for CXML BLAS: not found") + endif() endif() + endif() - # BLAS in Alpha DXML library? (now called CXML, see above) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "CXML") + endif() + +endif (BLA_VENDOR STREQUAL "CXML" OR BLA_VENDOR STREQUAL "All") + + +# BLAS in Alpha DXML library? (now called CXML, see above) +if (BLA_VENDOR STREQUAL "DXML" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" "dxml" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for DXML BLAS: found") + else() + message(STATUS "Looking for DXML BLAS: not found") + endif() endif() + endif() - # BLAS in Sun Performance library? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "DXML") + endif() + +endif (BLA_VENDOR STREQUAL "DXML" OR BLA_VENDOR STREQUAL "All") + + +# BLAS in Sun Performance library? +if (BLA_VENDOR STREQUAL "SunPerf" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "-xlic_lib=sunperf" "sunperf;sunmath" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(BLAS_LIBRARIES) + set(BLAS_LINKER_FLAGS "-xlic_lib=sunperf") + endif() + if(NOT BLAS_FIND_QUIETLY) if(BLAS_LIBRARIES) - # Extra linker flag - set(BLAS_LINKER_FLAGS "-xlic_lib=sunperf") + message(STATUS "Looking for SunPerf BLAS: found") + else() + message(STATUS "Looking for SunPerf BLAS: not found") endif() endif() + endif() - # BLAS in SCSL library? (SGI/Cray Scientific Library) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "SunPerf") + endif() + +endif () + + +# BLAS in SCSL library? (SGI/Cray Scientific Library) +if (BLA_VENDOR STREQUAL "SCSL" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" "scsl" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for SCSL BLAS: found") + else() + message(STATUS "Looking for SCSL BLAS: not found") + endif() endif() + endif() - # BLAS in SGIMATH library? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "SunPerf") + endif() + +endif () + + +# BLAS in SGIMATH library? +if (BLA_VENDOR STREQUAL "SGIMATH" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" "complib.sgimath" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for SGIMATH BLAS: found") + else() + message(STATUS "Looking for SGIMATH BLAS: not found") + endif() endif() + endif() - # BLAS in IBM ESSL library? (requires generic BLAS lib, too) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "SGIMATH") + endif() + +endif () + + +# BLAS in IBM ESSL library (requires generic BLAS lib, too) +if (BLA_VENDOR STREQUAL "IBMESSL" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "essl;blas" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "essl;xlfmath;xlf90_r;blas" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for IBM ESSL BLAS: found") + else() + message(STATUS "Looking for IBM ESSL BLAS: not found") + endif() endif() + endif() - #BLAS in intel mkl 10 library? (em64t 64bit) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "IBM ESSL") + endif() + +endif () + +# BLAS in IBM ESSL_MT library (requires generic BLAS lib, too) +if (BLA_VENDOR STREQUAL "IBMESSLMT" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "mkl_intel_lp64;mkl_intel_thread;mkl_core;guide;pthread" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" - ) - endif() - - ### windows version of intel mkl 10? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS - BLAS_LIBRARIES - BLAS - SGEMM + "esslsmp;xlsmp;xlfmath;xlf90_r;blas" "" - "mkl_c_dll;mkl_intel_thread_dll;mkl_core_dll;libguide40" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for IBM ESSL MT BLAS: found") + else() + message(STATUS "Looking for IBM ESSL MT BLAS: not found") + endif() endif() + endif() - #older versions of intel mkl libs + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "IBM ESSL MT") + endif() - # BLAS in intel mkl library? (shared) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS +endif () + + +#BLAS in acml library? +if (BLA_VENDOR MATCHES "ACML.*" OR BLA_VENDOR STREQUAL "All") + + if( ((BLA_VENDOR STREQUAL "ACML") AND (NOT BLAS_ACML_LIB_DIRS)) OR + ((BLA_VENDOR STREQUAL "ACML_MP") AND (NOT BLAS_ACML_MP_LIB_DIRS)) OR + ((BLA_VENDOR STREQUAL "ACML_GPU") AND (NOT BLAS_ACML_GPU_LIB_DIRS))) + + # try to find acml in "standard" paths + if( WIN32 ) + file( GLOB _ACML_ROOT "C:/AMD/acml*/ACML-EULA.txt" ) + else() + file( GLOB _ACML_ROOT "/opt/acml*/ACML-EULA.txt" ) + endif() + if( WIN32 ) + file( GLOB _ACML_GPU_ROOT "C:/AMD/acml*/GPGPUexamples" ) + else() + file( GLOB _ACML_GPU_ROOT "/opt/acml*/GPGPUexamples" ) + endif() + list(GET _ACML_ROOT 0 _ACML_ROOT) + list(GET _ACML_GPU_ROOT 0 _ACML_GPU_ROOT) + + if( _ACML_ROOT ) + + get_filename_component( _ACML_ROOT ${_ACML_ROOT} PATH ) + if( SIZEOF_INTEGER EQUAL 8 ) + set( _ACML_PATH_SUFFIX "_int64" ) + else() + set( _ACML_PATH_SUFFIX "" ) + endif() + if( CMAKE_Fortran_COMPILER_ID STREQUAL "Intel" ) + set( _ACML_COMPILER32 "ifort32" ) + set( _ACML_COMPILER64 "ifort64" ) + elseif( CMAKE_Fortran_COMPILER_ID STREQUAL "SunPro" ) + set( _ACML_COMPILER32 "sun32" ) + set( _ACML_COMPILER64 "sun64" ) + elseif( CMAKE_Fortran_COMPILER_ID STREQUAL "PGI" ) + set( _ACML_COMPILER32 "pgi32" ) + if( WIN32 ) + set( _ACML_COMPILER64 "win64" ) + else() + set( _ACML_COMPILER64 "pgi64" ) + endif() + elseif( CMAKE_Fortran_COMPILER_ID STREQUAL "Open64" ) + # 32 bit builds not supported on Open64 but for code simplicity + # We'll just use the same directory twice + set( _ACML_COMPILER32 "open64_64" ) + set( _ACML_COMPILER64 "open64_64" ) + elseif( CMAKE_Fortran_COMPILER_ID STREQUAL "NAG" ) + set( _ACML_COMPILER32 "nag32" ) + set( _ACML_COMPILER64 "nag64" ) + else() + set( _ACML_COMPILER32 "gfortran32" ) + set( _ACML_COMPILER64 "gfortran64" ) + endif() + + if( BLA_VENDOR STREQUAL "ACML_MP" ) + set(_ACML_MP_LIB_DIRS + "${_ACML_ROOT}/${_ACML_COMPILER32}_mp${_ACML_PATH_SUFFIX}/lib" + "${_ACML_ROOT}/${_ACML_COMPILER64}_mp${_ACML_PATH_SUFFIX}/lib" ) + else() + set(_ACML_LIB_DIRS + "${_ACML_ROOT}/${_ACML_COMPILER32}${_ACML_PATH_SUFFIX}/lib" + "${_ACML_ROOT}/${_ACML_COMPILER64}${_ACML_PATH_SUFFIX}/lib" ) + endif() + + endif(_ACML_ROOT) + + elseif(BLAS_${BLA_VENDOR}_LIB_DIRS) + + set(_${BLA_VENDOR}_LIB_DIRS ${BLAS_${BLA_VENDOR}_LIB_DIRS}) + + endif() + + if( BLA_VENDOR STREQUAL "ACML_MP" ) + foreach( BLAS_ACML_MP_LIB_DIRS ${_ACML_MP_LIB_DIRS}) + check_fortran_libraries ( + BLAS_LIBRARIES + BLAS + sgemm + "" "acml_mp;acml_mv" "" ${BLAS_ACML_MP_LIB_DIRS} + ) + if( BLAS_LIBRARIES ) + break() + endif() + endforeach() + elseif( BLA_VENDOR STREQUAL "ACML_GPU" ) + foreach( BLAS_ACML_GPU_LIB_DIRS ${_ACML_GPU_LIB_DIRS}) + check_fortran_libraries ( + BLAS_LIBRARIES + BLAS + sgemm + "" "acml;acml_mv;CALBLAS" "" ${BLAS_ACML_GPU_LIB_DIRS} + ) + if( BLAS_LIBRARIES ) + break() + endif() + endforeach() + else() + foreach( BLAS_ACML_LIB_DIRS ${_ACML_LIB_DIRS} ) + check_fortran_libraries ( + BLAS_LIBRARIES + BLAS + sgemm + "" "acml;acml_mv" "" ${BLAS_ACML_LIB_DIRS} + ) + if( BLAS_LIBRARIES ) + break() + endif() + endforeach() + endif() + + # Either acml or acml_mp should be in LD_LIBRARY_PATH but not both + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "mkl;guide;pthread" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "acml;acml_mv" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for ACML BLAS: found") + else() + message(STATUS "Looking for ACML BLAS: not found") + endif() endif() + endif() - #BLAS in intel mkl library? (static, 32bit) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "mkl_ia32;guide;pthread" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "acml_mp;acml_mv" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for ACML BLAS: found") + else() + message(STATUS "Looking for ACML BLAS: not found") + endif() endif() + endif() - #BLAS in intel mkl library? (static, em64t 64bit) - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS sgemm "" - "mkl_em64t;guide;pthread" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" - ) - endif() - - #BLAS in acml library? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS - BLAS_LIBRARIES - BLAS - sgemm + "acml;acml_mv;CALBLAS" "" - "acml" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for ACML BLAS: found") + else() + message(STATUS "Looking for ACML BLAS: not found") + endif() endif() + endif() - # Apple BLAS library? - if(NOT BLAS_LIBRARIES) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "ACML") + endif() + +endif (BLA_VENDOR MATCHES "ACML.*" OR BLA_VENDOR STREQUAL "All") # ACML + + +# Apple BLAS library? +if (BLA_VENDOR STREQUAL "Apple" OR BLA_VENDOR STREQUAL "All") + + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( BLAS_LIBRARIES BLAS - sgemm + dgemm "" "Accelerate" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + "" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Apple BLAS: found") + else() + message(STATUS "Looking for Apple BLAS: not found") + endif() endif() + endif() - if ( NOT BLAS_LIBRARIES ) - check_fortran_libraries( - BLAS_DEFINITIONS + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Apple Accelerate") + endif() + +endif (BLA_VENDOR STREQUAL "Apple" OR BLA_VENDOR STREQUAL "All") + + +if (BLA_VENDOR STREQUAL "NAS" OR BLA_VENDOR STREQUAL "All") + + if ( NOT BLAS_LIBRARIES ) + check_fortran_libraries( BLAS_LIBRARIES BLAS - sgemm + dgemm "" "vecLib" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" - ) - endif ( NOT BLAS_LIBRARIES ) - - # Generic BLAS library? - # This configuration *must* be the last try as this library is notably slow. - if ( NOT BLAS_LIBRARIES ) - check_fortran_libraries( - BLAS_DEFINITIONS - BLAS_LIBRARIES - BLAS - sgemm "" - "blas" - "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for NAS BLAS: found") + else() + message(STATUS "Looking for NAS BLAS: not found") + endif() endif() + endif () - if(BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "NAS") + endif() + +endif (BLA_VENDOR STREQUAL "NAS" OR BLA_VENDOR STREQUAL "All") + + +# Generic BLAS library? +if (BLA_VENDOR STREQUAL "Generic" OR BLA_VENDOR STREQUAL "All") + + set(BLAS_SEARCH_LIBS "blas;blas_LINUX;blas_MAC;blas_WINDOWS;refblas") + foreach (SEARCH_LIB ${BLAS_SEARCH_LIBS}) + if (BLAS_LIBRARIES) + else () + check_fortran_libraries( + BLAS_LIBRARIES + BLAS + sgemm + "" + "${SEARCH_LIB}" + "${LGFORTRAN}" + ) + if(NOT BLAS_FIND_QUIETLY) + if(BLAS_LIBRARIES) + message(STATUS "Looking for Generic BLAS: found") + else() + message(STATUS "Looking for Generic BLAS: not found") + endif() + endif() + endif() + endforeach () + + if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND) + set (BLAS_VENDOR_FOUND "Netlib or other Generic libblas") + endif() + +endif (BLA_VENDOR STREQUAL "Generic" OR BLA_VENDOR STREQUAL "All") + + +if(BLA_F95) + + if(BLAS95_LIBRARIES) + set(BLAS95_FOUND TRUE) + else() + set(BLAS95_FOUND FALSE) + endif() + + if(NOT BLAS_FIND_QUIETLY) + if(BLAS95_FOUND) + message(STATUS "A library with BLAS95 API found.") + message(STATUS "BLAS_LIBRARIES ${BLAS_LIBRARIES}") + else(BLAS95_FOUND) + message(WARNING "BLA_VENDOR has been set to ${BLA_VENDOR} but blas 95 libraries could not be found or check of symbols failed." + "\nPlease indicate where to find blas libraries. You have three options:\n" + "- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\n" + "- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\n" + "- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\n" + "\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure." + "\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name." + "\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit)," + "Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model)," + "Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic") + if(BLAS_FIND_REQUIRED) + message(FATAL_ERROR + "A required library with BLAS95 API not found. Please specify library location.") + else() + message(STATUS + "A library with BLAS95 API not found. Please specify library location.") + endif() + endif(BLAS95_FOUND) + endif(NOT BLAS_FIND_QUIETLY) + + set(BLAS_FOUND TRUE) + set(BLAS_LIBRARIES "${BLAS95_LIBRARIES}") + +else(BLA_F95) + + if(BLAS_LIBRARIES) set(BLAS_FOUND TRUE) else() set(BLAS_FOUND FALSE) @@ -388,32 +1366,41 @@ else() if(NOT BLAS_FIND_QUIETLY) if(BLAS_FOUND) message(STATUS "A library with BLAS API found.") + message(STATUS "BLAS_LIBRARIES ${BLAS_LIBRARIES}") else(BLAS_FOUND) + message(WARNING "BLA_VENDOR has been set to ${BLA_VENDOR} but blas libraries could not be found or check of symbols failed." + "\nPlease indicate where to find blas libraries. You have three options:\n" + "- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\n" + "- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\n" + "- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\n" + "\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure." + "\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name." + "\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit)," + "Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model)," + "Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic") if(BLAS_FIND_REQUIRED) - message(FATAL_ERROR "A required library with BLAS API not found. Please specify library location.") + message(FATAL_ERROR + "A required library with BLAS API not found. Please specify library location.") else() - message(STATUS "A library with BLAS API not found. Please specify library location.") + message(STATUS + "A library with BLAS API not found. Please specify library location.") endif() endif(BLAS_FOUND) endif(NOT BLAS_FIND_QUIETLY) - # Add variables to cache - set( BLAS_INCLUDE_DIR "${BLAS_INCLUDE_DIR}" - CACHE PATH "Directories containing the BLAS header files" FORCE ) - set( BLAS_DEFINITIONS "${BLAS_DEFINITIONS}" - CACHE STRING "Compilation options to use BLAS" FORCE ) - set( BLAS_LINKER_FLAGS "${BLAS_LINKER_FLAGS}" - CACHE STRING "Linker flags to use BLAS" FORCE ) - set( BLAS_LIBRARIES "${BLAS_LIBRARIES}" - CACHE FILEPATH "BLAS libraries name" FORCE ) - set( BLAS_LIBRARIES_DIR "${BLAS_LIBRARIES_DIR}" - CACHE PATH "Directories containing the BLAS libraries" FORCE ) +endif(BLA_F95) - #message("DEBUG: BLAS_INCLUDE_DIR = ${BLAS_INCLUDE_DIR}") - #message("DEBUG: BLAS_DEFINITIONS = ${BLAS_DEFINITIONS}") - #message("DEBUG: BLAS_LINKER_FLAGS = ${BLAS_LINKER_FLAGS}") - #message("DEBUG: BLAS_LIBRARIES = ${BLAS_LIBRARIES}") - #message("DEBUG: BLAS_LIBRARIES_DIR = ${BLAS_LIBRARIES_DIR}") - #message("DEBUG: BLAS_FOUND = ${BLAS_FOUND}") +set(CMAKE_FIND_LIBRARY_SUFFIXES ${_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES}) -endif(BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) +if (BLAS_FOUND) + list(GET BLAS_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + if (${first_lib_path} MATCHES "(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)") + string(REGEX REPLACE "(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)" "" not_cached_dir "${first_lib_path}") + set(BLAS_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of BLAS library" FORCE) + else() + set(BLAS_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of BLAS library" FORCE) + endif() +endif() +mark_as_advanced(BLAS_DIR) +mark_as_advanced(BLAS_DIR_FOUND) diff --git a/gtsam/3rdparty/Eigen/cmake/FindBLASEXT.cmake b/gtsam/3rdparty/Eigen/cmake/FindBLASEXT.cmake new file mode 100644 index 000000000..0fe7fb849 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindBLASEXT.cmake @@ -0,0 +1,380 @@ +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2016 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find BLAS EXTENDED for MORSE projects: find include dirs and libraries +# +# This module allows to find BLAS libraries by calling the official FindBLAS module +# and handles the creation of different library lists whether the user wishes to link +# with a sequential BLAS or a multihreaded (BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES). +# BLAS is detected with a FindBLAS call then if the BLAS vendor is Intel10_64lp, ACML +# or IBMESSLMT then the module attempts to find the corresponding multithreaded libraries. +# +# The following variables have been added to manage links with sequential or multithreaded +# versions: +# BLAS_INCLUDE_DIRS - BLAS include directories +# BLAS_LIBRARY_DIRS - Link directories for BLAS libraries +# BLAS_SEQ_LIBRARIES - BLAS component libraries to be linked (sequential) +# BLAS_PAR_LIBRARIES - BLAS component libraries to be linked (multithreaded) + +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013-2016 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) + +# macro to factorize this call +macro(find_package_blas) + if(BLASEXT_FIND_REQUIRED) + if(BLASEXT_FIND_QUIETLY) + find_package(BLAS REQUIRED QUIET) + else() + find_package(BLAS REQUIRED) + endif() + else() + if(BLASEXT_FIND_QUIETLY) + find_package(BLAS QUIET) + else() + find_package(BLAS) + endif() + endif() +endmacro() + +# add a cache variable to let the user specify the BLAS vendor +set(BLA_VENDOR "" CACHE STRING "list of possible BLAS vendor: + Open, Eigen, Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT, + Intel10_32 (intel mkl v10 32 bit), + Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), + Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model), + Intel( older versions of mkl 32 and 64 bit), + ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic") + +if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "In FindBLASEXT") + message(STATUS "If you want to force the use of one specific library, " + "\n please specify the BLAS vendor by setting -DBLA_VENDOR=blas_vendor_name" + "\n at cmake configure.") + message(STATUS "List of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, " + "\n DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT, Intel10_32 (intel mkl v10 32 bit)," + "\n Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model)," + "\n Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model)," + "\n Intel( older versions of mkl 32 and 64 bit)," + "\n ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic") +endif() + +if (NOT BLAS_FOUND) + # First try to detect two cases: + # 1: only SEQ libs are handled + # 2: both SEQ and PAR libs are handled + find_package_blas() +endif () + +# detect the cases where SEQ and PAR libs are handled +if(BLA_VENDOR STREQUAL "All" AND + (BLAS_mkl_core_LIBRARY OR BLAS_mkl_core_dll_LIBRARY) + ) + set(BLA_VENDOR "Intel") + if(BLAS_mkl_intel_LIBRARY) + set(BLA_VENDOR "Intel10_32") + endif() + if(BLAS_mkl_intel_lp64_LIBRARY) + set(BLA_VENDOR "Intel10_64lp") + endif() + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "A BLAS library has been found (${BLAS_LIBRARIES}) but we" + "\n have also potentially detected some multithreaded BLAS libraries from the MKL." + "\n We try to find both libraries lists (Sequential/Multithreaded).") + endif() + set(BLAS_FOUND "") +elseif(BLA_VENDOR STREQUAL "All" AND BLAS_acml_LIBRARY) + set(BLA_VENDOR "ACML") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "A BLAS library has been found (${BLAS_LIBRARIES}) but we" + "\n have also potentially detected some multithreaded BLAS libraries from the ACML." + "\n We try to find both libraries lists (Sequential/Multithreaded).") + endif() + set(BLAS_FOUND "") +elseif(BLA_VENDOR STREQUAL "All" AND BLAS_essl_LIBRARY) + set(BLA_VENDOR "IBMESSL") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "A BLAS library has been found (${BLAS_LIBRARIES}) but we" + "\n have also potentially detected some multithreaded BLAS libraries from the ESSL." + "\n We try to find both libraries lists (Sequential/Multithreaded).") + endif() + set(BLAS_FOUND "") +endif() + +# Intel case +if(BLA_VENDOR MATCHES "Intel*") + + ### + # look for include path if the BLAS vendor is Intel + ### + + # gather system include paths + unset(_inc_env) + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() + list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") + list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") + set(ENV_MKLROOT "$ENV{MKLROOT}") + if (ENV_MKLROOT) + list(APPEND _inc_env "${ENV_MKLROOT}/include") + endif() + list(REMOVE_DUPLICATES _inc_env) + + # find mkl.h inside known include paths + set(BLAS_mkl.h_INCLUDE_DIRS "BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND") + if(BLAS_INCDIR) + set(BLAS_mkl.h_INCLUDE_DIRS "BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_INCLUDE_DIRS + NAMES mkl.h + HINTS ${BLAS_INCDIR}) + else() + if(BLAS_DIR) + set(BLAS_mkl.h_INCLUDE_DIRS "BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_INCLUDE_DIRS + NAMES mkl.h + HINTS ${BLAS_DIR} + PATH_SUFFIXES include) + else() + set(BLAS_mkl.h_INCLUDE_DIRS "BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND") + find_path(BLAS_mkl.h_INCLUDE_DIRS + NAMES mkl.h + HINTS ${_inc_env}) + endif() + endif() + mark_as_advanced(BLAS_mkl.h_INCLUDE_DIRS) + ## Print status if not found + ## ------------------------- + #if (NOT BLAS_mkl.h_INCLUDE_DIRS AND MORSE_VERBOSE) + # Print_Find_Header_Status(blas mkl.h) + #endif () + set(BLAS_INCLUDE_DIRS "") + if(BLAS_mkl.h_INCLUDE_DIRS) + list(APPEND BLAS_INCLUDE_DIRS "${BLAS_mkl.h_INCLUDE_DIRS}" ) + endif() + + ### + # look for libs + ### + # if Intel 10 64 bit -> look for sequential and multithreaded versions + if(BLA_VENDOR MATCHES "Intel10_64lp*") + + ## look for the sequential version + set(BLA_VENDOR "Intel10_64lp_seq") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "Look for the sequential version Intel10_64lp_seq") + endif() + find_package_blas() + if(BLAS_FOUND) + set(BLAS_SEQ_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_SEQ_LIBRARIES "${BLAS_SEQ_LIBRARIES-NOTFOUND}") + endif() + + ## look for the multithreaded version + set(BLA_VENDOR "Intel10_64lp") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "Look for the multithreaded version Intel10_64lp") + endif() + find_package_blas() + if(BLAS_FOUND) + set(BLAS_PAR_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_PAR_LIBRARIES "${BLAS_PAR_LIBRARIES-NOTFOUND}") + endif() + + else() + + if(BLAS_FOUND) + set(BLAS_SEQ_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_SEQ_LIBRARIES "${BLAS_SEQ_LIBRARIES-NOTFOUND}") + endif() + + endif() + + # ACML case +elseif(BLA_VENDOR MATCHES "ACML*") + + ## look for the sequential version + set(BLA_VENDOR "ACML") + find_package_blas() + if(BLAS_FOUND) + set(BLAS_SEQ_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_SEQ_LIBRARIES "${BLAS_SEQ_LIBRARIES-NOTFOUND}") + endif() + + ## look for the multithreaded version + set(BLA_VENDOR "ACML_MP") + find_package_blas() + if(BLAS_FOUND) + set(BLAS_PAR_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_PAR_LIBRARIES "${BLAS_PAR_LIBRARIES-NOTFOUND}") + endif() + + # IBMESSL case +elseif(BLA_VENDOR MATCHES "IBMESSL*") + + ## look for the sequential version + set(BLA_VENDOR "IBMESSL") + find_package_blas() + if(BLAS_FOUND) + set(BLAS_SEQ_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_SEQ_LIBRARIES "${BLAS_SEQ_LIBRARIES-NOTFOUND}") + endif() + + ## look for the multithreaded version + set(BLA_VENDOR "IBMESSLMT") + find_package_blas() + if(BLAS_FOUND) + set(BLAS_PAR_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_PAR_LIBRARIES "${BLAS_PAR_LIBRARIES-NOTFOUND}") + endif() + +else() + + if(BLAS_FOUND) + # define the SEQ libs as the BLAS_LIBRARIES + set(BLAS_SEQ_LIBRARIES "${BLAS_LIBRARIES}") + else() + set(BLAS_SEQ_LIBRARIES "${BLAS_SEQ_LIBRARIES-NOTFOUND}") + endif() + set(BLAS_PAR_LIBRARIES "${BLAS_PAR_LIBRARIES-NOTFOUND}") + +endif() + + +if(BLAS_SEQ_LIBRARIES) + set(BLAS_LIBRARIES "${BLAS_SEQ_LIBRARIES}") +endif() + +# extract libs paths +# remark: because it is not given by find_package(BLAS) +set(BLAS_LIBRARY_DIRS "") +string(REPLACE " " ";" BLAS_LIBRARIES "${BLAS_LIBRARIES}") +foreach(blas_lib ${BLAS_LIBRARIES}) + if (EXISTS "${blas_lib}") + get_filename_component(a_blas_lib_dir "${blas_lib}" PATH) + list(APPEND BLAS_LIBRARY_DIRS "${a_blas_lib_dir}" ) + else() + string(REPLACE "-L" "" blas_lib "${blas_lib}") + if (EXISTS "${blas_lib}") + list(APPEND BLAS_LIBRARY_DIRS "${blas_lib}" ) + else() + get_filename_component(a_blas_lib_dir "${blas_lib}" PATH) + if (EXISTS "${a_blas_lib_dir}") + list(APPEND BLAS_LIBRARY_DIRS "${a_blas_lib_dir}" ) + endif() + endif() + endif() +endforeach() +if (BLAS_LIBRARY_DIRS) + list(REMOVE_DUPLICATES BLAS_LIBRARY_DIRS) +endif () + +# check that BLAS has been found +# --------------------------------- +include(FindPackageHandleStandardArgs) +if(BLA_VENDOR MATCHES "Intel*") + if(BLA_VENDOR MATCHES "Intel10_64lp*") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS found is Intel MKL:" + "\n we manage two lists of libs, one sequential and one parallel if found" + "\n (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)") + message(STATUS "BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_SEQ_LIBRARIES + BLAS_LIBRARY_DIRS + BLAS_INCLUDE_DIRS) + if(BLAS_PAR_LIBRARIES) + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS parallel libraries stored in BLAS_PAR_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_PAR_LIBRARIES) + endif() + else() + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_SEQ_LIBRARIES + BLAS_LIBRARY_DIRS + BLAS_INCLUDE_DIRS) + endif() +elseif(BLA_VENDOR MATCHES "ACML*") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS found is ACML:" + "\n we manage two lists of libs, one sequential and one parallel if found" + "\n (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)") + message(STATUS "BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_SEQ_LIBRARIES + BLAS_LIBRARY_DIRS) + if(BLAS_PAR_LIBRARIES) + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS parallel libraries stored in BLAS_PAR_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_PAR_LIBRARIES) + endif() +elseif(BLA_VENDOR MATCHES "IBMESSL*") + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS found is ESSL:" + "\n we manage two lists of libs, one sequential and one parallel if found" + "\n (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)") + message(STATUS "BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_SEQ_LIBRARIES + BLAS_LIBRARY_DIRS) + if(BLAS_PAR_LIBRARIES) + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS parallel libraries stored in BLAS_PAR_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_PAR_LIBRARIES) + endif() +else() + if(NOT BLASEXT_FIND_QUIETLY) + message(STATUS "BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES") + endif() + find_package_handle_standard_args(BLAS DEFAULT_MSG + BLAS_SEQ_LIBRARIES + BLAS_LIBRARY_DIRS) +endif() diff --git a/gtsam/3rdparty/Eigen/cmake/FindComputeCpp.cmake b/gtsam/3rdparty/Eigen/cmake/FindComputeCpp.cmake new file mode 100644 index 000000000..07ebed61b --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindComputeCpp.cmake @@ -0,0 +1,245 @@ +#.rst: +# FindComputeCpp +#--------------- +# +# Copyright 2016 Codeplay Software Ltd. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use these files except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +######################### +# FindComputeCpp.cmake +######################### +# +# Tools for finding and building with ComputeCpp. +# +# User must define COMPUTECPP_PACKAGE_ROOT_DIR pointing to the ComputeCpp +# installation. +# +# Latest version of this file can be found at: +# https://github.com/codeplaysoftware/computecpp-sdk + +# Require CMake version 3.2.2 or higher +cmake_minimum_required(VERSION 3.2.2) + +# Check that a supported host compiler can be found +if(CMAKE_COMPILER_IS_GNUCXX) + # Require at least gcc 4.8 + if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8) + message(FATAL_ERROR + "host compiler - Not found! (gcc version must be at least 4.8)") + # Require the GCC dual ABI to be disabled for 5.1 or higher + elseif (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 5.1) + set(COMPUTECPP_DISABLE_GCC_DUAL_ABI "True") + message(STATUS + "host compiler - gcc ${CMAKE_CXX_COMPILER_VERSION} (note pre 5.1 gcc ABI enabled)") + else() + message(STATUS "host compiler - gcc ${CMAKE_CXX_COMPILER_VERSION}") + endif() +elseif ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + # Require at least clang 3.6 + if (${CMAKE_CXX_COMPILER_VERSION} VERSION_LESS 3.6) + message(FATAL_ERROR + "host compiler - Not found! (clang version must be at least 3.6)") + else() + message(STATUS "host compiler - clang ${CMAKE_CXX_COMPILER_VERSION}") + endif() +else() + message(WARNING + "host compiler - Not found! (ComputeCpp supports GCC and Clang, see readme)") +endif() + +set(COMPUTECPP_64_BIT_DEFAULT ON) +option(COMPUTECPP_64_BIT_CODE "Compile device code in 64 bit mode" + ${COMPUTECPP_64_BIT_DEFAULT}) +mark_as_advanced(COMPUTECPP_64_BIT_CODE) + +# Find OpenCL package +find_package(OpenCL REQUIRED) + +# Find ComputeCpp packagee +if(NOT COMPUTECPP_PACKAGE_ROOT_DIR) + message(FATAL_ERROR + "ComputeCpp package - Not found! (please set COMPUTECPP_PACKAGE_ROOT_DIR") +else() + message(STATUS "ComputeCpp package - Found") +endif() +option(COMPUTECPP_PACKAGE_ROOT_DIR "Path to the ComputeCpp Package") + +# Obtain the path to compute++ +find_program(COMPUTECPP_DEVICE_COMPILER compute++ PATHS + ${COMPUTECPP_PACKAGE_ROOT_DIR} PATH_SUFFIXES bin) +if (EXISTS ${COMPUTECPP_DEVICE_COMPILER}) + mark_as_advanced(COMPUTECPP_DEVICE_COMPILER) + message(STATUS "compute++ - Found") +else() + message(FATAL_ERROR "compute++ - Not found! (${COMPUTECPP_DEVICE_COMPILER})") +endif() + +# Obtain the path to computecpp_info +find_program(COMPUTECPP_INFO_TOOL computecpp_info PATHS + ${COMPUTECPP_PACKAGE_ROOT_DIR} PATH_SUFFIXES bin) +if (EXISTS ${COMPUTECPP_INFO_TOOL}) + mark_as_advanced(${COMPUTECPP_INFO_TOOL}) + message(STATUS "computecpp_info - Found") +else() + message(FATAL_ERROR "computecpp_info - Not found! (${COMPUTECPP_INFO_TOOL})") +endif() + +# Obtain the path to the ComputeCpp runtime library +find_library(COMPUTECPP_RUNTIME_LIBRARY ComputeCpp PATHS ${COMPUTECPP_PACKAGE_ROOT_DIR} + HINTS ${COMPUTECPP_PACKAGE_ROOT_DIR}/lib PATH_SUFFIXES lib + DOC "ComputeCpp Runtime Library" NO_DEFAULT_PATH) + +if (EXISTS ${COMPUTECPP_RUNTIME_LIBRARY}) + mark_as_advanced(COMPUTECPP_RUNTIME_LIBRARY) + message(STATUS "libComputeCpp.so - Found") +else() + message(FATAL_ERROR "libComputeCpp.so - Not found!") +endif() + +# Obtain the ComputeCpp include directory +set(COMPUTECPP_INCLUDE_DIRECTORY ${COMPUTECPP_PACKAGE_ROOT_DIR}/include/) +if (NOT EXISTS ${COMPUTECPP_INCLUDE_DIRECTORY}) + message(FATAL_ERROR "ComputeCpp includes - Not found!") +else() + message(STATUS "ComputeCpp includes - Found") +endif() + +# Obtain the package version +execute_process(COMMAND ${COMPUTECPP_INFO_TOOL} "--dump-version" + OUTPUT_VARIABLE COMPUTECPP_PACKAGE_VERSION + RESULT_VARIABLE COMPUTECPP_INFO_TOOL_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE) +if(NOT COMPUTECPP_INFO_TOOL_RESULT EQUAL "0") + message(FATAL_ERROR "Package version - Error obtaining version!") +else() + mark_as_advanced(COMPUTECPP_PACKAGE_VERSION) + message(STATUS "Package version - ${COMPUTECPP_PACKAGE_VERSION}") +endif() + +# Obtain the device compiler flags +execute_process(COMMAND ${COMPUTECPP_INFO_TOOL} "--dump-device-compiler-flags" + OUTPUT_VARIABLE COMPUTECPP_DEVICE_COMPILER_FLAGS + RESULT_VARIABLE COMPUTECPP_INFO_TOOL_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE) +if(NOT COMPUTECPP_INFO_TOOL_RESULT EQUAL "0") + message(FATAL_ERROR "compute++ flags - Error obtaining compute++ flags!") +else() + mark_as_advanced(COMPUTECPP_COMPILER_FLAGS) + message(STATUS "compute++ flags - ${COMPUTECPP_DEVICE_COMPILER_FLAGS}") +endif() + +set(COMPUTECPP_DEVICE_COMPILER_FLAGS ${COMPUTECPP_DEVICE_COMPILER_FLAGS} -sycl-compress-name -no-serial-memop -DEIGEN_NO_ASSERTION_CHECKING=1) + +# Check if the platform is supported +execute_process(COMMAND ${COMPUTECPP_INFO_TOOL} "--dump-is-supported" + OUTPUT_VARIABLE COMPUTECPP_PLATFORM_IS_SUPPORTED + RESULT_VARIABLE COMPUTECPP_INFO_TOOL_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE) +if(NOT COMPUTECPP_INFO_TOOL_RESULT EQUAL "0") + message(FATAL_ERROR "platform - Error checking platform support!") +else() + mark_as_advanced(COMPUTECPP_PLATFORM_IS_SUPPORTED) + if (COMPUTECPP_PLATFORM_IS_SUPPORTED) + message(STATUS "platform - your system can support ComputeCpp") + else() + message(STATUS "platform - your system CANNOT support ComputeCpp") + endif() +endif() + +#################### +# __build_sycl +#################### +# +# Adds a custom target for running compute++ and adding a dependency for the +# resulting integration header. +# +# targetName : Name of the target. +# sourceFile : Source file to be compiled. +# binaryDir : Intermediate directory to output the integration header. +# +function(__build_spir targetName sourceFile binaryDir) + + # Retrieve source file name. + get_filename_component(sourceFileName ${sourceFile} NAME) + + # Set the path to the Sycl file. + set(outputSyclFile ${binaryDir}/${sourceFileName}.sycl) + + # Add any user-defined include to the device compiler + get_property(includeDirectories DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY + INCLUDE_DIRECTORIES) + set(device_compiler_includes "") + foreach(directory ${includeDirectories}) + set(device_compiler_includes "-I${directory}" ${device_compiler_includes}) + endforeach() + if (CMAKE_INCLUDE_PATH) + foreach(directory ${CMAKE_INCLUDE_PATH}) + set(device_compiler_includes "-I${directory}" + ${device_compiler_includes}) + endforeach() + endif() + + # Convert argument list format + separate_arguments(COMPUTECPP_DEVICE_COMPILER_FLAGS) + + # Add custom command for running compute++ + add_custom_command( + OUTPUT ${outputSyclFile} + COMMAND ${COMPUTECPP_DEVICE_COMPILER} + ${COMPUTECPP_DEVICE_COMPILER_FLAGS} + -isystem ${COMPUTECPP_INCLUDE_DIRECTORY} + ${COMPUTECPP_PLATFORM_SPECIFIC_ARGS} + ${device_compiler_includes} + -o ${outputSyclFile} + -c ${CMAKE_CURRENT_SOURCE_DIR}/${sourceFile} + DEPENDS ${sourceFile} + WORKING_DIRECTORY ${binaryDir} + COMMENT "Building ComputeCpp integration header file ${outputSyclFile}") + + # Add a custom target for the generated integration header + add_custom_target(${targetName}_integration_header DEPENDS ${outputSyclFile}) + + # Add a dependency on the integration header + add_dependencies(${targetName} ${targetName}_integration_header) + + # Set the host compiler C++ standard to C++11 + set_property(TARGET ${targetName} PROPERTY CXX_STANDARD 11) + + # Disable GCC dual ABI on GCC 5.1 and higher + if(COMPUTECPP_DISABLE_GCC_DUAL_ABI) + set_property(TARGET ${targetName} APPEND PROPERTY COMPILE_DEFINITIONS + "_GLIBCXX_USE_CXX11_ABI=0") + endif() + +endfunction() + +####################### +# add_sycl_to_target +####################### +# +# Adds a SYCL compilation custom command associated with an existing +# target and sets a dependancy on that new command. +# +# targetName : Name of the target to add a SYCL to. +# sourceFile : Source file to be compiled for SYCL. +# binaryDir : Intermediate directory to output the integration header. +# +function(add_sycl_to_target targetName sourceFile binaryDir) + + # Add custom target to run compute++ and generate the integration header + __build_spir(${targetName} ${sourceFile} ${binaryDir}) + + # Link with the ComputeCpp runtime library + target_link_libraries(${targetName} PUBLIC ${COMPUTECPP_RUNTIME_LIBRARY} + PUBLIC ${OpenCL_LIBRARIES}) + +endfunction(add_sycl_to_target) diff --git a/gtsam/3rdparty/Eigen/cmake/FindEigen3.cmake b/gtsam/3rdparty/Eigen/cmake/FindEigen3.cmake index 9c546a05d..9e9697860 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindEigen3.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindEigen3.cmake @@ -9,6 +9,12 @@ # EIGEN3_FOUND - system has eigen lib with correct version # EIGEN3_INCLUDE_DIR - the eigen include directory # EIGEN3_VERSION - eigen version +# +# This module reads hints about search locations from +# the following enviroment variables: +# +# EIGEN3_ROOT +# EIGEN3_ROOT_DIR # Copyright (c) 2006, 2007 Montel Laurent, # Copyright (c) 2008, 2009 Gael Guennebaud, @@ -60,13 +66,23 @@ if (EIGEN3_INCLUDE_DIR) set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) else (EIGEN3_INCLUDE_DIR) + + # search first if an Eigen3Config.cmake is available in the system, + # if successful this would set EIGEN3_INCLUDE_DIR and the rest of + # the script will work as usual + find_package(Eigen3 ${Eigen3_FIND_VERSION} NO_MODULE QUIET) - find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library - PATHS - ${CMAKE_INSTALL_PREFIX}/include - ${KDE4_INCLUDE_DIR} - PATH_SUFFIXES eigen3 eigen - ) + if(NOT EIGEN3_INCLUDE_DIR) + find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + HINTS + ENV EIGEN3_ROOT + ENV EIGEN3_ROOT_DIR + PATHS + ${CMAKE_INSTALL_PREFIX}/include + ${KDE4_INCLUDE_DIR} + PATH_SUFFIXES eigen3 eigen + ) + endif(NOT EIGEN3_INCLUDE_DIR) if(EIGEN3_INCLUDE_DIR) _eigen3_check_version() diff --git a/gtsam/3rdparty/Eigen/cmake/FindHWLOC.cmake b/gtsam/3rdparty/Eigen/cmake/FindHWLOC.cmake new file mode 100644 index 000000000..a831b5c72 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindHWLOC.cmake @@ -0,0 +1,331 @@ +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2014 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find HWLOC include dirs and libraries +# Use this module by invoking find_package with the form: +# find_package(HWLOC +# [REQUIRED]) # Fail with error if hwloc is not found +# +# This module finds headers and hwloc library. +# Results are reported in variables: +# HWLOC_FOUND - True if headers and requested libraries were found +# HWLOC_INCLUDE_DIRS - hwloc include directories +# HWLOC_LIBRARY_DIRS - Link directories for hwloc libraries +# HWLOC_LIBRARIES - hwloc component libraries to be linked +# +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DHWLOC_DIR=path/to/hwloc): +# HWLOC_DIR - Where to find the base directory of hwloc +# HWLOC_INCDIR - Where to find the header files +# HWLOC_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: HWLOC_DIR, HWLOC_INCDIR, HWLOC_LIBDIR + +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) + +include(CheckStructHasMember) +include(CheckCSourceCompiles) + +if (NOT HWLOC_FOUND) + set(HWLOC_DIR "" CACHE PATH "Installation directory of HWLOC library") + if (NOT HWLOC_FIND_QUIETLY) + message(STATUS "A cache variable, namely HWLOC_DIR, has been set to specify the install directory of HWLOC") + endif() +endif() + +set(ENV_HWLOC_DIR "$ENV{HWLOC_DIR}") +set(ENV_HWLOC_INCDIR "$ENV{HWLOC_INCDIR}") +set(ENV_HWLOC_LIBDIR "$ENV{HWLOC_LIBDIR}") +set(HWLOC_GIVEN_BY_USER "FALSE") +if ( HWLOC_DIR OR ( HWLOC_INCDIR AND HWLOC_LIBDIR) OR ENV_HWLOC_DIR OR (ENV_HWLOC_INCDIR AND ENV_HWLOC_LIBDIR) ) + set(HWLOC_GIVEN_BY_USER "TRUE") +endif() + +# Optionally use pkg-config to detect include/library dirs (if pkg-config is available) +# ------------------------------------------------------------------------------------- +include(FindPkgConfig) +find_package(PkgConfig QUIET) +if( PKG_CONFIG_EXECUTABLE AND NOT HWLOC_GIVEN_BY_USER ) + + pkg_search_module(HWLOC hwloc) + if (NOT HWLOC_FIND_QUIETLY) + if (HWLOC_FOUND AND HWLOC_LIBRARIES) + message(STATUS "Looking for HWLOC - found using PkgConfig") + #if(NOT HWLOC_INCLUDE_DIRS) + # message("${Magenta}HWLOC_INCLUDE_DIRS is empty using PkgConfig." + # "Perhaps the path to hwloc headers is already present in your" + # "C(PLUS)_INCLUDE_PATH environment variable.${ColourReset}") + #endif() + else() + message(STATUS "${Magenta}Looking for HWLOC - not found using PkgConfig." + "\n Perhaps you should add the directory containing hwloc.pc to" + "\n the PKG_CONFIG_PATH environment variable.${ColourReset}") + endif() + endif() + +endif( PKG_CONFIG_EXECUTABLE AND NOT HWLOC_GIVEN_BY_USER ) + +if( (NOT PKG_CONFIG_EXECUTABLE) OR (PKG_CONFIG_EXECUTABLE AND NOT HWLOC_FOUND) OR (HWLOC_GIVEN_BY_USER) ) + + if (NOT HWLOC_FIND_QUIETLY) + message(STATUS "Looking for HWLOC - PkgConfig not used") + endif() + + # Looking for include + # ------------------- + + # Add system include paths to search include + # ------------------------------------------ + unset(_inc_env) + if(ENV_HWLOC_INCDIR) + list(APPEND _inc_env "${ENV_HWLOC_INCDIR}") + elseif(ENV_HWLOC_DIR) + list(APPEND _inc_env "${ENV_HWLOC_DIR}") + list(APPEND _inc_env "${ENV_HWLOC_DIR}/include") + list(APPEND _inc_env "${ENV_HWLOC_DIR}/include/hwloc") + else() + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() + endif() + list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") + list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") + list(REMOVE_DUPLICATES _inc_env) + + # set paths where to look for + set(PATH_TO_LOOK_FOR "${_inc_env}") + + # Try to find the hwloc header in the given paths + # ------------------------------------------------- + # call cmake macro to find the header path + if(HWLOC_INCDIR) + set(HWLOC_hwloc.h_DIRS "HWLOC_hwloc.h_DIRS-NOTFOUND") + find_path(HWLOC_hwloc.h_DIRS + NAMES hwloc.h + HINTS ${HWLOC_INCDIR}) + else() + if(HWLOC_DIR) + set(HWLOC_hwloc.h_DIRS "HWLOC_hwloc.h_DIRS-NOTFOUND") + find_path(HWLOC_hwloc.h_DIRS + NAMES hwloc.h + HINTS ${HWLOC_DIR} + PATH_SUFFIXES "include" "include/hwloc") + else() + set(HWLOC_hwloc.h_DIRS "HWLOC_hwloc.h_DIRS-NOTFOUND") + find_path(HWLOC_hwloc.h_DIRS + NAMES hwloc.h + HINTS ${PATH_TO_LOOK_FOR} + PATH_SUFFIXES "hwloc") + endif() + endif() + mark_as_advanced(HWLOC_hwloc.h_DIRS) + + # Add path to cmake variable + # ------------------------------------ + if (HWLOC_hwloc.h_DIRS) + set(HWLOC_INCLUDE_DIRS "${HWLOC_hwloc.h_DIRS}") + else () + set(HWLOC_INCLUDE_DIRS "HWLOC_INCLUDE_DIRS-NOTFOUND") + if(NOT HWLOC_FIND_QUIETLY) + message(STATUS "Looking for hwloc -- hwloc.h not found") + endif() + endif () + + if (HWLOC_INCLUDE_DIRS) + list(REMOVE_DUPLICATES HWLOC_INCLUDE_DIRS) + endif () + + + # Looking for lib + # --------------- + + # Add system library paths to search lib + # -------------------------------------- + unset(_lib_env) + if(ENV_HWLOC_LIBDIR) + list(APPEND _lib_env "${ENV_HWLOC_LIBDIR}") + elseif(ENV_HWLOC_DIR) + list(APPEND _lib_env "${ENV_HWLOC_DIR}") + list(APPEND _lib_env "${ENV_HWLOC_DIR}/lib") + else() + if(WIN32) + string(REPLACE ":" ";" _lib_env "$ENV{LIB}") + else() + if(APPLE) + string(REPLACE ":" ";" _lib_env "$ENV{DYLD_LIBRARY_PATH}") + else() + string(REPLACE ":" ";" _lib_env "$ENV{LD_LIBRARY_PATH}") + endif() + list(APPEND _lib_env "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _lib_env "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() + endif() + list(REMOVE_DUPLICATES _lib_env) + + # set paths where to look for + set(PATH_TO_LOOK_FOR "${_lib_env}") + + # Try to find the hwloc lib in the given paths + # ---------------------------------------------- + + # call cmake macro to find the lib path + if(HWLOC_LIBDIR) + set(HWLOC_hwloc_LIBRARY "HWLOC_hwloc_LIBRARY-NOTFOUND") + find_library(HWLOC_hwloc_LIBRARY + NAMES hwloc + HINTS ${HWLOC_LIBDIR}) + else() + if(HWLOC_DIR) + set(HWLOC_hwloc_LIBRARY "HWLOC_hwloc_LIBRARY-NOTFOUND") + find_library(HWLOC_hwloc_LIBRARY + NAMES hwloc + HINTS ${HWLOC_DIR} + PATH_SUFFIXES lib lib32 lib64) + else() + set(HWLOC_hwloc_LIBRARY "HWLOC_hwloc_LIBRARY-NOTFOUND") + find_library(HWLOC_hwloc_LIBRARY + NAMES hwloc + HINTS ${PATH_TO_LOOK_FOR}) + endif() + endif() + mark_as_advanced(HWLOC_hwloc_LIBRARY) + + # If found, add path to cmake variable + # ------------------------------------ + if (HWLOC_hwloc_LIBRARY) + get_filename_component(hwloc_lib_path ${HWLOC_hwloc_LIBRARY} PATH) + # set cmake variables (respects naming convention) + set(HWLOC_LIBRARIES "${HWLOC_hwloc_LIBRARY}") + set(HWLOC_LIBRARY_DIRS "${hwloc_lib_path}") + else () + set(HWLOC_LIBRARIES "HWLOC_LIBRARIES-NOTFOUND") + set(HWLOC_LIBRARY_DIRS "HWLOC_LIBRARY_DIRS-NOTFOUND") + if(NOT HWLOC_FIND_QUIETLY) + message(STATUS "Looking for hwloc -- lib hwloc not found") + endif() + endif () + + if (HWLOC_LIBRARY_DIRS) + list(REMOVE_DUPLICATES HWLOC_LIBRARY_DIRS) + endif () + + # check a function to validate the find + if(HWLOC_LIBRARIES) + + set(REQUIRED_INCDIRS) + set(REQUIRED_LIBDIRS) + set(REQUIRED_LIBS) + + # HWLOC + if (HWLOC_INCLUDE_DIRS) + set(REQUIRED_INCDIRS "${HWLOC_INCLUDE_DIRS}") + endif() + if (HWLOC_LIBRARY_DIRS) + set(REQUIRED_LIBDIRS "${HWLOC_LIBRARY_DIRS}") + endif() + set(REQUIRED_LIBS "${HWLOC_LIBRARIES}") + + # set required libraries for link + set(CMAKE_REQUIRED_INCLUDES "${REQUIRED_INCDIRS}") + set(CMAKE_REQUIRED_LIBRARIES) + foreach(lib_dir ${REQUIRED_LIBDIRS}) + list(APPEND CMAKE_REQUIRED_LIBRARIES "-L${lib_dir}") + endforeach() + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LIBS}") + string(REGEX REPLACE "^ -" "-" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + + # test link + unset(HWLOC_WORKS CACHE) + include(CheckFunctionExists) + check_function_exists(hwloc_topology_init HWLOC_WORKS) + mark_as_advanced(HWLOC_WORKS) + + if(NOT HWLOC_WORKS) + if(NOT HWLOC_FIND_QUIETLY) + message(STATUS "Looking for hwloc : test of hwloc_topology_init with hwloc library fails") + message(STATUS "CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}") + message(STATUS "CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}") + message(STATUS "Check in CMakeFiles/CMakeError.log to figure out why it fails") + endif() + endif() + set(CMAKE_REQUIRED_INCLUDES) + set(CMAKE_REQUIRED_FLAGS) + set(CMAKE_REQUIRED_LIBRARIES) + endif(HWLOC_LIBRARIES) + +endif( (NOT PKG_CONFIG_EXECUTABLE) OR (PKG_CONFIG_EXECUTABLE AND NOT HWLOC_FOUND) OR (HWLOC_GIVEN_BY_USER) ) + +if (HWLOC_LIBRARIES) + if (HWLOC_LIBRARY_DIRS) + list(GET HWLOC_LIBRARY_DIRS 0 first_lib_path) + else() + list(GET HWLOC_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + endif() + if (${first_lib_path} MATCHES "/lib(32|64)?$") + string(REGEX REPLACE "/lib(32|64)?$" "" not_cached_dir "${first_lib_path}") + set(HWLOC_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of HWLOC library" FORCE) + else() + set(HWLOC_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of HWLOC library" FORCE) + endif() +endif() +mark_as_advanced(HWLOC_DIR) +mark_as_advanced(HWLOC_DIR_FOUND) + +# check that HWLOC has been found +# ------------------------------- +include(FindPackageHandleStandardArgs) +if (PKG_CONFIG_EXECUTABLE AND HWLOC_FOUND) + find_package_handle_standard_args(HWLOC DEFAULT_MSG + HWLOC_LIBRARIES) +else() + find_package_handle_standard_args(HWLOC DEFAULT_MSG + HWLOC_LIBRARIES + HWLOC_WORKS) +endif() + +if (HWLOC_FOUND) + set(HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES}) + list(APPEND CMAKE_REQUIRED_INCLUDES ${HWLOC_INCLUDE_DIRS}) + + # test headers to guess the version + check_struct_has_member( "struct hwloc_obj" parent hwloc.h HAVE_HWLOC_PARENT_MEMBER ) + check_struct_has_member( "struct hwloc_cache_attr_s" size hwloc.h HAVE_HWLOC_CACHE_ATTR ) + check_c_source_compiles( "#include + int main(void) { hwloc_obj_t o; o->type = HWLOC_OBJ_PU; return 0;}" HAVE_HWLOC_OBJ_PU) + include(CheckLibraryExists) + check_library_exists(${HWLOC_LIBRARIES} hwloc_bitmap_free "" HAVE_HWLOC_BITMAP) + + set(CMAKE_REQUIRED_INCLUDES ${HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES}) +endif() diff --git a/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake index 6a0ce790c..da2f1f1d7 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindMetis.cmake @@ -1,59 +1,264 @@ -# Pastix requires METIS or METIS (partitioning and reordering tools) +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2014 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find METIS include dirs and libraries +# Use this module by invoking find_package with the form: +# find_package(METIS +# [REQUIRED] # Fail with error if metis is not found +# ) +# +# This module finds headers and metis library. +# Results are reported in variables: +# METIS_FOUND - True if headers and requested libraries were found +# METIS_INCLUDE_DIRS - metis include directories +# METIS_LIBRARY_DIRS - Link directories for metis libraries +# METIS_LIBRARIES - metis component libraries to be linked +# +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DMETIS_DIR=path/to/metis): +# METIS_DIR - Where to find the base directory of metis +# METIS_INCDIR - Where to find the header files +# METIS_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: METIS_DIR, METIS_INCDIR, METIS_LIBDIR -if (METIS_INCLUDES AND METIS_LIBRARIES) - set(METIS_FIND_QUIETLY TRUE) -endif (METIS_INCLUDES AND METIS_LIBRARIES) +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) -find_path(METIS_INCLUDES - NAMES - metis.h - PATHS - $ENV{METISDIR} - ${INCLUDE_INSTALL_DIR} - PATH_SUFFIXES - . - metis - include -) - -macro(_metis_check_version) - file(READ "${METIS_INCLUDES}/metis.h" _metis_version_header) - - string(REGEX MATCH "define[ \t]+METIS_VER_MAJOR[ \t]+([0-9]+)" _metis_major_version_match "${_metis_version_header}") - set(METIS_MAJOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+METIS_VER_MINOR[ \t]+([0-9]+)" _metis_minor_version_match "${_metis_version_header}") - set(METIS_MINOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+METIS_VER_SUBMINOR[ \t]+([0-9]+)" _metis_subminor_version_match "${_metis_version_header}") - set(METIS_SUBMINOR_VERSION "${CMAKE_MATCH_1}") - if(NOT METIS_MAJOR_VERSION) - message(STATUS "Could not determine Metis version. Assuming version 4.0.0") - set(METIS_VERSION 4.0.0) - else() - set(METIS_VERSION ${METIS_MAJOR_VERSION}.${METIS_MINOR_VERSION}.${METIS_SUBMINOR_VERSION}) +if (NOT METIS_FOUND) + set(METIS_DIR "" CACHE PATH "Installation directory of METIS library") + if (NOT METIS_FIND_QUIETLY) + message(STATUS "A cache variable, namely METIS_DIR, has been set to specify the install directory of METIS") endif() - if(${METIS_VERSION} VERSION_LESS ${Metis_FIND_VERSION}) - set(METIS_VERSION_OK FALSE) +endif() + +# Looking for include +# ------------------- + +# Add system include paths to search include +# ------------------------------------------ +unset(_inc_env) +set(ENV_METIS_DIR "$ENV{METIS_DIR}") +set(ENV_METIS_INCDIR "$ENV{METIS_INCDIR}") +if(ENV_METIS_INCDIR) + list(APPEND _inc_env "${ENV_METIS_INCDIR}") +elseif(ENV_METIS_DIR) + list(APPEND _inc_env "${ENV_METIS_DIR}") + list(APPEND _inc_env "${ENV_METIS_DIR}/include") + list(APPEND _inc_env "${ENV_METIS_DIR}/include/metis") +else() + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") else() - set(METIS_VERSION_OK TRUE) + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() +endif() +list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") +list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") +list(REMOVE_DUPLICATES _inc_env) + + +# Try to find the metis header in the given paths +# ------------------------------------------------- +# call cmake macro to find the header path +if(METIS_INCDIR) + set(METIS_metis.h_DIRS "METIS_metis.h_DIRS-NOTFOUND") + find_path(METIS_metis.h_DIRS + NAMES metis.h + HINTS ${METIS_INCDIR}) +else() + if(METIS_DIR) + set(METIS_metis.h_DIRS "METIS_metis.h_DIRS-NOTFOUND") + find_path(METIS_metis.h_DIRS + NAMES metis.h + HINTS ${METIS_DIR} + PATH_SUFFIXES "include" "include/metis") + else() + set(METIS_metis.h_DIRS "METIS_metis.h_DIRS-NOTFOUND") + find_path(METIS_metis.h_DIRS + NAMES metis.h + HINTS ${_inc_env}) + endif() +endif() +mark_as_advanced(METIS_metis.h_DIRS) + + +# If found, add path to cmake variable +# ------------------------------------ +if (METIS_metis.h_DIRS) + set(METIS_INCLUDE_DIRS "${METIS_metis.h_DIRS}") +else () + set(METIS_INCLUDE_DIRS "METIS_INCLUDE_DIRS-NOTFOUND") + if(NOT METIS_FIND_QUIETLY) + message(STATUS "Looking for metis -- metis.h not found") + endif() +endif() + + +# Looking for lib +# --------------- + +# Add system library paths to search lib +# -------------------------------------- +unset(_lib_env) +set(ENV_METIS_LIBDIR "$ENV{METIS_LIBDIR}") +if(ENV_METIS_LIBDIR) + list(APPEND _lib_env "${ENV_METIS_LIBDIR}") +elseif(ENV_METIS_DIR) + list(APPEND _lib_env "${ENV_METIS_DIR}") + list(APPEND _lib_env "${ENV_METIS_DIR}/lib") +else() + if(WIN32) + string(REPLACE ":" ";" _lib_env "$ENV{LIB}") + else() + if(APPLE) + string(REPLACE ":" ";" _lib_env "$ENV{DYLD_LIBRARY_PATH}") + else() + string(REPLACE ":" ";" _lib_env "$ENV{LD_LIBRARY_PATH}") + endif() + list(APPEND _lib_env "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _lib_env "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() +endif() +list(REMOVE_DUPLICATES _lib_env) + +# Try to find the metis lib in the given paths +# ---------------------------------------------- +# call cmake macro to find the lib path +if(METIS_LIBDIR) + set(METIS_metis_LIBRARY "METIS_metis_LIBRARY-NOTFOUND") + find_library(METIS_metis_LIBRARY + NAMES metis + HINTS ${METIS_LIBDIR}) +else() + if(METIS_DIR) + set(METIS_metis_LIBRARY "METIS_metis_LIBRARY-NOTFOUND") + find_library(METIS_metis_LIBRARY + NAMES metis + HINTS ${METIS_DIR} + PATH_SUFFIXES lib lib32 lib64) + else() + set(METIS_metis_LIBRARY "METIS_metis_LIBRARY-NOTFOUND") + find_library(METIS_metis_LIBRARY + NAMES metis + HINTS ${_lib_env}) + endif() +endif() +mark_as_advanced(METIS_metis_LIBRARY) + + +# If found, add path to cmake variable +# ------------------------------------ +if (METIS_metis_LIBRARY) + get_filename_component(metis_lib_path "${METIS_metis_LIBRARY}" PATH) + # set cmake variables + set(METIS_LIBRARIES "${METIS_metis_LIBRARY}") + set(METIS_LIBRARY_DIRS "${metis_lib_path}") +else () + set(METIS_LIBRARIES "METIS_LIBRARIES-NOTFOUND") + set(METIS_LIBRARY_DIRS "METIS_LIBRARY_DIRS-NOTFOUND") + if(NOT METIS_FIND_QUIETLY) + message(STATUS "Looking for metis -- lib metis not found") + endif() +endif () + +# check a function to validate the find +if(METIS_LIBRARIES) + + set(REQUIRED_INCDIRS) + set(REQUIRED_LIBDIRS) + set(REQUIRED_LIBS) + + # METIS + if (METIS_INCLUDE_DIRS) + set(REQUIRED_INCDIRS "${METIS_INCLUDE_DIRS}") + endif() + if (METIS_LIBRARY_DIRS) + set(REQUIRED_LIBDIRS "${METIS_LIBRARY_DIRS}") + endif() + set(REQUIRED_LIBS "${METIS_LIBRARIES}") + # m + find_library(M_LIBRARY NAMES m) + mark_as_advanced(M_LIBRARY) + if(M_LIBRARY) + list(APPEND REQUIRED_LIBS "-lm") endif() - if(NOT METIS_VERSION_OK) - message(STATUS "Metis version ${METIS_VERSION} found in ${METIS_INCLUDES}, " - "but at least version ${Metis_FIND_VERSION} is required") - endif(NOT METIS_VERSION_OK) -endmacro(_metis_check_version) + # set required libraries for link + set(CMAKE_REQUIRED_INCLUDES "${REQUIRED_INCDIRS}") + set(CMAKE_REQUIRED_LIBRARIES) + foreach(lib_dir ${REQUIRED_LIBDIRS}) + list(APPEND CMAKE_REQUIRED_LIBRARIES "-L${lib_dir}") + endforeach() + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LIBS}") + string(REGEX REPLACE "^ -" "-" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") - if(METIS_INCLUDES AND Metis_FIND_VERSION) - _metis_check_version() - else() - set(METIS_VERSION_OK TRUE) + # test link + unset(METIS_WORKS CACHE) + include(CheckFunctionExists) + check_function_exists(METIS_NodeND METIS_WORKS) + mark_as_advanced(METIS_WORKS) + + if(NOT METIS_WORKS) + if(NOT METIS_FIND_QUIETLY) + message(STATUS "Looking for METIS : test of METIS_NodeND with METIS library fails") + message(STATUS "CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}") + message(STATUS "CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}") + message(STATUS "Check in CMakeFiles/CMakeError.log to figure out why it fails") + endif() endif() + set(CMAKE_REQUIRED_INCLUDES) + set(CMAKE_REQUIRED_FLAGS) + set(CMAKE_REQUIRED_LIBRARIES) +endif(METIS_LIBRARIES) +if (METIS_LIBRARIES) + list(GET METIS_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + if (${first_lib_path} MATCHES "/lib(32|64)?$") + string(REGEX REPLACE "/lib(32|64)?$" "" not_cached_dir "${first_lib_path}") + set(METIS_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of METIS library" FORCE) + else() + set(METIS_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of METIS library" FORCE) + endif() +endif() +mark_as_advanced(METIS_DIR) +mark_as_advanced(METIS_DIR_FOUND) -find_library(METIS_LIBRARIES metis PATHS $ENV{METISDIR} ${LIB_INSTALL_DIR} PATH_SUFFIXES lib) - +# check that METIS has been found +# --------------------------------- include(FindPackageHandleStandardArgs) find_package_handle_standard_args(METIS DEFAULT_MSG - METIS_INCLUDES METIS_LIBRARIES METIS_VERSION_OK) - -mark_as_advanced(METIS_INCLUDES METIS_LIBRARIES) + METIS_LIBRARIES + METIS_WORKS) +# +# TODO: Add possibility to check for specific functions in the library +# diff --git a/gtsam/3rdparty/Eigen/cmake/FindPTSCOTCH.cmake b/gtsam/3rdparty/Eigen/cmake/FindPTSCOTCH.cmake new file mode 100644 index 000000000..1396d0582 --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/FindPTSCOTCH.cmake @@ -0,0 +1,423 @@ +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2016 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find PTSCOTCH include dirs and libraries +# Use this module by invoking find_package with the form: +# find_package(PTSCOTCH +# [REQUIRED] # Fail with error if ptscotch is not found +# [COMPONENTS ...] # dependencies +# ) +# +# PTSCOTCH depends on the following libraries: +# - Threads +# - MPI +# +# COMPONENTS can be some of the following: +# - ESMUMPS: to activate detection of PT-Scotch with the esmumps interface +# +# This module finds headers and ptscotch library. +# Results are reported in variables: +# PTSCOTCH_FOUND - True if headers and requested libraries were found +# PTSCOTCH_LINKER_FLAGS - list of required linker flags (excluding -l and -L) +# PTSCOTCH_INCLUDE_DIRS - ptscotch include directories +# PTSCOTCH_LIBRARY_DIRS - Link directories for ptscotch libraries +# PTSCOTCH_LIBRARIES - ptscotch component libraries to be linked +# PTSCOTCH_INCLUDE_DIRS_DEP - ptscotch + dependencies include directories +# PTSCOTCH_LIBRARY_DIRS_DEP - ptscotch + dependencies link directories +# PTSCOTCH_LIBRARIES_DEP - ptscotch libraries + dependencies +# PTSCOTCH_INTSIZE - Number of octets occupied by a SCOTCH_Num +# +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DPTSCOTCH=path/to/ptscotch): +# PTSCOTCH_DIR - Where to find the base directory of ptscotch +# PTSCOTCH_INCDIR - Where to find the header files +# PTSCOTCH_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: PTSCOTCH_DIR, PTSCOTCH_INCDIR, PTSCOTCH_LIBDIR + +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013-2016 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) + +if (NOT PTSCOTCH_FOUND) + set(PTSCOTCH_DIR "" CACHE PATH "Installation directory of PTSCOTCH library") + if (NOT PTSCOTCH_FIND_QUIETLY) + message(STATUS "A cache variable, namely PTSCOTCH_DIR, has been set to specify the install directory of PTSCOTCH") + endif() +endif() + +# Set the version to find +set(PTSCOTCH_LOOK_FOR_ESMUMPS OFF) + +if( PTSCOTCH_FIND_COMPONENTS ) + foreach( component ${PTSCOTCH_FIND_COMPONENTS} ) + if (${component} STREQUAL "ESMUMPS") + # means we look for esmumps library + set(PTSCOTCH_LOOK_FOR_ESMUMPS ON) + endif() + endforeach() +endif() + +# PTSCOTCH depends on Threads, try to find it +if (NOT THREADS_FOUND) + if (PTSCOTCH_FIND_REQUIRED) + find_package(Threads REQUIRED) + else() + find_package(Threads) + endif() +endif() + +# PTSCOTCH depends on MPI, try to find it +if (NOT MPI_FOUND) + if (PTSCOTCH_FIND_REQUIRED) + find_package(MPI REQUIRED) + else() + find_package(MPI) + endif() +endif() + +# Looking for include +# ------------------- + +# Add system include paths to search include +# ------------------------------------------ +unset(_inc_env) +set(ENV_PTSCOTCH_DIR "$ENV{PTSCOTCH_DIR}") +set(ENV_PTSCOTCH_INCDIR "$ENV{PTSCOTCH_INCDIR}") +if(ENV_PTSCOTCH_INCDIR) + list(APPEND _inc_env "${ENV_PTSCOTCH_INCDIR}") +elseif(ENV_PTSCOTCH_DIR) + list(APPEND _inc_env "${ENV_PTSCOTCH_DIR}") + list(APPEND _inc_env "${ENV_PTSCOTCH_DIR}/include") + list(APPEND _inc_env "${ENV_PTSCOTCH_DIR}/include/ptscotch") +else() + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() +endif() +list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") +list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") +list(REMOVE_DUPLICATES _inc_env) + + +# Try to find the ptscotch header in the given paths +# ------------------------------------------------- + +set(PTSCOTCH_hdrs_to_find "ptscotch.h;scotch.h") + +# call cmake macro to find the header path +if(PTSCOTCH_INCDIR) + foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find}) + set(PTSCOTCH_${ptscotch_hdr}_DIRS "PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND") + find_path(PTSCOTCH_${ptscotch_hdr}_DIRS + NAMES ${ptscotch_hdr} + HINTS ${PTSCOTCH_INCDIR}) + mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS) + endforeach() +else() + if(PTSCOTCH_DIR) + foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find}) + set(PTSCOTCH_${ptscotch_hdr}_DIRS "PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND") + find_path(PTSCOTCH_${ptscotch_hdr}_DIRS + NAMES ${ptscotch_hdr} + HINTS ${PTSCOTCH_DIR} + PATH_SUFFIXES "include" "include/scotch") + mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS) + endforeach() + else() + foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find}) + set(PTSCOTCH_${ptscotch_hdr}_DIRS "PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND") + find_path(PTSCOTCH_${ptscotch_hdr}_DIRS + NAMES ${ptscotch_hdr} + HINTS ${_inc_env} + PATH_SUFFIXES "scotch") + mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS) + endforeach() + endif() +endif() + +# If found, add path to cmake variable +# ------------------------------------ +foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find}) + if (PTSCOTCH_${ptscotch_hdr}_DIRS) + list(APPEND PTSCOTCH_INCLUDE_DIRS "${PTSCOTCH_${ptscotch_hdr}_DIRS}") + else () + set(PTSCOTCH_INCLUDE_DIRS "PTSCOTCH_INCLUDE_DIRS-NOTFOUND") + if (NOT PTSCOTCH_FIND_QUIETLY) + message(STATUS "Looking for ptscotch -- ${ptscotch_hdr} not found") + endif() + endif() +endforeach() +list(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS) + +# Looking for lib +# --------------- + +# Add system library paths to search lib +# -------------------------------------- +unset(_lib_env) +set(ENV_PTSCOTCH_LIBDIR "$ENV{PTSCOTCH_LIBDIR}") +if(ENV_PTSCOTCH_LIBDIR) + list(APPEND _lib_env "${ENV_PTSCOTCH_LIBDIR}") +elseif(ENV_PTSCOTCH_DIR) + list(APPEND _lib_env "${ENV_PTSCOTCH_DIR}") + list(APPEND _lib_env "${ENV_PTSCOTCH_DIR}/lib") +else() + if(WIN32) + string(REPLACE ":" ";" _lib_env "$ENV{LIB}") + else() + if(APPLE) + string(REPLACE ":" ";" _lib_env "$ENV{DYLD_LIBRARY_PATH}") + else() + string(REPLACE ":" ";" _lib_env "$ENV{LD_LIBRARY_PATH}") + endif() + list(APPEND _lib_env "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _lib_env "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() +endif() +list(REMOVE_DUPLICATES _lib_env) + +# Try to find the ptscotch lib in the given paths +# ---------------------------------------------- + +set(PTSCOTCH_libs_to_find "ptscotch;ptscotcherr") +if (PTSCOTCH_LOOK_FOR_ESMUMPS) + list(INSERT PTSCOTCH_libs_to_find 0 "ptesmumps") + list(APPEND PTSCOTCH_libs_to_find "esmumps" ) +endif() +list(APPEND PTSCOTCH_libs_to_find "scotch;scotcherr") + +# call cmake macro to find the lib path +if(PTSCOTCH_LIBDIR) + foreach(ptscotch_lib ${PTSCOTCH_libs_to_find}) + set(PTSCOTCH_${ptscotch_lib}_LIBRARY "PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND") + find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY + NAMES ${ptscotch_lib} + HINTS ${PTSCOTCH_LIBDIR}) + endforeach() +else() + if(PTSCOTCH_DIR) + foreach(ptscotch_lib ${PTSCOTCH_libs_to_find}) + set(PTSCOTCH_${ptscotch_lib}_LIBRARY "PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND") + find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY + NAMES ${ptscotch_lib} + HINTS ${PTSCOTCH_DIR} + PATH_SUFFIXES lib lib32 lib64) + endforeach() + else() + foreach(ptscotch_lib ${PTSCOTCH_libs_to_find}) + set(PTSCOTCH_${ptscotch_lib}_LIBRARY "PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND") + find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY + NAMES ${ptscotch_lib} + HINTS ${_lib_env}) + endforeach() + endif() +endif() + +set(PTSCOTCH_LIBRARIES "") +set(PTSCOTCH_LIBRARY_DIRS "") +# If found, add path to cmake variable +# ------------------------------------ +foreach(ptscotch_lib ${PTSCOTCH_libs_to_find}) + + if (PTSCOTCH_${ptscotch_lib}_LIBRARY) + get_filename_component(${ptscotch_lib}_lib_path "${PTSCOTCH_${ptscotch_lib}_LIBRARY}" PATH) + # set cmake variables + list(APPEND PTSCOTCH_LIBRARIES "${PTSCOTCH_${ptscotch_lib}_LIBRARY}") + list(APPEND PTSCOTCH_LIBRARY_DIRS "${${ptscotch_lib}_lib_path}") + else () + list(APPEND PTSCOTCH_LIBRARIES "${PTSCOTCH_${ptscotch_lib}_LIBRARY}") + if (NOT PTSCOTCH_FIND_QUIETLY) + message(STATUS "Looking for ptscotch -- lib ${ptscotch_lib} not found") + endif() + endif () + + mark_as_advanced(PTSCOTCH_${ptscotch_lib}_LIBRARY) + +endforeach() +list(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS) + +# check a function to validate the find +if(PTSCOTCH_LIBRARIES) + + set(REQUIRED_LDFLAGS) + set(REQUIRED_INCDIRS) + set(REQUIRED_LIBDIRS) + set(REQUIRED_LIBS) + + # PTSCOTCH + if (PTSCOTCH_INCLUDE_DIRS) + set(REQUIRED_INCDIRS "${PTSCOTCH_INCLUDE_DIRS}") + endif() + if (PTSCOTCH_LIBRARY_DIRS) + set(REQUIRED_LIBDIRS "${PTSCOTCH_LIBRARY_DIRS}") + endif() + set(REQUIRED_LIBS "${PTSCOTCH_LIBRARIES}") + # MPI + if (MPI_FOUND) + if (MPI_C_INCLUDE_PATH) + list(APPEND CMAKE_REQUIRED_INCLUDES "${MPI_C_INCLUDE_PATH}") + endif() + if (MPI_C_LINK_FLAGS) + if (${MPI_C_LINK_FLAGS} MATCHES " -") + string(REGEX REPLACE " -" "-" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS}) + endif() + list(APPEND REQUIRED_LDFLAGS "${MPI_C_LINK_FLAGS}") + endif() + list(APPEND REQUIRED_LIBS "${MPI_C_LIBRARIES}") + endif() + # THREADS + if(CMAKE_THREAD_LIBS_INIT) + list(APPEND REQUIRED_LIBS "${CMAKE_THREAD_LIBS_INIT}") + endif() + set(Z_LIBRARY "Z_LIBRARY-NOTFOUND") + find_library(Z_LIBRARY NAMES z) + mark_as_advanced(Z_LIBRARY) + if(Z_LIBRARY) + list(APPEND REQUIRED_LIBS "-lz") + endif() + set(M_LIBRARY "M_LIBRARY-NOTFOUND") + find_library(M_LIBRARY NAMES m) + mark_as_advanced(M_LIBRARY) + if(M_LIBRARY) + list(APPEND REQUIRED_LIBS "-lm") + endif() + set(RT_LIBRARY "RT_LIBRARY-NOTFOUND") + find_library(RT_LIBRARY NAMES rt) + mark_as_advanced(RT_LIBRARY) + if(RT_LIBRARY) + list(APPEND REQUIRED_LIBS "-lrt") + endif() + + # set required libraries for link + set(CMAKE_REQUIRED_INCLUDES "${REQUIRED_INCDIRS}") + set(CMAKE_REQUIRED_LIBRARIES) + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LDFLAGS}") + foreach(lib_dir ${REQUIRED_LIBDIRS}) + list(APPEND CMAKE_REQUIRED_LIBRARIES "-L${lib_dir}") + endforeach() + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LIBS}") + list(APPEND CMAKE_REQUIRED_FLAGS "${REQUIRED_FLAGS}") + string(REGEX REPLACE "^ -" "-" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + + # test link + unset(PTSCOTCH_WORKS CACHE) + include(CheckFunctionExists) + check_function_exists(SCOTCH_dgraphInit PTSCOTCH_WORKS) + mark_as_advanced(PTSCOTCH_WORKS) + + if(PTSCOTCH_WORKS) + # save link with dependencies + set(PTSCOTCH_LIBRARIES_DEP "${REQUIRED_LIBS}") + set(PTSCOTCH_LIBRARY_DIRS_DEP "${REQUIRED_LIBDIRS}") + set(PTSCOTCH_INCLUDE_DIRS_DEP "${REQUIRED_INCDIRS}") + set(PTSCOTCH_LINKER_FLAGS "${REQUIRED_LDFLAGS}") + list(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS_DEP) + list(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS_DEP) + list(REMOVE_DUPLICATES PTSCOTCH_LINKER_FLAGS) + else() + if(NOT PTSCOTCH_FIND_QUIETLY) + message(STATUS "Looking for PTSCOTCH : test of SCOTCH_dgraphInit with PTSCOTCH library fails") + message(STATUS "CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}") + message(STATUS "CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}") + message(STATUS "Check in CMakeFiles/CMakeError.log to figure out why it fails") + endif() + endif() + set(CMAKE_REQUIRED_INCLUDES) + set(CMAKE_REQUIRED_FLAGS) + set(CMAKE_REQUIRED_LIBRARIES) +endif(PTSCOTCH_LIBRARIES) + +if (PTSCOTCH_LIBRARIES) + list(GET PTSCOTCH_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + if (${first_lib_path} MATCHES "/lib(32|64)?$") + string(REGEX REPLACE "/lib(32|64)?$" "" not_cached_dir "${first_lib_path}") + set(PTSCOTCH_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of PTSCOTCH library" FORCE) + else() + set(PTSCOTCH_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of PTSCOTCH library" FORCE) + endif() +endif() +mark_as_advanced(PTSCOTCH_DIR) +mark_as_advanced(PTSCOTCH_DIR_FOUND) + +# Check the size of SCOTCH_Num +# --------------------------------- +set(CMAKE_REQUIRED_INCLUDES ${PTSCOTCH_INCLUDE_DIRS}) + +include(CheckCSourceRuns) +#stdio.h and stdint.h should be included by scotch.h directly +set(PTSCOTCH_C_TEST_SCOTCH_Num_4 " +#include +#include +#include +int main(int argc, char **argv) { + if (sizeof(SCOTCH_Num) == 4) + return 0; + else + return 1; +} +") + +set(PTSCOTCH_C_TEST_SCOTCH_Num_8 " +#include +#include +#include +int main(int argc, char **argv) { + if (sizeof(SCOTCH_Num) == 8) + return 0; + else + return 1; +} +") +check_c_source_runs("${PTSCOTCH_C_TEST_SCOTCH_Num_4}" PTSCOTCH_Num_4) +if(NOT PTSCOTCH_Num_4) + check_c_source_runs("${PTSCOTCH_C_TEST_SCOTCH_Num_8}" PTSCOTCH_Num_8) + if(NOT PTSCOTCH_Num_8) + set(PTSCOTCH_INTSIZE -1) + else() + set(PTSCOTCH_INTSIZE 8) + endif() +else() + set(PTSCOTCH_INTSIZE 4) +endif() +set(CMAKE_REQUIRED_INCLUDES "") + +# check that PTSCOTCH has been found +# --------------------------------- +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(PTSCOTCH DEFAULT_MSG + PTSCOTCH_LIBRARIES + PTSCOTCH_WORKS) +# +# TODO: Add possibility to check for specific functions in the library +# diff --git a/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake b/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake index e2e6c810d..470477fdc 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindPastix.cmake @@ -1,25 +1,704 @@ -# Pastix lib requires linking to a blas library. -# It is up to the user of this module to find a BLAS and link to it. -# Pastix requires SCOTCH or METIS (partitioning and reordering tools) as well +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2014 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find PASTIX include dirs and libraries +# Use this module by invoking find_package with the form: +# find_package(PASTIX +# [REQUIRED] # Fail with error if pastix is not found +# [COMPONENTS ...] # dependencies +# ) +# +# PASTIX depends on the following libraries: +# - Threads, m, rt +# - MPI +# - HWLOC +# - BLAS +# +# COMPONENTS are optional libraries PASTIX could be linked with, +# Use it to drive detection of a specific compilation chain +# COMPONENTS can be some of the following: +# - MPI: to activate detection of the parallel MPI version (default) +# it looks for Threads, HWLOC, BLAS, MPI and ScaLAPACK libraries +# - SEQ: to activate detection of the sequential version (exclude MPI version) +# - STARPU: to activate detection of StarPU version +# it looks for MPI version of StarPU (default behaviour) +# if SEQ and STARPU are given, it looks for a StarPU without MPI +# - STARPU_CUDA: to activate detection of StarPU with CUDA +# - STARPU_FXT: to activate detection of StarPU with FxT +# - SCOTCH: to activate detection of PASTIX linked with SCOTCH +# - PTSCOTCH: to activate detection of PASTIX linked with SCOTCH +# - METIS: to activate detection of PASTIX linked with SCOTCH +# +# This module finds headers and pastix library. +# Results are reported in variables: +# PASTIX_FOUND - True if headers and requested libraries were found +# PASTIX_LINKER_FLAGS - list of required linker flags (excluding -l and -L) +# PASTIX_INCLUDE_DIRS - pastix include directories +# PASTIX_LIBRARY_DIRS - Link directories for pastix libraries +# PASTIX_LIBRARIES - pastix libraries +# PASTIX_INCLUDE_DIRS_DEP - pastix + dependencies include directories +# PASTIX_LIBRARY_DIRS_DEP - pastix + dependencies link directories +# PASTIX_LIBRARIES_DEP - pastix libraries + dependencies +# +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DPASTIX_DIR=path/to/pastix): +# PASTIX_DIR - Where to find the base directory of pastix +# PASTIX_INCDIR - Where to find the header files +# PASTIX_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: PASTIX_DIR, PASTIX_INCDIR, PASTIX_LIBDIR -if (PASTIX_INCLUDES AND PASTIX_LIBRARIES) - set(PASTIX_FIND_QUIETLY TRUE) -endif (PASTIX_INCLUDES AND PASTIX_LIBRARIES) - -find_path(PASTIX_INCLUDES - NAMES - pastix_nompi.h - PATHS - $ENV{PASTIXDIR} - ${INCLUDE_INSTALL_DIR} -) - -find_library(PASTIX_LIBRARIES pastix PATHS $ENV{PASTIXDIR} ${LIB_INSTALL_DIR}) +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) +if (NOT PASTIX_FOUND) + set(PASTIX_DIR "" CACHE PATH "Installation directory of PASTIX library") + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "A cache variable, namely PASTIX_DIR, has been set to specify the install directory of PASTIX") + endif() +endif() +# Set the version to find +set(PASTIX_LOOK_FOR_MPI ON) +set(PASTIX_LOOK_FOR_SEQ OFF) +set(PASTIX_LOOK_FOR_STARPU OFF) +set(PASTIX_LOOK_FOR_STARPU_CUDA OFF) +set(PASTIX_LOOK_FOR_STARPU_FXT OFF) +set(PASTIX_LOOK_FOR_SCOTCH ON) +set(PASTIX_LOOK_FOR_PTSCOTCH OFF) +set(PASTIX_LOOK_FOR_METIS OFF) + +if( PASTIX_FIND_COMPONENTS ) + foreach( component ${PASTIX_FIND_COMPONENTS} ) + if (${component} STREQUAL "SEQ") + # means we look for the sequential version of PaStiX (without MPI) + set(PASTIX_LOOK_FOR_SEQ ON) + set(PASTIX_LOOK_FOR_MPI OFF) + endif() + if (${component} STREQUAL "MPI") + # means we look for the MPI version of PaStiX (default) + set(PASTIX_LOOK_FOR_SEQ OFF) + set(PASTIX_LOOK_FOR_MPI ON) + endif() + if (${component} STREQUAL "STARPU") + # means we look for PaStiX with StarPU + set(PASTIX_LOOK_FOR_STARPU ON) + endif() + if (${component} STREQUAL "STARPU_CUDA") + # means we look for PaStiX with StarPU + CUDA + set(PASTIX_LOOK_FOR_STARPU ON) + set(PASTIX_LOOK_FOR_STARPU_CUDA ON) + endif() + if (${component} STREQUAL "STARPU_FXT") + # means we look for PaStiX with StarPU + FxT + set(PASTIX_LOOK_FOR_STARPU_FXT ON) + endif() + if (${component} STREQUAL "SCOTCH") + set(PASTIX_LOOK_FOR_SCOTCH ON) + endif() + if (${component} STREQUAL "SCOTCH") + set(PASTIX_LOOK_FOR_PTSCOTCH ON) + endif() + if (${component} STREQUAL "METIS") + set(PASTIX_LOOK_FOR_METIS ON) + endif() + endforeach() +endif() + +# Dependencies detection +# ---------------------- + + +# Required dependencies +# --------------------- + +if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect pthread") +endif() +if (PASTIX_FIND_REQUIRED) + find_package(Threads REQUIRED QUIET) +else() + find_package(Threads QUIET) +endif() +set(PASTIX_EXTRA_LIBRARIES "") +if( THREADS_FOUND ) + list(APPEND PASTIX_EXTRA_LIBRARIES ${CMAKE_THREAD_LIBS_INIT}) +endif () + +# Add math library to the list of extra +# it normally exists on all common systems provided with a C compiler +if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect libm") +endif() +set(PASTIX_M_LIBRARIES "") +if(UNIX OR WIN32) + find_library( + PASTIX_M_m_LIBRARY + NAMES m + ) + mark_as_advanced(PASTIX_M_m_LIBRARY) + if (PASTIX_M_m_LIBRARY) + list(APPEND PASTIX_M_LIBRARIES "${PASTIX_M_m_LIBRARY}") + list(APPEND PASTIX_EXTRA_LIBRARIES "${PASTIX_M_m_LIBRARY}") + else() + if (PASTIX_FIND_REQUIRED) + message(FATAL_ERROR "Could NOT find libm on your system." + "Are you sure to a have a C compiler installed?") + endif() + endif() +endif() + +# Try to find librt (libposix4 - POSIX.1b Realtime Extensions library) +# on Unix systems except Apple ones because it does not exist on it +if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect librt") +endif() +set(PASTIX_RT_LIBRARIES "") +if(UNIX AND NOT APPLE) + find_library( + PASTIX_RT_rt_LIBRARY + NAMES rt + ) + mark_as_advanced(PASTIX_RT_rt_LIBRARY) + if (PASTIX_RT_rt_LIBRARY) + list(APPEND PASTIX_RT_LIBRARIES "${PASTIX_RT_rt_LIBRARY}") + list(APPEND PASTIX_EXTRA_LIBRARIES "${PASTIX_RT_rt_LIBRARY}") + else() + if (PASTIX_FIND_REQUIRED) + message(FATAL_ERROR "Could NOT find librt on your system") + endif() + endif() +endif() + +# PASTIX depends on HWLOC +#------------------------ +if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect HWLOC") +endif() +if (PASTIX_FIND_REQUIRED) + find_package(HWLOC REQUIRED QUIET) +else() + find_package(HWLOC QUIET) +endif() + +# PASTIX depends on BLAS +#----------------------- +if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect BLAS") +endif() +if (PASTIX_FIND_REQUIRED) + find_package(BLASEXT REQUIRED QUIET) +else() + find_package(BLASEXT QUIET) +endif() + +# Optional dependencies +# --------------------- + +# PASTIX may depend on MPI +#------------------------- +if (NOT MPI_FOUND AND PASTIX_LOOK_FOR_MPI) + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect MPI") + endif() + # allows to use an external mpi compilation by setting compilers with + # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90 + # at cmake configure + if(NOT MPI_C_COMPILER) + set(MPI_C_COMPILER mpicc) + endif() + if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_MPI) + find_package(MPI REQUIRED QUIET) + else() + find_package(MPI QUIET) + endif() + if (MPI_FOUND) + mark_as_advanced(MPI_LIBRARY) + mark_as_advanced(MPI_EXTRA_LIBRARY) + endif() +endif (NOT MPI_FOUND AND PASTIX_LOOK_FOR_MPI) + +# PASTIX may depend on STARPU +#---------------------------- +if( NOT STARPU_FOUND AND PASTIX_LOOK_FOR_STARPU) + + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect StarPU") + endif() + + set(PASTIX_STARPU_VERSION "1.1" CACHE STRING "oldest STARPU version desired") + + # create list of components in order to make a single call to find_package(starpu...) + # we explicitly need a StarPU version built with hwloc + set(STARPU_COMPONENT_LIST "HWLOC") + + # StarPU may depend on MPI + # allows to use an external mpi compilation by setting compilers with + # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90 + # at cmake configure + if (PASTIX_LOOK_FOR_MPI) + if(NOT MPI_C_COMPILER) + set(MPI_C_COMPILER mpicc) + endif() + list(APPEND STARPU_COMPONENT_LIST "MPI") + endif() + if (PASTIX_LOOK_FOR_STARPU_CUDA) + list(APPEND STARPU_COMPONENT_LIST "CUDA") + endif() + if (PASTIX_LOOK_FOR_STARPU_FXT) + list(APPEND STARPU_COMPONENT_LIST "FXT") + endif() + # set the list of optional dependencies we may discover + if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_STARPU) + find_package(STARPU ${PASTIX_STARPU_VERSION} REQUIRED + COMPONENTS ${STARPU_COMPONENT_LIST}) + else() + find_package(STARPU ${PASTIX_STARPU_VERSION} + COMPONENTS ${STARPU_COMPONENT_LIST}) + endif() + +endif( NOT STARPU_FOUND AND PASTIX_LOOK_FOR_STARPU) + +# PASTIX may depends on SCOTCH +#----------------------------- +if (NOT SCOTCH_FOUND AND PASTIX_LOOK_FOR_SCOTCH) + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect SCOTCH") + endif() + if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_SCOTCH) + find_package(SCOTCH REQUIRED QUIET) + else() + find_package(SCOTCH QUIET) + endif() +endif() + +# PASTIX may depends on PTSCOTCH +#------------------------------- +if (NOT PTSCOTCH_FOUND AND PASTIX_LOOK_FOR_PTSCOTCH) + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect PTSCOTCH") + endif() + if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_PTSCOTCH) + find_package(PTSCOTCH REQUIRED QUIET) + else() + find_package(PTSCOTCH QUIET) + endif() +endif() + +# PASTIX may depends on METIS +#---------------------------- +if (NOT METIS_FOUND AND PASTIX_LOOK_FOR_METIS) + if (NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX - Try to detect METIS") + endif() + if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_METIS) + find_package(METIS REQUIRED QUIET) + else() + find_package(METIS QUIET) + endif() +endif() + +# Error if pastix required and no partitioning lib found +if (PASTIX_FIND_REQUIRED AND NOT SCOTCH_FOUND AND NOT PTSCOTCH_FOUND AND NOT METIS_FOUND) + message(FATAL_ERROR "Could NOT find any partitioning library on your system" + " (install scotch, ptscotch or metis)") +endif() + + +# Looking for PaStiX +# ------------------ + +# Looking for include +# ------------------- + +# Add system include paths to search include +# ------------------------------------------ +unset(_inc_env) +set(ENV_PASTIX_DIR "$ENV{PASTIX_DIR}") +set(ENV_PASTIX_INCDIR "$ENV{PASTIX_INCDIR}") +if(ENV_PASTIX_INCDIR) + list(APPEND _inc_env "${ENV_PASTIX_INCDIR}") +elseif(ENV_PASTIX_DIR) + list(APPEND _inc_env "${ENV_PASTIX_DIR}") + list(APPEND _inc_env "${ENV_PASTIX_DIR}/include") + list(APPEND _inc_env "${ENV_PASTIX_DIR}/include/pastix") +else() + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() +endif() +list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") +list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") +list(REMOVE_DUPLICATES _inc_env) + + +# Try to find the pastix header in the given paths +# --------------------------------------------------- +# call cmake macro to find the header path +if(PASTIX_INCDIR) + set(PASTIX_pastix.h_DIRS "PASTIX_pastix.h_DIRS-NOTFOUND") + find_path(PASTIX_pastix.h_DIRS + NAMES pastix.h + HINTS ${PASTIX_INCDIR}) +else() + if(PASTIX_DIR) + set(PASTIX_pastix.h_DIRS "PASTIX_pastix.h_DIRS-NOTFOUND") + find_path(PASTIX_pastix.h_DIRS + NAMES pastix.h + HINTS ${PASTIX_DIR} + PATH_SUFFIXES "include" "include/pastix") + else() + set(PASTIX_pastix.h_DIRS "PASTIX_pastix.h_DIRS-NOTFOUND") + find_path(PASTIX_pastix.h_DIRS + NAMES pastix.h + HINTS ${_inc_env} + PATH_SUFFIXES "pastix") + endif() +endif() +mark_as_advanced(PASTIX_pastix.h_DIRS) + +# If found, add path to cmake variable +# ------------------------------------ +if (PASTIX_pastix.h_DIRS) + set(PASTIX_INCLUDE_DIRS "${PASTIX_pastix.h_DIRS}") +else () + set(PASTIX_INCLUDE_DIRS "PASTIX_INCLUDE_DIRS-NOTFOUND") + if(NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for pastix -- pastix.h not found") + endif() +endif() + + +# Looking for lib +# --------------- + +# Add system library paths to search lib +# -------------------------------------- +unset(_lib_env) +set(ENV_PASTIX_LIBDIR "$ENV{PASTIX_LIBDIR}") +if(ENV_PASTIX_LIBDIR) + list(APPEND _lib_env "${ENV_PASTIX_LIBDIR}") +elseif(ENV_PASTIX_DIR) + list(APPEND _lib_env "${ENV_PASTIX_DIR}") + list(APPEND _lib_env "${ENV_PASTIX_DIR}/lib") +else() + if(WIN32) + string(REPLACE ":" ";" _lib_env "$ENV{LIB}") + else() + if(APPLE) + string(REPLACE ":" ";" _lib_env "$ENV{DYLD_LIBRARY_PATH}") + else() + string(REPLACE ":" ";" _lib_env "$ENV{LD_LIBRARY_PATH}") + endif() + list(APPEND _lib_env "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _lib_env "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() +endif() +list(REMOVE_DUPLICATES _lib_env) + +# Try to find the pastix lib in the given paths +# ------------------------------------------------ + +# create list of libs to find +set(PASTIX_libs_to_find "pastix_murge;pastix") + +# call cmake macro to find the lib path +if(PASTIX_LIBDIR) + foreach(pastix_lib ${PASTIX_libs_to_find}) + set(PASTIX_${pastix_lib}_LIBRARY "PASTIX_${pastix_lib}_LIBRARY-NOTFOUND") + find_library(PASTIX_${pastix_lib}_LIBRARY + NAMES ${pastix_lib} + HINTS ${PASTIX_LIBDIR}) + endforeach() +else() + if(PASTIX_DIR) + foreach(pastix_lib ${PASTIX_libs_to_find}) + set(PASTIX_${pastix_lib}_LIBRARY "PASTIX_${pastix_lib}_LIBRARY-NOTFOUND") + find_library(PASTIX_${pastix_lib}_LIBRARY + NAMES ${pastix_lib} + HINTS ${PASTIX_DIR} + PATH_SUFFIXES lib lib32 lib64) + endforeach() + else() + foreach(pastix_lib ${PASTIX_libs_to_find}) + set(PASTIX_${pastix_lib}_LIBRARY "PASTIX_${pastix_lib}_LIBRARY-NOTFOUND") + find_library(PASTIX_${pastix_lib}_LIBRARY + NAMES ${pastix_lib} + HINTS ${_lib_env}) + endforeach() + endif() +endif() + +# If found, add path to cmake variable +# ------------------------------------ +foreach(pastix_lib ${PASTIX_libs_to_find}) + + get_filename_component(${pastix_lib}_lib_path ${PASTIX_${pastix_lib}_LIBRARY} PATH) + # set cmake variables (respects naming convention) + if (PASTIX_LIBRARIES) + list(APPEND PASTIX_LIBRARIES "${PASTIX_${pastix_lib}_LIBRARY}") + else() + set(PASTIX_LIBRARIES "${PASTIX_${pastix_lib}_LIBRARY}") + endif() + if (PASTIX_LIBRARY_DIRS) + list(APPEND PASTIX_LIBRARY_DIRS "${${pastix_lib}_lib_path}") + else() + set(PASTIX_LIBRARY_DIRS "${${pastix_lib}_lib_path}") + endif() + mark_as_advanced(PASTIX_${pastix_lib}_LIBRARY) + +endforeach(pastix_lib ${PASTIX_libs_to_find}) + +# check a function to validate the find +if(PASTIX_LIBRARIES) + + set(REQUIRED_LDFLAGS) + set(REQUIRED_INCDIRS) + set(REQUIRED_LIBDIRS) + set(REQUIRED_LIBS) + + # PASTIX + if (PASTIX_INCLUDE_DIRS) + set(REQUIRED_INCDIRS "${PASTIX_INCLUDE_DIRS}") + endif() + foreach(libdir ${PASTIX_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + set(REQUIRED_LIBS "${PASTIX_LIBRARIES}") + # STARPU + if (PASTIX_LOOK_FOR_STARPU AND STARPU_FOUND) + if (STARPU_INCLUDE_DIRS_DEP) + list(APPEND REQUIRED_INCDIRS "${STARPU_INCLUDE_DIRS_DEP}") + elseif (STARPU_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${STARPU_INCLUDE_DIRS}") + endif() + if(STARPU_LIBRARY_DIRS_DEP) + list(APPEND REQUIRED_LIBDIRS "${STARPU_LIBRARY_DIRS_DEP}") + elseif(STARPU_LIBRARY_DIRS) + list(APPEND REQUIRED_LIBDIRS "${STARPU_LIBRARY_DIRS}") + endif() + if (STARPU_LIBRARIES_DEP) + list(APPEND REQUIRED_LIBS "${STARPU_LIBRARIES_DEP}") + elseif (STARPU_LIBRARIES) + foreach(lib ${STARPU_LIBRARIES}) + if (EXISTS ${lib} OR ${lib} MATCHES "^-") + list(APPEND REQUIRED_LIBS "${lib}") + else() + list(APPEND REQUIRED_LIBS "-l${lib}") + endif() + endforeach() + endif() + endif() + # CUDA + if (PASTIX_LOOK_FOR_STARPU_CUDA AND CUDA_FOUND) + if (CUDA_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${CUDA_INCLUDE_DIRS}") + endif() + foreach(libdir ${CUDA_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + list(APPEND REQUIRED_LIBS "${CUDA_CUBLAS_LIBRARIES};${CUDA_LIBRARIES}") + endif() + # MPI + if (PASTIX_LOOK_FOR_MPI AND MPI_FOUND) + if (MPI_C_INCLUDE_PATH) + list(APPEND REQUIRED_INCDIRS "${MPI_C_INCLUDE_PATH}") + endif() + if (MPI_C_LINK_FLAGS) + if (${MPI_C_LINK_FLAGS} MATCHES " -") + string(REGEX REPLACE " -" "-" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS}) + endif() + list(APPEND REQUIRED_LDFLAGS "${MPI_C_LINK_FLAGS}") + endif() + list(APPEND REQUIRED_LIBS "${MPI_C_LIBRARIES}") + endif() + # HWLOC + if (HWLOC_FOUND) + if (HWLOC_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${HWLOC_INCLUDE_DIRS}") + endif() + foreach(libdir ${HWLOC_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + foreach(lib ${HWLOC_LIBRARIES}) + if (EXISTS ${lib} OR ${lib} MATCHES "^-") + list(APPEND REQUIRED_LIBS "${lib}") + else() + list(APPEND REQUIRED_LIBS "-l${lib}") + endif() + endforeach() + endif() + # BLAS + if (BLAS_FOUND) + if (BLAS_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${BLAS_INCLUDE_DIRS}") + endif() + foreach(libdir ${BLAS_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + list(APPEND REQUIRED_LIBS "${BLAS_LIBRARIES}") + if (BLAS_LINKER_FLAGS) + list(APPEND REQUIRED_LDFLAGS "${BLAS_LINKER_FLAGS}") + endif() + endif() + # SCOTCH + if (PASTIX_LOOK_FOR_SCOTCH AND SCOTCH_FOUND) + if (SCOTCH_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${SCOTCH_INCLUDE_DIRS}") + endif() + foreach(libdir ${SCOTCH_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + list(APPEND REQUIRED_LIBS "${SCOTCH_LIBRARIES}") + endif() + # PTSCOTCH + if (PASTIX_LOOK_FOR_PTSCOTCH AND PTSCOTCH_FOUND) + if (PTSCOTCH_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${PTSCOTCH_INCLUDE_DIRS}") + endif() + foreach(libdir ${PTSCOTCH_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + list(APPEND REQUIRED_LIBS "${PTSCOTCH_LIBRARIES}") + endif() + # METIS + if (PASTIX_LOOK_FOR_METIS AND METIS_FOUND) + if (METIS_INCLUDE_DIRS) + list(APPEND REQUIRED_INCDIRS "${METIS_INCLUDE_DIRS}") + endif() + foreach(libdir ${METIS_LIBRARY_DIRS}) + if (libdir) + list(APPEND REQUIRED_LIBDIRS "${libdir}") + endif() + endforeach() + list(APPEND REQUIRED_LIBS "${METIS_LIBRARIES}") + endif() + # Fortran + if (CMAKE_C_COMPILER_ID MATCHES "GNU") + find_library( + FORTRAN_gfortran_LIBRARY + NAMES gfortran + HINTS ${_lib_env} + ) + mark_as_advanced(FORTRAN_gfortran_LIBRARY) + if (FORTRAN_gfortran_LIBRARY) + list(APPEND REQUIRED_LIBS "${FORTRAN_gfortran_LIBRARY}") + endif() + elseif (CMAKE_C_COMPILER_ID MATCHES "Intel") + find_library( + FORTRAN_ifcore_LIBRARY + NAMES ifcore + HINTS ${_lib_env} + ) + mark_as_advanced(FORTRAN_ifcore_LIBRARY) + if (FORTRAN_ifcore_LIBRARY) + list(APPEND REQUIRED_LIBS "${FORTRAN_ifcore_LIBRARY}") + endif() + endif() + # EXTRA LIBS such that pthread, m, rt + list(APPEND REQUIRED_LIBS ${PASTIX_EXTRA_LIBRARIES}) + + # set required libraries for link + set(CMAKE_REQUIRED_INCLUDES "${REQUIRED_INCDIRS}") + set(CMAKE_REQUIRED_LIBRARIES) + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LDFLAGS}") + foreach(lib_dir ${REQUIRED_LIBDIRS}) + list(APPEND CMAKE_REQUIRED_LIBRARIES "-L${lib_dir}") + endforeach() + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LIBS}") + list(APPEND CMAKE_REQUIRED_FLAGS "${REQUIRED_FLAGS}") + string(REGEX REPLACE "^ -" "-" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + + # test link + unset(PASTIX_WORKS CACHE) + include(CheckFunctionExists) + check_function_exists(pastix PASTIX_WORKS) + mark_as_advanced(PASTIX_WORKS) + + if(PASTIX_WORKS) + # save link with dependencies + set(PASTIX_LIBRARIES_DEP "${REQUIRED_LIBS}") + set(PASTIX_LIBRARY_DIRS_DEP "${REQUIRED_LIBDIRS}") + set(PASTIX_INCLUDE_DIRS_DEP "${REQUIRED_INCDIRS}") + set(PASTIX_LINKER_FLAGS "${REQUIRED_LDFLAGS}") + list(REMOVE_DUPLICATES PASTIX_LIBRARY_DIRS_DEP) + list(REMOVE_DUPLICATES PASTIX_INCLUDE_DIRS_DEP) + list(REMOVE_DUPLICATES PASTIX_LINKER_FLAGS) + else() + if(NOT PASTIX_FIND_QUIETLY) + message(STATUS "Looking for PASTIX : test of pastix() fails") + message(STATUS "CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}") + message(STATUS "CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}") + message(STATUS "Check in CMakeFiles/CMakeError.log to figure out why it fails") + message(STATUS "Maybe PASTIX is linked with specific libraries. " + "Have you tried with COMPONENTS (MPI/SEQ, STARPU, STARPU_CUDA, SCOTCH, PTSCOTCH, METIS)? " + "See the explanation in FindPASTIX.cmake.") + endif() + endif() + set(CMAKE_REQUIRED_INCLUDES) + set(CMAKE_REQUIRED_FLAGS) + set(CMAKE_REQUIRED_LIBRARIES) +endif(PASTIX_LIBRARIES) + +if (PASTIX_LIBRARIES) + list(GET PASTIX_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + if (${first_lib_path} MATCHES "/lib(32|64)?$") + string(REGEX REPLACE "/lib(32|64)?$" "" not_cached_dir "${first_lib_path}") + set(PASTIX_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of PASTIX library" FORCE) + else() + set(PASTIX_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of PASTIX library" FORCE) + endif() +endif() +mark_as_advanced(PASTIX_DIR) +mark_as_advanced(PASTIX_DIR_FOUND) + +# check that PASTIX has been found +# --------------------------------- include(FindPackageHandleStandardArgs) find_package_handle_standard_args(PASTIX DEFAULT_MSG - PASTIX_INCLUDES PASTIX_LIBRARIES) - -mark_as_advanced(PASTIX_INCLUDES PASTIX_LIBRARIES) + PASTIX_LIBRARIES + PASTIX_WORKS) diff --git a/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake b/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake index 530340b16..89d295ac2 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindScotch.cmake @@ -1,24 +1,369 @@ -# Pastix requires SCOTCH or METIS (partitioning and reordering tools) +### +# +# @copyright (c) 2009-2014 The University of Tennessee and The University +# of Tennessee Research Foundation. +# All rights reserved. +# @copyright (c) 2012-2014 Inria. All rights reserved. +# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved. +# +### +# +# - Find SCOTCH include dirs and libraries +# Use this module by invoking find_package with the form: +# find_package(SCOTCH +# [REQUIRED] # Fail with error if scotch is not found +# [COMPONENTS ...] # dependencies +# ) +# +# COMPONENTS can be some of the following: +# - ESMUMPS: to activate detection of Scotch with the esmumps interface +# +# This module finds headers and scotch library. +# Results are reported in variables: +# SCOTCH_FOUND - True if headers and requested libraries were found +# SCOTCH_INCLUDE_DIRS - scotch include directories +# SCOTCH_LIBRARY_DIRS - Link directories for scotch libraries +# SCOTCH_LIBRARIES - scotch component libraries to be linked +# SCOTCH_INTSIZE - Number of octets occupied by a SCOTCH_Num +# +# The user can give specific paths where to find the libraries adding cmake +# options at configure (ex: cmake path/to/project -DSCOTCH=path/to/scotch): +# SCOTCH_DIR - Where to find the base directory of scotch +# SCOTCH_INCDIR - Where to find the header files +# SCOTCH_LIBDIR - Where to find the library files +# The module can also look for the following environment variables if paths +# are not given as cmake variable: SCOTCH_DIR, SCOTCH_INCDIR, SCOTCH_LIBDIR -if (SCOTCH_INCLUDES AND SCOTCH_LIBRARIES) - set(SCOTCH_FIND_QUIETLY TRUE) -endif (SCOTCH_INCLUDES AND SCOTCH_LIBRARIES) +#============================================================================= +# Copyright 2012-2013 Inria +# Copyright 2012-2013 Emmanuel Agullo +# Copyright 2012-2013 Mathieu Faverge +# Copyright 2012 Cedric Castagnede +# Copyright 2013 Florent Pruvost +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file MORSE-Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of Morse, substitute the full +# License text for the above reference.) -find_path(SCOTCH_INCLUDES - NAMES - scotch.h - PATHS - $ENV{SCOTCHDIR} - ${INCLUDE_INSTALL_DIR} - PATH_SUFFIXES - scotch -) +if (NOT SCOTCH_FOUND) + set(SCOTCH_DIR "" CACHE PATH "Installation directory of SCOTCH library") + if (NOT SCOTCH_FIND_QUIETLY) + message(STATUS "A cache variable, namely SCOTCH_DIR, has been set to specify the install directory of SCOTCH") + endif() +endif() + +# Set the version to find +set(SCOTCH_LOOK_FOR_ESMUMPS OFF) + +if( SCOTCH_FIND_COMPONENTS ) + foreach( component ${SCOTCH_FIND_COMPONENTS} ) + if (${component} STREQUAL "ESMUMPS") + # means we look for esmumps library + set(SCOTCH_LOOK_FOR_ESMUMPS ON) + endif() + endforeach() +endif() + +# SCOTCH may depend on Threads, try to find it +if (NOT THREADS_FOUND) + if (SCOTCH_FIND_REQUIRED) + find_package(Threads REQUIRED) + else() + find_package(Threads) + endif() +endif() + +# Looking for include +# ------------------- + +# Add system include paths to search include +# ------------------------------------------ +unset(_inc_env) +set(ENV_SCOTCH_DIR "$ENV{SCOTCH_DIR}") +set(ENV_SCOTCH_INCDIR "$ENV{SCOTCH_INCDIR}") +if(ENV_SCOTCH_INCDIR) + list(APPEND _inc_env "${ENV_SCOTCH_INCDIR}") +elseif(ENV_SCOTCH_DIR) + list(APPEND _inc_env "${ENV_SCOTCH_DIR}") + list(APPEND _inc_env "${ENV_SCOTCH_DIR}/include") + list(APPEND _inc_env "${ENV_SCOTCH_DIR}/include/scotch") +else() + if(WIN32) + string(REPLACE ":" ";" _inc_env "$ENV{INCLUDE}") + else() + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{C_INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{CPATH}") + list(APPEND _inc_env "${_path_env}") + string(REPLACE ":" ";" _path_env "$ENV{INCLUDE_PATH}") + list(APPEND _inc_env "${_path_env}") + endif() +endif() +list(APPEND _inc_env "${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}") +list(APPEND _inc_env "${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}") +list(REMOVE_DUPLICATES _inc_env) -find_library(SCOTCH_LIBRARIES scotch PATHS $ENV{SCOTCHDIR} ${LIB_INSTALL_DIR}) +# Try to find the scotch header in the given paths +# ------------------------------------------------- +# call cmake macro to find the header path +if(SCOTCH_INCDIR) + set(SCOTCH_scotch.h_DIRS "SCOTCH_scotch.h_DIRS-NOTFOUND") + find_path(SCOTCH_scotch.h_DIRS + NAMES scotch.h + HINTS ${SCOTCH_INCDIR}) +else() + if(SCOTCH_DIR) + set(SCOTCH_scotch.h_DIRS "SCOTCH_scotch.h_DIRS-NOTFOUND") + find_path(SCOTCH_scotch.h_DIRS + NAMES scotch.h + HINTS ${SCOTCH_DIR} + PATH_SUFFIXES "include" "include/scotch") + else() + set(SCOTCH_scotch.h_DIRS "SCOTCH_scotch.h_DIRS-NOTFOUND") + find_path(SCOTCH_scotch.h_DIRS + NAMES scotch.h + HINTS ${_inc_env} + PATH_SUFFIXES "scotch") + endif() +endif() +mark_as_advanced(SCOTCH_scotch.h_DIRS) +# If found, add path to cmake variable +# ------------------------------------ +if (SCOTCH_scotch.h_DIRS) + set(SCOTCH_INCLUDE_DIRS "${SCOTCH_scotch.h_DIRS}") +else () + set(SCOTCH_INCLUDE_DIRS "SCOTCH_INCLUDE_DIRS-NOTFOUND") + if (NOT SCOTCH_FIND_QUIETLY) + message(STATUS "Looking for scotch -- scotch.h not found") + endif() +endif() +list(REMOVE_DUPLICATES SCOTCH_INCLUDE_DIRS) + +# Looking for lib +# --------------- + +# Add system library paths to search lib +# -------------------------------------- +unset(_lib_env) +set(ENV_SCOTCH_LIBDIR "$ENV{SCOTCH_LIBDIR}") +if(ENV_SCOTCH_LIBDIR) + list(APPEND _lib_env "${ENV_SCOTCH_LIBDIR}") +elseif(ENV_SCOTCH_DIR) + list(APPEND _lib_env "${ENV_SCOTCH_DIR}") + list(APPEND _lib_env "${ENV_SCOTCH_DIR}/lib") +else() + if(WIN32) + string(REPLACE ":" ";" _lib_env "$ENV{LIB}") + else() + if(APPLE) + string(REPLACE ":" ";" _lib_env "$ENV{DYLD_LIBRARY_PATH}") + else() + string(REPLACE ":" ";" _lib_env "$ENV{LD_LIBRARY_PATH}") + endif() + list(APPEND _lib_env "${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}") + list(APPEND _lib_env "${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}") + endif() +endif() +list(REMOVE_DUPLICATES _lib_env) + +# Try to find the scotch lib in the given paths +# ---------------------------------------------- + +set(SCOTCH_libs_to_find "scotch;scotcherrexit") +if (SCOTCH_LOOK_FOR_ESMUMPS) + list(INSERT SCOTCH_libs_to_find 0 "esmumps") +endif() + +# call cmake macro to find the lib path +if(SCOTCH_LIBDIR) + foreach(scotch_lib ${SCOTCH_libs_to_find}) + set(SCOTCH_${scotch_lib}_LIBRARY "SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND") + find_library(SCOTCH_${scotch_lib}_LIBRARY + NAMES ${scotch_lib} + HINTS ${SCOTCH_LIBDIR}) + endforeach() +else() + if(SCOTCH_DIR) + foreach(scotch_lib ${SCOTCH_libs_to_find}) + set(SCOTCH_${scotch_lib}_LIBRARY "SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND") + find_library(SCOTCH_${scotch_lib}_LIBRARY + NAMES ${scotch_lib} + HINTS ${SCOTCH_DIR} + PATH_SUFFIXES lib lib32 lib64) + endforeach() + else() + foreach(scotch_lib ${SCOTCH_libs_to_find}) + set(SCOTCH_${scotch_lib}_LIBRARY "SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND") + find_library(SCOTCH_${scotch_lib}_LIBRARY + NAMES ${scotch_lib} + HINTS ${_lib_env}) + endforeach() + endif() +endif() + +set(SCOTCH_LIBRARIES "") +set(SCOTCH_LIBRARY_DIRS "") +# If found, add path to cmake variable +# ------------------------------------ +foreach(scotch_lib ${SCOTCH_libs_to_find}) + + if (SCOTCH_${scotch_lib}_LIBRARY) + get_filename_component(${scotch_lib}_lib_path "${SCOTCH_${scotch_lib}_LIBRARY}" PATH) + # set cmake variables + list(APPEND SCOTCH_LIBRARIES "${SCOTCH_${scotch_lib}_LIBRARY}") + list(APPEND SCOTCH_LIBRARY_DIRS "${${scotch_lib}_lib_path}") + else () + list(APPEND SCOTCH_LIBRARIES "${SCOTCH_${scotch_lib}_LIBRARY}") + if (NOT SCOTCH_FIND_QUIETLY) + message(STATUS "Looking for scotch -- lib ${scotch_lib} not found") + endif() + endif () + + mark_as_advanced(SCOTCH_${scotch_lib}_LIBRARY) + +endforeach() +list(REMOVE_DUPLICATES SCOTCH_LIBRARY_DIRS) + +# check a function to validate the find +if(SCOTCH_LIBRARIES) + + set(REQUIRED_INCDIRS) + set(REQUIRED_LIBDIRS) + set(REQUIRED_LIBS) + + # SCOTCH + if (SCOTCH_INCLUDE_DIRS) + set(REQUIRED_INCDIRS "${SCOTCH_INCLUDE_DIRS}") + endif() + if (SCOTCH_LIBRARY_DIRS) + set(REQUIRED_LIBDIRS "${SCOTCH_LIBRARY_DIRS}") + endif() + set(REQUIRED_LIBS "${SCOTCH_LIBRARIES}") + # THREADS + if(CMAKE_THREAD_LIBS_INIT) + list(APPEND REQUIRED_LIBS "${CMAKE_THREAD_LIBS_INIT}") + endif() + set(Z_LIBRARY "Z_LIBRARY-NOTFOUND") + find_library(Z_LIBRARY NAMES z) + mark_as_advanced(Z_LIBRARY) + if(Z_LIBRARY) + list(APPEND REQUIRED_LIBS "-lz") + endif() + set(M_LIBRARY "M_LIBRARY-NOTFOUND") + find_library(M_LIBRARY NAMES m) + mark_as_advanced(M_LIBRARY) + if(M_LIBRARY) + list(APPEND REQUIRED_LIBS "-lm") + endif() + set(RT_LIBRARY "RT_LIBRARY-NOTFOUND") + find_library(RT_LIBRARY NAMES rt) + mark_as_advanced(RT_LIBRARY) + if(RT_LIBRARY) + list(APPEND REQUIRED_LIBS "-lrt") + endif() + + # set required libraries for link + set(CMAKE_REQUIRED_INCLUDES "${REQUIRED_INCDIRS}") + set(CMAKE_REQUIRED_LIBRARIES) + foreach(lib_dir ${REQUIRED_LIBDIRS}) + list(APPEND CMAKE_REQUIRED_LIBRARIES "-L${lib_dir}") + endforeach() + list(APPEND CMAKE_REQUIRED_LIBRARIES "${REQUIRED_LIBS}") + string(REGEX REPLACE "^ -" "-" CMAKE_REQUIRED_LIBRARIES "${CMAKE_REQUIRED_LIBRARIES}") + + # test link + unset(SCOTCH_WORKS CACHE) + include(CheckFunctionExists) + check_function_exists(SCOTCH_graphInit SCOTCH_WORKS) + mark_as_advanced(SCOTCH_WORKS) + + if(SCOTCH_WORKS) + # save link with dependencies + set(SCOTCH_LIBRARIES "${REQUIRED_LIBS}") + else() + if(NOT SCOTCH_FIND_QUIETLY) + message(STATUS "Looking for SCOTCH : test of SCOTCH_graphInit with SCOTCH library fails") + message(STATUS "CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}") + message(STATUS "CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}") + message(STATUS "Check in CMakeFiles/CMakeError.log to figure out why it fails") + endif() + endif() + set(CMAKE_REQUIRED_INCLUDES) + set(CMAKE_REQUIRED_FLAGS) + set(CMAKE_REQUIRED_LIBRARIES) +endif(SCOTCH_LIBRARIES) + +if (SCOTCH_LIBRARIES) + list(GET SCOTCH_LIBRARIES 0 first_lib) + get_filename_component(first_lib_path "${first_lib}" PATH) + if (${first_lib_path} MATCHES "/lib(32|64)?$") + string(REGEX REPLACE "/lib(32|64)?$" "" not_cached_dir "${first_lib_path}") + set(SCOTCH_DIR_FOUND "${not_cached_dir}" CACHE PATH "Installation directory of SCOTCH library" FORCE) + else() + set(SCOTCH_DIR_FOUND "${first_lib_path}" CACHE PATH "Installation directory of SCOTCH library" FORCE) + endif() +endif() +mark_as_advanced(SCOTCH_DIR) +mark_as_advanced(SCOTCH_DIR_FOUND) + +# Check the size of SCOTCH_Num +# --------------------------------- +set(CMAKE_REQUIRED_INCLUDES ${SCOTCH_INCLUDE_DIRS}) + +include(CheckCSourceRuns) +#stdio.h and stdint.h should be included by scotch.h directly +set(SCOTCH_C_TEST_SCOTCH_Num_4 " +#include +#include +#include +int main(int argc, char **argv) { + if (sizeof(SCOTCH_Num) == 4) + return 0; + else + return 1; +} +") + +set(SCOTCH_C_TEST_SCOTCH_Num_8 " +#include +#include +#include +int main(int argc, char **argv) { + if (sizeof(SCOTCH_Num) == 8) + return 0; + else + return 1; +} +") +check_c_source_runs("${SCOTCH_C_TEST_SCOTCH_Num_4}" SCOTCH_Num_4) +if(NOT SCOTCH_Num_4) + check_c_source_runs("${SCOTCH_C_TEST_SCOTCH_Num_8}" SCOTCH_Num_8) + if(NOT SCOTCH_Num_8) + set(SCOTCH_INTSIZE -1) + else() + set(SCOTCH_INTSIZE 8) + endif() +else() + set(SCOTCH_INTSIZE 4) +endif() +set(CMAKE_REQUIRED_INCLUDES "") + +# check that SCOTCH has been found +# --------------------------------- include(FindPackageHandleStandardArgs) find_package_handle_standard_args(SCOTCH DEFAULT_MSG - SCOTCH_INCLUDES SCOTCH_LIBRARIES) - -mark_as_advanced(SCOTCH_INCLUDES SCOTCH_LIBRARIES) + SCOTCH_LIBRARIES + SCOTCH_WORKS) +# +# TODO: Add possibility to check for specific functions in the library +# diff --git a/gtsam/3rdparty/Eigen/cmake/FindSuperLU.cmake b/gtsam/3rdparty/Eigen/cmake/FindSuperLU.cmake index 8a3df3666..f38146e06 100644 --- a/gtsam/3rdparty/Eigen/cmake/FindSuperLU.cmake +++ b/gtsam/3rdparty/Eigen/cmake/FindSuperLU.cmake @@ -17,10 +17,81 @@ find_path(SUPERLU_INCLUDES SRC ) -find_library(SUPERLU_LIBRARIES superlu PATHS $ENV{SUPERLUDIR} ${LIB_INSTALL_DIR} PATH_SUFFIXES lib) - +find_library(SUPERLU_LIBRARIES + NAMES "superlu_5.2.1" "superlu_5.2" "superlu_5.1.1" "superlu_5.1" "superlu_5.0" "superlu_4.3" "superlu_4.2" "superlu_4.1" "superlu_4.0" "superlu_3.1" "superlu_3.0" "superlu" + PATHS $ENV{SUPERLUDIR} ${LIB_INSTALL_DIR} + PATH_SUFFIXES lib) + +if(SUPERLU_INCLUDES AND SUPERLU_LIBRARIES) + +include(CheckCXXSourceCompiles) +include(CMakePushCheckState) +cmake_push_check_state() + +set(CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES} ${SUPERLU_INCLUDES}) + +# check whether struct mem_usage_t is globally defined +check_cxx_source_compiles(" +typedef int int_t; +#include +#include +int main() { + mem_usage_t mem; + return 0; +}" +SUPERLU_HAS_GLOBAL_MEM_USAGE_T) + + +check_cxx_source_compiles(" +typedef int int_t; +#include +#include +int main() { + return SLU_SINGLE; +}" +SUPERLU_HAS_CLEAN_ENUMS) + +check_cxx_source_compiles(" +typedef int int_t; +#include +#include +int main(void) +{ + GlobalLU_t glu; + return 0; +}" +SUPERLU_HAS_GLOBALLU_T) + +if(SUPERLU_HAS_GLOBALLU_T) + # at least 5.0 + set(SUPERLU_VERSION_VAR "5.0") +elseif(SUPERLU_HAS_CLEAN_ENUMS) + # at least 4.3 + set(SUPERLU_VERSION_VAR "4.3") +elseif(SUPERLU_HAS_GLOBAL_MEM_USAGE_T) + # at least 4.0 + set(SUPERLU_VERSION_VAR "4.0") +else() + set(SUPERLU_VERSION_VAR "3.0") +endif() + +cmake_pop_check_state() + +if(SuperLU_FIND_VERSION) + if(${SUPERLU_VERSION_VAR} VERSION_LESS ${SuperLU_FIND_VERSION}) + set(SUPERLU_VERSION_OK FALSE) + else() + set(SUPERLU_VERSION_OK TRUE) + endif() +else() + set(SUPERLU_VERSION_OK TRUE) +endif() + +endif() + include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(SUPERLU DEFAULT_MSG - SUPERLU_INCLUDES SUPERLU_LIBRARIES) +find_package_handle_standard_args(SUPERLU + REQUIRED_VARS SUPERLU_INCLUDES SUPERLU_LIBRARIES SUPERLU_VERSION_OK + VERSION_VAR SUPERLU_VERSION_VAR) mark_as_advanced(SUPERLU_INCLUDES SUPERLU_LIBRARIES) diff --git a/gtsam/3rdparty/Eigen/cmake/UseEigen3.cmake b/gtsam/3rdparty/Eigen/cmake/UseEigen3.cmake new file mode 100644 index 000000000..a38bac82d --- /dev/null +++ b/gtsam/3rdparty/Eigen/cmake/UseEigen3.cmake @@ -0,0 +1,6 @@ +# -*- cmake -*- +# +# UseEigen3.cmake + +add_definitions ( ${EIGEN3_DEFINITIONS} ) +include_directories ( ${EIGEN3_INCLUDE_DIRS} ) diff --git a/gtsam/3rdparty/Eigen/cmake/language_support.cmake b/gtsam/3rdparty/Eigen/cmake/language_support.cmake index 231f7ff70..2f14f30b8 100644 --- a/gtsam/3rdparty/Eigen/cmake/language_support.cmake +++ b/gtsam/3rdparty/Eigen/cmake/language_support.cmake @@ -43,7 +43,7 @@ function(workaround_9220 language language_works) if(return_code EQUAL 0) # Second run execute_process ( - COMMAND ${CMAKE_COMMAND} . + COMMAND ${CMAKE_COMMAND} . -G "${CMAKE_GENERATOR}" WORKING_DIRECTORY ${CMAKE_BINARY_DIR}/language_tests/${language} RESULT_VARIABLE return_code OUTPUT_QUIET @@ -64,3 +64,4 @@ endfunction(workaround_9220) #message("CXX_language_works = ${CXX_language_works}") #workaround_9220(CXXp CXXp_language_works) #message("CXXp_language_works = ${CXXp_language_works}") + diff --git a/gtsam/3rdparty/Eigen/debug/gdb/printers.py b/gtsam/3rdparty/Eigen/debug/gdb/printers.py index 86996a4f9..0d67a5f99 100644 --- a/gtsam/3rdparty/Eigen/debug/gdb/printers.py +++ b/gtsam/3rdparty/Eigen/debug/gdb/printers.py @@ -49,7 +49,7 @@ class EigenMatrixPrinter: regex = re.compile('\<.*\>') m = regex.findall(tag)[0][1:-1] template_params = m.split(',') - template_params = map(lambda x:x.replace(" ", ""), template_params) + template_params = [x.replace(" ", "") for x in template_params] if template_params[1] == '-0x00000000000000001' or template_params[1] == '-0x000000001' or template_params[1] == '-1': self.rows = val['m_storage']['m_rows'] @@ -88,8 +88,11 @@ class EigenMatrixPrinter: def __iter__ (self): return self - + def next(self): + return self.__next__() # Python 2.x compatibility + + def __next__(self): row = self.currentRow col = self.currentCol @@ -151,8 +154,11 @@ class EigenQuaternionPrinter: def __iter__ (self): return self - + def next(self): + return self.__next__() # Python 2.x compatibility + + def __next__(self): element = self.currentElement if self.currentElement >= 4: #there are 4 elements in a quanternion diff --git a/gtsam/3rdparty/Eigen/demos/opengl/quaternion_demo.cpp b/gtsam/3rdparty/Eigen/demos/opengl/quaternion_demo.cpp index 04165619b..dd323a4c9 100644 --- a/gtsam/3rdparty/Eigen/demos/opengl/quaternion_demo.cpp +++ b/gtsam/3rdparty/Eigen/demos/opengl/quaternion_demo.cpp @@ -234,7 +234,7 @@ void RenderingWidget::drawScene() gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitZ(), Color(0,0,1,1)); // draw the fractal object - float sqrt3 = internal::sqrt(3.); + float sqrt3 = std::sqrt(3.); glLightfv(GL_LIGHT0, GL_AMBIENT, Vector4f(0.5,0.5,0.5,1).data()); glLightfv(GL_LIGHT0, GL_DIFFUSE, Vector4f(0.5,1,0.5,1).data()); glLightfv(GL_LIGHT0, GL_SPECULAR, Vector4f(1,1,1,1).data()); diff --git a/gtsam/3rdparty/Eigen/demos/opengl/trackball.cpp b/gtsam/3rdparty/Eigen/demos/opengl/trackball.cpp index 77ac790c8..7c2da8e96 100644 --- a/gtsam/3rdparty/Eigen/demos/opengl/trackball.cpp +++ b/gtsam/3rdparty/Eigen/demos/opengl/trackball.cpp @@ -23,7 +23,7 @@ void Trackball::track(const Vector2i& point2D) { Vector3f axis = mLastPoint3D.cross(newPoint3D).normalized(); float cos_angle = mLastPoint3D.dot(newPoint3D); - if ( internal::abs(cos_angle) < 1.0 ) + if ( std::abs(cos_angle) < 1.0 ) { float angle = 2. * acos(cos_angle); if (mMode==Around) diff --git a/gtsam/3rdparty/Eigen/doc/A05_PortingFrom2To3.dox b/gtsam/3rdparty/Eigen/doc/A05_PortingFrom2To3.dox index 4d5f3ae1f..51555f996 100644 --- a/gtsam/3rdparty/Eigen/doc/A05_PortingFrom2To3.dox +++ b/gtsam/3rdparty/Eigen/doc/A05_PortingFrom2To3.dox @@ -2,8 +2,6 @@ namespace Eigen { /** \page Eigen2ToEigen3 Porting from Eigen2 to Eigen3 -
Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3.
- This page lists the most important API changes between Eigen2 and Eigen3, and gives tips to help porting your application from Eigen2 to Eigen3. @@ -11,11 +9,8 @@ and gives tips to help porting your application from Eigen2 to Eigen3. \section CompatibilitySupport Eigen2 compatibility support -In order to ease the switch from Eigen2 to Eigen3, Eigen3 features \subpage Eigen2SupportModes "Eigen2 support modes". - -The quick way to enable this is to define the \c EIGEN2_SUPPORT preprocessor token \b before including any Eigen header (typically it should be set in your project options). - -A more powerful, \em staged migration path is also provided, which may be useful to migrate larger projects from Eigen2 to Eigen3. This is explained in the \ref Eigen2SupportModes "Eigen 2 support modes" page. +Up to version 3.2 %Eigen provides Eigen2 support modes. These are removed now, because they were barely used anymore and became hard to maintain after internal re-designs. +You can still use them by first porting your code to Eigen 3.2. \section Using The USING_PART_OF_NAMESPACE_EIGEN macro @@ -228,7 +223,7 @@ triangular part to work on \section GeometryModule Changes in the Geometry module -The Geometry module is the one that changed the most. If you rely heavily on it, it's probably a good idea to use the \ref Eigen2SupportModes "Eigen 2 support modes" to perform your migration. +The Geometry module is the one that changed the most. If you rely heavily on it, it's probably a good idea to use the "Eigen 2 support modes" to perform your migration. \section Transform The Transform class @@ -266,7 +261,7 @@ use it unless you are sure of what you are doing, i.e., you have rigourosly meas The EIGEN_ALIGN_128 macro has been renamed to EIGEN_ALIGN16. Don't be surprised, it's just that we switched to counting in bytes ;-) -The EIGEN_DONT_ALIGN option still exists in Eigen 3, but it has a new cousin: EIGEN_DONT_ALIGN_STATICALLY. It allows to get rid of all static alignment issues while keeping alignment of dynamic-size heap-allocated arrays, thus keeping vectorization for dynamic-size objects. +The \link TopicPreprocessorDirectivesPerformance EIGEN_DONT_ALIGN \endlink option still exists in Eigen 3, but it has a new cousin: \link TopicPreprocessorDirectivesPerformance EIGEN_DONT_ALIGN_STATICALLY.\endlink It allows to get rid of all static alignment issues while keeping alignment of dynamic-size heap-allocated arrays. Vectorization of statically allocated arrays is still preserved (unless you define \link TopicPreprocessorDirectivesPerformance EIGEN_UNALIGNED_VECTORIZE \endlink =0), at the cost of unaligned memory stores. \section AlignedMap Aligned Map objects @@ -283,7 +278,7 @@ result = Vector4f::MapAligned(some_aligned_array); \section StdContainers STL Containers -In Eigen2, #include tweaked std::vector to automatically align elements. The problem was that that was quite invasive. In Eigen3, we only override standard behavior if you use Eigen::aligned_allocator as your allocator type. So for example, if you use std::vector, you need to do the following change (note that aligned_allocator is under namespace Eigen): +In Eigen2, \#include\ tweaked std::vector to automatically align elements. The problem was that that was quite invasive. In Eigen3, we only override standard behavior if you use Eigen::aligned_allocator as your allocator type. So for example, if you use std::vector, you need to do the following change (note that aligned_allocator is under namespace Eigen): diff --git a/gtsam/3rdparty/Eigen/doc/A10_Eigen2SupportModes.dox b/gtsam/3rdparty/Eigen/doc/A10_Eigen2SupportModes.dox deleted file mode 100644 index f3df91515..000000000 --- a/gtsam/3rdparty/Eigen/doc/A10_Eigen2SupportModes.dox +++ /dev/null @@ -1,95 +0,0 @@ -namespace Eigen { - -/** \page Eigen2SupportModes Eigen 2 support modes - -
Eigen2 support is deprecated in Eigen 3.2.x and it will be removed in Eigen 3.3.
- -This page documents the Eigen2 support modes, a powerful tool to help migrating your project from Eigen 2 to Eigen 3. -Don't miss our page on \ref Eigen2ToEigen3 "API changes" between Eigen 2 and Eigen 3. - -\eigenAutoToc - -\section EIGEN2_SUPPORT_Macro The quick way: define EIGEN2_SUPPORT - -By defining EIGEN2_SUPPORT before including any Eigen 3 header, you get back a large part of the Eigen 2 API, while keeping the Eigen 3 API and ABI unchanged. - -This defaults to the \ref Stage30 "stage 30" described below. - -The rest of this page describes an optional, more powerful \em staged migration path. - -\section StagedMigrationPathOverview Overview of the staged migration path - -The primary reason why EIGEN2_SUPPORT alone may not be enough to migrate a large project from Eigen 2 to Eigen 3 is that some of the Eigen 2 API is inherently incompatible with the Eigen 3 API. This happens when the same identifier is used in Eigen 2 and in Eigen 3 with different meanings. To help migrate projects that rely on such API, we provide a staged migration path allowing to perform the migration \em incrementally. - -It goes as follows: -\li Step 0: start with a project using Eigen 2. -\li Step 1: build your project against Eigen 3 with \ref Stage10 "Eigen 2 support stage 10". This mode enables maximum compatibility with the Eigen 2 API, with just a few exceptions. -\li Step 2: build your project against Eigen 3 with \ref Stage20 "Eigen 2 support stage 20". This mode forces you to add eigen2_ prefixes to the Eigen2 identifiers that conflict with Eigen 3 API. -\li Step 3: build your project against Eigen 3 with \ref Stage30 "Eigen 2 support stage 30". This mode enables the full Eigen 3 API. -\li Step 4: build your project against Eigen 3 with \ref Stage40 "Eigen 2 support stage 40". This mode enables the full Eigen 3 strictness on matters, such as const-correctness, where Eigen 2 was looser. -\li Step 5: build your project against Eigen 3 without any Eigen 2 support mode. - -\section Stage10 Stage 10: define EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API - -Enable this mode by defining the EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API preprocessor macro before including any Eigen 3 header. - -This mode maximizes support for the Eigen 2 API. As a result, it does not offer the full Eigen 3 API. Also, it doesn't offer quite 100% of the Eigen 2 API. - -The part of the Eigen 3 API that is not present in this mode, is Eigen 3's Geometry module. Indeed, this mode completely replaces it by a copy of Eigen 2's Geometry module. - -The parts of the API that are still not 100% Eigen 2 compatible in this mode are: -\li Dot products over complex numbers. Eigen 2's dot product was linear in the first variable. Eigen 3's dot product is linear in the second variable. In other words, the Eigen 2 code \code x.dot(y) \endcode is equivalent to the Eigen 3 code \code y.dot(x) \endcode In yet other words, dot products are complex-conjugated in Eigen 3 compared to Eigen 2. The switch to the new convention was commanded by common usage, especially with the notation \f$ x^Ty \f$ for dot products of column-vectors. -\li The Sparse module. -\li Certain fine details of linear algebraic decompositions. For example, LDLT decomposition is now pivoting in Eigen 3 whereas it wasn't in Eigen 2, so code that was relying on its underlying matrix structure will break. -\li Usage of Eigen types in STL containers, \ref Eigen2ToEigen3 "as explained on this page". - -\section Stage20 Stage 20: define EIGEN2_SUPPORT_STAGE20_RESOLVE_API_CONFLICTS - -Enable this mode by defining the EIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API preprocessor macro before including any Eigen 3 header. - -This mode removes the Eigen 2 API that is directly conflicting with Eigen 3 API. Instead, these bits of Eigen 2 API remain available with eigen2_ prefixes. The main examples of such API are: -\li the whole Geometry module. For example, replace \c Quaternion by \c eigen2_Quaternion, replace \c Transform3f by \c eigen2_Transform3f, etc. -\li the lu() method to obtain a LU decomposition. Replace by eigen2_lu(). - -There is also one more eigen2_-prefixed identifier that you should know about, even though its use is not checked at compile time by this mode: the dot() method. As was discussed above, over complex numbers, its meaning is different between Eigen 2 and Eigen 3. You can use eigen2_dot() to get the Eigen 2 behavior. - -\section Stage30 Stage 30: define EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API - -Enable this mode by defining the EIGEN2_SUPPORT_STAGE30_FULL_EIGEN3_API preprocessor macro before including any Eigen 3 header. Also, this mode is what you get by default when you just define EIGEN2_SUPPORT. - -This mode gives you the full unaltered Eigen 3 API, while still keeping as much support as possible for the Eigen 2 API. - -The eigen2_-prefixed identifiers are still available, but at this stage you should now replace them by Eigen 3 identifiers. Have a look at our page on \ref Eigen2ToEigen3 "API changes" between Eigen 2 and Eigen 3. - -\section Stage40 Stage 40: define EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS - -Enable this mode by defining the EIGEN2_SUPPORT_STAGE40_FULL_EIGEN3_STRICTNESS preprocessor macro before including any Eigen 3 header. - -This mode tightens the last bits of strictness, especially const-correctness, that had to be loosened to support what Eigen 2 allowed. For example, this code compiled in Eigen 2: -\code -const float array[4]; -x = Map(array); -\endcode -That allowed to circumvent constness. This is no longer allowed in Eigen 3. If you have to map const data in Eigen 3, map it as a const-qualified type. However, rather than explictly constructing Map objects, we strongly encourage you to use the static Map methods instead, as they take care of all of this for you: -\code -const float array[4]; -x = Vector4f::Map(array); -\endcode -This lets Eigen do the right thing for you and works equally well in Eigen 2 and in Eigen 3. - -\section FinallyDropAllEigen2Support Finally drop all Eigen 2 support - -Stage 40 is the first where it's "comfortable" to stay for a little longer period, since it preserves 100% Eigen 3 compatibility. However, we still encourage you to complete your migration as quickly as possible. While we do run the Eigen 2 test suite against Eigen 3's stage 10 support mode, we can't guarantee the same level of support and quality assurance for Eigen 2 support as we do for Eigen 3 itself, especially not in the long term. \ref Eigen2ToEigen3 "This page" describes a large part of the changes that you may need to perform. - -\section ABICompatibility What about ABI compatibility? - -It goes as follows: -\li Stage 10 already is ABI compatible with Eigen 3 for the basic (Matrix, Array, SparseMatrix...) types. However, since this stage uses a copy of Eigen 2's Geometry module instead of Eigen 3's own Geometry module, the ABI in the Geometry module is not Eigen 3 compatible. -\li Stage 20 removes the Eigen 3-incompatible Eigen 2 Geometry module (it remains available with eigen2_ prefix). So at this stage, all the identifiers that exist in Eigen 3 have the Eigen 3 ABI (and API). -\li Stage 30 introduces the remaining Eigen 3 identifiers. So at this stage, you have the full Eigen 3 ABI. -\li Stage 40 is no different than Stage 30 in these matters. - - -*/ - -} diff --git a/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt b/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt index b9f497f87..0ca54cef3 100644 --- a/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt +++ b/gtsam/3rdparty/Eigen/doc/AsciiQuickReference.txt @@ -32,17 +32,19 @@ A << 1, 2, 3, // Initialize A. The elements can also be B << A, A, A; // B is three horizontally stacked A's. A.fill(10); // Fill A with all 10's. -// Eigen // Matlab -MatrixXd::Identity(rows,cols) // eye(rows,cols) -C.setIdentity(rows,cols) // C = eye(rows,cols) -MatrixXd::Zero(rows,cols) // zeros(rows,cols) -C.setZero(rows,cols) // C = ones(rows,cols) -MatrixXd::Ones(rows,cols) // ones(rows,cols) -C.setOnes(rows,cols) // C = ones(rows,cols) -MatrixXd::Random(rows,cols) // rand(rows,cols)*2-1 // MatrixXd::Random returns uniform random numbers in (-1, 1). -C.setRandom(rows,cols) // C = rand(rows,cols)*2-1 -VectorXd::LinSpaced(size,low,high) // linspace(low,high,size)' -v.setLinSpaced(size,low,high) // v = linspace(low,high,size)' +// Eigen // Matlab +MatrixXd::Identity(rows,cols) // eye(rows,cols) +C.setIdentity(rows,cols) // C = eye(rows,cols) +MatrixXd::Zero(rows,cols) // zeros(rows,cols) +C.setZero(rows,cols) // C = zeros(rows,cols) +MatrixXd::Ones(rows,cols) // ones(rows,cols) +C.setOnes(rows,cols) // C = ones(rows,cols) +MatrixXd::Random(rows,cols) // rand(rows,cols)*2-1 // MatrixXd::Random returns uniform random numbers in (-1, 1). +C.setRandom(rows,cols) // C = rand(rows,cols)*2-1 +VectorXd::LinSpaced(size,low,high) // linspace(low,high,size)' +v.setLinSpaced(size,low,high) // v = linspace(low,high,size)' +VectorXi::LinSpaced(((hi-low)/step)+1, // low:step:hi + low,low+step*(size-1)) // // Matrix slicing and blocks. All expressions listed here are read/write. @@ -82,17 +84,20 @@ P.bottomRightCorner() // P(end-rows+1:end, end-cols+1:end) // Of particular note is Eigen's swap function which is highly optimized. // Eigen // Matlab -R.row(i) = P.col(j); // R(i, :) = P(:, i) +R.row(i) = P.col(j); // R(i, :) = P(:, j) R.col(j1).swap(mat1.col(j2)); // R(:, [j1 j2]) = R(:, [j2, j1]) -// Views, transpose, etc; all read-write except for .adjoint(). +// Views, transpose, etc; // Eigen // Matlab R.adjoint() // R' -R.transpose() // R.' or conj(R') -R.diagonal() // diag(R) +R.transpose() // R.' or conj(R') // Read-write +R.diagonal() // diag(R) // Read-write x.asDiagonal() // diag(x) -R.transpose().colwise().reverse(); // rot90(R) -R.conjugate() // conj(R) +R.transpose().colwise().reverse() // rot90(R) // Read-write +R.rowwise().reverse() // fliplr(R) +R.colwise().reverse() // flipud(R) +R.replicate(i,j) // repmat(P,i,j) + // All the same as Matlab, but matlab doesn't have *= style operators. // Matrix-vector. Matrix-matrix. Matrix-scalar. @@ -104,37 +109,40 @@ a *= M; R = P + Q; R = P/s; R -= Q; R /= s; // Vectorized operations on each element independently -// Eigen // Matlab -R = P.cwiseProduct(Q); // R = P .* Q -R = P.array() * s.array();// R = P .* s -R = P.cwiseQuotient(Q); // R = P ./ Q -R = P.array() / Q.array();// R = P ./ Q -R = P.array() + s.array();// R = P + s -R = P.array() - s.array();// R = P - s -R.array() += s; // R = R + s -R.array() -= s; // R = R - s -R.array() < Q.array(); // R < Q -R.array() <= Q.array(); // R <= Q -R.cwiseInverse(); // 1 ./ P -R.array().inverse(); // 1 ./ P -R.array().sin() // sin(P) -R.array().cos() // cos(P) -R.array().pow(s) // P .^ s -R.array().square() // P .^ 2 -R.array().cube() // P .^ 3 -R.cwiseSqrt() // sqrt(P) -R.array().sqrt() // sqrt(P) -R.array().exp() // exp(P) -R.array().log() // log(P) -R.cwiseMax(P) // max(R, P) -R.array().max(P.array()) // max(R, P) -R.cwiseMin(P) // min(R, P) -R.array().min(P.array()) // min(R, P) -R.cwiseAbs() // abs(P) -R.array().abs() // abs(P) -R.cwiseAbs2() // abs(P.^2) -R.array().abs2() // abs(P.^2) -(R.array() < s).select(P,Q); // (R < s ? P : Q) +// Eigen // Matlab +R = P.cwiseProduct(Q); // R = P .* Q +R = P.array() * s.array(); // R = P .* s +R = P.cwiseQuotient(Q); // R = P ./ Q +R = P.array() / Q.array(); // R = P ./ Q +R = P.array() + s.array(); // R = P + s +R = P.array() - s.array(); // R = P - s +R.array() += s; // R = R + s +R.array() -= s; // R = R - s +R.array() < Q.array(); // R < Q +R.array() <= Q.array(); // R <= Q +R.cwiseInverse(); // 1 ./ P +R.array().inverse(); // 1 ./ P +R.array().sin() // sin(P) +R.array().cos() // cos(P) +R.array().pow(s) // P .^ s +R.array().square() // P .^ 2 +R.array().cube() // P .^ 3 +R.cwiseSqrt() // sqrt(P) +R.array().sqrt() // sqrt(P) +R.array().exp() // exp(P) +R.array().log() // log(P) +R.cwiseMax(P) // max(R, P) +R.array().max(P.array()) // max(R, P) +R.cwiseMin(P) // min(R, P) +R.array().min(P.array()) // min(R, P) +R.cwiseAbs() // abs(P) +R.array().abs() // abs(P) +R.cwiseAbs2() // abs(P.^2) +R.array().abs2() // abs(P.^2) +(R.array() < s).select(P,Q ); // (R < s ? P : Q) +R = (Q.array()==0).select(P,R) // R(Q==0) = P(Q==0) +R = P.unaryExpr(ptr_fun(func)) // R = arrayfun(func, P) // with: scalar func(const scalar &x); + // Reductions. int r, c; @@ -165,12 +173,12 @@ x.dot(y) // dot(x, y) x.cross(y) // cross(x, y) Requires #include //// Type conversion -// Eigen // Matlab -A.cast(); // double(A) -A.cast(); // single(A) -A.cast(); // int32(A) -A.real(); // real(A) -A.imag(); // imag(A) +// Eigen // Matlab +A.cast(); // double(A) +A.cast(); // single(A) +A.cast(); // int32(A) +A.real(); // real(A) +A.imag(); // imag(A) // if the original type equals destination type, no work is done // Note that for most operations Eigen requires all operands to have the same type: diff --git a/gtsam/3rdparty/Eigen/doc/B01_Experimental.dox b/gtsam/3rdparty/Eigen/doc/B01_Experimental.dox index 5fc0ccd60..e1f031db8 100644 --- a/gtsam/3rdparty/Eigen/doc/B01_Experimental.dox +++ b/gtsam/3rdparty/Eigen/doc/B01_Experimental.dox @@ -4,7 +4,7 @@ namespace Eigen { \eigenAutoToc -\section summary Summary +\section Experimental_summary Summary With the 2.0 release, Eigen's API is, to a large extent, stable. However, we wish to retain the freedom to make API incompatible changes. To that effect, we call many parts of Eigen "experimental" which means that they are not subject to API stability guarantee. @@ -17,7 +17,7 @@ Experimental features may at any time: \li be subject to an API incompatible change; \li introduce API or ABI incompatible changes in your own code if you let them affect your API or ABI. -\section modules Experimental modules +\section Experimental_modules Experimental modules The following modules are considered entirely experimental, and we make no firm API stability guarantee about them for the time being: \li SVD @@ -26,7 +26,7 @@ The following modules are considered entirely experimental, and we make no firm \li Sparse \li Geometry (this one should be mostly stable, but it's a little too early to make a formal guarantee) -\section core Experimental parts of the Core module +\section Experimental_core Experimental parts of the Core module In the Core module, the only classes subject to ABI stability guarantee (meaning that you can use it for data members in your public ABI) is: \li Matrix diff --git a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt index 02790ee43..db413bc65 100644 --- a/gtsam/3rdparty/Eigen/doc/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/CMakeLists.txt @@ -10,12 +10,20 @@ if(CMAKE_COMPILER_IS_GNUCXX) endif(CMAKE_SYSTEM_NAME MATCHES Linux) endif(CMAKE_COMPILER_IS_GNUCXX) +option(EIGEN_INTERNAL_DOCUMENTATION "Build internal documentation" OFF) + + # Set some Doxygen flags set(EIGEN_DOXY_PROJECT_NAME "Eigen") set(EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX "") set(EIGEN_DOXY_INPUT "\"${Eigen_SOURCE_DIR}/Eigen\" \"${Eigen_SOURCE_DIR}/doc\"") set(EIGEN_DOXY_HTML_COLORSTYLE_HUE "220") set(EIGEN_DOXY_TAGFILES "") +if(EIGEN_INTERNAL_DOCUMENTATION) + set(EIGEN_DOXY_INTERNAL "YES") +else(EIGEN_INTERNAL_DOCUMENTATION) + set(EIGEN_DOXY_INTERNAL "NO") +endif(EIGEN_INTERNAL_DOCUMENTATION) configure_file( ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in @@ -70,6 +78,8 @@ add_custom_target( COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/html/ COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js ${CMAKE_CURRENT_BINARY_DIR}/html/ COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png ${CMAKE_CURRENT_BINARY_DIR}/html/ + COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png ${CMAKE_CURRENT_BINARY_DIR}/html/ + COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png ${CMAKE_CURRENT_BINARY_DIR}/html/ COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/AsciiQuickReference.txt ${CMAKE_CURRENT_BINARY_DIR}/html/ WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} ) @@ -80,6 +90,8 @@ add_custom_target( COMMAND ${CMAKE_COMMAND} -E make_directory ${Eigen_BINARY_DIR}/doc/html/unsupported COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/ COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/ + COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/ + COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/ WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc ) diff --git a/gtsam/3rdparty/Eigen/doc/CoeffwiseMathFunctionsTable.dox b/gtsam/3rdparty/Eigen/doc/CoeffwiseMathFunctionsTable.dox new file mode 100644 index 000000000..3ae9420dc --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/CoeffwiseMathFunctionsTable.dox @@ -0,0 +1,525 @@ +namespace Eigen { + +/** \eigenManualPage CoeffwiseMathFunctions Catalog of coefficient-wise math functions + + + + +This table presents a catalog of the coefficient-wise math functions supported by %Eigen. +In this table, \c a, \c b, refer to Array objects or expressions, and \c m refers to a linear algebra Matrix/Vector object. Standard scalar types are abbreviated as follows: + - \c int: \c i32 + - \c float: \c f + - \c double: \c d + - \c std::complex: \c cf + - \c std::complex: \c cd + +For each row, the first column list the equivalent calls for arrays, and matrices when supported. Of course, all functions are available for matrices by first casting it as an array: \c m.array(). + +The third column gives some hints in the underlying scalar implementation. In most cases, %Eigen does not implement itself the math function but relies on the STL for standard scalar types, or user-provided functions for custom scalar types. +For instance, some simply calls the respective function of the STL while preserving argument-dependent lookup for custom types. +The following: +\code +using std::foo; +foo(a[i]); +\endcode +means that the STL's function \c std::foo will be potentially called if it is compatible with the underlying scalar type. If not, then the user must ensure that an overload of the function foo is available for the given scalar type (usually defined in the same namespace as the given scalar type). +This also means that, unless specified, if the function \c std::foo is available only in some recent c++ versions (e.g., c++11), then the respective %Eigen's function/method will be usable on standard types only if the compiler support the required c++ version. + +
Eigen 2Eigen 3
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
APIDescriptionDefault scalar implementationSIMD
Basic operations
+ \anchor cwisetable_abs + a.\link ArrayBase::abs abs\endlink(); \n + \link Eigen::abs abs\endlink(a); \n + m.\link MatrixBase::cwiseAbs cwiseAbs\endlink(); + absolute value (\f$ |a_i| \f$) + using std::abs; \n + abs(a[i]); + SSE2, AVX (i32,f,d)
+ \anchor cwisetable_inverse + a.\link ArrayBase::inverse inverse\endlink(); \n + \link Eigen::inverse inverse\endlink(a); \n + m.\link MatrixBase::cwiseInverse cwiseInverse\endlink(); + inverse value (\f$ 1/a_i \f$) + 1/a[i]; + All engines (f,d,fc,fd)
+ \anchor cwisetable_conj + a.\link ArrayBase::conjugate conjugate\endlink(); \n + \link Eigen::conj conj\endlink(a); \n + m.\link MatrixBase::conjugate conjugate(); + complex conjugate (\f$ \bar{a_i} \f$),\n + no-op for real + using std::conj; \n + conj(a[i]); + All engines (fc,fd)
Exponential functions
+ \anchor cwisetable_exp + a.\link ArrayBase::exp exp\endlink(); \n + \link Eigen::exp exp\endlink(a); + \f$ e \f$ raised to the given power (\f$ e^{a_i} \f$) + using std::exp; \n + exp(a[i]); + SSE2, AVX (f,d)
+ \anchor cwisetable_log + a.\link ArrayBase::log log\endlink(); \n + \link Eigen::log log\endlink(a); + natural (base \f$ e \f$) logarithm (\f$ \ln({a_i}) \f$) + using std::log; \n + log(a[i]); + SSE2, AVX (f)
+ \anchor cwisetable_log1p + a.\link ArrayBase::log1p log1p\endlink(); \n + \link Eigen::log1p log1p\endlink(a); + natural (base \f$ e \f$) logarithm of 1 plus \n the given number (\f$ \ln({1+a_i}) \f$)built-in generic implementation based on \c log,\n + plus \c using \c std::log1p ; \cpp11
+ \anchor cwisetable_log10 + a.\link ArrayBase::log10 log10\endlink(); \n + \link Eigen::log10 log10\endlink(a); + base 10 logarithm (\f$ \log_{10}({a_i}) \f$) + using std::log10; \n + log10(a[i]); +
Power functions
+ \anchor cwisetable_pow + a.\link ArrayBase::pow pow\endlink(b); \n + \link Eigen::pow pow\endlink(a,b); + raises a number to the given power (\f$ a_i ^ {b_i} \f$) \n \c a and \c b can be either an array or scalar. + using std::pow; \n + pow(a[i],b[i]);\n + (plus builtin for integer types)
+ \anchor cwisetable_sqrt + a.\link ArrayBase::sqrt sqrt\endlink(); \n + \link Eigen::sqrt sqrt\endlink(a);\n + m.\link MatrixBase::cwiseSqrt cwiseSqrt\endlink(); + computes square root (\f$ \sqrt a_i \f$) + using std::sqrt; \n + sqrt(a[i]);SSE2, AVX (f,d)
+ \anchor cwisetable_rsqrt + a.\link ArrayBase::rsqrt rsqrt\endlink(); \n + \link Eigen::rsqrt rsqrt\endlink(a); + reciprocal square root (\f$ 1/{\sqrt a_i} \f$) + using std::sqrt; \n + 1/sqrt(a[i]); \n + SSE2, AVX, AltiVec, ZVector (f,d)\n + (approx + 1 Newton iteration)
+ \anchor cwisetable_square + a.\link ArrayBase::square square\endlink(); \n + \link Eigen::square square\endlink(a); + computes square power (\f$ a_i^2 \f$) + a[i]*a[i]All (i32,f,d,cf,cd)
+ \anchor cwisetable_cube + a.\link ArrayBase::cube cube\endlink(); \n + \link Eigen::cube cube\endlink(a); + computes cubic power (\f$ a_i^3 \f$) + a[i]*a[i]*a[i]All (i32,f,d,cf,cd)
+ \anchor cwisetable_abs2 + a.\link ArrayBase::abs2 abs2\endlink(); \n + \link Eigen::abs2 abs2\endlink(a);\n + m.\link MatrixBase::cwiseAbs2 cwiseAbs2\endlink(); + computes the squared absolute value (\f$ |a_i|^2 \f$) + real: a[i]*a[i] \n + complex: real(a[i])*real(a[i]) \n +        + imag(a[i])*imag(a[i])All (i32,f,d)
Trigonometric functions
+ \anchor cwisetable_sin + a.\link ArrayBase::sin sin\endlink(); \n + \link Eigen::sin sin\endlink(a); + computes sine + using std::sin; \n + sin(a[i]);SSE2, AVX (f)
+ \anchor cwisetable_cos + a.\link ArrayBase::cos cos\endlink(); \n + \link Eigen::cos cos\endlink(a); + computes cosine + using std::cos; \n + cos(a[i]);SSE2, AVX (f)
+ \anchor cwisetable_tan + a.\link ArrayBase::tan tan\endlink(); \n + \link Eigen::tan tan\endlink(a); + computes tangent + using std::tan; \n + tan(a[i]);
+ \anchor cwisetable_asin + a.\link ArrayBase::asin asin\endlink(); \n + \link Eigen::asin asin\endlink(a); + computes arc sine (\f$ \sin^{-1} a_i \f$) + using std::asin; \n + asin(a[i]);
+ \anchor cwisetable_acos + a.\link ArrayBase::acos acos\endlink(); \n + \link Eigen::acos acos\endlink(a); + computes arc cosine (\f$ \cos^{-1} a_i \f$) + using std::acos; \n + acos(a[i]);
+ \anchor cwisetable_atan + a.\link ArrayBase::atan tan\endlink(); \n + \link Eigen::atan atan\endlink(a); + computes arc tangent (\f$ \tan^{-1} a_i \f$) + using std::atan; \n + atan(a[i]);
Hyperbolic functions
+ \anchor cwisetable_sinh + a.\link ArrayBase::sinh sinh\endlink(); \n + \link Eigen::sinh sinh\endlink(a); + computes hyperbolic sine + using std::sinh; \n + sinh(a[i]);
+ \anchor cwisetable_cosh + a.\link ArrayBase::cosh cohs\endlink(); \n + \link Eigen::cosh cosh\endlink(a); + computes hyperbolic cosine + using std::cosh; \n + cosh(a[i]);
+ \anchor cwisetable_tanh + a.\link ArrayBase::tanh tanh\endlink(); \n + \link Eigen::tanh tanh\endlink(a); + computes hyperbolic tangent + using std::tanh; \n + tanh(a[i]);
Nearest integer floating point operations
+ \anchor cwisetable_ceil + a.\link ArrayBase::ceil ceil\endlink(); \n + \link Eigen::ceil ceil\endlink(a); + nearest integer not less than the given value + using std::ceil; \n + ceil(a[i]);SSE4,AVX,ZVector (f,d)
+ \anchor cwisetable_floor + a.\link ArrayBase::floor floor\endlink(); \n + \link Eigen::floor floor\endlink(a); + nearest integer not greater than the given value + using std::floor; \n + floor(a[i]);SSE4,AVX,ZVector (f,d)
+ \anchor cwisetable_round + a.\link ArrayBase::round round\endlink(); \n + \link Eigen::round round\endlink(a); + nearest integer, \n rounding away from zero in halfway casesbuilt-in generic implementation \n based on \c floor and \c ceil,\n + plus \c using \c std::round ; \cpp11SSE4,AVX,ZVector (f,d)
Floating point manipulation functions
Classification and comparison
+ \anchor cwisetable_isfinite + a.\link ArrayBase::isFinite isFinite\endlink(); \n + \link Eigen::isfinite isfinite\endlink(a); + checks if the given number has finite valuebuilt-in generic implementation,\n + plus \c using \c std::isfinite ; \cpp11
+ \anchor cwisetable_isinf + a.\link ArrayBase::isInf isInf\endlink(); \n + \link Eigen::isinf isinf\endlink(a); + checks if the given number is infinitebuilt-in generic implementation,\n + plus \c using \c std::isinf ; \cpp11
+ \anchor cwisetable_isnan + a.\link ArrayBase::isNaN isNaN\endlink(); \n + \link Eigen::isnan isnan\endlink(a); + checks if the given number is not a numberbuilt-in generic implementation,\n + plus \c using \c std::isnan ; \cpp11
Error and gamma functions
Require \c \#include \c
+ \anchor cwisetable_erf + a.\link ArrayBase::erf erf\endlink(); \n + \link Eigen::erf erf\endlink(a); + error function + using std::erf; \cpp11 \n + erf(a[i]); +
+ \anchor cwisetable_erfc + a.\link ArrayBase::erfc erfc\endlink(); \n + \link Eigen::erfc erfc\endlink(a); + complementary error function + using std::erfc; \cpp11 \n + erfc(a[i]); +
+ \anchor cwisetable_lgamma + a.\link ArrayBase::lgamma lgamma\endlink(); \n + \link Eigen::lgamma lgamma\endlink(a); + natural logarithm of the gamma function + using std::lgamma; \cpp11 \n + lgamma(a[i]); +
+ \anchor cwisetable_digamma + a.\link ArrayBase::digamma digamma\endlink(); \n + \link Eigen::digamma digamma\endlink(a); + logarithmic derivative of the gamma function + built-in for float and double +
+ \anchor cwisetable_igamma + \link Eigen::igamma igamma\endlink(a,x); + lower incomplete gamma integral + \n \f$ \gamma(a_i,x_i)= \frac{1}{|a_i|} \int_{0}^{x_i}e^{\text{-}t} t^{a_i-1} \mathrm{d} t \f$ + built-in for float and double,\n but requires \cpp11 +
+ \anchor cwisetable_igammac + \link Eigen::igammac igammac\endlink(a,x); + upper incomplete gamma integral + \n \f$ \Gamma(a_i,x_i) = \frac{1}{|a_i|} \int_{x_i}^{\infty}e^{\text{-}t} t^{a_i-1} \mathrm{d} t \f$ + built-in for float and double,\n but requires \cpp11 +
Special functions
Require \c \#include \c
+ \anchor cwisetable_polygamma + \link Eigen::polygamma polygamma\endlink(n,x); + n-th derivative of digamma at x + built-in generic based on\n \c lgamma , + \c digamma + and \c zeta . +
+ \anchor cwisetable_betainc + \link Eigen::betainc betainc\endlink(a,b,x); + Incomplete beta function + built-in for float and double,\n but requires \cpp11 +
+ \anchor cwisetable_zeta + \link Eigen::zeta zeta\endlink(a,b); + Hurwitz zeta function + \n \f$ \zeta(a_i,b_i)=\sum_{k=0}^{\infty}(b_i+k)^{\text{-}a_i} \f$ + built-in for float and double +
+ +\n + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/CustomizingEigen.dox b/gtsam/3rdparty/Eigen/doc/CustomizingEigen.dox deleted file mode 100644 index 5a0890ea9..000000000 --- a/gtsam/3rdparty/Eigen/doc/CustomizingEigen.dox +++ /dev/null @@ -1,188 +0,0 @@ -namespace Eigen { - -/** \page TopicCustomizingEigen Customizing/Extending Eigen - -Eigen can be extended in several ways, for instance, by defining global methods, \ref ExtendingMatrixBase "by adding custom methods to MatrixBase", adding support to \ref CustomScalarType "custom types" etc. - -\eigenAutoToc - -\section ExtendingMatrixBase Extending MatrixBase (and other classes) - -In this section we will see how to add custom methods to MatrixBase. Since all expressions and matrix types inherit MatrixBase, adding a method to MatrixBase make it immediately available to all expressions ! A typical use case is, for instance, to make Eigen compatible with another API. - -You certainly know that in C++ it is not possible to add methods to an existing class. So how that's possible ? Here the trick is to include in the declaration of MatrixBase a file defined by the preprocessor token \c EIGEN_MATRIXBASE_PLUGIN: -\code -class MatrixBase { - // ... - #ifdef EIGEN_MATRIXBASE_PLUGIN - #include EIGEN_MATRIXBASE_PLUGIN - #endif -}; -\endcode -Therefore to extend MatrixBase with your own methods you just have to create a file with your method declaration and define EIGEN_MATRIXBASE_PLUGIN before you include any Eigen's header file. - -You can extend many of the other classes used in Eigen by defining similarly named preprocessor symbols. For instance, define \c EIGEN_ARRAYBASE_PLUGIN if you want to extend the ArrayBase class. A full list of classes that can be extended in this way and the corresponding preprocessor symbols can be found on our page \ref TopicPreprocessorDirectives. - -Here is an example of an extension file for adding methods to MatrixBase: \n -\b MatrixBaseAddons.h -\code -inline Scalar at(uint i, uint j) const { return this->operator()(i,j); } -inline Scalar& at(uint i, uint j) { return this->operator()(i,j); } -inline Scalar at(uint i) const { return this->operator[](i); } -inline Scalar& at(uint i) { return this->operator[](i); } - -inline RealScalar squaredLength() const { return squaredNorm(); } -inline RealScalar length() const { return norm(); } -inline RealScalar invLength(void) const { return fast_inv_sqrt(squaredNorm()); } - -template -inline Scalar squaredDistanceTo(const MatrixBase& other) const -{ return (derived() - other.derived()).squaredNorm(); } - -template -inline RealScalar distanceTo(const MatrixBase& other) const -{ return internal::sqrt(derived().squaredDistanceTo(other)); } - -inline void scaleTo(RealScalar l) { RealScalar vl = norm(); if (vl>1e-9) derived() *= (l/vl); } - -inline Transpose transposed() {return this->transpose();} -inline const Transpose transposed() const {return this->transpose();} - -inline uint minComponentId(void) const { int i; this->minCoeff(&i); return i; } -inline uint maxComponentId(void) const { int i; this->maxCoeff(&i); return i; } - -template -void makeFloor(const MatrixBase& other) { derived() = derived().cwiseMin(other.derived()); } -template -void makeCeil(const MatrixBase& other) { derived() = derived().cwiseMax(other.derived()); } - -const CwiseUnaryOp, Derived> -operator+(const Scalar& scalar) const -{ return CwiseUnaryOp, Derived>(derived(), internal::scalar_add_op(scalar)); } - -friend const CwiseUnaryOp, Derived> -operator+(const Scalar& scalar, const MatrixBase& mat) -{ return CwiseUnaryOp, Derived>(mat.derived(), internal::scalar_add_op(scalar)); } -\endcode - -Then one can the following declaration in the config.h or whatever prerequisites header file of his project: -\code -#define EIGEN_MATRIXBASE_PLUGIN "MatrixBaseAddons.h" -\endcode - -\section InheritingFromMatrix Inheriting from Matrix - -Before inheriting from Matrix, be really, i mean REALLY sure that using -EIGEN_MATRIX_PLUGIN is not what you really want (see previous section). -If you just need to add few members to Matrix, this is the way to go. - -An example of when you actually need to inherit Matrix, is when you have -several layers of heritage such as MyVerySpecificVector1,MyVerySpecificVector1 -> MyVector1 -> Matrix and. -MyVerySpecificVector3,MyVerySpecificVector4 -> MyVector2 -> Matrix. - -In order for your object to work within the %Eigen framework, you need to -define a few members in your inherited class. - -Here is a minimalistic example:\n -\code -class MyVectorType : public Eigen::VectorXd -{ -public: - MyVectorType(void):Eigen::VectorXd() {} - - typedef Eigen::VectorXd Base; - - // This constructor allows you to construct MyVectorType from Eigen expressions - template - MyVectorType(const Eigen::MatrixBase& other) - : Eigen::Vector3d(other) - { } - - // This method allows you to assign Eigen expressions to MyVectorType - template - MyVectorType & operator= (const Eigen::MatrixBase & other) - { - this->Base::operator=(other); - return *this; - } -}; -\endcode - -This is the kind of error you can get if you don't provide those methods -\code -error: no match for ‘operator=’ in ‘delta = -(((Eigen::MatrixBase, 10000, 1, 2, 10000, -1> >*)(& delta)) + 8u)->Eigen::MatrixBase::cwise [with Derived = -Eigen::Matrix, 10000, 1, 2, 10000, -1>]().Eigen::Cwise::operator* [with OtherDerived = -Eigen::Matrix, 10000, 1, 2, 10000, 1>, ExpressionType = -Eigen::Matrix, 10000, 1, 2, 10000, 1>](((const -Eigen::MatrixBase, 10000, 1, 2, 10000, 1> ->&)(((const Eigen::MatrixBase, 10000, 1, ->2, 10000, 1> >*)((const spectral1d*)where)) + 8u)))’ -\endcode - -\anchor user_defined_scalars \section CustomScalarType Using custom scalar types - -By default, Eigen currently supports standard floating-point types (\c float, \c double, \c std::complex, \c std::complex, \c long \c double), as well as all native integer types (e.g., \c int, \c unsigned \c int, \c short, etc.), and \c bool. -On x86-64 systems, \c long \c double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE). - -In order to add support for a custom type \c T you need: --# make sure the common operator (+,-,*,/,etc.) are supported by the type \c T --# add a specialization of struct Eigen::NumTraits (see \ref NumTraits) --# define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific. - (see the file Eigen/src/Core/MathFunctions.h) - -The math function should be defined in the same namespace than \c T, or in the \c std namespace though that second approach is not recommended. - -Here is a concrete example adding support for the Adolc's \c adouble type. Adolc is an automatic differentiation library. The type \c adouble is basically a real value tracking the values of any number of partial derivatives. - -\code -#ifndef ADOLCSUPPORT_H -#define ADOLCSUPPORT_H - -#define ADOLC_TAPELESS -#include -#include - -namespace Eigen { - -template<> struct NumTraits - : NumTraits // permits to get the epsilon, dummy_precision, lowest, highest functions -{ - typedef adtl::adouble Real; - typedef adtl::adouble NonInteger; - typedef adtl::adouble Nested; - - enum { - IsComplex = 0, - IsInteger = 0, - IsSigned = 1, - RequireInitialization = 1, - ReadCost = 1, - AddCost = 3, - MulCost = 3 - }; -}; - -} - -namespace adtl { - -inline const adouble& conj(const adouble& x) { return x; } -inline const adouble& real(const adouble& x) { return x; } -inline adouble imag(const adouble&) { return 0.; } -inline adouble abs(const adouble& x) { return fabs(x); } -inline adouble abs2(const adouble& x) { return x*x; } - -} - -#endif // ADOLCSUPPORT_H -\endcode - - -\sa \ref TopicPreprocessorDirectives - -*/ - -} diff --git a/gtsam/3rdparty/Eigen/doc/CustomizingEigen_CustomScalar.dox b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_CustomScalar.dox new file mode 100644 index 000000000..1ee78cbe5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_CustomScalar.dox @@ -0,0 +1,120 @@ +namespace Eigen { + +/** \page TopicCustomizing_CustomScalar Using custom scalar types +\anchor user_defined_scalars + +By default, Eigen currently supports standard floating-point types (\c float, \c double, \c std::complex, \c std::complex, \c long \c double), as well as all native integer types (e.g., \c int, \c unsigned \c int, \c short, etc.), and \c bool. +On x86-64 systems, \c long \c double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE). + +In order to add support for a custom type \c T you need: +-# make sure the common operator (+,-,*,/,etc.) are supported by the type \c T +-# add a specialization of struct Eigen::NumTraits (see \ref NumTraits) +-# define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific. + (see the file Eigen/src/Core/MathFunctions.h) + +The math function should be defined in the same namespace than \c T, or in the \c std namespace though that second approach is not recommended. + +Here is a concrete example adding support for the Adolc's \c adouble type. Adolc is an automatic differentiation library. The type \c adouble is basically a real value tracking the values of any number of partial derivatives. + +\code +#ifndef ADOLCSUPPORT_H +#define ADOLCSUPPORT_H + +#define ADOLC_TAPELESS +#include +#include + +namespace Eigen { + +template<> struct NumTraits + : NumTraits // permits to get the epsilon, dummy_precision, lowest, highest functions +{ + typedef adtl::adouble Real; + typedef adtl::adouble NonInteger; + typedef adtl::adouble Nested; + + enum { + IsComplex = 0, + IsInteger = 0, + IsSigned = 1, + RequireInitialization = 1, + ReadCost = 1, + AddCost = 3, + MulCost = 3 + }; +}; + +} + +namespace adtl { + +inline const adouble& conj(const adouble& x) { return x; } +inline const adouble& real(const adouble& x) { return x; } +inline adouble imag(const adouble&) { return 0.; } +inline adouble abs(const adouble& x) { return fabs(x); } +inline adouble abs2(const adouble& x) { return x*x; } + +} + +#endif // ADOLCSUPPORT_H +\endcode + +This other example adds support for the \c mpq_class type from GMP. It shows in particular how to change the way Eigen picks the best pivot during LU factorization. It selects the coefficient with the highest score, where the score is by default the absolute value of a number, but we can define a different score, for instance to prefer pivots with a more compact representation (this is an example, not a recommendation). Note that the scores should always be non-negative and only zero is allowed to have a score of zero. Also, this can interact badly with thresholds for inexact scalar types. + +\code +#include +#include +#include + +namespace Eigen { + template<> struct NumTraits : GenericNumTraits + { + typedef mpq_class Real; + typedef mpq_class NonInteger; + typedef mpq_class Nested; + + static inline Real epsilon() { return 0; } + static inline Real dummy_precision() { return 0; } + static inline Real digits10() { return 0; } + + enum { + IsInteger = 0, + IsSigned = 1, + IsComplex = 0, + RequireInitialization = 1, + ReadCost = 6, + AddCost = 150, + MulCost = 100 + }; + }; + + namespace internal { + + template<> struct scalar_score_coeff_op { + struct result_type : boost::totally_ordered1 { + std::size_t len; + result_type(int i = 0) : len(i) {} // Eigen uses Score(0) and Score() + result_type(mpq_class const& q) : + len(mpz_size(q.get_num_mpz_t())+ + mpz_size(q.get_den_mpz_t())-1) {} + friend bool operator<(result_type x, result_type y) { + // 0 is the worst possible pivot + if (x.len == 0) return y.len > 0; + if (y.len == 0) return false; + // Prefer a pivot with a small representation + return x.len > y.len; + } + friend bool operator==(result_type x, result_type y) { + // Only used to test if the score is 0 + return x.len == y.len; + } + }; + result_type operator()(mpq_class const& x) const { return x; } + }; + } +} +\endcode + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/CustomizingEigen_InheritingMatrix.dox b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_InheritingMatrix.dox new file mode 100644 index 000000000..b21e55433 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_InheritingMatrix.dox @@ -0,0 +1,34 @@ +namespace Eigen { + +/** \page TopicCustomizing_InheritingMatrix Inheriting from Matrix + +Before inheriting from Matrix, be really, I mean REALLY, sure that using +EIGEN_MATRIX_PLUGIN is not what you really want (see previous section). +If you just need to add few members to Matrix, this is the way to go. + +An example of when you actually need to inherit Matrix, is when you +have several layers of heritage such as +MyVerySpecificVector1, MyVerySpecificVector2 -> MyVector1 -> Matrix and +MyVerySpecificVector3, MyVerySpecificVector4 -> MyVector2 -> Matrix. + +In order for your object to work within the %Eigen framework, you need to +define a few members in your inherited class. + +Here is a minimalistic example: + +\include CustomizingEigen_Inheritance.cpp + +Output: \verbinclude CustomizingEigen_Inheritance.out + +This is the kind of error you can get if you don't provide those methods +\verbatim +error: no match for ‘operator=’ in ‘v = Eigen::operator*( +const Eigen::MatrixBase >::Scalar&, +const Eigen::MatrixBase >::StorageBaseType&) +(((const Eigen::MatrixBase >::StorageBaseType&) +((const Eigen::MatrixBase >::StorageBaseType*)(& v))))’ +\endverbatim + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/CustomizingEigen_NullaryExpr.dox b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_NullaryExpr.dox new file mode 100644 index 000000000..37c8dcd89 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_NullaryExpr.dox @@ -0,0 +1,86 @@ +namespace Eigen { + +/** \page TopicCustomizing_NullaryExpr Matrix manipulation via nullary-expressions + + +The main purpose of the class CwiseNullaryOp is to define \em procedural matrices such as constant or random matrices as returned by the Ones(), Zero(), Constant(), Identity() and Random() methods. +Nevertheless, with some imagination it is possible to accomplish very sophisticated matrix manipulation with minimal efforts such that \ref TopicNewExpressionType "implementing new expression" is rarely needed. + +\section NullaryExpr_Circulant Example 1: circulant matrix + +To explore these possibilities let us start with the \em circulant example of the \ref TopicNewExpressionType "implementing new expression" topic. +Let us recall that a circulant matrix is a matrix where each column is the same as the +column to the left, except that it is cyclically shifted downwards. +For example, here is a 4-by-4 circulant matrix: +\f[ \begin{bmatrix} + 1 & 8 & 4 & 2 \\ + 2 & 1 & 8 & 4 \\ + 4 & 2 & 1 & 8 \\ + 8 & 4 & 2 & 1 +\end{bmatrix} \f] +A circulant matrix is uniquely determined by its first column. We wish +to write a function \c makeCirculant which, given the first column, +returns an expression representing the circulant matrix. + +For this exercise, the return type of \c makeCirculant will be a CwiseNullaryOp that we need to instantiate with: +1 - a proper \c circulant_functor storing the input vector and implementing the adequate coefficient accessor \c operator(i,j) +2 - a template instantiation of class Matrix conveying compile-time information such as the scalar type, sizes, and preferred storage layout. + +Calling \c ArgType the type of the input vector, we can construct the equivalent squared Matrix type as follows: + +\snippet make_circulant2.cpp square + +This little helper structure will help us to implement our \c makeCirculant function as follows: + +\snippet make_circulant2.cpp makeCirculant + +As usual, our function takes as argument a \c MatrixBase (see this \ref TopicFunctionTakingEigenTypes "page" for more details). +Then, the CwiseNullaryOp object is constructed through the DenseBase::NullaryExpr static method with the adequate runtime sizes. + +Then, we need to implement our \c circulant_functor, which is a straightforward exercise: + +\snippet make_circulant2.cpp circulant_func + +We are now all set to try our new feature: + +\snippet make_circulant2.cpp main + + +If all the fragments are combined, the following output is produced, +showing that the program works as expected: + +\include make_circulant2.out + +This implementation of \c makeCirculant is much simpler than \ref TopicNewExpressionType "defining a new expression" from scratch. + + +\section NullaryExpr_Indexing Example 2: indexing rows and columns + +The goal here is to mimic MatLab's ability to index a matrix through two vectors of indices referencing the rows and columns to be picked respectively, like this: + +\snippet nullary_indexing.out main1 + +To this end, let us first write a nullary-functor storing references to the input matrix and to the two arrays of indices, and implementing the required \c operator()(i,j): + +\snippet nullary_indexing.cpp functor + +Then, let's create an \c indexing(A,rows,cols) function creating the nullary expression: + +\snippet nullary_indexing.cpp function + +Finally, here is an example of how this function can be used: + +\snippet nullary_indexing.cpp main1 + +This straightforward implementation is already quite powerful as the row or column index arrays can also be expressions to perform offsetting, modulo, striding, reverse, etc. + +\snippet nullary_indexing.cpp main2 + +and the output is: + +\snippet nullary_indexing.out main2 + +*/ + +} + diff --git a/gtsam/3rdparty/Eigen/doc/CustomizingEigen_Plugins.dox b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_Plugins.dox new file mode 100644 index 000000000..d88f2409b --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/CustomizingEigen_Plugins.dox @@ -0,0 +1,69 @@ +namespace Eigen { + +/** \page TopicCustomizing_Plugins Extending MatrixBase (and other classes) + +In this section we will see how to add custom methods to MatrixBase. Since all expressions and matrix types inherit MatrixBase, adding a method to MatrixBase make it immediately available to all expressions ! A typical use case is, for instance, to make Eigen compatible with another API. + +You certainly know that in C++ it is not possible to add methods to an existing class. So how that's possible ? Here the trick is to include in the declaration of MatrixBase a file defined by the preprocessor token \c EIGEN_MATRIXBASE_PLUGIN: +\code +class MatrixBase { + // ... + #ifdef EIGEN_MATRIXBASE_PLUGIN + #include EIGEN_MATRIXBASE_PLUGIN + #endif +}; +\endcode +Therefore to extend MatrixBase with your own methods you just have to create a file with your method declaration and define EIGEN_MATRIXBASE_PLUGIN before you include any Eigen's header file. + +You can extend many of the other classes used in Eigen by defining similarly named preprocessor symbols. For instance, define \c EIGEN_ARRAYBASE_PLUGIN if you want to extend the ArrayBase class. A full list of classes that can be extended in this way and the corresponding preprocessor symbols can be found on our page \ref TopicPreprocessorDirectives. + +Here is an example of an extension file for adding methods to MatrixBase: \n +\b MatrixBaseAddons.h +\code +inline Scalar at(uint i, uint j) const { return this->operator()(i,j); } +inline Scalar& at(uint i, uint j) { return this->operator()(i,j); } +inline Scalar at(uint i) const { return this->operator[](i); } +inline Scalar& at(uint i) { return this->operator[](i); } + +inline RealScalar squaredLength() const { return squaredNorm(); } +inline RealScalar length() const { return norm(); } +inline RealScalar invLength(void) const { return fast_inv_sqrt(squaredNorm()); } + +template +inline Scalar squaredDistanceTo(const MatrixBase& other) const +{ return (derived() - other.derived()).squaredNorm(); } + +template +inline RealScalar distanceTo(const MatrixBase& other) const +{ return internal::sqrt(derived().squaredDistanceTo(other)); } + +inline void scaleTo(RealScalar l) { RealScalar vl = norm(); if (vl>1e-9) derived() *= (l/vl); } + +inline Transpose transposed() {return this->transpose();} +inline const Transpose transposed() const {return this->transpose();} + +inline uint minComponentId(void) const { int i; this->minCoeff(&i); return i; } +inline uint maxComponentId(void) const { int i; this->maxCoeff(&i); return i; } + +template +void makeFloor(const MatrixBase& other) { derived() = derived().cwiseMin(other.derived()); } +template +void makeCeil(const MatrixBase& other) { derived() = derived().cwiseMax(other.derived()); } + +const CwiseBinaryOp, const Derived, const ConstantReturnType> +operator+(const Scalar& scalar) const +{ return CwiseBinaryOp, const Derived, const ConstantReturnType>(derived(), Constant(rows(),cols(),scalar)); } + +friend const CwiseBinaryOp, const ConstantReturnType, Derived> +operator+(const Scalar& scalar, const MatrixBase& mat) +{ return CwiseBinaryOp, const ConstantReturnType, Derived>(Constant(rows(),cols(),scalar), mat.derived()); } +\endcode + +Then one can the following declaration in the config.h or whatever prerequisites header file of his project: +\code +#define EIGEN_MATRIXBASE_PLUGIN "MatrixBaseAddons.h" +\endcode + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/DenseDecompositionBenchmark.dox b/gtsam/3rdparty/Eigen/doc/DenseDecompositionBenchmark.dox new file mode 100644 index 000000000..7be9c70cd --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/DenseDecompositionBenchmark.dox @@ -0,0 +1,42 @@ +namespace Eigen { + +/** \eigenManualPage DenseDecompositionBenchmark Benchmark of dense decompositions + +This page presents a speed comparison of the dense matrix decompositions offered by %Eigen for a wide range of square matrices and overconstrained problems. + +For a more general overview on the features and numerical robustness of linear solvers and decompositions, check this \link TopicLinearAlgebraDecompositions table \endlink. + +This benchmark has been run on a laptop equipped with an Intel core i7 \@ 2,6 GHz, and compiled with clang with \b AVX and \b FMA instruction sets enabled but without multi-threading. +It uses \b single \b precision \b float numbers. For double, you can get a good estimate by multiplying the timings by a factor 2. + +The square matrices are symmetric, and for the overconstrained matrices, the reported timmings include the cost to compute the symmetric covariance matrix \f$ A^T A \f$ for the first four solvers based on Cholesky and LU, as denoted by the \b * symbol (top-right corner part of the table). +Timings are in \b milliseconds, and factors are relative to the LLT decomposition which is the fastest but also the least general and robust. + + + + + + + + + + + + + + +
solver/size8x8 100x100 1000x1000 4000x4000 10000x8 10000x100 10000x1000 10000x4000
LLT0.050.425.83374.556.79 *30.15 *236.34 *3847.17 *
LDLT0.07 (x1.3)0.65 (x1.5)26.86 (x4.6)2361.18 (x6.3)6.81 (x1) *31.91 (x1.1) *252.61 (x1.1) *5807.66 (x1.5) *
PartialPivLU0.08 (x1.5)0.69 (x1.6)15.63 (x2.7)709.32 (x1.9)6.81 (x1) *31.32 (x1) *241.68 (x1) *4270.48 (x1.1) *
FullPivLU0.1 (x1.9)4.48 (x10.6)281.33 (x48.2)-6.83 (x1) *32.67 (x1.1) *498.25 (x2.1) *-
HouseholderQR0.19 (x3.5)2.18 (x5.2)23.42 (x4)1337.52 (x3.6)34.26 (x5)129.01 (x4.3)377.37 (x1.6)4839.1 (x1.3)
ColPivHouseholderQR0.23 (x4.3)2.23 (x5.3)103.34 (x17.7)9987.16 (x26.7)36.05 (x5.3)163.18 (x5.4)2354.08 (x10)37860.5 (x9.8)
CompleteOrthogonalDecomposition0.23 (x4.3)2.22 (x5.2)99.44 (x17.1)10555.3 (x28.2)35.75 (x5.3)169.39 (x5.6)2150.56 (x9.1)36981.8 (x9.6)
FullPivHouseholderQR0.23 (x4.3)4.64 (x11)289.1 (x49.6)-69.38 (x10.2)446.73 (x14.8)4852.12 (x20.5)-
JacobiSVD1.01 (x18.6)71.43 (x168.4)--113.81 (x16.7)1179.66 (x39.1)--
BDCSVD1.07 (x19.7)21.83 (x51.5)331.77 (x56.9)18587.9 (x49.6)110.53 (x16.3)397.67 (x13.2)2975 (x12.6)48593.2 (x12.6)
+ +\b *: This decomposition do not support direct least-square solving for over-constrained problems, and the reported timing include the cost to form the symmetric covariance matrix \f$ A^T A \f$. + +\b Observations: + + LLT is always the fastest solvers. + + For largely over-constrained problems, the cost of Cholesky/LU decompositions is dominated by the computation of the symmetric covariance matrix. + + For large problem sizes, only the decomposition implementing a cache-friendly blocking strategy scale well. Those include LLT, PartialPivLU, HouseholderQR, and BDCSVD. This explain why for a 4k x 4k matrix, HouseholderQR is faster than LDLT. In the future, LDLT and ColPivHouseholderQR will also implement blocking strategies. + + CompleteOrthogonalDecomposition is based on ColPivHouseholderQR and they thus achieve the same level of performance. + +The above table has been generated by the bench/dense_solvers.cpp file, feel-free to hack it to generate a table matching your hardware, compiler, and favorite problem sizes. + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/Doxyfile.in b/gtsam/3rdparty/Eigen/doc/Doxyfile.in index 696dd2af1..48bb0a8ec 100644 --- a/gtsam/3rdparty/Eigen/doc/Doxyfile.in +++ b/gtsam/3rdparty/Eigen/doc/Doxyfile.in @@ -125,7 +125,7 @@ ALWAYS_DETAILED_SEC = NO # members were ordinary class members. Constructors, destructors and assignment # operators of the base classes will not be shown. -INLINE_INHERITED_MEMB = YES +INLINE_INHERITED_MEMB = NO # If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full # path before files name in the file list and in the header files. If set @@ -206,6 +206,7 @@ TAB_SIZE = 8 # You can put \n's in the value part of an alias to insert newlines. ALIASES = "only_for_vectors=This is only for vectors (either row-vectors or column-vectors), i.e. matrices which are known at compile-time to have either one row or one column." \ + "not_reentrant=\warning This function is not re-entrant." \ "array_module=This is defined in the %Array module. \code #include \endcode" \ "cholesky_module=This is defined in the %Cholesky module. \code #include \endcode" \ "eigenvalues_module=This is defined in the %Eigenvalues module. \code #include \endcode" \ @@ -215,6 +216,7 @@ ALIASES = "only_for_vectors=This is only for vectors (either row- "lu_module=This is defined in the %LU module. \code #include \endcode" \ "qr_module=This is defined in the %QR module. \code #include \endcode" \ "svd_module=This is defined in the %SVD module. \code #include \endcode" \ + "specialfunctions_module=This is defined in the \b unsupported SpecialFunctions module. \code #include \endcode" \ "label=\bug" \ "matrixworld=*" \ "arrayworld=*" \ @@ -222,7 +224,13 @@ ALIASES = "only_for_vectors=This is only for vectors (either row- "note_about_using_kernel_to_study_multiple_solutions=If you need a complete analysis of the space of solutions, take the one solution obtained by this method and add to it elements of the kernel, as determined by kernel()." \ "note_about_checking_solutions=This method just tries to find as good a solution as possible. If you want to check whether a solution exists or if it is accurate, just call this function to get a result and then compute the error of this result, or use MatrixBase::isApprox() directly, for instance like this: \code bool a_solution_exists = (A*result).isApprox(b, precision); \endcode This method avoids dividing by zero, so that the non-existence of a solution doesn't by itself mean that you'll get \c inf or \c nan values." \ "note_try_to_help_rvo=This function returns the result by value. In order to make that efficient, it is implemented as just a return statement using a special constructor, hopefully allowing the compiler to perform a RVO (return value optimization)." \ - "nonstableyet=\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \ref Experimental \"Experimental parts of Eigen\"" + "nonstableyet=\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \ref Experimental \"Experimental parts of Eigen\"" \ + "implsparsesolverconcept=This class follows the \link TutorialSparseSolverConcept sparse solver concept \endlink." \ + "blank= " \ + "cpp11=[c++11]" \ + "cpp14=[c++14]" \ + "cpp17=[c++17]" + ALIASES += "eigenAutoToc= " ALIASES += "eigenManualPage=\defgroup" @@ -270,7 +278,7 @@ OPTIMIZE_OUTPUT_VHDL = NO # (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions # you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. -EXTENSION_MAPPING = +EXTENSION_MAPPING = .h=C++ no_extension=C++ # If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all # comments according to the Markdown format, which allows for more readable @@ -458,7 +466,7 @@ HIDE_IN_BODY_DOCS = NO # to NO (the default) then the documentation will be excluded. # Set it to YES to include the internal documentation. -INTERNAL_DOCS = NO +INTERNAL_DOCS = ${EIGEN_DOXY_INTERNAL} # If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate # file names in lower-case letters. If set to YES upper-case letters are also @@ -472,13 +480,13 @@ CASE_SENSE_NAMES = YES # will show members with their full class and namespace scopes in the # documentation. If set to YES the scope will be hidden. -HIDE_SCOPE_NAMES = YES +HIDE_SCOPE_NAMES = NO # If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen # will put a list of the files that are included by a file in the documentation # of that file. -SHOW_INCLUDE_FILES = NO +SHOW_INCLUDE_FILES = ${EIGEN_DOXY_INTERNAL} # If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen # will list include files with double quotes in the documentation @@ -544,7 +552,7 @@ STRICT_PROTO_MATCHING = NO # disable (NO) the todo list. This list is created by putting \todo # commands in the documentation. -GENERATE_TODOLIST = NO +GENERATE_TODOLIST = ${EIGEN_DOXY_INTERNAL} # The GENERATE_TESTLIST tag can be used to enable (YES) or # disable (NO) the test list. This list is created by putting \test @@ -556,7 +564,7 @@ GENERATE_TESTLIST = NO # disable (NO) the bug list. This list is created by putting \bug # commands in the documentation. -GENERATE_BUGLIST = NO +GENERATE_BUGLIST = ${EIGEN_DOXY_INTERNAL} # The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or # disable (NO) the deprecated list. This list is created by putting @@ -719,7 +727,8 @@ RECURSIVE = YES # Note that relative paths are relative to the directory from which doxygen is # run. -EXCLUDE = "${Eigen_SOURCE_DIR}/Eigen/Eigen2Support" \ +EXCLUDE = "${Eigen_SOURCE_DIR}/Eigen/src/Core/products" \ + "${Eigen_SOURCE_DIR}/Eigen/Eigen2Support" \ "${Eigen_SOURCE_DIR}/Eigen/src/Eigen2Support" \ "${Eigen_SOURCE_DIR}/doc/examples" \ "${Eigen_SOURCE_DIR}/doc/special_examples" \ @@ -800,7 +809,7 @@ EXAMPLE_RECURSIVE = NO # directories that contain image that are included in the documentation (see # the \image command). -IMAGE_PATH = +IMAGE_PATH = ${Eigen_BINARY_DIR}/doc/html # The INPUT_FILTER tag can be used to specify a program that doxygen should # invoke to filter for each input file. Doxygen will invoke the filter program @@ -864,13 +873,13 @@ STRIP_CODE_COMMENTS = YES # then for each documented function all documented # functions referencing it will be listed. -REFERENCED_BY_RELATION = YES +REFERENCED_BY_RELATION = NO # If the REFERENCES_RELATION tag is set to YES # then for each documented function all documented entities # called/used by that function will be listed. -REFERENCES_RELATION = YES +REFERENCES_RELATION = NO # If the REFERENCES_LINK_SOURCE tag is set to YES (the default) # and SOURCE_BROWSER tag is set to YES, then the hyperlinks from @@ -1581,9 +1590,14 @@ PREDEFINED = EIGEN_EMPTY_STRUCT \ EIGEN_VECTORIZE \ EIGEN_QT_SUPPORT \ EIGEN_STRONG_INLINE=inline \ - "EIGEN2_SUPPORT_STAGE=99" \ + EIGEN_DEVICE_FUNC= \ "EIGEN_MAKE_CWISE_BINARY_OP(METHOD,FUNCTOR)=template const CwiseBinaryOp, const Derived, const OtherDerived> METHOD(const EIGEN_CURRENT_STORAGE_BASE_CLASS &other) const;" \ - "EIGEN_CWISE_PRODUCT_RETURN_TYPE(LHS,RHS)=CwiseBinaryOp, const LHS, const RHS>" + "EIGEN_CWISE_PRODUCT_RETURN_TYPE(LHS,RHS)=CwiseBinaryOp, const LHS, const RHS>"\ + "EIGEN_CAT2(a,b)= a ## b"\ + "EIGEN_CAT(a,b)=EIGEN_CAT2(a,b)"\ + "EIGEN_CWISE_BINARY_RETURN_TYPE(LHS,RHS,OPNAME)=CwiseBinaryOp, const LHS, const RHS>"\ + DOXCOMMA=, + # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then # this tag can be used to specify a list of macro names that should be expanded. @@ -1599,7 +1613,15 @@ EXPAND_AS_DEFINED = EIGEN_MAKE_TYPEDEFS \ EIGEN_CURRENT_STORAGE_BASE_CLASS \ EIGEN_MATHFUNC_IMPL \ _EIGEN_GENERIC_PUBLIC_INTERFACE \ - EIGEN2_SUPPORT + EIGEN_ARRAY_DECLARE_GLOBAL_UNARY \ + EIGEN_EMPTY \ + EIGEN_EULER_ANGLES_TYPEDEFS \ + EIGEN_EULER_ANGLES_SINGLE_TYPEDEF \ + EIGEN_EULER_SYSTEM_TYPEDEF \ + EIGEN_DOC_UNARY_ADDONS \ + EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL \ + EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF + # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then # doxygen's preprocessor will remove all references to function-like macros diff --git a/gtsam/3rdparty/Eigen/doc/FixedSizeVectorizable.dox b/gtsam/3rdparty/Eigen/doc/FixedSizeVectorizable.dox index 8ae135173..49e38af76 100644 --- a/gtsam/3rdparty/Eigen/doc/FixedSizeVectorizable.dox +++ b/gtsam/3rdparty/Eigen/doc/FixedSizeVectorizable.dox @@ -4,7 +4,7 @@ namespace Eigen { The goal of this page is to explain what we mean by "fixed-size vectorizable". -\section summary Executive Summary +\section FixedSizeVectorizable_summary Executive Summary An Eigen object is called "fixed-size vectorizable" if it has fixed size and that size is a multiple of 16 bytes. @@ -21,7 +21,7 @@ Examples include: \li Eigen::Quaterniond \li Eigen::Quaternionf -\section explanation Explanation +\section FixedSizeVectorizable_explanation Explanation First, "fixed-size" should be clear: an Eigen object has fixed size if its number of rows and its number of columns are fixed at compile-time. So for example Matrix3f has fixed size, but MatrixXf doesn't (the opposite of fixed-size is dynamic-size). diff --git a/gtsam/3rdparty/Eigen/doc/InplaceDecomposition.dox b/gtsam/3rdparty/Eigen/doc/InplaceDecomposition.dox new file mode 100644 index 000000000..cb1c6d413 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/InplaceDecomposition.dox @@ -0,0 +1,115 @@ +namespace Eigen { + +/** \eigenManualPage InplaceDecomposition Inplace matrix decompositions + +Starting from %Eigen 3.3, the LU, Cholesky, and QR decompositions can operate \em inplace, that is, directly within the given input matrix. +This feature is especially useful when dealing with huge matrices, and or when the available memory is very limited (embedded systems). + +To this end, the respective decomposition class must be instantiated with a Ref<> matrix type, and the decomposition object must be constructed with the input matrix as argument. As an example, let us consider an inplace LU decomposition with partial pivoting. + +Let's start with the basic inclusions, and declaration of a 2x2 matrix \c A: + + + + + + + +
codeoutput
\snippet TutorialInplaceLU.cpp init + \snippet TutorialInplaceLU.out init +
+ +No surprise here! Then, let's declare our inplace LU object \c lu, and check the content of the matrix \c A: + + + + + + +
\snippet TutorialInplaceLU.cpp declaration + \snippet TutorialInplaceLU.out declaration +
+ +Here, the \c lu object computes and stores the \c L and \c U factors within the memory held by the matrix \c A. +The coefficients of \c A have thus been destroyed during the factorization, and replaced by the L and U factors as one can verify: + + + + + + +
\snippet TutorialInplaceLU.cpp matrixLU + \snippet TutorialInplaceLU.out matrixLU +
+ +Then, one can use the \c lu object as usual, for instance to solve the Ax=b problem: + + + + + +
\snippet TutorialInplaceLU.cpp solve + \snippet TutorialInplaceLU.out solve +
+ +Here, since the content of the original matrix \c A has been lost, we had to declared a new matrix \c A0 to verify the result. + +Since the memory is shared between \c A and \c lu, modifying the matrix \c A will make \c lu invalid. +This can easily be verified by modifying the content of \c A and trying to solve the initial problem again: + + + + + + +
\snippet TutorialInplaceLU.cpp modifyA + \snippet TutorialInplaceLU.out modifyA +
+ +Note that there is no shared pointer under the hood, it is the \b responsibility \b of \b the \b user to keep the input matrix \c A in life as long as \c lu is living. + +If one wants to update the factorization with the modified A, one has to call the compute method as usual: + + + + + +
\snippet TutorialInplaceLU.cpp recompute + \snippet TutorialInplaceLU.out recompute +
+ +Note that calling compute does not change the memory which is referenced by the \c lu object. Therefore, if the compute method is called with another matrix \c A1 different than \c A, then the content of \c A1 won't be modified. This is still the content of \c A that will be used to store the L and U factors of the matrix \c A1. +This can easily be verified as follows: + + + + + +
\snippet TutorialInplaceLU.cpp recompute_bis0 + \snippet TutorialInplaceLU.out recompute_bis0 +
+The matrix \c A1 is unchanged, and one can thus solve A1*x=b, and directly check the residual without any copy of \c A1: + + + + + +
\snippet TutorialInplaceLU.cpp recompute_bis1 + \snippet TutorialInplaceLU.out recompute_bis1 +
+ + +Here is the list of matrix decompositions supporting this inplace mechanism: + +- class LLT +- class LDLT +- class PartialPivLU +- class FullPivLU +- class HouseholderQR +- class ColPivHouseholderQR +- class FullPivHouseholderQR +- class CompleteOrthogonalDecomposition + +*/ + +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/LeastSquares.dox b/gtsam/3rdparty/Eigen/doc/LeastSquares.dox new file mode 100644 index 000000000..e2191a22f --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/LeastSquares.dox @@ -0,0 +1,70 @@ +namespace Eigen { + +/** \eigenManualPage LeastSquares Solving linear least squares systems + +This page describes how to solve linear least squares systems using %Eigen. An overdetermined system +of equations, say \a Ax = \a b, has no solutions. In this case, it makes sense to search for the +vector \a x which is closest to being a solution, in the sense that the difference \a Ax - \a b is +as small as possible. This \a x is called the least square solution (if the Euclidean norm is used). + +The three methods discussed on this page are the SVD decomposition, the QR decomposition and normal +equations. Of these, the SVD decomposition is generally the most accurate but the slowest, normal +equations is the fastest but least accurate, and the QR decomposition is in between. + +\eigenAutoToc + + +\section LeastSquaresSVD Using the SVD decomposition + +The \link JacobiSVD::solve() solve() \endlink method in the JacobiSVD class can be directly used to +solve linear squares systems. It is not enough to compute only the singular values (the default for +this class); you also need the singular vectors but the thin SVD decomposition suffices for +computing least squares solutions: + + + + + + + +
Example:Output:
\include TutorialLinAlgSVDSolve.cpp \verbinclude TutorialLinAlgSVDSolve.out
+ +This is example from the page \link TutorialLinearAlgebra Linear algebra and decompositions \endlink. + + +\section LeastSquaresQR Using the QR decomposition + +The solve() method in QR decomposition classes also computes the least squares solution. There are +three QR decomposition classes: HouseholderQR (no pivoting, so fast but unstable), +ColPivHouseholderQR (column pivoting, thus a bit slower but more accurate) and FullPivHouseholderQR +(full pivoting, so slowest and most stable). Here is an example with column pivoting: + + + + + + + +
Example:Output:
\include LeastSquaresQR.cpp \verbinclude LeastSquaresQR.out
+ + +\section LeastSquaresNormalEquations Using normal equations + +Finding the least squares solution of \a Ax = \a b is equivalent to solving the normal equation +ATAx = ATb. This leads to the following code + + + + + + + +
Example:Output:
\include LeastSquaresNormalEquations.cpp \verbinclude LeastSquaresNormalEquations.out
+ +If the matrix \a A is ill-conditioned, then this is not a good method, because the condition number +of ATA is the square of the condition number of \a A. This means that you +lose twice as many digits using normal equation than if you use the other methods. + +*/ + +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/Manual.dox b/gtsam/3rdparty/Eigen/doc/Manual.dox index 52427f066..342b145fd 100644 --- a/gtsam/3rdparty/Eigen/doc/Manual.dox +++ b/gtsam/3rdparty/Eigen/doc/Manual.dox @@ -3,19 +3,32 @@ namespace Eigen { +/** \page UserManual_CustomizingEigen Extending/Customizing Eigen + %Eigen can be extended in several ways, for instance, by defining global methods, by inserting custom methods within main %Eigen's classes through the \ref TopicCustomizing_Plugins "plugin" mechanism, by adding support to \ref TopicCustomizing_CustomScalar "custom scalar types" etc. See below for the respective sub-topics. + - \subpage TopicCustomizing_Plugins + - \subpage TopicCustomizing_InheritingMatrix + - \subpage TopicCustomizing_CustomScalar + - \subpage TopicCustomizing_NullaryExpr + - \subpage TopicNewExpressionType + \sa \ref TopicPreprocessorDirectives +*/ + + /** \page UserManual_Generalities General topics - \subpage Eigen2ToEigen3 - \subpage TopicFunctionTakingEigenTypes - \subpage TopicPreprocessorDirectives - \subpage TopicAssertions - - \subpage TopicCustomizingEigen - \subpage TopicMultiThreading + - \subpage TopicUsingBlasLapack - \subpage TopicUsingIntelMKL + - \subpage TopicCUDA - \subpage TopicPitfalls - \subpage TopicTemplateKeyword - \subpage UserManual_UnderstandingEigen + - \subpage TopicCMakeGuide */ - + /** \page UserManual_UnderstandingEigen Understanding Eigen - \subpage TopicInsideEigenExample - \subpage TopicClassHierarchy @@ -57,6 +70,8 @@ namespace Eigen { \ingroup DenseMatrixManipulation_chapter */ /** \addtogroup TutorialMapClass \ingroup DenseMatrixManipulation_chapter */ +/** \addtogroup TutorialReshapeSlicing + \ingroup DenseMatrixManipulation_chapter */ /** \addtogroup TopicAliasing \ingroup DenseMatrixManipulation_chapter */ /** \addtogroup TopicStorageOrders @@ -86,6 +101,9 @@ namespace Eigen { /** \addtogroup Householder_Module \ingroup DenseMatrixManipulation_Reference */ +/** \addtogroup CoeffwiseMathFunctions + \ingroup DenseMatrixManipulation_chapter */ + /** \addtogroup QuickRefPage \ingroup DenseMatrixManipulation_chapter */ @@ -97,6 +115,12 @@ namespace Eigen { \ingroup DenseLinearSolvers_chapter */ /** \addtogroup TopicLinearAlgebraDecompositions \ingroup DenseLinearSolvers_chapter */ +/** \addtogroup LeastSquares + \ingroup DenseLinearSolvers_chapter */ +/** \addtogroup InplaceDecomposition + \ingroup DenseLinearSolvers_chapter */ +/** \addtogroup DenseDecompositionBenchmark + \ingroup DenseLinearSolvers_chapter */ /** \addtogroup DenseLinearSolvers_Reference \ingroup DenseLinearSolvers_chapter */ @@ -159,4 +183,7 @@ namespace Eigen { \ingroup Geometry_Reference */ /** \addtogroup Splines_Module \ingroup Geometry_Reference */ + +/** \internal \brief Namespace containing low-level routines from the %Eigen library. */ +namespace internal {} } diff --git a/gtsam/3rdparty/Eigen/doc/MatrixfreeSolverExample.dox b/gtsam/3rdparty/Eigen/doc/MatrixfreeSolverExample.dox new file mode 100644 index 000000000..3efa292b5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/MatrixfreeSolverExample.dox @@ -0,0 +1,20 @@ + +namespace Eigen { + +/** + +\eigenManualPage MatrixfreeSolverExample Matrix-free solvers + +Iterative solvers such as ConjugateGradient and BiCGSTAB can be used in a matrix free context. To this end, user must provide a wrapper class inheriting EigenBase<> and implementing the following methods: + - \c Index \c rows() and \c Index \c cols(): returns number of rows and columns respectively + - \c operator* with your type and an %Eigen dense column vector (its actual implementation goes in a specialization of the internal::generic_product_impl class) + +\c Eigen::internal::traits<> must also be specialized for the wrapper type. + +Here is a complete example wrapping an Eigen::SparseMatrix: +\include matrixfree_cg.cpp +Output: \verbinclude matrixfree_cg.out + +*/ + +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/NewExpressionType.dox b/gtsam/3rdparty/Eigen/doc/NewExpressionType.dox new file mode 100644 index 000000000..c2f243312 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/NewExpressionType.dox @@ -0,0 +1,143 @@ +namespace Eigen { + +/** \page TopicNewExpressionType Adding a new expression type + + +\warning +Disclaimer: this page is tailored to very advanced users who are not afraid of dealing with some %Eigen's internal aspects. +In most cases, a custom expression can be avoided by either using custom \ref MatrixBase::unaryExpr "unary" or \ref MatrixBase::binaryExpr "binary" functors, +while extremely complex matrix manipulations can be achieved by a nullary functors as described in the \ref TopicCustomizing_NullaryExpr "previous page". + +This page describes with the help of an example how to implement a new +light-weight expression type in %Eigen. This consists of three parts: +the expression type itself, a traits class containing compile-time +information about the expression, and the evaluator class which is +used to evaluate the expression to a matrix. + +\b TO \b DO: Write a page explaining the design, with details on +vectorization etc., and refer to that page here. + + +\eigenAutoToc + +\section TopicSetting The setting + +A circulant matrix is a matrix where each column is the same as the +column to the left, except that it is cyclically shifted downwards. +For example, here is a 4-by-4 circulant matrix: +\f[ \begin{bmatrix} + 1 & 8 & 4 & 2 \\ + 2 & 1 & 8 & 4 \\ + 4 & 2 & 1 & 8 \\ + 8 & 4 & 2 & 1 +\end{bmatrix} \f] +A circulant matrix is uniquely determined by its first column. We wish +to write a function \c makeCirculant which, given the first column, +returns an expression representing the circulant matrix. + +For simplicity, we restrict the \c makeCirculant function to dense +matrices. It may make sense to also allow arrays, or sparse matrices, +but we will not do so here. We also do not want to support +vectorization. + + +\section TopicPreamble Getting started + +We will present the file implementing the \c makeCirculant function +part by part. We start by including the appropriate header files and +forward declaring the expression class, which we will call +\c Circulant. The \c makeCirculant function will return an object of +this type. The class \c Circulant is in fact a class template; the +template argument \c ArgType refers to the type of the vector passed +to the \c makeCirculant function. + +\include make_circulant.cpp.preamble + + +\section TopicTraits The traits class + +For every expression class \c X, there should be a traits class +\c Traits in the \c Eigen::internal namespace containing +information about \c X known as compile time. + +As explained in \ref TopicSetting, we designed the \c Circulant +expression class to refer to dense matrices. The entries of the +circulant matrix have the same type as the entries of the vector +passed to the \c makeCirculant function. The type used to index the +entries is also the same. Again for simplicity, we will only return +column-major matrices. Finally, the circulant matrix is a square +matrix (number of rows equals number of columns), and the number of +rows equals the number of rows of the column vector passed to the +\c makeCirculant function. If this is a dynamic-size vector, then the +size of the circulant matrix is not known at compile-time. + +This leads to the following code: + +\include make_circulant.cpp.traits + + +\section TopicExpression The expression class + +The next step is to define the expression class itself. In our case, +we want to inherit from \c MatrixBase in order to expose the interface +for dense matrices. In the constructor, we check that we are passed a +column vector (see \ref TopicAssertions) and we store the vector from +which we are going to build the circulant matrix in the member +variable \c m_arg. Finally, the expression class should compute the +size of the corresponding circulant matrix. As explained above, this +is a square matrix with as many columns as the vector used to +construct the matrix. + +\b TO \b DO: What about the \c Nested typedef? It seems to be +necessary; is this only temporary? + +\include make_circulant.cpp.expression + + +\section TopicEvaluator The evaluator + +The last big fragment implements the evaluator for the \c Circulant +expression. The evaluator computes the entries of the circulant +matrix; this is done in the \c .coeff() member function. The entries +are computed by finding the corresponding entry of the vector from +which the circulant matrix is constructed. Getting this entry may +actually be non-trivial when the circulant matrix is constructed from +a vector which is given by a complicated expression, so we use the +evaluator which corresponds to the vector. + +The \c CoeffReadCost constant records the cost of computing an entry +of the circulant matrix; we ignore the index computation and say that +this is the same as the cost of computing an entry of the vector from +which the circulant matrix is constructed. + +In the constructor, we save the evaluator for the column vector which +defined the circulant matrix. We also save the size of that vector; +remember that we can query an expression object to find the size but +not the evaluator. + +\include make_circulant.cpp.evaluator + + +\section TopicEntry The entry point + +After all this, the \c makeCirculant function is very simple. It +simply creates an expression object and returns it. + +\include make_circulant.cpp.entry + + +\section TopicMain A simple main function for testing + +Finally, a short \c main function that shows how the \c makeCirculant +function can be called. + +\include make_circulant.cpp.main + +If all the fragments are combined, the following output is produced, +showing that the program works as expected: + +\include make_circulant.out + +*/ +} + diff --git a/gtsam/3rdparty/Eigen/doc/Overview.dox b/gtsam/3rdparty/Eigen/doc/Overview.dox index 9ab96233a..dbb49bd21 100644 --- a/gtsam/3rdparty/Eigen/doc/Overview.dox +++ b/gtsam/3rdparty/Eigen/doc/Overview.dox @@ -17,7 +17,9 @@ You're a MatLab user? There is also a short AS The \b main \b documentation is organized into \em chapters covering different domains of features. They are themselves composed of \em user \em manual pages describing the different features in a comprehensive way, and \em reference pages that gives you access to the API documentation through the related Eigen's \em modules and \em classes. -Under the \subpage UserManual_Generalities section, you will find documentation on more general topics such as preprocessor directives, controlling assertions, multi-threading, MKL support, some Eigen's internal insights, and much more... +Under the \subpage UserManual_CustomizingEigen section, you will find discussions and examples on extending %Eigen's features and supporting custom scalar types. + +Under the \subpage UserManual_Generalities section, you will find documentation on more general topics such as preprocessor directives, controlling assertions, multi-threading, MKL support, some Eigen's internal insights, and much more... Finally, do not miss the search engine, useful to quickly get to the documentation of a given class or function. diff --git a/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox b/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox index cfaba35d8..f01b39aec 100644 --- a/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox +++ b/gtsam/3rdparty/Eigen/doc/PreprocessorDirectives.dox @@ -5,7 +5,7 @@ namespace Eigen { You can control some aspects of %Eigen by defining the preprocessor tokens using \c \#define. These macros should be defined before any %Eigen headers are included. Often they are best set in the project options. -This page lists the preprocesor tokens recognised by %Eigen. +This page lists the preprocessor tokens recognized by %Eigen. \eigenAutoToc @@ -18,25 +18,67 @@ one option, and other parts (or libraries that you use) are compiled with anothe fail to link or exhibit subtle bugs. Nevertheless, these options can be useful for people who know what they are doing. - - \b EIGEN2_SUPPORT - if defined, enables the Eigen2 compatibility mode. This is meant to ease the transition - of Eigen2 to Eigen3 (see \ref Eigen2ToEigen3). Not defined by default. - - \b EIGEN2_SUPPORT_STAGEnn_xxx (for various values of nn and xxx) - staged migration path from Eigen2 to - Eigen3; see \ref Eigen2SupportModes. + - \b EIGEN2_SUPPORT and \b EIGEN2_SUPPORT_STAGEnn_xxx are disabled starting from the 3.3 release. + Defining one of these will raise a compile-error. If you need to compile Eigen2 code, + check this site. - \b EIGEN_DEFAULT_DENSE_INDEX_TYPE - the type for column and row indices in matrices, vectors and array (DenseBase::Index). Set to \c std::ptrdiff_t by default. - \b EIGEN_DEFAULT_IO_FORMAT - the IOFormat to use when printing a matrix if no %IOFormat is specified. Defaults to the %IOFormat constructed by the default constructor IOFormat::IOFormat(). - \b EIGEN_INITIALIZE_MATRICES_BY_ZERO - if defined, all entries of newly constructed matrices and arrays are initialized to zero, as are new entries in matrices and arrays after resizing. Not defined by default. + \warning The unary (resp. binary) constructor of \c 1x1 (resp. \c 2x1 or \c 1x2) fixed size matrices is + always interpreted as an initialization constructor where the argument(s) are the coefficient values + and not the sizes. For instance, \code Vector2d v(2,1); \endcode will create a vector with coeficients [2,1], + and \b not a \c 2x1 vector initialized with zeros (i.e., [0,0]). If such cases might occur, then it is + recommended to use the default constructor with a explicit call to resize: + \code + Matrix v; + v.resize(size); + Matrix m; + m.resize(rows,cols); + \endcode - \b EIGEN_INITIALIZE_MATRICES_BY_NAN - if defined, all entries of newly constructed matrices and arrays are initialized to NaN, as are new entries in matrices and arrays after resizing. This option is especially useful for debugging purpose, though a memory tool like valgrind is preferable. Not defined by default. + \warning See the documentation of \c EIGEN_INITIALIZE_MATRICES_BY_ZERO for a discussion on a limitations + of these macros when applied to \c 1x1, \c 1x2, and \c 2x1 fixed-size matrices. - \b EIGEN_NO_AUTOMATIC_RESIZING - if defined, the matrices (or arrays) on both sides of an assignment a = b have to be of the same size; otherwise, %Eigen automatically resizes \c a so that it is of the correct size. Not defined by default. +\section TopicPreprocessorDirectivesCppVersion C++ standard features + +By default, %Eigen strive to automatically detect and enable langage features at compile-time based on +the information provided by the compiler. + + - \b EIGEN_MAX_CPP_VER - disables usage of C++ features requiring a version greater than EIGEN_MAX_CPP_VER. + Possible values are: 03, 11, 14, 17, etc. If not defined (the default), %Eigen enables all features supported + by the compiler. + +Individual features can be explicitly enabled or disabled by defining the following token to 0 or 1 respectively. +For instance, one might limit the C++ version to C++03 by defining EIGEN_MAX_CPP_VER=03, but still enable C99 math +functions by defining EIGEN_HAS_C99_MATH=1. + + - \b EIGEN_HAS_C99_MATH - controls the usage of C99 math functions such as erf, erfc, lgamma, etc. + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_CXX11_MATH - controls the implementation of some functions such as round, logp1, isinf, isnan, etc. + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_RVALUE_REFERENCES - defines whetehr rvalue references are supported + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_STD_RESULT_OF - defines whether std::result_of is supported + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_VARIADIC_TEMPLATES - defines whether variadic templates are supported + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_CONSTEXPR - defines whether relaxed const expression are supported + Automatic detection disabled if EIGEN_MAX_CPP_VER<14. + - \b EIGEN_HAS_CXX11_CONTAINERS - defines whether STL's containers follows C++11 specifications + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + - \b EIGEN_HAS_CXX11_NOEXCEPT - defines whether noexcept is supported + Automatic detection disabled if EIGEN_MAX_CPP_VER<11. + \section TopicPreprocessorDirectivesAssertions Assertions The %Eigen library contains many assertions to guard against programming errors, both at compile time and at @@ -55,32 +97,39 @@ run time. However, these assertions do cost time and can thus be turned off. \section TopicPreprocessorDirectivesPerformance Alignment, vectorization and performance tweaking - - \b EIGEN_MALLOC_ALREADY_ALIGNED - Can be set to 0 or 1 to tell whether default system malloc already + - \b \c EIGEN_MALLOC_ALREADY_ALIGNED - Can be set to 0 or 1 to tell whether default system \c malloc already returns aligned buffers. In not defined, then this information is automatically deduced from the compiler and system preprocessor tokens. - - \b EIGEN_DONT_ALIGN - disables alignment completely. %Eigen will not try to align its objects and does not - expect that any objects passed to it are aligned. This will turn off vectorization. Not defined by default. - - \b EIGEN_DONT_ALIGN_STATICALLY - disables alignment of arrays on the stack. Not defined by default, unless - \c EIGEN_DONT_ALIGN is defined. - - \b EIGEN_DONT_PARALLELIZE - if defined, this disables multi-threading. This is only relevant if you enabled OpenMP. + - \b \c EIGEN_MAX_ALIGN_BYTES - Must be a power of two, or 0. Defines an upper bound on the memory boundary in bytes on which dynamically and statically allocated data may be aligned by %Eigen. If not defined, a default value is automatically computed based on architecture, compiler, and OS. + This option is typically used to enforce binary compatibility between code/libraries compiled with different SIMD options. For instance, one may compile AVX code and enforce ABI compatibility with existing SSE code by defining \c EIGEN_MAX_ALIGN_BYTES=16. In the other way round, since by default AVX implies 32 bytes alignment for best performance, one can compile SSE code to be ABI compatible with AVX code by defining \c EIGEN_MAX_ALIGN_BYTES=32. + - \b \c EIGEN_MAX_STATIC_ALIGN_BYTES - Same as \c EIGEN_MAX_ALIGN_BYTES but for statically allocated data only. By default, if only \c EIGEN_MAX_ALIGN_BYTES is defined, then \c EIGEN_MAX_STATIC_ALIGN_BYTES == \c EIGEN_MAX_ALIGN_BYTES, otherwise a default value is automatically computed based on architecture, compiler, and OS (can be smaller than the default value of EIGEN_MAX_ALIGN_BYTES on architectures that do not support stack alignment). + Let us emphasize that \c EIGEN_MAX_*_ALIGN_BYTES define only a diserable upper bound. In practice data is aligned to largest power-of-two common divisor of \c EIGEN_MAX_STATIC_ALIGN_BYTES and the size of the data, such that memory is not wasted. + - \b \c EIGEN_DONT_PARALLELIZE - if defined, this disables multi-threading. This is only relevant if you enabled OpenMP. See \ref TopicMultiThreading for details. - \b EIGEN_DONT_VECTORIZE - disables explicit vectorization when defined. Not defined by default, unless alignment is disabled by %Eigen's platform test or the user defining \c EIGEN_DONT_ALIGN. - - \b EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. This currently + - \b \c EIGEN_UNALIGNED_VECTORIZE - disables/enables vectorization with unaligned stores. Default is 1 (enabled). + If set to 0 (disabled), then expression for which the destination cannot be aligned are not vectorized (e.g., unaligned + small fixed size vectors or matrices) + - \b \c EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. This currently enables the SSE vectorization of sin() and cos(), and speedups sqrt() for single precision. Defined to 1 by default. Define it to 0 to disable. - - \b EIGEN_UNROLLING_LIMIT - defines the size of a loop to enable meta unrolling. Set it to zero to disable + - \b \c EIGEN_UNROLLING_LIMIT - defines the size of a loop to enable meta unrolling. Set it to zero to disable unrolling. The size of a loop here is expressed in %Eigen's own notion of "number of FLOPS", it does not correspond to the number of iterations or the number of instructions. The default is value 100. - - \b EIGEN_STACK_ALLOCATION_LIMIT - defines the maximum bytes for a buffer to be allocated on the stack. For internal + - \b \c EIGEN_STACK_ALLOCATION_LIMIT - defines the maximum bytes for a buffer to be allocated on the stack. For internal temporary buffers, dynamic memory allocation is employed as a fall back. For fixed-size matrices or arrays, exceeding this threshold raises a compile time assertion. Use 0 to set no limit. Default is 128 KB. + - \c EIGEN_DONT_ALIGN - Deprecated, it is a synonym for \c EIGEN_MAX_ALIGN_BYTES=0. It disables alignment completely. %Eigen will not try to align its objects and does not expect that any objects passed to it are aligned. This will turn off vectorization if \b EIGEN_UNALIGNED_VECTORIZE=1. Not defined by default. + - \c EIGEN_DONT_ALIGN_STATICALLY - Deprecated, it is a synonym for \c EIGEN_MAX_STATIC_ALIGN_BYTES=0. It disables alignment of arrays on the stack. Not defined by default, unless \c EIGEN_DONT_ALIGN is defined. + + \section TopicPreprocessorDirectivesPlugins Plugins It is possible to add new methods to many fundamental classes in %Eigen by writing a plugin. As explained in -the section \ref ExtendingMatrixBase, the plugin is specified by defining a \c EIGEN_xxx_PLUGIN macro. The +the section \ref TopicCustomizing_Plugins, the plugin is specified by defining a \c EIGEN_xxx_PLUGIN macro. The following macros are supported; none of them are defined by default. - \b EIGEN_ARRAY_PLUGIN - filename of plugin for extending the Array class. @@ -92,6 +141,7 @@ following macros are supported; none of them are defined by default. - \b EIGEN_MATRIXBASE_PLUGIN - filename of plugin for extending the MatrixBase class. - \b EIGEN_PLAINOBJECTBASE_PLUGIN - filename of plugin for extending the PlainObjectBase class. - \b EIGEN_MAPBASE_PLUGIN - filename of plugin for extending the MapBase class. + - \b EIGEN_QUATERNION_PLUGIN - filename of plugin for extending the Quaternion class. - \b EIGEN_QUATERNIONBASE_PLUGIN - filename of plugin for extending the QuaternionBase class. - \b EIGEN_SPARSEMATRIX_PLUGIN - filename of plugin for extending the SparseMatrix class. - \b EIGEN_SPARSEMATRIXBASE_PLUGIN - filename of plugin for extending the SparseMatrixBase class. diff --git a/gtsam/3rdparty/Eigen/doc/QuickReference.dox b/gtsam/3rdparty/Eigen/doc/QuickReference.dox index a4be0f68a..44f5410db 100644 --- a/gtsam/3rdparty/Eigen/doc/QuickReference.dox +++ b/gtsam/3rdparty/Eigen/doc/QuickReference.dox @@ -13,17 +13,17 @@ The Eigen library is divided in a Core module and several additional modules. Ea - + - - - - - - - - - + + + + + + + + +
ModuleHeader fileContents
\link Core_Module Core \endlink\code#include \endcodeMatrix and Array classes, basic linear algebra (including triangular and selfadjoint products), array manipulation
\link Core_Module Core \endlink\code#include \endcodeMatrix and Array classes, basic linear algebra (including triangular and selfadjoint products), array manipulation
\link Geometry_Module Geometry \endlink\code#include \endcodeTransform, Translation, Scaling, Rotation2D and 3D rotations (Quaternion, AngleAxis)
\link LU_Module LU \endlink\code#include \endcodeInverse, determinant, LU decompositions with solver (FullPivLU, PartialPivLU)
\link Cholesky_Module Cholesky \endlink\code#include \endcodeLLT and LDLT Cholesky factorization with solver
\link Householder_Module Householder \endlink\code#include \endcodeHouseholder transformations; this module is used by several linear algebra modules
\link SVD_Module SVD \endlink\code#include \endcodeSVD decomposition with least-squares solver (JacobiSVD)
\link QR_Module QR \endlink\code#include \endcodeQR decomposition with solver (HouseholderQR, ColPivHouseholderQR, FullPivHouseholderQR)
\link Eigenvalues_Module Eigenvalues \endlink\code#include \endcodeEigenvalue, eigenvector decompositions (EigenSolver, SelfAdjointEigenSolver, ComplexEigenSolver)
\link Sparse_modules Sparse \endlink\code#include \endcode%Sparse matrix storage and related basic linear algebra (SparseMatrix, DynamicSparseMatrix, SparseVector)
\code#include \endcodeIncludes Core, Geometry, LU, Cholesky, SVD, QR, and Eigenvalues header files
\code#include \endcodeIncludes %Dense and %Sparse header files (the whole Eigen library)
\link LU_Module LU \endlink\code#include \endcodeInverse, determinant, LU decompositions with solver (FullPivLU, PartialPivLU)
\link Cholesky_Module Cholesky \endlink\code#include \endcodeLLT and LDLT Cholesky factorization with solver
\link Householder_Module Householder \endlink\code#include \endcodeHouseholder transformations; this module is used by several linear algebra modules
\link SVD_Module SVD \endlink\code#include \endcodeSVD decompositions with least-squares solver (JacobiSVD, BDCSVD)
\link QR_Module QR \endlink\code#include \endcodeQR decomposition with solver (HouseholderQR, ColPivHouseholderQR, FullPivHouseholderQR)
\link Eigenvalues_Module Eigenvalues \endlink\code#include \endcodeEigenvalue, eigenvector decompositions (EigenSolver, SelfAdjointEigenSolver, ComplexEigenSolver)
\link Sparse_Module Sparse \endlink\code#include \endcode%Sparse matrix storage and related basic linear algebra (SparseMatrix, SparseVector) \n (see \ref SparseQuickRefPage for details on sparse modules)
\code#include \endcodeIncludes Core, Geometry, LU, Cholesky, SVD, QR, and Eigenvalues header files
\code#include \endcodeIncludes %Dense and %Sparse header files (the whole Eigen library)
top @@ -340,7 +340,7 @@ mat1 = mat2.adjoint(); mat1.adjointInPlace(); \endcode -\link MatrixBase::dot() dot \endlink product \n inner product \matrixworld\code +\link MatrixBase::dot dot \endlink product \n inner product \matrixworld\code scalar = vec1.dot(vec2); scalar = col1.adjoint() * col2; scalar = (col1.adjoint() * col2).value();\endcode @@ -364,32 +364,10 @@ vec3 = vec1.cross(vec2);\endcode top \section QuickRef_Coeffwise Coefficient-wise \& Array operators -Coefficient-wise operators for matrices and vectors: - - - -
Matrix API \matrixworldVia Array conversions
\code -mat1.cwiseMin(mat2) -mat1.cwiseMax(mat2) -mat1.cwiseAbs2() -mat1.cwiseAbs() -mat1.cwiseSqrt() -mat1.cwiseProduct(mat2) -mat1.cwiseQuotient(mat2)\endcode -\code -mat1.array().min(mat2.array()) -mat1.array().max(mat2.array()) -mat1.array().abs2() -mat1.array().abs() -mat1.array().sqrt() -mat1.array() * mat2.array() -mat1.array() / mat2.array() -\endcode
-It is also very simple to apply any user defined function \c foo using DenseBase::unaryExpr together with std::ptr_fun: -\code mat1.unaryExpr(std::ptr_fun(foo))\endcode - -Array operators:\arrayworld +In addition to the aforementioned operators, Eigen supports numerous coefficient-wise operator and functions. +Most of them unambiguously makes sense in array-world\arrayworld. The following operators are readily available for arrays, +or available through .array() for vectors and matrices: -
Arithmetic operators\code @@ -400,28 +378,108 @@ array1 + scalar array1 - scalar array1 += scalar array1 -= scalar array1 < array2 array1 > array2 array1 < scalar array1 > scalar array1 <= array2 array1 >= array2 array1 <= scalar array1 >= scalar array1 == array2 array1 != array2 array1 == scalar array1 != scalar +array1.min(array2) array1.max(array2) array1.min(scalar) array1.max(scalar) \endcode
Trigo, power, and \n misc functions \n and the STL variants\code -array1.min(array2) -array1.max(array2) +
Trigo, power, and \n misc functions \n and the STL-like variants\code array1.abs2() array1.abs() abs(array1) array1.sqrt() sqrt(array1) array1.log() log(array1) +array1.log10() log10(array1) array1.exp() exp(array1) -array1.pow(exponent) pow(array1,exponent) +array1.pow(array2) pow(array1,array2) +array1.pow(scalar) pow(array1,scalar) + pow(scalar,array2) array1.square() array1.cube() array1.inverse() + array1.sin() sin(array1) array1.cos() cos(array1) array1.tan() tan(array1) array1.asin() asin(array1) array1.acos() acos(array1) +array1.atan() atan(array1) +array1.sinh() sinh(array1) +array1.cosh() cosh(array1) +array1.tanh() tanh(array1) +array1.arg() arg(array1) + +array1.floor() floor(array1) +array1.ceil() ceil(array1) +array1.round() round(aray1) + +array1.isFinite() isfinite(array1) +array1.isInf() isinf(array1) +array1.isNaN() isnan(array1) \endcode
+ +The following coefficient-wise operators are available for all kind of expressions (matrices, vectors, and arrays), and for both real or complex scalar types: + + + + +
Eigen's APISTL-like APIs\arrayworld Comments
\code +mat1.real() +mat1.imag() +mat1.conjugate() +\endcode +\code +real(array1) +imag(array1) +conj(array1) +\endcode + +\code + // read-write, no-op for real expressions + // read-only for real, read-write for complexes + // no-op for real expressions +\endcode +
+ +Some coefficient-wise operators are readily available for for matrices and vectors through the following cwise* methods: + + + +
Matrix API \matrixworldVia Array conversions
\code +mat1.cwiseMin(mat2) mat1.cwiseMin(scalar) +mat1.cwiseMax(mat2) mat1.cwiseMax(scalar) +mat1.cwiseAbs2() +mat1.cwiseAbs() +mat1.cwiseSqrt() +mat1.cwiseInverse() +mat1.cwiseProduct(mat2) +mat1.cwiseQuotient(mat2) +mat1.cwiseEqual(mat2) mat1.cwiseEqual(scalar) +mat1.cwiseNotEqual(mat2) +\endcode +\code +mat1.array().min(mat2.array()) mat1.array().min(scalar) +mat1.array().max(mat2.array()) mat1.array().max(scalar) +mat1.array().abs2() +mat1.array().abs() +mat1.array().sqrt() +mat1.array().inverse() +mat1.array() * mat2.array() +mat1.array() / mat2.array() +mat1.array() == mat2.array() mat1.array() == scalar +mat1.array() != mat2.array() +\endcode
+The main difference between the two API is that the one based on cwise* methods returns an expression in the matrix world, +while the second one (based on .array()) returns an array expression. +Recall that .array() has no cost, it only changes the available API and interpretation of the data. + +It is also very simple to apply any user defined function \c foo using DenseBase::unaryExpr together with std::ptr_fun (c++03), std::ref (c++11), or lambdas (c++11): +\code +mat1.unaryExpr(std::ptr_fun(foo)); +mat1.unaryExpr(std::ref(foo)); +mat1.unaryExpr([](double x) { return foo(x); }); +\endcode + + top \section QuickRef_Reductions Reductions diff --git a/gtsam/3rdparty/Eigen/doc/SparseLinearSystems.dox b/gtsam/3rdparty/Eigen/doc/SparseLinearSystems.dox index b66e2ba2b..fc33b93e7 100644 --- a/gtsam/3rdparty/Eigen/doc/SparseLinearSystems.dox +++ b/gtsam/3rdparty/Eigen/doc/SparseLinearSystems.dox @@ -4,33 +4,63 @@ In Eigen, there are several methods available to solve linear systems when the c \eigenAutoToc -\section TutorialSparseDirectSolvers Sparse solvers +\section TutorialSparseSolverList List of sparse solvers -%Eigen currently provides a limited set of built-in solvers, as well as wrappers to external solver libraries. -They are summarized in the following table: +%Eigen currently provides a wide set of built-in solvers, as well as wrappers to external solver libraries. +They are summarized in the following tables: + +\subsection TutorialSparseSolverList_Direct Built-in direct solvers + + + + + + + + + + + + + + + + + + + + + + +
ClassSolver kindMatrix kindFeatures related to performanceLicense

Notes

SimplicialLLT \n \#includeDirect LLt factorizationSPDFill-in reducingLGPLSimplicialLDLT is often preferable
SimplicialLDLT \n \#includeDirect LDLt factorizationSPDFill-in reducingLGPLRecommended for very sparse and not too large problems (e.g., 2D Poisson eq.)
SparseLU \n \#include LU factorization Square Fill-in reducing, Leverage fast dense algebraMPL2optimized for small and large problems with irregular patterns
SparseQR \n \#include QR factorizationAny, rectangular Fill-in reducingMPL2recommended for least-square problems, has a basic rank-revealing feature
+ +\subsection TutorialSparseSolverList_Iterative Built-in iterative solvers + + + + + + + + + + + + + + + + + + + +
ClassSolver kindMatrix kindSupported preconditioners, [default]License

Notes

ConjugateGradient \n \#include Classic iterative CGSPDIdentityPreconditioner, [DiagonalPreconditioner], IncompleteCholeskyMPL2Recommended for large symmetric problems (e.g., 3D Poisson eq.)
LeastSquaresConjugateGradient \n \#includeCG for rectangular least-square problemRectangularIdentityPreconditioner, [LeastSquareDiagonalPreconditioner]MPL2Solve for min |A'Ax-b|^2 without forming A'A
BiCGSTAB \n \#includeIterative stabilized bi-conjugate gradientSquareIdentityPreconditioner, [DiagonalPreconditioner], IncompleteLUTMPL2To speedup the convergence, try it with the \ref IncompleteLUT preconditioner.
+ +\subsection TutorialSparseSolverList_Wrapper Wrappers to external solvers - - - - - - - - - - - - - - - - - - - @@ -53,6 +83,8 @@ They are summarized in the following table: Here \c SPD means symmetric positive definite. +\section TutorialSparseSolverConcept Sparse solver concept + All these solvers follow the same general concept. Here is a typical and general example: \code @@ -104,8 +136,10 @@ x2 = solver.solve(b2); \endcode The compute() method is equivalent to calling both analyzePattern() and factorize(). -Finally, each solver provides some specific features, such as determinant, access to the factors, controls of the iterations, and so on. -More details are availble in the documentations of the respective classes. +Each solver provides some specific features, such as determinant, access to the factors, controls of the iterations, and so on. +More details are available in the documentations of the respective classes. + +Finally, most of the iterative solvers, can also be used in a \b matrix-free context, see the following \link MatrixfreeSolverExample example \endlink. \section TheSparseCompute The Compute Step In the compute() function, the matrix is generally factorized: LLT for self-adjoint matrices, LDLT for general hermitian matrices, LU for non hermitian matrices and QR for rectangular matrices. These are the results of using direct solvers. For this class of solvers precisely, the compute step is further subdivided into analyzePattern() and factorize(). @@ -143,7 +177,16 @@ x2 = solver.solve(b2); For direct methods, the solution are computed at the machine precision. Sometimes, the solution need not be too accurate. In this case, the iterative methods are more suitable and the desired accuracy can be set before the solve step using \b setTolerance(). For all the available functions, please, refer to the documentation of the \link IterativeLinearSolvers_Module Iterative solvers module \endlink. \section BenchmarkRoutine -Most of the time, all you need is to know how much time it will take to qolve your system, and hopefully, what is the most suitable solver. In Eigen, we provide a benchmark routine that can be used for this purpose. It is very easy to use. In the build directory, navigate to bench/spbench and compile the routine by typing \b make \e spbenchsolver. Run it with --help option to get the list of all available options. Basically, the matrices to test should be in MatrixMarket Coordinate format, and the routine returns the statistics from all available solvers in Eigen. +Most of the time, all you need is to know how much time it will take to solve your system, and hopefully, what is the most suitable solver. In Eigen, we provide a benchmark routine that can be used for this purpose. It is very easy to use. In the build directory, navigate to bench/spbench and compile the routine by typing \b make \e spbenchsolver. Run it with --help option to get the list of all available options. Basically, the matrices to test should be in MatrixMarket Coordinate format, and the routine returns the statistics from all available solvers in Eigen. + +To export your matrices and right-hand-side vectors in the matrix-market format, you can the the unsupported SparseExtra module: +\code +#include +... +Eigen::saveMarket(A, "filename.mtx"); +Eigen::saveMarket(A, "filename_SPD.mtx", Eigen::Symmetric); // if A is symmetric-positive-definite +Eigen::saveMarketVector(B, "filename_b.mtx"); +\endcode The following table gives an example of XML statistics from several Eigen built-in and external solvers.
ClassModuleSolver kindMatrix kindFeatures related to performance Dependencies,License

Notes

SimplicialLLT \link SparseCholesky_Module SparseCholesky \endlinkDirect LLt factorizationSPDFill-in reducingbuilt-in, LGPLSimplicialLDLT is often preferable
SimplicialLDLT \link SparseCholesky_Module SparseCholesky \endlinkDirect LDLt factorizationSPDFill-in reducingbuilt-in, LGPLRecommended for very sparse and not too large problems (e.g., 2D Poisson eq.)
ConjugateGradient\link IterativeLinearSolvers_Module IterativeLinearSolvers \endlinkClassic iterative CGSPDPreconditionningbuilt-in, MPL2Recommended for large symmetric problems (e.g., 3D Poisson eq.)
BiCGSTAB\link IterativeLinearSolvers_Module IterativeLinearSolvers \endlinkIterative stabilized bi-conjugate gradientSquarePreconditionningbuilt-in, MPL2To speedup the convergence, try it with the \ref IncompleteLUT preconditioner.
SparseLU \link SparseLU_Module SparseLU \endlink LU factorization Square Fill-in reducing, Leverage fast dense algebra built-in, MPL2 optimized for small and large problems with irregular patterns
SparseQR \link SparseQR_Module SparseQR \endlink QR factorizationAny, rectangular Fill-in reducingbuilt-in, MPL2recommended for least-square problems, has a basic rank-revealing feature
Wrappers to external solvers
PastixLLT \n PastixLDLT \n PastixLU\link PaStiXSupport_Module PaStiXSupport \endlinkDirect LLt, LDLt, LU factorizationsSPD \n SPD \n SquareFill-in reducing, Leverage fast dense algebra, Multithreading Requires the PaStiX package, \b CeCILL-C optimized for tough problems and symmetric patterns
diff --git a/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox b/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox index e0a30edcc..a25622e80 100644 --- a/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox +++ b/gtsam/3rdparty/Eigen/doc/SparseQuickReference.dox @@ -206,7 +206,7 @@ See \ref TutorialSparse_SubMatrices and below for read-write sub-matrices. sm1.innerVectors(start, size); // RW sm1.leftCols(size); // RW sm2.rightCols(size); // RO because sm2 is row-major - sm1.middleRows(start, numRows); // RO becasue sm1 is column-major + sm1.middleRows(start, numRows); // RO because sm1 is column-major sm1.middleCols(start, numCols); // RW sm1.col(j); // RW \endcode @@ -253,6 +253,20 @@ If the matrix is not in compressed form, makeCompressed() should be called befor Note that these functions are mostly provided for interoperability purposes with external libraries.\n A better access to the values of the matrix is done by using the InnerIterator class as described in \link TutorialSparse the Tutorial Sparse \endlink section + + + + +
Mapping external buffers
+\code +int outerIndexPtr[cols+1]; +int innerIndices[nnz]; +double values[nnz]; +Map > sm1(rows,cols,nnz,outerIndexPtr, // read-write + innerIndices,values); +Map > sm2(...); // read-only +\endcode +As for dense matrices, class Map can be used to see external buffers as an %Eigen's SparseMatrix object.
*/ } diff --git a/gtsam/3rdparty/Eigen/doc/StlContainers.dox b/gtsam/3rdparty/Eigen/doc/StlContainers.dox index d8d0d529c..e0f8714a9 100644 --- a/gtsam/3rdparty/Eigen/doc/StlContainers.dox +++ b/gtsam/3rdparty/Eigen/doc/StlContainers.dox @@ -4,7 +4,7 @@ namespace Eigen { \eigenAutoToc -\section summary Executive summary +\section StlContainers_summary Executive summary Using STL containers on \ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen types", or classes having members of such types, requires taking the following two steps: @@ -28,7 +28,7 @@ std::map, \endcode Note that the third parameter "std::less" is just the default value, but we have to include it because we want to specify the fourth parameter, which is the allocator type. -\section vector The case of std::vector +\section StlContainers_vector The case of std::vector The situation with std::vector was even worse (explanation below) so we had to specialize it for the Eigen::aligned_allocator type. In practice you \b must use the Eigen::aligned_allocator (not another aligned allocator), \b and \#include . diff --git a/gtsam/3rdparty/Eigen/doc/StructHavingEigenMembers.dox b/gtsam/3rdparty/Eigen/doc/StructHavingEigenMembers.dox index 74a8d5217..7fbed0eb0 100644 --- a/gtsam/3rdparty/Eigen/doc/StructHavingEigenMembers.dox +++ b/gtsam/3rdparty/Eigen/doc/StructHavingEigenMembers.dox @@ -4,11 +4,11 @@ namespace Eigen { \eigenAutoToc -\section summary Executive Summary +\section StructHavingEigenMembers_summary Executive Summary -If you define a structure having members of \ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen types", you must overload its "operator new" so that it generates 16-bytes-aligned pointers. Fortunately, Eigen provides you with a macro EIGEN_MAKE_ALIGNED_OPERATOR_NEW that does that for you. +If you define a structure having members of \ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen types", you must overload its "operator new" so that it generates 16-bytes-aligned pointers. Fortunately, %Eigen provides you with a macro EIGEN_MAKE_ALIGNED_OPERATOR_NEW that does that for you. -\section what What kind of code needs to be changed? +\section StructHavingEigenMembers_what What kind of code needs to be changed? The kind of code that needs to be changed is this: @@ -27,7 +27,7 @@ Foo *foo = new Foo; In other words: you have a class that has as a member a \ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen object", and then you dynamically create an object of that class. -\section how How should such code be modified? +\section StructHavingEigenMembers_how How should such code be modified? Very easy, you just need to put a EIGEN_MAKE_ALIGNED_OPERATOR_NEW macro in a public part of your class, like this: @@ -48,9 +48,9 @@ Foo *foo = new Foo; This macro makes "new Foo" always return an aligned pointer. -If this approach is too intrusive, see also the \ref othersolutions. +If this approach is too intrusive, see also the \ref StructHavingEigenMembers_othersolutions "other solutions". -\section why Why is this needed? +\section StructHavingEigenMembers_why Why is this needed? OK let's say that your code looks like this: @@ -67,7 +67,7 @@ class Foo Foo *foo = new Foo; \endcode -A Eigen::Vector2d consists of 2 doubles, which is 128 bits. Which is exactly the size of a SSE packet, which makes it possible to use SSE for all sorts of operations on this vector. But SSE instructions (at least the ones that Eigen uses, which are the fast ones) require 128-bit alignment. Otherwise you get a segmentation fault. +A Eigen::Vector2d consists of 2 doubles, which is 128 bits. Which is exactly the size of a SSE packet, which makes it possible to use SSE for all sorts of operations on this vector. But SSE instructions (at least the ones that %Eigen uses, which are the fast ones) require 128-bit alignment. Otherwise you get a segmentation fault. For this reason, Eigen takes care by itself to require 128-bit alignment for Eigen::Vector2d, by doing two things: \li Eigen requires 128-bit alignment for the Eigen::Vector2d's array (of 2 doubles). With GCC, this is done with a __attribute__ ((aligned(16))). @@ -81,7 +81,7 @@ The alignment attribute of the member v is then relative to the start of the cla The solution is to let class Foo have an aligned "operator new", as we showed in the previous section. -\section movetotop Should I then put all the members of Eigen types at the beginning of my class? +\section StructHavingEigenMembers_movetotop Should I then put all the members of Eigen types at the beginning of my class? That's not required. Since Eigen takes care of declaring 128-bit alignment, all members that need it are automatically 128-bit aligned relatively to the class. So code like this works fine: @@ -95,15 +95,15 @@ public: }; \endcode -\section dynamicsize What about dynamic-size matrices and vectors? +\section StructHavingEigenMembers_dynamicsize What about dynamic-size matrices and vectors? Dynamic-size matrices and vectors, such as Eigen::VectorXd, allocate dynamically their own array of coefficients, so they take care of requiring absolute alignment automatically. So they don't cause this issue. The issue discussed here is only with \ref TopicFixedSizeVectorizable "fixed-size vectorizable matrices and vectors". -\section bugineigen So is this a bug in Eigen? +\section StructHavingEigenMembers_bugineigen So is this a bug in Eigen? No, it's not our bug. It's more like an inherent problem of the C++98 language specification, and seems to be taken care of in the upcoming language revision: see this document. -\section conditional What if I want to do this conditionnally (depending on template parameters) ? +\section StructHavingEigenMembers_conditional What if I want to do this conditionnally (depending on template parameters) ? For this situation, we offer the macro EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign). It will generate aligned operators like EIGEN_MAKE_ALIGNED_OPERATOR_NEW if NeedsToAlign is true. It will generate operators with the default alignment if NeedsToAlign is false. @@ -128,7 +128,7 @@ Foo<3> *foo3 = new Foo<3>; // foo3 has only the system default alignment guarant \endcode -\section othersolutions Other solutions +\section StructHavingEigenMembers_othersolutions Other solutions In case putting the EIGEN_MAKE_ALIGNED_OPERATOR_NEW macro everywhere is too intrusive, there exists at least two other solutions. diff --git a/gtsam/3rdparty/Eigen/doc/TemplateKeyword.dox b/gtsam/3rdparty/Eigen/doc/TemplateKeyword.dox index f4e4f237e..b84cfdae9 100644 --- a/gtsam/3rdparty/Eigen/doc/TemplateKeyword.dox +++ b/gtsam/3rdparty/Eigen/doc/TemplateKeyword.dox @@ -5,7 +5,8 @@ namespace Eigen { There are two uses for the \c template and \c typename keywords in C++. One of them is fairly well known amongst programmers: to define templates. The other use is more obscure: to specify that an expression refers to a template function or a type. This regularly trips up programmers that use the %Eigen library, often -leading to error messages from the compiler that are difficult to understand. +leading to error messages from the compiler that are difficult to understand, such as "expected expression" or +"no match for operator<". \eigenAutoToc @@ -72,23 +73,23 @@ for operator<". The reason that the \c template keyword is necessary in the last example has to do with the rules for how templates are supposed to be compiled in C++. The compiler has to check the code for correct syntax at the point where the template is defined, without knowing the actual value of the template arguments (\c Derived1 -and \c Derived2 in the example). That means that the compiler cannot know that dst.triangularPart is +and \c Derived2 in the example). That means that the compiler cannot know that dst.triangularView is a member template and that the following < symbol is part of the delimiter for the template -parameter. Another possibility would be that dst.triangularPart is a member variable with the < +parameter. Another possibility would be that dst.triangularView is a member variable with the < symbol refering to the operator<() function. In fact, the compiler should choose the second -possibility, according to the standard. If dst.triangularPart is a member template (as in our case), +possibility, according to the standard. If dst.triangularView is a member template (as in our case), the programmer should specify this explicitly with the \c template keyword and write dst.template -triangularPart. +triangularView. The precise rules are rather complicated, but ignoring some subtleties we can summarize them as follows: - A dependent name is name that depends (directly or indirectly) on a template parameter. In the example, \c dst is a dependent name because it is of type MatrixBase<Derived1> which depends on the template parameter \c Derived1. -- If the code contains either one of the contructions xxx.yyy or xxx->yyy and \c xxx is a +- If the code contains either one of the constructs xxx.yyy or xxx->yyy and \c xxx is a dependent name and \c yyy refers to a member template, then the \c template keyword must be used before \c yyy, leading to xxx.template yyy or xxx->template yyy. -- If the code contains the contruction xxx::yyy and \c xxx is a dependent name and \c yyy refers to a - member typedef, then the \c typename keyword must be used before the whole construction, leading to +- If the code contains the construct xxx::yyy and \c xxx is a dependent name and \c yyy refers to a + member typedef, then the \c typename keyword must be used before the whole construct, leading to typename xxx::yyy. As an example where the \c typename keyword is required, consider the following code in \ref TutorialSparse diff --git a/gtsam/3rdparty/Eigen/doc/TopicAliasing.dox b/gtsam/3rdparty/Eigen/doc/TopicAliasing.dox index c2654aed2..a8f164428 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicAliasing.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicAliasing.dox @@ -153,10 +153,11 @@ not necessary to evaluate the right-hand side explicitly. \section TopicAliasingMatrixMult Aliasing and matrix multiplication -Matrix multiplication is the only operation in %Eigen that assumes aliasing by default. Thus, if \c matA is a -matrix, then the statement matA = matA * matA; is safe. All other operations in %Eigen assume that -there are no aliasing problems, either because the result is assigned to a different matrix or because it is a -component-wise operation. +Matrix multiplication is the only operation in %Eigen that assumes aliasing by default, under the +condition that the destination matrix is not resized. +Thus, if \c matA is a \b squared matrix, then the statement matA = matA * matA; is safe. +All other operations in %Eigen assume that there are no aliasing problems, +either because the result is assigned to a different matrix or because it is a component-wise operation. @@ -198,6 +199,27 @@ may get wrong results: \verbinclude TopicAliasing_mult3.out
ExampleOutput
+Moreover, starting in Eigen 3.3, aliasing is \b not assumed if the destination matrix is resized and the product is not directly assigned to the destination. +Therefore, the following example is also wrong: + + + + +
ExampleOutput
+\include TopicAliasing_mult4.cpp + +\verbinclude TopicAliasing_mult4.out +
+ +As for any aliasing issue, you can resolve it by explicitly evaluating the expression prior to assignment: + + + +
ExampleOutput
+\include TopicAliasing_mult5.cpp + +\verbinclude TopicAliasing_mult5.out +
\section TopicAliasingSummary Summary diff --git a/gtsam/3rdparty/Eigen/doc/TopicCMakeGuide.dox b/gtsam/3rdparty/Eigen/doc/TopicCMakeGuide.dox new file mode 100644 index 000000000..896cfa831 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/TopicCMakeGuide.dox @@ -0,0 +1,52 @@ +namespace Eigen { + +/** + +\page TopicCMakeGuide Using %Eigen in CMake Projects + +%Eigen provides native CMake support which allows the library to be easily +used in CMake projects. + +\note %CMake 3.0 (or later) is required to enable this functionality. + +%Eigen exports a CMake target called `Eigen3::Eigen` which can be imported +using the `find_package` CMake command and used by calling +`target_link_libraries` as in the following example: +\code{.cmake} +cmake_minimum_required (VERSION 3.0) +project (myproject) + +find_package (Eigen3 3.3 REQUIRED NO_MODULE) + +add_executable (example example.cpp) +target_link_libraries (example Eigen3::Eigen) +\endcode + +The above code snippet must be placed in a file called `CMakeLists.txt` alongside +`example.cpp`. After running +\code{.sh} +$ cmake path-to-example-directory +\endcode +CMake will produce project files that generate an executable called `example` +which requires at least version 3.3 of %Eigen. Here, `path-to-example-directory` +is the path to the directory that contains both `CMakeLists.txt` and +`example.cpp`. + +If you have multiple installed version of %Eigen, you can pick your favorite one by setting the \c Eigen3_DIR cmake's variable to the respective path containing the \c Eigen3*.cmake files. For instance: +\code +cmake path-to-example-directory -DEigen3_DIR=$HOME/mypackages/share/eigen3/cmake/ +\endcode + +If the `REQUIRED` option is omitted when locating %Eigen using +`find_package`, one can check whether the package was found as follows: +\code{.cmake} +find_package (Eigen3 3.3 NO_MODULE) + +if (TARGET Eigen3::Eigen) + # Use the imported target +endif (TARGET Eigen3::Eigen) +\endcode + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/TopicLazyEvaluation.dox b/gtsam/3rdparty/Eigen/doc/TopicLazyEvaluation.dox index 393bc41d8..101ef8c72 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicLazyEvaluation.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicLazyEvaluation.dox @@ -36,7 +36,7 @@ Here is now a more involved example: Eigen chooses lazy evaluation at every stage in that example, which is clearly the correct choice. In fact, lazy evaluation is the "default choice" and Eigen will choose it except in a few circumstances. -The first circumstance in which Eigen chooses immediate evaluation, is when it sees an assignment a = b; and the expression \c b has the evaluate-before-assigning \link flags flag\endlink. The most important example of such an expression is the \link GeneralProduct matrix product expression\endlink. For example, when you do +The first circumstance in which Eigen chooses immediate evaluation, is when it sees an assignment a = b; and the expression \c b has the evaluate-before-assigning \link flags flag\endlink. The most important example of such an expression is the \link Product matrix product expression\endlink. For example, when you do \code matrix = matrix * matrix; \endcode @@ -48,7 +48,7 @@ What if you know that the result does no alias the operand of the product and wa Here, since we know that matrix2 is not the same matrix as matrix1, we know that lazy evaluation is not dangerous, so we may force lazy evaluation. Concretely, the effect of noalias() here is to bypass the evaluate-before-assigning \link flags flag\endlink. -The second circumstance in which Eigen chooses immediate evaluation, is when it sees a nested expression such as a + b where \c b is already an expression having the evaluate-before-nesting \link flags flag\endlink. Again, the most important example of such an expression is the \link GeneralProduct matrix product expression\endlink. For example, when you do +The second circumstance in which Eigen chooses immediate evaluation, is when it sees a nested expression such as a + b where \c b is already an expression having the evaluate-before-nesting \link flags flag\endlink. Again, the most important example of such an expression is the \link Product matrix product expression\endlink. For example, when you do \code matrix1 = matrix2 + matrix3 * matrix4; \endcode diff --git a/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox b/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox index 8649cc27b..491470627 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicLinearAlgebraDecompositions.dox @@ -4,6 +4,7 @@ namespace Eigen { This page presents a catalogue of the dense matrix decompositions offered by Eigen. For an introduction on linear solvers and decompositions, check this \link TutorialLinearAlgebra page \endlink. +To get an overview of the true relative speed of the different decomposition, check this \link DenseDecompositionBenchmark benchmark \endlink. \section TopicLinAlgBigTable Catalogue of decompositions offered by Eigen @@ -116,7 +117,7 @@ For an introduction on linear solvers and decompositions, check this \link Tutor JacobiSVD (two-sided) - Slow (but fast for small matrices) - Excellent-Proven3 + Proven3 Yes Singular values/vectors, least squares Yes (and does least squares) @@ -132,7 +133,7 @@ For an introduction on linear solvers and decompositions, check this \link Tutor Yes Eigenvalues/vectors - - Good + Excellent Closed forms for 2x2 and 3x3 @@ -249,13 +250,14 @@ For an introduction on linear solvers and decompositions, check this \link Tutor
Implicit Multi Threading (MT)
Means the algorithm can take advantage of multicore processors via OpenMP. "Implicit" means the algortihm itself is not parallelized, but that it relies on parallelized matrix-matrix product rountines.
Explicit Multi Threading (MT)
-
Means the algorithm is explicitely parallelized to take advantage of multicore processors via OpenMP.
+
Means the algorithm is explicitly parallelized to take advantage of multicore processors via OpenMP.
Meta-unroller
Means the algorithm is automatically and explicitly unrolled for very small fixed size matrices.
+ */ } diff --git a/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox index 7db2b0e07..47c9b261f 100644 --- a/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox +++ b/gtsam/3rdparty/Eigen/doc/TopicMultithreading.dox @@ -8,13 +8,13 @@ Some Eigen's algorithms can exploit the multiple cores present in your hardware. * GCC: \c -fopenmp * ICC: \c -openmp * MSVC: check the respective option in the build properties. -You can control the number of thread that will be used using either the OpenMP API or Eiegn's API using the following priority: +You can control the number of thread that will be used using either the OpenMP API or Eigen's API using the following priority: \code OMP_NUM_THREADS=n ./my_program omp_set_num_threads(n); Eigen::setNbThreads(n); \endcode -Unless setNbThreads has been called, Eigen uses the number of threads specified by OpenMP. You can restore this bahavior by calling \code setNbThreads(0); \endcode +Unless setNbThreads has been called, Eigen uses the number of threads specified by OpenMP. You can restore this behavior by calling \code setNbThreads(0); \endcode You can query the number of threads that will be used with: \code n = Eigen::nbThreads( ); @@ -22,8 +22,12 @@ n = Eigen::nbThreads( ); You can disable Eigen's multi threading at compile time by defining the EIGEN_DONT_PARALLELIZE preprocessor token. Currently, the following algorithms can make use of multi-threading: - * general matrix - matrix products - * PartialPivLU + - general dense matrix - matrix products + - PartialPivLU + - row-major-sparse * dense vector/matrix products + - ConjugateGradient with \c Lower|Upper as the \c UpLo template parameter. + - BiCGSTAB with a row-major sparse matrix format. + - LeastSquaresConjugateGradient \section TopicMultiThreading_UsingEigenWithMT Using Eigen in a multi-threaded application @@ -39,6 +43,10 @@ int main(int argc, char** argv) } \endcode +\note With Eigen 3.3, and a fully C++11 compliant compiler (i.e., thread-safe static local variable initialization), then calling \c initParallel() is optional. + +\warning note that all functions generating random matrices are \b not re-entrant nor thread-safe. Those include DenseBase::Random(), and DenseBase::setRandom() despite a call to Eigen::initParallel(). This is because these functions are based on std::rand which is not re-entrant. For thread-safe random generator, we recommend the use of boost::random or c++11 random feature. + In the case your application is parallelized with OpenMP, you might want to disable Eigen's own parallization as detailed in the previous section. */ diff --git a/gtsam/3rdparty/Eigen/doc/TutorialArrayClass.dox b/gtsam/3rdparty/Eigen/doc/TutorialArrayClass.dox index 6432684aa..f6f351091 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialArrayClass.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialArrayClass.dox @@ -157,7 +157,7 @@ The following example shows how to use array operations on a Matrix object by em * to multiply them coefficient-wise and assigns the result to the matrix variable \c result (this is legal because Eigen allows assigning array expressions to matrix variables). -As a matter of fact, this usage case is so common that Eigen provides a \link MatrixBase::cwiseProduct() const +As a matter of fact, this usage case is so common that Eigen provides a \link MatrixBase::cwiseProduct const .cwiseProduct(.) \endlink method for matrices to compute the coefficient-wise product. This is also shown in the example program. diff --git a/gtsam/3rdparty/Eigen/doc/TutorialGeometry.dox b/gtsam/3rdparty/Eigen/doc/TutorialGeometry.dox index 372a275de..2e1420f98 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialGeometry.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialGeometry.dox @@ -126,11 +126,12 @@ Apply the transformation to a \b vector \code VectorNf vec1, vec2; vec2 = t.linear() * vec1;\endcode -Apply a \em general transformation \n to a \b normal \b vector -(explanations)\code +Apply a \em general transformation \n to a \b normal \b vector \n +\code VectorNf n1, n2; MatrixNf normalMatrix = t.linear().inverse().transpose(); n2 = (normalMatrix * n1).normalized();\endcode +(See subject 5.27 of this faq for the explanations) Apply a transformation with \em pure \em rotation \n to a \b normal \b vector (no scaling, no shear)\code @@ -231,8 +232,8 @@ On the other hand, since there exist 24 different conventions, they are pretty c to create a rotation matrix according to the 2-1-2 convention.\code Matrix3f m; m = AngleAxisf(angle1, Vector3f::UnitZ()) -* * AngleAxisf(angle2, Vector3f::UnitY()) -* * AngleAxisf(angle3, Vector3f::UnitZ()); + * AngleAxisf(angle2, Vector3f::UnitY()) + * AngleAxisf(angle3, Vector3f::UnitZ()); \endcode diff --git a/gtsam/3rdparty/Eigen/doc/TutorialLinearAlgebra.dox b/gtsam/3rdparty/Eigen/doc/TutorialLinearAlgebra.dox index b09f3543e..cb92ceeae 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialLinearAlgebra.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialLinearAlgebra.dox @@ -40,8 +40,9 @@ depending on your matrix and the trade-off you want to make: Decomposition Method - Requirements on the matrix - Speed + Requirements
on the matrix + Speed
(small-to-medium) + Speed
(large) Accuracy @@ -49,6 +50,7 @@ depending on your matrix and the trade-off you want to make: partialPivLu() Invertible ++ + ++ + @@ -56,6 +58,7 @@ depending on your matrix and the trade-off you want to make: fullPivLu() None - + - - +++ @@ -63,20 +66,23 @@ depending on your matrix and the trade-off you want to make: householderQr() None ++ + ++ + ColPivHouseholderQR colPivHouseholderQr() None - + ++ + - + +++ FullPivHouseholderQR fullPivHouseholderQr() None - + - - +++ @@ -84,21 +90,31 @@ depending on your matrix and the trade-off you want to make: llt() Positive definite +++ + +++ + LDLT ldlt() - Positive or negative semidefinite + Positive or negative
semidefinite +++ + + ++ + + JacobiSVD + jacobiSvd() + None + - - + - - - + +++ + All of these decompositions offer a solve() method that works as in the above example. For example, if your matrix is positive definite, the above table says that a very good -choice is then the LDLT decomposition. Here's an example, also demonstrating that using a general +choice is then the LLT or LDLT decomposition. Here's an example, also demonstrating that using a general matrix (not a vector) as right hand side is possible. @@ -167,8 +183,8 @@ Here is an example: \section TutorialLinAlgLeastsquares Least squares solving -The best way to do least squares solving is with a SVD decomposition. Eigen provides one as the JacobiSVD class, and its solve() -is doing least-squares solving. +The most accurate method to do least squares solving is with a SVD decomposition. Eigen provides one +as the JacobiSVD class, and its solve() is doing least-squares solving. Here is an example:
@@ -179,9 +195,10 @@ Here is an example:
-Another way, potentially faster but less reliable, is to use a LDLT decomposition -of the normal matrix. In any case, just read any reference text on least squares, and it will be very easy for you -to implement any linear least squares computation on top of Eigen. +Another methods, potentially faster but less reliable, are to use a Cholesky decomposition of the +normal matrix or a QR decomposition. Our page on \link LeastSquares least squares solving \endlink +has more details. + \section TutorialLinAlgSeparateComputation Separating the computation from the construction diff --git a/gtsam/3rdparty/Eigen/doc/TutorialReductionsVisitorsBroadcasting.dox b/gtsam/3rdparty/Eigen/doc/TutorialReductionsVisitorsBroadcasting.dox index 992cf6f34..f5322b4a6 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialReductionsVisitorsBroadcasting.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialReductionsVisitorsBroadcasting.dox @@ -32,7 +32,7 @@ Eigen also provides the \link MatrixBase::norm() norm() \endlink method, which r These operations can also operate on matrices; in that case, a n-by-p matrix is seen as a vector of size (n*p), so for example the \link MatrixBase::norm() norm() \endlink method returns the "Frobenius" or "Hilbert-Schmidt" norm. We refrain from speaking of the \f$\ell^2\f$ norm of a matrix because that can mean different things. -If you want other \f$\ell^p\f$ norms, use the \link MatrixBase::lpNorm() lpNnorm

() \endlink method. The template parameter \a p can take the special value \a Infinity if you want the \f$\ell^\infty\f$ norm, which is the maximum of the absolute values of the coefficients. +If you want other coefficient-wise \f$\ell^p\f$ norms, use the \link MatrixBase::lpNorm lpNorm

() \endlink method. The template parameter \a p can take the special value \a Infinity if you want the \f$\ell^\infty\f$ norm, which is the maximum of the absolute values of the coefficients. The following example demonstrates these methods. @@ -45,6 +45,17 @@ The following example demonstrates these methods. \verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.out +\b Operator \b norm: The 1-norm and \f$\infty\f$-norm matrix operator norms can easily be computed as follows: + + + +
Example:Output:
+\include Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp + +\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.out +
+See below for more explanations on the syntax of these expressions. + \subsection TutorialReductionsVisitorsBroadcastingReductionsBool Boolean reductions The following reductions operate on boolean values: @@ -79,7 +90,7 @@ Array. The arguments passed to a visitor are pointers to the variables where the row and column position are to be stored. These variables should be of type -\link DenseBase::Index Index \endlink, as shown below: +\link Eigen::Index Index \endlink, as shown below: @@ -90,17 +101,16 @@ row and column position are to be stored. These variables should be of type \verbinclude Tutorial_ReductionsVisitorsBroadcasting_visitors.out
Example:Output:
-Note that both functions also return the value of the minimum or maximum coefficient if needed, -as if it was a typical reduction operation. +Both functions also return the value of the minimum or maximum coefficient. \section TutorialReductionsVisitorsBroadcastingPartialReductions Partial reductions Partial reductions are reductions that can operate column- or row-wise on a Matrix or Array, applying the reduction operation on each column or row and -returning a column or row-vector with the corresponding values. Partial reductions are applied +returning a column or row vector with the corresponding values. Partial reductions are applied with \link DenseBase::colwise() colwise() \endlink or \link DenseBase::rowwise() rowwise() \endlink. A simple example is obtaining the maximum of the elements -in each column in a given matrix, storing the result in a row-vector: +in each column in a given matrix, storing the result in a row vector: @@ -122,8 +132,7 @@ The same operation can be performed row-wise: \verbinclude Tutorial_ReductionsVisitorsBroadcasting_rowwise.out
Example:Output:
-Note that column-wise operations return a 'row-vector' while row-wise operations -return a 'column-vector' +Note that column-wise operations return a row vector, while row-wise operations return a column vector. \subsection TutorialReductionsVisitorsBroadcastingPartialReductionsCombined Combining partial reductions with other operations It is also possible to use the result of a partial reduction to do further processing. @@ -165,7 +174,7 @@ The concept behind broadcasting is similar to partial reductions, with the diffe constructs an expression where a vector (column or row) is interpreted as a matrix by replicating it in one direction. -A simple example is to add a certain column-vector to each column in a matrix. +A simple example is to add a certain column vector to each column in a matrix. This can be accomplished with: @@ -242,7 +251,7 @@ is a new matrix whose size is the same as matrix m: \f[ \f] - (m.colwise() - v).colwise().squaredNorm() is a partial reduction, computing the squared norm column-wise. The result of -this operation is a row-vector where each coefficient is the squared Euclidean distance between each column in m and v: \f[ +this operation is a row vector where each coefficient is the squared Euclidean distance between each column in m and v: \f[ \mbox{(m.colwise() - v).colwise().squaredNorm()} = \begin{bmatrix} 1 & 505 & 32 & 50 diff --git a/gtsam/3rdparty/Eigen/doc/TutorialReshapeSlicing.dox b/gtsam/3rdparty/Eigen/doc/TutorialReshapeSlicing.dox new file mode 100644 index 000000000..3730a5de6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/TutorialReshapeSlicing.dox @@ -0,0 +1,65 @@ +namespace Eigen { + +/** \eigenManualPage TutorialReshapeSlicing Reshape and Slicing + +%Eigen does not expose convenient methods to take slices or to reshape a matrix yet. +Nonetheless, such features can easily be emulated using the Map class. + +\eigenAutoToc + +\section TutorialReshape Reshape + +A reshape operation consists in modifying the sizes of a matrix while keeping the same coefficients. +Instead of modifying the input matrix itself, which is not possible for compile-time sizes, the approach consist in creating a different \em view on the storage using class Map. +Here is a typical example creating a 1D linear view of a matrix: + +
+ + +
Example:Output:
+\include Tutorial_ReshapeMat2Vec.cpp + +\verbinclude Tutorial_ReshapeMat2Vec.out +
+ +Remark how the storage order of the input matrix modifies the order of the coefficients in the linear view. +Here is another example reshaping a 2x6 matrix to a 6x2 one: + + + +
Example:Output:
+\include Tutorial_ReshapeMat2Mat.cpp + +\verbinclude Tutorial_ReshapeMat2Mat.out +
+ + + +\section TutorialSlicing Slicing + +Slicing consists in taking a set of rows, columns, or elements, uniformly spaced within a matrix. +Again, the class Map allows to easily mimic this feature. + +For instance, one can skip every P elements in a vector: + + + +
Example:Output:
+\include Tutorial_SlicingVec.cpp + +\verbinclude Tutorial_SlicingVec.out +
+ +One can olso take one column over three using an adequate outer-stride or inner-stride depending on the actual storage order: + + + +
Example:Output:
+\include Tutorial_SlicingCol.cpp + +\verbinclude Tutorial_SlicingCol.out +
+ +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox b/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox index ee206cc42..352907408 100644 --- a/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox +++ b/gtsam/3rdparty/Eigen/doc/TutorialSparse.dox @@ -83,7 +83,7 @@ There is no notion of compressed/uncompressed mode for a SparseVector. \section TutorialSparseExample First example -Before describing each individual class, let's start with the following typical example: solving the Laplace equation \f$ \nabla u = 0 \f$ on a regular 2D grid using a finite difference scheme and Dirichlet boundary conditions. +Before describing each individual class, let's start with the following typical example: solving the Laplace equation \f$ \Delta u = 0 \f$ on a regular 2D grid using a finite difference scheme and Dirichlet boundary conditions. Such problem can be mathematically expressed as a linear problem of the form \f$ Ax=b \f$ where \f$ x \f$ is the vector of \c m unknowns (in our case, the values of the pixels), \f$ b \f$ is the right hand side vector resulting from the boundary conditions, and \f$ A \f$ is an \f$ m \times m \f$ matrix containing only a few non-zero elements resulting from the discretization of the Laplacian operator. @@ -253,15 +253,19 @@ SparseMatrix A, B; B = SparseMatrix(A.transpose()) + A; \endcode -Some binary coefficient-wise operators can also mix sparse and dense expressions: +Binary coefficient wise operators can also mix sparse and dense expressions: \code sm2 = sm1.cwiseProduct(dm1); -dm1 += sm1; +dm2 = sm1 + dm1; +dm2 = dm1 - sm1; \endcode +Performance-wise, the adding/subtracting sparse and dense matrices is better performed in two steps. For instance, instead of doing dm2 = sm1 + dm1, better write: +\code +dm2 = dm1; +dm2 += sm1; +\endcode +This version has the advantage to fully exploit the higher performance of dense storage (no indirection, SIMD, etc.), and to pay the cost of slow sparse evaluation on the few non-zeros of the sparse matrix only. -However, it is not yet possible to add a sparse and a dense matrix as in dm2 = sm1 + dm1. -Please write this as the equivalent dm2 = dm1; dm2 += sm1 (we plan to lift this restriction -in the next release of %Eigen). %Sparse expressions also support transposition: \code diff --git a/gtsam/3rdparty/Eigen/doc/UnalignedArrayAssert.dox b/gtsam/3rdparty/Eigen/doc/UnalignedArrayAssert.dox index b0d6e18f2..95d95a2d5 100644 --- a/gtsam/3rdparty/Eigen/doc/UnalignedArrayAssert.dox +++ b/gtsam/3rdparty/Eigen/doc/UnalignedArrayAssert.dox @@ -8,7 +8,7 @@ my_program: path/to/eigen/Eigen/src/Core/DenseStorage.h:44: Eigen::internal::matrix_array::internal::matrix_array() [with T = double, int Size = 2, int MatrixOptions = 2, bool Align = true]: Assertion `(reinterpret_cast(array) & (sizemask)) == 0 && "this assertion -is explained here: http://eigen.tuxfamily.org/dox/group__TopicUnalignedArrayAssert.html +is explained here: http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html **** READ THIS WEB PAGE !!! ****"' failed. @@ -92,27 +92,28 @@ Note that here, Eigen::Quaternionf is only used as an example, more generally th \section explanation General explanation of this assertion -\ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen objects" must absolutely be created at 16-byte-aligned locations, otherwise SIMD instructions adressing them will crash. +\ref TopicFixedSizeVectorizable "fixed-size vectorizable Eigen objects" must absolutely be created at 16-byte-aligned locations, otherwise SIMD instructions addressing them will crash. Eigen normally takes care of these alignment issues for you, by setting an alignment attribute on them and by overloading their "operator new". However there are a few corner cases where these alignment settings get overridden: they are the possible causes for this assertion. -\section getrid I don't care about vectorization, how do I get rid of that stuff? +\section getrid I don't care about optimal vectorization, how do I get rid of that stuff? -Two possibilities: +Three possibilities:
    -
  • Define EIGEN_DONT_ALIGN_STATICALLY. That disables all 128-bit static alignment code, while keeping 128-bit heap alignment. This has the effect of - disabling vectorization for fixed-size objects (like Matrix4d) while keeping vectorization of dynamic-size objects - (like MatrixXd). But do note that this breaks ABI compatibility with the default behavior of 128-bit static alignment.
  • -
  • Or define both EIGEN_DONT_VECTORIZE and EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT. This keeps the - 128-bit alignment code and thus preserves ABI compatibility, but completely disables vectorization.
  • +
  • Use the \c DontAlign option to Matrix, Array, Quaternion, etc. objects that gives you trouble. This way Eigen won't try to align them, and thus won"t assume any special alignment. On the down side, you will pay the cost of unaligned loads/stores for them, but on modern CPUs, the overhead is either null or marginal. See \link StructHavingEigenMembers_othersolutions here \endlink for an example.
  • +
  • Define \link TopicPreprocessorDirectivesPerformance EIGEN_DONT_ALIGN_STATICALLY \endlink. That disables all 16-byte (and above) static alignment code, while keeping 16-byte (or above) heap alignment. This has the effect of + vectorizing fixed-size objects (like Matrix4d) through unaligned stores (as controlled by \link TopicPreprocessorDirectivesPerformance EIGEN_UNALIGNED_VECTORIZE \endlink), while keeping unchanged the vectorization of dynamic-size objects + (like MatrixXd). But do note that this breaks ABI compatibility with the default behavior of static alignment.
  • +
  • Or define both \link TopicPreprocessorDirectivesPerformance EIGEN_DONT_VECTORIZE \endlink and EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT. This keeps the + 16-byte alignment code and thus preserves ABI compatibility, but completely disables vectorization.
-If you want to know why defining EIGEN_DONT_VECTORIZE does not by itself disable 128-bit alignment and the assertion, here's the explanation: +If you want to know why defining EIGEN_DONT_VECTORIZE does not by itself disable 16-byte alignment and the assertion, here's the explanation: It doesn't disable the assertion, because otherwise code that runs fine without vectorization would suddenly crash when enabling vectorization. -It doesn't disable 128bit alignment, because that would mean that vectorized and non-vectorized code are not mutually ABI-compatible. This ABI compatibility is very important, even for people who develop only an in-house application, as for instance one may want to have in the same application a vectorized path and a non-vectorized path. +It doesn't disable 16-byte alignment, because that would mean that vectorized and non-vectorized code are not mutually ABI-compatible. This ABI compatibility is very important, even for people who develop only an in-house application, as for instance one may want to have in the same application a vectorized path and a non-vectorized path. */ diff --git a/gtsam/3rdparty/Eigen/doc/UsingBlasLapackBackends.dox b/gtsam/3rdparty/Eigen/doc/UsingBlasLapackBackends.dox new file mode 100644 index 000000000..caa597122 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/UsingBlasLapackBackends.dox @@ -0,0 +1,133 @@ +/* + Copyright (c) 2011, Intel Corporation. All rights reserved. + Copyright (C) 2011-2016 Gael Guennebaud + + Redistribution and use in source and binary forms, with or without modification, + are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of Intel Corporation nor the names of its contributors may + be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON + ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + ******************************************************************************** + * Content : Documentation on the use of BLAS/LAPACK libraries through Eigen + ******************************************************************************** +*/ + +namespace Eigen { + +/** \page TopicUsingBlasLapack Using BLAS/LAPACK from %Eigen + + +Since %Eigen version 3.3 and later, any F77 compatible BLAS or LAPACK libraries can be used as backends for dense matrix products and dense matrix decompositions. +For instance, one can use Intel® MKL, Apple's Accelerate framework on OSX, OpenBLAS, Netlib LAPACK, etc. + +Do not miss this \link TopicUsingIntelMKL page \endlink for further discussions on the specific use of Intel® MKL (also includes VML, PARDISO, etc.) + +In order to use an external BLAS and/or LAPACK library, you must link you own application to the respective libraries and their dependencies. +For LAPACK, you must also link to the standard Lapacke library, which is used as a convenient think layer between %Eigen's C++ code and LAPACK F77 interface. Then you must activate their usage by defining one or multiple of the following macros (\b before including any %Eigen's header): + +\note For Mac users, in order to use the lapack version shipped with the Accelerate framework, you also need the lapacke library. +Using MacPorts, this is as easy as: +\code +sudo port install lapack +\endcode +and then use the following link flags: \c -framework \c Accelerate \c /opt/local/lib/lapack/liblapacke.dylib + +
+ + + +
\c EIGEN_USE_BLAS Enables the use of external BLAS level 2 and 3 routines (compatible with any F77 BLAS interface)
\c EIGEN_USE_LAPACKE Enables the use of external Lapack routines via the Lapacke C interface to Lapack (compatible with any F77 LAPACK interface)
\c EIGEN_USE_LAPACKE_STRICT Same as \c EIGEN_USE_LAPACKE but algorithms of lower numerical robustness are disabled. \n This currently concerns only JacobiSVD which otherwise would be replaced by \c gesvd that is less robust than Jacobi rotations.
+ +When doing so, a number of %Eigen's algorithms are silently substituted with calls to BLAS or LAPACK routines. +These substitutions apply only for \b Dynamic \b or \b large enough objects with one of the following four standard scalar types: \c float, \c double, \c complex, and \c complex. +Operations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms. + +The breadth of %Eigen functionality that can be substituted is listed in the table below. + + + + + + + + + + +
Functional domainCode exampleBLAS/LAPACK routines
Matrix-matrix operations \n \c EIGEN_USE_BLAS \code +m1*m2.transpose(); +m1.selfadjointView()*m2; +m1*m2.triangularView(); +m1.selfadjointView().rankUpdate(m2,1.0); +\endcode\code +?gemm +?symm/?hemm +?trmm +dsyrk/ssyrk +\endcode
Matrix-vector operations \n \c EIGEN_USE_BLAS \code +m1.adjoint()*b; +m1.selfadjointView()*b; +m1.triangularView()*b; +\endcode\code +?gemv +?symv/?hemv +?trmv +\endcode
LU decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +v1 = m1.lu().solve(v2); +\endcode\code +?getrf +\endcode
Cholesky decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +v1 = m2.selfadjointView().llt().solve(v2); +\endcode\code +?potrf +\endcode
QR decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +m1.householderQr(); +m1.colPivHouseholderQr(); +\endcode\code +?geqrf +?geqp3 +\endcode
Singular value decomposition \n \c EIGEN_USE_LAPACKE \code +JacobiSVD svd; +svd.compute(m1, ComputeThinV); +\endcode\code +?gesvd +\endcode
Eigen-value decompositions \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +EigenSolver es(m1); +ComplexEigenSolver ces(m1); +SelfAdjointEigenSolver saes(m1+m1.transpose()); +GeneralizedSelfAdjointEigenSolver + gsaes(m1+m1.transpose(),m2+m2.transpose()); +\endcode\code +?gees +?gees +?syev/?heev +?syev/?heev, +?potrf +\endcode
Schur decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code +RealSchur schurR(m1); +ComplexSchur schurC(m1); +\endcode\code +?gees +\endcode
+In the examples, m1 and m2 are dense matrices and v1 and v2 are dense vectors. + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox index 84db992b6..a1a3a18f2 100644 --- a/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox +++ b/gtsam/3rdparty/Eigen/doc/UsingIntelMKL.dox @@ -32,107 +32,45 @@ namespace Eigen { -/** \page TopicUsingIntelMKL Using Intel® Math Kernel Library from Eigen +/** \page TopicUsingIntelMKL Using Intel® MKL from %Eigen -\section TopicUsingIntelMKL_Intro Eigen and Intel® Math Kernel Library (Intel® MKL) + + +Since %Eigen version 3.1 and later, users can benefit from built-in Intel® Math Kernel Library (MKL) optimizations with an installed copy of Intel MKL 10.3 (or later). -Since Eigen version 3.1 and later, users can benefit from built-in Intel MKL optimizations with an installed copy of Intel MKL 10.3 (or later). Intel MKL provides highly optimized multi-threaded mathematical routines for x86-compatible architectures. Intel MKL is available on Linux, Mac and Windows for both Intel64 and IA32 architectures. \note Intel® MKL is a proprietary software and it is the responsibility of users to buy or register for community (free) Intel MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL. -Using Intel MKL through Eigen is easy: --# define the \c EIGEN_USE_MKL_ALL macro before including any Eigen's header +Using Intel MKL through %Eigen is easy: +-# define the \c EIGEN_USE_MKL_ALL macro before including any %Eigen's header -# link your program to MKL libraries (see the MKL linking advisor) -# on a 64bits system, you must use the LP64 interface (not the ILP64 one) -When doing so, a number of Eigen's algorithms are silently substituted with calls to Intel MKL routines. +When doing so, a number of %Eigen's algorithms are silently substituted with calls to Intel MKL routines. These substitutions apply only for \b Dynamic \b or \b large enough objects with one of the following four standard scalar types: \c float, \c double, \c complex, and \c complex. Operations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms. -In addition you can coarsely select choose which parts will be substituted by defining one or multiple of the following macros: +In addition you can choose which parts will be substituted by defining one or multiple of the following macros: - - - + + +
\c EIGEN_USE_BLAS Enables the use of external BLAS level 2 and 3 routines (currently works with Intel MKL only)
\c EIGEN_USE_LAPACKE Enables the use of external Lapack routines via the Intel Lapacke C interface to Lapack (currently works with Intel MKL only)
\c EIGEN_USE_LAPACKE_STRICT Same as \c EIGEN_USE_LAPACKE but algorithm of lower robustness are disabled. This currently concerns only JacobiSVD which otherwise would be replaced by \c gesvd that is less robust than Jacobi rotations.
\c EIGEN_USE_BLAS Enables the use of external BLAS level 2 and 3 routines
\c EIGEN_USE_LAPACKE Enables the use of external Lapack routines via the Lapacke C interface to Lapack
\c EIGEN_USE_LAPACKE_STRICT Same as \c EIGEN_USE_LAPACKE but algorithm of lower robustness are disabled. \n This currently concerns only JacobiSVD which otherwise would be replaced by \c gesvd that is less robust than Jacobi rotations.
\c EIGEN_USE_MKL_VML Enables the use of Intel VML (vector operations)
\c EIGEN_USE_MKL_ALL Defines \c EIGEN_USE_BLAS, \c EIGEN_USE_LAPACKE, and \c EIGEN_USE_MKL_VML
+Note that the BLAS and LAPACKE backends can be enabled for any F77 compatible BLAS and LAPACK libraries. See this \link TopicUsingBlasLapack page \endlink for the details. + Finally, the PARDISO sparse solver shipped with Intel MKL can be used through the \ref PardisoLU, \ref PardisoLLT and \ref PardisoLDLT classes of the \ref PardisoSupport_Module. - -\section TopicUsingIntelMKL_SupportedFeatures List of supported features - -The breadth of Eigen functionality covered by Intel MKL is listed in the table below. +The following table summarizes the list of functions covered by \c EIGEN_USE_MKL_VML: - - - - - - - - - - +
Functional domainCode exampleMKL routines
Matrix-matrix operations \n \c EIGEN_USE_BLAS \code -m1*m2.transpose(); -m1.selfadjointView()*m2; -m1*m2.triangularView(); -m1.selfadjointView().rankUpdate(m2,1.0); -\endcode\code -?gemm -?symm/?hemm -?trmm -dsyrk/ssyrk -\endcode
Matrix-vector operations \n \c EIGEN_USE_BLAS \code -m1.adjoint()*b; -m1.selfadjointView()*b; -m1.triangularView()*b; -\endcode\code -?gemv -?symv/?hemv -?trmv -\endcode
LU decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code -v1 = m1.lu().solve(v2); -\endcode\code -?getrf -\endcode
Cholesky decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code -v1 = m2.selfadjointView().llt().solve(v2); -\endcode\code -?potrf -\endcode
QR decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code -m1.householderQr(); -m1.colPivHouseholderQr(); -\endcode\code -?geqrf -?geqp3 -\endcode
Singular value decomposition \n \c EIGEN_USE_LAPACKE \code -JacobiSVD svd; -svd.compute(m1, ComputeThinV); -\endcode\code -?gesvd -\endcode
Eigen-value decompositions \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code -EigenSolver es(m1); -ComplexEigenSolver ces(m1); -SelfAdjointEigenSolver saes(m1+m1.transpose()); -GeneralizedSelfAdjointEigenSolver - gsaes(m1+m1.transpose(),m2+m2.transpose()); -\endcode\code -?gees -?gees -?syev/?heev -?syev/?heev, -?potrf -\endcode
Schur decomposition \n \c EIGEN_USE_LAPACKE \n \c EIGEN_USE_LAPACKE_STRICT \code -RealSchur schurR(m1); -ComplexSchur schurC(m1); -\endcode\code -?gees -\endcode
Vector Math \n \c EIGEN_USE_MKL_VML \code +
Code exampleMKL routines
\code v2=v1.array().sin(); v2=v1.array().asin(); v2=v1.array().cos(); @@ -156,7 +94,7 @@ v?Sqr v?Powx \endcode
-In the examples, m1 and m2 are dense matrices and v1 and v2 are dense vectors. +In the examples, v1 and v2 are dense vectors. \section TopicUsingIntelMKL_Links Links diff --git a/gtsam/3rdparty/Eigen/doc/UsingNVCC.dox b/gtsam/3rdparty/Eigen/doc/UsingNVCC.dox new file mode 100644 index 000000000..f8e755b79 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/UsingNVCC.dox @@ -0,0 +1,32 @@ + +namespace Eigen { + +/** \page TopicCUDA Using Eigen in CUDA kernels + +\b Disclaimer: this page is about an \b experimental feature in %Eigen. + +Staring from CUDA 5.0, the CUDA compiler, \c nvcc, is able to properly parse %Eigen's code (almost). +A few adaptations of the %Eigen's code already allows to use some parts of %Eigen in your own CUDA kernels. +To this end you need the devel branch of %Eigen, CUDA 5.0 or greater with GCC. + +Known issues: + + - \c nvcc with MS Visual Studio does not work (patch welcome) + + - \c nvcc with \c clang does not work (patch welcome) + + - \c nvcc 5.5 with gcc-4.7 (or greater) has issues with the standard \c \ header file. To workaround this, you can add the following before including any other files: + \code + // workaround issue between gcc >= 4.7 and cuda 5.5 + #if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7) + #undef _GLIBCXX_ATOMIC_BUILTINS + #undef _GLIBCXX_USE_INT128 + #endif + \endcode + + - On 64bits system Eigen uses \c long \c int as the default type for indexes and sizes. On CUDA device, it would make sense to default to 32 bits \c int. + However, to keep host and CUDA code compatible, this cannot be done automatically by %Eigen, and the user is thus required to define \c EIGEN_DEFAULT_DENSE_INDEX_TYPE to \c int throughout his code (or only for CUDA code if there is no interaction between host and CUDA code through %Eigen's object). + +*/ + +} diff --git a/gtsam/3rdparty/Eigen/doc/eigendoxy.css b/gtsam/3rdparty/Eigen/doc/eigendoxy.css index efaeb46dc..6274e6c70 100644 --- a/gtsam/3rdparty/Eigen/doc/eigendoxy.css +++ b/gtsam/3rdparty/Eigen/doc/eigendoxy.css @@ -45,7 +45,7 @@ pre.fragment { /* Common style for all Eigen's tables */ -table.example, table.manual, table.manual-vl { +table.example, table.manual, table.manual-vl, table.manual-hl { max-width:100%; border-collapse: collapse; border-style: solid; @@ -58,7 +58,7 @@ table.example, table.manual, table.manual-vl { -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); } -table.example th, table.manual th, table.manual-vl th { +table.example th, table.manual th, table.manual-vl th, table.manual-hl th { padding: 0.5em 0.5em 0.5em 0.5em; text-align: left; padding-right: 1em; @@ -70,7 +70,7 @@ table.example th, table.manual th, table.manual-vl th { filter: progid:DXImageTransform.Microsoft.gradient(startColorstr='#FFFFFF', endColorstr='#F4F4E5'); } -table.example td, table.manual td, table.manual-vl td { +table.example td, table.manual td, table.manual-vl td, table.manual-hl td { vertical-align:top; border-width: 1px; border-color: #cccccc; @@ -108,15 +108,15 @@ table.example td { /* standard class for the manual */ -table.manual, table.manual-vl { +table.manual, table.manual-vl, table.manual-hl { padding: 0.2em 0em 0.5em 0em; } -table.manual th, table.manual-vl th { +table.manual th, table.manual-vl th, table.manual-hl th { margin: 0em 0em 0.3em 0em; } -table.manual td, table.manual-vl td { +table.manual td, table.manual-vl td, table.manual-hl td { padding: 0.3em 0.5em 0.3em 0.5em; vertical-align:top; border-width: 1px; @@ -136,6 +136,16 @@ table.manual-vl th.inter { border-style: solid solid solid solid; } +table.manual-hl td { + border-color: #cccccc; + border-width: 1px; + border-style: solid none solid none; +} + +table td.code { + font-family: monospace; +} + h2 { margin-top:2em; border-style: none none solid none; @@ -166,6 +176,11 @@ div.toc ul { margin: 0.2em 0 0.4em 0.5em; } +span.cpp11,span.cpp14,span.cpp17 { + color: #119911; + font-weight: bold; +} + /**** old Eigen's styles ****/ @@ -177,8 +192,8 @@ table.tutorial_code td { /* Whenever doxygen meets a '\n' or a '
', it will put - * the text containing the characted into a

. - * This little hack togehter with table.tutorial_code td.note + * the text containing the character into a

. + * This little hack together with table.tutorial_code td.note * aims at fixing this issue. */ table.tutorial_code td.note p.starttd { margin: 0px; @@ -199,13 +214,3 @@ h3.version { td.width20em p.endtd { width: 20em; } - -.bigwarning { - font-size:2em; - font-weight:bold; - margin:1em; - padding:1em; - color:red; - border:solid; -} - diff --git a/gtsam/3rdparty/Eigen/doc/examples/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/examples/CMakeLists.txt index 08cf8efd7..f7a19055f 100644 --- a/gtsam/3rdparty/Eigen/doc/examples/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/examples/CMakeLists.txt @@ -14,3 +14,8 @@ foreach(example_src ${examples_SRCS}) ) add_dependencies(all_examples ${example}) endforeach(example_src) + +check_cxx_compiler_flag("-std=c++11" EIGEN_COMPILER_SUPPORT_CPP11) +if(EIGEN_COMPILER_SUPPORT_CPP11) +ei_add_target_property(nullary_indexing COMPILE_FLAGS "-std=c++11") +endif() \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/examples/CustomizingEigen_Inheritance.cpp b/gtsam/3rdparty/Eigen/doc/examples/CustomizingEigen_Inheritance.cpp new file mode 100644 index 000000000..48df64ee3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/CustomizingEigen_Inheritance.cpp @@ -0,0 +1,30 @@ +#include +#include + +class MyVectorType : public Eigen::VectorXd +{ +public: + MyVectorType(void):Eigen::VectorXd() {} + + // This constructor allows you to construct MyVectorType from Eigen expressions + template + MyVectorType(const Eigen::MatrixBase& other) + : Eigen::VectorXd(other) + { } + + // This method allows you to assign Eigen expressions to MyVectorType + template + MyVectorType& operator=(const Eigen::MatrixBase & other) + { + this->Eigen::VectorXd::operator=(other); + return *this; + } +}; + +int main() +{ + MyVectorType v = MyVectorType::Ones(4); + v(2) += 10; + v = 2 * v; + std::cout << v.transpose() << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/Cwise_erf.cpp b/gtsam/3rdparty/Eigen/doc/examples/Cwise_erf.cpp new file mode 100644 index 000000000..e7cd2c1c0 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/Cwise_erf.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(-0.5,2,0,-7); + std::cout << v.erf() << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/Cwise_erfc.cpp b/gtsam/3rdparty/Eigen/doc/examples/Cwise_erfc.cpp new file mode 100644 index 000000000..d8bb04c30 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/Cwise_erfc.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(-0.5,2,0,-7); + std::cout << v.erfc() << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/Cwise_lgamma.cpp b/gtsam/3rdparty/Eigen/doc/examples/Cwise_lgamma.cpp new file mode 100644 index 000000000..f1c4f503e --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/Cwise_lgamma.cpp @@ -0,0 +1,9 @@ +#include +#include +#include +using namespace Eigen; +int main() +{ + Array4d v(0.5,10,0,-1); + std::cout << v.lgamma() << std::endl; +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/examples/MatrixBase_cwise_const.cpp b/gtsam/3rdparty/Eigen/doc/examples/MatrixBase_cwise_const.cpp deleted file mode 100644 index 23700e0b6..000000000 --- a/gtsam/3rdparty/Eigen/doc/examples/MatrixBase_cwise_const.cpp +++ /dev/null @@ -1,18 +0,0 @@ -#define EIGEN2_SUPPORT -#include -#include - -using namespace Eigen; -using namespace std; - -int main() -{ - Matrix3i m = Matrix3i::Random(); - cout << "Here is the matrix m:" << endl << m << endl; - Matrix3i n = Matrix3i::Random(); - cout << "And here is the matrix n:" << endl << n << endl; - cout << "The coefficient-wise product of m and n is:" << endl; - cout << m.cwise() * n << endl; - cout << "Taking the cube of the coefficients of m yields:" << endl; - cout << m.cwise().pow(3) << endl; -} diff --git a/gtsam/3rdparty/Eigen/doc/examples/TutorialInplaceLU.cpp b/gtsam/3rdparty/Eigen/doc/examples/TutorialInplaceLU.cpp new file mode 100644 index 000000000..cb9c59b60 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/TutorialInplaceLU.cpp @@ -0,0 +1,61 @@ +#include +struct init { + init() { std::cout << "[" << "init" << "]" << std::endl; } +}; +init init_obj; +// [init] +#include +#include + +using namespace std; +using namespace Eigen; + +int main() +{ + MatrixXd A(2,2); + A << 2, -1, 1, 3; + cout << "Here is the input matrix A before decomposition:\n" << A << endl; +cout << "[init]" << endl; + +cout << "[declaration]" << endl; + PartialPivLU > lu(A); + cout << "Here is the input matrix A after decomposition:\n" << A << endl; +cout << "[declaration]" << endl; + +cout << "[matrixLU]" << endl; + cout << "Here is the matrix storing the L and U factors:\n" << lu.matrixLU() << endl; +cout << "[matrixLU]" << endl; + +cout << "[solve]" << endl; + MatrixXd A0(2,2); A0 << 2, -1, 1, 3; + VectorXd b(2); b << 1, 2; + VectorXd x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[solve]" << endl; + +cout << "[modifyA]" << endl; + A << 3, 4, -2, 1; + x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[modifyA]" << endl; + +cout << "[recompute]" << endl; + A0 = A; // save A + lu.compute(A); + x = lu.solve(b); + cout << "Residual: " << (A0 * x - b).norm() << endl; +cout << "[recompute]" << endl; + +cout << "[recompute_bis0]" << endl; + MatrixXd A1(2,2); + A1 << 5,-2,3,4; + lu.compute(A1); + cout << "Here is the input matrix A1 after decomposition:\n" << A1 << endl; +cout << "[recompute_bis0]" << endl; + +cout << "[recompute_bis1]" << endl; + x = lu.solve(b); + cout << "Residual: " << (A1 * x - b).norm() << endl; +cout << "[recompute_bis1]" << endl; + +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp b/gtsam/3rdparty/Eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp index 43970ff05..14dde5b35 100644 --- a/gtsam/3rdparty/Eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp +++ b/gtsam/3rdparty/Eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp @@ -13,4 +13,4 @@ int main() cout << "Here is the matrix A:\n" << A << endl; cout << "The determinant of A is " << A.determinant() << endl; cout << "The inverse of A is:\n" << A.inverse() << endl; -} \ No newline at end of file +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp b/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp new file mode 100644 index 000000000..62e28fc31 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp @@ -0,0 +1,18 @@ +#include +#include + +using namespace Eigen; +using namespace std; + +int main() +{ + MatrixXf m(2,2); + m << 1,-2, + -3,4; + + cout << "1-norm(m) = " << m.cwiseAbs().colwise().sum().maxCoeff() + << " == " << m.colwise().lpNorm<1>().maxCoeff() << endl; + + cout << "infty-norm(m) = " << m.cwiseAbs().rowwise().sum().maxCoeff() + << " == " << m.rowwise().lpNorm<1>().maxCoeff() << endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp new file mode 100644 index 000000000..92e6aaa2b --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp @@ -0,0 +1,11 @@ +/* +This program is presented in several fragments in the doc page. +Every fragment is in its own file; this file simply combines them. +*/ + +#include "make_circulant.cpp.preamble" +#include "make_circulant.cpp.traits" +#include "make_circulant.cpp.expression" +#include "make_circulant.cpp.evaluator" +#include "make_circulant.cpp.entry" +#include "make_circulant.cpp.main" diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.entry b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.entry new file mode 100644 index 000000000..f9d2eb8a9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.entry @@ -0,0 +1,5 @@ +template +Circulant makeCirculant(const Eigen::MatrixBase& arg) +{ + return Circulant(arg.derived()); +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.evaluator b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.evaluator new file mode 100644 index 000000000..2ba79e783 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.evaluator @@ -0,0 +1,32 @@ +namespace Eigen { + namespace internal { + template + struct evaluator > + : evaluator_base > + { + typedef Circulant XprType; + typedef typename nested_eval::type ArgTypeNested; + typedef typename remove_all::type ArgTypeNestedCleaned; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + enum { + CoeffReadCost = evaluator::CoeffReadCost, + Flags = Eigen::ColMajor + }; + + evaluator(const XprType& xpr) + : m_argImpl(xpr.m_arg), m_rows(xpr.rows()) + { } + + CoeffReturnType coeff(Index row, Index col) const + { + Index index = row - col; + if (index < 0) index += m_rows; + return m_argImpl.coeff(index); + } + + evaluator m_argImpl; + const Index m_rows; + }; + } +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.expression b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.expression new file mode 100644 index 000000000..380cd4450 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.expression @@ -0,0 +1,20 @@ +template +class Circulant : public Eigen::MatrixBase > +{ +public: + Circulant(const ArgType& arg) + : m_arg(arg) + { + EIGEN_STATIC_ASSERT(ArgType::ColsAtCompileTime == 1, + YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX); + } + + typedef typename Eigen::internal::ref_selector::type Nested; + + typedef Eigen::Index Index; + Index rows() const { return m_arg.rows(); } + Index cols() const { return m_arg.rows(); } + + typedef typename Eigen::internal::ref_selector::type ArgTypeNested; + ArgTypeNested m_arg; +}; diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.main b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.main new file mode 100644 index 000000000..877f97f62 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.main @@ -0,0 +1,8 @@ +int main() +{ + Eigen::VectorXd vec(4); + vec << 1, 2, 4, 8; + Eigen::MatrixXd mat; + mat = makeCirculant(vec); + std::cout << mat << std::endl; +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.preamble b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.preamble new file mode 100644 index 000000000..e575cce14 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.preamble @@ -0,0 +1,4 @@ +#include +#include + +template class Circulant; diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.traits b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.traits new file mode 100644 index 000000000..4e04535d3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant.cpp.traits @@ -0,0 +1,19 @@ +namespace Eigen { + namespace internal { + template + struct traits > + { + typedef Eigen::Dense StorageKind; + typedef Eigen::MatrixXpr XprKind; + typedef typename ArgType::StorageIndex StorageIndex; + typedef typename ArgType::Scalar Scalar; + enum { + Flags = Eigen::ColMajor, + RowsAtCompileTime = ArgType::RowsAtCompileTime, + ColsAtCompileTime = ArgType::RowsAtCompileTime, + MaxRowsAtCompileTime = ArgType::MaxRowsAtCompileTime, + MaxColsAtCompileTime = ArgType::MaxRowsAtCompileTime + }; + }; + } +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/make_circulant2.cpp b/gtsam/3rdparty/Eigen/doc/examples/make_circulant2.cpp new file mode 100644 index 000000000..95d3dd31a --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/make_circulant2.cpp @@ -0,0 +1,52 @@ +#include +#include + +using namespace Eigen; + +// [circulant_func] +template +class circulant_functor { + const ArgType &m_vec; +public: + circulant_functor(const ArgType& arg) : m_vec(arg) {} + + const typename ArgType::Scalar& operator() (Index row, Index col) const { + Index index = row - col; + if (index < 0) index += m_vec.size(); + return m_vec(index); + } +}; +// [circulant_func] + +// [square] +template +struct circulant_helper { + typedef Matrix MatrixType; +}; +// [square] + +// [makeCirculant] +template +CwiseNullaryOp, typename circulant_helper::MatrixType> +makeCirculant(const Eigen::MatrixBase& arg) +{ + typedef typename circulant_helper::MatrixType MatrixType; + return MatrixType::NullaryExpr(arg.size(), arg.size(), circulant_functor(arg.derived())); +} +// [makeCirculant] + +// [main] +int main() +{ + Eigen::VectorXd vec(4); + vec << 1, 2, 4, 8; + Eigen::MatrixXd mat; + mat = makeCirculant(vec); + std::cout << mat << std::endl; +} +// [main] diff --git a/gtsam/3rdparty/Eigen/doc/examples/matrixfree_cg.cpp b/gtsam/3rdparty/Eigen/doc/examples/matrixfree_cg.cpp new file mode 100644 index 000000000..6a205aea3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/matrixfree_cg.cpp @@ -0,0 +1,128 @@ +#include +#include +#include +#include +#include + +class MatrixReplacement; +using Eigen::SparseMatrix; + +namespace Eigen { +namespace internal { + // MatrixReplacement looks-like a SparseMatrix, so let's inherits its traits: + template<> + struct traits : public Eigen::internal::traits > + {}; +} +} + +// Example of a matrix-free wrapper from a user type to Eigen's compatible type +// For the sake of simplicity, this example simply wrap a Eigen::SparseMatrix. +class MatrixReplacement : public Eigen::EigenBase { +public: + // Required typedefs, constants, and method: + typedef double Scalar; + typedef double RealScalar; + typedef int StorageIndex; + enum { + ColsAtCompileTime = Eigen::Dynamic, + MaxColsAtCompileTime = Eigen::Dynamic, + IsRowMajor = false + }; + + Index rows() const { return mp_mat->rows(); } + Index cols() const { return mp_mat->cols(); } + + template + Eigen::Product operator*(const Eigen::MatrixBase& x) const { + return Eigen::Product(*this, x.derived()); + } + + // Custom API: + MatrixReplacement() : mp_mat(0) {} + + void attachMyMatrix(const SparseMatrix &mat) { + mp_mat = &mat; + } + const SparseMatrix my_matrix() const { return *mp_mat; } + +private: + const SparseMatrix *mp_mat; +}; + + +// Implementation of MatrixReplacement * Eigen::DenseVector though a specialization of internal::generic_product_impl: +namespace Eigen { +namespace internal { + + template + struct generic_product_impl // GEMV stands for matrix-vector + : generic_product_impl_base > + { + typedef typename Product::Scalar Scalar; + + template + static void scaleAndAddTo(Dest& dst, const MatrixReplacement& lhs, const Rhs& rhs, const Scalar& alpha) + { + // This method should implement "dst += alpha * lhs * rhs" inplace, + // however, for iterative solvers, alpha is always equal to 1, so let's not bother about it. + assert(alpha==Scalar(1) && "scaling is not implemented"); + + // Here we could simply call dst.noalias() += lhs.my_matrix() * rhs, + // but let's do something fancier (and less efficient): + for(Index i=0; i S = Eigen::MatrixXd::Random(n,n).sparseView(0.5,1); + S = S.transpose()*S; + + MatrixReplacement A; + A.attachMyMatrix(S); + + Eigen::VectorXd b(n), x; + b.setRandom(); + + // Solve Ax = b using various iterative solver with matrix-free version: + { + Eigen::ConjugateGradient cg; + cg.compute(A); + x = cg.solve(b); + std::cout << "CG: #iterations: " << cg.iterations() << ", estimated error: " << cg.error() << std::endl; + } + + { + Eigen::BiCGSTAB bicg; + bicg.compute(A); + x = bicg.solve(b); + std::cout << "BiCGSTAB: #iterations: " << bicg.iterations() << ", estimated error: " << bicg.error() << std::endl; + } + + { + Eigen::GMRES gmres; + gmres.compute(A); + x = gmres.solve(b); + std::cout << "GMRES: #iterations: " << gmres.iterations() << ", estimated error: " << gmres.error() << std::endl; + } + + { + Eigen::DGMRES gmres; + gmres.compute(A); + x = gmres.solve(b); + std::cout << "DGMRES: #iterations: " << gmres.iterations() << ", estimated error: " << gmres.error() << std::endl; + } + + { + Eigen::MINRES minres; + minres.compute(A); + x = minres.solve(b); + std::cout << "MINRES: #iterations: " << minres.iterations() << ", estimated error: " << minres.error() << std::endl; + } +} diff --git a/gtsam/3rdparty/Eigen/doc/examples/nullary_indexing.cpp b/gtsam/3rdparty/Eigen/doc/examples/nullary_indexing.cpp new file mode 100644 index 000000000..e27c3585a --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/examples/nullary_indexing.cpp @@ -0,0 +1,66 @@ +#include +#include + +using namespace Eigen; + +// [functor] +template +class indexing_functor { + const ArgType &m_arg; + const RowIndexType &m_rowIndices; + const ColIndexType &m_colIndices; +public: + typedef Matrix MatrixType; + + indexing_functor(const ArgType& arg, const RowIndexType& row_indices, const ColIndexType& col_indices) + : m_arg(arg), m_rowIndices(row_indices), m_colIndices(col_indices) + {} + + const typename ArgType::Scalar& operator() (Index row, Index col) const { + return m_arg(m_rowIndices[row], m_colIndices[col]); + } +}; +// [functor] + +// [function] +template +CwiseNullaryOp, typename indexing_functor::MatrixType> +indexing(const Eigen::MatrixBase& arg, const RowIndexType& row_indices, const ColIndexType& col_indices) +{ + typedef indexing_functor Func; + typedef typename Func::MatrixType MatrixType; + return MatrixType::NullaryExpr(row_indices.size(), col_indices.size(), Func(arg.derived(), row_indices, col_indices)); +} +// [function] + + +int main() +{ + std::cout << "[main1]\n"; + Eigen::MatrixXi A = Eigen::MatrixXi::Random(4,4); + Array3i ri(1,2,1); + ArrayXi ci(6); ci << 3,2,1,0,0,2; + Eigen::MatrixXi B = indexing(A, ri, ci); + std::cout << "A =" << std::endl; + std::cout << A << std::endl << std::endl; + std::cout << "A([" << ri.transpose() << "], [" << ci.transpose() << "]) =" << std::endl; + std::cout << B << std::endl; + std::cout << "[main1]\n"; + + std::cout << "[main2]\n"; + B = indexing(A, ri+1, ci); + std::cout << "A(ri+1,ci) =" << std::endl; + std::cout << B << std::endl << std::endl; +#if __cplusplus >= 201103L + B = indexing(A, ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)); + std::cout << "A(ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)) =" << std::endl; + std::cout << B << std::endl << std::endl; +#endif + std::cout << "[main2]\n"; +} + diff --git a/gtsam/3rdparty/Eigen/doc/ftv2node.png b/gtsam/3rdparty/Eigen/doc/ftv2node.png new file mode 100644 index 0000000000000000000000000000000000000000..63c605bb4c3d941c921a4b6cfa74951e946bcb48 GIT binary patch literal 86 zcmeAS@N?(olHy`uVBq!ia0vp^0zfRr!3HExu9B$%QnH>djv*C{Z|`mdau^P8_z}#X h?B8GEpdi4(BFDx$je&7RrDQEg&ePS;Wt~$(69Dh@6T1Ka literal 0 HcmV?d00001 diff --git a/gtsam/3rdparty/Eigen/doc/ftv2pnode.png b/gtsam/3rdparty/Eigen/doc/ftv2pnode.png new file mode 100644 index 0000000000000000000000000000000000000000..c6ee22f937a07d1dbfc27c669d11f8ed13e2f152 GIT binary patch literal 229 zcmV^P)R?RzRoKvklcaQ%HF6%rK2&ZgO(-ihJ_C zzrKgp4jgO( fd_(yg|3PpEQb#9`a?Pz_00000NkvXXu0mjftR`5K literal 0 HcmV?d00001 diff --git a/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_simple.cpp b/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_simple.cpp new file mode 100644 index 000000000..5520f4f1f --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_simple.cpp @@ -0,0 +1,11 @@ + int n = 10000; + VectorXd x(n), b(n); + SparseMatrix A(n,n); + /* ... fill A and b ... */ + BiCGSTAB > solver; + solver.compute(A); + x = solver.solve(b); + std::cout << "#iterations: " << solver.iterations() << std::endl; + std::cout << "estimated error: " << solver.error() << std::endl; + /* ... update b ... */ + x = solver.solve(b); // solve again \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_step_by_step.cpp b/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_step_by_step.cpp new file mode 100644 index 000000000..06147bb81 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/BiCGSTAB_step_by_step.cpp @@ -0,0 +1,14 @@ + int n = 10000; + VectorXd x(n), b(n); + SparseMatrix A(n,n); + /* ... fill A and b ... */ + BiCGSTAB > solver(A); + // start from a random solution + x = VectorXd::Random(n); + solver.setMaxIterations(1); + int i = 0; + do { + x = solver.solveWithGuess(b,x); + std::cout << i << " : " << solver.error() << std::endl; + ++i; + } while (solver.info()!=Success && i<100); \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/snippets/CMakeLists.txt index 1135900cf..1baf32fba 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/snippets/CMakeLists.txt @@ -24,5 +24,3 @@ foreach(snippet_src ${snippets_SRCS}) set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src} PROPERTIES OBJECT_DEPENDS ${snippet_src}) endforeach(snippet_src) - -ei_add_target_property(compile_tut_arithmetic_transpose_aliasing COMPILE_FLAGS -DEIGEN_NO_DEBUG) diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_arg.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_arg.cpp new file mode 100644 index 000000000..3f45133b6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_arg.cpp @@ -0,0 +1,3 @@ +ArrayXcf v = ArrayXcf::Random(3); +cout << v << endl << endl; +cout << arg(v) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_array_power_array.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_array_power_array.cpp new file mode 100644 index 000000000..432a76ee5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_array_power_array.cpp @@ -0,0 +1,4 @@ +Array x(8,25,3), + e(1./3.,0.5,2.); +cout << "[" << x << "]^[" << e << "] = " << x.pow(e) << endl; // using ArrayBase::pow +cout << "[" << x << "]^[" << e << "] = " << pow(x,e) << endl; // using Eigen::pow diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_atan.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_atan.cpp new file mode 100644 index 000000000..446844726 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_atan.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << v.atan() << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_not.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_not.cpp new file mode 100644 index 000000000..40009f15a --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_not.cpp @@ -0,0 +1,5 @@ +Array3d v(1,2,3); +v(1) *= 0.0/0.0; +v(2) /= 0.0; +cout << v << endl << endl; +cout << !isfinite(v) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_xor.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_xor.cpp new file mode 100644 index 000000000..fafbec806 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_boolean_xor.cpp @@ -0,0 +1,2 @@ +Array3d v(-1,2,1), w(-3,2,3); +cout << ((v e(2,-3,1./3.); +cout << "10^[" << e << "] = " << pow(10,e) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sign.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sign.cpp new file mode 100644 index 000000000..49920e4f1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sign.cpp @@ -0,0 +1,2 @@ +Array3d v(-3,5,0); +cout << v.sign() << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sinh.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sinh.cpp new file mode 100644 index 000000000..fac9b19a8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_sinh.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << sinh(v) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Cwise_tanh.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_tanh.cpp new file mode 100644 index 000000000..30cd0450d --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Cwise_tanh.cpp @@ -0,0 +1,2 @@ +ArrayXd v = ArrayXd::LinSpaced(5,0,1); +cout << tanh(v) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/DenseBase_LinSpacedInt.cpp b/gtsam/3rdparty/Eigen/doc/snippets/DenseBase_LinSpacedInt.cpp new file mode 100644 index 000000000..0d7ae068e --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/DenseBase_LinSpacedInt.cpp @@ -0,0 +1,8 @@ +cout << "Even spacing inputs:" << endl; +cout << VectorXi::LinSpaced(8,1,4).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,8).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,15).transpose() << endl; +cout << "Uneven spacing inputs:" << endl; +cout << VectorXi::LinSpaced(8,1,7).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,9).transpose() << endl; +cout << VectorXi::LinSpaced(8,1,16).transpose() << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/DirectionWise_hnormalized.cpp b/gtsam/3rdparty/Eigen/doc/snippets/DirectionWise_hnormalized.cpp new file mode 100644 index 000000000..3410790a8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/DirectionWise_hnormalized.cpp @@ -0,0 +1,7 @@ +typedef Matrix Matrix4Xd; +Matrix4Xd M = Matrix4Xd::Random(4,5); +Projective3d P(Matrix4d::Random()); +cout << "The matrix M is:" << endl << M << endl << endl; +cout << "M.colwise().hnormalized():" << endl << M.colwise().hnormalized() << endl << endl; +cout << "P*M:" << endl << P*M << endl << endl; +cout << "(P*M).colwise().hnormalized():" << endl << (P*M).colwise().hnormalized() << endl << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/EigenSolver_eigenvectors.cpp b/gtsam/3rdparty/Eigen/doc/snippets/EigenSolver_eigenvectors.cpp index 0fad4dadb..8355f76c9 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/EigenSolver_eigenvectors.cpp +++ b/gtsam/3rdparty/Eigen/doc/snippets/EigenSolver_eigenvectors.cpp @@ -1,4 +1,4 @@ MatrixXd ones = MatrixXd::Ones(3,3); EigenSolver es(ones); -cout << "The first eigenvector of the 3x3 matrix of ones is:" - << endl << es.eigenvectors().col(1) << endl; +cout << "The first eigenvector of the 3x3 matrix of ones is:" + << endl << es.eigenvectors().col(0) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresNormalEquations.cpp b/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresNormalEquations.cpp new file mode 100644 index 000000000..997cf1715 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresNormalEquations.cpp @@ -0,0 +1,4 @@ +MatrixXf A = MatrixXf::Random(3, 2); +VectorXf b = VectorXf::Random(3); +cout << "The solution using normal equations is:\n" + << (A.transpose() * A).ldlt().solve(A.transpose() * b) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresQR.cpp b/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresQR.cpp new file mode 100644 index 000000000..6c9704547 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/LeastSquaresQR.cpp @@ -0,0 +1,4 @@ +MatrixXf A = MatrixXf::Random(3, 2); +VectorXf b = VectorXf::Random(3); +cout << "The solution using the QR decomposition is:\n" + << A.colPivHouseholderQr().solve(b) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_cwiseSign.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_cwiseSign.cpp new file mode 100644 index 000000000..efd717955 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_cwiseSign.cpp @@ -0,0 +1,4 @@ +MatrixXd m(2,3); +m << 2, -4, 6, + -5, 1, 0; +cout << m.cwiseSign() << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_hnormalized.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_hnormalized.cpp new file mode 100644 index 000000000..652cd77c0 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_hnormalized.cpp @@ -0,0 +1,6 @@ +Vector4d v = Vector4d::Random(); +Projective3d P(Matrix4d::Random()); +cout << "v = " << v.transpose() << "]^T" << endl; +cout << "v.hnormalized() = " << v.hnormalized().transpose() << "]^T" << endl; +cout << "P*v = " << (P*v).transpose() << "]^T" << endl; +cout << "(P*v).hnormalized() = " << (P*v).hnormalized().transpose() << "]^T" << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_homogeneous.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_homogeneous.cpp new file mode 100644 index 000000000..457c28f91 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_homogeneous.cpp @@ -0,0 +1,6 @@ +Vector3d v = Vector3d::Random(), w; +Projective3d P(Matrix4d::Random()); +cout << "v = [" << v.transpose() << "]^T" << endl; +cout << "h.homogeneous() = [" << v.homogeneous().transpose() << "]^T" << endl; +cout << "(P * v.homogeneous()) = [" << (P * v.homogeneous()).transpose() << "]^T" << endl; +cout << "(P * v.homogeneous()).hnormalized() = [" << (P * v.homogeneous()).eval().hnormalized().transpose() << "]^T" << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_marked.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_marked.cpp deleted file mode 100644 index f60712178..000000000 --- a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_marked.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef _MSC_VER - #warning deprecated -#endif -/* -Matrix3d m = Matrix3d::Zero(); -m.part().setOnes(); -cout << "Here is the matrix m:" << endl << m << endl; -Matrix3d n = Matrix3d::Ones(); -n.part() *= 2; -cout << "Here is the matrix n:" << endl << n << endl; -cout << "And now here is m.inverse()*n, taking advantage of the fact that" - " m is upper-triangular:" << endl - << m.marked().solveTriangular(n); -*/ \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_part.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_part.cpp deleted file mode 100644 index d3e7f482e..000000000 --- a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_part.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#ifndef _MSC_VER - #warning deprecated -#endif -/* -Matrix3d m = Matrix3d::Zero(); -m.part().setOnes(); -cout << "Here is the matrix m:" << endl << m << endl; -cout << "And let us now compute m*m.adjoint() in a very optimized way" << endl - << "taking advantage of the symmetry." << endl; -Matrix3d n; -n.part() = (m*m.adjoint()).lazy(); -cout << "The result is:" << endl << n << endl; -*/ \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_selfadjointView.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_selfadjointView.cpp new file mode 100644 index 000000000..4bd3c7eeb --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_selfadjointView.cpp @@ -0,0 +1,6 @@ +Matrix3i m = Matrix3i::Random(); +cout << "Here is the matrix m:" << endl << m << endl; +cout << "Here is the symmetric matrix extracted from the upper part of m:" << endl + << Matrix3i(m.selfadjointView()) << endl; +cout << "Here is the symmetric matrix extracted from the lower part of m:" << endl + << Matrix3i(m.selfadjointView()) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_extract.cpp b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_triangularView.cpp similarity index 55% rename from gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_extract.cpp rename to gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_triangularView.cpp index c96220f72..03aa303f0 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_extract.cpp +++ b/gtsam/3rdparty/Eigen/doc/snippets/MatrixBase_triangularView.cpp @@ -1,13 +1,9 @@ -#ifndef _MSC_VER - #warning deprecated -#endif -/* deprecated Matrix3i m = Matrix3i::Random(); cout << "Here is the matrix m:" << endl << m << endl; cout << "Here is the upper-triangular matrix extracted from m:" << endl - << m.part() << endl; + << Matrix3i(m.triangularView()) << endl; cout << "Here is the strictly-upper-triangular matrix extracted from m:" << endl - << m.part() << endl; + << Matrix3i(m.triangularView()) << endl; cout << "Here is the unit-lower-triangular matrix extracted from m:" << endl - << m.part() << endl; -*/ \ No newline at end of file + << Matrix3i(m.triangularView()) << endl; +// FIXME need to implement output for triangularViews (Bug 885) diff --git a/gtsam/3rdparty/Eigen/doc/snippets/PartialRedux_count.cpp b/gtsam/3rdparty/Eigen/doc/snippets/PartialRedux_count.cpp index c7b3097e4..1c3b3a28f 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/PartialRedux_count.cpp +++ b/gtsam/3rdparty/Eigen/doc/snippets/PartialRedux_count.cpp @@ -1,3 +1,5 @@ Matrix3d m = Matrix3d::Random(); cout << "Here is the matrix m:" << endl << m << endl; -cout << "Here is the count of elements larger or equal than 0.5 of each row:" << endl << (m.array() >= 0.5).rowwise().count() << endl; +Matrix res = (m.array() >= 0.5).rowwise().count(); +cout << "Here is the count of elements larger or equal than 0.5 of each row:" << endl; +cout << res << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/SparseMatrix_coeffs.cpp b/gtsam/3rdparty/Eigen/doc/snippets/SparseMatrix_coeffs.cpp new file mode 100644 index 000000000..f71a69b07 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/SparseMatrix_coeffs.cpp @@ -0,0 +1,9 @@ +SparseMatrix A(3,3); +A.insert(1,2) = 0; +A.insert(0,1) = 1; +A.insert(2,0) = 2; +A.makeCompressed(); +cout << "The matrix A is:" << endl << MatrixXd(A) << endl; +cout << "it has " << A.nonZeros() << " stored non zero coefficients that are: " << A.coeffs().transpose() << endl; +A.coeffs() += 10; +cout << "After adding 10 to every stored non zero coefficient, the matrix A is:" << endl << MatrixXd(A) << endl; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult4.cpp b/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult4.cpp new file mode 100644 index 000000000..8a8992f6c --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult4.cpp @@ -0,0 +1,5 @@ +MatrixXf A(2,2), B(3,2); +B << 2, 0, 0, 3, 1, 1; +A << 2, 0, 0, -2; +A = (B * A).cwiseAbs(); +cout << A; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult5.cpp b/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult5.cpp new file mode 100644 index 000000000..1a36defde --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/TopicAliasing_mult5.cpp @@ -0,0 +1,5 @@ +MatrixXf A(2,2), B(3,2); +B << 2, 0, 0, 3, 1, 1; +A << 2, 0, 0, -2; +A = (B * A).eval().cwiseAbs(); +cout << A; diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Triangular_solve.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Triangular_solve.cpp new file mode 100644 index 000000000..548442467 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Triangular_solve.cpp @@ -0,0 +1,11 @@ +Matrix3d m = Matrix3d::Zero(); +m.triangularView().setOnes(); +cout << "Here is the matrix m:\n" << m << endl; +Matrix3d n = Matrix3d::Ones(); +n.triangularView() *= 2; +cout << "Here is the matrix n:\n" << n << endl; +cout << "And now here is m.inverse()*n, taking advantage of the fact that" + " m is upper-triangular:\n" + << m.triangularView().solve(n) << endl; +cout << "And this is n*m.inverse():\n" + << m.triangularView().solve(n); diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp index 84e8715cb..55a21539d 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp +++ b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp @@ -3,7 +3,7 @@ vec1 << 1, 2, 3; std::cout << "vec1 = " << vec1 << std::endl; RowVectorXd vec2(4); -vec2 << 1, 4, 9, 16;; +vec2 << 1, 4, 9, 16; std::cout << "vec2 = " << vec2 << std::endl; RowVectorXd joined(7); diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp new file mode 100644 index 000000000..f84d6e76d --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp @@ -0,0 +1,6 @@ +MatrixXf M1(2,6); // Column-major storage +M1 << 1, 2, 3, 4, 5, 6, + 7, 8, 9, 10, 11, 12; + +Map M2(M1.data(), 6,2); +cout << "M2:" << endl << M2 << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp new file mode 100644 index 000000000..95bd4e0e6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp @@ -0,0 +1,11 @@ +MatrixXf M1(3,3); // Column-major storage +M1 << 1, 2, 3, + 4, 5, 6, + 7, 8, 9; + +Map v1(M1.data(), M1.size()); +cout << "v1:" << endl << v1 << endl; + +Matrix M2(M1); +Map v2(M2.data(), M2.size()); +cout << "v2:" << endl << v2 << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingCol.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingCol.cpp new file mode 100644 index 000000000..f667ff689 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingCol.cpp @@ -0,0 +1,11 @@ +MatrixXf M1 = MatrixXf::Random(3,8); +cout << "Column major input:" << endl << M1 << "\n"; +Map > M2(M1.data(), M1.rows(), (M1.cols()+2)/3, OuterStride<>(M1.outerStride()*3)); +cout << "1 column over 3:" << endl << M2 << "\n"; + +typedef Matrix RowMajorMatrixXf; +RowMajorMatrixXf M3(M1); +cout << "Row major input:" << endl << M3 << "\n"; +Map > M4(M3.data(), M3.rows(), (M3.cols()+2)/3, + Stride(M3.outerStride(),3)); +cout << "1 column over 3:" << endl << M4 << "\n"; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingVec.cpp b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingVec.cpp new file mode 100644 index 000000000..07e10bf69 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/Tutorial_SlicingVec.cpp @@ -0,0 +1,4 @@ +RowVectorXf v = RowVectorXf::LinSpaced(20,0,19); +cout << "Input:" << endl << v << endl; +Map > v2(v.data(), v.size()/2); +cout << "Even:" << v2 << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/VectorwiseOp_homogeneous.cpp b/gtsam/3rdparty/Eigen/doc/snippets/VectorwiseOp_homogeneous.cpp new file mode 100644 index 000000000..aba4fed0e --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/snippets/VectorwiseOp_homogeneous.cpp @@ -0,0 +1,7 @@ +typedef Matrix Matrix3Xd; +Matrix3Xd M = Matrix3Xd::Random(3,5); +Projective3d P(Matrix4d::Random()); +cout << "The matrix M is:" << endl << M << endl << endl; +cout << "M.colwise().homogeneous():" << endl << M.colwise().homogeneous() << endl << endl; +cout << "P * M.colwise().homogeneous():" << endl << P * M.colwise().homogeneous() << endl << endl; +cout << "P * M.colwise().homogeneous().hnormalized(): " << endl << (P * M.colwise().homogeneous()).colwise().hnormalized() << endl << endl; \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in b/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in index 894cd526c..d63f371a3 100644 --- a/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in +++ b/gtsam/3rdparty/Eigen/doc/snippets/compile_snippet.cpp.in @@ -1,5 +1,13 @@ -#include +static bool eigen_did_assert = false; +#define eigen_assert(X) if(!eigen_did_assert && !(X)){ std::cout << "### Assertion raised in " << __FILE__ << ":" << __LINE__ << ":\n" #X << "\n### The following would happen without assertions:\n"; eigen_did_assert = true;} + #include +#include + +#ifndef M_PI +#define M_PI 3.1415926535897932384626433832795 +#endif + using namespace Eigen; using namespace std; diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt index 3ab75dbfe..101fbc5f9 100644 --- a/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/doc/special_examples/CMakeLists.txt @@ -19,3 +19,17 @@ if(QT4_FOUND) add_dependencies(all_examples Tutorial_sparse_example) endif(QT4_FOUND) +check_cxx_compiler_flag("-std=c++11" EIGEN_COMPILER_SUPPORT_CPP11) +if(EIGEN_COMPILER_SUPPORT_CPP11) + add_executable(random_cpp11 random_cpp11.cpp) + target_link_libraries(random_cpp11 ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}) + add_dependencies(all_examples random_cpp11) + ei_add_target_property(random_cpp11 COMPILE_FLAGS "-std=c++11") + + add_custom_command( + TARGET random_cpp11 + POST_BUILD + COMMAND random_cpp11 + ARGS >${CMAKE_CURRENT_BINARY_DIR}/random_cpp11.out + ) +endif() diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp index 002f19f01..830e196ea 100644 --- a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp +++ b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example.cpp @@ -9,6 +9,8 @@ void saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename); int main(int argc, char** argv) { + assert(argc==2); + int n = 300; // size of the image int m = n*n; // number of unknows (=number of pixels) diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp index 7d820b44a..bc18b0188 100644 --- a/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp +++ b/gtsam/3rdparty/Eigen/doc/special_examples/Tutorial_sparse_example_details.cpp @@ -8,7 +8,7 @@ typedef Eigen::Triplet T; void insertCoefficient(int id, int i, int j, double w, std::vector& coeffs, Eigen::VectorXd& b, const Eigen::VectorXd& boundary) { - int n = boundary.size(); + int n = int(boundary.size()); int id1 = i+j*n; if(i==-1 || i==n) b(id) -= w * boundary(j); // constrained coefficient diff --git a/gtsam/3rdparty/Eigen/doc/special_examples/random_cpp11.cpp b/gtsam/3rdparty/Eigen/doc/special_examples/random_cpp11.cpp new file mode 100644 index 000000000..33744c051 --- /dev/null +++ b/gtsam/3rdparty/Eigen/doc/special_examples/random_cpp11.cpp @@ -0,0 +1,14 @@ +#include +#include +#include + +using namespace Eigen; + +int main() { + std::default_random_engine generator; + std::poisson_distribution distribution(4.1); + auto poisson = [&] () {return distribution(generator);}; + + RowVectorXi v = RowVectorXi::NullaryExpr(10, poisson ); + std::cout << v << "\n"; +} diff --git a/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt b/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt index cadc6a255..1a73f05e6 100644 --- a/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/failtest/CMakeLists.txt @@ -7,6 +7,9 @@ ei_add_failtest("block_nonconst_ctor_on_const_xpr_1") ei_add_failtest("block_nonconst_ctor_on_const_xpr_2") ei_add_failtest("transpose_nonconst_ctor_on_const_xpr") ei_add_failtest("diagonal_nonconst_ctor_on_const_xpr") +ei_add_failtest("cwiseunaryview_nonconst_ctor_on_const_xpr") +ei_add_failtest("triangularview_nonconst_ctor_on_const_xpr") +ei_add_failtest("selfadjointview_nonconst_ctor_on_const_xpr") ei_add_failtest("const_qualified_block_method_retval_0") ei_add_failtest("const_qualified_block_method_retval_1") @@ -25,6 +28,9 @@ ei_add_failtest("block_on_const_type_actually_const_0") ei_add_failtest("block_on_const_type_actually_const_1") ei_add_failtest("transpose_on_const_type_actually_const") ei_add_failtest("diagonal_on_const_type_actually_const") +ei_add_failtest("cwiseunaryview_on_const_type_actually_const") +ei_add_failtest("triangularview_on_const_type_actually_const") +ei_add_failtest("selfadjointview_on_const_type_actually_const") ei_add_failtest("ref_1") ei_add_failtest("ref_2") @@ -32,6 +38,20 @@ ei_add_failtest("ref_3") ei_add_failtest("ref_4") ei_add_failtest("ref_5") +ei_add_failtest("swap_1") +ei_add_failtest("swap_2") + +ei_add_failtest("ternary_1") +ei_add_failtest("ternary_2") + +ei_add_failtest("sparse_ref_1") +ei_add_failtest("sparse_ref_2") +ei_add_failtest("sparse_ref_3") +ei_add_failtest("sparse_ref_4") +ei_add_failtest("sparse_ref_5") + +ei_add_failtest("sparse_storage_mismatch") + ei_add_failtest("partialpivlu_int") ei_add_failtest("fullpivlu_int") ei_add_failtest("llt_int") @@ -40,6 +60,7 @@ ei_add_failtest("qr_int") ei_add_failtest("colpivqr_int") ei_add_failtest("fullpivqr_int") ei_add_failtest("jacobisvd_int") +ei_add_failtest("bdcsvd_int") ei_add_failtest("eigensolver_int") ei_add_failtest("eigensolver_cplx") diff --git a/gtsam/3rdparty/Eigen/failtest/bdcsvd_int.cpp b/gtsam/3rdparty/Eigen/failtest/bdcsvd_int.cpp new file mode 100644 index 000000000..670752cf5 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/bdcsvd_int.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/SVD" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define SCALAR int +#else +#define SCALAR float +#endif + +using namespace Eigen; + +int main() +{ + BDCSVD > qr(Matrix::Random(10,10)); +} diff --git a/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp b/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 000000000..e23cf8fd8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + CwiseUnaryView,Matrix3d> t(m); +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp b/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp new file mode 100644 index 000000000..fcd41dfdb --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + CwiseUnaryView,CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp b/gtsam/3rdparty/Eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 000000000..a240f8184 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + SelfAdjointView t(m); +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/failtest/selfadjointview_on_const_type_actually_const.cpp b/gtsam/3rdparty/Eigen/failtest/selfadjointview_on_const_type_actually_const.cpp new file mode 100644 index 000000000..19aaad6d0 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/selfadjointview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + SelfAdjointView(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_ref_1.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_ref_1.cpp new file mode 100644 index 000000000..d78d1f9b1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_ref_1.cpp @@ -0,0 +1,18 @@ +#include "../Eigen/Sparse" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix a(10,10); + CV_QUALIFIER SparseMatrix& ac(a); + call_ref(ac); +} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_ref_2.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_ref_2.cpp new file mode 100644 index 000000000..46c9440c2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_ref_2.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.row(3)); +#else + call_ref(A.col(3)); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_ref_3.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_ref_3.cpp new file mode 100644 index 000000000..a9949b552 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_ref_3.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +void call_ref(Ref > a) { } +#else +void call_ref(const Ref > &a) { } +#endif + +int main() +{ + SparseMatrix a(10,10); + call_ref(a+a); +} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_ref_4.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_ref_4.cpp new file mode 100644 index 000000000..57bb6a1fc --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_ref_4.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) {} + +int main() +{ + SparseMatrix A(10,10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(A.transpose()); +#else + call_ref(A); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_ref_5.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_ref_5.cpp new file mode 100644 index 000000000..4478f6f2f --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_ref_5.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Sparse" + +using namespace Eigen; + +void call_ref(Ref > a) { } + +int main() +{ + SparseMatrix a(10,10); + SparseMatrixBase > &ac(a); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + call_ref(ac); +#else + call_ref(ac.derived()); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/sparse_storage_mismatch.cpp b/gtsam/3rdparty/Eigen/failtest/sparse_storage_mismatch.cpp new file mode 100644 index 000000000..51840d416 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/sparse_storage_mismatch.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Sparse" +using namespace Eigen; + +typedef SparseMatrix Mat1; +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +typedef SparseMatrix Mat2; +#else +typedef SparseMatrix Mat2; +#endif + +int main() +{ + Mat1 a(10,10); + Mat2 b(10,10); + a += b; +} diff --git a/gtsam/3rdparty/Eigen/failtest/swap_1.cpp b/gtsam/3rdparty/Eigen/failtest/swap_1.cpp new file mode 100644 index 000000000..106379720 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/swap_1.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main() +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + const DenseBase &ac(a); +#else + DenseBase &ac(a); +#endif + b.swap(ac); +} diff --git a/gtsam/3rdparty/Eigen/failtest/swap_2.cpp b/gtsam/3rdparty/Eigen/failtest/swap_2.cpp new file mode 100644 index 000000000..c130ba6e4 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/swap_2.cpp @@ -0,0 +1,14 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main() +{ + VectorXf a(10), b(10); + VectorXf const &ac(a); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b.swap(ac); +#else + b.swap(ac.const_cast_derived()); +#endif +} \ No newline at end of file diff --git a/gtsam/3rdparty/Eigen/failtest/ternary_1.cpp b/gtsam/3rdparty/Eigen/failtest/ternary_1.cpp new file mode 100644 index 000000000..b40bcb0cc --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ternary_1.cpp @@ -0,0 +1,13 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main(int argc,char **) +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b = argc>1 ? 2*a : -a; +#else + b = argc>1 ? 2*a : VectorXf(-a); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/ternary_2.cpp b/gtsam/3rdparty/Eigen/failtest/ternary_2.cpp new file mode 100644 index 000000000..a46b12b2b --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/ternary_2.cpp @@ -0,0 +1,13 @@ +#include "../Eigen/Core" + +using namespace Eigen; + +int main(int argc,char **) +{ + VectorXf a(10), b(10); +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD + b = argc>1 ? 2*a : a+a; +#else + b = argc>1 ? VectorXf(2*a) : VectorXf(a+a); +#endif +} diff --git a/gtsam/3rdparty/Eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp b/gtsam/3rdparty/Eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp new file mode 100644 index 000000000..807447e4b --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp @@ -0,0 +1,15 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(CV_QUALIFIER Matrix3d &m){ + TriangularView t(m); +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/failtest/triangularview_on_const_type_actually_const.cpp b/gtsam/3rdparty/Eigen/failtest/triangularview_on_const_type_actually_const.cpp new file mode 100644 index 000000000..0a381a612 --- /dev/null +++ b/gtsam/3rdparty/Eigen/failtest/triangularview_on_const_type_actually_const.cpp @@ -0,0 +1,16 @@ +#include "../Eigen/Core" + +#ifdef EIGEN_SHOULD_FAIL_TO_BUILD +#define CV_QUALIFIER const +#else +#define CV_QUALIFIER +#endif + +using namespace Eigen; + +void foo(){ + MatrixXf m; + TriangularView(m).coeffRef(0, 0) = 1.0f; +} + +int main() {} diff --git a/gtsam/3rdparty/Eigen/lapack/complex_double.cpp b/gtsam/3rdparty/Eigen/lapack/complex_double.cpp index 424d2b8ca..c9c575273 100644 --- a/gtsam/3rdparty/Eigen/lapack/complex_double.cpp +++ b/gtsam/3rdparty/Eigen/lapack/complex_double.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" +#include "svd.cpp" diff --git a/gtsam/3rdparty/Eigen/lapack/complex_single.cpp b/gtsam/3rdparty/Eigen/lapack/complex_single.cpp index c0b2d29ae..6d11b26cd 100644 --- a/gtsam/3rdparty/Eigen/lapack/complex_single.cpp +++ b/gtsam/3rdparty/Eigen/lapack/complex_single.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" +#include "svd.cpp" diff --git a/gtsam/3rdparty/Eigen/lapack/double.cpp b/gtsam/3rdparty/Eigen/lapack/double.cpp index d86549e19..ea78bb662 100644 --- a/gtsam/3rdparty/Eigen/lapack/double.cpp +++ b/gtsam/3rdparty/Eigen/lapack/double.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" #include "eigenvalues.cpp" +#include "svd.cpp" diff --git a/gtsam/3rdparty/Eigen/lapack/eigenvalues.cpp b/gtsam/3rdparty/Eigen/lapack/eigenvalues.cpp index a1526ebcd..921c51569 100644 --- a/gtsam/3rdparty/Eigen/lapack/eigenvalues.cpp +++ b/gtsam/3rdparty/Eigen/lapack/eigenvalues.cpp @@ -7,10 +7,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -#include "common.h" +#include "lapack_common.h" #include -// computes an LU factorization of a general M-by-N matrix A using partial pivoting with row interchanges +// computes eigen values and vectors of a general N-by-N matrix A EIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Scalar* w, Scalar* /*work*/, int* lwork, int *info)) { // TODO exploit the work buffer @@ -22,24 +22,7 @@ EIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Sca else if(*n<0) *info = -3; else if(*lda +// Copyright (C) 2010-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -11,6 +11,7 @@ #define EIGEN_LAPACK_COMMON_H #include "../blas/common.h" +#include "../Eigen/src/misc/lapack.h" #define EIGEN_LAPACK_FUNC(FUNC,ARGLIST) \ extern "C" { int EIGEN_BLAS_FUNC(FUNC) ARGLIST; } \ @@ -18,6 +19,11 @@ typedef Eigen::Map > PivotsType; +#if ISCOMPLEX +#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) X, +#else +#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) +#endif #endif // EIGEN_LAPACK_COMMON_H diff --git a/gtsam/3rdparty/Eigen/lapack/single.cpp b/gtsam/3rdparty/Eigen/lapack/single.cpp index a64ed44e1..c7da3effa 100644 --- a/gtsam/3rdparty/Eigen/lapack/single.cpp +++ b/gtsam/3rdparty/Eigen/lapack/single.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009-2011 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -15,3 +15,4 @@ #include "cholesky.cpp" #include "lu.cpp" #include "eigenvalues.cpp" +#include "svd.cpp" diff --git a/gtsam/3rdparty/Eigen/lapack/svd.cpp b/gtsam/3rdparty/Eigen/lapack/svd.cpp new file mode 100644 index 000000000..77b302b6b --- /dev/null +++ b/gtsam/3rdparty/Eigen/lapack/svd.cpp @@ -0,0 +1,138 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "lapack_common.h" +#include + +// computes the singular values/vectors a general M-by-N matrix A using divide-and-conquer +EIGEN_LAPACK_FUNC(gesdd,(char *jobz, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork, + EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int * /*iwork*/, int *info)) +{ + // TODO exploit the work buffer + bool query_size = *lwork==-1; + int diag_size = (std::min)(*m,*n); + + *info = 0; + if(*jobz!='A' && *jobz!='S' && *jobz!='O' && *jobz!='N') *info = -1; + else if(*m<0) *info = -2; + else if(*n<0) *info = -3; + else if(*lda=*n && *ldvt<*n)) *info = -10; + + if(*info!=0) + { + int e = -*info; + return xerbla_(SCALAR_SUFFIX_UP"GESDD ", &e, 6); + } + + if(query_size) + { + *lwork = 0; + return 0; + } + + if(*n==0 || *m==0) + return 0; + + PlainMatrixType mat(*m,*n); + mat = matrix(a,*m,*n,*lda); + + int option = *jobz=='A' ? ComputeFullU|ComputeFullV + : *jobz=='S' ? ComputeThinU|ComputeThinV + : *jobz=='O' ? ComputeThinU|ComputeThinV + : 0; + + BDCSVD svd(mat,option); + + make_vector(s,diag_size) = svd.singularValues().head(diag_size); + + if(*jobz=='A') + { + matrix(u,*m,*m,*ldu) = svd.matrixU(); + matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='S') + { + matrix(u,*m,diag_size,*ldu) = svd.matrixU(); + matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='O' && *m>=*n) + { + matrix(a,*m,*n,*lda) = svd.matrixU(); + matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + } + else if(*jobz=='O') + { + matrix(u,*m,*m,*ldu) = svd.matrixU(); + matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint(); + } + + return 0; +} + +// computes the singular values/vectors a general M-by-N matrix A using two sided jacobi algorithm +EIGEN_LAPACK_FUNC(gesvd,(char *jobu, char *jobv, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork, + EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int *info)) +{ + // TODO exploit the work buffer + bool query_size = *lwork==-1; + int diag_size = (std::min)(*m,*n); + + *info = 0; + if( *jobu!='A' && *jobu!='S' && *jobu!='O' && *jobu!='N') *info = -1; + else if((*jobv!='A' && *jobv!='S' && *jobv!='O' && *jobv!='N') + || (*jobu=='O' && *jobv=='O')) *info = -2; + else if(*m<0) *info = -3; + else if(*n<0) *info = -4; + else if(*lda svd(mat,option); + + make_vector(s,diag_size) = svd.singularValues().head(diag_size); + { + if(*jobu=='A') matrix(u,*m,*m,*ldu) = svd.matrixU(); + else if(*jobu=='S') matrix(u,*m,diag_size,*ldu) = svd.matrixU(); + else if(*jobu=='O') matrix(a,*m,diag_size,*lda) = svd.matrixU(); + } + { + if(*jobv=='A') matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint(); + else if(*jobv=='S') matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint(); + else if(*jobv=='O') matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint(); + } + return 0; +} diff --git a/gtsam/3rdparty/Eigen/scripts/buildtests.in b/gtsam/3rdparty/Eigen/scripts/buildtests.in index 7026373cf..526d5b74b 100755 --- a/gtsam/3rdparty/Eigen/scripts/buildtests.in +++ b/gtsam/3rdparty/Eigen/scripts/buildtests.in @@ -2,7 +2,7 @@ if [[ $# != 1 || $1 == *help ]] then - echo "usage: ./check regexp" + echo "usage: $0 regexp" echo " Builds tests matching the regexp." echo " The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'." echo " For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'" @@ -14,9 +14,9 @@ targets_to_make=`echo "$TESTSLIST" | egrep "$1" | xargs echo` if [ -n "${EIGEN_MAKE_ARGS:+x}" ] then - make $targets_to_make ${EIGEN_MAKE_ARGS} + @CMAKE_MAKE_PROGRAM@ $targets_to_make ${EIGEN_MAKE_ARGS} else - make $targets_to_make + @CMAKE_MAKE_PROGRAM@ $targets_to_make @EIGEN_TEST_BUILD_FLAGS@ fi exit $? diff --git a/gtsam/3rdparty/Eigen/scripts/check.in b/gtsam/3rdparty/Eigen/scripts/check.in index a90061a57..7717e2d93 100755 --- a/gtsam/3rdparty/Eigen/scripts/check.in +++ b/gtsam/3rdparty/Eigen/scripts/check.in @@ -3,7 +3,7 @@ if [[ $# != 1 || $1 == *help ]] then - echo "usage: ./check regexp" + echo "usage: $0 regexp" echo " Builds and runs tests matching the regexp." echo " The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'." echo " For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'" diff --git a/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs b/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs index 0e6f9ada2..787dcb325 100644 --- a/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs +++ b/gtsam/3rdparty/Eigen/scripts/eigen_gen_docs @@ -4,7 +4,7 @@ # You should call this script with USER set as you want, else some default # will be used USER=${USER:-'orzel'} -UPLOAD_DIR=dox +UPLOAD_DIR=dox-devel #ulimit -v 1024000 diff --git a/gtsam/3rdparty/Eigen/test/CMakeLists.txt b/gtsam/3rdparty/Eigen/test/CMakeLists.txt index 40c8f669d..0747aa6cb 100644 --- a/gtsam/3rdparty/Eigen/test/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/test/CMakeLists.txt @@ -1,22 +1,38 @@ - -# generate split test header file -message(STATUS ${CMAKE_CURRENT_BINARY_DIR}) -file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h "") -foreach(i RANGE 1 999) - file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h - "#ifdef EIGEN_TEST_PART_${i}\n" - "#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\n" - "#else\n" - "#define CALL_SUBTEST_${i}(FUNC)\n" - "#endif\n\n" +# generate split test header file only if it does not yet exist +# in order to prevent a rebuild everytime cmake is configured +if(NOT EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h) + file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h "") + foreach(i RANGE 1 999) + file(APPEND ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h + "#ifdef EIGEN_TEST_PART_${i}\n" + "#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\n" + "#else\n" + "#define CALL_SUBTEST_${i}(FUNC)\n" + "#endif\n\n" ) -endforeach() + endforeach() +endif() + +# check if we have a Fortran compiler +include("../cmake/language_support.cmake") + +workaround_9220(Fortran EIGEN_Fortran_COMPILER_WORKS) + +if(EIGEN_Fortran_COMPILER_WORKS) + enable_language(Fortran OPTIONAL) + if(NOT CMAKE_Fortran_COMPILER) + set(EIGEN_Fortran_COMPILER_WORKS OFF) + endif() +endif() + +if(NOT EIGEN_Fortran_COMPILER_WORKS) + # search for a default Lapack library to complete Eigen's one + find_package(LAPACK QUIET) +endif() # configure blas/lapack (use Eigen's ones) -set(BLAS_FOUND TRUE) -set(LAPACK_FOUND TRUE) -set(BLAS_LIBRARIES eigen_blas) -set(LAPACK_LIBRARIES eigen_lapack) +set(EIGEN_BLAS_LIBRARIES eigen_blas) +set(EIGEN_LAPACK_LIBRARIES eigen_lapack) set(EIGEN_TEST_MATRIX_DIR "" CACHE STRING "Enable testing of realword sparse matrices contained in the specified path") if(EIGEN_TEST_MATRIX_DIR) @@ -31,56 +47,63 @@ endif(EIGEN_TEST_MATRIX_DIR) set(SPARSE_LIBS " ") find_package(Cholmod) -if(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND) +if(CHOLMOD_FOUND) add_definitions("-DEIGEN_CHOLMOD_SUPPORT") include_directories(${CHOLMOD_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) - set(CHOLMOD_ALL_LIBS ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES}) + set(CHOLMOD_ALL_LIBS ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "Cholmod, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "Cholmod, ") endif() find_package(Umfpack) -if(UMFPACK_FOUND AND BLAS_FOUND) +if(UMFPACK_FOUND) add_definitions("-DEIGEN_UMFPACK_SUPPORT") include_directories(${UMFPACK_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) - set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) + set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "UmfPack, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "UmfPack, ") endif() -find_package(SuperLU) -if(SUPERLU_FOUND AND BLAS_FOUND) +find_package(SuperLU 4.0) +if(SUPERLU_FOUND) add_definitions("-DEIGEN_SUPERLU_SUPPORT") include_directories(${SUPERLU_INCLUDES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) - set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) + set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES}) ei_add_property(EIGEN_TESTED_BACKENDS "SuperLU, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "SuperLU, ") endif() -find_package(Pastix) -find_package(Scotch) -find_package(Metis 5.0 REQUIRED) -if(PASTIX_FOUND AND BLAS_FOUND) +find_package(PASTIX QUIET COMPONENTS METIS SCOTCH) +# check that the PASTIX found is a version without MPI +find_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS + NAMES pastix_nompi.h + HINTS ${PASTIX_INCLUDE_DIRS} +) +if (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS) + message(STATUS "A version of Pastix has been found but pastix_nompi.h does not exist in the include directory." + " Because Eigen tests require a version without MPI, we disable the Pastix backend.") +endif() +if(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS) add_definitions("-DEIGEN_PASTIX_SUPPORT") - include_directories(${PASTIX_INCLUDES}) + include_directories(${PASTIX_INCLUDE_DIRS_DEP}) if(SCOTCH_FOUND) - include_directories(${SCOTCH_INCLUDES}) + include_directories(${SCOTCH_INCLUDE_DIRS}) set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES}) elseif(METIS_FOUND) - include_directories(${METIS_INCLUDES}) + include_directories(${METIS_INCLUDE_DIRS}) set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES}) else(SCOTCH_FOUND) ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") endif(SCOTCH_FOUND) - set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES} ${ORDERING_LIBRARIES} ${BLAS_LIBRARIES}) - set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES} ${BLAS_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES}) + set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP}) ei_add_property(EIGEN_TESTED_BACKENDS "PaStiX, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "PaStiX, ") @@ -88,23 +111,21 @@ endif() if(METIS_FOUND) add_definitions("-DEIGEN_METIS_SUPPORT") - include_directories(${METIS_INCLUDES}) + include_directories(${METIS_INCLUDE_DIRS}) ei_add_property(EIGEN_TESTED_BACKENDS "METIS, ") else() ei_add_property(EIGEN_MISSING_BACKENDS "METIS, ") endif() find_package(SPQR) -if(SPQR_FOUND AND BLAS_FOUND AND LAPACK_FOUND) - if(CHOLMOD_FOUND) - add_definitions("-DEIGEN_SPQR_SUPPORT") - include_directories(${SPQR_INCLUDES}) - set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${LAPACK_LIBRARIES} ${BLAS_LIBRARIES}) - set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS}) - ei_add_property(EIGEN_TESTED_BACKENDS "SPQR, ") - else(CHOLMOD_FOUND) - ei_add_property(EIGEN_MISSING_BACKENDS "SPQR, ") - endif(CHOLMOD_FOUND) +if(SPQR_FOUND AND CHOLMOD_FOUND AND (EIGEN_Fortran_COMPILER_WORKS OR LAPACK_FOUND) ) + add_definitions("-DEIGEN_SPQR_SUPPORT") + include_directories(${SPQR_INCLUDES}) + set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${LAPACK_LIBRARIES}) + set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS}) + ei_add_property(EIGEN_TESTED_BACKENDS "SPQR, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "SPQR, ") endif() option(EIGEN_TEST_NOQT "Disable Qt support in unit tests" OFF) @@ -127,24 +148,31 @@ add_custom_target(BuildOfficial) ei_add_test(rand) ei_add_test(meta) +ei_add_test(numext) ei_add_test(sizeof) ei_add_test(dynalloc) ei_add_test(nomalloc) ei_add_test(first_aligned) +ei_add_test(nullary) ei_add_test(mixingtypes) -ei_add_test(packetmath) +ei_add_test(packetmath "-DEIGEN_FAST_MATH=1") ei_add_test(unalignedassert) ei_add_test(vectorization_logic) ei_add_test(basicstuff) +ei_add_test(constructor) ei_add_test(linearstructure) ei_add_test(integer_types) -ei_add_test(cwiseop) ei_add_test(unalignedcount) -ei_add_test(exceptions) +if(NOT EIGEN_TEST_NO_EXCEPTIONS) + ei_add_test(exceptions) +endif() ei_add_test(redux) ei_add_test(visitor) ei_add_test(block) ei_add_test(corners) +ei_add_test(swap) +ei_add_test(resize) +ei_add_test(conservative_resize) ei_add_test(product_small) ei_add_test(product_large) ei_add_test(product_extra) @@ -162,6 +190,7 @@ ei_add_test(array_for_matrix) ei_add_test(array_replicate) ei_add_test(array_reverse) ei_add_test(ref) +ei_add_test(is_same_dense) ei_add_test(triangular) ei_add_test(selfadjoint) ei_add_test(product_selfadjoint) @@ -173,6 +202,7 @@ ei_add_test(product_trsolve) ei_add_test(product_mmtr) ei_add_test(product_notemporary) ei_add_test(stable_norm) +ei_add_test(permutationmatrices) ei_add_test(bandmatrix) ei_add_test(cholesky) ei_add_test(lu) @@ -192,56 +222,75 @@ ei_add_test(real_qz) ei_add_test(eigensolver_generalized_real) ei_add_test(jacobi) ei_add_test(jacobisvd) +ei_add_test(bdcsvd) +ei_add_test(householder) ei_add_test(geo_orthomethods) -ei_add_test(geo_homogeneous) ei_add_test(geo_quaternion) -ei_add_test(geo_transformations) ei_add_test(geo_eulerangles) -ei_add_test(geo_hyperplane) ei_add_test(geo_parametrizedline) ei_add_test(geo_alignedbox) +ei_add_test(geo_hyperplane) +ei_add_test(geo_transformations) +ei_add_test(geo_homogeneous) ei_add_test(stdvector) ei_add_test(stdvector_overload) ei_add_test(stdlist) ei_add_test(stdlist_overload) ei_add_test(stddeque) ei_add_test(stddeque_overload) -ei_add_test(resize) -ei_add_test(sparse_vector) ei_add_test(sparse_basic) +ei_add_test(sparse_block) +ei_add_test(sparse_vector) ei_add_test(sparse_product) +ei_add_test(sparse_ref) ei_add_test(sparse_solvers) -ei_add_test(umeyama) -ei_add_test(householder) -ei_add_test(swap) -ei_add_test(conservative_resize) -ei_add_test(permutationmatrices) ei_add_test(sparse_permutations) -ei_add_test(nullary) +ei_add_test(simplicial_cholesky) +ei_add_test(conjugate_gradient) +ei_add_test(incomplete_cholesky) +ei_add_test(bicgstab) +ei_add_test(lscg) +ei_add_test(sparselu) +ei_add_test(sparseqr) +ei_add_test(umeyama) ei_add_test(nesting_ops "${CMAKE_CXX_FLAGS_DEBUG}") ei_add_test(zerosized) ei_add_test(dontalign) -ei_add_test(sizeoverflow) +ei_add_test(evaluators) +if(NOT EIGEN_TEST_NO_EXCEPTIONS) + ei_add_test(sizeoverflow) +endif() ei_add_test(prec_inverse_4x4) ei_add_test(vectorwiseop) ei_add_test(special_numbers) ei_add_test(rvalue_types) +ei_add_test(dense_storage) +ei_add_test(ctorleak) ei_add_test(mpl2only) +ei_add_test(inplace_decomposition) +ei_add_test(half_float) +ei_add_test(array_of_string) -ei_add_test(simplicial_cholesky) -ei_add_test(conjugate_gradient) -ei_add_test(bicgstab) -ei_add_test(sparselu) -ei_add_test(sparseqr) +add_executable(bug1213 bug1213.cpp bug1213_main.cpp) -# ei_add_test(denseLM) +check_cxx_compiler_flag("-ffast-math" COMPILER_SUPPORT_FASTMATH) +if(COMPILER_SUPPORT_FASTMATH) + set(EIGEN_FASTMATH_FLAGS "-ffast-math") +else() + check_cxx_compiler_flag("/fp:fast" COMPILER_SUPPORT_FPFAST) + if(COMPILER_SUPPORT_FPFAST) + set(EIGEN_FASTMATH_FLAGS "/fp:fast") + endif() +endif() + +ei_add_test(fastmath " ${EIGEN_FASTMATH_FLAGS} ") + +# # ei_add_test(denseLM) if(QT4_FOUND) ei_add_test(qtvector "" "${QT_QTCORE_LIBRARY}") endif(QT4_FOUND) -ei_add_test(eigen2support) - if(UMFPACK_FOUND) ei_add_test(umfpack_support "" "${UMFPACK_ALL_LIBS}") endif() @@ -286,9 +335,54 @@ ei_add_property(EIGEN_TESTING_SUMMARY "Sparse lib flags: ${SPARSE_LIBS}\n") option(EIGEN_TEST_EIGEN2 "Run whole Eigen2 test suite against EIGEN2_SUPPORT" OFF) mark_as_advanced(EIGEN_TEST_EIGEN2) if(EIGEN_TEST_EIGEN2) - add_subdirectory(eigen2) + message(WARNING "The Eigen2 test suite has been removed") endif() +# boost MP unit test +find_package(Boost) +if(Boost_FOUND) + include_directories(${Boost_INCLUDE_DIRS}) + ei_add_test(boostmultiprec "" "${Boost_LIBRARIES}") + ei_add_property(EIGEN_TESTED_BACKENDS "Boost.Multiprecision, ") +else() + ei_add_property(EIGEN_MISSING_BACKENDS "Boost.Multiprecision, ") +endif() + + +# CUDA unit tests +option(EIGEN_TEST_CUDA "Enable CUDA support in unit tests" OFF) +option(EIGEN_TEST_CUDA_CLANG "Use clang instead of nvcc to compile the CUDA tests" OFF) + +if(EIGEN_TEST_CUDA_CLANG AND NOT CMAKE_CXX_COMPILER MATCHES "clang") + message(WARNING "EIGEN_TEST_CUDA_CLANG is set, but CMAKE_CXX_COMPILER does not appear to be clang.") +endif() + +if(EIGEN_TEST_CUDA) + +find_package(CUDA 5.0) +if(CUDA_FOUND) + + set(CUDA_PROPAGATE_HOST_FLAGS OFF) + if("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + set(CUDA_NVCC_FLAGS "-ccbin ${CMAKE_C_COMPILER}" CACHE STRING "nvcc flags" FORCE) + endif() + if(EIGEN_TEST_CUDA_CLANG) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 --cuda-gpu-arch=sm_30") + endif() + cuda_include_directories(${CMAKE_CURRENT_BINARY_DIR}) + set(EIGEN_ADD_TEST_FILENAME_EXTENSION "cu") + + ei_add_test(cuda_basic) + + unset(EIGEN_ADD_TEST_FILENAME_EXTENSION) + +endif(CUDA_FOUND) + +endif(EIGEN_TEST_CUDA) + + +file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/failtests) +add_test(NAME failtests WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/failtests COMMAND ${CMAKE_COMMAND} ${Eigen_SOURCE_DIR} -G "${CMAKE_GENERATOR}" -DEIGEN_FAILTEST=ON) option(EIGEN_TEST_BUILD_DOCUMENTATION "Test building the doxygen documentation" OFF) IF(EIGEN_TEST_BUILD_DOCUMENTATION) diff --git a/gtsam/3rdparty/Eigen/test/adjoint.cpp b/gtsam/3rdparty/Eigen/test/adjoint.cpp index ea36f7841..bdea51c10 100644 --- a/gtsam/3rdparty/Eigen/test/adjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/adjoint.cpp @@ -42,6 +42,17 @@ template<> struct adjoint_specific { VERIFY_IS_APPROX(v1, v1.norm() * v3); VERIFY_IS_APPROX(v3, v1.normalized()); VERIFY_IS_APPROX(v3.norm(), RealScalar(1)); + + // check null inputs + VERIFY_IS_APPROX((v1*0).normalized(), (v1*0)); +#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE) + RealScalar very_small = (std::numeric_limits::min)(); + VERIFY( (v1*very_small).norm() == 0 ); + VERIFY_IS_APPROX((v1*very_small).normalized(), (v1*very_small)); + v3 = v1*very_small; + v3.normalize(); + VERIFY_IS_APPROX(v3, (v1*very_small)); +#endif // check compatibility of dot and adjoint ref = NumTraits::IsInteger ? 0 : (std::max)((std::max)(v1.norm(),v2.norm()),(std::max)((square * v2).norm(),(square.adjoint() * v1).norm())); @@ -64,6 +75,7 @@ template void adjoint(const MatrixType& m) typedef typename NumTraits::Real RealScalar; typedef Matrix VectorType; typedef Matrix SquareMatrixType; + const Index PacketSize = internal::packet_traits::size; Index rows = m.rows(); Index cols = m.cols(); @@ -108,6 +120,17 @@ template void adjoint(const MatrixType& m) VERIFY_IS_APPROX(m3,m1.transpose()); m3.transposeInPlace(); VERIFY_IS_APPROX(m3,m1); + + if(PacketSize(0,m3.rows()-PacketSize); + Index j = internal::random(0,m3.cols()-PacketSize); + m3.template block(i,j).transposeInPlace(); + VERIFY_IS_APPROX( (m3.template block(i,j)), (m1.template block(i,j).transpose()) ); + m3.template block(i,j).transposeInPlace(); + VERIFY_IS_APPROX(m3,m1); + } // check inplace adjoint m3 = m1; @@ -129,14 +152,24 @@ void test_adjoint() CALL_SUBTEST_1( adjoint(Matrix()) ); CALL_SUBTEST_2( adjoint(Matrix3d()) ); CALL_SUBTEST_3( adjoint(Matrix4f()) ); + CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_5( adjoint(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_6( adjoint(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + + // Complement for 128 bits vectorization: + CALL_SUBTEST_8( adjoint(Matrix2d()) ); + CALL_SUBTEST_9( adjoint(Matrix()) ); + + // 256 bits vectorization: + CALL_SUBTEST_10( adjoint(Matrix()) ); + CALL_SUBTEST_11( adjoint(Matrix()) ); + CALL_SUBTEST_12( adjoint(Matrix()) ); } // test a large static matrix only once CALL_SUBTEST_7( adjoint(Matrix()) ); -#ifdef EIGEN_TEST_PART_4 +#ifdef EIGEN_TEST_PART_13 { MatrixXcf a(10,10), b(10,10); VERIFY_RAISES_ASSERT(a = a.transpose()); @@ -154,6 +187,13 @@ void test_adjoint() a.transpose() = a.adjoint(); a.transpose() += a.adjoint(); a.transpose() += a.adjoint() + b; + + // regression tests for check_for_aliasing + MatrixXd c(10,10); + c = 1.0 * MatrixXd::Ones(10,10) + c; + c = MatrixXd::Ones(10,10) * 1.0 + c; + c = c + MatrixXd::Ones(10,10) .cwiseProduct( MatrixXd::Zero(10,10) ); + c = MatrixXd::Ones(10,10) * MatrixXd::Zero(10,10); } #endif } diff --git a/gtsam/3rdparty/Eigen/test/array.cpp b/gtsam/3rdparty/Eigen/test/array.cpp index 68f6b3d7a..15c3266a9 100644 --- a/gtsam/3rdparty/Eigen/test/array.cpp +++ b/gtsam/3rdparty/Eigen/test/array.cpp @@ -13,6 +13,7 @@ template void array(const ArrayType& m) { typedef typename ArrayType::Index Index; typedef typename ArrayType::Scalar Scalar; + typedef typename ArrayType::RealScalar RealScalar; typedef Array ColVectorType; typedef Array RowVectorType; @@ -22,6 +23,8 @@ template void array(const ArrayType& m) ArrayType m1 = ArrayType::Random(rows, cols), m2 = ArrayType::Random(rows, cols), m3(rows, cols); + ArrayType m4 = m1; // copy constructor + VERIFY_IS_APPROX(m1, m4); ColVectorType cv1 = ColVectorType::Random(rows); RowVectorType rv1 = RowVectorType::Random(cols); @@ -70,7 +73,7 @@ template void array(const ArrayType& m) VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.rowwise().sum().sum() - m1.sum()), m1.abs().sum()); if (!internal::isMuchSmallerThan(abs(m1.sum() - (m1+m2).sum()), m1.abs().sum(), test_precision())) VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); + VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); // vector-wise ops m3 = m1; @@ -81,6 +84,47 @@ template void array(const ArrayType& m) VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1); m3 = m1; VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1); + + // Conversion from scalar + VERIFY_IS_APPROX((m3 = s1), ArrayType::Constant(rows,cols,s1)); + VERIFY_IS_APPROX((m3 = 1), ArrayType::Constant(rows,cols,1)); + VERIFY_IS_APPROX((m3.topLeftCorner(rows,cols) = 1), ArrayType::Constant(rows,cols,1)); + typedef Array FixedArrayType; + FixedArrayType f1(s1); + VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1)); + FixedArrayType f2(numext::real(s1)); + VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1))); + FixedArrayType f3((int)100*numext::real(s1)); + VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1))); + f1.setRandom(); + FixedArrayType f4(f1.data()); + VERIFY_IS_APPROX(f4, f1); + + // pow + VERIFY_IS_APPROX(m1.pow(2), m1.square()); + VERIFY_IS_APPROX(pow(m1,2), m1.square()); + VERIFY_IS_APPROX(m1.pow(3), m1.cube()); + VERIFY_IS_APPROX(pow(m1,3), m1.cube()); + VERIFY_IS_APPROX((-m1).pow(3), -m1.cube()); + VERIFY_IS_APPROX(pow(2*m1,3), 8*m1.cube()); + ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2)); + VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square()); + VERIFY_IS_APPROX(m1.pow(exponents), m1.square()); + VERIFY_IS_APPROX(Eigen::pow(2*m1,exponents), 4*m1.square()); + VERIFY_IS_APPROX((2*m1).pow(exponents), 4*m1.square()); + VERIFY_IS_APPROX(Eigen::pow(m1,2*exponents), m1.square().square()); + VERIFY_IS_APPROX(m1.pow(2*exponents), m1.square().square()); + VERIFY_IS_APPROX(Eigen::pow(m1(0,0), exponents), ArrayType::Constant(rows,cols,m1(0,0)*m1(0,0))); + + // Check possible conflicts with 1D ctor + typedef Array OneDArrayType; + OneDArrayType o1(rows); + VERIFY(o1.size()==rows); + OneDArrayType o4((int)rows); + VERIFY(o4.size()==rows); } template void comparisons(const ArrayType& m) @@ -97,8 +141,11 @@ template void comparisons(const ArrayType& m) c = internal::random(0, cols-1); ArrayType m1 = ArrayType::Random(rows, cols), - m2 = ArrayType::Random(rows, cols), - m3(rows, cols); + m2 = ArrayType::Random(rows, cols), + m3(rows, cols), + m4 = m1; + + m4 = (m4.abs()==Scalar(0)).select(1,m4); VERIFY(((m1 + Scalar(1)) > m1).all()); VERIFY(((m1 - Scalar(1)) < m1).all()); @@ -112,11 +159,17 @@ template void comparisons(const ArrayType& m) VERIFY(!(m1 > m2 && m1 < m2).any()); VERIFY((m1 <= m2 || m1 >= m2).all()); - // comparisons to scalar + // comparisons array to scalar VERIFY( (m1 != (m1(r,c)+1) ).any() ); - VERIFY( (m1 > (m1(r,c)-1) ).any() ); - VERIFY( (m1 < (m1(r,c)+1) ).any() ); - VERIFY( (m1 == m1(r,c) ).any() ); + VERIFY( (m1 > (m1(r,c)-1) ).any() ); + VERIFY( (m1 < (m1(r,c)+1) ).any() ); + VERIFY( (m1 == m1(r,c) ).any() ); + + // comparisons scalar to array + VERIFY( ( (m1(r,c)+1) != m1).any() ); + VERIFY( ( (m1(r,c)-1) < m1).any() ); + VERIFY( ( (m1(r,c)+1) > m1).any() ); + VERIFY( ( m1(r,c) == m1).any() ); // test Select VERIFY_IS_APPROX( (m1 void array_real(const ArrayType& m) ArrayType m1 = ArrayType::Random(rows, cols), m2 = ArrayType::Random(rows, cols), - m3(rows, cols); + m3(rows, cols), + m4 = m1; + + m4 = (m4.abs()==Scalar(0)).select(1,m4); Scalar s1 = internal::random(); - // these tests are mostly to check possible compilation issues. + // these tests are mostly to check possible compilation issues with free-functions. VERIFY_IS_APPROX(m1.sin(), sin(m1)); VERIFY_IS_APPROX(m1.cos(), cos(m1)); + VERIFY_IS_APPROX(m1.tan(), tan(m1)); VERIFY_IS_APPROX(m1.asin(), asin(m1)); VERIFY_IS_APPROX(m1.acos(), acos(m1)); - VERIFY_IS_APPROX(m1.tan(), tan(m1)); - - VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.atan(), atan(m1)); + VERIFY_IS_APPROX(m1.sinh(), sinh(m1)); + VERIFY_IS_APPROX(m1.cosh(), cosh(m1)); + VERIFY_IS_APPROX(m1.tanh(), tanh(m1)); - VERIFY_IS_APPROX(m1.abs().sqrt(), sqrt(abs(m1))); - VERIFY_IS_APPROX(m1.abs(), sqrt(numext::abs2(m1))); + VERIFY_IS_APPROX(m1.arg(), arg(m1)); + VERIFY_IS_APPROX(m1.round(), round(m1)); + VERIFY_IS_APPROX(m1.floor(), floor(m1)); + VERIFY_IS_APPROX(m1.ceil(), ceil(m1)); + VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all()); + VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all()); + VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all()); + VERIFY_IS_APPROX(m1.inverse(), inverse(m1)); + VERIFY_IS_APPROX(m1.abs(), abs(m1)); + VERIFY_IS_APPROX(m1.abs2(), abs2(m1)); + VERIFY_IS_APPROX(m1.square(), square(m1)); + VERIFY_IS_APPROX(m1.cube(), cube(m1)); + VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.sign(), sign(m1)); + + + // avoid NaNs with abs() so verification doesn't fail + m3 = m1.abs(); + VERIFY_IS_APPROX(m3.sqrt(), sqrt(abs(m1))); + VERIFY_IS_APPROX(m3.rsqrt(), Scalar(1)/sqrt(abs(m1))); + VERIFY_IS_APPROX(rsqrt(m3), Scalar(1)/sqrt(abs(m1))); + VERIFY_IS_APPROX(m3.log(), log(m3)); + VERIFY_IS_APPROX(m3.log1p(), log1p(m3)); + VERIFY_IS_APPROX(m3.log10(), log10(m3)); + + + VERIFY((!(m1>m2) == (m1<=m2)).all()); + + VERIFY_IS_APPROX(sin(m1.asin()), m1); + VERIFY_IS_APPROX(cos(m1.acos()), m1); + VERIFY_IS_APPROX(tan(m1.atan()), m1); + VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1))); + VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1))); + VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1)))); + VERIFY_IS_APPROX(arg(m1), ((m1<0).template cast())*std::acos(-1.0)); + VERIFY((round(m1) <= ceil(m1) && round(m1) >= floor(m1)).all()); + VERIFY((Eigen::isnan)((m1*0.0)/0.0).all()); + VERIFY((Eigen::isinf)(m4/0.0).all()); + VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*0.0/0.0)) && (!(Eigen::isfinite)(m4/0.0))).all()); + VERIFY_IS_APPROX(inverse(inverse(m1)),m1); + VERIFY((abs(m1) == m1 || abs(m1) == -m1).all()); + VERIFY_IS_APPROX(m3, sqrt(abs2(m1))); + VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() ); + VERIFY_IS_APPROX( m1*m1.sign(),m1.abs()); + VERIFY_IS_APPROX(m1.sign() * m1.abs(), m1); VERIFY_IS_APPROX(numext::abs2(numext::real(m1)) + numext::abs2(numext::imag(m1)), numext::abs2(m1)); VERIFY_IS_APPROX(numext::abs2(real(m1)) + numext::abs2(imag(m1)), numext::abs2(m1)); @@ -187,52 +288,138 @@ template void array_real(const ArrayType& m) // shift argument of logarithm so that it is not zero Scalar smallNumber = NumTraits::dummy_precision(); - VERIFY_IS_APPROX((m1.abs() + smallNumber).log() , log(abs(m1) + smallNumber)); + VERIFY_IS_APPROX((m3 + smallNumber).log() , log(abs(m1) + smallNumber)); + VERIFY_IS_APPROX((m3 + smallNumber + 1).log() , log1p(abs(m1) + smallNumber)); VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2)); VERIFY_IS_APPROX(m1.exp(), exp(m1)); VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp()); - VERIFY_IS_APPROX(m1.pow(2), m1.square()); - VERIFY_IS_APPROX(pow(m1,2), m1.square()); - - ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2)); - VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square()); - - m3 = m1.abs(); VERIFY_IS_APPROX(m3.pow(RealScalar(0.5)), m3.sqrt()); VERIFY_IS_APPROX(pow(m3,RealScalar(0.5)), m3.sqrt()); + VERIFY_IS_APPROX(m3.pow(RealScalar(-0.5)), m3.rsqrt()); + VERIFY_IS_APPROX(pow(m3,RealScalar(-0.5)), m3.rsqrt()); + + VERIFY_IS_APPROX(log10(m3), log(m3)/log(10)); + // scalar by array division const RealScalar tiny = sqrt(std::numeric_limits::epsilon()); s1 += Scalar(tiny); m1 += ArrayType::Constant(rows,cols,Scalar(tiny)); VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse()); - + // check inplace transpose m3 = m1; m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1.transpose()); + VERIFY_IS_APPROX(m3, m1.transpose()); m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1); + VERIFY_IS_APPROX(m3, m1); } template void array_complex(const ArrayType& m) { typedef typename ArrayType::Index Index; + typedef typename ArrayType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; Index rows = m.rows(); Index cols = m.cols(); ArrayType m1 = ArrayType::Random(rows, cols), - m2(rows, cols); + m2(rows, cols), + m4 = m1; + + m4.real() = (m4.real().abs()==RealScalar(0)).select(RealScalar(1),m4.real()); + m4.imag() = (m4.imag().abs()==RealScalar(0)).select(RealScalar(1),m4.imag()); + + Array m3(rows, cols); for (Index i = 0; i < m.rows(); ++i) for (Index j = 0; j < m.cols(); ++j) m2(i,j) = sqrt(m1(i,j)); - VERIFY_IS_APPROX(m1.sqrt(), m2); - VERIFY_IS_APPROX(m1.sqrt(), Eigen::sqrt(m1)); + // these tests are mostly to check possible compilation issues with free-functions. + VERIFY_IS_APPROX(m1.sin(), sin(m1)); + VERIFY_IS_APPROX(m1.cos(), cos(m1)); + VERIFY_IS_APPROX(m1.tan(), tan(m1)); + VERIFY_IS_APPROX(m1.sinh(), sinh(m1)); + VERIFY_IS_APPROX(m1.cosh(), cosh(m1)); + VERIFY_IS_APPROX(m1.tanh(), tanh(m1)); + VERIFY_IS_APPROX(m1.arg(), arg(m1)); + VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all()); + VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all()); + VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all()); + VERIFY_IS_APPROX(m1.inverse(), inverse(m1)); + VERIFY_IS_APPROX(m1.log(), log(m1)); + VERIFY_IS_APPROX(m1.log10(), log10(m1)); + VERIFY_IS_APPROX(m1.abs(), abs(m1)); + VERIFY_IS_APPROX(m1.abs2(), abs2(m1)); + VERIFY_IS_APPROX(m1.sqrt(), sqrt(m1)); + VERIFY_IS_APPROX(m1.square(), square(m1)); + VERIFY_IS_APPROX(m1.cube(), cube(m1)); + VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval())); + VERIFY_IS_APPROX(m1.sign(), sign(m1)); + + + VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2)); + VERIFY_IS_APPROX(m1.exp(), exp(m1)); + VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp()); + + VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1))); + VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1))); + VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1)))); + + for (Index i = 0; i < m.rows(); ++i) + for (Index j = 0; j < m.cols(); ++j) + m3(i,j) = std::atan2(imag(m1(i,j)), real(m1(i,j))); + VERIFY_IS_APPROX(arg(m1), m3); + + std::complex zero(0.0,0.0); + VERIFY((Eigen::isnan)(m1*zero/zero).all()); +#if EIGEN_COMP_MSVC + // msvc complex division is not robust + VERIFY((Eigen::isinf)(m4/RealScalar(0)).all()); +#else +#if EIGEN_COMP_CLANG + // clang's complex division is notoriously broken too + if((numext::isinf)(m4(0,0)/RealScalar(0))) { +#endif + VERIFY((Eigen::isinf)(m4/zero).all()); +#if EIGEN_COMP_CLANG + } + else + { + VERIFY((Eigen::isinf)(m4.real()/zero.real()).all()); + } +#endif +#endif // MSVC + + VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*zero/zero)) && (!(Eigen::isfinite)(m1/zero))).all()); + + VERIFY_IS_APPROX(inverse(inverse(m1)),m1); + VERIFY_IS_APPROX(conj(m1.conjugate()), m1); + VERIFY_IS_APPROX(abs(m1), sqrt(square(real(m1))+square(imag(m1)))); + VERIFY_IS_APPROX(abs(m1), sqrt(abs2(m1))); + VERIFY_IS_APPROX(log10(m1), log(m1)/log(10)); + + VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() ); + VERIFY_IS_APPROX( m1.sign() * m1.abs(), m1); + + // scalar by array division + Scalar s1 = internal::random(); + const RealScalar tiny = std::sqrt(std::numeric_limits::epsilon()); + s1 += Scalar(tiny); + m1 += ArrayType::Constant(rows,cols,Scalar(tiny)); + VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse()); + + // check inplace transpose + m2 = m1; + m2.transposeInPlace(); + VERIFY_IS_APPROX(m2, m1.transpose()); + m2.transposeInPlace(); + VERIFY_IS_APPROX(m2, m1); + } template void min_max(const ArrayType& m) @@ -301,7 +488,7 @@ void test_array() VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, int >::value)); VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, float >::value)); VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, ArrayBase >::value)); - typedef CwiseUnaryOp, ArrayXd > Xpr; + typedef CwiseUnaryOp, ArrayXd > Xpr; VERIFY((internal::is_same< internal::global_math_functions_filtering_base::type, ArrayBase >::value)); diff --git a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp index 9667e1f14..b8721391f 100644 --- a/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp +++ b/gtsam/3rdparty/Eigen/test/array_for_matrix.cpp @@ -45,7 +45,7 @@ template void array_for_matrix(const MatrixType& m) VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum().sum() - m1.sum(), m1.squaredNorm()); VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum() + m2.colwise().sum() - (m1+m2).colwise().sum(), (m1+m2).squaredNorm()); VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum() - m2.rowwise().sum() - (m1-m2).rowwise().sum(), (m1-m2).squaredNorm()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); + VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); // vector-wise ops m3 = m1; @@ -68,6 +68,16 @@ template void array_for_matrix(const MatrixType& m) const Scalar& ref_a2 = m.array().matrix().coeffRef(0,0); VERIFY(&ref_a1 == &ref_m1); VERIFY(&ref_a2 == &ref_m2); + + // Check write accessors: + m1.array().coeffRef(0,0) = 1; + VERIFY_IS_APPROX(m1(0,0),Scalar(1)); + m1.array()(0,0) = 2; + VERIFY_IS_APPROX(m1(0,0),Scalar(2)); + m1.array().matrix().coeffRef(0,0) = 3; + VERIFY_IS_APPROX(m1(0,0),Scalar(3)); + m1.array().matrix()(0,0) = 4; + VERIFY_IS_APPROX(m1(0,0),Scalar(4)); } template void comparisons(const MatrixType& m) @@ -124,6 +134,12 @@ template void comparisons(const MatrixType& m) // count VERIFY(((m1.array().abs()+1)>RealScalar(0.1)).count() == rows*cols); + // and/or + VERIFY( ((m1.array()RealScalar(0)).matrix()).count() == 0); + VERIFY( ((m1.array()=RealScalar(0)).matrix()).count() == rows*cols); + RealScalar a = m1.cwiseAbs().mean(); + VERIFY( ((m1.array()<-a).matrix() || (m1.array()>a).matrix()).count() == (m1.cwiseAbs().array()>a).count()); + typedef Matrix VectorOfIndices; // TODO allows colwise/rowwise for array @@ -134,9 +150,21 @@ template void comparisons(const MatrixType& m) template void lpNorm(const VectorType& v) { using std::sqrt; + typedef typename VectorType::RealScalar RealScalar; VectorType u = VectorType::Random(v.size()); - VERIFY_IS_APPROX(u.template lpNorm(), u.cwiseAbs().maxCoeff()); + if(v.size()==0) + { + VERIFY_IS_APPROX(u.template lpNorm(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<1>(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<2>(), RealScalar(0)); + VERIFY_IS_APPROX(u.template lpNorm<5>(), RealScalar(0)); + } + else + { + VERIFY_IS_APPROX(u.template lpNorm(), u.cwiseAbs().maxCoeff()); + } + VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwiseAbs().sum()); VERIFY_IS_APPROX(u.template lpNorm<2>(), sqrt(u.array().abs().square().sum())); VERIFY_IS_APPROX(numext::pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.array().abs().pow(5).sum()); @@ -207,12 +235,31 @@ template void resize(const MatrixTraits& t) VERIFY(a1.size()==cols); } +template void regression_bug_654() { ArrayXf a = RowVectorXf(3); VectorXf v = Array(3); } +// Check propagation of LvalueBit through Array/Matrix-Wrapper +template +void regrrssion_bug_1410() +{ + const Matrix4i M; + const Array4i A; + ArrayWrapper MA = M.array(); + MA.row(0); + MatrixWrapper AM = A.matrix(); + AM.row(0); + + VERIFY((internal::traits >::Flags&LvalueBit)==0); + VERIFY((internal::traits >::Flags&LvalueBit)==0); + + VERIFY((internal::traits >::Flags&LvalueBit)==LvalueBit); + VERIFY((internal::traits >::Flags&LvalueBit)==LvalueBit); +} + void test_array_for_matrix() { for(int i = 0; i < g_repeat; i++) { @@ -245,10 +292,13 @@ void test_array_for_matrix() CALL_SUBTEST_5( lpNorm(VectorXf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } + CALL_SUBTEST_5( lpNorm(VectorXf(0)) ); + CALL_SUBTEST_4( lpNorm(VectorXcf(0)) ); for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_4( resize(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_5( resize(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_6( resize(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } - CALL_SUBTEST_6( regression_bug_654() ); + CALL_SUBTEST_6( regression_bug_654<0>() ); + CALL_SUBTEST_6( regrrssion_bug_1410<0>() ); } diff --git a/gtsam/3rdparty/Eigen/test/array_of_string.cpp b/gtsam/3rdparty/Eigen/test/array_of_string.cpp new file mode 100644 index 000000000..e23b7c59e --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/array_of_string.cpp @@ -0,0 +1,32 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +void test_array_of_string() +{ + typedef Array ArrayXs; + ArrayXs a1(3), a2(3), a3(3), a3ref(3); + a1 << "one", "two", "three"; + a2 << "1", "2", "3"; + a3ref << "one (1)", "two (2)", "three (3)"; + std::stringstream s1; + s1 << a1; + VERIFY_IS_EQUAL(s1.str(), std::string(" one two three")); + a3 = a1 + std::string(" (") + a2 + std::string(")"); + VERIFY((a3==a3ref).all()); + + a3 = a1; + a3 += std::string(" (") + a2 + std::string(")"); + VERIFY((a3==a3ref).all()); + + a1.swap(a3); + VERIFY((a1==a3ref).all()); + VERIFY((a3!=a3ref).all()); +} diff --git a/gtsam/3rdparty/Eigen/test/array_replicate.cpp b/gtsam/3rdparty/Eigen/test/array_replicate.cpp index f412d1aed..779c8fc2f 100644 --- a/gtsam/3rdparty/Eigen/test/array_replicate.cpp +++ b/gtsam/3rdparty/Eigen/test/array_replicate.cpp @@ -44,6 +44,19 @@ template void replicate(const MatrixType& m) x2 << m2, m2, m2, m2, m2, m2; VERIFY_IS_APPROX(x2, (m2.template replicate<2,3>())); + + x2.resize(rows,3*cols); + x2 << m2, m2, m2; + VERIFY_IS_APPROX(x2, (m2.template replicate<1,3>())); + + vx1.resize(3*rows,cols); + vx1 << m2, m2, m2; + VERIFY_IS_APPROX(vx1+vx1, vx1+(m2.template replicate<3,1>())); + + vx1=m2+(m2.colwise().replicate(1)); + + if(m2.cols()==1) + VERIFY_IS_APPROX(m2.coeff(0), (m2.template replicate<3,1>().coeff(m2.rows()))); x2.resize(rows,f1); for (int j=0; j void reverse(const MatrixType& m) // this test relies a lot on Random.h, and there's not much more that we can do // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols); + MatrixType m1 = MatrixType::Random(rows, cols), m2; VectorType v1 = VectorType::Random(rows); MatrixType m1_r = m1.reverse(); @@ -96,14 +96,32 @@ template void reverse(const MatrixType& m) m1.reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(rows - 1 - r, cols - 1 - c)); + + m2 = m1; + m2.reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.reverse().eval()); + + m2 = m1; + m2.col(0).reverseInPlace(); + VERIFY_IS_APPROX(m2.col(0),m1.col(0).reverse().eval()); + + m2 = m1; + m2.row(0).reverseInPlace(); + VERIFY_IS_APPROX(m2.row(0),m1.row(0).reverse().eval()); + + m2 = m1; + m2.rowwise().reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.rowwise().reverse().eval()); + + m2 = m1; + m2.colwise().reverseInPlace(); + VERIFY_IS_APPROX(m2,m1.colwise().reverse().eval()); - /* m1.colwise().reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(rows - 1 - r, c)); m1.rowwise().reverse()(r, c) = x; VERIFY_IS_APPROX(x, m1(r, cols - 1 - c)); - */ } void test_array_reverse() @@ -113,11 +131,11 @@ void test_array_reverse() CALL_SUBTEST_2( reverse(Matrix2f()) ); CALL_SUBTEST_3( reverse(Matrix4f()) ); CALL_SUBTEST_4( reverse(Matrix4d()) ); - CALL_SUBTEST_5( reverse(MatrixXcf(3, 3)) ); - CALL_SUBTEST_6( reverse(MatrixXi(6, 3)) ); - CALL_SUBTEST_7( reverse(MatrixXcd(20, 20)) ); + CALL_SUBTEST_5( reverse(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_6( reverse(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( reverse(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_8( reverse(Matrix()) ); - CALL_SUBTEST_9( reverse(Matrix(6,3)) ); + CALL_SUBTEST_9( reverse(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } #ifdef EIGEN_TEST_PART_3 Vector4f x; x << 1, 2, 3, 4; diff --git a/gtsam/3rdparty/Eigen/test/bandmatrix.cpp b/gtsam/3rdparty/Eigen/test/bandmatrix.cpp index 5e4e8e07b..f8c38f7c3 100644 --- a/gtsam/3rdparty/Eigen/test/bandmatrix.cpp +++ b/gtsam/3rdparty/Eigen/test/bandmatrix.cpp @@ -11,7 +11,6 @@ template void bandmatrix(const MatrixType& _m) { - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; typedef Matrix DenseMatrixType; @@ -62,8 +61,6 @@ using Eigen::internal::BandMatrix; void test_bandmatrix() { - typedef BandMatrix::Index Index; - for(int i = 0; i < 10*g_repeat ; i++) { Index rows = internal::random(1,10); Index cols = internal::random(1,10); diff --git a/gtsam/3rdparty/Eigen/test/basicstuff.cpp b/gtsam/3rdparty/Eigen/test/basicstuff.cpp index 8c0621ecd..99d91f9da 100644 --- a/gtsam/3rdparty/Eigen/test/basicstuff.cpp +++ b/gtsam/3rdparty/Eigen/test/basicstuff.cpp @@ -126,6 +126,20 @@ template void basicStuff(const MatrixType& m) for(typename MatrixType::Index i=0;i(0,10)>5; + m3 = b ? m1 : m2; + if(b) VERIFY_IS_APPROX(m3,m1); + else VERIFY_IS_APPROX(m3,m2); + m3 = b ? -m1 : m2; + if(b) VERIFY_IS_APPROX(m3,-m1); + else VERIFY_IS_APPROX(m3,m2); + m3 = b ? m1 : -m2; + if(b) VERIFY_IS_APPROX(m3,m1); + else VERIFY_IS_APPROX(m3,-m2); + } } template void basicStuffComplex(const MatrixType& m) @@ -180,15 +194,64 @@ void casting() template void fixedSizeMatrixConstruction() { - const Scalar raw[3] = {1,2,3}; - Matrix m(raw); - Array a(raw); - VERIFY(m(0) == 1); - VERIFY(m(1) == 2); - VERIFY(m(2) == 3); - VERIFY(a(0) == 1); - VERIFY(a(1) == 2); - VERIFY(a(2) == 3); + Scalar raw[4]; + for(int k=0; k<4; ++k) + raw[k] = internal::random(); + + { + Matrix m(raw); + Array a(raw); + for(int k=0; k<4; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<4; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1],raw[2],raw[3]))); + VERIFY((a==(Array(raw[0],raw[1],raw[2],raw[3]))).all()); + } + { + Matrix m(raw); + Array a(raw); + for(int k=0; k<3; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<3; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1],raw[2]))); + VERIFY((a==Array(raw[0],raw[1],raw[2])).all()); + } + { + Matrix m(raw), m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + Array a(raw), a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1]))); + VERIFY((a==Array(raw[0],raw[1])).all()); + for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k])); + } + { + Matrix m(raw), + m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ), + m3( (int(raw[0])), (int(raw[1])) ), + m4( (float(raw[0])), (float(raw[1])) ); + Array a(raw), a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ); + for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]); + for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]); + VERIFY_IS_EQUAL(m,(Matrix(raw[0],raw[1]))); + VERIFY((a==Array(raw[0],raw[1])).all()); + for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k])); + for(int k=0; k<2; ++k) VERIFY(m3(k) == int(raw[k])); + for(int k=0; k<2; ++k) VERIFY((m4(k)) == Scalar(float(raw[k]))); + } + { + Matrix m(raw), m1(raw[0]), m2( (DenseIndex(raw[0])) ), m3( (int(raw[0])) ); + Array a(raw), a1(raw[0]), a2( (DenseIndex(raw[0])) ); + VERIFY(m(0) == raw[0]); + VERIFY(a(0) == raw[0]); + VERIFY(m1(0) == raw[0]); + VERIFY(a1(0) == raw[0]); + VERIFY(m2(0) == DenseIndex(raw[0])); + VERIFY(a2(0) == DenseIndex(raw[0])); + VERIFY(m3(0) == int(raw[0])); + VERIFY_IS_EQUAL(m,(Matrix(raw[0]))); + VERIFY((a==Array(raw[0])).all()); + } } void test_basicstuff() @@ -207,8 +270,11 @@ void test_basicstuff() } CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); CALL_SUBTEST_1(fixedSizeMatrixConstruction()); - CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); + CALL_SUBTEST_1(fixedSizeMatrixConstruction()); CALL_SUBTEST_2(casting()); } diff --git a/gtsam/3rdparty/Eigen/test/bdcsvd.cpp b/gtsam/3rdparty/Eigen/test/bdcsvd.cpp new file mode 100644 index 000000000..f9f687aac --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/bdcsvd.cpp @@ -0,0 +1,111 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Gauthier Brun +// Copyright (C) 2013 Nicolas Carre +// Copyright (C) 2013 Jean Ceccato +// Copyright (C) 2013 Pierre Zoppitelli +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/ + +// discard stack allocation as that too bypasses malloc +#define EIGEN_STACK_ALLOCATION_LIMIT 0 +#define EIGEN_RUNTIME_NO_MALLOC + +#include "main.h" +#include +#include +#include + + +#define SVD_DEFAULT(M) BDCSVD +#define SVD_FOR_MIN_NORM(M) BDCSVD +#include "svd_common.h" + +// Check all variants of JacobiSVD +template +void bdcsvd(const MatrixType& a = MatrixType(), bool pickrandom = true) +{ + MatrixType m = a; + if(pickrandom) + svd_fill_random(m); + + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); +} + +template +void bdcsvd_method() +{ + enum { Size = MatrixType::RowsAtCompileTime }; + typedef typename MatrixType::RealScalar RealScalar; + typedef Matrix RealVecType; + MatrixType m = MatrixType::Identity(); + VERIFY_IS_APPROX(m.bdcSvd().singularValues(), RealVecType::Ones()); + VERIFY_RAISES_ASSERT(m.bdcSvd().matrixU()); + VERIFY_RAISES_ASSERT(m.bdcSvd().matrixV()); + VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).solve(m), m); +} + +// compare the Singular values returned with Jacobi and Bdc +template +void compare_bdc_jacobi(const MatrixType& a = MatrixType(), unsigned int computationOptions = 0) +{ + MatrixType m = MatrixType::Random(a.rows(), a.cols()); + BDCSVD bdc_svd(m); + JacobiSVD jacobi_svd(m); + VERIFY_IS_APPROX(bdc_svd.singularValues(), jacobi_svd.singularValues()); + if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU()); + if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU()); + if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV()); + if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV()); +} + +void test_bdcsvd() +{ + CALL_SUBTEST_3(( svd_verify_assert >(Matrix3f()) )); + CALL_SUBTEST_4(( svd_verify_assert >(Matrix4d()) )); + CALL_SUBTEST_7(( svd_verify_assert >(MatrixXf(10,12)) )); + CALL_SUBTEST_8(( svd_verify_assert >(MatrixXcd(7,5)) )); + + CALL_SUBTEST_101(( svd_all_trivial_2x2(bdcsvd) )); + CALL_SUBTEST_102(( svd_all_trivial_2x2(bdcsvd) )); + + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_3(( bdcsvd() )); + CALL_SUBTEST_4(( bdcsvd() )); + CALL_SUBTEST_5(( bdcsvd >() )); + + int r = internal::random(1, EIGEN_TEST_MAX_SIZE/2), + c = internal::random(1, EIGEN_TEST_MAX_SIZE/2); + + TEST_SET_BUT_UNUSED_VARIABLE(r) + TEST_SET_BUT_UNUSED_VARIABLE(c) + + CALL_SUBTEST_6(( bdcsvd(Matrix(r,2)) )); + CALL_SUBTEST_7(( bdcsvd(MatrixXf(r,c)) )); + CALL_SUBTEST_7(( compare_bdc_jacobi(MatrixXf(r,c)) )); + CALL_SUBTEST_10(( bdcsvd(MatrixXd(r,c)) )); + CALL_SUBTEST_10(( compare_bdc_jacobi(MatrixXd(r,c)) )); + CALL_SUBTEST_8(( bdcsvd(MatrixXcd(r,c)) )); + CALL_SUBTEST_8(( compare_bdc_jacobi(MatrixXcd(r,c)) )); + + // Test on inf/nan matrix + CALL_SUBTEST_7( (svd_inf_nan, MatrixXf>()) ); + CALL_SUBTEST_10( (svd_inf_nan, MatrixXd>()) ); + } + + // test matrixbase method + CALL_SUBTEST_1(( bdcsvd_method() )); + CALL_SUBTEST_3(( bdcsvd_method() )); + + // Test problem size constructors + CALL_SUBTEST_7( BDCSVD(10,10) ); + + // Check that preallocation avoids subsequent mallocs + CALL_SUBTEST_9( svd_preallocate() ); + + CALL_SUBTEST_2( svd_underoverflow() ); +} + diff --git a/gtsam/3rdparty/Eigen/test/bicgstab.cpp b/gtsam/3rdparty/Eigen/test/bicgstab.cpp index f327e2fac..4cc0dd31c 100644 --- a/gtsam/3rdparty/Eigen/test/bicgstab.cpp +++ b/gtsam/3rdparty/Eigen/test/bicgstab.cpp @@ -10,13 +10,16 @@ #include "sparse_solver.h" #include -template void test_bicgstab_T() +template void test_bicgstab_T() { - BiCGSTAB, DiagonalPreconditioner > bicgstab_colmajor_diag; - BiCGSTAB, IdentityPreconditioner > bicgstab_colmajor_I; - BiCGSTAB, IncompleteLUT > bicgstab_colmajor_ilut; + BiCGSTAB, DiagonalPreconditioner > bicgstab_colmajor_diag; + BiCGSTAB, IdentityPreconditioner > bicgstab_colmajor_I; + BiCGSTAB, IncompleteLUT > bicgstab_colmajor_ilut; //BiCGSTAB, SSORPreconditioner > bicgstab_colmajor_ssor; + bicgstab_colmajor_diag.setTolerance(NumTraits::epsilon()*4); + bicgstab_colmajor_ilut.setTolerance(NumTraits::epsilon()*4); + CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_diag) ); // CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_I) ); CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ilut) ); @@ -25,6 +28,7 @@ template void test_bicgstab_T() void test_bicgstab() { - CALL_SUBTEST_1(test_bicgstab_T()); - CALL_SUBTEST_2(test_bicgstab_T >()); + CALL_SUBTEST_1((test_bicgstab_T()) ); + CALL_SUBTEST_2((test_bicgstab_T, int>())); + CALL_SUBTEST_3((test_bicgstab_T())); } diff --git a/gtsam/3rdparty/Eigen/test/block.cpp b/gtsam/3rdparty/Eigen/test/block.cpp index 9ed5d7bc5..39565af83 100644 --- a/gtsam/3rdparty/Eigen/test/block.cpp +++ b/gtsam/3rdparty/Eigen/test/block.cpp @@ -130,6 +130,14 @@ template void block(const MatrixType& m) VERIFY(numext::real(ones.col(c1).dot(ones.col(c2))) == RealScalar(rows)); VERIFY(numext::real(ones.row(r1).dot(ones.row(r2))) == RealScalar(cols)); + + // chekc that linear acccessors works on blocks + m1 = m1_copy; + if((MatrixType::Flags&RowMajorBit)==0) + VERIFY_IS_EQUAL(m1.leftCols(c1).coeff(r1+c1*rows), m1(r1,c1)); + else + VERIFY_IS_EQUAL(m1.topRows(r1).coeff(c1+r1*cols), m1(r1,c1)); + // now test some block-inside-of-block. @@ -141,11 +149,11 @@ template void block(const MatrixType& m) VERIFY_IS_EQUAL( (m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() ); // expressions without direct access - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) ); - VERIFY_IS_EQUAL( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); - VERIFY_IS_EQUAL( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) ); + VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); + VERIFY_IS_APPROX( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() ); // evaluation into plain matrices from expressions with direct access (stress MapBase) DynamicMatrixType dm; @@ -173,6 +181,19 @@ template void block(const MatrixType& m) dm = m1.row(r1).segment(c1,c2-c1+1).transpose(); dv = m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0); VERIFY_IS_EQUAL(dv, dm); + + VERIFY_IS_EQUAL( (m1.template block(1,0,0,1)), m1.block(1,0,0,1)); + VERIFY_IS_EQUAL( (m1.template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0)); + VERIFY_IS_EQUAL( ((m1*1).template block(1,0,0,1)), m1.block(1,0,0,1)); + VERIFY_IS_EQUAL( ((m1*1).template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0)); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.col(0) ); + VERIFY_RAISES_ASSERT( m1 -= m1.col(0) ); + VERIFY_RAISES_ASSERT( m1.array() *= m1.col(0).array() ); + VERIFY_RAISES_ASSERT( m1.array() /= m1.col(0).array() ); + } } diff --git a/gtsam/3rdparty/Eigen/test/boostmultiprec.cpp b/gtsam/3rdparty/Eigen/test/boostmultiprec.cpp new file mode 100644 index 000000000..e06e9bdaf --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/boostmultiprec.cpp @@ -0,0 +1,201 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include + +#ifdef EIGEN_TEST_MAX_SIZE +#undef EIGEN_TEST_MAX_SIZE +#endif + +#define EIGEN_TEST_MAX_SIZE 50 + +#ifdef EIGEN_TEST_PART_1 +#include "cholesky.cpp" +#endif + +#ifdef EIGEN_TEST_PART_2 +#include "lu.cpp" +#endif + +#ifdef EIGEN_TEST_PART_3 +#include "qr.cpp" +#endif + +#ifdef EIGEN_TEST_PART_4 +#include "qr_colpivoting.cpp" +#endif + +#ifdef EIGEN_TEST_PART_5 +#include "qr_fullpivoting.cpp" +#endif + +#ifdef EIGEN_TEST_PART_6 +#include "eigensolver_selfadjoint.cpp" +#endif + +#ifdef EIGEN_TEST_PART_7 +#include "eigensolver_generic.cpp" +#endif + +#ifdef EIGEN_TEST_PART_8 +#include "eigensolver_generalized_real.cpp" +#endif + +#ifdef EIGEN_TEST_PART_9 +#include "jacobisvd.cpp" +#endif + +#ifdef EIGEN_TEST_PART_10 +#include "bdcsvd.cpp" +#endif + +#include + +#undef min +#undef max +#undef isnan +#undef isinf +#undef isfinite + +#include +#include +#include +#include + +namespace mp = boost::multiprecision; +typedef mp::number, mp::et_on> Real; + +namespace Eigen { + template<> struct NumTraits : GenericNumTraits { + static inline Real dummy_precision() { return 1e-50; } + }; + + template + struct NumTraits > : NumTraits {}; + + template<> + Real test_precision() { return 1e-50; } + + // needed in C++93 mode where number does not support explicit cast. + namespace internal { + template + struct cast_impl { + static inline NewType run(const Real& x) { + return x.template convert_to(); + } + }; + + template<> + struct cast_impl > { + static inline std::complex run(const Real& x) { + return std::complex(x); + } + }; + } +} + +namespace boost { +namespace multiprecision { + // to make ADL works as expected: + using boost::math::isfinite; + using boost::math::isnan; + using boost::math::isinf; + using boost::math::copysign; + using boost::math::hypot; + + // The following is needed for std::complex: + Real fabs(const Real& a) { return abs EIGEN_NOT_A_MACRO (a); } + Real fmax(const Real& a, const Real& b) { using std::max; return max(a,b); } + + // some specialization for the unit tests: + inline bool test_isMuchSmallerThan(const Real& a, const Real& b) { + return internal::isMuchSmallerThan(a, b, test_precision()); + } + + inline bool test_isApprox(const Real& a, const Real& b) { + return internal::isApprox(a, b, test_precision()); + } + + inline bool test_isApproxOrLessThan(const Real& a, const Real& b) { + return internal::isApproxOrLessThan(a, b, test_precision()); + } + + Real get_test_precision(const Real&) { + return test_precision(); + } + + Real test_relative_error(const Real &a, const Real &b) { + using Eigen::numext::abs2; + return sqrt(abs2(a-b)/Eigen::numext::mini(abs2(a),abs2(b))); + } +} +} + +namespace Eigen { + +} + +void test_boostmultiprec() +{ + typedef Matrix Mat; + typedef Matrix,Dynamic,Dynamic> MatC; + + std::cout << "NumTraits::epsilon() = " << NumTraits::epsilon() << std::endl; + std::cout << "NumTraits::dummy_precision() = " << NumTraits::dummy_precision() << std::endl; + std::cout << "NumTraits::lowest() = " << NumTraits::lowest() << std::endl; + std::cout << "NumTraits::highest() = " << NumTraits::highest() << std::endl; + std::cout << "NumTraits::digits10() = " << NumTraits::digits10() << std::endl; + + // chekc stream output + { + Mat A(10,10); + A.setRandom(); + std::stringstream ss; + ss << A; + } + { + MatC A(10,10); + A.setRandom(); + std::stringstream ss; + ss << A; + } + + for(int i = 0; i < g_repeat; i++) { + int s = internal::random(1,EIGEN_TEST_MAX_SIZE); + + CALL_SUBTEST_1( cholesky(Mat(s,s)) ); + + CALL_SUBTEST_2( lu_non_invertible() ); + CALL_SUBTEST_2( lu_invertible() ); + CALL_SUBTEST_2( lu_non_invertible() ); + CALL_SUBTEST_2( lu_invertible() ); + + CALL_SUBTEST_3( qr(Mat(internal::random(1,EIGEN_TEST_MAX_SIZE),internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_3( qr_invertible() ); + + CALL_SUBTEST_4( qr() ); + CALL_SUBTEST_4( cod() ); + CALL_SUBTEST_4( qr_invertible() ); + + CALL_SUBTEST_5( qr() ); + CALL_SUBTEST_5( qr_invertible() ); + + CALL_SUBTEST_6( selfadjointeigensolver(Mat(s,s)) ); + + CALL_SUBTEST_7( eigensolver(Mat(s,s)) ); + + CALL_SUBTEST_8( generalized_eigensolver_real(Mat(s,s)) ); + + TEST_SET_BUT_UNUSED_VARIABLE(s) + } + + CALL_SUBTEST_9(( jacobisvd(Mat(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); + CALL_SUBTEST_10(( bdcsvd(Mat(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); +} + diff --git a/gtsam/3rdparty/Eigen/test/bug1213.cpp b/gtsam/3rdparty/Eigen/test/bug1213.cpp new file mode 100644 index 000000000..581760c1a --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/bug1213.cpp @@ -0,0 +1,13 @@ + +// This anonymous enum is essential to trigger the linking issue +enum { + Foo +}; + +#include "bug1213.h" + +bool bug1213_1(const Eigen::Vector3f& x) +{ + return bug1213_2(x); +} + diff --git a/gtsam/3rdparty/Eigen/test/bug1213.h b/gtsam/3rdparty/Eigen/test/bug1213.h new file mode 100644 index 000000000..040e5a470 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/bug1213.h @@ -0,0 +1,8 @@ + +#include + +template +bool bug1213_2(const Eigen::Matrix& x); + +bool bug1213_1(const Eigen::Vector3f& x); + diff --git a/gtsam/3rdparty/Eigen/test/bug1213_main.cpp b/gtsam/3rdparty/Eigen/test/bug1213_main.cpp new file mode 100644 index 000000000..4802c0003 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/bug1213_main.cpp @@ -0,0 +1,18 @@ + +// This is a regression unit regarding a weird linking issue with gcc. + +#include "bug1213.h" + +int main() +{ + return 0; +} + + +template +bool bug1213_2(const Eigen::Matrix& ) +{ + return true; +} + +template bool bug1213_2(const Eigen::Vector3f&); diff --git a/gtsam/3rdparty/Eigen/test/cholesky.cpp b/gtsam/3rdparty/Eigen/test/cholesky.cpp index 56885deb7..8ad5ac639 100644 --- a/gtsam/3rdparty/Eigen/test/cholesky.cpp +++ b/gtsam/3rdparty/Eigen/test/cholesky.cpp @@ -11,20 +11,17 @@ #define EIGEN_NO_ASSERTION_CHECKING #endif -static int nb_temporaries; - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { if(size!=0) nb_temporaries++; } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" #include #include -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } +template +typename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) { + MatrixType symm = m.template selfadjointView(); + return symm.cwiseAbs().colwise().sum().maxCoeff(); +} template class CholType> void test_chol_update(const MatrixType& symm) { @@ -83,14 +80,10 @@ template void cholesky(const MatrixType& m) symm += a1 * a1.adjoint(); } - // to test if really Cholesky only uses the upper triangular part, uncomment the following - // FIXME: currently that fails !! - //symm.template part().setZero(); - { SquareMatrixType symmUp = symm.template triangularView(); SquareMatrixType symmLo = symm.template triangularView(); - + LLT chollo(symmLo); VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix()); vecX = chollo.solve(vecB); @@ -98,6 +91,14 @@ template void cholesky(const MatrixType& m) matX = chollo.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + const MatrixType symmLo_inverse = chollo.solve(MatrixType::Identity(rows,cols)); + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(symmLo)) / + matrix_l1_norm(symmLo_inverse); + RealScalar rcond_est = chollo.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + // test the upper mode LLT cholup(symmUp); VERIFY_IS_APPROX(symm, cholup.reconstructedMatrix()); @@ -106,6 +107,15 @@ template void cholesky(const MatrixType& m) matX = cholup.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + const MatrixType symmUp_inverse = cholup.solve(MatrixType::Identity(rows,cols)); + rcond = (RealScalar(1) / matrix_l1_norm(symmUp)) / + matrix_l1_norm(symmUp_inverse); + rcond_est = cholup.rcond(); + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + MatrixType neg = -symmLo; chollo.compute(neg); VERIFY(chollo.info()==NumericalIssue); @@ -114,7 +124,7 @@ template void cholesky(const MatrixType& m) VERIFY_IS_APPROX(MatrixType(chollo.matrixU().transpose().conjugate()), MatrixType(chollo.matrixL())); VERIFY_IS_APPROX(MatrixType(cholup.matrixL().transpose().conjugate()), MatrixType(cholup.matrixU())); VERIFY_IS_APPROX(MatrixType(cholup.matrixU().transpose().conjugate()), MatrixType(cholup.matrixL())); - + // test some special use cases of SelfCwiseBinaryOp: MatrixType m1 = MatrixType::Random(rows,cols), m2(rows,cols); m2 = m1; @@ -144,19 +154,38 @@ template void cholesky(const MatrixType& m) SquareMatrixType symmLo = symm.template triangularView(); LDLT ldltlo(symmLo); + VERIFY(ldltlo.info()==Success); VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); matX = ldltlo.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + const MatrixType symmLo_inverse = ldltlo.solve(MatrixType::Identity(rows,cols)); + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(symmLo)) / + matrix_l1_norm(symmLo_inverse); + RealScalar rcond_est = ldltlo.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + LDLT ldltup(symmUp); + VERIFY(ldltup.info()==Success); VERIFY_IS_APPROX(symm, ldltup.reconstructedMatrix()); vecX = ldltup.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); matX = ldltup.solve(matB); VERIFY_IS_APPROX(symm * matX, matB); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + const MatrixType symmUp_inverse = ldltup.solve(MatrixType::Identity(rows,cols)); + rcond = (RealScalar(1) / matrix_l1_norm(symmUp)) / + matrix_l1_norm(symmUp_inverse); + rcond_est = ldltup.rcond(); + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + VERIFY_IS_APPROX(MatrixType(ldltlo.matrixL().transpose().conjugate()), MatrixType(ldltlo.matrixU())); VERIFY_IS_APPROX(MatrixType(ldltlo.matrixU().transpose().conjugate()), MatrixType(ldltlo.matrixL())); VERIFY_IS_APPROX(MatrixType(ldltup.matrixL().transpose().conjugate()), MatrixType(ldltup.matrixU())); @@ -185,7 +214,7 @@ template void cholesky(const MatrixType& m) if(rows>=3) { SquareMatrixType A = symm; - int c = internal::random(0,rows-2); + Index c = internal::random(0,rows-2); A.bottomRightCorner(c,c).setZero(); // Make sure a solution exists: vecX.setRandom(); @@ -196,11 +225,11 @@ template void cholesky(const MatrixType& m) vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(A * vecX, vecB); } - + // check non-full rank matrices if(rows>=3) { - int r = internal::random(1,rows-1); + Index r = internal::random(1,rows-1); Matrix a = Matrix::Random(rows,r); SquareMatrixType A = a * a.adjoint(); // Make sure a solution exists: @@ -212,15 +241,17 @@ template void cholesky(const MatrixType& m) vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(A * vecX, vecB); } - + // check matrices with a wide spectrum if(rows>=3) { + using std::pow; + using std::sqrt; RealScalar s = (std::min)(16,std::numeric_limits::max_exponent10/8); Matrix a = Matrix::Random(rows,rows); Matrix d = Matrix::Random(rows); - for(int k=0; k(-s,s)); + for(Index k=0; k(-s,s)); SquareMatrixType A = a * d.asDiagonal() * a.adjoint(); // Make sure a solution exists: vecX.setRandom(); @@ -229,7 +260,20 @@ template void cholesky(const MatrixType& m) ldltlo.compute(A); VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); - VERIFY_IS_APPROX(A * vecX, vecB); + + if(ldltlo.vectorD().real().cwiseAbs().minCoeff()>RealScalar(0)) + { + VERIFY_IS_APPROX(A * vecX,vecB); + } + else + { + RealScalar large_tol = sqrt(test_precision()); + VERIFY((A * vecX).isApprox(vecB, large_tol)); + + ++g_test_level; + VERIFY_IS_APPROX(A * vecX,vecB); + --g_test_level; + } } } @@ -289,6 +333,7 @@ template void cholesky_cplx(const MatrixType& m) RealMatrixType symmLo = symm.template triangularView(); LDLT ldltlo(symmLo); + VERIFY(ldltlo.info()==Success); VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix()); vecX = ldltlo.solve(vecB); VERIFY_IS_APPROX(symm * vecX, vecB); @@ -314,46 +359,101 @@ template void cholesky_bug241(const MatrixType& m) } // LDLT is not guaranteed to work for indefinite matrices, but happens to work fine if matrix is diagonal. -// This test checks that LDLT reports correctly that matrix is indefinite. +// This test checks that LDLT reports correctly that matrix is indefinite. // See http://forum.kde.org/viewtopic.php?f=74&t=106942 and bug 736 template void cholesky_definiteness(const MatrixType& m) { eigen_assert(m.rows() == 2 && m.cols() == 2); MatrixType mat; LDLT ldlt(2); - + { mat << 1, 0, 0, -1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } { mat << 1, 2, 2, 1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } { mat << 0, 0, 0, 0; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(ldlt.isNegative()); VERIFY(ldlt.isPositive()); } { mat << 0, 0, 0, 1; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(!ldlt.isNegative()); VERIFY(ldlt.isPositive()); } { mat << -1, 0, 0, 0; ldlt.compute(mat); + VERIFY(ldlt.info()==Success); VERIFY(ldlt.isNegative()); VERIFY(!ldlt.isPositive()); } } +template +void cholesky_faillure_cases() +{ + MatrixXd mat; + LDLT ldlt; + + { + mat.resize(2,2); + mat << 0, 1, 1, 0; + ldlt.compute(mat); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + VERIFY(ldlt.info()==NumericalIssue); + } +#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE_SSE2) + { + mat.resize(3,3); + mat << -1, -3, 3, + -3, -8.9999999999999999999, 1, + 3, 1, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } +#endif + { + mat.resize(3,3); + mat << 1, 2, 3, + 2, 4, 1, + 3, 1, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } + + { + mat.resize(8,8); + mat << 0.1, 0, -0.1, 0, 0, 0, 1, 0, + 0, 4.24667, 0, 2.00333, 0, 0, 0, 0, + -0.1, 0, 0.2, 0, -0.1, 0, 0, 0, + 0, 2.00333, 0, 8.49333, 0, 2.00333, 0, 0, + 0, 0, -0.1, 0, 0.1, 0, 0, 1, + 0, 0, 0, 2.00333, 0, 4.24667, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 0, 0; + ldlt.compute(mat); + VERIFY(ldlt.info()==NumericalIssue); + VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix()); + } +} + template void cholesky_verify_assert() { MatrixType tmp; @@ -384,10 +484,14 @@ void test_cholesky() CALL_SUBTEST_3( cholesky_definiteness(Matrix2d()) ); CALL_SUBTEST_4( cholesky(Matrix3f()) ); CALL_SUBTEST_5( cholesky(Matrix4d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( cholesky(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_6( cholesky_cplx(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } CALL_SUBTEST_4( cholesky_verify_assert() ); @@ -398,7 +502,8 @@ void test_cholesky() // Test problem size constructors CALL_SUBTEST_9( LLT(10) ); CALL_SUBTEST_9( LDLT(10) ); - - TEST_SET_BUT_UNUSED_VARIABLE(s) + + CALL_SUBTEST_2( cholesky_faillure_cases() ); + TEST_SET_BUT_UNUSED_VARIABLE(nb_temporaries) } diff --git a/gtsam/3rdparty/Eigen/test/cholmod_support.cpp b/gtsam/3rdparty/Eigen/test/cholmod_support.cpp index 8f8be3c0e..a7eda28f7 100644 --- a/gtsam/3rdparty/Eigen/test/cholmod_support.cpp +++ b/gtsam/3rdparty/Eigen/test/cholmod_support.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include @@ -40,13 +41,13 @@ template void test_cholmod_T() check_sparse_spd_solving(llt_colmajor_upper); check_sparse_spd_solving(ldlt_colmajor_lower); check_sparse_spd_solving(ldlt_colmajor_upper); - -// check_sparse_spd_determinant(chol_colmajor_lower); -// check_sparse_spd_determinant(chol_colmajor_upper); -// check_sparse_spd_determinant(llt_colmajor_lower); -// check_sparse_spd_determinant(llt_colmajor_upper); -// check_sparse_spd_determinant(ldlt_colmajor_lower); -// check_sparse_spd_determinant(ldlt_colmajor_upper); + + check_sparse_spd_determinant(chol_colmajor_lower); + check_sparse_spd_determinant(chol_colmajor_upper); + check_sparse_spd_determinant(llt_colmajor_lower); + check_sparse_spd_determinant(llt_colmajor_upper); + check_sparse_spd_determinant(ldlt_colmajor_lower); + check_sparse_spd_determinant(ldlt_colmajor_upper); } void test_cholmod_support() diff --git a/gtsam/3rdparty/Eigen/test/commainitializer.cpp b/gtsam/3rdparty/Eigen/test/commainitializer.cpp index 296592340..9844adbd2 100644 --- a/gtsam/3rdparty/Eigen/test/commainitializer.cpp +++ b/gtsam/3rdparty/Eigen/test/commainitializer.cpp @@ -70,8 +70,9 @@ void test_commainitializer() Matrix3d m3; Matrix4d m4; - #ifndef _MSC_VER VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8) ); + + #ifndef _MSC_VER VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10) ); #endif @@ -99,6 +100,7 @@ void test_commainitializer() vec[2].transpose(); VERIFY_IS_APPROX(m3, ref); + // recursively test all block-sizes from 0 to 3: test_block_recursion<(1<<8) - 1>(); } diff --git a/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp b/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp index 019cc4d64..9622fd86d 100644 --- a/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp +++ b/gtsam/3rdparty/Eigen/test/conjugate_gradient.cpp @@ -10,13 +10,14 @@ #include "sparse_solver.h" #include -template void test_conjugate_gradient_T() +template void test_conjugate_gradient_T() { - ConjugateGradient, Lower > cg_colmajor_lower_diag; - ConjugateGradient, Upper > cg_colmajor_upper_diag; - ConjugateGradient, Lower|Upper> cg_colmajor_loup_diag; - ConjugateGradient, Lower, IdentityPreconditioner> cg_colmajor_lower_I; - ConjugateGradient, Upper, IdentityPreconditioner> cg_colmajor_upper_I; + typedef SparseMatrix SparseMatrixType; + ConjugateGradient cg_colmajor_lower_diag; + ConjugateGradient cg_colmajor_upper_diag; + ConjugateGradient cg_colmajor_loup_diag; + ConjugateGradient cg_colmajor_lower_I; + ConjugateGradient cg_colmajor_upper_I; CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag) ); CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag) ); @@ -27,6 +28,7 @@ template void test_conjugate_gradient_T() void test_conjugate_gradient() { - CALL_SUBTEST_1(test_conjugate_gradient_T()); - CALL_SUBTEST_2(test_conjugate_gradient_T >()); + CALL_SUBTEST_1(( test_conjugate_gradient_T() )); + CALL_SUBTEST_2(( test_conjugate_gradient_T, int>() )); + CALL_SUBTEST_3(( test_conjugate_gradient_T() )); } diff --git a/gtsam/3rdparty/Eigen/test/constructor.cpp b/gtsam/3rdparty/Eigen/test/constructor.cpp new file mode 100644 index 000000000..eec9e2192 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/constructor.cpp @@ -0,0 +1,84 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + + +#define TEST_ENABLE_TEMPORARY_TRACKING + +#include "main.h" + +template struct Wrapper +{ + MatrixType m_mat; + inline Wrapper(const MatrixType &x) : m_mat(x) {} + inline operator const MatrixType& () const { return m_mat; } + inline operator MatrixType& () { return m_mat; } +}; + +template void ctor_init1(const MatrixType& m) +{ + // Check logic in PlainObjectBase::_init1 + Index rows = m.rows(); + Index cols = m.cols(); + + MatrixType m0 = MatrixType::Random(rows,cols); + + VERIFY_EVALUATION_COUNT( MatrixType m1(m0), 1); + VERIFY_EVALUATION_COUNT( MatrixType m2(m0+m0), 1); + VERIFY_EVALUATION_COUNT( MatrixType m2(m0.block(0,0,rows,cols)) , 1); + + Wrapper wrapper(m0); + VERIFY_EVALUATION_COUNT( MatrixType m3(wrapper) , 1); +} + + +void test_constructor() +{ + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( ctor_init1(Matrix()) ); + CALL_SUBTEST_1( ctor_init1(Matrix4d()) ); + CALL_SUBTEST_1( ctor_init1(MatrixXcf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_1( ctor_init1(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } + { + Matrix a(123); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Matrix a(123.0); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Matrix a(123); + VERIFY_IS_EQUAL(a[0], 123.f); + } + { + Array a(123); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Array a(123.0); + VERIFY_IS_EQUAL(a[0], 123); + } + { + Array a(123); + VERIFY_IS_EQUAL(a[0], 123.f); + } + { + Array a(123); + VERIFY_IS_EQUAL(a(4), 123); + } + { + Array a(123.0); + VERIFY_IS_EQUAL(a(4), 123); + } + { + Array a(123); + VERIFY_IS_EQUAL(a(4), 123.f); + } +} diff --git a/gtsam/3rdparty/Eigen/test/ctorleak.cpp b/gtsam/3rdparty/Eigen/test/ctorleak.cpp new file mode 100644 index 000000000..c158f5e4e --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/ctorleak.cpp @@ -0,0 +1,69 @@ +#include "main.h" + +#include // std::exception + +struct Foo +{ + static Index object_count; + static Index object_limit; + int dummy; + + Foo() + { +#ifdef EIGEN_EXCEPTIONS + // TODO: Is this the correct way to handle this? + if (Foo::object_count > Foo::object_limit) { std::cout << "\nThrow!\n"; throw Foo::Fail(); } +#endif + std::cout << '+'; + ++Foo::object_count; + } + + ~Foo() + { + std::cout << '-'; + --Foo::object_count; + } + + class Fail : public std::exception {}; +}; + +Index Foo::object_count = 0; +Index Foo::object_limit = 0; + +#undef EIGEN_TEST_MAX_SIZE +#define EIGEN_TEST_MAX_SIZE 3 + +void test_ctorleak() +{ + typedef Matrix MatrixX; + typedef Matrix VectorX; + Foo::object_count = 0; + for(int i = 0; i < g_repeat; i++) { + Index rows = internal::random(2,EIGEN_TEST_MAX_SIZE), cols = internal::random(2,EIGEN_TEST_MAX_SIZE); + Foo::object_limit = internal::random(0, rows*cols - 2); + std::cout << "object_limit =" << Foo::object_limit << std::endl; +#ifdef EIGEN_EXCEPTIONS + try + { +#endif + std::cout << "\nMatrixX m(" << rows << ", " << cols << ");\n"; + MatrixX m(rows, cols); +#ifdef EIGEN_EXCEPTIONS + VERIFY(false); // not reached if exceptions are enabled + } + catch (const Foo::Fail&) { /* ignore */ } +#endif + VERIFY_IS_EQUAL(Index(0), Foo::object_count); + + { + Foo::object_limit = (rows+1)*(cols+1); + MatrixX A(rows, cols); + VERIFY_IS_EQUAL(Foo::object_count, rows*cols); + VectorX v=A.row(0); + VERIFY_IS_EQUAL(Foo::object_count, (rows+1)*cols); + v = A.col(0); + VERIFY_IS_EQUAL(Foo::object_count, rows*(cols+1)); + } + VERIFY_IS_EQUAL(Index(0), Foo::object_count); + } +} diff --git a/gtsam/3rdparty/Eigen/test/cuda_basic.cu b/gtsam/3rdparty/Eigen/test/cuda_basic.cu new file mode 100644 index 000000000..cb2e4167a --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/cuda_basic.cu @@ -0,0 +1,173 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015-2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +// workaround issue between gcc >= 4.7 and cuda 5.5 +#if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7) + #undef _GLIBCXX_ATOMIC_BUILTINS + #undef _GLIBCXX_USE_INT128 +#endif + +#define EIGEN_TEST_NO_LONGDOUBLE +#define EIGEN_TEST_NO_COMPLEX +#define EIGEN_TEST_FUNC cuda_basic +#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int + +#include +#include +#if defined __CUDACC_VER__ && __CUDACC_VER__ >= 70500 +#include +#endif +#include "main.h" +#include "cuda_common.h" + +// Check that dense modules can be properly parsed by nvcc +#include + +// struct Foo{ +// EIGEN_DEVICE_FUNC +// void operator()(int i, const float* mats, float* vecs) const { +// using namespace Eigen; +// // Matrix3f M(data); +// // Vector3f x(data+9); +// // Map(data+9) = M.inverse() * x; +// Matrix3f M(mats+i/16); +// Vector3f x(vecs+i*3); +// // using std::min; +// // using std::sqrt; +// Map(vecs+i*3) << x.minCoeff(), 1, 2;// / x.dot(x);//(M.inverse() * x) / x.x(); +// //x = x*2 + x.y() * x + x * x.maxCoeff() - x / x.sum(); +// } +// }; + +template +struct coeff_wise { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + T x1(in+i); + T x2(in+i+1); + T x3(in+i+2); + Map res(out+i*T::MaxSizeAtCompileTime); + + res.array() += (in[0] * x1 + x2).array() * x3.array(); + } +}; + +template +struct replicate { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + T x1(in+i); + int step = x1.size() * 4; + int stride = 3 * step; + + typedef Map > MapType; + MapType(out+i*stride+0*step, x1.rows()*2, x1.cols()*2) = x1.replicate(2,2); + MapType(out+i*stride+1*step, x1.rows()*3, x1.cols()) = in[i] * x1.colwise().replicate(3); + MapType(out+i*stride+2*step, x1.rows(), x1.cols()*3) = in[i] * x1.rowwise().replicate(3); + } +}; + +template +struct redux { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + int N = 10; + T x1(in+i); + out[i*N+0] = x1.minCoeff(); + out[i*N+1] = x1.maxCoeff(); + out[i*N+2] = x1.sum(); + out[i*N+3] = x1.prod(); + out[i*N+4] = x1.matrix().squaredNorm(); + out[i*N+5] = x1.matrix().norm(); + out[i*N+6] = x1.colwise().sum().maxCoeff(); + out[i*N+7] = x1.rowwise().maxCoeff().sum(); + out[i*N+8] = x1.matrix().colwise().squaredNorm().sum(); + } +}; + +template +struct prod_test { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const + { + using namespace Eigen; + typedef Matrix T3; + T1 x1(in+i); + T2 x2(in+i+1); + Map res(out+i*T3::MaxSizeAtCompileTime); + res += in[i] * x1 * x2; + } +}; + +template +struct diagonal { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const + { + using namespace Eigen; + T1 x1(in+i); + Map res(out+i*T2::MaxSizeAtCompileTime); + res += x1.diagonal(); + } +}; + +template +struct eigenvalues { + EIGEN_DEVICE_FUNC + void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const + { + using namespace Eigen; + typedef Matrix Vec; + T M(in+i); + Map res(out+i*Vec::MaxSizeAtCompileTime); + T A = M*M.adjoint(); + SelfAdjointEigenSolver eig; + eig.computeDirect(M); + res = eig.eigenvalues(); + } +}; + +void test_cuda_basic() +{ + ei_test_init_cuda(); + + int nthreads = 100; + Eigen::VectorXf in, out; + + #ifndef __CUDA_ARCH__ + int data_size = nthreads * 512; + in.setRandom(data_size); + out.setRandom(data_size); + #endif + + CALL_SUBTEST( run_and_compare_to_cuda(coeff_wise(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(coeff_wise(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(replicate(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(replicate(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(redux(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(redux(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(prod_test(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(prod_test(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(diagonal(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(diagonal(), nthreads, in, out) ); + + CALL_SUBTEST( run_and_compare_to_cuda(eigenvalues(), nthreads, in, out) ); + CALL_SUBTEST( run_and_compare_to_cuda(eigenvalues(), nthreads, in, out) ); + +} diff --git a/gtsam/3rdparty/Eigen/test/cuda_common.h b/gtsam/3rdparty/Eigen/test/cuda_common.h new file mode 100644 index 000000000..9737693ac --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/cuda_common.h @@ -0,0 +1,101 @@ + +#ifndef EIGEN_TEST_CUDA_COMMON_H +#define EIGEN_TEST_CUDA_COMMON_H + +#include +#include +#include +#include + +#ifndef __CUDACC__ +dim3 threadIdx, blockDim, blockIdx; +#endif + +template +void run_on_cpu(const Kernel& ker, int n, const Input& in, Output& out) +{ + for(int i=0; i +__global__ +void run_on_cuda_meta_kernel(const Kernel ker, int n, const Input* in, Output* out) +{ + int i = threadIdx.x + blockIdx.x*blockDim.x; + if(i +void run_on_cuda(const Kernel& ker, int n, const Input& in, Output& out) +{ + typename Input::Scalar* d_in; + typename Output::Scalar* d_out; + std::ptrdiff_t in_bytes = in.size() * sizeof(typename Input::Scalar); + std::ptrdiff_t out_bytes = out.size() * sizeof(typename Output::Scalar); + + cudaMalloc((void**)(&d_in), in_bytes); + cudaMalloc((void**)(&d_out), out_bytes); + + cudaMemcpy(d_in, in.data(), in_bytes, cudaMemcpyHostToDevice); + cudaMemcpy(d_out, out.data(), out_bytes, cudaMemcpyHostToDevice); + + // Simple and non-optimal 1D mapping assuming n is not too large + // That's only for unit testing! + dim3 Blocks(128); + dim3 Grids( (n+int(Blocks.x)-1)/int(Blocks.x) ); + + cudaThreadSynchronize(); + run_on_cuda_meta_kernel<<>>(ker, n, d_in, d_out); + cudaThreadSynchronize(); + + // check inputs have not been modified + cudaMemcpy(const_cast(in.data()), d_in, in_bytes, cudaMemcpyDeviceToHost); + cudaMemcpy(out.data(), d_out, out_bytes, cudaMemcpyDeviceToHost); + + cudaFree(d_in); + cudaFree(d_out); +} + + +template +void run_and_compare_to_cuda(const Kernel& ker, int n, const Input& in, Output& out) +{ + Input in_ref, in_cuda; + Output out_ref, out_cuda; + #ifndef __CUDA_ARCH__ + in_ref = in_cuda = in; + out_ref = out_cuda = out; + #endif + run_on_cpu (ker, n, in_ref, out_ref); + run_on_cuda(ker, n, in_cuda, out_cuda); + #ifndef __CUDA_ARCH__ + VERIFY_IS_APPROX(in_ref, in_cuda); + VERIFY_IS_APPROX(out_ref, out_cuda); + #endif +} + + +void ei_test_init_cuda() +{ + int device = 0; + cudaDeviceProp deviceProp; + cudaGetDeviceProperties(&deviceProp, device); + std::cout << "CUDA device info:\n"; + std::cout << " name: " << deviceProp.name << "\n"; + std::cout << " capability: " << deviceProp.major << "." << deviceProp.minor << "\n"; + std::cout << " multiProcessorCount: " << deviceProp.multiProcessorCount << "\n"; + std::cout << " maxThreadsPerMultiProcessor: " << deviceProp.maxThreadsPerMultiProcessor << "\n"; + std::cout << " warpSize: " << deviceProp.warpSize << "\n"; + std::cout << " regsPerBlock: " << deviceProp.regsPerBlock << "\n"; + std::cout << " concurrentKernels: " << deviceProp.concurrentKernels << "\n"; + std::cout << " clockRate: " << deviceProp.clockRate << "\n"; + std::cout << " canMapHostMemory: " << deviceProp.canMapHostMemory << "\n"; + std::cout << " computeMode: " << deviceProp.computeMode << "\n"; +} + +#endif // EIGEN_TEST_CUDA_COMMON_H diff --git a/gtsam/3rdparty/Eigen/test/cwiseop.cpp b/gtsam/3rdparty/Eigen/test/cwiseop.cpp deleted file mode 100644 index d13002cae..000000000 --- a/gtsam/3rdparty/Eigen/test/cwiseop.cpp +++ /dev/null @@ -1,187 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN2_SUPPORT -#define EIGEN_NO_EIGEN2_DEPRECATED_WARNING - -#define EIGEN_NO_STATIC_ASSERT -#include "main.h" -#include - -#ifdef min -#undef min -#endif - -#ifdef max -#undef max -#endif - -using namespace std; - -template struct AddIfNull { - const Scalar operator() (const Scalar a, const Scalar b) const {return a<=1e-3 ? b : a;} - enum { Cost = NumTraits::AddCost }; -}; - -template -typename Eigen::internal::enable_if::IsInteger,typename MatrixType::Scalar>::type -cwiseops_real_only(MatrixType& m1, MatrixType& m2, MatrixType& m3, MatrixType& mones) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - VERIFY_IS_APPROX(m1.cwise() / m2, m1.cwise() * (m2.cwise().inverse())); - m3 = m1.cwise().abs().cwise().sqrt(); - VERIFY_IS_APPROX(m3.cwise().square(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().square().cwise().sqrt(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().abs().cwise().log().cwise().exp() , m1.cwise().abs()); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - m3 = (m1.cwise().abs().cwise()<=RealScalar(0.01)).select(mones,m1); - VERIFY_IS_APPROX(m3.cwise().pow(-1), m3.cwise().inverse()); - m3 = m1.cwise().abs(); - VERIFY_IS_APPROX(m3.cwise().pow(RealScalar(0.5)), m3.cwise().sqrt()); - -// VERIFY_IS_APPROX(m1.cwise().tan(), m1.cwise().sin().cwise() / m1.cwise().cos()); - VERIFY_IS_APPROX(mones, m1.cwise().sin().cwise().square() + m1.cwise().cos().cwise().square()); - m3 = m1; - m3.cwise() /= m2; - VERIFY_IS_APPROX(m3, m1.cwise() / m2); - - return Scalar(0); -} - -template -typename Eigen::internal::enable_if::IsInteger,typename MatrixType::Scalar>::type -cwiseops_real_only(MatrixType& , MatrixType& , MatrixType& , MatrixType& ) -{ - return 0; -} - -template void cwiseops(const MatrixType& m) -{ - typedef typename MatrixType::Index Index; - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - Index rows = m.rows(); - Index cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m1bis = m1, - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols), - identity = Matrix - ::Identity(rows, rows); - VectorType vzero = VectorType::Zero(rows), - vones = VectorType::Ones(rows), - v3(rows); - - Index r = internal::random(0, rows-1), - c = internal::random(0, cols-1); - - Scalar s1 = internal::random(); - - // test Zero, Ones, Constant, and the set* variants - m3 = MatrixType::Constant(rows, cols, s1); - for (int j=0; j >(mones); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().abs2()); - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - VERIFY_IS_APPROX(m1.cwise().pow(3), m1.cwise().cube()); - - VERIFY_IS_APPROX(m1 + mones, m1.cwise()+Scalar(1)); - VERIFY_IS_APPROX(m1 - mones, m1.cwise()-Scalar(1)); - m3 = m1; m3.cwise() += 1; - VERIFY_IS_APPROX(m1 + mones, m3); - m3 = m1; m3.cwise() -= 1; - VERIFY_IS_APPROX(m1 - mones, m3); - - VERIFY_IS_APPROX(m2, m2.cwise() * mones); - VERIFY_IS_APPROX(m1.cwise() * m2, m2.cwise() * m1); - m3 = m1; - m3.cwise() *= m2; - VERIFY_IS_APPROX(m3, m1.cwise() * m2); - - VERIFY_IS_APPROX(mones, m2.cwise()/m2); - - // check min - VERIFY_IS_APPROX( m1.cwise().min(m2), m2.cwise().min(m1) ); - VERIFY_IS_APPROX( m1.cwise().min(m1+mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().min(m1-mones), m1-mones ); - - // check max - VERIFY_IS_APPROX( m1.cwise().max(m2), m2.cwise().max(m1) ); - VERIFY_IS_APPROX( m1.cwise().max(m1-mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().max(m1+mones), m1+mones ); - - VERIFY( (m1.cwise() == m1).all() ); - VERIFY( (m1.cwise() != m2).any() ); - VERIFY(!(m1.cwise() == (m1+mones)).any() ); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY( (m1.cwise() == m3).any() ); - VERIFY( !(m1.cwise() == m3).all() ); - } - VERIFY( (m1.cwise().min(m2).cwise() <= m2).all() ); - VERIFY( (m1.cwise().max(m2).cwise() >= m2).all() ); - VERIFY( (m1.cwise().min(m2).cwise() < (m1+mones)).all() ); - VERIFY( (m1.cwise().max(m2).cwise() > (m1-mones)).all() ); - -#if(__cplusplus < 201103L) -// std::binder* are deprecated since c++11 and will be removed in c++17 - VERIFY( (m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()>m1bis.unaryExpr(bind2nd(plus(), Scalar(1)))).any() ); -#endif - - cwiseops_real_only(m1, m2, m3, mones); -} - -void test_cwiseop() -{ - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( cwiseops(Matrix()) ); - CALL_SUBTEST_2( cwiseops(Matrix4d()) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_4( cwiseops(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_5( cwiseops(MatrixXi(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - CALL_SUBTEST_6( cwiseops(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/dense_storage.cpp b/gtsam/3rdparty/Eigen/test/dense_storage.cpp new file mode 100644 index 000000000..e63712b1a --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/dense_storage.cpp @@ -0,0 +1,76 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include + +template +void dense_storage_copy() +{ + static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols); + typedef DenseStorage DenseStorageType; + + const int rows = (Rows==Dynamic) ? 4 : Rows; + const int cols = (Cols==Dynamic) ? 3 : Cols; + const int size = rows*cols; + DenseStorageType reference(size, rows, cols); + T* raw_reference = reference.data(); + for (int i=0; i(i); + + DenseStorageType copied_reference(reference); + const T* raw_copied_reference = copied_reference.data(); + for (int i=0; i +void dense_storage_assignment() +{ + static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols); + typedef DenseStorage DenseStorageType; + + const int rows = (Rows==Dynamic) ? 4 : Rows; + const int cols = (Cols==Dynamic) ? 3 : Cols; + const int size = rows*cols; + DenseStorageType reference(size, rows, cols); + T* raw_reference = reference.data(); + for (int i=0; i(i); + + DenseStorageType copied_reference; + copied_reference = reference; + const T* raw_copied_reference = copied_reference.data(); + for (int i=0; i(); + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + dense_storage_copy(); + + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); + dense_storage_assignment(); +} diff --git a/gtsam/3rdparty/Eigen/test/diagonal.cpp b/gtsam/3rdparty/Eigen/test/diagonal.cpp index 53814a588..c1546e97d 100644 --- a/gtsam/3rdparty/Eigen/test/diagonal.cpp +++ b/gtsam/3rdparty/Eigen/test/diagonal.cpp @@ -20,6 +20,8 @@ template void diagonal(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols), m2 = MatrixType::Random(rows, cols); + Scalar s1 = internal::random(); + //check diagonal() VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal()); m2.diagonal() = 2 * m1.diagonal(); @@ -58,6 +60,26 @@ template void diagonal(const MatrixType& m) VERIFY_IS_APPROX(m2.template diagonal(), static_cast(2) * m1.diagonal(N2)); m2.diagonal(N2)[0] *= 3; VERIFY_IS_APPROX(m2.diagonal(N2)[0], static_cast(6) * m1.diagonal(N2)[0]); + + m2.diagonal(N2).x() = s1; + VERIFY_IS_APPROX(m2.diagonal(N2).x(), s1); + m2.diagonal(N2).coeffRef(0) = Scalar(2)*s1; + VERIFY_IS_APPROX(m2.diagonal(N2).coeff(0), Scalar(2)*s1); + } +} + +template void diagonal_assert(const MatrixType& m) { + Index rows = m.rows(); + Index cols = m.cols(); + + MatrixType m1 = MatrixType::Random(rows, cols); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.diagonal() ); + VERIFY_RAISES_ASSERT( m1 -= m1.diagonal() ); + VERIFY_RAISES_ASSERT( m1.array() *= m1.diagonal().array() ); + VERIFY_RAISES_ASSERT( m1.array() /= m1.diagonal().array() ); } } @@ -74,4 +96,6 @@ void test_diagonal() CALL_SUBTEST_1( diagonal(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_1( diagonal(Matrix(3, 4)) ); } + + CALL_SUBTEST_1( diagonal_assert(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } diff --git a/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp b/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp index 149f1db2f..cd6dc8cf0 100644 --- a/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp +++ b/gtsam/3rdparty/Eigen/test/diagonalmatrices.cpp @@ -17,6 +17,7 @@ template void diagonalmatrices(const MatrixType& m) typedef Matrix VectorType; typedef Matrix RowVectorType; typedef Matrix SquareMatrixType; + typedef Matrix DynMatrixType; typedef DiagonalMatrix LeftDiagonalMatrix; typedef DiagonalMatrix RightDiagonalMatrix; typedef Matrix BigMatrix; @@ -64,6 +65,13 @@ template void diagonalmatrices(const MatrixType& m) VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * (m1+m2))(i,j)) , (v1+v2)(i) * (m1+m2)(i,j) ); VERIFY_IS_APPROX( ((m1 * (rv1+rv2).asDiagonal())(i,j)) , (rv1+rv2)(j) * m1(i,j) ); VERIFY_IS_APPROX( (((m1+m2) * (rv1+rv2).asDiagonal())(i,j)) , (rv1+rv2)(j) * (m1+m2)(i,j) ); + + if(rows>1) + { + DynMatrixType tmp = m1.topRows(rows/2), res; + VERIFY_IS_APPROX( (res = m1.topRows(rows/2) * rv1.asDiagonal()), tmp * rv1.asDiagonal() ); + VERIFY_IS_APPROX( (res = v1.head(rows/2).asDiagonal()*m1.topRows(rows/2)), v1.head(rows/2).asDiagonal()*tmp ); + } BigMatrix big; big.setZero(2*rows, 2*cols); @@ -84,6 +92,24 @@ template void diagonalmatrices(const MatrixType& m) VERIFY_IS_APPROX(m1 * (rdm1 * s1), (m1 * rdm1) * s1); VERIFY_IS_APPROX(m1 * (s1 * rdm1), (m1 * rdm1) * s1); + + // Diagonal to dense + sq_m1.setRandom(); + sq_m2 = sq_m1; + VERIFY_IS_APPROX( (sq_m1 += (s1*v1).asDiagonal()), sq_m2 += (s1*v1).asDiagonal().toDenseMatrix() ); + VERIFY_IS_APPROX( (sq_m1 -= (s1*v1).asDiagonal()), sq_m2 -= (s1*v1).asDiagonal().toDenseMatrix() ); + VERIFY_IS_APPROX( (sq_m1 = (s1*v1).asDiagonal()), (s1*v1).asDiagonal().toDenseMatrix() ); +} + +template +void bug987() +{ + Matrix3Xd points = Matrix3Xd::Random(3, 3); + Vector2d diag = Vector2d::Random(); + Matrix2Xd tmp1 = points.topRows<2>(), res1, res2; + VERIFY_IS_APPROX( res1 = diag.asDiagonal() * points.topRows<2>(), res2 = diag.asDiagonal() * tmp1 ); + Matrix2d tmp2 = points.topLeftCorner<2,2>(); + VERIFY_IS_APPROX(( res1 = points.topLeftCorner<2,2>()*diag.asDiagonal()) , res2 = tmp2*diag.asDiagonal() ); } void test_diagonalmatrices() @@ -99,4 +125,5 @@ void test_diagonalmatrices() CALL_SUBTEST_8( diagonalmatrices(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_9( diagonalmatrices(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } + CALL_SUBTEST_10( bug987<0>() ); } diff --git a/gtsam/3rdparty/Eigen/test/dynalloc.cpp b/gtsam/3rdparty/Eigen/test/dynalloc.cpp index ef92c0507..f1cc70bee 100644 --- a/gtsam/3rdparty/Eigen/test/dynalloc.cpp +++ b/gtsam/3rdparty/Eigen/test/dynalloc.cpp @@ -9,18 +9,20 @@ #include "main.h" -#if EIGEN_ALIGN -#define ALIGNMENT 16 +#if EIGEN_MAX_ALIGN_BYTES>0 +#define ALIGNMENT EIGEN_MAX_ALIGN_BYTES #else #define ALIGNMENT 1 #endif +typedef Matrix Vector8f; + void check_handmade_aligned_malloc() { for(int i = 1; i < 1000; i++) { char *p = (char*)internal::handmade_aligned_malloc(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::handmade_aligned_free(p); @@ -29,10 +31,10 @@ void check_handmade_aligned_malloc() void check_aligned_malloc() { - for(int i = 1; i < 1000; i++) + for(int i = ALIGNMENT; i < 1000; i++) { char *p = (char*)internal::aligned_malloc(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::aligned_free(p); @@ -41,10 +43,10 @@ void check_aligned_malloc() void check_aligned_new() { - for(int i = 1; i < 1000; i++) + for(int i = ALIGNMENT; i < 1000; i++) { float *p = internal::aligned_new(i); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; internal::aligned_delete(p,i); @@ -53,10 +55,10 @@ void check_aligned_new() void check_aligned_stack_alloc() { - for(int i = 1; i < 400; i++) + for(int i = ALIGNMENT; i < 400; i++) { ei_declare_aligned_stack_constructed_variable(float,p,i,0); - VERIFY(size_t(p)%ALIGNMENT==0); + VERIFY(internal::UIntPtr(p)%ALIGNMENT==0); // if the buffer is wrongly allocated this will give a bad write --> check with valgrind for(int j = 0; j < i; j++) p[j]=0; } @@ -68,7 +70,7 @@ struct MyStruct { EIGEN_MAKE_ALIGNED_OPERATOR_NEW char dummychar; - Vector4f avec; + Vector8f avec; }; class MyClassA @@ -76,15 +78,19 @@ class MyClassA public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW char dummychar; - Vector4f avec; + Vector8f avec; }; template void check_dynaligned() { - T* obj = new T; - VERIFY(T::NeedsToAlign==1); - VERIFY(size_t(obj)%ALIGNMENT==0); - delete obj; + // TODO have to be updated once we support multiple alignment values + if(T::SizeAtCompileTime % ALIGNMENT == 0) + { + T* obj = new T; + VERIFY(T::NeedsToAlign==1); + VERIFY(internal::UIntPtr(obj)%ALIGNMENT==0); + delete obj; + } } template void check_custom_new_delete() @@ -100,7 +106,7 @@ template void check_custom_new_delete() delete[] t; } -#ifdef EIGEN_ALIGN +#if EIGEN_MAX_ALIGN_BYTES>0 { T* t = static_cast((T::operator new)(sizeof(T))); (T::operator delete)(t, sizeof(T)); @@ -120,9 +126,17 @@ void test_dynalloc() CALL_SUBTEST(check_aligned_malloc()); CALL_SUBTEST(check_aligned_new()); CALL_SUBTEST(check_aligned_stack_alloc()); + + for (int i=0; i() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST( check_custom_new_delete() ); + } // check static allocation, who knows ? - #if EIGEN_ALIGN_STATICALLY + #if EIGEN_MAX_STATIC_ALIGN_BYTES for (int i=0; i() ); @@ -130,23 +144,19 @@ void test_dynalloc() CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); CALL_SUBTEST(check_dynaligned() ); - - CALL_SUBTEST( check_custom_new_delete() ); - CALL_SUBTEST( check_custom_new_delete() ); - CALL_SUBTEST( check_custom_new_delete() ); - CALL_SUBTEST( check_custom_new_delete() ); + CALL_SUBTEST(check_dynaligned() ); } { - MyStruct foo0; VERIFY(size_t(foo0.avec.data())%ALIGNMENT==0); - MyClassA fooA; VERIFY(size_t(fooA.avec.data())%ALIGNMENT==0); + MyStruct foo0; VERIFY(internal::UIntPtr(foo0.avec.data())%ALIGNMENT==0); + MyClassA fooA; VERIFY(internal::UIntPtr(fooA.avec.data())%ALIGNMENT==0); } // dynamic allocation, single object for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA(); VERIFY(size_t(fooA->avec.data())%ALIGNMENT==0); + MyStruct *foo0 = new MyStruct(); VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0); + MyClassA *fooA = new MyClassA(); VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0); delete foo0; delete fooA; } @@ -155,8 +165,8 @@ void test_dynalloc() const int N = 10; for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA[N]; VERIFY(size_t(fooA->avec.data())%ALIGNMENT==0); + MyStruct *foo0 = new MyStruct[N]; VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0); + MyClassA *fooA = new MyClassA[N]; VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0); delete[] foo0; delete[] fooA; } diff --git a/gtsam/3rdparty/Eigen/test/eigen2/CMakeLists.txt b/gtsam/3rdparty/Eigen/test/eigen2/CMakeLists.txt deleted file mode 100644 index 9615a6026..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/CMakeLists.txt +++ /dev/null @@ -1,61 +0,0 @@ -add_custom_target(eigen2_buildtests) -add_custom_target(eigen2_check COMMAND "ctest -R eigen2") -add_dependencies(eigen2_check eigen2_buildtests) -add_dependencies(buildtests eigen2_buildtests) - -add_definitions("-DEIGEN2_SUPPORT_STAGE10_FULL_EIGEN2_API") -add_definitions("-DEIGEN_NO_EIGEN2_DEPRECATED_WARNING") - -ei_add_test(eigen2_meta) -ei_add_test(eigen2_sizeof) -ei_add_test(eigen2_dynalloc) -ei_add_test(eigen2_nomalloc) -#ei_add_test(eigen2_first_aligned) -ei_add_test(eigen2_mixingtypes) -#ei_add_test(eigen2_packetmath) -ei_add_test(eigen2_unalignedassert) -#ei_add_test(eigen2_vectorization_logic) -ei_add_test(eigen2_basicstuff) -ei_add_test(eigen2_linearstructure) -ei_add_test(eigen2_cwiseop) -ei_add_test(eigen2_sum) -ei_add_test(eigen2_product_small) -ei_add_test(eigen2_product_large ${EI_OFLAG}) -ei_add_test(eigen2_adjoint) -ei_add_test(eigen2_submatrices) -ei_add_test(eigen2_miscmatrices) -ei_add_test(eigen2_commainitializer) -ei_add_test(eigen2_smallvectors) -ei_add_test(eigen2_map) -ei_add_test(eigen2_array) -ei_add_test(eigen2_triangular) -ei_add_test(eigen2_cholesky " " "${GSL_LIBRARIES}") -ei_add_test(eigen2_lu ${EI_OFLAG}) -ei_add_test(eigen2_determinant ${EI_OFLAG}) -ei_add_test(eigen2_inverse) -ei_add_test(eigen2_qr) -ei_add_test(eigen2_eigensolver " " "${GSL_LIBRARIES}") -ei_add_test(eigen2_svd) -ei_add_test(eigen2_geometry) -ei_add_test(eigen2_geometry_with_eigen2_prefix) -ei_add_test(eigen2_hyperplane) -ei_add_test(eigen2_parametrizedline) -ei_add_test(eigen2_alignedbox) -ei_add_test(eigen2_regression) -ei_add_test(eigen2_stdvector) -ei_add_test(eigen2_newstdvector) -if(QT4_FOUND) - ei_add_test(eigen2_qtvector " " "${QT_QTCORE_LIBRARY}") -endif(QT4_FOUND) -# no support for eigen2 sparse module -# if(NOT EIGEN_DEFAULT_TO_ROW_MAJOR) -# ei_add_test(eigen2_sparse_vector) -# ei_add_test(eigen2_sparse_basic) -# ei_add_test(eigen2_sparse_solvers " " "${SPARSE_LIBS}") -# ei_add_test(eigen2_sparse_product) -# endif() -ei_add_test(eigen2_swap) -ei_add_test(eigen2_visitor) -ei_add_test(eigen2_bug_132) - -ei_add_test(eigen2_prec_inverse_4x4 ${EI_OFLAG}) diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_adjoint.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_adjoint.cpp deleted file mode 100644 index c0f811459..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_adjoint.cpp +++ /dev/null @@ -1,99 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void adjoint(const MatrixType& m) -{ - /* this test covers the following files: - Transpose.h Conjugate.h Dot.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix SquareMatrixType; - int rows = m.rows(); - int cols = m.cols(); - - RealScalar largerEps = test_precision(); - if (ei_is_same_type::ret) - largerEps = RealScalar(1e-3f); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - square = SquareMatrixType::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - v2 = VectorType::Random(rows), - v3 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); - - Scalar s1 = ei_random(), - s2 = ei_random(); - - // check basic compatibility of adjoint, transpose, conjugate - VERIFY_IS_APPROX(m1.transpose().conjugate().adjoint(), m1); - VERIFY_IS_APPROX(m1.adjoint().conjugate().transpose(), m1); - - // check multiplicative behavior - VERIFY_IS_APPROX((m1.adjoint() * m2).adjoint(), m2.adjoint() * m1); - VERIFY_IS_APPROX((s1 * m1).adjoint(), ei_conj(s1) * m1.adjoint()); - - // check basic properties of dot, norm, norm2 - typedef typename NumTraits::Real RealScalar; - VERIFY(ei_isApprox((s1 * v1 + s2 * v2).eigen2_dot(v3), s1 * v1.eigen2_dot(v3) + s2 * v2.eigen2_dot(v3), largerEps)); - VERIFY(ei_isApprox(v3.eigen2_dot(s1 * v1 + s2 * v2), ei_conj(s1)*v3.eigen2_dot(v1)+ei_conj(s2)*v3.eigen2_dot(v2), largerEps)); - VERIFY_IS_APPROX(ei_conj(v1.eigen2_dot(v2)), v2.eigen2_dot(v1)); - VERIFY_IS_APPROX(ei_real(v1.eigen2_dot(v1)), v1.squaredNorm()); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_APPROX(v1.squaredNorm(), v1.norm() * v1.norm()); - VERIFY_IS_MUCH_SMALLER_THAN(ei_abs(vzero.eigen2_dot(v1)), static_cast(1)); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_MUCH_SMALLER_THAN(vzero.norm(), static_cast(1)); - - // check compatibility of dot and adjoint - VERIFY(ei_isApprox(v1.eigen2_dot(square * v2), (square.adjoint() * v1).eigen2_dot(v2), largerEps)); - - // like in testBasicStuff, test operator() to check const-qualification - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - VERIFY_IS_APPROX(m1.conjugate()(r,c), ei_conj(m1(r,c))); - VERIFY_IS_APPROX(m1.adjoint()(c,r), ei_conj(m1(r,c))); - - if(NumTraits::HasFloatingPoint) - { - // check that Random().normalized() works: tricky as the random xpr must be evaluated by - // normalized() in order to produce a consistent result. - VERIFY_IS_APPROX(VectorType::Random(rows).normalized().norm(), RealScalar(1)); - } - - // check inplace transpose - m3 = m1; - m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1.transpose()); - m3.transposeInPlace(); - VERIFY_IS_APPROX(m3,m1); - -} - -void test_eigen2_adjoint() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( adjoint(Matrix()) ); - CALL_SUBTEST_2( adjoint(Matrix3d()) ); - CALL_SUBTEST_3( adjoint(Matrix4f()) ); - CALL_SUBTEST_4( adjoint(MatrixXcf(4, 4)) ); - CALL_SUBTEST_5( adjoint(MatrixXi(8, 12)) ); - CALL_SUBTEST_6( adjoint(MatrixXf(21, 21)) ); - } - // test a large matrix only once - CALL_SUBTEST_7( adjoint(Matrix()) ); -} - diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_alignedbox.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_alignedbox.cpp deleted file mode 100644 index 35043b958..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_alignedbox.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void alignedbox(const BoxType& _box) -{ - /* this test covers the following files: - AlignedBox.h - */ - - const int dim = _box.dim(); - typedef typename BoxType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - RealScalar s1 = ei_random(0,1); - - BoxType b0(dim); - BoxType b1(VectorType::Random(dim),VectorType::Random(dim)); - BoxType b2; - - b0.extend(p0); - b0.extend(p1); - VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1)); - VERIFY(!b0.contains(p0 + (1+s1)*(p1-p0))); - - (b2 = b0).extend(b1); - VERIFY(b2.contains(b0)); - VERIFY(b2.contains(b1)); - VERIFY_IS_APPROX(b2.clamp(b0), b0); - - // casting - const int Dim = BoxType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - AlignedBox hp1f = b0.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),b0); - AlignedBox hp1d = b0.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),b0); -} - -void test_eigen2_alignedbox() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( alignedbox(AlignedBox()) ); - CALL_SUBTEST_2( alignedbox(AlignedBox()) ); - CALL_SUBTEST_3( alignedbox(AlignedBox()) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_array.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_array.cpp deleted file mode 100644 index c1ff40ce7..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_array.cpp +++ /dev/null @@ -1,142 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void array(const MatrixType& m) -{ - /* this test covers the following files: - Array.cpp - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - Scalar s1 = ei_random(), - s2 = ei_random(); - - // scalar addition - VERIFY_IS_APPROX(m1.cwise() + s1, s1 + m1.cwise()); - VERIFY_IS_APPROX(m1.cwise() + s1, MatrixType::Constant(rows,cols,s1) + m1); - VERIFY_IS_APPROX((m1*Scalar(2)).cwise() - s2, (m1+m1) - MatrixType::Constant(rows,cols,s2) ); - m3 = m1; - m3.cwise() += s2; - VERIFY_IS_APPROX(m3, m1.cwise() + s2); - m3 = m1; - m3.cwise() -= s1; - VERIFY_IS_APPROX(m3, m1.cwise() - s1); - - // reductions - VERIFY_IS_APPROX(m1.colwise().sum().sum(), m1.sum()); - VERIFY_IS_APPROX(m1.rowwise().sum().sum(), m1.sum()); - if (!ei_isApprox(m1.sum(), (m1+m2).sum())) - VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum()); - VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op())); -} - -template void comparisons(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - VERIFY(((m1.cwise() + Scalar(1)).cwise() > m1).all()); - VERIFY(((m1.cwise() - Scalar(1)).cwise() < m1).all()); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY(! (m1.cwise() < m3).all() ); - VERIFY(! (m1.cwise() > m3).all() ); - } - - // comparisons to scalar - VERIFY( (m1.cwise() != (m1(r,c)+1) ).any() ); - VERIFY( (m1.cwise() > (m1(r,c)-1) ).any() ); - VERIFY( (m1.cwise() < (m1(r,c)+1) ).any() ); - VERIFY( (m1.cwise() == m1(r,c) ).any() ); - - // test Select - VERIFY_IS_APPROX( (m1.cwise()m2).select(m1,m2), m1.cwise().max(m2) ); - Scalar mid = (m1.cwise().abs().minCoeff() + m1.cwise().abs().maxCoeff())/Scalar(2); - for (int j=0; j=MatrixType::Constant(rows,cols,mid)) - .select(m1,0), m3); - // even shorter version: - VERIFY_IS_APPROX( (m1.cwise().abs().cwise()RealScalar(0.1)).count() == rows*cols); - VERIFY_IS_APPROX(((m1.cwise().abs().cwise()+1).cwise()>RealScalar(0.1)).colwise().count().template cast(), RowVectorXi::Constant(cols,rows)); - VERIFY_IS_APPROX(((m1.cwise().abs().cwise()+1).cwise()>RealScalar(0.1)).rowwise().count().template cast(), VectorXi::Constant(rows, cols)); -} - -template void lpNorm(const VectorType& v) -{ - VectorType u = VectorType::Random(v.size()); - - VERIFY_IS_APPROX(u.template lpNorm(), u.cwise().abs().maxCoeff()); - VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwise().abs().sum()); - VERIFY_IS_APPROX(u.template lpNorm<2>(), ei_sqrt(u.cwise().abs().cwise().square().sum())); - VERIFY_IS_APPROX(ei_pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.cwise().abs().cwise().pow(5).sum()); -} - -void test_eigen2_array() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( array(Matrix()) ); - CALL_SUBTEST_2( array(Matrix2f()) ); - CALL_SUBTEST_3( array(Matrix4d()) ); - CALL_SUBTEST_4( array(MatrixXcf(3, 3)) ); - CALL_SUBTEST_5( array(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( array(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( comparisons(Matrix()) ); - CALL_SUBTEST_2( comparisons(Matrix2f()) ); - CALL_SUBTEST_3( comparisons(Matrix4d()) ); - CALL_SUBTEST_5( comparisons(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( comparisons(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( lpNorm(Matrix()) ); - CALL_SUBTEST_2( lpNorm(Vector2f()) ); - CALL_SUBTEST_3( lpNorm(Vector3d()) ); - CALL_SUBTEST_4( lpNorm(Vector4f()) ); - CALL_SUBTEST_5( lpNorm(VectorXf(16)) ); - CALL_SUBTEST_7( lpNorm(VectorXcd(10)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_basicstuff.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_basicstuff.cpp deleted file mode 100644 index dd2dec1ef..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_basicstuff.cpp +++ /dev/null @@ -1,105 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void basicStuff(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - mzero = MatrixType::Zero(rows, cols), - square = Matrix::Random(rows, rows); - VectorType v1 = VectorType::Random(rows), - vzero = VectorType::Zero(rows); - - Scalar x = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - m1.coeffRef(r,c) = x; - VERIFY_IS_APPROX(x, m1.coeff(r,c)); - m1(r,c) = x; - VERIFY_IS_APPROX(x, m1(r,c)); - v1.coeffRef(r) = x; - VERIFY_IS_APPROX(x, v1.coeff(r)); - v1(r) = x; - VERIFY_IS_APPROX(x, v1(r)); - v1[r] = x; - VERIFY_IS_APPROX(x, v1[r]); - - VERIFY_IS_APPROX( v1, v1); - VERIFY_IS_NOT_APPROX( v1, 2*v1); - VERIFY_IS_MUCH_SMALLER_THAN( vzero, v1); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_MUCH_SMALLER_THAN( vzero, v1.norm()); - VERIFY_IS_NOT_MUCH_SMALLER_THAN(v1, v1); - VERIFY_IS_APPROX( vzero, v1-v1); - VERIFY_IS_APPROX( m1, m1); - VERIFY_IS_NOT_APPROX( m1, 2*m1); - VERIFY_IS_MUCH_SMALLER_THAN( mzero, m1); - VERIFY_IS_NOT_MUCH_SMALLER_THAN(m1, m1); - VERIFY_IS_APPROX( mzero, m1-m1); - - // always test operator() on each read-only expression class, - // in order to check const-qualifiers. - // indeed, if an expression class (here Zero) is meant to be read-only, - // hence has no _write() method, the corresponding MatrixBase method (here zero()) - // should return a const-qualified object so that it is the const-qualified - // operator() that gets called, which in turn calls _read(). - VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows,cols)(r,c), static_cast(1)); - - // now test copying a row-vector into a (column-)vector and conversely. - square.col(r) = square.row(r).eval(); - Matrix rv(rows); - Matrix cv(rows); - rv = square.row(r); - cv = square.col(r); - VERIFY_IS_APPROX(rv, cv.transpose()); - - if(cols!=1 && rows!=1 && MatrixType::SizeAtCompileTime!=Dynamic) - { - VERIFY_RAISES_ASSERT(m1 = (m2.block(0,0, rows-1, cols-1))); - } - - VERIFY_IS_APPROX(m3 = m1,m1); - MatrixType m4; - VERIFY_IS_APPROX(m4 = m1,m1); - - // test swap - m3 = m1; - m1.swap(m2); - VERIFY_IS_APPROX(m3, m2); - if(rows*cols>=3) - { - VERIFY_IS_NOT_APPROX(m3, m1); - } -} - -void test_eigen2_basicstuff() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( basicStuff(Matrix()) ); - CALL_SUBTEST_2( basicStuff(Matrix4d()) ); - CALL_SUBTEST_3( basicStuff(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( basicStuff(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( basicStuff(MatrixXcd(20, 20)) ); - CALL_SUBTEST_6( basicStuff(Matrix()) ); - CALL_SUBTEST_7( basicStuff(Matrix(10,10)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_bug_132.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_bug_132.cpp deleted file mode 100644 index 7fe3610ce..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_bug_132.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2010 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_bug_132() { - int size = 100; - MatrixXd A(size, size); - VectorXd b(size), c(size); - { - VectorXd y = A.transpose() * (b-c); // bug 132: infinite recursion in coeffRef - VectorXd z = (b-c).transpose() * A; // bug 132: infinite recursion in coeffRef - } - - // the following ones weren't failing, but let's include them for completeness: - { - VectorXd y = A * (b-c); - VectorXd z = (b-c).transpose() * A.transpose(); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cholesky.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cholesky.cpp deleted file mode 100644 index 9c4b6f561..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cholesky.cpp +++ /dev/null @@ -1,113 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_ASSERTION_CHECKING -#include "main.h" -#include -#include - -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - -template void cholesky(const MatrixType& m) -{ - /* this test covers the following files: - LLT.h LDLT.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix SquareMatrixType; - typedef Matrix VectorType; - - MatrixType a0 = MatrixType::Random(rows,cols); - VectorType vecB = VectorType::Random(rows), vecX(rows); - MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols); - SquareMatrixType symm = a0 * a0.adjoint(); - // let's make sure the matrix is not singular or near singular - MatrixType a1 = MatrixType::Random(rows,cols); - symm += a1 * a1.adjoint(); - - #ifdef HAS_GSL - if (ei_is_same_type::ret) - { - typedef GslTraits Gsl; - typename Gsl::Matrix gMatA=0, gSymm=0; - typename Gsl::Vector gVecB=0, gVecX=0; - convert(symm, gSymm); - convert(symm, gMatA); - convert(vecB, gVecB); - convert(vecB, gVecX); - Gsl::cholesky(gMatA); - Gsl::cholesky_solve(gMatA, gVecB, gVecX); - VectorType vecX(rows), _vecX, _vecB; - convert(gVecX, _vecX); - symm.llt().solve(vecB, &vecX); - Gsl::prod(gSymm, gVecX, gVecB); - convert(gVecB, _vecB); - // test gsl itself ! - VERIFY_IS_APPROX(vecB, _vecB); - VERIFY_IS_APPROX(vecX, _vecX); - - Gsl::free(gMatA); - Gsl::free(gSymm); - Gsl::free(gVecB); - Gsl::free(gVecX); - } - #endif - - { - LDLT ldlt(symm); - VERIFY(ldlt.isPositiveDefinite()); - // in eigen3, LDLT is pivoting - //VERIFY_IS_APPROX(symm, ldlt.matrixL() * ldlt.vectorD().asDiagonal() * ldlt.matrixL().adjoint()); - ldlt.solve(vecB, &vecX); - VERIFY_IS_APPROX(symm * vecX, vecB); - ldlt.solve(matB, &matX); - VERIFY_IS_APPROX(symm * matX, matB); - } - - { - LLT chol(symm); - VERIFY(chol.isPositiveDefinite()); - VERIFY_IS_APPROX(symm, chol.matrixL() * chol.matrixL().adjoint()); - chol.solve(vecB, &vecX); - VERIFY_IS_APPROX(symm * vecX, vecB); - chol.solve(matB, &matX); - VERIFY_IS_APPROX(symm * matX, matB); - } - -#if 0 // cholesky is not rank-revealing anyway - // test isPositiveDefinite on non definite matrix - if (rows>4) - { - SquareMatrixType symm = a0.block(0,0,rows,cols-4) * a0.block(0,0,rows,cols-4).adjoint(); - LLT chol(symm); - VERIFY(!chol.isPositiveDefinite()); - LDLT cholnosqrt(symm); - VERIFY(!cholnosqrt.isPositiveDefinite()); - } -#endif -} - -void test_eigen2_cholesky() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( cholesky(Matrix()) ); - CALL_SUBTEST_2( cholesky(Matrix2d()) ); - CALL_SUBTEST_3( cholesky(Matrix3f()) ); - CALL_SUBTEST_4( cholesky(Matrix4d()) ); - CALL_SUBTEST_5( cholesky(MatrixXcd(7,7)) ); - CALL_SUBTEST_6( cholesky(MatrixXf(17,17)) ); - CALL_SUBTEST_7( cholesky(MatrixXd(33,33)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_commainitializer.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_commainitializer.cpp deleted file mode 100644 index e0f901e0b..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_commainitializer.cpp +++ /dev/null @@ -1,46 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_commainitializer() -{ - Matrix3d m3; - Matrix4d m4; - - VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8) ); - - #ifndef _MSC_VER - VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10) ); - #endif - - double data[] = {1, 2, 3, 4, 5, 6, 7, 8, 9}; - Matrix3d ref = Map >(data); - - m3 = Matrix3d::Random(); - m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9; - VERIFY_IS_APPROX(m3, ref ); - - Vector3d vec[3]; - vec[0] << 1, 4, 7; - vec[1] << 2, 5, 8; - vec[2] << 3, 6, 9; - m3 = Matrix3d::Random(); - m3 << vec[0], vec[1], vec[2]; - VERIFY_IS_APPROX(m3, ref); - - vec[0] << 1, 2, 3; - vec[1] << 4, 5, 6; - vec[2] << 7, 8, 9; - m3 = Matrix3d::Random(); - m3 << vec[0].transpose(), - 4, 5, 6, - vec[2].transpose(); - VERIFY_IS_APPROX(m3, ref); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cwiseop.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cwiseop.cpp deleted file mode 100644 index a36edd473..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_cwiseop.cpp +++ /dev/null @@ -1,158 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -using namespace std; - -template struct AddIfNull { - const Scalar operator() (const Scalar a, const Scalar b) const {return a<=1e-3 ? b : a;} - enum { Cost = NumTraits::AddCost }; -}; - -template void cwiseops(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - mzero = MatrixType::Zero(rows, cols), - mones = MatrixType::Ones(rows, cols), - identity = Matrix - ::Identity(rows, rows); - VectorType vzero = VectorType::Zero(rows), - vones = VectorType::Ones(rows), - v3(rows); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - Scalar s1 = ei_random(); - - // test Zero, Ones, Constant, and the set* variants - m3 = MatrixType::Constant(rows, cols, s1); - for (int j=0; j >(mones); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().abs2()); - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - VERIFY_IS_APPROX(m1.cwise().pow(3), m1.cwise().cube()); - - VERIFY_IS_APPROX(m1 + mones, m1.cwise()+Scalar(1)); - VERIFY_IS_APPROX(m1 - mones, m1.cwise()-Scalar(1)); - m3 = m1; m3.cwise() += 1; - VERIFY_IS_APPROX(m1 + mones, m3); - m3 = m1; m3.cwise() -= 1; - VERIFY_IS_APPROX(m1 - mones, m3); - - VERIFY_IS_APPROX(m2, m2.cwise() * mones); - VERIFY_IS_APPROX(m1.cwise() * m2, m2.cwise() * m1); - m3 = m1; - m3.cwise() *= m2; - VERIFY_IS_APPROX(m3, m1.cwise() * m2); - - VERIFY_IS_APPROX(mones, m2.cwise()/m2); - if(NumTraits::HasFloatingPoint) - { - VERIFY_IS_APPROX(m1.cwise() / m2, m1.cwise() * (m2.cwise().inverse())); - m3 = m1.cwise().abs().cwise().sqrt(); - VERIFY_IS_APPROX(m3.cwise().square(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().square().cwise().sqrt(), m1.cwise().abs()); - VERIFY_IS_APPROX(m1.cwise().abs().cwise().log().cwise().exp() , m1.cwise().abs()); - - VERIFY_IS_APPROX(m1.cwise().pow(2), m1.cwise().square()); - m3 = (m1.cwise().abs().cwise()<=RealScalar(0.01)).select(mones,m1); - VERIFY_IS_APPROX(m3.cwise().pow(-1), m3.cwise().inverse()); - m3 = m1.cwise().abs(); - VERIFY_IS_APPROX(m3.cwise().pow(RealScalar(0.5)), m3.cwise().sqrt()); - -// VERIFY_IS_APPROX(m1.cwise().tan(), m1.cwise().sin().cwise() / m1.cwise().cos()); - VERIFY_IS_APPROX(mones, m1.cwise().sin().cwise().square() + m1.cwise().cos().cwise().square()); - m3 = m1; - m3.cwise() /= m2; - VERIFY_IS_APPROX(m3, m1.cwise() / m2); - } - - // check min - VERIFY_IS_APPROX( m1.cwise().min(m2), m2.cwise().min(m1) ); - VERIFY_IS_APPROX( m1.cwise().min(m1+mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().min(m1-mones), m1-mones ); - - // check max - VERIFY_IS_APPROX( m1.cwise().max(m2), m2.cwise().max(m1) ); - VERIFY_IS_APPROX( m1.cwise().max(m1-mones), m1 ); - VERIFY_IS_APPROX( m1.cwise().max(m1+mones), m1+mones ); - - VERIFY( (m1.cwise() == m1).all() ); - VERIFY( (m1.cwise() != m2).any() ); - VERIFY(!(m1.cwise() == (m1+mones)).any() ); - if (rows*cols>1) - { - m3 = m1; - m3(r,c) += 1; - VERIFY( (m1.cwise() == m3).any() ); - VERIFY( !(m1.cwise() == m3).all() ); - } - VERIFY( (m1.cwise().min(m2).cwise() <= m2).all() ); - VERIFY( (m1.cwise().max(m2).cwise() >= m2).all() ); - VERIFY( (m1.cwise().min(m2).cwise() < (m1+mones)).all() ); - VERIFY( (m1.cwise().max(m2).cwise() > (m1-mones)).all() ); - -#if(__cplusplus < 201103L) -// std::binder* are deprecated since c++11 and will be removed in c++17 - VERIFY( (m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()(), Scalar(1)))).all() ); - VERIFY( !(m1.cwise()>m1.unaryExpr(bind2nd(plus(), Scalar(1)))).any() ); -#endif -} - -void test_eigen2_cwiseop() -{ - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( cwiseops(Matrix()) ); - CALL_SUBTEST_2( cwiseops(Matrix4d()) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(3, 3)) ); - CALL_SUBTEST_3( cwiseops(MatrixXf(22, 22)) ); - CALL_SUBTEST_4( cwiseops(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( cwiseops(MatrixXd(20, 20)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_determinant.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_determinant.cpp deleted file mode 100644 index c7b4ad053..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_determinant.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void determinant(const MatrixType& m) -{ - /* this test covers the following files: - Determinant.h - */ - int size = m.rows(); - - MatrixType m1(size, size), m2(size, size); - m1.setRandom(); - m2.setRandom(); - typedef typename MatrixType::Scalar Scalar; - Scalar x = ei_random(); - VERIFY_IS_APPROX(MatrixType::Identity(size, size).determinant(), Scalar(1)); - VERIFY_IS_APPROX((m1*m2).determinant(), m1.determinant() * m2.determinant()); - if(size==1) return; - int i = ei_random(0, size-1); - int j; - do { - j = ei_random(0, size-1); - } while(j==i); - m2 = m1; - m2.row(i).swap(m2.row(j)); - VERIFY_IS_APPROX(m2.determinant(), -m1.determinant()); - m2 = m1; - m2.col(i).swap(m2.col(j)); - VERIFY_IS_APPROX(m2.determinant(), -m1.determinant()); - VERIFY_IS_APPROX(m2.determinant(), m2.transpose().determinant()); - VERIFY_IS_APPROX(ei_conj(m2.determinant()), m2.adjoint().determinant()); - m2 = m1; - m2.row(i) += x*m2.row(j); - VERIFY_IS_APPROX(m2.determinant(), m1.determinant()); - m2 = m1; - m2.row(i) *= x; - VERIFY_IS_APPROX(m2.determinant(), m1.determinant() * x); -} - -void test_eigen2_determinant() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( determinant(Matrix()) ); - CALL_SUBTEST_2( determinant(Matrix()) ); - CALL_SUBTEST_3( determinant(Matrix()) ); - CALL_SUBTEST_4( determinant(Matrix()) ); - CALL_SUBTEST_5( determinant(Matrix, 10, 10>()) ); - CALL_SUBTEST_6( determinant(MatrixXd(20, 20)) ); - } - CALL_SUBTEST_6( determinant(MatrixXd(200, 200)) ); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_dynalloc.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_dynalloc.cpp deleted file mode 100644 index 1891a9e33..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_dynalloc.cpp +++ /dev/null @@ -1,131 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -#if EIGEN_ARCH_WANTS_ALIGNMENT -#define ALIGNMENT 16 -#else -#define ALIGNMENT 1 -#endif - -void check_handmade_aligned_malloc() -{ - for(int i = 1; i < 1000; i++) - { - char *p = (char*)ei_handmade_aligned_malloc(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_handmade_aligned_free(p); - } -} - -void check_aligned_malloc() -{ - for(int i = 1; i < 1000; i++) - { - char *p = (char*)ei_aligned_malloc(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_aligned_free(p); - } -} - -void check_aligned_new() -{ - for(int i = 1; i < 1000; i++) - { - float *p = ei_aligned_new(i); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - ei_aligned_delete(p,i); - } -} - -void check_aligned_stack_alloc() -{ - for(int i = 1; i < 1000; i++) - { - ei_declare_aligned_stack_constructed_variable(float, p, i, 0); - VERIFY(std::size_t(p)%ALIGNMENT==0); - // if the buffer is wrongly allocated this will give a bad write --> check with valgrind - for(int j = 0; j < i; j++) p[j]=0; - } -} - - -// test compilation with both a struct and a class... -struct MyStruct -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - char dummychar; - Vector4f avec; -}; - -class MyClassA -{ - public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - char dummychar; - Vector4f avec; -}; - -template void check_dynaligned() -{ - T* obj = new T; - VERIFY(std::size_t(obj)%ALIGNMENT==0); - delete obj; -} - -void test_eigen2_dynalloc() -{ - // low level dynamic memory allocation - CALL_SUBTEST(check_handmade_aligned_malloc()); - CALL_SUBTEST(check_aligned_malloc()); - CALL_SUBTEST(check_aligned_new()); - CALL_SUBTEST(check_aligned_stack_alloc()); - - for (int i=0; i() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - CALL_SUBTEST( check_dynaligned() ); - } - - // check static allocation, who knows ? - { - MyStruct foo0; VERIFY(std::size_t(foo0.avec.data())%ALIGNMENT==0); - MyClassA fooA; VERIFY(std::size_t(fooA.avec.data())%ALIGNMENT==0); - } - - // dynamic allocation, single object - for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA(); VERIFY(std::size_t(fooA->avec.data())%ALIGNMENT==0); - delete foo0; - delete fooA; - } - - // dynamic allocation, array - const int N = 10; - for (int i=0; iavec.data())%ALIGNMENT==0); - MyClassA *fooA = new MyClassA[N]; VERIFY(std::size_t(fooA->avec.data())%ALIGNMENT==0); - delete[] foo0; - delete[] fooA; - } - -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_eigensolver.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_eigensolver.cpp deleted file mode 100644 index 48b4ace43..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_eigensolver.cpp +++ /dev/null @@ -1,146 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -#ifdef HAS_GSL -#include "gsl_helper.h" -#endif - -template void selfadjointeigensolver(const MatrixType& m) -{ - /* this test covers the following files: - EigenSolver.h, SelfAdjointEigenSolver.h (and indirectly: Tridiagonalization.h) - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix RealVectorType; - typedef typename std::complex::Real> Complex; - - RealScalar largerEps = 10*test_precision(); - - MatrixType a = MatrixType::Random(rows,cols); - MatrixType a1 = MatrixType::Random(rows,cols); - MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; - - MatrixType b = MatrixType::Random(rows,cols); - MatrixType b1 = MatrixType::Random(rows,cols); - MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1; - - SelfAdjointEigenSolver eiSymm(symmA); - // generalized eigen pb - SelfAdjointEigenSolver eiSymmGen(symmA, symmB); - - #ifdef HAS_GSL - if (ei_is_same_type::ret) - { - typedef GslTraits Gsl; - typename Gsl::Matrix gEvec=0, gSymmA=0, gSymmB=0; - typename GslTraits::Vector gEval=0; - RealVectorType _eval; - MatrixType _evec; - convert(symmA, gSymmA); - convert(symmB, gSymmB); - convert(symmA, gEvec); - gEval = GslTraits::createVector(rows); - - Gsl::eigen_symm(gSymmA, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - - // test gsl itself ! - VERIFY((symmA * _evec).isApprox(_evec * _eval.asDiagonal(), largerEps)); - - // compare with eigen - VERIFY_IS_APPROX(_eval, eiSymm.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwise().abs(), eiSymm.eigenvectors().cwise().abs()); - - // generalized pb - Gsl::eigen_symm_gen(gSymmA, gSymmB, gEval, gEvec); - convert(gEval, _eval); - convert(gEvec, _evec); - // test GSL itself: - VERIFY((symmA * _evec).isApprox(symmB * (_evec * _eval.asDiagonal()), largerEps)); - - // compare with eigen - MatrixType normalized_eivec = eiSymmGen.eigenvectors()*eiSymmGen.eigenvectors().colwise().norm().asDiagonal().inverse(); - VERIFY_IS_APPROX(_eval, eiSymmGen.eigenvalues()); - VERIFY_IS_APPROX(_evec.cwiseAbs(), normalized_eivec.cwiseAbs()); - - Gsl::free(gSymmA); - Gsl::free(gSymmB); - GslTraits::free(gEval); - Gsl::free(gEvec); - } - #endif - - VERIFY((symmA * eiSymm.eigenvectors()).isApprox( - eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal(), largerEps)); - - // generalized eigen problem Ax = lBx - VERIFY((symmA * eiSymmGen.eigenvectors()).isApprox( - symmB * (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps)); - - MatrixType sqrtSymmA = eiSymm.operatorSqrt(); - VERIFY_IS_APPROX(symmA, sqrtSymmA*sqrtSymmA); - VERIFY_IS_APPROX(sqrtSymmA, symmA*eiSymm.operatorInverseSqrt()); -} - -template void eigensolver(const MatrixType& m) -{ - /* this test covers the following files: - EigenSolver.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix RealVectorType; - typedef typename std::complex::Real> Complex; - - // RealScalar largerEps = 10*test_precision(); - - MatrixType a = MatrixType::Random(rows,cols); - MatrixType a1 = MatrixType::Random(rows,cols); - MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; - - EigenSolver ei0(symmA); - VERIFY_IS_APPROX(symmA * ei0.pseudoEigenvectors(), ei0.pseudoEigenvectors() * ei0.pseudoEigenvalueMatrix()); - VERIFY_IS_APPROX((symmA.template cast()) * (ei0.pseudoEigenvectors().template cast()), - (ei0.pseudoEigenvectors().template cast()) * (ei0.eigenvalues().asDiagonal())); - - EigenSolver ei1(a); - VERIFY_IS_APPROX(a * ei1.pseudoEigenvectors(), ei1.pseudoEigenvectors() * ei1.pseudoEigenvalueMatrix()); - VERIFY_IS_APPROX(a.template cast() * ei1.eigenvectors(), - ei1.eigenvectors() * ei1.eigenvalues().asDiagonal()); - -} - -void test_eigen2_eigensolver() -{ - for(int i = 0; i < g_repeat; i++) { - // very important to test a 3x3 matrix since we provide a special path for it - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3f()) ); - CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) ); - CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(7,7)) ); - CALL_SUBTEST_4( selfadjointeigensolver(MatrixXcd(5,5)) ); - CALL_SUBTEST_5( selfadjointeigensolver(MatrixXd(19,19)) ); - - CALL_SUBTEST_6( eigensolver(Matrix4f()) ); - CALL_SUBTEST_5( eigensolver(MatrixXd(17,17)) ); - } -} - diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_first_aligned.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_first_aligned.cpp deleted file mode 100644 index 51bb3cad1..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_first_aligned.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template -void test_eigen2_first_aligned_helper(Scalar *array, int size) -{ - const int packet_size = sizeof(Scalar) * ei_packet_traits::size; - VERIFY(((std::size_t(array) + sizeof(Scalar) * ei_alignmentOffset(array, size)) % packet_size) == 0); -} - -template -void test_eigen2_none_aligned_helper(Scalar *array, int size) -{ - VERIFY(ei_packet_traits::size == 1 || ei_alignmentOffset(array, size) == size); -} - -struct some_non_vectorizable_type { float x; }; - -void test_eigen2_first_aligned() -{ - EIGEN_ALIGN_128 float array_float[100]; - test_first_aligned_helper(array_float, 50); - test_first_aligned_helper(array_float+1, 50); - test_first_aligned_helper(array_float+2, 50); - test_first_aligned_helper(array_float+3, 50); - test_first_aligned_helper(array_float+4, 50); - test_first_aligned_helper(array_float+5, 50); - - EIGEN_ALIGN_128 double array_double[100]; - test_first_aligned_helper(array_double, 50); - test_first_aligned_helper(array_double+1, 50); - test_first_aligned_helper(array_double+2, 50); - - double *array_double_plus_4_bytes = (double*)(std::size_t(array_double)+4); - test_none_aligned_helper(array_double_plus_4_bytes, 50); - test_none_aligned_helper(array_double_plus_4_bytes+1, 50); - - some_non_vectorizable_type array_nonvec[100]; - test_first_aligned_helper(array_nonvec, 100); - test_none_aligned_helper(array_nonvec, 100); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry.cpp deleted file mode 100644 index 514040774..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry.cpp +++ /dev/null @@ -1,432 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void geometry(void) -{ - /* this test covers the following files: - Cross.h Quaternion.h, Transform.cpp - */ - - typedef Matrix Matrix2; - typedef Matrix Matrix3; - typedef Matrix Matrix4; - typedef Matrix Vector2; - typedef Matrix Vector3; - typedef Matrix Vector4; - typedef Quaternion Quaternionx; - typedef AngleAxis AngleAxisx; - typedef Transform Transform2; - typedef Transform Transform3; - typedef Scaling Scaling2; - typedef Scaling Scaling3; - typedef Translation Translation2; - typedef Translation Translation3; - - Scalar largeEps = test_precision(); - if (ei_is_same_type::ret) - largeEps = 1e-2f; - - Vector3 v0 = Vector3::Random(), - v1 = Vector3::Random(), - v2 = Vector3::Random(); - Vector2 u0 = Vector2::Random(); - Matrix3 matrot1; - - Scalar a = ei_random(-Scalar(M_PI), Scalar(M_PI)); - - // cross product - VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).eigen2_dot(v1), Scalar(1)); - Matrix3 m; - m << v0.normalized(), - (v0.cross(v1)).normalized(), - (v0.cross(v1).cross(v0)).normalized(); - VERIFY(m.isUnitary()); - - // Quaternion: Identity(), setIdentity(); - Quaternionx q1, q2; - q2.setIdentity(); - VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs()); - q1.coeffs().setRandom(); - VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs()); - - // unitOrthogonal - VERIFY_IS_MUCH_SMALLER_THAN(u0.unitOrthogonal().eigen2_dot(u0), Scalar(1)); - VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().eigen2_dot(v0), Scalar(1)); - VERIFY_IS_APPROX(u0.unitOrthogonal().norm(), Scalar(1)); - VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), Scalar(1)); - - - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); - VERIFY_IS_APPROX(ei_cos(a)*v0.squaredNorm(), v0.eigen2_dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); - m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint(); - VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized())); - VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m); - - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(a, v1.normalized()); - - // angular distance - Scalar refangle = ei_abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; - - if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) - { - VERIFY(ei_isApprox(q1.angularDistance(q2), refangle, largeEps)); - } - - // rotation matrix conversion - VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2); - VERIFY_IS_APPROX(q1 * q2 * v2, - q1.toRotationMatrix() * q2.toRotationMatrix() * v2); - - VERIFY( (q2*q1).isApprox(q1*q2, largeEps) || !(q2 * q1 * v2).isApprox( - q1.toRotationMatrix() * q2.toRotationMatrix() * v2)); - - q2 = q1.toRotationMatrix(); - VERIFY_IS_APPROX(q1*v1,q2*v1); - - matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX()) - * AngleAxisx(Scalar(0.2), Vector3::UnitY()) - * AngleAxisx(Scalar(0.3), Vector3::UnitZ()); - VERIFY_IS_APPROX(matrot1 * v1, - AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1))); - - // angle-axis conversion - AngleAxisx aa = q1; - VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); - - // from two vector creation - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - - // inverse and conjugate - VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1); - VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1); - - // AngleAxis - VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(), - Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix()); - - AngleAxisx aa1; - m = q1.toRotationMatrix(); - aa1 = m; - VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(), - Quaternionx(m).toRotationMatrix()); - - // Transform - // TODO complete the tests ! - a = 0; - while (ei_abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); - q1 = AngleAxisx(a, v0.normalized()); - Transform3 t0, t1, t2; - // first test setIdentity() and Identity() - t0.setIdentity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - t0.matrix().setZero(); - t0 = Transform3::Identity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - - t0.linear() = q1.toRotationMatrix(); - t1.setIdentity(); - t1.linear() = q1.toRotationMatrix(); - - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); - t0.scale(v0); - t1.prescale(v0); - - VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).norm(), v0.x()); - //VERIFY(!ei_isApprox((t1 * Vector3(1,0,0)).norm(), v0.x())); - - t0.setIdentity(); - t1.setIdentity(); - v1 << 1, 2, 3; - t0.linear() = q1.toRotationMatrix(); - t0.pretranslate(v0); - t0.scale(v1); - t1.linear() = q1.conjugate().toRotationMatrix(); - t1.prescale(v1.cwise().inverse()); - t1.translate(-v0); - - VERIFY((t0.matrix() * t1.matrix()).isIdentity(test_precision())); - - t1.fromPositionOrientationScale(v0, q1, v1); - VERIFY_IS_APPROX(t1.matrix(), t0.matrix()); - VERIFY_IS_APPROX(t1*v1, t0*v1); - - t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix()); - t1.setIdentity(); t1.scale(v0).rotate(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix()); - VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix()); - - // More transform constructors, operator=, operator*= - - Matrix3 mat3 = Matrix3::Random(); - Matrix4 mat4; - mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose(); - Transform3 tmat3(mat3), tmat4(mat4); - tmat4.matrix()(3,3) = Scalar(1); - VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - - Scalar a3 = ei_random(-Scalar(M_PI), Scalar(M_PI)); - Vector3 v3 = Vector3::Random().normalized(); - AngleAxisx aa3(a3, v3); - Transform3 t3(aa3); - Transform3 t4; - t4 = aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - t4.rotate(AngleAxisx(-a3,v3)); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - - v3 = Vector3::Random(); - Translation3 tv3(v3); - Transform3 t5(tv3); - t4 = tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - - Scaling3 sv3(v3); - Transform3 t6(sv3); - t4 = sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - t4.scale(v3.cwise().inverse()); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - - // matrix * transform - VERIFY_IS_APPROX(Transform3(t3.matrix()*t4).matrix(), Transform3(t3*t4).matrix()); - - // chained Transform product - VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix()); - - // check that Transform product doesn't have aliasing problems - t5 = t4; - t5 = t5*t5; - VERIFY_IS_APPROX(t5, t4*t4); - - // 2D transformation - Transform2 t20, t21; - Vector2 v20 = Vector2::Random(); - Vector2 v21 = Vector2::Random(); - for (int k=0; k<2; ++k) - if (ei_abs(v21[k])(a).toRotationMatrix(); - VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(), - t21.pretranslate(v20).scale(v21).matrix()); - - t21.setIdentity(); - t21.linear() = Rotation2D(-a).toRotationMatrix(); - VERIFY( (t20.fromPositionOrientationScale(v20,a,v21) - * (t21.prescale(v21.cwise().inverse()).translate(-v20))).matrix().isIdentity(test_precision()) ); - - // Transform - new API - // 3D - t0.setIdentity(); - t0.rotate(q1).scale(v0).translate(v0); - // mat * scaling and mat * translation - t1 = (Matrix3(q1) * Scaling3(v0)) * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // mat * transformation and scaling * translation - t1 = Matrix3(q1) * (Scaling3(v0) * Translation3(v0)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.prerotate(q1).prescale(v0).pretranslate(v0); - // translation * scaling and transformation * mat - t1 = (Translation3(v0) * Scaling3(v0)) * Matrix3(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // scaling * mat and translation * mat - t1 = Translation3(v0) * (Scaling3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.scale(v0).translate(v0).rotate(q1); - // translation * mat and scaling * transformation - t1 = Scaling3(v0) * (Translation3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * scaling - t0.scale(v0); - t1 = t1 * Scaling3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * translation - t0.translate(v0); - t1 = t1 * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // translation * transformation - t0.pretranslate(v0); - t1 = Translation3(v0) * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // transform * quaternion - t0.rotate(q1); - t1 = t1 * q1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * quaternion - t0.translate(v1).rotate(q1); - t1 = t1 * (Translation3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // scaling * quaternion - t0.scale(v1).rotate(q1); - t1 = t1 * (Scaling3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * transform - t0.prerotate(q1); - t1 = q1 * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * translation - t0.rotate(q1).translate(v1); - t1 = t1 * (q1 * Translation3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * scaling - t0.rotate(q1).scale(v1); - t1 = t1 * (q1 * Scaling3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * vector - t0.setIdentity(); - t0.translate(v0); - VERIFY_IS_APPROX(t0 * v1, Translation3(v0) * v1); - - // scaling * vector - t0.setIdentity(); - t0.scale(v0); - VERIFY_IS_APPROX(t0 * v1, Scaling3(v0) * v1); - - // test transform inversion - t0.setIdentity(); - t0.translate(v0); - t0.linear().setRandom(); - VERIFY_IS_APPROX(t0.inverse(Affine), t0.matrix().inverse()); - t0.setIdentity(); - t0.translate(v0).rotate(q1); - VERIFY_IS_APPROX(t0.inverse(Isometry), t0.matrix().inverse()); - - // test extract rotation and scaling - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - VERIFY_IS_APPROX(t0.rotation() * v1, Matrix3(q1) * v1); - - Matrix3 mat_rotation, mat_scaling; - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - t0.computeRotationScaling(&mat_rotation, &mat_scaling); - VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - t0.computeScalingRotation(&mat_scaling, &mat_rotation); - VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - - // test casting - Transform t1f = t1.template cast(); - VERIFY_IS_APPROX(t1f.template cast(),t1); - Transform t1d = t1.template cast(); - VERIFY_IS_APPROX(t1d.template cast(),t1); - - Translation3 tr1(v0); - Translation tr1f = tr1.template cast(); - VERIFY_IS_APPROX(tr1f.template cast(),tr1); - Translation tr1d = tr1.template cast(); - VERIFY_IS_APPROX(tr1d.template cast(),tr1); - - Scaling3 sc1(v0); - Scaling sc1f = sc1.template cast(); - VERIFY_IS_APPROX(sc1f.template cast(),sc1); - Scaling sc1d = sc1.template cast(); - VERIFY_IS_APPROX(sc1d.template cast(),sc1); - - Quaternion q1f = q1.template cast(); - VERIFY_IS_APPROX(q1f.template cast(),q1); - Quaternion q1d = q1.template cast(); - VERIFY_IS_APPROX(q1d.template cast(),q1); - - AngleAxis aa1f = aa1.template cast(); - VERIFY_IS_APPROX(aa1f.template cast(),aa1); - AngleAxis aa1d = aa1.template cast(); - VERIFY_IS_APPROX(aa1d.template cast(),aa1); - - Rotation2D r2d1(ei_random()); - Rotation2D r2d1f = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); - Rotation2D r2d1d = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - m = q1; -// m.col(1) = Vector3(0,ei_random(),ei_random()).normalized(); -// m.col(0) = Vector3(-1,0,0).normalized(); -// m.col(2) = m.col(0).cross(m.col(1)); - #define VERIFY_EULER(I,J,K, X,Y,Z) { \ - Vector3 ea = m.eulerAngles(I,J,K); \ - Matrix3 m1 = Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z())); \ - VERIFY_IS_APPROX(m, m1); \ - VERIFY_IS_APPROX(m, Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z()))); \ - } - VERIFY_EULER(0,1,2, X,Y,Z); - VERIFY_EULER(0,1,0, X,Y,X); - VERIFY_EULER(0,2,1, X,Z,Y); - VERIFY_EULER(0,2,0, X,Z,X); - - VERIFY_EULER(1,2,0, Y,Z,X); - VERIFY_EULER(1,2,1, Y,Z,Y); - VERIFY_EULER(1,0,2, Y,X,Z); - VERIFY_EULER(1,0,1, Y,X,Y); - - VERIFY_EULER(2,0,1, Z,X,Y); - VERIFY_EULER(2,0,2, Z,X,Z); - VERIFY_EULER(2,1,0, Z,Y,X); - VERIFY_EULER(2,1,2, Z,Y,Z); - - // colwise/rowwise cross product - mat3.setRandom(); - Vector3 vec3 = Vector3::Random(); - Matrix3 mcross; - int i = ei_random(0,2); - mcross = mat3.colwise().cross(vec3); - VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); - mcross = mat3.rowwise().cross(vec3); - VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); - - -} - -void test_eigen2_geometry() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( geometry() ); - CALL_SUBTEST_2( geometry() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp deleted file mode 100644 index 12d4a71c3..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp +++ /dev/null @@ -1,435 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN2_SUPPORT_STAGE15_RESOLVE_API_CONFLICTS_WARN - -#include "main.h" -#include -#include -#include - -template void geometry(void) -{ - /* this test covers the following files: - Cross.h Quaternion.h, Transform.cpp - */ - - typedef Matrix Matrix2; - typedef Matrix Matrix3; - typedef Matrix Matrix4; - typedef Matrix Vector2; - typedef Matrix Vector3; - typedef Matrix Vector4; - typedef eigen2_Quaternion Quaternionx; - typedef eigen2_AngleAxis AngleAxisx; - typedef eigen2_Transform Transform2; - typedef eigen2_Transform Transform3; - typedef eigen2_Scaling Scaling2; - typedef eigen2_Scaling Scaling3; - typedef eigen2_Translation Translation2; - typedef eigen2_Translation Translation3; - - Scalar largeEps = test_precision(); - if (ei_is_same_type::ret) - largeEps = 1e-2f; - - Vector3 v0 = Vector3::Random(), - v1 = Vector3::Random(), - v2 = Vector3::Random(); - Vector2 u0 = Vector2::Random(); - Matrix3 matrot1; - - Scalar a = ei_random(-Scalar(M_PI), Scalar(M_PI)); - - // cross product - VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).eigen2_dot(v1), Scalar(1)); - Matrix3 m; - m << v0.normalized(), - (v0.cross(v1)).normalized(), - (v0.cross(v1).cross(v0)).normalized(); - VERIFY(m.isUnitary()); - - // Quaternion: Identity(), setIdentity(); - Quaternionx q1, q2; - q2.setIdentity(); - VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs()); - q1.coeffs().setRandom(); - VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs()); - - // unitOrthogonal - VERIFY_IS_MUCH_SMALLER_THAN(u0.unitOrthogonal().eigen2_dot(u0), Scalar(1)); - VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().eigen2_dot(v0), Scalar(1)); - VERIFY_IS_APPROX(u0.unitOrthogonal().norm(), Scalar(1)); - VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), Scalar(1)); - - - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); - VERIFY_IS_APPROX(ei_cos(a)*v0.squaredNorm(), v0.eigen2_dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); - m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint(); - VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized())); - VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m); - - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(a, v1.normalized()); - - // angular distance - Scalar refangle = ei_abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; - - if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) - { - VERIFY(ei_isApprox(q1.angularDistance(q2), refangle, largeEps)); - } - - // rotation matrix conversion - VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2); - VERIFY_IS_APPROX(q1 * q2 * v2, - q1.toRotationMatrix() * q2.toRotationMatrix() * v2); - - VERIFY( (q2*q1).isApprox(q1*q2, largeEps) || !(q2 * q1 * v2).isApprox( - q1.toRotationMatrix() * q2.toRotationMatrix() * v2)); - - q2 = q1.toRotationMatrix(); - VERIFY_IS_APPROX(q1*v1,q2*v1); - - matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX()) - * AngleAxisx(Scalar(0.2), Vector3::UnitY()) - * AngleAxisx(Scalar(0.3), Vector3::UnitZ()); - VERIFY_IS_APPROX(matrot1 * v1, - AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix() - * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1))); - - // angle-axis conversion - AngleAxisx aa = q1; - VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); - - // from two vector creation - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - VERIFY_IS_APPROX(v2.normalized(),(q2.setFromTwoVectors(v1,v2)*v1).normalized()); - - // inverse and conjugate - VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1); - VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1); - - // AngleAxis - VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(), - Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix()); - - AngleAxisx aa1; - m = q1.toRotationMatrix(); - aa1 = m; - VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(), - Quaternionx(m).toRotationMatrix()); - - // Transform - // TODO complete the tests ! - a = 0; - while (ei_abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); - q1 = AngleAxisx(a, v0.normalized()); - Transform3 t0, t1, t2; - // first test setIdentity() and Identity() - t0.setIdentity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - t0.matrix().setZero(); - t0 = Transform3::Identity(); - VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity()); - - t0.linear() = q1.toRotationMatrix(); - t1.setIdentity(); - t1.linear() = q1.toRotationMatrix(); - - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); - t0.scale(v0); - t1.prescale(v0); - - VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).norm(), v0.x()); - //VERIFY(!ei_isApprox((t1 * Vector3(1,0,0)).norm(), v0.x())); - - t0.setIdentity(); - t1.setIdentity(); - v1 << 1, 2, 3; - t0.linear() = q1.toRotationMatrix(); - t0.pretranslate(v0); - t0.scale(v1); - t1.linear() = q1.conjugate().toRotationMatrix(); - t1.prescale(v1.cwise().inverse()); - t1.translate(-v0); - - VERIFY((t0.matrix() * t1.matrix()).isIdentity(test_precision())); - - t1.fromPositionOrientationScale(v0, q1, v1); - VERIFY_IS_APPROX(t1.matrix(), t0.matrix()); - VERIFY_IS_APPROX(t1*v1, t0*v1); - - t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix()); - t1.setIdentity(); t1.scale(v0).rotate(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix()); - VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix()); - - // More transform constructors, operator=, operator*= - - Matrix3 mat3 = Matrix3::Random(); - Matrix4 mat4; - mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose(); - Transform3 tmat3(mat3), tmat4(mat4); - tmat4.matrix()(3,3) = Scalar(1); - VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - - Scalar a3 = ei_random(-Scalar(M_PI), Scalar(M_PI)); - Vector3 v3 = Vector3::Random().normalized(); - AngleAxisx aa3(a3, v3); - Transform3 t3(aa3); - Transform3 t4; - t4 = aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - t4.rotate(AngleAxisx(-a3,v3)); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= aa3; - VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - - v3 = Vector3::Random(); - Translation3 tv3(v3); - Transform3 t5(tv3); - t4 = tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= tv3; - VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - - Scaling3 sv3(v3); - Transform3 t6(sv3); - t4 = sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - t4.scale(v3.cwise().inverse()); - VERIFY_IS_APPROX(t4.matrix(), Matrix4::Identity()); - t4 *= sv3; - VERIFY_IS_APPROX(t6.matrix(), t4.matrix()); - - // matrix * transform - VERIFY_IS_APPROX(Transform3(t3.matrix()*t4).matrix(), Transform3(t3*t4).matrix()); - - // chained Transform product - VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix()); - - // check that Transform product doesn't have aliasing problems - t5 = t4; - t5 = t5*t5; - VERIFY_IS_APPROX(t5, t4*t4); - - // 2D transformation - Transform2 t20, t21; - Vector2 v20 = Vector2::Random(); - Vector2 v21 = Vector2::Random(); - for (int k=0; k<2; ++k) - if (ei_abs(v21[k])(a).toRotationMatrix(); - VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(), - t21.pretranslate(v20).scale(v21).matrix()); - - t21.setIdentity(); - t21.linear() = Rotation2D(-a).toRotationMatrix(); - VERIFY( (t20.fromPositionOrientationScale(v20,a,v21) - * (t21.prescale(v21.cwise().inverse()).translate(-v20))).matrix().isIdentity(test_precision()) ); - - // Transform - new API - // 3D - t0.setIdentity(); - t0.rotate(q1).scale(v0).translate(v0); - // mat * scaling and mat * translation - t1 = (Matrix3(q1) * Scaling3(v0)) * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // mat * transformation and scaling * translation - t1 = Matrix3(q1) * (Scaling3(v0) * Translation3(v0)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.prerotate(q1).prescale(v0).pretranslate(v0); - // translation * scaling and transformation * mat - t1 = (Translation3(v0) * Scaling3(v0)) * Matrix3(q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // scaling * mat and translation * mat - t1 = Translation3(v0) * (Scaling3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - t0.setIdentity(); - t0.scale(v0).translate(v0).rotate(q1); - // translation * mat and scaling * transformation - t1 = Scaling3(v0) * (Translation3(v0) * Matrix3(q1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * scaling - t0.scale(v0); - t1 = t1 * Scaling3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // transformation * translation - t0.translate(v0); - t1 = t1 * Translation3(v0); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - // translation * transformation - t0.pretranslate(v0); - t1 = Translation3(v0) * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // transform * quaternion - t0.rotate(q1); - t1 = t1 * q1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * quaternion - t0.translate(v1).rotate(q1); - t1 = t1 * (Translation3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // scaling * quaternion - t0.scale(v1).rotate(q1); - t1 = t1 * (Scaling3(v1) * q1); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * transform - t0.prerotate(q1); - t1 = q1 * t1; - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * translation - t0.rotate(q1).translate(v1); - t1 = t1 * (q1 * Translation3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // quaternion * scaling - t0.rotate(q1).scale(v1); - t1 = t1 * (q1 * Scaling3(v1)); - VERIFY_IS_APPROX(t0.matrix(), t1.matrix()); - - // translation * vector - t0.setIdentity(); - t0.translate(v0); - VERIFY_IS_APPROX(t0 * v1, Translation3(v0) * v1); - - // scaling * vector - t0.setIdentity(); - t0.scale(v0); - VERIFY_IS_APPROX(t0 * v1, Scaling3(v0) * v1); - - // test transform inversion - t0.setIdentity(); - t0.translate(v0); - t0.linear().setRandom(); - VERIFY_IS_APPROX(t0.inverse(Affine), t0.matrix().inverse()); - t0.setIdentity(); - t0.translate(v0).rotate(q1); - VERIFY_IS_APPROX(t0.inverse(Isometry), t0.matrix().inverse()); - - // test extract rotation and scaling - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - VERIFY_IS_APPROX(t0.rotation() * v1, Matrix3(q1) * v1); - - Matrix3 mat_rotation, mat_scaling; - t0.setIdentity(); - t0.translate(v0).rotate(q1).scale(v1); - t0.computeRotationScaling(&mat_rotation, &mat_scaling); - VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - t0.computeScalingRotation(&mat_scaling, &mat_rotation); - VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation); - VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity()); - VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1)); - - // test casting - eigen2_Transform t1f = t1.template cast(); - VERIFY_IS_APPROX(t1f.template cast(),t1); - eigen2_Transform t1d = t1.template cast(); - VERIFY_IS_APPROX(t1d.template cast(),t1); - - Translation3 tr1(v0); - eigen2_Translation tr1f = tr1.template cast(); - VERIFY_IS_APPROX(tr1f.template cast(),tr1); - eigen2_Translation tr1d = tr1.template cast(); - VERIFY_IS_APPROX(tr1d.template cast(),tr1); - - Scaling3 sc1(v0); - eigen2_Scaling sc1f = sc1.template cast(); - VERIFY_IS_APPROX(sc1f.template cast(),sc1); - eigen2_Scaling sc1d = sc1.template cast(); - VERIFY_IS_APPROX(sc1d.template cast(),sc1); - - eigen2_Quaternion q1f = q1.template cast(); - VERIFY_IS_APPROX(q1f.template cast(),q1); - eigen2_Quaternion q1d = q1.template cast(); - VERIFY_IS_APPROX(q1d.template cast(),q1); - - eigen2_AngleAxis aa1f = aa1.template cast(); - VERIFY_IS_APPROX(aa1f.template cast(),aa1); - eigen2_AngleAxis aa1d = aa1.template cast(); - VERIFY_IS_APPROX(aa1d.template cast(),aa1); - - eigen2_Rotation2D r2d1(ei_random()); - eigen2_Rotation2D r2d1f = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); - eigen2_Rotation2D r2d1d = r2d1.template cast(); - VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - m = q1; -// m.col(1) = Vector3(0,ei_random(),ei_random()).normalized(); -// m.col(0) = Vector3(-1,0,0).normalized(); -// m.col(2) = m.col(0).cross(m.col(1)); - #define VERIFY_EULER(I,J,K, X,Y,Z) { \ - Vector3 ea = m.eulerAngles(I,J,K); \ - Matrix3 m1 = Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z())); \ - VERIFY_IS_APPROX(m, m1); \ - VERIFY_IS_APPROX(m, Matrix3(AngleAxisx(ea[0], Vector3::Unit##X()) * AngleAxisx(ea[1], Vector3::Unit##Y()) * AngleAxisx(ea[2], Vector3::Unit##Z()))); \ - } - VERIFY_EULER(0,1,2, X,Y,Z); - VERIFY_EULER(0,1,0, X,Y,X); - VERIFY_EULER(0,2,1, X,Z,Y); - VERIFY_EULER(0,2,0, X,Z,X); - - VERIFY_EULER(1,2,0, Y,Z,X); - VERIFY_EULER(1,2,1, Y,Z,Y); - VERIFY_EULER(1,0,2, Y,X,Z); - VERIFY_EULER(1,0,1, Y,X,Y); - - VERIFY_EULER(2,0,1, Z,X,Y); - VERIFY_EULER(2,0,2, Z,X,Z); - VERIFY_EULER(2,1,0, Z,Y,X); - VERIFY_EULER(2,1,2, Z,Y,Z); - - // colwise/rowwise cross product - mat3.setRandom(); - Vector3 vec3 = Vector3::Random(); - Matrix3 mcross; - int i = ei_random(0,2); - mcross = mat3.colwise().cross(vec3); - VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); - mcross = mat3.rowwise().cross(vec3); - VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); - - -} - -void test_eigen2_geometry_with_eigen2_prefix() -{ - std::cout << "eigen2 support: " << EIGEN2_SUPPORT_STAGE << std::endl; - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( geometry() ); - CALL_SUBTEST_2( geometry() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_hyperplane.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_hyperplane.cpp deleted file mode 100644 index f3f85e14d..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_hyperplane.cpp +++ /dev/null @@ -1,126 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void hyperplane(const HyperplaneType& _plane) -{ - /* this test covers the following files: - Hyperplane.h - */ - - const int dim = _plane.dim(); - typedef typename HyperplaneType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix MatrixType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - - VectorType n0 = VectorType::Random(dim).normalized(); - VectorType n1 = VectorType::Random(dim).normalized(); - - HyperplaneType pl0(n0, p0); - HyperplaneType pl1(n1, p1); - HyperplaneType pl2 = pl1; - - Scalar s0 = ei_random(); - Scalar s1 = ei_random(); - - VERIFY_IS_APPROX( n1.eigen2_dot(n1), Scalar(1) ); - - VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) ); - VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0 ); - VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) ); - VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 + pl1.normal().unitOrthogonal() * s1), Scalar(1) ); - - // transform - if (!NumTraits::IsComplex) - { - MatrixType rot = MatrixType::Random(dim,dim).qr().matrixQ(); - Scaling scaling(VectorType::Random()); - Translation translation(VectorType::Random()); - - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot).absDistance(rot * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation) - .absDistance((rot*scaling*translation) * p1), Scalar(1) ); - pl2 = pl1; - VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry) - .absDistance((rot*translation) * p1), Scalar(1) ); - } - - // casting - const int Dim = HyperplaneType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - Hyperplane hp1f = pl1.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),pl1); - Hyperplane hp1d = pl1.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),pl1); -} - -template void lines() -{ - typedef Hyperplane HLine; - typedef ParametrizedLine PLine; - typedef Matrix Vector; - typedef Matrix CoeffsType; - - for(int i = 0; i < 10; i++) - { - Vector center = Vector::Random(); - Vector u = Vector::Random(); - Vector v = Vector::Random(); - Scalar a = ei_random(); - while (ei_abs(a-1) < 1e-4) a = ei_random(); - while (u.norm() < 1e-4) u = Vector::Random(); - while (v.norm() < 1e-4) v = Vector::Random(); - - HLine line_u = HLine::Through(center + u, center + a*u); - HLine line_v = HLine::Through(center + v, center + a*v); - - // the line equations should be normalized so that a^2+b^2=1 - VERIFY_IS_APPROX(line_u.normal().norm(), Scalar(1)); - VERIFY_IS_APPROX(line_v.normal().norm(), Scalar(1)); - - Vector result = line_u.intersection(line_v); - - // the lines should intersect at the point we called "center" - VERIFY_IS_APPROX(result, center); - - // check conversions between two types of lines - PLine pl(line_u); // gcc 3.3 will commit suicide if we don't name this variable - CoeffsType converted_coeffs(HLine(pl).coeffs()); - converted_coeffs *= line_u.coeffs()(0)/converted_coeffs(0); - VERIFY(line_u.coeffs().isApprox(converted_coeffs)); - } -} - -void test_eigen2_hyperplane() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( hyperplane(Hyperplane()) ); - CALL_SUBTEST_2( hyperplane(Hyperplane()) ); - CALL_SUBTEST_3( hyperplane(Hyperplane()) ); - CALL_SUBTEST_4( hyperplane(Hyperplane,5>()) ); - CALL_SUBTEST_5( lines() ); - CALL_SUBTEST_6( lines() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_inverse.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_inverse.cpp deleted file mode 100644 index ccd24a194..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_inverse.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void inverse(const MatrixType& m) -{ - /* this test covers the following files: - Inverse.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - - MatrixType m1 = MatrixType::Random(rows, cols), - m2(rows, cols), - identity = MatrixType::Identity(rows, rows); - - while(ei_abs(m1.determinant()) < RealScalar(0.1) && rows <= 8) - { - m1 = MatrixType::Random(rows, cols); - } - - m2 = m1.inverse(); - VERIFY_IS_APPROX(m1, m2.inverse() ); - - m1.computeInverse(&m2); - VERIFY_IS_APPROX(m1, m2.inverse() ); - - VERIFY_IS_APPROX((Scalar(2)*m2).inverse(), m2.inverse()*Scalar(0.5)); - - VERIFY_IS_APPROX(identity, m1.inverse() * m1 ); - VERIFY_IS_APPROX(identity, m1 * m1.inverse() ); - - VERIFY_IS_APPROX(m1, m1.inverse().inverse() ); - - // since for the general case we implement separately row-major and col-major, test that - VERIFY_IS_APPROX(m1.transpose().inverse(), m1.inverse().transpose()); -} - -void test_eigen2_inverse() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( inverse(Matrix()) ); - CALL_SUBTEST_2( inverse(Matrix2d()) ); - CALL_SUBTEST_3( inverse(Matrix3f()) ); - CALL_SUBTEST_4( inverse(Matrix4f()) ); - CALL_SUBTEST_5( inverse(MatrixXf(8,8)) ); - CALL_SUBTEST_6( inverse(MatrixXcd(7,7)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_linearstructure.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_linearstructure.cpp deleted file mode 100644 index 488f4c485..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_linearstructure.cpp +++ /dev/null @@ -1,83 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void linearStructure(const MatrixType& m) -{ - /* this test covers the following files: - Sum.h Difference.h Opposite.h ScalarMultiple.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - - Scalar s1 = ei_random(); - while (ei_abs(s1)<1e-3) s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - VERIFY_IS_APPROX(-(-m1), m1); - VERIFY_IS_APPROX(m1+m1, 2*m1); - VERIFY_IS_APPROX(m1+m2-m1, m2); - VERIFY_IS_APPROX(-m2+m1+m2, m1); - VERIFY_IS_APPROX(m1*s1, s1*m1); - VERIFY_IS_APPROX((m1+m2)*s1, s1*m1+s1*m2); - VERIFY_IS_APPROX((-m1+m2)*s1, -s1*m1+s1*m2); - m3 = m2; m3 += m1; - VERIFY_IS_APPROX(m3, m1+m2); - m3 = m2; m3 -= m1; - VERIFY_IS_APPROX(m3, m2-m1); - m3 = m2; m3 *= s1; - VERIFY_IS_APPROX(m3, s1*m2); - if(NumTraits::HasFloatingPoint) - { - m3 = m2; m3 /= s1; - VERIFY_IS_APPROX(m3, m2/s1); - } - - // again, test operator() to check const-qualification - VERIFY_IS_APPROX((-m1)(r,c), -(m1(r,c))); - VERIFY_IS_APPROX((m1-m2)(r,c), (m1(r,c))-(m2(r,c))); - VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c))); - VERIFY_IS_APPROX((s1*m1)(r,c), s1*(m1(r,c))); - VERIFY_IS_APPROX((m1*s1)(r,c), (m1(r,c))*s1); - if(NumTraits::HasFloatingPoint) - VERIFY_IS_APPROX((m1/s1)(r,c), (m1(r,c))/s1); - - // use .block to disable vectorization and compare to the vectorized version - VERIFY_IS_APPROX(m1+m1.block(0,0,rows,cols), m1+m1); - VERIFY_IS_APPROX(m1.cwise() * m1.block(0,0,rows,cols), m1.cwise() * m1); - VERIFY_IS_APPROX(m1 - m1.block(0,0,rows,cols), m1 - m1); - VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1); -} - -void test_eigen2_linearstructure() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( linearStructure(Matrix()) ); - CALL_SUBTEST_2( linearStructure(Matrix2f()) ); - CALL_SUBTEST_3( linearStructure(Vector3d()) ); - CALL_SUBTEST_4( linearStructure(Matrix4d()) ); - CALL_SUBTEST_5( linearStructure(MatrixXcf(3, 3)) ); - CALL_SUBTEST_6( linearStructure(MatrixXf(8, 12)) ); - CALL_SUBTEST_7( linearStructure(MatrixXi(8, 12)) ); - CALL_SUBTEST_8( linearStructure(MatrixXcd(20, 20)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_lu.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_lu.cpp deleted file mode 100644 index e993b1c7c..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_lu.cpp +++ /dev/null @@ -1,122 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template -void doSomeRankPreservingOperations(Eigen::MatrixBase& m) -{ - typedef typename Derived::RealScalar RealScalar; - for(int a = 0; a < 3*(m.rows()+m.cols()); a++) - { - RealScalar d = Eigen::ei_random(-1,1); - int i = Eigen::ei_random(0,m.rows()-1); // i is a random row number - int j; - do { - j = Eigen::ei_random(0,m.rows()-1); - } while (i==j); // j is another one (must be different) - m.row(i) += d * m.row(j); - - i = Eigen::ei_random(0,m.cols()-1); // i is a random column number - do { - j = Eigen::ei_random(0,m.cols()-1); - } while (i==j); // j is another one (must be different) - m.col(i) += d * m.col(j); - } -} - -template void lu_non_invertible() -{ - /* this test covers the following files: - LU.h - */ - // NOTE there seems to be a problem with too small sizes -- could easily lie in the doSomeRankPreservingOperations function - int rows = ei_random(20,200), cols = ei_random(20,200), cols2 = ei_random(20,200); - int rank = ei_random(1, std::min(rows, cols)-1); - - MatrixType m1(rows, cols), m2(cols, cols2), m3(rows, cols2), k(1,1); - m1 = MatrixType::Random(rows,cols); - if(rows <= cols) - for(int i = rank; i < rows; i++) m1.row(i).setZero(); - else - for(int i = rank; i < cols; i++) m1.col(i).setZero(); - doSomeRankPreservingOperations(m1); - - LU lu(m1); - typename LU::KernelResultType m1kernel = lu.kernel(); - typename LU::ImageResultType m1image = lu.image(); - - VERIFY(rank == lu.rank()); - VERIFY(cols - lu.rank() == lu.dimensionOfKernel()); - VERIFY(!lu.isInjective()); - VERIFY(!lu.isInvertible()); - VERIFY(lu.isSurjective() == (lu.rank() == rows)); - VERIFY((m1 * m1kernel).isMuchSmallerThan(m1)); - VERIFY(m1image.lu().rank() == rank); - MatrixType sidebyside(m1.rows(), m1.cols() + m1image.cols()); - sidebyside << m1, m1image; - VERIFY(sidebyside.lu().rank() == rank); - m2 = MatrixType::Random(cols,cols2); - m3 = m1*m2; - m2 = MatrixType::Random(cols,cols2); - lu.solve(m3, &m2); - VERIFY_IS_APPROX(m3, m1*m2); - /* solve now always returns true - m3 = MatrixType::Random(rows,cols2); - VERIFY(!lu.solve(m3, &m2)); - */ -} - -template void lu_invertible() -{ - /* this test covers the following files: - LU.h - */ - typedef typename NumTraits::Real RealScalar; - int size = ei_random(10,200); - - MatrixType m1(size, size), m2(size, size), m3(size, size); - m1 = MatrixType::Random(size,size); - - if (ei_is_same_type::ret) - { - // let's build a matrix more stable to inverse - MatrixType a = MatrixType::Random(size,size*2); - m1 += a * a.adjoint(); - } - - LU lu(m1); - VERIFY(0 == lu.dimensionOfKernel()); - VERIFY(size == lu.rank()); - VERIFY(lu.isInjective()); - VERIFY(lu.isSurjective()); - VERIFY(lu.isInvertible()); - VERIFY(lu.image().lu().isInvertible()); - m3 = MatrixType::Random(size,size); - lu.solve(m3, &m2); - VERIFY_IS_APPROX(m3, m1*m2); - VERIFY_IS_APPROX(m2, lu.inverse()*m3); - m3 = MatrixType::Random(size,size); - VERIFY(lu.solve(m3, &m2)); -} - -void test_eigen2_lu() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( lu_non_invertible() ); - CALL_SUBTEST_2( lu_non_invertible() ); - CALL_SUBTEST_3( lu_non_invertible() ); - CALL_SUBTEST_4( lu_non_invertible() ); - CALL_SUBTEST_1( lu_invertible() ); - CALL_SUBTEST_2( lu_invertible() ); - CALL_SUBTEST_3( lu_invertible() ); - CALL_SUBTEST_4( lu_invertible() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_map.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_map.cpp deleted file mode 100644 index 4a1c4e11a..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_map.cpp +++ /dev/null @@ -1,114 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2007-2010 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void map_class_vector(const VectorType& m) -{ - typedef typename VectorType::Scalar Scalar; - - int size = m.size(); - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - Scalar* array2 = ei_aligned_new(size); - Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - - Map(array1, size) = VectorType::Random(size); - Map(array2, size) = Map(array1, size); - Map(array3unaligned, size) = Map((const Scalar*)array1, size); // test non-const-correctness support in eigen2 - VectorType ma1 = Map(array1, size); - VectorType ma2 = Map(array2, size); - VectorType ma3 = Map(array3unaligned, size); - VERIFY_IS_APPROX(ma1, ma2); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - -template void map_class_matrix(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(), cols = m.cols(), size = rows*cols; - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - for(int i = 0; i < size; i++) array1[i] = Scalar(1); - Scalar* array2 = ei_aligned_new(size); - for(int i = 0; i < size; i++) array2[i] = Scalar(1); - Scalar* array3 = new Scalar[size+1]; - for(int i = 0; i < size+1; i++) array3[i] = Scalar(1); - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - Map(array1, rows, cols) = MatrixType::Ones(rows,cols); - Map(array2, rows, cols) = Map((const Scalar*)array1, rows, cols); // test non-const-correctness support in eigen2 - Map(array3unaligned, rows, cols) = Map(array1, rows, cols); - MatrixType ma1 = Map(array1, rows, cols); - MatrixType ma2 = Map(array2, rows, cols); - VERIFY_IS_APPROX(ma1, ma2); - MatrixType ma3 = Map(array3unaligned, rows, cols); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - -template void map_static_methods(const VectorType& m) -{ - typedef typename VectorType::Scalar Scalar; - - int size = m.size(); - - // test Map.h - Scalar* array1 = ei_aligned_new(size); - Scalar* array2 = ei_aligned_new(size); - Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = std::size_t(array3)%16 == 0 ? array3+1 : array3; - - VectorType::MapAligned(array1, size) = VectorType::Random(size); - VectorType::Map(array2, size) = VectorType::Map(array1, size); - VectorType::Map(array3unaligned, size) = VectorType::Map(array1, size); - VectorType ma1 = VectorType::Map(array1, size); - VectorType ma2 = VectorType::MapAligned(array2, size); - VectorType ma3 = VectorType::Map(array3unaligned, size); - VERIFY_IS_APPROX(ma1, ma2); - VERIFY_IS_APPROX(ma1, ma3); - - ei_aligned_delete(array1, size); - ei_aligned_delete(array2, size); - delete[] array3; -} - - -void test_eigen2_map() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( map_class_vector(Matrix()) ); - CALL_SUBTEST_2( map_class_vector(Vector4d()) ); - CALL_SUBTEST_3( map_class_vector(RowVector4f()) ); - CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) ); - CALL_SUBTEST_5( map_class_vector(VectorXi(12)) ); - - CALL_SUBTEST_1( map_class_matrix(Matrix()) ); - CALL_SUBTEST_2( map_class_matrix(Matrix4d()) ); - CALL_SUBTEST_6( map_class_matrix(Matrix()) ); - CALL_SUBTEST_4( map_class_matrix(MatrixXcf(ei_random(1,10),ei_random(1,10))) ); - CALL_SUBTEST_5( map_class_matrix(MatrixXi(ei_random(1,10),ei_random(1,10))) ); - - CALL_SUBTEST_1( map_static_methods(Matrix()) ); - CALL_SUBTEST_2( map_static_methods(Vector3f()) ); - CALL_SUBTEST_7( map_static_methods(RowVector3d()) ); - CALL_SUBTEST_4( map_static_methods(VectorXcd(8)) ); - CALL_SUBTEST_5( map_static_methods(VectorXf(12)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_meta.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_meta.cpp deleted file mode 100644 index 1d01bd84d..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_meta.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -void test_eigen2_meta() -{ - typedef float & FloatRef; - typedef const float & ConstFloatRef; - - VERIFY((ei_meta_if<(3<4),ei_meta_true, ei_meta_false>::ret::ret)); - VERIFY(( ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - VERIFY((!ei_is_same_type::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - VERIFY(( ei_is_same_type::type >::ret)); - - VERIFY(ei_meta_sqrt<1>::ret == 1); - #define VERIFY_META_SQRT(X) VERIFY(ei_meta_sqrt::ret == int(ei_sqrt(double(X)))) - VERIFY_META_SQRT(2); - VERIFY_META_SQRT(3); - VERIFY_META_SQRT(4); - VERIFY_META_SQRT(5); - VERIFY_META_SQRT(6); - VERIFY_META_SQRT(8); - VERIFY_META_SQRT(9); - VERIFY_META_SQRT(15); - VERIFY_META_SQRT(16); - VERIFY_META_SQRT(17); - VERIFY_META_SQRT(255); - VERIFY_META_SQRT(256); - VERIFY_META_SQRT(257); - VERIFY_META_SQRT(1023); - VERIFY_META_SQRT(1024); - VERIFY_META_SQRT(1025); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_miscmatrices.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_miscmatrices.cpp deleted file mode 100644 index 8bbb20cc8..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_miscmatrices.cpp +++ /dev/null @@ -1,48 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void miscMatrices(const MatrixType& m) -{ - /* this test covers the following files: - DiagonalMatrix.h Ones.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix VectorType; - typedef Matrix RowVectorType; - int rows = m.rows(); - int cols = m.cols(); - - int r = ei_random(0, rows-1), r2 = ei_random(0, rows-1), c = ei_random(0, cols-1); - VERIFY_IS_APPROX(MatrixType::Ones(rows,cols)(r,c), static_cast(1)); - MatrixType m1 = MatrixType::Ones(rows,cols); - VERIFY_IS_APPROX(m1(r,c), static_cast(1)); - VectorType v1 = VectorType::Random(rows); - v1[0]; - Matrix - square = v1.asDiagonal(); - if(r==r2) VERIFY_IS_APPROX(square(r,r2), v1[r]); - else VERIFY_IS_MUCH_SMALLER_THAN(square(r,r2), static_cast(1)); - square = MatrixType::Zero(rows, rows); - square.diagonal() = VectorType::Ones(rows); - VERIFY_IS_APPROX(square, MatrixType::Identity(rows, rows)); -} - -void test_eigen2_miscmatrices() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( miscMatrices(Matrix()) ); - CALL_SUBTEST_2( miscMatrices(Matrix4d()) ); - CALL_SUBTEST_3( miscMatrices(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( miscMatrices(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( miscMatrices(MatrixXcd(20, 20)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_mixingtypes.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_mixingtypes.cpp deleted file mode 100644 index fb5ac5dda..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_mixingtypes.cpp +++ /dev/null @@ -1,77 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_NO_STATIC_ASSERT -#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them -#endif - -#ifndef EIGEN_DONT_VECTORIZE -#define EIGEN_DONT_VECTORIZE // SSE intrinsics aren't designed to allow mixing types -#endif - -#include "main.h" - - -template void mixingtypes(int size = SizeAtCompileType) -{ - typedef Matrix Mat_f; - typedef Matrix Mat_d; - typedef Matrix, SizeAtCompileType, SizeAtCompileType> Mat_cf; - typedef Matrix, SizeAtCompileType, SizeAtCompileType> Mat_cd; - typedef Matrix Vec_f; - typedef Matrix Vec_d; - typedef Matrix, SizeAtCompileType, 1> Vec_cf; - typedef Matrix, SizeAtCompileType, 1> Vec_cd; - - Mat_f mf(size,size); - Mat_d md(size,size); - Mat_cf mcf(size,size); - Mat_cd mcd(size,size); - Vec_f vf(size,1); - Vec_d vd(size,1); - Vec_cf vcf(size,1); - Vec_cd vcd(size,1); - - mf+mf; - VERIFY_RAISES_ASSERT(mf+md); - VERIFY_RAISES_ASSERT(mf+mcf); - VERIFY_RAISES_ASSERT(vf=vd); - VERIFY_RAISES_ASSERT(vf+=vd); - VERIFY_RAISES_ASSERT(mcd=md); - - mf*mf; - md*mcd; - mcd*md; - mf*vcf; - mcf*vf; - mcf *= mf; - vcd = md*vcd; - vcf = mcf*vf; -#if 0 - // these are know generating hard build errors in eigen3 - VERIFY_RAISES_ASSERT(mf*md); - VERIFY_RAISES_ASSERT(mcf*mcd); - VERIFY_RAISES_ASSERT(mcf*vcd); - VERIFY_RAISES_ASSERT(vcf = mf*vf); - - vf.eigen2_dot(vf); - VERIFY_RAISES_ASSERT(vd.eigen2_dot(vf)); - VERIFY_RAISES_ASSERT(vcf.eigen2_dot(vf)); // yeah eventually we should allow this but i'm too lazy to make that change now in Dot.h - // especially as that might be rewritten as cwise product .sum() which would make that automatic. -#endif -} - -void test_eigen2_mixingtypes() -{ - // check that our operator new is indeed called: - CALL_SUBTEST_1(mixingtypes<3>()); - CALL_SUBTEST_2(mixingtypes<4>()); - CALL_SUBTEST_3(mixingtypes(20)); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_nomalloc.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_nomalloc.cpp deleted file mode 100644 index d34a69999..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_nomalloc.cpp +++ /dev/null @@ -1,53 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -// this hack is needed to make this file compiles with -pedantic (gcc) -#ifdef __GNUC__ -#define throw(X) -#endif -// discard stack allocation as that too bypasses malloc -#define EIGEN_STACK_ALLOCATION_LIMIT 0 -// any heap allocation will raise an assert -#define EIGEN_NO_MALLOC - -#include "main.h" - -template void nomalloc(const MatrixType& m) -{ - /* this test check no dynamic memory allocation are issued with fixed-size matrices - */ - - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols); - - Scalar s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - VERIFY_IS_APPROX((m1+m2)*s1, s1*m1+s1*m2); - VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c))); - VERIFY_IS_APPROX(m1.cwise() * m1.block(0,0,rows,cols), m1.cwise() * m1); - VERIFY_IS_APPROX((m1*m1.transpose())*m2, m1*(m1.transpose()*m2)); -} - -void test_eigen2_nomalloc() -{ - // check that our operator new is indeed called: - VERIFY_RAISES_ASSERT(MatrixXd dummy = MatrixXd::Random(3,3)); - CALL_SUBTEST_1( nomalloc(Matrix()) ); - CALL_SUBTEST_2( nomalloc(Matrix4d()) ); - CALL_SUBTEST_3( nomalloc(Matrix()) ); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_packetmath.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_packetmath.cpp deleted file mode 100644 index b1f325fe7..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_packetmath.cpp +++ /dev/null @@ -1,132 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -// using namespace Eigen; - -template bool areApprox(const Scalar* a, const Scalar* b, int size) -{ - for (int i=0; i const complex& min(const complex& a, const complex& b) -{ return a.real() < b.real() ? a : b; } - -template<> const complex& max(const complex& a, const complex& b) -{ return a.real() < b.real() ? b : a; } - -} - -template void packetmath() -{ - typedef typename ei_packet_traits::type Packet; - const int PacketSize = ei_packet_traits::size; - - const int size = PacketSize*4; - EIGEN_ALIGN_128 Scalar data1[ei_packet_traits::size*4]; - EIGEN_ALIGN_128 Scalar data2[ei_packet_traits::size*4]; - EIGEN_ALIGN_128 Packet packets[PacketSize*2]; - EIGEN_ALIGN_128 Scalar ref[ei_packet_traits::size*4]; - for (int i=0; i(); - data2[i] = ei_random(); - } - - ei_pstore(data2, ei_pload(data1)); - VERIFY(areApprox(data1, data2, PacketSize) && "aligned load/store"); - - for (int offset=0; offset(packets[0], packets[1]); - else if (offset==1) ei_palign<1>(packets[0], packets[1]); - else if (offset==2) ei_palign<2>(packets[0], packets[1]); - else if (offset==3) ei_palign<3>(packets[0], packets[1]); - ei_pstore(data2, packets[0]); - - for (int i=0; i Vector; - VERIFY(areApprox(ref, data2, PacketSize) && "ei_palign"); - } - - CHECK_CWISE(REF_ADD, ei_padd); - CHECK_CWISE(REF_SUB, ei_psub); - CHECK_CWISE(REF_MUL, ei_pmul); - #ifndef EIGEN_VECTORIZE_ALTIVEC - if (!ei_is_same_type::ret) - CHECK_CWISE(REF_DIV, ei_pdiv); - #endif - CHECK_CWISE(std::min, ei_pmin); - CHECK_CWISE(std::max, ei_pmax); - - for (int i=0; i() ); - CALL_SUBTEST_2( packetmath() ); - CALL_SUBTEST_3( packetmath() ); - CALL_SUBTEST_4( packetmath >() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_parametrizedline.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_parametrizedline.cpp deleted file mode 100644 index 814728870..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_parametrizedline.cpp +++ /dev/null @@ -1,62 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include -#include - -template void parametrizedline(const LineType& _line) -{ - /* this test covers the following files: - ParametrizedLine.h - */ - - const int dim = _line.dim(); - typedef typename LineType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - typedef Matrix VectorType; - typedef Matrix MatrixType; - - VectorType p0 = VectorType::Random(dim); - VectorType p1 = VectorType::Random(dim); - - VectorType d0 = VectorType::Random(dim).normalized(); - - LineType l0(p0, d0); - - Scalar s0 = ei_random(); - Scalar s1 = ei_abs(ei_random()); - - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0), RealScalar(1) ); - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0+s0*d0), RealScalar(1) ); - VERIFY_IS_APPROX( (l0.projection(p1)-p1).norm(), l0.distance(p1) ); - VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(l0.projection(p1)), RealScalar(1) ); - VERIFY_IS_APPROX( Scalar(l0.distance((p0+s0*d0) + d0.unitOrthogonal() * s1)), s1 ); - - // casting - const int Dim = LineType::AmbientDimAtCompileTime; - typedef typename GetDifferentType::type OtherScalar; - ParametrizedLine hp1f = l0.template cast(); - VERIFY_IS_APPROX(hp1f.template cast(),l0); - ParametrizedLine hp1d = l0.template cast(); - VERIFY_IS_APPROX(hp1d.template cast(),l0); -} - -void test_eigen2_parametrizedline() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_2( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_3( parametrizedline(ParametrizedLine()) ); - CALL_SUBTEST_4( parametrizedline(ParametrizedLine,5>()) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp deleted file mode 100644 index 8bfa55694..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_prec_inverse_4x4.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -template std::string type_name() { return "other"; } -template<> std::string type_name() { return "float"; } -template<> std::string type_name() { return "double"; } -template<> std::string type_name() { return "int"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } - -#define EIGEN_DEBUG_VAR(x) std::cerr << #x << " = " << x << std::endl; - -template inline typename NumTraits::Real epsilon() -{ - return std::numeric_limits::Real>::epsilon(); -} - -template void inverse_permutation_4x4() -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - Vector4i indices(0,1,2,3); - for(int i = 0; i < 24; ++i) - { - MatrixType m = MatrixType::Zero(); - m(indices(0),0) = 1; - m(indices(1),1) = 1; - m(indices(2),2) = 1; - m(indices(3),3) = 1; - MatrixType inv = m.inverse(); - double error = double( (m*inv-MatrixType::Identity()).norm() / epsilon() ); - VERIFY(error == 0.0); - std::next_permutation(indices.data(),indices.data()+4); - } -} - -template void inverse_general_4x4(int repeat) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - double error_sum = 0., error_max = 0.; - for(int i = 0; i < repeat; ++i) - { - MatrixType m; - RealScalar absdet; - do { - m = MatrixType::Random(); - absdet = ei_abs(m.determinant()); - } while(absdet < 10 * epsilon()); - MatrixType inv = m.inverse(); - double error = double( (m*inv-MatrixType::Identity()).norm() * absdet / epsilon() ); - error_sum += error; - error_max = std::max(error_max, error); - } - std::cerr << "inverse_general_4x4, Scalar = " << type_name() << std::endl; - double error_avg = error_sum / repeat; - EIGEN_DEBUG_VAR(error_avg); - EIGEN_DEBUG_VAR(error_max); - VERIFY(error_avg < (NumTraits::IsComplex ? 8.0 : 1.25)); - VERIFY(error_max < (NumTraits::IsComplex ? 64.0 : 20.0)); -} - -void test_eigen2_prec_inverse_4x4() -{ - CALL_SUBTEST_1((inverse_permutation_4x4())); - CALL_SUBTEST_1(( inverse_general_4x4(200000 * g_repeat) )); - - CALL_SUBTEST_2((inverse_permutation_4x4 >())); - CALL_SUBTEST_2(( inverse_general_4x4 >(200000 * g_repeat) )); - - CALL_SUBTEST_3((inverse_permutation_4x4())); - CALL_SUBTEST_3((inverse_general_4x4(50000 * g_repeat))); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_large.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_large.cpp deleted file mode 100644 index 5149ef748..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_large.cpp +++ /dev/null @@ -1,45 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "product.h" - -void test_eigen2_product_large() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product(MatrixXf(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_2( product(MatrixXd(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_3( product(MatrixXi(ei_random(1,320), ei_random(1,320))) ); - CALL_SUBTEST_4( product(MatrixXcf(ei_random(1,50), ei_random(1,50))) ); - CALL_SUBTEST_5( product(Matrix(ei_random(1,320), ei_random(1,320))) ); - } - -#ifdef EIGEN_TEST_PART_6 - { - // test a specific issue in DiagonalProduct - int N = 1000000; - VectorXf v = VectorXf::Ones(N); - MatrixXf m = MatrixXf::Ones(N,3); - m = (v+v).asDiagonal() * m; - VERIFY_IS_APPROX(m, MatrixXf::Constant(N,3,2)); - } - - { - // test deferred resizing in Matrix::operator= - MatrixXf a = MatrixXf::Random(10,4), b = MatrixXf::Random(4,10), c = a; - VERIFY_IS_APPROX((a = a * b), (c * b).eval()); - } - - { - MatrixXf mat1(10,10); mat1.setRandom(); - MatrixXf mat2(32,10); mat2.setRandom(); - MatrixXf result = mat1.row(2)*mat2.transpose(); - VERIFY_IS_APPROX(result, (mat1.row(2)*mat2.transpose()).eval()); - } -#endif -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_small.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_small.cpp deleted file mode 100644 index 4cd8c102f..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_product_small.cpp +++ /dev/null @@ -1,22 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_STATIC_ASSERT -#include "product.h" - -void test_eigen2_product_small() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( product(Matrix()) ); - CALL_SUBTEST_2( product(Matrix()) ); - CALL_SUBTEST_3( product(Matrix3d()) ); - CALL_SUBTEST_4( product(Matrix4d()) ); - CALL_SUBTEST_5( product(Matrix4f()) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qr.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qr.cpp deleted file mode 100644 index 76977e4c1..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qr.cpp +++ /dev/null @@ -1,69 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void qr(const MatrixType& m) -{ - /* this test covers the following files: - QR.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix SquareMatrixType; - typedef Matrix VectorType; - - MatrixType a = MatrixType::Random(rows,cols); - QR qrOfA(a); - VERIFY_IS_APPROX(a, qrOfA.matrixQ() * qrOfA.matrixR()); - VERIFY_IS_NOT_APPROX(a+MatrixType::Identity(rows, cols), qrOfA.matrixQ() * qrOfA.matrixR()); - - #if 0 // eigenvalues module not yet ready - SquareMatrixType b = a.adjoint() * a; - - // check tridiagonalization - Tridiagonalization tridiag(b); - VERIFY_IS_APPROX(b, tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint()); - - // check hessenberg decomposition - HessenbergDecomposition hess(b); - VERIFY_IS_APPROX(b, hess.matrixQ() * hess.matrixH() * hess.matrixQ().adjoint()); - VERIFY_IS_APPROX(tridiag.matrixT(), hess.matrixH()); - b = SquareMatrixType::Random(cols,cols); - hess.compute(b); - VERIFY_IS_APPROX(b, hess.matrixQ() * hess.matrixH() * hess.matrixQ().adjoint()); - #endif -} - -void test_eigen2_qr() -{ - for(int i = 0; i < 1; i++) { - CALL_SUBTEST_1( qr(Matrix2f()) ); - CALL_SUBTEST_2( qr(Matrix4d()) ); - CALL_SUBTEST_3( qr(MatrixXf(12,8)) ); - CALL_SUBTEST_4( qr(MatrixXcd(5,5)) ); - CALL_SUBTEST_4( qr(MatrixXcd(7,3)) ); - } - -#ifdef EIGEN_TEST_PART_5 - // small isFullRank test - { - Matrix3d mat; - mat << 1, 45, 1, 2, 2, 2, 1, 2, 3; - VERIFY(mat.qr().isFullRank()); - mat << 1, 1, 1, 2, 2, 2, 1, 2, 3; - //always returns true in eigen2support - //VERIFY(!mat.qr().isFullRank()); - } - -#endif -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qtvector.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qtvector.cpp deleted file mode 100644 index 6cfb58a26..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_qtvector.cpp +++ /dev/null @@ -1,158 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_WORK_AROUND_QT_BUG_CALLING_WRONG_OPERATOR_NEW_FIXED_IN_QT_4_5 - -#include "main.h" - -#include -#include - -#include - -template -void check_qtvector_matrix(const MatrixType& m) -{ - int rows = m.rows(); - int cols = m.cols(); - MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - QVector v(10, MatrixType(rows,cols)), w(20, y); - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], y); - } - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - MatrixType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(int i=23; i -void check_qtvector_transform(const TransformType&) -{ - typedef typename TransformType::MatrixType MatrixType; - TransformType x(MatrixType::Random()), y(MatrixType::Random()); - QVector v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - TransformType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; int(i) -void check_qtvector_quaternion(const QuaternionType&) -{ - typedef typename QuaternionType::Coefficients Coefficients; - QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - QVector v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.fill(y,22); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - QuaternionType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; int(i) -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template -void makeNoisyCohyperplanarPoints(int numPoints, - VectorType **points, - HyperplaneType *hyperplane, - typename VectorType::Scalar noiseAmplitude) -{ - typedef typename VectorType::Scalar Scalar; - const int size = points[0]->size(); - // pick a random hyperplane, store the coefficients of its equation - hyperplane->coeffs().resize(size + 1); - for(int j = 0; j < size + 1; j++) - { - do { - hyperplane->coeffs().coeffRef(j) = ei_random(); - } while(ei_abs(hyperplane->coeffs().coeff(j)) < 0.5); - } - - // now pick numPoints random points on this hyperplane - for(int i = 0; i < numPoints; i++) - { - VectorType& cur_point = *(points[i]); - do - { - cur_point = VectorType::Random(size)/*.normalized()*/; - // project cur_point onto the hyperplane - Scalar x = - (hyperplane->coeffs().start(size).cwise()*cur_point).sum(); - cur_point *= hyperplane->coeffs().coeff(size) / x; - } while( cur_point.norm() < 0.5 - || cur_point.norm() > 2.0 ); - } - - // add some noise to these points - for(int i = 0; i < numPoints; i++ ) - *(points[i]) += noiseAmplitude * VectorType::Random(size); -} - -template -void check_linearRegression(int numPoints, - VectorType **points, - const VectorType& original, - typename VectorType::Scalar tolerance) -{ - int size = points[0]->size(); - assert(size==2); - VectorType result(size); - linearRegression(numPoints, points, &result, 1); - typename VectorType::Scalar error = (result - original).norm() / original.norm(); - VERIFY(ei_abs(error) < ei_abs(tolerance)); -} - -template -void check_fitHyperplane(int numPoints, - VectorType **points, - const HyperplaneType& original, - typename VectorType::Scalar tolerance) -{ - int size = points[0]->size(); - HyperplaneType result(size); - fitHyperplane(numPoints, points, &result); - result.coeffs() *= original.coeffs().coeff(size)/result.coeffs().coeff(size); - typename VectorType::Scalar error = (result.coeffs() - original.coeffs()).norm() / original.coeffs().norm(); - std::cout << ei_abs(error) << " xxx " << ei_abs(tolerance) << std::endl; - VERIFY(ei_abs(error) < ei_abs(tolerance)); -} - -void test_eigen2_regression() -{ - for(int i = 0; i < g_repeat; i++) - { -#ifdef EIGEN_TEST_PART_1 - { - Vector2f points2f [1000]; - Vector2f *points2f_ptrs [1000]; - for(int i = 0; i < 1000; i++) points2f_ptrs[i] = &(points2f[i]); - Vector2f coeffs2f; - Hyperplane coeffs3f; - makeNoisyCohyperplanarPoints(1000, points2f_ptrs, &coeffs3f, 0.01f); - coeffs2f[0] = -coeffs3f.coeffs()[0]/coeffs3f.coeffs()[1]; - coeffs2f[1] = -coeffs3f.coeffs()[2]/coeffs3f.coeffs()[1]; - CALL_SUBTEST(check_linearRegression(10, points2f_ptrs, coeffs2f, 0.05f)); - CALL_SUBTEST(check_linearRegression(100, points2f_ptrs, coeffs2f, 0.01f)); - CALL_SUBTEST(check_linearRegression(1000, points2f_ptrs, coeffs2f, 0.002f)); - } -#endif -#ifdef EIGEN_TEST_PART_2 - { - Vector2f points2f [1000]; - Vector2f *points2f_ptrs [1000]; - for(int i = 0; i < 1000; i++) points2f_ptrs[i] = &(points2f[i]); - Hyperplane coeffs3f; - makeNoisyCohyperplanarPoints(1000, points2f_ptrs, &coeffs3f, 0.01f); - CALL_SUBTEST(check_fitHyperplane(10, points2f_ptrs, coeffs3f, 0.05f)); - CALL_SUBTEST(check_fitHyperplane(100, points2f_ptrs, coeffs3f, 0.01f)); - CALL_SUBTEST(check_fitHyperplane(1000, points2f_ptrs, coeffs3f, 0.002f)); - } -#endif -#ifdef EIGEN_TEST_PART_3 - { - Vector4d points4d [1000]; - Vector4d *points4d_ptrs [1000]; - for(int i = 0; i < 1000; i++) points4d_ptrs[i] = &(points4d[i]); - Hyperplane coeffs5d; - makeNoisyCohyperplanarPoints(1000, points4d_ptrs, &coeffs5d, 0.01); - CALL_SUBTEST(check_fitHyperplane(10, points4d_ptrs, coeffs5d, 0.05)); - CALL_SUBTEST(check_fitHyperplane(100, points4d_ptrs, coeffs5d, 0.01)); - CALL_SUBTEST(check_fitHyperplane(1000, points4d_ptrs, coeffs5d, 0.002)); - } -#endif -#ifdef EIGEN_TEST_PART_4 - { - VectorXcd *points11cd_ptrs[1000]; - for(int i = 0; i < 1000; i++) points11cd_ptrs[i] = new VectorXcd(11); - Hyperplane,Dynamic> *coeffs12cd = new Hyperplane,Dynamic>(11); - makeNoisyCohyperplanarPoints(1000, points11cd_ptrs, coeffs12cd, 0.01); - CALL_SUBTEST(check_fitHyperplane(100, points11cd_ptrs, *coeffs12cd, 0.025)); - CALL_SUBTEST(check_fitHyperplane(1000, points11cd_ptrs, *coeffs12cd, 0.006)); - delete coeffs12cd; - for(int i = 0; i < 1000; i++) delete points11cd_ptrs[i]; - } -#endif - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sizeof.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sizeof.cpp deleted file mode 100644 index ec1af5a06..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sizeof.cpp +++ /dev/null @@ -1,31 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void verifySizeOf(const MatrixType&) -{ - typedef typename MatrixType::Scalar Scalar; - if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic) - VERIFY(sizeof(MatrixType)==sizeof(Scalar)*MatrixType::SizeAtCompileTime); - else - VERIFY(sizeof(MatrixType)==sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); -} - -void test_eigen2_sizeof() -{ - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(Matrix4d()) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); - CALL_SUBTEST( verifySizeOf(MatrixXcf(3, 3)) ); - CALL_SUBTEST( verifySizeOf(MatrixXi(8, 12)) ); - CALL_SUBTEST( verifySizeOf(MatrixXcd(20, 20)) ); - CALL_SUBTEST( verifySizeOf(Matrix()) ); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_smallvectors.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_smallvectors.cpp deleted file mode 100644 index 03962b17d..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_smallvectors.cpp +++ /dev/null @@ -1,42 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void smallVectors() -{ - typedef Matrix V2; - typedef Matrix V3; - typedef Matrix V4; - Scalar x1 = ei_random(), - x2 = ei_random(), - x3 = ei_random(), - x4 = ei_random(); - V2 v2(x1, x2); - V3 v3(x1, x2, x3); - V4 v4(x1, x2, x3, x4); - VERIFY_IS_APPROX(x1, v2.x()); - VERIFY_IS_APPROX(x1, v3.x()); - VERIFY_IS_APPROX(x1, v4.x()); - VERIFY_IS_APPROX(x2, v2.y()); - VERIFY_IS_APPROX(x2, v3.y()); - VERIFY_IS_APPROX(x2, v4.y()); - VERIFY_IS_APPROX(x3, v3.z()); - VERIFY_IS_APPROX(x3, v4.z()); - VERIFY_IS_APPROX(x4, v4.w()); -} - -void test_eigen2_smallvectors() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST( smallVectors() ); - CALL_SUBTEST( smallVectors() ); - CALL_SUBTEST( smallVectors() ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_basic.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_basic.cpp deleted file mode 100644 index 049077670..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_basic.cpp +++ /dev/null @@ -1,317 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template -bool test_random_setter(SparseMatrix& sm, const DenseType& ref, const std::vector& nonzeroCoords) -{ - typedef SparseMatrix SparseType; - { - sm.setZero(); - SetterType w(sm); - std::vector remaining = nonzeroCoords; - while(!remaining.empty()) - { - int i = ei_random(0,remaining.size()-1); - w(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y()); - remaining[i] = remaining.back(); - remaining.pop_back(); - } - } - return sm.isApprox(ref); -} - -template -bool test_random_setter(DynamicSparseMatrix& sm, const DenseType& ref, const std::vector& nonzeroCoords) -{ - sm.setZero(); - std::vector remaining = nonzeroCoords; - while(!remaining.empty()) - { - int i = ei_random(0,remaining.size()-1); - sm.coeffRef(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y()); - remaining[i] = remaining.back(); - remaining.pop_back(); - } - return sm.isApprox(ref); -} - -template void sparse_basic(const SparseMatrixType& ref) -{ - const int rows = ref.rows(); - const int cols = ref.cols(); - typedef typename SparseMatrixType::Scalar Scalar; - enum { Flags = SparseMatrixType::Flags }; - - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - Scalar eps = 1e-6; - - SparseMatrixType m(rows, cols); - DenseMatrix refMat = DenseMatrix::Zero(rows, cols); - DenseVector vec1 = DenseVector::Random(rows); - Scalar s1 = ei_random(); - - std::vector zeroCoords; - std::vector nonzeroCoords; - initSparse(density, refMat, m, 0, &zeroCoords, &nonzeroCoords); - - if (zeroCoords.size()==0 || nonzeroCoords.size()==0) - return; - - // test coeff and coeffRef - for (int i=0; i<(int)zeroCoords.size(); ++i) - { - VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps ); - if(ei_is_same_type >::ret) - VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 ); - } - VERIFY_IS_APPROX(m, refMat); - - m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - - VERIFY_IS_APPROX(m, refMat); - /* - // test InnerIterators and Block expressions - for (int t=0; t<10; ++t) - { - int j = ei_random(0,cols-1); - int i = ei_random(0,rows-1); - int w = ei_random(1,cols-j-1); - int h = ei_random(1,rows-i-1); - -// VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); - for(int c=0; c w(m); -// for (int i=0; icoeffRef(nonzeroCoords[i].x(),nonzeroCoords[i].y()) = refMat.coeff(nonzeroCoords[i].x(),nonzeroCoords[i].y()); -// } -// } -// VERIFY_IS_APPROX(m, refMat); - - // random setter -// { -// m.setZero(); -// VERIFY_IS_NOT_APPROX(m, refMat); -// SparseSetter w(m); -// std::vector remaining = nonzeroCoords; -// while(!remaining.empty()) -// { -// int i = ei_random(0,remaining.size()-1); -// w->coeffRef(remaining[i].x(),remaining[i].y()) = refMat.coeff(remaining[i].x(),remaining[i].y()); -// remaining[i] = remaining.back(); -// remaining.pop_back(); -// } -// } -// VERIFY_IS_APPROX(m, refMat); - - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #ifdef EIGEN_UNORDERED_MAP_SUPPORT - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - #ifdef _DENSE_HASH_MAP_H_ - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - #ifdef _SPARSE_HASH_MAP_H_ - VERIFY(( test_random_setter >(m,refMat,nonzeroCoords) )); - #endif - - // test fillrand - { - DenseMatrix m1(rows,cols); - m1.setZero(); - SparseMatrixType m2(rows,cols); - m2.startFill(); - for (int j=0; j(0,rows-1); - if (m1.coeff(i,j)==Scalar(0)) - m2.fillrand(i,j) = m1(i,j) = ei_random(); - } - } - m2.endFill(); - VERIFY_IS_APPROX(m2,m1); - } - - // test RandomSetter - /*{ - SparseMatrixType m1(rows,cols), m2(rows,cols); - DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); - initSparse(density, refM1, m1); - { - Eigen::RandomSetter setter(m2); - for (int j=0; j(density, refM1, m1); - initSparse(density, refM2, m2); - initSparse(density, refM3, m3); - initSparse(density, refM4, m4); - - VERIFY_IS_APPROX(m1+m2, refM1+refM2); - VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3); - VERIFY_IS_APPROX(m3.cwise()*(m1+m2), refM3.cwise()*(refM1+refM2)); - VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2); - - VERIFY_IS_APPROX(m1*=s1, refM1*=s1); - VERIFY_IS_APPROX(m1/=s1, refM1/=s1); - - VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); - VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); - - VERIFY_IS_APPROX(m1.col(0).eigen2_dot(refM2.row(0)), refM1.col(0).eigen2_dot(refM2.row(0))); - - refM4.setRandom(); - // sparse cwise* dense - VERIFY_IS_APPROX(m3.cwise()*refM4, refM3.cwise()*refM4); -// VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4); - } - - // test innerVector() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - int j0 = ei_random(0,rows-1); - int j1 = ei_random(0,rows-1); - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); - //m2.innerVector(j0) = 2*m2.innerVector(j1); - //refMat2.col(j0) = 2*refMat2.col(j1); - //VERIFY_IS_APPROX(m2, refMat2); - } - - // test innerVectors() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - int j0 = ei_random(0,rows-2); - int j1 = ei_random(0,rows-2); - int n0 = ei_random(1,rows-std::max(j0,j1)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - //m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); - //refMat2.block(0,j0,rows,n0) = refMat2.block(0,j0,rows,n0) + refMat2.block(0,j1,rows,n0); - } - - // test transpose - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval()); - VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose()); - } - - // test prune - { - SparseMatrixType m2(rows, rows); - DenseMatrix refM2(rows, rows); - refM2.setZero(); - int countFalseNonZero = 0; - int countTrueNonZero = 0; - m2.startFill(); - for (int j=0; j(0,1); - if (x<0.1) - { - // do nothing - } - else if (x<0.5) - { - countFalseNonZero++; - m2.fill(i,j) = Scalar(0); - } - else - { - countTrueNonZero++; - m2.fill(i,j) = refM2(i,j) = Scalar(1); - } - } - m2.endFill(); - VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); - m2.prune(1); - VERIFY(countTrueNonZero==m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); - } -} - -void test_eigen2_sparse_basic() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_basic(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_basic(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_basic(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_basic(DynamicSparseMatrix(8, 8)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_product.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_product.cpp deleted file mode 100644 index d28e76dff..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_product.cpp +++ /dev/null @@ -1,115 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void sparse_product(const SparseMatrixType& ref) -{ - const int rows = ref.rows(); - const int cols = ref.cols(); - typedef typename SparseMatrixType::Scalar Scalar; - enum { Flags = SparseMatrixType::Flags }; - - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - - // test matrix-matrix product - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat3 = DenseMatrix::Zero(rows, rows); - DenseMatrix refMat4 = DenseMatrix::Zero(rows, rows); - DenseMatrix dm4 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - SparseMatrixType m4(rows, rows); - initSparse(density, refMat2, m2); - initSparse(density, refMat3, m3); - initSparse(density, refMat4, m4); - VERIFY_IS_APPROX(m4=m2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(m4=m2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - VERIFY_IS_APPROX(m4=m2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); - - // sparse * dense - VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=m2*refMat3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=m2.transpose()*refMat3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - - // dense * sparse - VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3); - VERIFY_IS_APPROX(dm4=refMat2*m3.transpose(), refMat4=refMat2*refMat3.transpose()); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3, refMat4=refMat2.transpose()*refMat3); - VERIFY_IS_APPROX(dm4=refMat2.transpose()*m3.transpose(), refMat4=refMat2.transpose()*refMat3.transpose()); - - VERIFY_IS_APPROX(m3=m3*m3, refMat3=refMat3*refMat3); - } - - // test matrix - diagonal product - if(false) // it compiles, but the precision is terrible. probably doesn't matter in this branch.... - { - DenseMatrix refM2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM3 = DenseMatrix::Zero(rows, rows); - DiagonalMatrix d1(DenseVector::Random(rows)); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - initSparse(density, refM2, m2); - initSparse(density, refM3, m3); - VERIFY_IS_APPROX(m3=m2*d1, refM3=refM2*d1); - VERIFY_IS_APPROX(m3=m2.transpose()*d1, refM3=refM2.transpose()*d1); - VERIFY_IS_APPROX(m3=d1*m2, refM3=d1*refM2); - VERIFY_IS_APPROX(m3=d1*m2.transpose(), refM3=d1 * refM2.transpose()); - } - - // test self adjoint products - { - DenseMatrix b = DenseMatrix::Random(rows, rows); - DenseMatrix x = DenseMatrix::Random(rows, rows); - DenseMatrix refX = DenseMatrix::Random(rows, rows); - DenseMatrix refUp = DenseMatrix::Zero(rows, rows); - DenseMatrix refLo = DenseMatrix::Zero(rows, rows); - DenseMatrix refS = DenseMatrix::Zero(rows, rows); - SparseMatrixType mUp(rows, rows); - SparseMatrixType mLo(rows, rows); - SparseMatrixType mS(rows, rows); - do { - initSparse(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular); - } while (refUp.isZero()); - refLo = refUp.transpose().conjugate(); - mLo = mUp.transpose().conjugate(); - refS = refUp + refLo; - refS.diagonal() *= 0.5; - mS = mUp + mLo; - for (int k=0; k()*b, refX=refS*b); - VERIFY_IS_APPROX(x=mLo.template marked()*b, refX=refS*b); - VERIFY_IS_APPROX(x=mS.template marked()*b, refX=refS*b); - } - -} - -void test_eigen2_sparse_product() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_product(SparseMatrix(8, 8)) ); - CALL_SUBTEST_2( sparse_product(SparseMatrix >(16, 16)) ); - CALL_SUBTEST_1( sparse_product(SparseMatrix(33, 33)) ); - - CALL_SUBTEST_3( sparse_product(DynamicSparseMatrix(8, 8)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_solvers.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_solvers.cpp deleted file mode 100644 index 3aef27ab4..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_solvers.cpp +++ /dev/null @@ -1,200 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void -initSPD(double density, - Matrix& refMat, - SparseMatrix& sparseMat) -{ - Matrix aux(refMat.rows(),refMat.cols()); - initSparse(density,refMat,sparseMat); - refMat = refMat * refMat.adjoint(); - for (int k=0; k<2; ++k) - { - initSparse(density,aux,sparseMat,ForceNonZeroDiag); - refMat += aux * aux.adjoint(); - } - sparseMat.startFill(); - for (int j=0 ; j void sparse_solvers(int rows, int cols) -{ - double density = std::max(8./(rows*cols), 0.01); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - // Scalar eps = 1e-6; - - DenseVector vec1 = DenseVector::Random(rows); - - std::vector zeroCoords; - std::vector nonzeroCoords; - - // test triangular solver - { - DenseVector vec2 = vec1, vec3 = vec1; - SparseMatrix m2(rows, cols); - DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); - - // lower - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().solveTriangular(vec2), - m2.template marked().solveTriangular(vec3)); - - // lower - transpose - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().transpose().solveTriangular(vec2), - m2.template marked().transpose().solveTriangular(vec3)); - - // upper - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().solveTriangular(vec2), - m2.template marked().solveTriangular(vec3)); - - // upper - transpose - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords); - VERIFY_IS_APPROX(refMat2.template marked().transpose().solveTriangular(vec2), - m2.template marked().transpose().solveTriangular(vec3)); - } - - // test LLT - { - // TODO fix the issue with complex (see SparseLLT::solveInPlace) - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSPD(density, refMat2, m2); - - refMat2.llt().solve(b, &refX); - typedef SparseMatrix SparseSelfAdjointMatrix; - if (!NumTraits::IsComplex) - { - x = b; - SparseLLT (m2).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: default"); - } - #ifdef EIGEN_CHOLMOD_SUPPORT - x = b; - SparseLLT(m2).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: cholmod"); - #endif - if (!NumTraits::IsComplex) - { - #ifdef EIGEN_TAUCS_SUPPORT - x = b; - SparseLLT(m2,IncompleteFactorization).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (IncompleteFactorization)"); - x = b; - SparseLLT(m2,SupernodalMultifrontal).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (SupernodalMultifrontal)"); - x = b; - SparseLLT(m2,SupernodalLeftLooking).solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LLT: taucs (SupernodalLeftLooking)"); - #endif - } - } - - // test LDLT - if (!NumTraits::IsComplex) - { - // TODO fix the issue with complex (see SparseLDLT::solveInPlace) - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - //initSPD(density, refMat2, m2); - initSparse(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, 0, 0); - refMat2 += refMat2.adjoint(); - refMat2.diagonal() *= 0.5; - - refMat2.ldlt().solve(b, &refX); - typedef SparseMatrix SparseSelfAdjointMatrix; - x = b; - SparseLDLT ldlt(m2); - if (ldlt.succeeded()) - ldlt.solveInPlace(x); - VERIFY(refX.isApprox(x,test_precision()) && "LDLT: default"); - } - - // test LU - { - static int count = 0; - SparseMatrix m2(rows, cols); - DenseMatrix refMat2(rows, cols); - - DenseVector b = DenseVector::Random(cols); - DenseVector refX(cols), x(cols); - - initSparse(density, refMat2, m2, ForceNonZeroDiag, &zeroCoords, &nonzeroCoords); - - LU refLu(refMat2); - refLu.solve(b, &refX); - #if defined(EIGEN_SUPERLU_SUPPORT) || defined(EIGEN_UMFPACK_SUPPORT) - Scalar refDet = refLu.determinant(); - #endif - x.setZero(); - // // SparseLU > (m2).solve(b,&x); - // // VERIFY(refX.isApprox(x,test_precision()) && "LU: default"); - #ifdef EIGEN_SUPERLU_SUPPORT - { - x.setZero(); - SparseLU,SuperLU> slu(m2); - if (slu.succeeded()) - { - if (slu.solve(b,&x)) { - VERIFY(refX.isApprox(x,test_precision()) && "LU: SuperLU"); - } - // std::cerr << refDet << " == " << slu.determinant() << "\n"; - if (count==0) { - VERIFY_IS_APPROX(refDet,slu.determinant()); // FIXME det is not very stable for complex - } - } - } - #endif - #ifdef EIGEN_UMFPACK_SUPPORT - { - // check solve - x.setZero(); - SparseLU,UmfPack> slu(m2); - if (slu.succeeded()) { - if (slu.solve(b,&x)) { - if (count==0) { - VERIFY(refX.isApprox(x,test_precision()) && "LU: umfpack"); // FIXME solve is not very stable for complex - } - } - VERIFY_IS_APPROX(refDet,slu.determinant()); - // TODO check the extracted data - //std::cerr << slu.matrixL() << "\n"; - } - } - #endif - count++; - } - -} - -void test_eigen2_sparse_solvers() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( sparse_solvers(8, 8) ); - CALL_SUBTEST_2( sparse_solvers >(16, 16) ); - CALL_SUBTEST_1( sparse_solvers(101, 101) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_vector.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_vector.cpp deleted file mode 100644 index e6d2d77a1..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sparse_vector.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "sparse.h" - -template void sparse_vector(int rows, int cols) -{ - double densityMat = std::max(8./(rows*cols), 0.01); - double densityVec = std::max(8./float(rows), 0.1); - typedef Matrix DenseMatrix; - typedef Matrix DenseVector; - typedef SparseVector SparseVectorType; - typedef SparseMatrix SparseMatrixType; - Scalar eps = 1e-6; - - SparseMatrixType m1(rows,cols); - SparseVectorType v1(rows), v2(rows), v3(rows); - DenseMatrix refM1 = DenseMatrix::Zero(rows, cols); - DenseVector refV1 = DenseVector::Random(rows), - refV2 = DenseVector::Random(rows), - refV3 = DenseVector::Random(rows); - - std::vector zerocoords, nonzerocoords; - initSparse(densityVec, refV1, v1, &zerocoords, &nonzerocoords); - initSparse(densityMat, refM1, m1); - - initSparse(densityVec, refV2, v2); - initSparse(densityVec, refV3, v3); - - Scalar s1 = ei_random(); - - // test coeff and coeffRef - for (unsigned int i=0; i(8, 8) ); - CALL_SUBTEST_2( sparse_vector >(16, 16) ); - CALL_SUBTEST_1( sparse_vector(299, 535) ); - } -} - diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_stdvector.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_stdvector.cpp deleted file mode 100644 index 6ab05c20a..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_stdvector.cpp +++ /dev/null @@ -1,148 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include -#include "main.h" -#include - -template -void check_stdvector_matrix(const MatrixType& m) -{ - int rows = m.rows(); - int cols = m.cols(); - MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - std::vector > v(10, MatrixType(rows,cols)), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(MatrixType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - MatrixType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -void check_stdvector_transform(const TransformType&) -{ - typedef typename TransformType::MatrixType MatrixType; - TransformType x(MatrixType::Random()), y(MatrixType::Random()); - std::vector > v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(TransformType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - TransformType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -void check_stdvector_quaternion(const QuaternionType&) -{ - typedef typename QuaternionType::Coefficients Coefficients; - QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - std::vector > v(10), w(20, y); - v[5] = x; - w[6] = v[5]; - VERIFY_IS_APPROX(w[6], v[5]); - v = w; - for(int i = 0; i < 20; i++) - { - VERIFY_IS_APPROX(w[i], v[i]); - } - - v.resize(21); - v[20] = x; - VERIFY_IS_APPROX(v[20], x); - v.resize(22,y); - VERIFY_IS_APPROX(v[21], y); - v.push_back(x); - VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(QuaternionType)); - - // do a lot of push_back such that the vector gets internally resized - // (with memory reallocation) - QuaternionType* ref = &w[0]; - for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) - v.push_back(w[i%w.size()]); - for(unsigned int i=23; i -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -// check minor separately in order to avoid the possible creation of a zero-sized -// array. Comes from a compilation error with gcc-3.4 or gcc-4 with -ansi -pedantic. -// Another solution would be to declare the array like this: T m_data[Size==0?1:Size]; in ei_matrix_storage -// but this is probably not bad to raise such an error at compile time... -template struct CheckMinor -{ - typedef Matrix MatrixType; - CheckMinor(MatrixType& m1, int r1, int c1) - { - int rows = m1.rows(); - int cols = m1.cols(); - - Matrix mi = m1.minor(0,0).eval(); - VERIFY_IS_APPROX(mi, m1.block(1,1,rows-1,cols-1)); - mi = m1.minor(r1,c1); - VERIFY_IS_APPROX(mi.transpose(), m1.transpose().minor(c1,r1)); - //check operator(), both constant and non-constant, on minor() - m1.minor(r1,c1)(0,0) = m1.minor(0,0)(0,0); - } -}; - -template struct CheckMinor -{ - typedef Matrix MatrixType; - CheckMinor(MatrixType&, int, int) {} -}; - -template void submatrices(const MatrixType& m) -{ - /* this test covers the following files: - Row.h Column.h Block.h Minor.h DiagonalCoeffs.h - */ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef Matrix VectorType; - typedef Matrix RowVectorType; - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - ones = MatrixType::Ones(rows, cols), - square = Matrix - ::Random(rows, rows); - VectorType v1 = VectorType::Random(rows); - - Scalar s1 = ei_random(); - - int r1 = ei_random(0,rows-1); - int r2 = ei_random(r1,rows-1); - int c1 = ei_random(0,cols-1); - int c2 = ei_random(c1,cols-1); - - //check row() and col() - VERIFY_IS_APPROX(m1.col(c1).transpose(), m1.transpose().row(c1)); - VERIFY_IS_APPROX(square.row(r1).eigen2_dot(m1.col(c1)), (square.lazy() * m1.conjugate())(r1,c1)); - //check operator(), both constant and non-constant, on row() and col() - m1.row(r1) += s1 * m1.row(r2); - m1.col(c1) += s1 * m1.col(c2); - - //check block() - Matrix b1(1,1); b1(0,0) = m1(r1,c1); - RowVectorType br1(m1.block(r1,0,1,cols)); - VectorType bc1(m1.block(0,c1,rows,1)); - VERIFY_IS_APPROX(b1, m1.block(r1,c1,1,1)); - VERIFY_IS_APPROX(m1.row(r1), br1); - VERIFY_IS_APPROX(m1.col(c1), bc1); - //check operator(), both constant and non-constant, on block() - m1.block(r1,c1,r2-r1+1,c2-c1+1) = s1 * m2.block(0, 0, r2-r1+1,c2-c1+1); - m1.block(r1,c1,r2-r1+1,c2-c1+1)(r2-r1,c2-c1) = m2.block(0, 0, r2-r1+1,c2-c1+1)(0,0); - - //check minor() - CheckMinor checkminor(m1,r1,c1); - - //check diagonal() - VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal()); - m2.diagonal() = 2 * m1.diagonal(); - m2.diagonal()[0] *= 3; - VERIFY_IS_APPROX(m2.diagonal()[0], static_cast(6) * m1.diagonal()[0]); - - enum { - BlockRows = EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::RowsAtCompileTime,2), - BlockCols = EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::ColsAtCompileTime,5) - }; - if (rows>=5 && cols>=8) - { - // test fixed block() as lvalue - m1.template block(1,1) *= s1; - // test operator() on fixed block() both as constant and non-constant - m1.template block(1,1)(0, 3) = m1.template block<2,5>(1,1)(1,2); - // check that fixed block() and block() agree - Matrix b = m1.template block(3,3); - VERIFY_IS_APPROX(b, m1.block(3,3,BlockRows,BlockCols)); - } - - if (rows>2) - { - // test sub vectors - VERIFY_IS_APPROX(v1.template start<2>(), v1.block(0,0,2,1)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.start(2)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.segment(0,2)); - VERIFY_IS_APPROX(v1.template start<2>(), v1.template segment<2>(0)); - int i = rows-2; - VERIFY_IS_APPROX(v1.template end<2>(), v1.block(i,0,2,1)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.end(2)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.segment(i,2)); - VERIFY_IS_APPROX(v1.template end<2>(), v1.template segment<2>(i)); - i = ei_random(0,rows-2); - VERIFY_IS_APPROX(v1.segment(i,2), v1.template segment<2>(i)); - } - - // stress some basic stuffs with block matrices - VERIFY(ei_real(ones.col(c1).sum()) == RealScalar(rows)); - VERIFY(ei_real(ones.row(r1).sum()) == RealScalar(cols)); - - VERIFY(ei_real(ones.col(c1).eigen2_dot(ones.col(c2))) == RealScalar(rows)); - VERIFY(ei_real(ones.row(r1).eigen2_dot(ones.row(r2))) == RealScalar(cols)); -} - -void test_eigen2_submatrices() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( submatrices(Matrix()) ); - CALL_SUBTEST_2( submatrices(Matrix4d()) ); - CALL_SUBTEST_3( submatrices(MatrixXcf(3, 3)) ); - CALL_SUBTEST_4( submatrices(MatrixXi(8, 12)) ); - CALL_SUBTEST_5( submatrices(MatrixXcd(20, 20)) ); - CALL_SUBTEST_6( submatrices(MatrixXf(20, 20)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sum.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sum.cpp deleted file mode 100644 index b47057caa..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_sum.cpp +++ /dev/null @@ -1,71 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void matrixSum(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols); - - VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1)); - VERIFY_IS_APPROX(MatrixType::Ones(rows, cols).sum(), Scalar(float(rows*cols))); // the float() here to shut up excessive MSVC warning about int->complex conversion being lossy - Scalar x = Scalar(0); - for(int i = 0; i < rows; i++) for(int j = 0; j < cols; j++) x += m1(i,j); - VERIFY_IS_APPROX(m1.sum(), x); -} - -template void vectorSum(const VectorType& w) -{ - typedef typename VectorType::Scalar Scalar; - int size = w.size(); - - VectorType v = VectorType::Random(size); - for(int i = 1; i < size; i++) - { - Scalar s = Scalar(0); - for(int j = 0; j < i; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.start(i).sum()); - } - - for(int i = 0; i < size-1; i++) - { - Scalar s = Scalar(0); - for(int j = i; j < size; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.end(size-i).sum()); - } - - for(int i = 0; i < size/2; i++) - { - Scalar s = Scalar(0); - for(int j = i; j < size-i; j++) s += v[j]; - VERIFY_IS_APPROX(s, v.segment(i, size-2*i).sum()); - } -} - -void test_eigen2_sum() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( matrixSum(Matrix()) ); - CALL_SUBTEST_2( matrixSum(Matrix2f()) ); - CALL_SUBTEST_3( matrixSum(Matrix4d()) ); - CALL_SUBTEST_4( matrixSum(MatrixXcf(3, 3)) ); - CALL_SUBTEST_5( matrixSum(MatrixXf(8, 12)) ); - CALL_SUBTEST_6( matrixSum(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_5( vectorSum(VectorXf(5)) ); - CALL_SUBTEST_7( vectorSum(VectorXd(10)) ); - CALL_SUBTEST_5( vectorSum(VectorXf(33)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_svd.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_svd.cpp deleted file mode 100644 index d4689a56f..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_svd.cpp +++ /dev/null @@ -1,87 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include - -template void svd(const MatrixType& m) -{ - /* this test covers the following files: - SVD.h - */ - int rows = m.rows(); - int cols = m.cols(); - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - MatrixType a = MatrixType::Random(rows,cols); - Matrix b = - Matrix::Random(rows,1); - Matrix x(cols,1), x2(cols,1); - - RealScalar largerEps = test_precision(); - if (ei_is_same_type::ret) - largerEps = 1e-3f; - - { - SVD svd(a); - MatrixType sigma = MatrixType::Zero(rows,cols); - MatrixType matU = MatrixType::Zero(rows,rows); - sigma.block(0,0,cols,cols) = svd.singularValues().asDiagonal(); - matU.block(0,0,rows,cols) = svd.matrixU(); - VERIFY_IS_APPROX(a, matU * sigma * svd.matrixV().transpose()); - } - - - if (rows==cols) - { - if (ei_is_same_type::ret) - { - MatrixType a1 = MatrixType::Random(rows,cols); - a += a * a.adjoint() + a1 * a1.adjoint(); - } - SVD svd(a); - svd.solve(b, &x); - VERIFY_IS_APPROX(a * x,b); - } - - - if(rows==cols) - { - SVD svd(a); - MatrixType unitary, positive; - svd.computeUnitaryPositive(&unitary, &positive); - VERIFY_IS_APPROX(unitary * unitary.adjoint(), MatrixType::Identity(unitary.rows(),unitary.rows())); - VERIFY_IS_APPROX(positive, positive.adjoint()); - for(int i = 0; i < rows; i++) VERIFY(positive.diagonal()[i] >= 0); // cheap necessary (not sufficient) condition for positivity - VERIFY_IS_APPROX(unitary*positive, a); - - svd.computePositiveUnitary(&positive, &unitary); - VERIFY_IS_APPROX(unitary * unitary.adjoint(), MatrixType::Identity(unitary.rows(),unitary.rows())); - VERIFY_IS_APPROX(positive, positive.adjoint()); - for(int i = 0; i < rows; i++) VERIFY(positive.diagonal()[i] >= 0); // cheap necessary (not sufficient) condition for positivity - VERIFY_IS_APPROX(positive*unitary, a); - } -} - -void test_eigen2_svd() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( svd(Matrix3f()) ); - CALL_SUBTEST_2( svd(Matrix4d()) ); - CALL_SUBTEST_3( svd(MatrixXf(7,7)) ); - CALL_SUBTEST_4( svd(MatrixXd(14,7)) ); - // complex are not implemented yet -// CALL_SUBTEST( svd(MatrixXcd(6,6)) ); -// CALL_SUBTEST( svd(MatrixXcf(3,3)) ); - SVD s; - MatrixXf m = MatrixXf::Random(10,1); - s.compute(m); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_swap.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_swap.cpp deleted file mode 100644 index f3a8846d9..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_swap.cpp +++ /dev/null @@ -1,83 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2009 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#define EIGEN_NO_STATIC_ASSERT -#include "main.h" - -template -struct other_matrix_type -{ - typedef int type; -}; - -template -struct other_matrix_type > -{ - typedef Matrix<_Scalar, _Rows, _Cols, _Options^RowMajor, _MaxRows, _MaxCols> type; -}; - -template void swap(const MatrixType& m) -{ - typedef typename other_matrix_type::type OtherMatrixType; - typedef typename MatrixType::Scalar Scalar; - - ei_assert((!ei_is_same_type::ret)); - int rows = m.rows(); - int cols = m.cols(); - - // construct 3 matrix guaranteed to be distinct - MatrixType m1 = MatrixType::Random(rows,cols); - MatrixType m2 = MatrixType::Random(rows,cols) + Scalar(100) * MatrixType::Identity(rows,cols); - OtherMatrixType m3 = OtherMatrixType::Random(rows,cols) + Scalar(200) * OtherMatrixType::Identity(rows,cols); - - MatrixType m1_copy = m1; - MatrixType m2_copy = m2; - OtherMatrixType m3_copy = m3; - - // test swapping 2 matrices of same type - m1.swap(m2); - VERIFY_IS_APPROX(m1,m2_copy); - VERIFY_IS_APPROX(m2,m1_copy); - m1 = m1_copy; - m2 = m2_copy; - - // test swapping 2 matrices of different types - m1.swap(m3); - VERIFY_IS_APPROX(m1,m3_copy); - VERIFY_IS_APPROX(m3,m1_copy); - m1 = m1_copy; - m3 = m3_copy; - - // test swapping matrix with expression - m1.swap(m2.block(0,0,rows,cols)); - VERIFY_IS_APPROX(m1,m2_copy); - VERIFY_IS_APPROX(m2,m1_copy); - m1 = m1_copy; - m2 = m2_copy; - - // test swapping two expressions of different types - m1.transpose().swap(m3.transpose()); - VERIFY_IS_APPROX(m1,m3_copy); - VERIFY_IS_APPROX(m3,m1_copy); - m1 = m1_copy; - m3 = m3_copy; - - // test assertion on mismatching size -- matrix case - VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); - // test assertion on mismatching size -- xpr case - VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); -} - -void test_eigen2_swap() -{ - CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization - CALL_SUBTEST_1( swap(Matrix4d()) ); // fixed size, possible vectorization - CALL_SUBTEST_1( swap(MatrixXd(3,3)) ); // dyn size, no vectorization - CALL_SUBTEST_1( swap(MatrixXf(30,30)) ); // dyn size, possible vectorization -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_triangular.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_triangular.cpp deleted file mode 100644 index 6f17b7dff..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_triangular.cpp +++ /dev/null @@ -1,148 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void triangular(const MatrixType& m) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::Real RealScalar; - - RealScalar largerEps = 10*test_precision(); - - int rows = m.rows(); - int cols = m.cols(); - - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols), - m4(rows, cols), - r1(rows, cols), - r2(rows, cols); - - MatrixType m1up = m1.template part(); - MatrixType m2up = m2.template part(); - - if (rows*cols>1) - { - VERIFY(m1up.isUpperTriangular()); - VERIFY(m2up.transpose().isLowerTriangular()); - VERIFY(!m2.isLowerTriangular()); - } - -// VERIFY_IS_APPROX(m1up.transpose() * m2, m1.upper().transpose().lower() * m2); - - // test overloaded operator+= - r1.setZero(); - r2.setZero(); - r1.template part() += m1; - r2 += m1up; - VERIFY_IS_APPROX(r1,r2); - - // test overloaded operator= - m1.setZero(); - m1.template part() = (m2.transpose() * m2).lazy(); - m3 = m2.transpose() * m2; - VERIFY_IS_APPROX(m3.template part().transpose(), m1); - - // test overloaded operator= - m1.setZero(); - m1.template part() = (m2.transpose() * m2).lazy(); - VERIFY_IS_APPROX(m3.template part(), m1); - - VERIFY_IS_APPROX(m3.template part(), m3.diagonal().asDiagonal()); - - m1 = MatrixType::Random(rows, cols); - for (int i=0; i(); - - Transpose trm4(m4); - // test back and forward subsitution - m3 = m1.template part(); - VERIFY(m3.template marked().solveTriangular(m3).cwise().abs().isIdentity(test_precision())); - VERIFY(m3.transpose().template marked() - .solveTriangular(m3.transpose()).cwise().abs().isIdentity(test_precision())); - // check M * inv(L) using in place API - m4 = m3; - m3.transpose().template marked().solveTriangularInPlace(trm4); - VERIFY(m4.cwise().abs().isIdentity(test_precision())); - - m3 = m1.template part(); - VERIFY(m3.template marked().solveTriangular(m3).cwise().abs().isIdentity(test_precision())); - VERIFY(m3.transpose().template marked() - .solveTriangular(m3.transpose()).cwise().abs().isIdentity(test_precision())); - // check M * inv(U) using in place API - m4 = m3; - m3.transpose().template marked().solveTriangularInPlace(trm4); - VERIFY(m4.cwise().abs().isIdentity(test_precision())); - - m3 = m1.template part(); - VERIFY(m2.isApprox(m3 * (m3.template marked().solveTriangular(m2)), largerEps)); - m3 = m1.template part(); - VERIFY(m2.isApprox(m3 * (m3.template marked().solveTriangular(m2)), largerEps)); - - VERIFY((m1.template part() * m2.template part()).isUpperTriangular()); - - // test swap - m1.setOnes(); - m2.setZero(); - m2.template part().swap(m1); - m3.setZero(); - m3.template part().setOnes(); - VERIFY_IS_APPROX(m2,m3); - -} - -void selfadjoint() -{ - Matrix2i m; - m << 1, 2, - 3, 4; - - Matrix2i m1 = Matrix2i::Zero(); - m1.part() = m; - Matrix2i ref1; - ref1 << 1, 2, - 2, 4; - VERIFY(m1 == ref1); - - Matrix2i m2 = Matrix2i::Zero(); - m2.part() = m.part(); - Matrix2i ref2; - ref2 << 1, 2, - 2, 4; - VERIFY(m2 == ref2); - - Matrix2i m3 = Matrix2i::Zero(); - m3.part() = m.part(); - Matrix2i ref3; - ref3 << 1, 0, - 0, 4; - VERIFY(m3 == ref3); - - // example inspired from bug 159 - int array[] = {1, 2, 3, 4}; - Matrix2i::Map(array).part() = Matrix2i::Random().part(); - - std::cout << "hello\n" << array << std::endl; -} - -void test_eigen2_triangular() -{ - CALL_SUBTEST_8( selfadjoint() ); - for(int i = 0; i < g_repeat ; i++) { - CALL_SUBTEST_1( triangular(Matrix()) ); - CALL_SUBTEST_2( triangular(Matrix()) ); - CALL_SUBTEST_3( triangular(Matrix3d()) ); - CALL_SUBTEST_4( triangular(MatrixXcf(4, 4)) ); - CALL_SUBTEST_5( triangular(Matrix,8, 8>()) ); - CALL_SUBTEST_6( triangular(MatrixXd(17,17)) ); - CALL_SUBTEST_7( triangular(Matrix(5, 5)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_unalignedassert.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_unalignedassert.cpp deleted file mode 100644 index d10b6f538..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_unalignedassert.cpp +++ /dev/null @@ -1,116 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -struct Good1 -{ - MatrixXd m; // good: m will allocate its own array, taking care of alignment. - Good1() : m(20,20) {} -}; - -struct Good2 -{ - Matrix3d m; // good: m's size isn't a multiple of 16 bytes, so m doesn't have to be aligned -}; - -struct Good3 -{ - Vector2f m; // good: same reason -}; - -struct Bad4 -{ - Vector2d m; // bad: sizeof(m)%16==0 so alignment is required -}; - -struct Bad5 -{ - Matrix m; // bad: same reason -}; - -struct Bad6 -{ - Matrix m; // bad: same reason -}; - -struct Good7 -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - Vector2d m; - float f; // make the struct have sizeof%16!=0 to make it a little more tricky when we allow an array of 2 such objects -}; - -struct Good8 -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - float f; // try the f at first -- the EIGEN_ALIGN_128 attribute of m should make that still work - Matrix4f m; -}; - -struct Good9 -{ - Matrix m; // good: no alignment requested - float f; -}; - -template struct Depends -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(Align) - Vector2d m; - float f; -}; - -template -void check_unalignedassert_good() -{ - T *x, *y; - x = new T; - delete x; - y = new T[2]; - delete[] y; -} - -#if EIGEN_ARCH_WANTS_ALIGNMENT -template -void check_unalignedassert_bad() -{ - float buf[sizeof(T)+16]; - float *unaligned = buf; - while((reinterpret_cast(unaligned)&0xf)==0) ++unaligned; // make sure unaligned is really unaligned - T *x = ::new(static_cast(unaligned)) T; - x->~T(); -} -#endif - -void unalignedassert() -{ - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good(); -#if EIGEN_ARCH_WANTS_ALIGNMENT - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); - VERIFY_RAISES_ASSERT(check_unalignedassert_bad()); -#endif - - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good(); - check_unalignedassert_good >(); - -#if EIGEN_ARCH_WANTS_ALIGNMENT - VERIFY_RAISES_ASSERT(check_unalignedassert_bad >()); -#endif -} - -void test_eigen2_unalignedassert() -{ - CALL_SUBTEST(unalignedassert()); -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_visitor.cpp b/gtsam/3rdparty/Eigen/test/eigen2/eigen2_visitor.cpp deleted file mode 100644 index 4781991de..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_visitor.cpp +++ /dev/null @@ -1,116 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. -// -// Copyright (C) 2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" - -template void matrixVisitor(const MatrixType& p) -{ - typedef typename MatrixType::Scalar Scalar; - - int rows = p.rows(); - int cols = p.cols(); - - // construct a random matrix where all coefficients are different - MatrixType m; - m = MatrixType::Random(rows, cols); - for(int i = 0; i < m.size(); i++) - for(int i2 = 0; i2 < i; i2++) - while(m(i) == m(i2)) // yes, == - m(i) = ei_random(); - - Scalar minc = Scalar(1000), maxc = Scalar(-1000); - int minrow=0,mincol=0,maxrow=0,maxcol=0; - for(int j = 0; j < cols; j++) - for(int i = 0; i < rows; i++) - { - if(m(i,j) < minc) - { - minc = m(i,j); - minrow = i; - mincol = j; - } - if(m(i,j) > maxc) - { - maxc = m(i,j); - maxrow = i; - maxcol = j; - } - } - int eigen_minrow, eigen_mincol, eigen_maxrow, eigen_maxcol; - Scalar eigen_minc, eigen_maxc; - eigen_minc = m.minCoeff(&eigen_minrow,&eigen_mincol); - eigen_maxc = m.maxCoeff(&eigen_maxrow,&eigen_maxcol); - VERIFY(minrow == eigen_minrow); - VERIFY(maxrow == eigen_maxrow); - VERIFY(mincol == eigen_mincol); - VERIFY(maxcol == eigen_maxcol); - VERIFY_IS_APPROX(minc, eigen_minc); - VERIFY_IS_APPROX(maxc, eigen_maxc); - VERIFY_IS_APPROX(minc, m.minCoeff()); - VERIFY_IS_APPROX(maxc, m.maxCoeff()); -} - -template void vectorVisitor(const VectorType& w) -{ - typedef typename VectorType::Scalar Scalar; - - int size = w.size(); - - // construct a random vector where all coefficients are different - VectorType v; - v = VectorType::Random(size); - for(int i = 0; i < size; i++) - for(int i2 = 0; i2 < i; i2++) - while(v(i) == v(i2)) // yes, == - v(i) = ei_random(); - - Scalar minc = Scalar(1000), maxc = Scalar(-1000); - int minidx=0,maxidx=0; - for(int i = 0; i < size; i++) - { - if(v(i) < minc) - { - minc = v(i); - minidx = i; - } - if(v(i) > maxc) - { - maxc = v(i); - maxidx = i; - } - } - int eigen_minidx, eigen_maxidx; - Scalar eigen_minc, eigen_maxc; - eigen_minc = v.minCoeff(&eigen_minidx); - eigen_maxc = v.maxCoeff(&eigen_maxidx); - VERIFY(minidx == eigen_minidx); - VERIFY(maxidx == eigen_maxidx); - VERIFY_IS_APPROX(minc, eigen_minc); - VERIFY_IS_APPROX(maxc, eigen_maxc); - VERIFY_IS_APPROX(minc, v.minCoeff()); - VERIFY_IS_APPROX(maxc, v.maxCoeff()); -} - -void test_eigen2_visitor() -{ - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_1( matrixVisitor(Matrix()) ); - CALL_SUBTEST_2( matrixVisitor(Matrix2f()) ); - CALL_SUBTEST_3( matrixVisitor(Matrix4d()) ); - CALL_SUBTEST_4( matrixVisitor(MatrixXd(8, 12)) ); - CALL_SUBTEST_5( matrixVisitor(Matrix(20, 20)) ); - CALL_SUBTEST_6( matrixVisitor(MatrixXi(8, 12)) ); - } - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_7( vectorVisitor(Vector4f()) ); - CALL_SUBTEST_4( vectorVisitor(VectorXd(10)) ); - CALL_SUBTEST_4( vectorVisitor(RowVectorXd(10)) ); - CALL_SUBTEST_8( vectorVisitor(VectorXf(33)) ); - } -} diff --git a/gtsam/3rdparty/Eigen/test/eigen2/gsl_helper.h b/gtsam/3rdparty/Eigen/test/eigen2/gsl_helper.h deleted file mode 100644 index d1d854533..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/gsl_helper.h +++ /dev/null @@ -1,175 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_GSL_HELPER -#define EIGEN_GSL_HELPER - -#include - -#include -#include -#include -#include -#include -#include - -namespace Eigen { - -template::IsComplex> struct GslTraits -{ - typedef gsl_matrix* Matrix; - typedef gsl_vector* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_alloc(size); } - static void free(Matrix& m) { gsl_matrix_free(m); m=0; } - static void free(Vector& m) { gsl_vector_free(m); m=0; } - static void prod(const Matrix& m, const Vector& v, Vector& x) { gsl_blas_dgemv(CblasNoTrans,1,m,v,0,x); } - static void cholesky(Matrix& m) { gsl_linalg_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_cholesky_solve(m,b,x); } - static void eigen_symm(const Matrix& m, Vector& eval, Matrix& evec) - { - gsl_eigen_symmv_workspace * w = gsl_eigen_symmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_memcpy(a, m); - gsl_eigen_symmv(a,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_symmv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, Vector& eval, Matrix& evec) - { - gsl_eigen_gensymmv_workspace * w = gsl_eigen_gensymmv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_memcpy(a, m); - gsl_matrix_memcpy(b, _b); - gsl_eigen_gensymmv(a,b,eval,evec,w); - gsl_eigen_symmv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_gensymmv_free(w); - free(a); - } -}; - -template struct GslTraits -{ - typedef gsl_matrix_complex* Matrix; - typedef gsl_vector_complex* Vector; - static Matrix createMatrix(int rows, int cols) { return gsl_matrix_complex_alloc(rows,cols); } - static Vector createVector(int size) { return gsl_vector_complex_alloc(size); } - static void free(Matrix& m) { gsl_matrix_complex_free(m); m=0; } - static void free(Vector& m) { gsl_vector_complex_free(m); m=0; } - static void cholesky(Matrix& m) { gsl_linalg_complex_cholesky_decomp(m); } - static void cholesky_solve(const Matrix& m, const Vector& b, Vector& x) { gsl_linalg_complex_cholesky_solve(m,b,x); } - static void prod(const Matrix& m, const Vector& v, Vector& x) - { gsl_blas_zgemv(CblasNoTrans,gsl_complex_rect(1,0),m,v,gsl_complex_rect(0,0),x); } - static void eigen_symm(const Matrix& m, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_hermv_workspace * w = gsl_eigen_hermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_eigen_hermv(a,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_hermv_free(w); - free(a); - } - static void eigen_symm_gen(const Matrix& m, const Matrix& _b, gsl_vector* &eval, Matrix& evec) - { - gsl_eigen_genhermv_workspace * w = gsl_eigen_genhermv_alloc(m->size1); - Matrix a = createMatrix(m->size1, m->size2); - Matrix b = createMatrix(_b->size1, _b->size2); - gsl_matrix_complex_memcpy(a, m); - gsl_matrix_complex_memcpy(b, _b); - gsl_eigen_genhermv(a,b,eval,evec,w); - gsl_eigen_hermv_sort(eval, evec, GSL_EIGEN_SORT_VAL_ASC); - gsl_eigen_genhermv_free(w); - free(a); - } -}; - -template -void convert(const MatrixType& m, gsl_matrix* &res) -{ -// if (res) -// gsl_matrix_free(res); - res = gsl_matrix_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector* &res) -{ - if (res) gsl_vector_free(res); - res = gsl_vector_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector* m, VectorType& res) -{ - res.resize (m->size); - for (int i=0 ; i -void convert(const MatrixType& m, gsl_matrix_complex* &res) -{ - res = gsl_matrix_complex_alloc(m.rows(), m.cols()); - for (int i=0 ; i -void convert(const gsl_matrix_complex* m, MatrixType& res) -{ - res.resize(int(m->size1), int(m->size2)); - for (int i=0 ; i -void convert(const VectorType& m, gsl_vector_complex* &res) -{ - res = gsl_vector_complex_alloc(m.size()); - for (int i=0 ; i -void convert(const gsl_vector_complex* m, VectorType& res) -{ - res.resize(m->size); - for (int i=0 ; i -// Copyright (C) 2008 Gael Guennebaud -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include -#include -#include -#include -#include - -#ifndef EIGEN_TEST_FUNC -#error EIGEN_TEST_FUNC must be defined -#endif - -#define DEFAULT_REPEAT 10 - -namespace Eigen -{ - static std::vector g_test_stack; - static int g_repeat; -} - -#define EI_PP_MAKE_STRING2(S) #S -#define EI_PP_MAKE_STRING(S) EI_PP_MAKE_STRING2(S) - -#define EI_PP_CAT2(a,b) a ## b -#define EI_PP_CAT(a,b) EI_PP_CAT2(a,b) - -#ifndef EIGEN_NO_ASSERTION_CHECKING - - namespace Eigen - { - static const bool should_raise_an_assert = false; - - // Used to avoid to raise two exceptions at a time in which - // case the exception is not properly caught. - // This may happen when a second exceptions is raise in a destructor. - static bool no_more_assert = false; - - struct eigen_assert_exception - { - eigen_assert_exception(void) {} - ~eigen_assert_exception() { Eigen::no_more_assert = false; } - }; - } - - // If EIGEN_DEBUG_ASSERTS is defined and if no assertion is raised while - // one should have been, then the list of excecuted assertions is printed out. - // - // EIGEN_DEBUG_ASSERTS is not enabled by default as it - // significantly increases the compilation time - // and might even introduce side effects that would hide - // some memory errors. - #ifdef EIGEN_DEBUG_ASSERTS - - namespace Eigen - { - static bool ei_push_assert = false; - static std::vector eigen_assert_list; - } - - #define eigen_assert(a) \ - if( (!(a)) && (!no_more_assert) ) \ - { \ - Eigen::no_more_assert = true; \ - throw Eigen::eigen_assert_exception(); \ - } \ - else if (Eigen::ei_push_assert) \ - { \ - eigen_assert_list.push_back(std::string(EI_PP_MAKE_STRING(__FILE__)" ("EI_PP_MAKE_STRING(__LINE__)") : "#a) ); \ - } - - #define VERIFY_RAISES_ASSERT(a) \ - { \ - Eigen::no_more_assert = false; \ - try { \ - Eigen::eigen_assert_list.clear(); \ - Eigen::ei_push_assert = true; \ - a; \ - Eigen::ei_push_assert = false; \ - std::cerr << "One of the following asserts should have been raised:\n"; \ - for (uint ai=0 ; ai - - -#define VERIFY(a) do { if (!(a)) { \ - std::cerr << "Test " << g_test_stack.back() << " failed in "EI_PP_MAKE_STRING(__FILE__) << " (" << EI_PP_MAKE_STRING(__LINE__) << ")" \ - << std::endl << " " << EI_PP_MAKE_STRING(a) << std::endl << std::endl; \ - abort(); \ - } } while (0) - -#define VERIFY_IS_APPROX(a, b) VERIFY(test_ei_isApprox(a, b)) -#define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_ei_isApprox(a, b)) -#define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_ei_isMuchSmallerThan(a, b)) -#define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_ei_isMuchSmallerThan(a, b)) -#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b) VERIFY(test_ei_isApproxOrLessThan(a, b)) -#define VERIFY_IS_NOT_APPROX_OR_LESS_THAN(a, b) VERIFY(!test_ei_isApproxOrLessThan(a, b)) - -#define CALL_SUBTEST(FUNC) do { \ - g_test_stack.push_back(EI_PP_MAKE_STRING(FUNC)); \ - FUNC; \ - g_test_stack.pop_back(); \ - } while (0) - -namespace Eigen { - -template inline typename NumTraits::Real test_precision(); -template<> inline int test_precision() { return 0; } -template<> inline float test_precision() { return 1e-3f; } -template<> inline double test_precision() { return 1e-6; } -template<> inline float test_precision >() { return test_precision(); } -template<> inline double test_precision >() { return test_precision(); } -template<> inline long double test_precision() { return 1e-6; } - -inline bool test_ei_isApprox(const int& a, const int& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const int& a, const int& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const int& a, const int& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const float& a, const float& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const float& a, const float& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const float& a, const float& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const double& a, const double& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const double& a, const double& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const double& a, const double& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -inline bool test_ei_isApprox(const std::complex& a, const std::complex& b) -{ return ei_isApprox(a, b, test_precision >()); } -inline bool test_ei_isMuchSmallerThan(const std::complex& a, const std::complex& b) -{ return ei_isMuchSmallerThan(a, b, test_precision >()); } - -inline bool test_ei_isApprox(const std::complex& a, const std::complex& b) -{ return ei_isApprox(a, b, test_precision >()); } -inline bool test_ei_isMuchSmallerThan(const std::complex& a, const std::complex& b) -{ return ei_isMuchSmallerThan(a, b, test_precision >()); } - -inline bool test_ei_isApprox(const long double& a, const long double& b) -{ return ei_isApprox(a, b, test_precision()); } -inline bool test_ei_isMuchSmallerThan(const long double& a, const long double& b) -{ return ei_isMuchSmallerThan(a, b, test_precision()); } -inline bool test_ei_isApproxOrLessThan(const long double& a, const long double& b) -{ return ei_isApproxOrLessThan(a, b, test_precision()); } - -template -inline bool test_ei_isApprox(const Type1& a, const Type2& b) -{ - return a.isApprox(b, test_precision()); -} - -template -inline bool test_ei_isMuchSmallerThan(const MatrixBase& m1, - const MatrixBase& m2) -{ - return m1.isMuchSmallerThan(m2, test_precision::Scalar>()); -} - -template -inline bool test_ei_isMuchSmallerThan(const MatrixBase& m, - const typename NumTraits::Scalar>::Real& s) -{ - return m.isMuchSmallerThan(s, test_precision::Scalar>()); -} - -} // end namespace Eigen - -template struct GetDifferentType; - -template<> struct GetDifferentType { typedef double type; }; -template<> struct GetDifferentType { typedef float type; }; -template struct GetDifferentType > -{ typedef std::complex::type> type; }; - -// forward declaration of the main test function -void EI_PP_CAT(test_,EIGEN_TEST_FUNC)(); - -using namespace Eigen; - -#ifdef EIGEN_TEST_PART_1 -#define CALL_SUBTEST_1(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_1(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_2 -#define CALL_SUBTEST_2(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_2(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_3 -#define CALL_SUBTEST_3(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_3(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_4 -#define CALL_SUBTEST_4(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_4(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_5 -#define CALL_SUBTEST_5(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_5(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_6 -#define CALL_SUBTEST_6(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_6(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_7 -#define CALL_SUBTEST_7(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_7(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_8 -#define CALL_SUBTEST_8(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_8(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_9 -#define CALL_SUBTEST_9(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_9(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_10 -#define CALL_SUBTEST_10(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_10(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_11 -#define CALL_SUBTEST_11(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_11(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_12 -#define CALL_SUBTEST_12(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_12(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_13 -#define CALL_SUBTEST_13(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_13(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_14 -#define CALL_SUBTEST_14(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_14(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_15 -#define CALL_SUBTEST_15(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_15(FUNC) -#endif - -#ifdef EIGEN_TEST_PART_16 -#define CALL_SUBTEST_16(FUNC) CALL_SUBTEST(FUNC) -#else -#define CALL_SUBTEST_16(FUNC) -#endif - - - -int main(int argc, char *argv[]) -{ - bool has_set_repeat = false; - bool has_set_seed = false; - bool need_help = false; - unsigned int seed = 0; - int repeat = DEFAULT_REPEAT; - - for(int i = 1; i < argc; i++) - { - if(argv[i][0] == 'r') - { - if(has_set_repeat) - { - std::cout << "Argument " << argv[i] << " conflicting with a former argument" << std::endl; - return 1; - } - repeat = std::atoi(argv[i]+1); - has_set_repeat = true; - if(repeat <= 0) - { - std::cout << "Invalid \'repeat\' value " << argv[i]+1 << std::endl; - return 1; - } - } - else if(argv[i][0] == 's') - { - if(has_set_seed) - { - std::cout << "Argument " << argv[i] << " conflicting with a former argument" << std::endl; - return 1; - } - seed = int(std::strtoul(argv[i]+1, 0, 10)); - has_set_seed = true; - bool ok = seed!=0; - if(!ok) - { - std::cout << "Invalid \'seed\' value " << argv[i]+1 << std::endl; - return 1; - } - } - else - { - need_help = true; - } - } - - if(need_help) - { - std::cout << "This test application takes the following optional arguments:" << std::endl; - std::cout << " rN Repeat each test N times (default: " << DEFAULT_REPEAT << ")" << std::endl; - std::cout << " sN Use N as seed for random numbers (default: based on current time)" << std::endl; - return 1; - } - - if(!has_set_seed) seed = (unsigned int) std::time(NULL); - if(!has_set_repeat) repeat = DEFAULT_REPEAT; - - std::cout << "Initializing random number generator with seed " << seed << std::endl; - std::srand(seed); - std::cout << "Repeating each test " << repeat << " times" << std::endl; - - Eigen::g_repeat = repeat; - Eigen::g_test_stack.push_back(EI_PP_MAKE_STRING(EIGEN_TEST_FUNC)); - - EI_PP_CAT(test_,EIGEN_TEST_FUNC)(); - return 0; -} - - - diff --git a/gtsam/3rdparty/Eigen/test/eigen2/product.h b/gtsam/3rdparty/Eigen/test/eigen2/product.h deleted file mode 100644 index ae1b4bae4..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/product.h +++ /dev/null @@ -1,129 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2006-2008 Benoit Jacob -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#include "main.h" -#include -#include - -template -bool areNotApprox(const MatrixBase& m1, const MatrixBase& m2, typename Derived1::RealScalar epsilon = precision()) -{ - return !((m1-m2).cwise().abs2().maxCoeff() < epsilon * epsilon - * std::max(m1.cwise().abs2().maxCoeff(), m2.cwise().abs2().maxCoeff())); -} - -template void product(const MatrixType& m) -{ - /* this test covers the following files: - Identity.h Product.h - */ - - typedef typename MatrixType::Scalar Scalar; - typedef typename NumTraits::FloatingPoint FloatingPoint; - typedef Matrix RowVectorType; - typedef Matrix ColVectorType; - typedef Matrix RowSquareMatrixType; - typedef Matrix ColSquareMatrixType; - typedef Matrix OtherMajorMatrixType; - - int rows = m.rows(); - int cols = m.cols(); - - // this test relies a lot on Random.h, and there's not much more that we can do - // to test it, hence I consider that we will have tested Random.h - MatrixType m1 = MatrixType::Random(rows, cols), - m2 = MatrixType::Random(rows, cols), - m3(rows, cols); - RowSquareMatrixType - identity = RowSquareMatrixType::Identity(rows, rows), - square = RowSquareMatrixType::Random(rows, rows), - res = RowSquareMatrixType::Random(rows, rows); - ColSquareMatrixType - square2 = ColSquareMatrixType::Random(cols, cols), - res2 = ColSquareMatrixType::Random(cols, cols); - RowVectorType v1 = RowVectorType::Random(rows); - ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols); - OtherMajorMatrixType tm1 = m1; - - Scalar s1 = ei_random(); - - int r = ei_random(0, rows-1), - c = ei_random(0, cols-1); - - // begin testing Product.h: only associativity for now - // (we use Transpose.h but this doesn't count as a test for it) - - VERIFY_IS_APPROX((m1*m1.transpose())*m2, m1*(m1.transpose()*m2)); - m3 = m1; - m3 *= m1.transpose() * m2; - VERIFY_IS_APPROX(m3, m1 * (m1.transpose()*m2)); - VERIFY_IS_APPROX(m3, m1.lazy() * (m1.transpose()*m2)); - - // continue testing Product.h: distributivity - VERIFY_IS_APPROX(square*(m1 + m2), square*m1+square*m2); - VERIFY_IS_APPROX(square*(m1 - m2), square*m1-square*m2); - - // continue testing Product.h: compatibility with ScalarMultiple.h - VERIFY_IS_APPROX(s1*(square*m1), (s1*square)*m1); - VERIFY_IS_APPROX(s1*(square*m1), square*(m1*s1)); - - // again, test operator() to check const-qualification - s1 += (square.lazy() * m1)(r,c); - - // test Product.h together with Identity.h - VERIFY_IS_APPROX(v1, identity*v1); - VERIFY_IS_APPROX(v1.transpose(), v1.transpose() * identity); - // again, test operator() to check const-qualification - VERIFY_IS_APPROX(MatrixType::Identity(rows, cols)(r,c), static_cast(r==c)); - - if (rows!=cols) - VERIFY_RAISES_ASSERT(m3 = m1*m1); - - // test the previous tests were not screwed up because operator* returns 0 - // (we use the more accurate default epsilon) - if (NumTraits::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(m1.transpose()*m2,m2.transpose()*m1)); - } - - // test optimized operator+= path - res = square; - res += (m1 * m2.transpose()).lazy(); - VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); - if (NumTraits::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(res,square + m2 * m1.transpose())); - } - vcres = vc2; - vcres += (m1.transpose() * v1).lazy(); - VERIFY_IS_APPROX(vcres, vc2 + m1.transpose() * v1); - tm1 = m1; - VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1); - VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1); - - // test submatrix and matrix/vector product - for (int i=0; i::HasFloatingPoint && std::min(rows,cols)>1) - { - VERIFY(areNotApprox(res2,square2 + m2.transpose() * m1)); - } -} - diff --git a/gtsam/3rdparty/Eigen/test/eigen2/runtest.sh b/gtsam/3rdparty/Eigen/test/eigen2/runtest.sh deleted file mode 100755 index bc693af13..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/runtest.sh +++ /dev/null @@ -1,28 +0,0 @@ -#!/bin/bash - -black='\E[30m' -red='\E[31m' -green='\E[32m' -yellow='\E[33m' -blue='\E[34m' -magenta='\E[35m' -cyan='\E[36m' -white='\E[37m' - -if make test_$1 > /dev/null 2> .runtest.log ; then - if ! ./test_$1 r20 > /dev/null 2> .runtest.log ; then - echo -e $red Test $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 - else - echo -e $green Test $1 passed$black - fi -else - echo -e $red Build of target $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 -fi diff --git a/gtsam/3rdparty/Eigen/test/eigen2/sparse.h b/gtsam/3rdparty/Eigen/test/eigen2/sparse.h deleted file mode 100644 index e12f89990..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/sparse.h +++ /dev/null @@ -1,154 +0,0 @@ -// This file is part of Eigen, a lightweight C++ template library -// for linear algebra. Eigen itself is part of the KDE project. -// -// Copyright (C) 2008 Daniel Gomez Ferro -// -// This Source Code Form is subject to the terms of the Mozilla -// Public License v. 2.0. If a copy of the MPL was not distributed -// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. - -#ifndef EIGEN_TESTSPARSE_H - -#include "main.h" - -#if EIGEN_GNUC_AT_LEAST(4,0) && !defined __ICC -#include -#define EIGEN_UNORDERED_MAP_SUPPORT -namespace std { - using std::tr1::unordered_map; -} -#endif - -#ifdef EIGEN_GOOGLEHASH_SUPPORT - #include -#endif - -#include -#include -#include - -enum { - ForceNonZeroDiag = 1, - MakeLowerTriangular = 2, - MakeUpperTriangular = 4, - ForceRealDiag = 8 -}; - -/* Initializes both a sparse and dense matrix with same random values, - * and a ratio of \a density non zero entries. - * \param flags is a union of ForceNonZeroDiag, MakeLowerTriangular and MakeUpperTriangular - * allowing to control the shape of the matrix. - * \param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero, - * and zero coefficients respectively. - */ -template void -initSparse(double density, - Matrix& refMat, - SparseMatrix& sparseMat, - int flags = 0, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseMat.startFill(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? ei_random() : Scalar(0); - if ((flags&ForceNonZeroDiag) && (i==j)) - { - v = ei_random()*Scalar(3.); - v = v*v + Scalar(5.); - } - if ((flags & MakeLowerTriangular) && j>i) - v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); - } - else if (zeroCoords) - { - zeroCoords->push_back(Vector2i(i,j)); - } - refMat(i,j) = v; - } - } - sparseMat.endFill(); -} - -template void -initSparse(double density, - Matrix& refMat, - DynamicSparseMatrix& sparseMat, - int flags = 0, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseMat.startFill(int(refMat.rows()*refMat.cols()*density)); - for(int j=0; j(0,1) < density) ? ei_random() : Scalar(0); - if ((flags&ForceNonZeroDiag) && (i==j)) - { - v = ei_random()*Scalar(3.); - v = v*v + Scalar(5.); - } - if ((flags & MakeLowerTriangular) && j>i) - v = Scalar(0); - else if ((flags & MakeUpperTriangular) && jpush_back(Vector2i(i,j)); - } - else if (zeroCoords) - { - zeroCoords->push_back(Vector2i(i,j)); - } - refMat(i,j) = v; - } - } - sparseMat.endFill(); -} - -template void -initSparse(double density, - Matrix& refVec, - SparseVector& sparseVec, - std::vector* zeroCoords = 0, - std::vector* nonzeroCoords = 0) -{ - sparseVec.reserve(int(refVec.size()*density)); - sparseVec.setZero(); - for(int i=0; i(0,1) < density) ? ei_random() : Scalar(0); - if (v!=Scalar(0)) - { - sparseVec.fill(i) = v; - if (nonzeroCoords) - nonzeroCoords->push_back(i); - } - else if (zeroCoords) - zeroCoords->push_back(i); - refVec[i] = v; - } -} - -#endif // EIGEN_TESTSPARSE_H diff --git a/gtsam/3rdparty/Eigen/test/eigen2/testsuite.cmake b/gtsam/3rdparty/Eigen/test/eigen2/testsuite.cmake deleted file mode 100644 index 12b6bfa2e..000000000 --- a/gtsam/3rdparty/Eigen/test/eigen2/testsuite.cmake +++ /dev/null @@ -1,197 +0,0 @@ - -#################################################################### -# -# Usage: -# - create a new folder, let's call it cdash -# - in that folder, do: -# ctest -S path/to/eigen2/test/testsuite.cmake[,option1=value1[,option2=value2]] -# -# Options: -# - EIGEN_CXX: compiler, eg.: g++-4.2 -# default: default c++ compiler -# - EIGEN_SITE: eg, INRIA-Bdx_pc-gael, or the name of the contributor, etc. -# default: hostname -# - EIGEN_BUILD_STRING: a string which identify the system/compiler. It should be formed like that: -# --- -# with: -# = opensuse, debian, osx, windows, cygwin, freebsd, solaris, etc. -# = 11.1, XP, vista, leopard, etc. -# = i386, x86_64, ia64, powerpc, etc. -# = gcc-4.3.2, icc-11.0, MSVC-2008, etc. -# - EIGEN_EXPLICIT_VECTORIZATION: novec, SSE2, Altivec -# default: SSE2 for x86_64 systems, novec otherwise -# Its value is automatically appended to EIGEN_BUILD_STRING -# - EIGEN_CMAKE_DIR: path to cmake executable -# - EIGEN_MODE: dashboard model, can be Experimental, Nightly, or Continuous -# default: Nightly -# - EIGEN_WORK_DIR: directory used to download the source files and make the builds -# default: folder which contains this script -# - EIGEN_CMAKE_ARGS: additional arguments passed to cmake -# - CTEST_SOURCE_DIRECTORY: path to eigen's src (use a new and empty folder, not the one you are working on) -# default: /src -# - CTEST_BINARY_DIRECTORY: build directory -# default: /nightly- -# -# Here is an example running several compilers on a linux system: -# #!/bin/bash -# ARCH=`uname -m` -# SITE=`hostname` -# VERSION=opensuse-11.1 -# WORK_DIR=/home/gael/Coding/eigen2/cdash -# # get the last version of the script -# wget http://bitbucket.org/eigen/eigen/raw/tip/test/testsuite.cmake -o $WORK_DIR/testsuite.cmake -# COMMON="ctest -S $WORK_DIR/testsuite.cmake,EIGEN_WORK_DIR=$WORK_DIR,EIGEN_SITE=$SITE,EIGEN_MODE=$1,EIGEN_BUILD_STRING=$OS_VERSION-$ARCH" -# $COMMON-gcc-3.4.6,EIGEN_CXX=g++-3.4 -# $COMMON-gcc-4.0.1,EIGEN_CXX=g++-4.0.1 -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=novec -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=SSE2 -# $COMMON-icc-11.0,EIGEN_CXX=icpc -# -#################################################################### - -# process the arguments - -set(ARGLIST ${CTEST_SCRIPT_ARG}) -while(${ARGLIST} MATCHES ".+.*") - - # pick first - string(REGEX MATCH "([^,]*)(,.*)?" DUMMY ${ARGLIST}) - SET(TOP ${CMAKE_MATCH_1}) - - # remove first - string(REGEX MATCHALL "[^,]*,(.*)" DUMMY ${ARGLIST}) - SET(ARGLIST ${CMAKE_MATCH_1}) - - # decompose as a pair key=value - string(REGEX MATCH "([^=]*)(=.*)?" DUMMY ${TOP}) - SET(KEY ${CMAKE_MATCH_1}) - - string(REGEX MATCH "[^=]*=(.*)" DUMMY ${TOP}) - SET(VALUE ${CMAKE_MATCH_1}) - - # set the variable to the specified value - if(VALUE) - SET(${KEY} ${VALUE}) - else(VALUE) - SET(${KEY} ON) - endif(VALUE) - -endwhile(${ARGLIST} MATCHES ".+.*") - -#################################################################### -# Automatically set some user variables if they have not been defined manually -#################################################################### -cmake_minimum_required(VERSION 2.6 FATAL_ERROR) - -if(NOT EIGEN_SITE) - site_name(EIGEN_SITE) -endif(NOT EIGEN_SITE) - -if(NOT EIGEN_CMAKE_DIR) - SET(EIGEN_CMAKE_DIR "") -endif(NOT EIGEN_CMAKE_DIR) - -if(NOT EIGEN_BUILD_STRING) - - # let's try to find all information we need to make the build string ourself - - # OS - build_name(EIGEN_OS_VERSION) - - # arch - set(EIGEN_ARCH ${CMAKE_SYSTEM_PROCESSOR}) - if(WIN32) - set(EIGEN_ARCH $ENV{PROCESSOR_ARCHITECTURE}) - else(WIN32) - execute_process(COMMAND uname -m OUTPUT_VARIABLE EIGEN_ARCH OUTPUT_STRIP_TRAILING_WHITESPACE) - endif(WIN32) - - set(EIGEN_BUILD_STRING ${EIGEN_OS_VERSION}${EIGEN_ARCH}-${EIGEN_CXX}) - -endif(NOT EIGEN_BUILD_STRING) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - set(EIGEN_BUILD_STRING ${EIGEN_BUILD_STRING}-${EIGEN_EXPLICIT_VECTORIZATION}) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(NOT EIGEN_WORK_DIR) - set(EIGEN_WORK_DIR ${CTEST_SCRIPT_DIRECTORY}) -endif(NOT EIGEN_WORK_DIR) - -if(NOT CTEST_SOURCE_DIRECTORY) - SET (CTEST_SOURCE_DIRECTORY "${EIGEN_WORK_DIR}/src") -endif(NOT CTEST_SOURCE_DIRECTORY) - -if(NOT CTEST_BINARY_DIRECTORY) - SET (CTEST_BINARY_DIRECTORY "${EIGEN_WORK_DIR}/nightly_${EIGEN_CXX}") -endif(NOT CTEST_BINARY_DIRECTORY) - -if(NOT EIGEN_MODE) - set(EIGEN_MODE Nightly) -endif(NOT EIGEN_MODE) - -## mandatory variables (the default should be ok in most cases): - -SET (CTEST_CVS_COMMAND "hg") -SET (CTEST_CVS_CHECKOUT "${CTEST_CVS_COMMAND} clone -r 2.0 http://bitbucket.org/eigen/eigen \"${CTEST_SOURCE_DIRECTORY}\"") - -# which ctest command to use for running the dashboard -SET (CTEST_COMMAND "${EIGEN_CMAKE_DIR}ctest -D ${EIGEN_MODE}") - -# what cmake command to use for configuring this dashboard -SET (CTEST_CMAKE_COMMAND "${EIGEN_CMAKE_DIR}cmake -DEIGEN_BUILD_TESTS=on ") - -#################################################################### -# The values in this section are optional you can either -# have them or leave them commented out -#################################################################### - -# this make sure we get consistent outputs -SET($ENV{LC_MESSAGES} "en_EN") - -# should ctest wipe the binary tree before running -SET(CTEST_START_WITH_EMPTY_BINARY_DIRECTORY TRUE) -SET(CTEST_BACKUP_AND_RESTORE TRUE) - -# this is the initial cache to use for the binary tree, be careful to escape -# any quotes inside of this string if you use it -if(WIN32 AND NOT UNIX) - #message(SEND_ERROR "win32") - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"NMake Makefiles\" -DCMAKE_MAKE_PROGRAM=nmake") - SET (CTEST_INITIAL_CACHE " - MAKECOMMAND:STRING=nmake -i - CMAKE_MAKE_PROGRAM:FILEPATH=nmake - CMAKE_GENERATOR:INTERNAL=NMake Makefiles - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -else(WIN32 AND NOT UNIX) - SET (CTEST_INITIAL_CACHE " - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -endif(WIN32 AND NOT UNIX) - -# set any extra environment variables to use during the execution of the script here: - -if(EIGEN_CXX) - set(CTEST_ENVIRONMENT "CXX=${EIGEN_CXX}") -endif(EIGEN_CXX) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - if(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES Altivec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_ALTIVEC=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES novec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_NO_EXPLICIT_VECTORIZATION=ON") - else(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - message(FATAL_ERROR "Invalid value for EIGEN_EXPLICIT_VECTORIZATION (${EIGEN_EXPLICIT_VECTORIZATION}), must be: novec, SSE2, SSE3, Altivec") - endif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(DEFINED EIGEN_CMAKE_ARGS) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} ${EIGEN_CMAKE_ARGS}") -endif(DEFINED EIGEN_CMAKE_ARGS) diff --git a/gtsam/3rdparty/Eigen/test/eigen2support.cpp b/gtsam/3rdparty/Eigen/test/eigen2support.cpp index 1fa49a8c8..ad1d98091 100644 --- a/gtsam/3rdparty/Eigen/test/eigen2support.cpp +++ b/gtsam/3rdparty/Eigen/test/eigen2support.cpp @@ -8,7 +8,6 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #define EIGEN2_SUPPORT -#define EIGEN_NO_EIGEN2_DEPRECATED_WARNING #include "main.h" diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp index c9d8c0877..293b1b265 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_complex.cpp @@ -13,20 +13,59 @@ #include #include -/* Check that two column vectors are approximately equal upto permutations, - by checking that the k-th power sums are equal for k = 1, ..., vec1.rows() */ +template bool find_pivot(typename MatrixType::Scalar tol, MatrixType &diffs, Index col=0) +{ + bool match = diffs.diagonal().sum() <= tol; + if(match || col==diffs.cols()) + { + return match; + } + else + { + Index n = diffs.cols(); + std::vector > transpositions; + for(Index i=col; i tol) + break; + + best_index += col; + + diffs.row(col).swap(diffs.row(best_index)); + if(find_pivot(tol,diffs,col+1)) return true; + diffs.row(col).swap(diffs.row(best_index)); + + // move current pivot to the end + diffs.row(n-(i-col)-1).swap(diffs.row(best_index)); + transpositions.push_back(std::pair(n-(i-col)-1,best_index)); + } + // restore + for(Index k=transpositions.size()-1; k>=0; --k) + diffs.row(transpositions[k].first).swap(diffs.row(transpositions[k].second)); + } + return false; +} + +/* Check that two column vectors are approximately equal upto permutations. + * Initially, this method checked that the k-th power sums are equal for all k = 1, ..., vec1.rows(), + * however this strategy is numerically inacurate because of numerical cancellation issues. + */ template void verify_is_approx_upto_permutation(const VectorType& vec1, const VectorType& vec2) { - typedef typename NumTraits::Real RealScalar; + typedef typename VectorType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; VERIFY(vec1.cols() == 1); VERIFY(vec2.cols() == 1); VERIFY(vec1.rows() == vec2.rows()); - for (int k = 1; k <= vec1.rows(); ++k) - { - VERIFY_IS_APPROX(vec1.array().pow(RealScalar(k)).sum(), vec2.array().pow(RealScalar(k)).sum()); - } + + Index n = vec1.rows(); + RealScalar tol = test_precision()*test_precision()*numext::maxi(vec1.squaredNorm(),vec2.squaredNorm()); + Matrix diffs = (vec1.rowwise().replicate(n) - vec2.rowwise().replicate(n).transpose()).cwiseAbs2(); + + VERIFY( find_pivot(tol, diffs) ); } @@ -79,13 +118,28 @@ template void eigensolver(const MatrixType& m) MatrixType id = MatrixType::Identity(rows, cols); VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1)); - if (rows > 1) + if (rows > 1 && rows < 20) { // Test matrix with NaN a(0,0) = std::numeric_limits::quiet_NaN(); ComplexEigenSolver eiNaN(a); VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + ComplexEigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + ComplexEigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } } template void eigensolver_verify_assert(const MatrixType& m) @@ -108,6 +162,7 @@ void test_eigensolver_complex() CALL_SUBTEST_2( eigensolver(MatrixXcd(s,s)) ); CALL_SUBTEST_3( eigensolver(Matrix, 1, 1>()) ); CALL_SUBTEST_4( eigensolver(Matrix3f()) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4cf()) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_generalized_real.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_generalized_real.cpp index 566a4bdc6..9c0838ba4 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_generalized_real.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_generalized_real.cpp @@ -1,15 +1,17 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2012 Gael Guennebaud +// Copyright (C) 2012-2016 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include #include +#include template void generalized_eigensolver_real(const MatrixType& m) { @@ -21,6 +23,7 @@ template void generalized_eigensolver_real(const MatrixType Index cols = m.cols(); typedef typename MatrixType::Scalar Scalar; + typedef std::complex ComplexScalar; typedef Matrix VectorType; MatrixType a = MatrixType::Random(rows,cols); @@ -31,14 +34,49 @@ template void generalized_eigensolver_real(const MatrixType MatrixType spdB = b.adjoint() * b + b1.adjoint() * b1; // lets compare to GeneralizedSelfAdjointEigenSolver - GeneralizedSelfAdjointEigenSolver symmEig(spdA, spdB); - GeneralizedEigenSolver eig(spdA, spdB); + { + GeneralizedSelfAdjointEigenSolver symmEig(spdA, spdB); + GeneralizedEigenSolver eig(spdA, spdB); - VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0); + VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0); - VectorType realEigenvalues = eig.eigenvalues().real(); - std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size()); - VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues()); + VectorType realEigenvalues = eig.eigenvalues().real(); + std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size()); + VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues()); + + // check eigenvectors + typename GeneralizedEigenSolver::EigenvectorsType D = eig.eigenvalues().asDiagonal(); + typename GeneralizedEigenSolver::EigenvectorsType V = eig.eigenvectors(); + VERIFY_IS_APPROX(spdA*V, spdB*V*D); + } + + // non symmetric case: + { + GeneralizedEigenSolver eig(rows); + // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition + //Eigen::internal::set_is_malloc_allowed(false); + eig.compute(a,b); + //Eigen::internal::set_is_malloc_allowed(true); + for(Index k=0; k tmp = (eig.betas()(k)*a).template cast() - eig.alphas()(k)*b; + if(tmp.size()>1 && tmp.norm()>(std::numeric_limits::min)()) + tmp /= tmp.norm(); + VERIFY_IS_MUCH_SMALLER_THAN( std::abs(tmp.determinant()), Scalar(1) ); + } + // check eigenvectors + typename GeneralizedEigenSolver::EigenvectorsType D = eig.eigenvalues().asDiagonal(); + typename GeneralizedEigenSolver::EigenvectorsType V = eig.eigenvectors(); + VERIFY_IS_APPROX(a*V, b*V*D); + } + + // regression test for bug 1098 + { + GeneralizedSelfAdjointEigenSolver eig1(a.adjoint() * a,b.adjoint() * b); + eig1.compute(a.adjoint() * a,b.adjoint() * b); + GeneralizedEigenSolver eig2(a.adjoint() * a,b.adjoint() * b); + eig2.compute(a.adjoint() * a,b.adjoint() * b); + } } void test_eigensolver_generalized_real() @@ -49,7 +87,7 @@ void test_eigensolver_generalized_real() s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(s,s)) ); - // some trivial but implementation-wise tricky cases + // some trivial but implementation-wise special cases CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(1,1)) ); CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(2,2)) ); CALL_SUBTEST_3( generalized_eigensolver_real(Matrix()) ); diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp index 005af81eb..d0e644d4b 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_generic.cpp @@ -63,13 +63,28 @@ template void eigensolver(const MatrixType& m) MatrixType id = MatrixType::Identity(rows, cols); VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1)); - if (rows > 2) + if (rows > 2 && rows < 20) { // Test matrix with NaN a(0,0) = std::numeric_limits::quiet_NaN(); EigenSolver eiNaN(a); VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + EigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + EigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } } template void eigensolver_verify_assert(const MatrixType& m) @@ -93,6 +108,7 @@ void test_eigensolver_generic() CALL_SUBTEST_1( eigensolver(Matrix4f()) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); CALL_SUBTEST_2( eigensolver(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) // some trivial but implementation-wise tricky cases CALL_SUBTEST_2( eigensolver(MatrixXd(1,1)) ); @@ -114,12 +130,37 @@ void test_eigensolver_generic() CALL_SUBTEST_2( { MatrixXd A(1,1); - A(0,0) = std::sqrt(-1.); + A(0,0) = std::sqrt(-1.); // is Not-a-Number Eigen::EigenSolver solver(A); - MatrixXd V(1, 1); - V(0,0) = solver.eigenvectors()(0,0).real(); + VERIFY_IS_EQUAL(solver.info(), NumericalIssue); } ); +#ifdef EIGEN_TEST_PART_2 + { + // regression test for bug 793 + MatrixXd a(3,3); + a << 0, 0, 1, + 1, 1, 1, + 1, 1e+200, 1; + Eigen::EigenSolver eig(a); + double scale = 1e-200; // scale to avoid overflow during the comparisons + VERIFY_IS_APPROX(a * eig.pseudoEigenvectors()*scale, eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()*scale); + VERIFY_IS_APPROX(a * eig.eigenvectors()*scale, eig.eigenvectors() * eig.eigenvalues().asDiagonal()*scale); + } + { + // check a case where all eigenvalues are null. + MatrixXd a(2,2); + a << 1, 1, + -1, -1; + Eigen::EigenSolver eig(a); + VERIFY_IS_APPROX(eig.pseudoEigenvectors().squaredNorm(), 2.); + VERIFY_IS_APPROX((a * eig.pseudoEigenvectors()).norm()+1., 1.); + VERIFY_IS_APPROX((eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()).norm()+1., 1.); + VERIFY_IS_APPROX((a * eig.eigenvectors()).norm()+1., 1.); + VERIFY_IS_APPROX((eig.eigenvectors() * eig.eigenvalues().asDiagonal()).norm()+1., 1.); + } +#endif + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp index 38689cfbf..39ad4130e 100644 --- a/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/eigensolver_selfadjoint.cpp @@ -9,8 +9,62 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" +#include "svd_fill.h" #include #include +#include + + +template void selfadjointeigensolver_essential_check(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + RealScalar eival_eps = numext::mini(test_precision(), NumTraits::dummy_precision()*20000); + + SelfAdjointEigenSolver eiSymm(m); + VERIFY_IS_EQUAL(eiSymm.info(), Success); + + RealScalar scaling = m.cwiseAbs().maxCoeff(); + + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(eiSymm.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX((m.template selfadjointView() * eiSymm.eigenvectors())/scaling, + (eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal())/scaling); + } + VERIFY_IS_APPROX(m.template selfadjointView().eigenvalues(), eiSymm.eigenvalues()); + VERIFY_IS_UNITARY(eiSymm.eigenvectors()); + + if(m.cols()<=4) + { + SelfAdjointEigenSolver eiDirect; + eiDirect.computeDirect(m); + VERIFY_IS_EQUAL(eiDirect.info(), Success); + if(! eiSymm.eigenvalues().isApprox(eiDirect.eigenvalues(), eival_eps) ) + { + std::cerr << "reference eigenvalues: " << eiSymm.eigenvalues().transpose() << "\n" + << "obtained eigenvalues: " << eiDirect.eigenvalues().transpose() << "\n" + << "diff: " << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).transpose() << "\n" + << "error (eps): " << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).norm() / eiSymm.eigenvalues().norm() << " (" << eival_eps << ")\n"; + } + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(eiDirect.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX(eiSymm.eigenvalues()/scaling, eiDirect.eigenvalues()/scaling); + VERIFY_IS_APPROX((m.template selfadjointView() * eiDirect.eigenvectors())/scaling, + (eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal())/scaling); + VERIFY_IS_APPROX(m.template selfadjointView().eigenvalues()/scaling, eiDirect.eigenvalues()/scaling); + } + + VERIFY_IS_UNITARY(eiDirect.eigenvectors()); + } +} template void selfadjointeigensolver(const MatrixType& m) { @@ -31,17 +85,8 @@ template void selfadjointeigensolver(const MatrixType& m) MatrixType symmA = a.adjoint() * a + a1.adjoint() * a1; MatrixType symmC = symmA; - // randomly nullify some rows/columns - { - Index count = 1;//internal::random(-cols,cols); - for(Index k=0; k(0,cols-1); - symmA.row(i).setZero(); - symmA.col(i).setZero(); - } - } - + svd_fill_random(symmA,Symmetric); + symmA.template triangularView().setZero(); symmC.template triangularView().setZero(); @@ -49,23 +94,13 @@ template void selfadjointeigensolver(const MatrixType& m) MatrixType b1 = MatrixType::Random(rows,cols); MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1; symmB.template triangularView().setZero(); + + CALL_SUBTEST( selfadjointeigensolver_essential_check(symmA) ); SelfAdjointEigenSolver eiSymm(symmA); - SelfAdjointEigenSolver eiDirect; - eiDirect.computeDirect(symmA); // generalized eigen pb GeneralizedSelfAdjointEigenSolver eiSymmGen(symmC, symmB); - VERIFY_IS_EQUAL(eiSymm.info(), Success); - VERIFY((symmA.template selfadjointView() * eiSymm.eigenvectors()).isApprox( - eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal(), largerEps)); - VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiSymm.eigenvalues()); - - VERIFY_IS_EQUAL(eiDirect.info(), Success); - VERIFY((symmA.template selfadjointView() * eiDirect.eigenvectors()).isApprox( - eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal(), largerEps)); - VERIFY_IS_APPROX(symmA.template selfadjointView().eigenvalues(), eiDirect.eigenvalues()); - SelfAdjointEigenSolver eiSymmNoEivecs(symmA, false); VERIFY_IS_EQUAL(eiSymmNoEivecs.info(), Success); VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmNoEivecs.eigenvalues()); @@ -111,37 +146,111 @@ template void selfadjointeigensolver(const MatrixType& m) // test Tridiagonalization's methods Tridiagonalization tridiag(symmC); - // FIXME tridiag.matrixQ().adjoint() does not work + VERIFY_IS_APPROX(tridiag.diagonal(), tridiag.matrixT().diagonal()); + VERIFY_IS_APPROX(tridiag.subDiagonal(), tridiag.matrixT().template diagonal<-1>()); + Matrix T = tridiag.matrixT(); + if(rows>1 && cols>1) { + // FIXME check that upper and lower part are 0: + //VERIFY(T.topRightCorner(rows-2, cols-2).template triangularView().isZero()); + } + VERIFY_IS_APPROX(tridiag.diagonal(), T.diagonal()); + VERIFY_IS_APPROX(tridiag.subDiagonal(), T.template diagonal<1>()); VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView()), tridiag.matrixQ() * tridiag.matrixT().eval() * MatrixType(tridiag.matrixQ()).adjoint()); + VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView()), tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint()); - if (rows > 1) + // Test computation of eigenvalues from tridiagonal matrix + if(rows > 1) + { + SelfAdjointEigenSolver eiSymmTridiag; + eiSymmTridiag.computeFromTridiagonal(tridiag.matrixT().diagonal(), tridiag.matrixT().diagonal(-1), ComputeEigenvectors); + VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmTridiag.eigenvalues()); + VERIFY_IS_APPROX(tridiag.matrixT(), eiSymmTridiag.eigenvectors().real() * eiSymmTridiag.eigenvalues().asDiagonal() * eiSymmTridiag.eigenvectors().real().transpose()); + } + + if (rows > 1 && rows < 20) { // Test matrix with NaN symmC(0,0) = std::numeric_limits::quiet_NaN(); SelfAdjointEigenSolver eiSymmNaN(symmC); VERIFY_IS_EQUAL(eiSymmNaN.info(), NoConvergence); } + + // regression test for bug 1098 + { + SelfAdjointEigenSolver eig(a.adjoint() * a); + eig.compute(a.adjoint() * a); + } + + // regression test for bug 478 + { + a.setZero(); + SelfAdjointEigenSolver ei3(a); + VERIFY_IS_EQUAL(ei3.info(), Success); + VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1)); + VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity()); + } +} + +template +void bug_854() +{ + Matrix3d m; + m << 850.961, 51.966, 0, + 51.966, 254.841, 0, + 0, 0, 0; + selfadjointeigensolver_essential_check(m); +} + +template +void bug_1014() +{ + Matrix3d m; + m << 0.11111111111111114658, 0, 0, + 0, 0.11111111111111109107, 0, + 0, 0, 0.11111111111111107719; + selfadjointeigensolver_essential_check(m); +} + +template +void bug_1225() +{ + Matrix3d m1, m2; + m1.setRandom(); + m1 = m1*m1.transpose(); + m2 = m1.triangularView(); + SelfAdjointEigenSolver eig1(m1); + SelfAdjointEigenSolver eig2(m2.selfadjointView()); + VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues()); +} + +template +void bug_1204() +{ + SparseMatrix A(2,2); + A.setIdentity(); + SelfAdjointEigenSolver > eig(A); } void test_eigensolver_selfadjoint() { int s = 0; for(int i = 0; i < g_repeat; i++) { + // trivial test for 1x1 matrices: + CALL_SUBTEST_1( selfadjointeigensolver(Matrix())); + CALL_SUBTEST_1( selfadjointeigensolver(Matrix())); // very important to test 3x3 and 2x2 matrices since we provide special paths for them - CALL_SUBTEST_1( selfadjointeigensolver(Matrix2f()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix2d()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3f()) ); - CALL_SUBTEST_1( selfadjointeigensolver(Matrix3d()) ); + CALL_SUBTEST_12( selfadjointeigensolver(Matrix2f()) ); + CALL_SUBTEST_12( selfadjointeigensolver(Matrix2d()) ); + CALL_SUBTEST_13( selfadjointeigensolver(Matrix3f()) ); + CALL_SUBTEST_13( selfadjointeigensolver(Matrix3d()) ); CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); - CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) ); s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); + CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) ); + CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) ); + CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) ); CALL_SUBTEST_9( selfadjointeigensolver(Matrix,Dynamic,Dynamic,RowMajor>(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) // some trivial but implementation-wise tricky cases CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(1,1)) ); @@ -149,6 +258,11 @@ void test_eigensolver_selfadjoint() CALL_SUBTEST_6( selfadjointeigensolver(Matrix()) ); CALL_SUBTEST_7( selfadjointeigensolver(Matrix()) ); } + + CALL_SUBTEST_13( bug_854<0>() ); + CALL_SUBTEST_13( bug_1014<0>() ); + CALL_SUBTEST_13( bug_1204<0>() ); + CALL_SUBTEST_13( bug_1225<0>() ); // Test problem size constructors s = internal::random(1,EIGEN_TEST_MAX_SIZE/4); diff --git a/gtsam/3rdparty/Eigen/test/evaluator_common.h b/gtsam/3rdparty/Eigen/test/evaluator_common.h new file mode 100644 index 000000000..e69de29bb diff --git a/gtsam/3rdparty/Eigen/test/evaluators.cpp b/gtsam/3rdparty/Eigen/test/evaluators.cpp new file mode 100644 index 000000000..aed5a05a7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/evaluators.cpp @@ -0,0 +1,499 @@ + +#include "main.h" + +namespace Eigen { + + template + const Product + prod(const Lhs& lhs, const Rhs& rhs) + { + return Product(lhs,rhs); + } + + template + const Product + lazyprod(const Lhs& lhs, const Rhs& rhs) + { + return Product(lhs,rhs); + } + + template + EIGEN_STRONG_INLINE + DstXprType& copy_using_evaluator(const EigenBase &dst, const SrcXprType &src) + { + call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op()); + return dst.const_cast_derived(); + } + + template class StorageBase, typename SrcXprType> + EIGEN_STRONG_INLINE + const DstXprType& copy_using_evaluator(const NoAlias& dst, const SrcXprType &src) + { + call_assignment(dst, src.derived(), internal::assign_op()); + return dst.expression(); + } + + template + EIGEN_STRONG_INLINE + DstXprType& copy_using_evaluator(const PlainObjectBase &dst, const SrcXprType &src) + { + #ifdef EIGEN_NO_AUTOMATIC_RESIZING + eigen_assert((dst.size()==0 || (IsVectorAtCompileTime ? (dst.size() == src.size()) + : (dst.rows() == src.rows() && dst.cols() == src.cols()))) + && "Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined"); + #else + dst.const_cast_derived().resizeLike(src.derived()); + #endif + + call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op()); + return dst.const_cast_derived(); + } + + template + void add_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(const_cast(dst), src.derived(), internal::add_assign_op()); + } + + template + void subtract_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(const_cast(dst), src.derived(), internal::sub_assign_op()); + } + + template + void multiply_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.derived(), internal::mul_assign_op()); + } + + template + void divide_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.derived(), internal::div_assign_op()); + } + + template + void swap_using_evaluator(const DstXprType& dst, const SrcXprType& src) + { + typedef typename DstXprType::Scalar Scalar; + call_assignment(dst.const_cast_derived(), src.const_cast_derived(), internal::swap_assign_op()); + } + + namespace internal { + template class StorageBase, typename Src, typename Func> + EIGEN_DEVICE_FUNC void call_assignment(const NoAlias& dst, const Src& src, const Func& func) + { + call_assignment_no_alias(dst.expression(), src, func); + } + } + +} + +template long get_cost(const XprType& ) { return Eigen::internal::evaluator::CoeffReadCost; } + +using namespace std; + +#define VERIFY_IS_APPROX_EVALUATOR(DEST,EXPR) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (EXPR).eval()); +#define VERIFY_IS_APPROX_EVALUATOR2(DEST,EXPR,REF) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (REF).eval()); + +void test_evaluators() +{ + // Testing Matrix evaluator and Transpose + Vector2d v = Vector2d::Random(); + const Vector2d v_const(v); + Vector2d v2; + RowVector2d w; + + VERIFY_IS_APPROX_EVALUATOR(v2, v); + VERIFY_IS_APPROX_EVALUATOR(v2, v_const); + + // Testing Transpose + VERIFY_IS_APPROX_EVALUATOR(w, v.transpose()); // Transpose as rvalue + VERIFY_IS_APPROX_EVALUATOR(w, v_const.transpose()); + + copy_using_evaluator(w.transpose(), v); // Transpose as lvalue + VERIFY_IS_APPROX(w,v.transpose().eval()); + + copy_using_evaluator(w.transpose(), v_const); + VERIFY_IS_APPROX(w,v_const.transpose().eval()); + + // Testing Array evaluator + { + ArrayXXf a(2,3); + ArrayXXf b(3,2); + a << 1,2,3, 4,5,6; + const ArrayXXf a_const(a); + + VERIFY_IS_APPROX_EVALUATOR(b, a.transpose()); + + VERIFY_IS_APPROX_EVALUATOR(b, a_const.transpose()); + + // Testing CwiseNullaryOp evaluator + copy_using_evaluator(w, RowVector2d::Random()); + VERIFY((w.array() >= -1).all() && (w.array() <= 1).all()); // not easy to test ... + + VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Zero()); + + VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Constant(3)); + + // mix CwiseNullaryOp and transpose + VERIFY_IS_APPROX_EVALUATOR(w, Vector2d::Zero().transpose()); + } + + { + // test product expressions + int s = internal::random(1,100); + MatrixXf a(s,s), b(s,s), c(s,s), d(s,s); + a.setRandom(); + b.setRandom(); + c.setRandom(); + d.setRandom(); + VERIFY_IS_APPROX_EVALUATOR(d, (a + b)); + VERIFY_IS_APPROX_EVALUATOR(d, (a + b).transpose()); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b), a*b); + VERIFY_IS_APPROX_EVALUATOR2(d.noalias(), prod(a,b), a*b); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + c, a*b + c); + VERIFY_IS_APPROX_EVALUATOR2(d, s * prod(a,b), s * a*b); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b).transpose(), (a*b).transpose()); + VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + prod(b,c), a*b + b*c); + + // check that prod works even with aliasing present + c = a*a; + copy_using_evaluator(a, prod(a,a)); + VERIFY_IS_APPROX(a,c); + + // check compound assignment of products + d = c; + add_assign_using_evaluator(c.noalias(), prod(a,b)); + d.noalias() += a*b; + VERIFY_IS_APPROX(c, d); + + d = c; + subtract_assign_using_evaluator(c.noalias(), prod(a,b)); + d.noalias() -= a*b; + VERIFY_IS_APPROX(c, d); + } + + { + // test product with all possible sizes + int s = internal::random(1,100); + Matrix m11, res11; m11.setRandom(1,1); + Matrix m14, res14; m14.setRandom(1,4); + Matrix m1X, res1X; m1X.setRandom(1,s); + Matrix m41, res41; m41.setRandom(4,1); + Matrix m44, res44; m44.setRandom(4,4); + Matrix m4X, res4X; m4X.setRandom(4,s); + Matrix mX1, resX1; mX1.setRandom(s,1); + Matrix mX4, resX4; mX4.setRandom(s,4); + Matrix mXX, resXX; mXX.setRandom(s,s); + + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m11,m11), m11*m11); + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m14,m41), m14*m41); + VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m1X,mX1), m1X*mX1); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m11,m14), m11*m14); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m14,m44), m14*m44); + VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m1X,mX4), m1X*mX4); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m11,m1X), m11*m1X); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m14,m4X), m14*m4X); + VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m1X,mXX), m1X*mXX); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m41,m11), m41*m11); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m44,m41), m44*m41); + VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m4X,mX1), m4X*mX1); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m41,m14), m41*m14); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m44,m44), m44*m44); + VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m4X,mX4), m4X*mX4); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m41,m1X), m41*m1X); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m44,m4X), m44*m4X); + VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m4X,mXX), m4X*mXX); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX1,m11), mX1*m11); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX4,m41), mX4*m41); + VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mXX,mX1), mXX*mX1); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX1,m14), mX1*m14); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX4,m44), mX4*m44); + VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mXX,mX4), mXX*mX4); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX1,m1X), mX1*m1X); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX4,m4X), mX4*m4X); + VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mXX,mXX), mXX*mXX); + } + + { + ArrayXXf a(2,3); + ArrayXXf b(3,2); + a << 1,2,3, 4,5,6; + const ArrayXXf a_const(a); + + // this does not work because Random is eval-before-nested: + // copy_using_evaluator(w, Vector2d::Random().transpose()); + + // test CwiseUnaryOp + VERIFY_IS_APPROX_EVALUATOR(v2, 3 * v); + VERIFY_IS_APPROX_EVALUATOR(w, (3 * v).transpose()); + VERIFY_IS_APPROX_EVALUATOR(b, (a + 3).transpose()); + VERIFY_IS_APPROX_EVALUATOR(b, (2 * a_const + 3).transpose()); + + // test CwiseBinaryOp + VERIFY_IS_APPROX_EVALUATOR(v2, v + Vector2d::Ones()); + VERIFY_IS_APPROX_EVALUATOR(w, (v + Vector2d::Ones()).transpose().cwiseProduct(RowVector2d::Constant(3))); + + // dynamic matrices and arrays + MatrixXd mat1(6,6), mat2(6,6); + VERIFY_IS_APPROX_EVALUATOR(mat1, MatrixXd::Identity(6,6)); + VERIFY_IS_APPROX_EVALUATOR(mat2, mat1); + copy_using_evaluator(mat2.transpose(), mat1); + VERIFY_IS_APPROX(mat2.transpose(), mat1); + + ArrayXXd arr1(6,6), arr2(6,6); + VERIFY_IS_APPROX_EVALUATOR(arr1, ArrayXXd::Constant(6,6, 3.0)); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1); + + // test automatic resizing + mat2.resize(3,3); + VERIFY_IS_APPROX_EVALUATOR(mat2, mat1); + arr2.resize(9,9); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1); + + // test direct traversal + Matrix3f m3; + Array33f a3; + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity()); // matrix, nullary + // TODO: find a way to test direct traversal with array + VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Identity().transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Identity()); // unary + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity() + Matrix3f::Zero()); // binary + VERIFY_IS_APPROX_EVALUATOR(m3.block(0,0,2,2), Matrix3f::Identity().block(1,1,2,2)); // block + + // test linear traversal + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero()); // matrix, nullary + VERIFY_IS_APPROX_EVALUATOR(a3, Array33f::Zero()); // array + VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Zero().transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Zero()); // unary + VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero() + m3); // binary + + // test inner vectorization + Matrix4f m4, m4src = Matrix4f::Random(); + Array44f a4, a4src = Matrix4f::Random(); + VERIFY_IS_APPROX_EVALUATOR(m4, m4src); // matrix + VERIFY_IS_APPROX_EVALUATOR(a4, a4src); // array + VERIFY_IS_APPROX_EVALUATOR(m4.transpose(), m4src.transpose()); // transpose + // TODO: find out why Matrix4f::Zero() does not allow inner vectorization + VERIFY_IS_APPROX_EVALUATOR(m4, 2 * m4src); // unary + VERIFY_IS_APPROX_EVALUATOR(m4, m4src + m4src); // binary + + // test linear vectorization + MatrixXf mX(6,6), mXsrc = MatrixXf::Random(6,6); + ArrayXXf aX(6,6), aXsrc = ArrayXXf::Random(6,6); + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc); // matrix + VERIFY_IS_APPROX_EVALUATOR(aX, aXsrc); // array + VERIFY_IS_APPROX_EVALUATOR(mX.transpose(), mXsrc.transpose()); // transpose + VERIFY_IS_APPROX_EVALUATOR(mX, MatrixXf::Zero(6,6)); // nullary + VERIFY_IS_APPROX_EVALUATOR(mX, 2 * mXsrc); // unary + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc + mXsrc); // binary + + // test blocks and slice vectorization + VERIFY_IS_APPROX_EVALUATOR(m4, (mXsrc.block<4,4>(1,0))); + VERIFY_IS_APPROX_EVALUATOR(aX, ArrayXXf::Constant(10, 10, 3.0).block(2, 3, 6, 6)); + + Matrix4f m4ref = m4; + copy_using_evaluator(m4.block(1, 1, 2, 3), m3.bottomRows(2)); + m4ref.block(1, 1, 2, 3) = m3.bottomRows(2); + VERIFY_IS_APPROX(m4, m4ref); + + mX.setIdentity(20,20); + MatrixXf mXref = MatrixXf::Identity(20,20); + mXsrc = MatrixXf::Random(9,12); + copy_using_evaluator(mX.block(4, 4, 9, 12), mXsrc); + mXref.block(4, 4, 9, 12) = mXsrc; + VERIFY_IS_APPROX(mX, mXref); + + // test Map + const float raw[3] = {1,2,3}; + float buffer[3] = {0,0,0}; + Vector3f v3; + Array3f a3f; + VERIFY_IS_APPROX_EVALUATOR(v3, Map(raw)); + VERIFY_IS_APPROX_EVALUATOR(a3f, Map(raw)); + Vector3f::Map(buffer) = 2*v3; + VERIFY(buffer[0] == 2); + VERIFY(buffer[1] == 4); + VERIFY(buffer[2] == 6); + + // test CwiseUnaryView + mat1.setRandom(); + mat2.setIdentity(); + MatrixXcd matXcd(6,6), matXcd_ref(6,6); + copy_using_evaluator(matXcd.real(), mat1); + copy_using_evaluator(matXcd.imag(), mat2); + matXcd_ref.real() = mat1; + matXcd_ref.imag() = mat2; + VERIFY_IS_APPROX(matXcd, matXcd_ref); + + // test Select + VERIFY_IS_APPROX_EVALUATOR(aX, (aXsrc > 0).select(aXsrc, -aXsrc)); + + // test Replicate + mXsrc = MatrixXf::Random(6, 6); + VectorXf vX = VectorXf::Random(6); + mX.resize(6, 6); + VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc.colwise() + vX); + matXcd.resize(12, 12); + VERIFY_IS_APPROX_EVALUATOR(matXcd, matXcd_ref.replicate(2,2)); + VERIFY_IS_APPROX_EVALUATOR(matXcd, (matXcd_ref.replicate<2,2>())); + + // test partial reductions + VectorXd vec1(6); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.rowwise().sum()); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.colwise().sum().transpose()); + + // test MatrixWrapper and ArrayWrapper + mat1.setRandom(6,6); + arr1.setRandom(6,6); + VERIFY_IS_APPROX_EVALUATOR(mat2, arr1.matrix()); + VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array()); + VERIFY_IS_APPROX_EVALUATOR(mat2, (arr1 + 2).matrix()); + VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array() + 2); + mat2.array() = arr1 * arr1; + VERIFY_IS_APPROX(mat2, (arr1 * arr1).matrix()); + arr2.matrix() = MatrixXd::Identity(6,6); + VERIFY_IS_APPROX(arr2, MatrixXd::Identity(6,6).array()); + + // test Reverse + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.reverse()); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.colwise().reverse()); + VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.rowwise().reverse()); + arr2.reverse() = arr1; + VERIFY_IS_APPROX(arr2, arr1.reverse()); + mat2.array() = mat1.array().reverse(); + VERIFY_IS_APPROX(mat2.array(), mat1.array().reverse()); + + // test Diagonal + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal()); + vec1.resize(5); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal(1)); + VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal<-1>()); + vec1.setRandom(); + + mat2 = mat1; + copy_using_evaluator(mat1.diagonal(1), vec1); + mat2.diagonal(1) = vec1; + VERIFY_IS_APPROX(mat1, mat2); + + copy_using_evaluator(mat1.diagonal<-1>(), mat1.diagonal(1)); + mat2.diagonal<-1>() = mat2.diagonal(1); + VERIFY_IS_APPROX(mat1, mat2); + } + + { + // test swapping + MatrixXd mat1, mat2, mat1ref, mat2ref; + mat1ref = mat1 = MatrixXd::Random(6, 6); + mat2ref = mat2 = 2 * mat1 + MatrixXd::Identity(6, 6); + swap_using_evaluator(mat1, mat2); + mat1ref.swap(mat2ref); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + + swap_using_evaluator(mat1.block(0, 0, 3, 3), mat2.block(3, 3, 3, 3)); + mat1ref.block(0, 0, 3, 3).swap(mat2ref.block(3, 3, 3, 3)); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + + swap_using_evaluator(mat1.row(2), mat2.col(3).transpose()); + mat1.row(2).swap(mat2.col(3).transpose()); + VERIFY_IS_APPROX(mat1, mat1ref); + VERIFY_IS_APPROX(mat2, mat2ref); + } + + { + // test compound assignment + const Matrix4d mat_const = Matrix4d::Random(); + Matrix4d mat, mat_ref; + mat = mat_ref = Matrix4d::Identity(); + add_assign_using_evaluator(mat, mat_const); + mat_ref += mat_const; + VERIFY_IS_APPROX(mat, mat_ref); + + subtract_assign_using_evaluator(mat.row(1), 2*mat.row(2)); + mat_ref.row(1) -= 2*mat_ref.row(2); + VERIFY_IS_APPROX(mat, mat_ref); + + const ArrayXXf arr_const = ArrayXXf::Random(5,3); + ArrayXXf arr, arr_ref; + arr = arr_ref = ArrayXXf::Constant(5, 3, 0.5); + multiply_assign_using_evaluator(arr, arr_const); + arr_ref *= arr_const; + VERIFY_IS_APPROX(arr, arr_ref); + + divide_assign_using_evaluator(arr.row(1), arr.row(2) + 1); + arr_ref.row(1) /= (arr_ref.row(2) + 1); + VERIFY_IS_APPROX(arr, arr_ref); + } + + { + // test triangular shapes + MatrixXd A = MatrixXd::Random(6,6), B(6,6), C(6,6), D(6,6); + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView(), MatrixXd(A.triangularView())); + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A; + copy_using_evaluator(B.triangularView(), A); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A)"); + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A.triangularView(); + copy_using_evaluator(B.triangularView(), A.triangularView()); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A.triangularView())"); + + + A.setRandom();B.setRandom(); + C = B; C.triangularView() = A.triangularView().transpose(); + copy_using_evaluator(B.triangularView(), A.triangularView().transpose()); + VERIFY(B.isApprox(C) && "copy_using_evaluator(B.triangularView(), A.triangularView().transpose())"); + + + A.setRandom();B.setRandom(); C = B; D = A; + C.triangularView().swap(D.triangularView()); + swap_using_evaluator(B.triangularView(), A.triangularView()); + VERIFY(B.isApprox(C) && "swap_using_evaluator(B.triangularView(), A.triangularView())"); + + + VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.triangularView(),A), MatrixXd(A.triangularView()*A)); + + VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.selfadjointView(),A), MatrixXd(A.selfadjointView()*A)); + } + + { + // test diagonal shapes + VectorXd d = VectorXd::Random(6); + MatrixXd A = MatrixXd::Random(6,6), B(6,6); + A.setRandom();B.setRandom(); + + VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(d.asDiagonal(),A), MatrixXd(d.asDiagonal()*A)); + VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(A,d.asDiagonal()), MatrixXd(A*d.asDiagonal())); + } + + { + // test CoeffReadCost + Matrix4d a, b; + VERIFY_IS_EQUAL( get_cost(a), 1 ); + VERIFY_IS_EQUAL( get_cost(a+b), 3); + VERIFY_IS_EQUAL( get_cost(2*a+b), 4); + VERIFY_IS_EQUAL( get_cost(a*b), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(b)), 15); + VERIFY_IS_EQUAL( get_cost(a*(a*b)), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a*b)), 15); + VERIFY_IS_EQUAL( get_cost(a*(a+b)), 1); + VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a+b)), 15); + } +} diff --git a/gtsam/3rdparty/Eigen/test/fastmath.cpp b/gtsam/3rdparty/Eigen/test/fastmath.cpp new file mode 100644 index 000000000..cc5db0746 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/fastmath.cpp @@ -0,0 +1,99 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +void check(bool b, bool ref) +{ + std::cout << b; + if(b==ref) + std::cout << " OK "; + else + std::cout << " BAD "; +} + +#if EIGEN_COMP_MSVC && EIGEN_COMP_MSVC < 1800 +namespace std { + template bool (isfinite)(T x) { return _finite(x); } + template bool (isnan)(T x) { return _isnan(x); } + template bool (isinf)(T x) { return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; } +} +#endif + +template +void check_inf_nan(bool dryrun) { + Matrix m(10); + m.setRandom(); + m(3) = std::numeric_limits::quiet_NaN(); + + if(dryrun) + { + std::cout << "std::isfinite(" << m(3) << ") = "; check((std::isfinite)(m(3)),false); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(3)), false); std::cout << "\n"; + std::cout << "std::isinf(" << m(3) << ") = "; check((std::isinf)(m(3)),false); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(3)), false); std::cout << "\n"; + std::cout << "std::isnan(" << m(3) << ") = "; check((std::isnan)(m(3)),true); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(3)), true); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 1); std::cout << "\n"; + std::cout << "\n"; + } + else + { + VERIFY( !(numext::isfinite)(m(3)) ); + VERIFY( !(numext::isinf)(m(3)) ); + VERIFY( (numext::isnan)(m(3)) ); + VERIFY( !m.allFinite() ); + VERIFY( m.hasNaN() ); + } + T hidden_zero = (std::numeric_limits::min)()*(std::numeric_limits::min)(); + m(4) /= hidden_zero; + if(dryrun) + { + std::cout << "std::isfinite(" << m(4) << ") = "; check((std::isfinite)(m(4)),false); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(4)), false); std::cout << "\n"; + std::cout << "std::isinf(" << m(4) << ") = "; check((std::isinf)(m(4)),true); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(4)), true); std::cout << "\n"; + std::cout << "std::isnan(" << m(4) << ") = "; check((std::isnan)(m(4)),false); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(4)), false); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 1); std::cout << "\n"; + std::cout << "\n"; + } + else + { + VERIFY( !(numext::isfinite)(m(4)) ); + VERIFY( (numext::isinf)(m(4)) ); + VERIFY( !(numext::isnan)(m(4)) ); + VERIFY( !m.allFinite() ); + VERIFY( m.hasNaN() ); + } + m(3) = 0; + if(dryrun) + { + std::cout << "std::isfinite(" << m(3) << ") = "; check((std::isfinite)(m(3)),true); std::cout << " ; numext::isfinite = "; check((numext::isfinite)(m(3)), true); std::cout << "\n"; + std::cout << "std::isinf(" << m(3) << ") = "; check((std::isinf)(m(3)),false); std::cout << " ; numext::isinf = "; check((numext::isinf)(m(3)), false); std::cout << "\n"; + std::cout << "std::isnan(" << m(3) << ") = "; check((std::isnan)(m(3)),false); std::cout << " ; numext::isnan = "; check((numext::isnan)(m(3)), false); std::cout << "\n"; + std::cout << "allFinite: "; check(m.allFinite(), 0); std::cout << "\n"; + std::cout << "hasNaN: "; check(m.hasNaN(), 0); std::cout << "\n"; + std::cout << "\n\n"; + } + else + { + VERIFY( (numext::isfinite)(m(3)) ); + VERIFY( !(numext::isinf)(m(3)) ); + VERIFY( !(numext::isnan)(m(3)) ); + VERIFY( !m.allFinite() ); + VERIFY( !m.hasNaN() ); + } +} + +void test_fastmath() { + std::cout << "*** float *** \n\n"; check_inf_nan(true); + std::cout << "*** double ***\n\n"; check_inf_nan(true); + std::cout << "*** long double *** \n\n"; check_inf_nan(true); + + check_inf_nan(false); + check_inf_nan(false); + check_inf_nan(false); +} diff --git a/gtsam/3rdparty/Eigen/test/first_aligned.cpp b/gtsam/3rdparty/Eigen/test/first_aligned.cpp index 467f94510..ae2d4bc42 100644 --- a/gtsam/3rdparty/Eigen/test/first_aligned.cpp +++ b/gtsam/3rdparty/Eigen/test/first_aligned.cpp @@ -13,7 +13,7 @@ template void test_first_aligned_helper(Scalar *array, int size) { const int packet_size = sizeof(Scalar) * internal::packet_traits::size; - VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_aligned(array, size)) % packet_size) == 0); + VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_default_aligned(array, size)) % packet_size) == 0); } template @@ -21,7 +21,7 @@ void test_none_aligned_helper(Scalar *array, int size) { EIGEN_UNUSED_VARIABLE(array); EIGEN_UNUSED_VARIABLE(size); - VERIFY(internal::packet_traits::size == 1 || internal::first_aligned(array, size) == size); + VERIFY(internal::packet_traits::size == 1 || internal::first_default_aligned(array, size) == size); } struct some_non_vectorizable_type { float x; }; @@ -41,7 +41,7 @@ void test_first_aligned() test_first_aligned_helper(array_double+1, 50); test_first_aligned_helper(array_double+2, 50); - double *array_double_plus_4_bytes = (double*)(size_t(array_double)+4); + double *array_double_plus_4_bytes = (double*)(internal::UIntPtr(array_double)+4); test_none_aligned_helper(array_double_plus_4_bytes, 50); test_none_aligned_helper(array_double_plus_4_bytes+1, 50); diff --git a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp index 84663ad1f..d2339a651 100644 --- a/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_alignedbox.cpp @@ -16,7 +16,7 @@ using namespace std; template EIGEN_DONT_INLINE -void kill_extra_precision(T& x) { eigen_assert(&x != 0); } +void kill_extra_precision(T& x) { eigen_assert((void*)(&x) != (void*)0); } template void alignedbox(const BoxType& _box) @@ -48,12 +48,21 @@ template void alignedbox(const BoxType& _box) b0.extend(p0); b0.extend(p1); VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1)); + VERIFY(b0.contains(b0.center())); + VERIFY_IS_APPROX(b0.center(),(p0+p1)/Scalar(2)); (b2 = b0).extend(b1); VERIFY(b2.contains(b0)); VERIFY(b2.contains(b1)); VERIFY_IS_APPROX(b2.clamp(b0), b0); + // intersection + BoxType box1(VectorType::Random(dim)); + box1.extend(VectorType::Random(dim)); + BoxType box2(VectorType::Random(dim)); + box2.extend(VectorType::Random(dim)); + + VERIFY(box1.intersects(box2) == !box1.intersection(box2).isEmpty()); // alignment -- make sure there is no memory alignment assertion BoxType *bp0 = new BoxType(dim); diff --git a/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp b/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp index b4830bd41..932ebe773 100644 --- a/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_eulerangles.cpp @@ -26,16 +26,16 @@ void verify_euler(const Matrix& ea, int i, int j, int k) VERIFY_IS_APPROX(m, mbis); /* If I==K, and ea[1]==0, then there no unique solution. */ /* The remark apply in the case where I!=K, and |ea[1]| is close to pi/2. */ - if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(M_PI/2),test_precision())) ) + if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision())) ) VERIFY((ea-eabis).norm() <= test_precision()); // approx_or_less_than does not work for 0 VERIFY(0 < eabis[0] || test_isMuchSmallerThan(eabis[0], Scalar(1))); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(M_PI)); - VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(M_PI), eabis[1]); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(M_PI)); - VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(M_PI), eabis[2]); - VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(M_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(EIGEN_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[1]); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(EIGEN_PI)); + VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[2]); + VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(EIGEN_PI)); } template void check_all_var(const Matrix& ea) @@ -64,7 +64,7 @@ template void eulerangles() typedef Quaternion Quaternionx; typedef AngleAxis AngleAxisx; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Quaternionx q1; q1 = AngleAxisx(a, Vector3::Random().normalized()); Matrix3 m; @@ -84,13 +84,13 @@ template void eulerangles() check_all_var(ea); // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi]. - ea = (Array3::Random() + Array3(1,0,0))*Scalar(M_PI)*Array3(0.5,1,1); + ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1); check_all_var(ea); - ea[2] = ea[0] = internal::random(0,Scalar(M_PI)); + ea[2] = ea[0] = internal::random(0,Scalar(EIGEN_PI)); check_all_var(ea); - ea[0] = ea[1] = internal::random(0,Scalar(M_PI)); + ea[0] = ea[1] = internal::random(0,Scalar(EIGEN_PI)); check_all_var(ea); ea[1] = 0; diff --git a/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp b/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp index 01330308a..2187c7bf9 100644 --- a/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_homogeneous.cpp @@ -38,6 +38,10 @@ template void homogeneous(void) hv0 << v0, 1; VERIFY_IS_APPROX(v0.homogeneous(), hv0); VERIFY_IS_APPROX(v0, hv0.hnormalized()); + + VERIFY_IS_APPROX(v0.homogeneous().sum(), hv0.sum()); + VERIFY_IS_APPROX(v0.homogeneous().minCoeff(), hv0.minCoeff()); + VERIFY_IS_APPROX(v0.homogeneous().maxCoeff(), hv0.maxCoeff()); hm0 << m0, ones.transpose(); VERIFY_IS_APPROX(m0.colwise().homogeneous(), hm0); @@ -59,7 +63,6 @@ template void homogeneous(void) VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t2, v0.transpose().rowwise().homogeneous() * t2); - m0.transpose().rowwise().homogeneous().eval(); VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t2, m0.transpose().rowwise().homogeneous() * t2); @@ -84,7 +87,7 @@ template void homogeneous(void) VERIFY_IS_APPROX(aff * pts.colwise().homogeneous(), (aff * pts1).colwise().hnormalized()); VERIFY_IS_APPROX(caff * pts.colwise().homogeneous(), (caff * pts1).colwise().hnormalized()); VERIFY_IS_APPROX(proj * pts.colwise().homogeneous(), (proj * pts1)); - + VERIFY_IS_APPROX((aff * pts1).colwise().hnormalized(), aff * pts); VERIFY_IS_APPROX((caff * pts1).colwise().hnormalized(), caff * pts); @@ -93,6 +96,23 @@ template void homogeneous(void) VERIFY_IS_APPROX((aff * pts2).colwise().hnormalized(), aff * pts2.colwise().hnormalized()); VERIFY_IS_APPROX((caff * pts2).colwise().hnormalized(), caff * pts2.colwise().hnormalized()); VERIFY_IS_APPROX((proj * pts2).colwise().hnormalized(), (proj * pts2.colwise().hnormalized().colwise().homogeneous()).colwise().hnormalized()); + + // Test combination of homogeneous + + VERIFY_IS_APPROX( (t2 * v0.homogeneous()).hnormalized(), + (t2.template topLeftCorner() * v0 + t2.template topRightCorner()) + / ((t2.template bottomLeftCorner<1,Size>()*v0).value() + t2(Size,Size)) ); + + VERIFY_IS_APPROX( (t2 * pts.colwise().homogeneous()).colwise().hnormalized(), + (Matrix(t2 * pts1).colwise().hnormalized()) ); + + VERIFY_IS_APPROX( (t2 .lazyProduct( v0.homogeneous() )).hnormalized(), (t2 * v0.homogeneous()).hnormalized() ); + VERIFY_IS_APPROX( (t2 .lazyProduct ( pts.colwise().homogeneous() )).colwise().hnormalized(), (t2 * pts1).colwise().hnormalized() ); + + VERIFY_IS_APPROX( (v0.transpose().homogeneous() .lazyProduct( t2 )).hnormalized(), (v0.transpose().homogeneous()*t2).hnormalized() ); + VERIFY_IS_APPROX( (pts.transpose().rowwise().homogeneous() .lazyProduct( t2 )).rowwise().hnormalized(), (pts1.transpose()*t2).rowwise().hnormalized() ); + + VERIFY_IS_APPROX( (t2.template triangularView() * v0.homogeneous()).eval(), (t2.template triangularView()*hv0) ); } void test_geo_homogeneous() diff --git a/gtsam/3rdparty/Eigen/test/geo_hyperplane.cpp b/gtsam/3rdparty/Eigen/test/geo_hyperplane.cpp index 327537801..27892850d 100644 --- a/gtsam/3rdparty/Eigen/test/geo_hyperplane.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_hyperplane.cpp @@ -18,10 +18,12 @@ template void hyperplane(const HyperplaneType& _plane) /* this test covers the following files: Hyperplane.h */ + using std::abs; typedef typename HyperplaneType::Index Index; const Index dim = _plane.dim(); enum { Options = HyperplaneType::Options }; typedef typename HyperplaneType::Scalar Scalar; + typedef typename HyperplaneType::RealScalar RealScalar; typedef Matrix VectorType; typedef Matrix MatrixType; @@ -42,7 +44,10 @@ template void hyperplane(const HyperplaneType& _plane) VERIFY_IS_APPROX( n1.dot(n1), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) ); - VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0 ); + if(numext::abs2(s0)>RealScalar(1e-6)) + VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0); + else + VERIFY_IS_MUCH_SMALLER_THAN( abs(pl1.signedDistance(p1 + n1 * s0) - s0), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) ); VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 + pl1.normal().unitOrthogonal() * s1), Scalar(1) ); @@ -52,6 +57,8 @@ template void hyperplane(const HyperplaneType& _plane) MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ(); DiagonalMatrix scaling(VectorType::Random()); Translation translation(VectorType::Random()); + + while(scaling.diagonal().cwiseAbs().minCoeff() void hyperplane(const HyperplaneType& _plane) VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation) - .absDistance((rot*scaling*translation) * p1), Scalar(1) ); + .absDistance((rot*scaling*translation) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); pl2 = pl1; VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry) .absDistance((rot*translation) * p1), Scalar(1) ); + VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) ); } // casting @@ -90,9 +100,9 @@ template void lines() Vector u = Vector::Random(); Vector v = Vector::Random(); Scalar a = internal::random(); - while (abs(a-1) < 1e-4) a = internal::random(); - while (u.norm() < 1e-4) u = Vector::Random(); - while (v.norm() < 1e-4) v = Vector::Random(); + while (abs(a-1) < Scalar(1e-4)) a = internal::random(); + while (u.norm() < Scalar(1e-4)) u = Vector::Random(); + while (v.norm() < Scalar(1e-4)) v = Vector::Random(); HLine line_u = HLine::Through(center + u, center + a*u); HLine line_v = HLine::Through(center + v, center + a*v); @@ -104,12 +114,15 @@ template void lines() Vector result = line_u.intersection(line_v); // the lines should intersect at the point we called "center" - VERIFY_IS_APPROX(result, center); + if(abs(a-1) > Scalar(1e-2) && abs(v.normalized().dot(u.normalized())) void hyperplane_alignment() typedef Hyperplane Plane3a; typedef Hyperplane Plane3u; - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* array3u = array3+1; Plane3a *p1 = ::new(reinterpret_cast(array1)) Plane3a; @@ -161,8 +174,8 @@ template void hyperplane_alignment() VERIFY_IS_APPROX(p1->coeffs(), p2->coeffs()); VERIFY_IS_APPROX(p1->coeffs(), p3->coeffs()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES > 0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Plane3a)); #endif } diff --git a/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp b/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp index c836dae40..e178df257 100644 --- a/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_orthomethods.cpp @@ -33,12 +33,16 @@ template void orthomethods_3() VERIFY_IS_MUCH_SMALLER_THAN(v1.dot(v1.cross(v2)), Scalar(1)); VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v2), Scalar(1)); VERIFY_IS_MUCH_SMALLER_THAN(v2.dot(v1.cross(v2)), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(Vector3::Random()).dot(v1), Scalar(1)); Matrix3 mat3; mat3 << v0.normalized(), (v0.cross(v1)).normalized(), (v0.cross(v1).cross(v0)).normalized(); VERIFY(mat3.isUnitary()); - + + mat3.setRandom(); + VERIFY_IS_APPROX(v0.cross(mat3*v1), -(mat3*v1).cross(v0)); + VERIFY_IS_APPROX(v0.cross(mat3.lazyProduct(v1)), -(mat3.lazyProduct(v1)).cross(v0)); // colwise/rowwise cross product mat3.setRandom(); @@ -47,6 +51,13 @@ template void orthomethods_3() int i = internal::random(0,2); mcross = mat3.colwise().cross(vec3); VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3)); + + VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(vec3)).diagonal().cwiseAbs().sum(), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(Vector3::Random())).diagonal().cwiseAbs().sum(), Scalar(1)); + + VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * mat3.colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1)); + VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * Matrix3::Random().colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1)); + mcross = mat3.rowwise().cross(vec3); VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3)); @@ -57,6 +68,7 @@ template void orthomethods_3() v40.w() = v41.w() = v42.w() = 0; v42.template head<3>() = v40.template head<3>().cross(v41.template head<3>()); VERIFY_IS_APPROX(v40.cross3(v41), v42); + VERIFY_IS_MUCH_SMALLER_THAN(v40.cross3(Vector4::Random()).dot(v40), Scalar(1)); // check mixed product typedef Matrix RealVector3; diff --git a/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp b/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp index f0462d40a..9bf5f3c1d 100644 --- a/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_parametrizedline.cpp @@ -66,9 +66,9 @@ template void parametrizedline_alignment() typedef ParametrizedLine Line4a; typedef ParametrizedLine Line4u; - EIGEN_ALIGN16 Scalar array1[8]; - EIGEN_ALIGN16 Scalar array2[8]; - EIGEN_ALIGN16 Scalar array3[8+1]; + EIGEN_ALIGN_MAX Scalar array1[16]; + EIGEN_ALIGN_MAX Scalar array2[16]; + EIGEN_ALIGN_MAX Scalar array3[16+1]; Scalar* array3u = array3+1; Line4a *p1 = ::new(reinterpret_cast(array1)) Line4a; @@ -85,8 +85,8 @@ template void parametrizedline_alignment() VERIFY_IS_APPROX(p1->direction(), p2->direction()); VERIFY_IS_APPROX(p1->direction(), p3->direction()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Line4a)); #endif } diff --git a/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp b/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp index 1694b32c7..96889e722 100644 --- a/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_quaternion.cpp @@ -30,8 +30,8 @@ template void check_slerp(const QuatType& q0, const QuatType& Scalar largeEps = test_precision(); Scalar theta_tot = AA(q1*q0.inverse()).angle(); - if(theta_tot>M_PI) - theta_tot = Scalar(2.*M_PI)-theta_tot; + if(theta_tot>Scalar(EIGEN_PI)) + theta_tot = Scalar(2.)*Scalar(EIGEN_PI)-theta_tot; for(Scalar t=0; t<=Scalar(1.001); t+=Scalar(0.1)) { QuatType q = q0.slerp(t,q1); @@ -49,13 +49,13 @@ template void quaternion(void) */ using std::abs; typedef Matrix Vector3; - typedef Matrix Vector4; + typedef Matrix Matrix3; typedef Quaternion Quaternionx; typedef AngleAxis AngleAxisx; Scalar largeEps = test_precision(); if (internal::is_same::value) - largeEps = 1e-3f; + largeEps = Scalar(1e-3); Scalar eps = internal::random() * Scalar(1e-2); @@ -64,8 +64,8 @@ template void quaternion(void) v2 = Vector3::Random(), v3 = Vector3::Random(); - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)), - b = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)), + b = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); // Quaternion: Identity(), setIdentity(); Quaternionx q1, q2; @@ -82,8 +82,8 @@ template void quaternion(void) // angular distance Scalar refangle = abs(AngleAxisx(q1.inverse()*q2).angle()); - if (refangle>Scalar(M_PI)) - refangle = Scalar(2)*Scalar(M_PI) - refangle; + if (refangle>Scalar(EIGEN_PI)) + refangle = Scalar(2)*Scalar(EIGEN_PI) - refangle; if((q1.coeffs()-q2.coeffs()).norm() > 10*largeEps) { @@ -101,6 +101,11 @@ template void quaternion(void) q2 = q1.toRotationMatrix(); VERIFY_IS_APPROX(q1*v1,q2*v1); + Matrix3 rot1(q1); + VERIFY_IS_APPROX(q1*v1,rot1*v1); + Quaternionx q3(rot1.transpose()*rot1); + VERIFY_IS_APPROX(q3*v1,v1); + // angle-axis conversion AngleAxisx aa = AngleAxisx(q1); @@ -109,8 +114,8 @@ template void quaternion(void) // Do not execute the test if the rotation angle is almost zero, or // the rotation axis and v1 are almost parallel. if (abs(aa.angle()) > 5*test_precision() - && (aa.axis() - v1.normalized()).norm() < 1.99 - && (aa.axis() + v1.normalized()).norm() < 1.99) + && (aa.axis() - v1.normalized()).norm() < Scalar(1.99) + && (aa.axis() + v1.normalized()).norm() < Scalar(1.99)) { VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1); } @@ -151,19 +156,19 @@ template void quaternion(void) Quaternionx *q = new Quaternionx; delete q; - q1 = AngleAxisx(a, v0.normalized()); - q2 = AngleAxisx(b, v1.normalized()); + q1 = Quaternionx::UnitRandom(); + q2 = Quaternionx::UnitRandom(); check_slerp(q1,q2); q1 = AngleAxisx(b, v1.normalized()); - q2 = AngleAxisx(b+Scalar(M_PI), v1.normalized()); + q2 = AngleAxisx(b+Scalar(EIGEN_PI), v1.normalized()); check_slerp(q1,q2); q1 = AngleAxisx(b, v1.normalized()); q2 = AngleAxisx(-b, -v1.normalized()); check_slerp(q1,q2); - q1.coeffs() = Vector4::Random().normalized(); + q1 = Quaternionx::UnitRandom(); q2.coeffs() = -q1.coeffs(); check_slerp(q1,q2); } @@ -179,11 +184,11 @@ template void mapQuaternion(void){ Vector3 v0 = Vector3::Random(), v1 = Vector3::Random(); - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* array3unaligned = array3+1; MQuaternionA mq1(array1); @@ -232,9 +237,9 @@ template void quaternionAlignment(void){ typedef Quaternion QuaternionA; typedef Quaternion QuaternionUA; - EIGEN_ALIGN16 Scalar array1[4]; - EIGEN_ALIGN16 Scalar array2[4]; - EIGEN_ALIGN16 Scalar array3[4+1]; + EIGEN_ALIGN_MAX Scalar array1[4]; + EIGEN_ALIGN_MAX Scalar array2[4]; + EIGEN_ALIGN_MAX Scalar array3[4+1]; Scalar* arrayunaligned = array3+1; QuaternionA *q1 = ::new(reinterpret_cast(array1)) QuaternionA; @@ -247,8 +252,8 @@ template void quaternionAlignment(void){ VERIFY_IS_APPROX(q1->coeffs(), q2->coeffs()); VERIFY_IS_APPROX(q1->coeffs(), q3->coeffs()); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY - if(internal::packet_traits::Vectorizable) + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(internal::packet_traits::Vectorizable && internal::packet_traits::size<=4) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(arrayunaligned)) QuaternionA)); #endif } diff --git a/gtsam/3rdparty/Eigen/test/geo_transformations.cpp b/gtsam/3rdparty/Eigen/test/geo_transformations.cpp old mode 100644 new mode 100755 index 383c42bad..278e527c2 --- a/gtsam/3rdparty/Eigen/test/geo_transformations.cpp +++ b/gtsam/3rdparty/Eigen/test/geo_transformations.cpp @@ -12,6 +12,17 @@ #include #include +template +Matrix angleToVec(T a) +{ + return Matrix(std::cos(a), std::sin(a)); +} + +// This permits to workaround a bug in clang/llvm code generation. +template +EIGEN_DONT_INLINE +void dont_over_optimize(T& x) { volatile typename T::Scalar tmp = x(0); x(0) = tmp; } + template void non_projective_only() { /* this test covers the following files: @@ -29,7 +40,7 @@ template void non_projective_only() Transform3 t0, t1, t2; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Quaternionx q1, q2; @@ -97,16 +108,14 @@ template void transformations() v1 = Vector3::Random(); Matrix3 matrot1, m; - Scalar a = internal::random(-Scalar(M_PI), Scalar(M_PI)); - Scalar s0 = internal::random(), - s1 = internal::random(); + Scalar a = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); + Scalar s0 = internal::random(), s1 = internal::random(); while(v0.norm() < test_precision()) v0 = Vector3::Random(); while(v1.norm() < test_precision()) v1 = Vector3::Random(); - VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0); - VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(M_PI), v0.unitOrthogonal()) * v0); + VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(EIGEN_PI), v0.unitOrthogonal()) * v0); if(abs(cos(a)) > test_precision()) { VERIFY_IS_APPROX(cos(a)*v0.squaredNorm(), v0.dot(AngleAxisx(a, v0.unitOrthogonal()) * v0)); @@ -132,14 +141,16 @@ template void transformations() AngleAxisx aa = AngleAxisx(q1); VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - if(abs(aa.angle()) > NumTraits::dummy_precision()) + // The following test is stable only if 2*angle != angle and v1 is not colinear with axis + if( (abs(aa.angle()) > test_precision()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision())) ) { VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) ); } aa.fromRotationMatrix(aa.toRotationMatrix()); VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1); - if(abs(aa.angle()) > NumTraits::dummy_precision()) + // The following test is stable only if 2*angle != angle and v1 is not colinear with axis + if( (abs(aa.angle()) > test_precision()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision())) ) { VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) ); } @@ -158,7 +169,7 @@ template void transformations() // TODO complete the tests ! a = 0; while (abs(a)(-Scalar(0.4)*Scalar(M_PI), Scalar(0.4)*Scalar(M_PI)); + a = internal::random(-Scalar(0.4)*Scalar(EIGEN_PI), Scalar(0.4)*Scalar(EIGEN_PI)); q1 = AngleAxisx(a, v0.normalized()); Transform3 t0, t1, t2; @@ -204,7 +215,7 @@ template void transformations() tmat4.matrix()(3,3) = Scalar(1); VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix()); - Scalar a3 = internal::random(-Scalar(M_PI), Scalar(M_PI)); + Scalar a3 = internal::random(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)); Vector3 v3 = Vector3::Random().normalized(); AngleAxisx aa3(a3, v3); Transform3 t3(aa3); @@ -216,12 +227,15 @@ template void transformations() t4 *= aa3; VERIFY_IS_APPROX(t3.matrix(), t4.matrix()); - v3 = Vector3::Random(); + do { + v3 = Vector3::Random(); + dont_over_optimize(v3); + } while (v3.cwiseAbs().minCoeff()::epsilon()); Translation3 tv3(v3); Transform3 t5(tv3); t4 = tv3; VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); - t4.translate(-v3); + t4.translate((-v3).eval()); VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity()); t4 *= tv3; VERIFY_IS_APPROX(t5.matrix(), t4.matrix()); @@ -413,12 +427,28 @@ template void transformations() VERIFY_IS_APPROX(r2d1f.template cast(),r2d1); Rotation2D r2d1d = r2d1.template cast(); VERIFY_IS_APPROX(r2d1d.template cast(),r2d1); - - t20 = Translation2(v20) * (Rotation2D(s0) * Eigen::Scaling(s0)); - t21 = Translation2(v20) * Rotation2D(s0) * Eigen::Scaling(s0); - VERIFY_IS_APPROX(t20,t21); + for(int k=0; k<100; ++k) + { + Scalar angle = internal::random(-100,100); + Rotation2D rot2(angle); + VERIFY( rot2.smallestPositiveAngle() >= 0 ); + VERIFY( rot2.smallestPositiveAngle() <= Scalar(2)*Scalar(EIGEN_PI) ); + VERIFY_IS_APPROX( angleToVec(rot2.smallestPositiveAngle()), angleToVec(rot2.angle()) ); + + VERIFY( rot2.smallestAngle() >= -Scalar(EIGEN_PI) ); + VERIFY( rot2.smallestAngle() <= Scalar(EIGEN_PI) ); + VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot2.angle()) ); + + Matrix rot2_as_mat(rot2); + Rotation2D rot3(rot2_as_mat); + VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot3.angle()) ); + } + + s0 = internal::random(-100,100); + s1 = internal::random(-100,100); Rotation2D R0(s0), R1(s1); + t20 = Translation2(v20) * (R0 * Eigen::Scaling(s0)); t21 = Translation2(v20) * R0 * Eigen::Scaling(s0); VERIFY_IS_APPROX(t20,t21); @@ -428,9 +458,24 @@ template void transformations() VERIFY_IS_APPROX(t20,t21); VERIFY_IS_APPROX(s0, (R0.slerp(0, R1)).angle()); - VERIFY_IS_APPROX(s1, (R0.slerp(1, R1)).angle()); - VERIFY_IS_APPROX(s0, (R0.slerp(0.5, R0)).angle()); - VERIFY_IS_APPROX(Scalar(0), (R0.slerp(0.5, R0.inverse())).angle()); + VERIFY_IS_APPROX( angleToVec(R1.smallestPositiveAngle()), angleToVec((R0.slerp(1, R1)).smallestPositiveAngle()) ); + VERIFY_IS_APPROX(R0.smallestPositiveAngle(), (R0.slerp(0.5, R0)).smallestPositiveAngle()); + + if(std::cos(s0)>0) + VERIFY_IS_MUCH_SMALLER_THAN((R0.slerp(0.5, R0.inverse())).smallestAngle(), Scalar(1)); + else + VERIFY_IS_APPROX(Scalar(EIGEN_PI), (R0.slerp(0.5, R0.inverse())).smallestPositiveAngle()); + + // Check path length + Scalar l = 0; + int path_steps = 100; + for(int k=0; k::epsilon()*Scalar(path_steps/2))); // check basic features { @@ -520,9 +565,9 @@ template void transform_alignment() typedef Transform Projective3a; typedef Transform Projective3u; - EIGEN_ALIGN16 Scalar array1[16]; - EIGEN_ALIGN16 Scalar array2[16]; - EIGEN_ALIGN16 Scalar array3[16+1]; + EIGEN_ALIGN_MAX Scalar array1[16]; + EIGEN_ALIGN_MAX Scalar array2[16]; + EIGEN_ALIGN_MAX Scalar array3[16+1]; Scalar* array3u = array3+1; Projective3a *p1 = ::new(reinterpret_cast(array1)) Projective3a; @@ -538,7 +583,7 @@ template void transform_alignment() VERIFY_IS_APPROX( (*p1) * (*p1), (*p2)*(*p3)); - #if defined(EIGEN_VECTORIZE) && EIGEN_ALIGN_STATICALLY + #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0 if(internal::packet_traits::Vectorizable) VERIFY_RAISES_ASSERT((::new(reinterpret_cast(array3u)) Projective3a)); #endif @@ -594,7 +639,7 @@ void test_geo_transformations() CALL_SUBTEST_7(( transform_products() )); CALL_SUBTEST_7(( transform_products() )); - CALL_SUBTEST_8(( transform_associativity(Rotation2D(internal::random()*double(3.14))) )); - CALL_SUBTEST_8(( transform_associativity(Quaterniond(Vector4d::Random().normalized())) )); + CALL_SUBTEST_8(( transform_associativity(Rotation2D(internal::random()*double(EIGEN_PI))) )); + CALL_SUBTEST_8(( transform_associativity(Quaterniond::UnitRandom()) )); } } diff --git a/gtsam/3rdparty/Eigen/test/half_float.cpp b/gtsam/3rdparty/Eigen/test/half_float.cpp new file mode 100644 index 000000000..3d2410aef --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/half_float.cpp @@ -0,0 +1,264 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include + +#include "main.h" + +#include + +// Make sure it's possible to forward declare Eigen::half +namespace Eigen { +struct half; +} + +using Eigen::half; + +void test_conversion() +{ + using Eigen::half_impl::__half; + + // Conversion from float. + VERIFY_IS_EQUAL(half(1.0f).x, 0x3c00); + VERIFY_IS_EQUAL(half(0.5f).x, 0x3800); + VERIFY_IS_EQUAL(half(0.33333f).x, 0x3555); + VERIFY_IS_EQUAL(half(0.0f).x, 0x0000); + VERIFY_IS_EQUAL(half(-0.0f).x, 0x8000); + VERIFY_IS_EQUAL(half(65504.0f).x, 0x7bff); + VERIFY_IS_EQUAL(half(65536.0f).x, 0x7c00); // Becomes infinity. + + // Denormals. + VERIFY_IS_EQUAL(half(-5.96046e-08f).x, 0x8001); + VERIFY_IS_EQUAL(half(5.96046e-08f).x, 0x0001); + VERIFY_IS_EQUAL(half(1.19209e-07f).x, 0x0002); + + // Verify round-to-nearest-even behavior. + float val1 = float(half(__half(0x3c00))); + float val2 = float(half(__half(0x3c01))); + float val3 = float(half(__half(0x3c02))); + VERIFY_IS_EQUAL(half(0.5f * (val1 + val2)).x, 0x3c00); + VERIFY_IS_EQUAL(half(0.5f * (val2 + val3)).x, 0x3c02); + + // Conversion from int. + VERIFY_IS_EQUAL(half(-1).x, 0xbc00); + VERIFY_IS_EQUAL(half(0).x, 0x0000); + VERIFY_IS_EQUAL(half(1).x, 0x3c00); + VERIFY_IS_EQUAL(half(2).x, 0x4000); + VERIFY_IS_EQUAL(half(3).x, 0x4200); + + // Conversion from bool. + VERIFY_IS_EQUAL(half(false).x, 0x0000); + VERIFY_IS_EQUAL(half(true).x, 0x3c00); + + // Conversion to float. + VERIFY_IS_EQUAL(float(half(__half(0x0000))), 0.0f); + VERIFY_IS_EQUAL(float(half(__half(0x3c00))), 1.0f); + + // Denormals. + VERIFY_IS_APPROX(float(half(__half(0x8001))), -5.96046e-08f); + VERIFY_IS_APPROX(float(half(__half(0x0001))), 5.96046e-08f); + VERIFY_IS_APPROX(float(half(__half(0x0002))), 1.19209e-07f); + + // NaNs and infinities. + VERIFY(!(numext::isinf)(float(half(65504.0f)))); // Largest finite number. + VERIFY(!(numext::isnan)(float(half(0.0f)))); + VERIFY((numext::isinf)(float(half(__half(0xfc00))))); + VERIFY((numext::isnan)(float(half(__half(0xfc01))))); + VERIFY((numext::isinf)(float(half(__half(0x7c00))))); + VERIFY((numext::isnan)(float(half(__half(0x7c01))))); + +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY((numext::isnan)(float(half(0.0 / 0.0)))); + VERIFY((numext::isinf)(float(half(1.0 / 0.0)))); + VERIFY((numext::isinf)(float(half(-1.0 / 0.0)))); +#endif + + // Exactly same checks as above, just directly on the half representation. + VERIFY(!(numext::isinf)(half(__half(0x7bff)))); + VERIFY(!(numext::isnan)(half(__half(0x0000)))); + VERIFY((numext::isinf)(half(__half(0xfc00)))); + VERIFY((numext::isnan)(half(__half(0xfc01)))); + VERIFY((numext::isinf)(half(__half(0x7c00)))); + VERIFY((numext::isnan)(half(__half(0x7c01)))); + +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY((numext::isnan)(half(0.0 / 0.0))); + VERIFY((numext::isinf)(half(1.0 / 0.0))); + VERIFY((numext::isinf)(half(-1.0 / 0.0))); +#endif +} + +void test_numtraits() +{ + std::cout << "epsilon = " << NumTraits::epsilon() << " (0x" << std::hex << NumTraits::epsilon().x << ")" << std::endl; + std::cout << "highest = " << NumTraits::highest() << " (0x" << std::hex << NumTraits::highest().x << ")" << std::endl; + std::cout << "lowest = " << NumTraits::lowest() << " (0x" << std::hex << NumTraits::lowest().x << ")" << std::endl; + std::cout << "min = " << (std::numeric_limits::min)() << " (0x" << std::hex << half((std::numeric_limits::min)()).x << ")" << std::endl; + std::cout << "denorm min = " << (std::numeric_limits::denorm_min)() << " (0x" << std::hex << half((std::numeric_limits::denorm_min)()).x << ")" << std::endl; + std::cout << "infinity = " << NumTraits::infinity() << " (0x" << std::hex << NumTraits::infinity().x << ")" << std::endl; + std::cout << "quiet nan = " << NumTraits::quiet_NaN() << " (0x" << std::hex << NumTraits::quiet_NaN().x << ")" << std::endl; + std::cout << "signaling nan = " << std::numeric_limits::signaling_NaN() << " (0x" << std::hex << std::numeric_limits::signaling_NaN().x << ")" << std::endl; + + VERIFY(NumTraits::IsSigned); + + VERIFY_IS_EQUAL( std::numeric_limits::infinity().x, half(std::numeric_limits::infinity()).x ); + VERIFY_IS_EQUAL( std::numeric_limits::quiet_NaN().x, half(std::numeric_limits::quiet_NaN()).x ); + VERIFY_IS_EQUAL( std::numeric_limits::signaling_NaN().x, half(std::numeric_limits::signaling_NaN()).x ); + VERIFY( (std::numeric_limits::min)() > half(0.f) ); + VERIFY( (std::numeric_limits::denorm_min)() > half(0.f) ); + VERIFY( (std::numeric_limits::min)()/half(2) > half(0.f) ); + VERIFY_IS_EQUAL( (std::numeric_limits::denorm_min)()/half(2), half(0.f) ); +} + +void test_arithmetic() +{ + VERIFY_IS_EQUAL(float(half(2) + half(2)), 4); + VERIFY_IS_EQUAL(float(half(2) + half(-2)), 0); + VERIFY_IS_APPROX(float(half(0.33333f) + half(0.66667f)), 1.0f); + VERIFY_IS_EQUAL(float(half(2.0f) * half(-5.5f)), -11.0f); + VERIFY_IS_APPROX(float(half(1.0f) / half(3.0f)), 0.33333f); + VERIFY_IS_EQUAL(float(-half(4096.0f)), -4096.0f); + VERIFY_IS_EQUAL(float(-half(-4096.0f)), 4096.0f); +} + +void test_comparison() +{ + VERIFY(half(1.0f) > half(0.5f)); + VERIFY(half(0.5f) < half(1.0f)); + VERIFY(!(half(1.0f) < half(0.5f))); + VERIFY(!(half(0.5f) > half(1.0f))); + + VERIFY(!(half(4.0f) > half(4.0f))); + VERIFY(!(half(4.0f) < half(4.0f))); + + VERIFY(!(half(0.0f) < half(-0.0f))); + VERIFY(!(half(-0.0f) < half(0.0f))); + VERIFY(!(half(0.0f) > half(-0.0f))); + VERIFY(!(half(-0.0f) > half(0.0f))); + + VERIFY(half(0.2f) > half(-1.0f)); + VERIFY(half(-1.0f) < half(0.2f)); + VERIFY(half(-16.0f) < half(-15.0f)); + + VERIFY(half(1.0f) == half(1.0f)); + VERIFY(half(1.0f) != half(2.0f)); + + // Comparisons with NaNs and infinities. +#if !EIGEN_COMP_MSVC + // Visual Studio errors out on divisions by 0 + VERIFY(!(half(0.0 / 0.0) == half(0.0 / 0.0))); + VERIFY(half(0.0 / 0.0) != half(0.0 / 0.0)); + + VERIFY(!(half(1.0) == half(0.0 / 0.0))); + VERIFY(!(half(1.0) < half(0.0 / 0.0))); + VERIFY(!(half(1.0) > half(0.0 / 0.0))); + VERIFY(half(1.0) != half(0.0 / 0.0)); + + VERIFY(half(1.0) < half(1.0 / 0.0)); + VERIFY(half(1.0) > half(-1.0 / 0.0)); +#endif +} + +void test_basic_functions() +{ + VERIFY_IS_EQUAL(float(numext::abs(half(3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(abs(half(3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(numext::abs(half(-3.5f))), 3.5f); + VERIFY_IS_EQUAL(float(abs(half(-3.5f))), 3.5f); + + VERIFY_IS_EQUAL(float(numext::floor(half(3.5f))), 3.0f); + VERIFY_IS_EQUAL(float(floor(half(3.5f))), 3.0f); + VERIFY_IS_EQUAL(float(numext::floor(half(-3.5f))), -4.0f); + VERIFY_IS_EQUAL(float(floor(half(-3.5f))), -4.0f); + + VERIFY_IS_EQUAL(float(numext::ceil(half(3.5f))), 4.0f); + VERIFY_IS_EQUAL(float(ceil(half(3.5f))), 4.0f); + VERIFY_IS_EQUAL(float(numext::ceil(half(-3.5f))), -3.0f); + VERIFY_IS_EQUAL(float(ceil(half(-3.5f))), -3.0f); + + VERIFY_IS_APPROX(float(numext::sqrt(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(sqrt(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::sqrt(half(4.0f))), 2.0f); + VERIFY_IS_APPROX(float(sqrt(half(4.0f))), 2.0f); + + VERIFY_IS_APPROX(float(numext::pow(half(0.0f), half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(pow(half(0.0f), half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::pow(half(2.0f), half(2.0f))), 4.0f); + VERIFY_IS_APPROX(float(pow(half(2.0f), half(2.0f))), 4.0f); + + VERIFY_IS_EQUAL(float(numext::exp(half(0.0f))), 1.0f); + VERIFY_IS_EQUAL(float(exp(half(0.0f))), 1.0f); + VERIFY_IS_APPROX(float(numext::exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI)); + VERIFY_IS_APPROX(float(exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI)); + + VERIFY_IS_EQUAL(float(numext::log(half(1.0f))), 0.0f); + VERIFY_IS_EQUAL(float(log(half(1.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::log(half(10.0f))), 2.30273f); + VERIFY_IS_APPROX(float(log(half(10.0f))), 2.30273f); + + VERIFY_IS_EQUAL(float(numext::log1p(half(0.0f))), 0.0f); + VERIFY_IS_EQUAL(float(log1p(half(0.0f))), 0.0f); + VERIFY_IS_APPROX(float(numext::log1p(half(10.0f))), 2.3978953f); + VERIFY_IS_APPROX(float(log1p(half(10.0f))), 2.3978953f); +} + +void test_trigonometric_functions() +{ + VERIFY_IS_APPROX(numext::cos(half(0.0f)), half(cosf(0.0f))); + VERIFY_IS_APPROX(cos(half(0.0f)), half(cosf(0.0f))); + VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI)), half(cosf(EIGEN_PI))); + //VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI/2)), half(cosf(EIGEN_PI/2))); + //VERIFY_IS_APPROX(numext::cos(half(3*EIGEN_PI/2)), half(cosf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::cos(half(3.5f)), half(cosf(3.5f))); + + VERIFY_IS_APPROX(numext::sin(half(0.0f)), half(sinf(0.0f))); + VERIFY_IS_APPROX(sin(half(0.0f)), half(sinf(0.0f))); + // VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI)), half(sinf(EIGEN_PI))); + VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI/2)), half(sinf(EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::sin(half(3*EIGEN_PI/2)), half(sinf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::sin(half(3.5f)), half(sinf(3.5f))); + + VERIFY_IS_APPROX(numext::tan(half(0.0f)), half(tanf(0.0f))); + VERIFY_IS_APPROX(tan(half(0.0f)), half(tanf(0.0f))); + // VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI)), half(tanf(EIGEN_PI))); + // VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI/2)), half(tanf(EIGEN_PI/2))); + //VERIFY_IS_APPROX(numext::tan(half(3*EIGEN_PI/2)), half(tanf(3*EIGEN_PI/2))); + VERIFY_IS_APPROX(numext::tan(half(3.5f)), half(tanf(3.5f))); +} + +void test_array() +{ + typedef Array ArrayXh; + Index size = internal::random(1,10); + Index i = internal::random(0,size-1); + ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size); + VERIFY_IS_APPROX( a1+a1, half(2)*a1 ); + VERIFY( (a1.abs() >= half(0)).all() ); + VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() ); + + VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() ); + a1(i) = half(-10.); + VERIFY_IS_EQUAL( a1.minCoeff(), half(-10.) ); + a1(i) = half(10.); + VERIFY_IS_EQUAL( a1.maxCoeff(), half(10.) ); + + std::stringstream ss; + ss << a1; +} + +void test_half_float() +{ + CALL_SUBTEST(test_conversion()); + CALL_SUBTEST(test_numtraits()); + CALL_SUBTEST(test_arithmetic()); + CALL_SUBTEST(test_comparison()); + CALL_SUBTEST(test_basic_functions()); + CALL_SUBTEST(test_trigonometric_functions()); + CALL_SUBTEST(test_array()); +} diff --git a/gtsam/3rdparty/Eigen/test/incomplete_cholesky.cpp b/gtsam/3rdparty/Eigen/test/incomplete_cholesky.cpp new file mode 100644 index 000000000..59ffe9259 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/incomplete_cholesky.cpp @@ -0,0 +1,65 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015-2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +// #define EIGEN_DONT_VECTORIZE +// #define EIGEN_MAX_ALIGN_BYTES 0 +#include "sparse_solver.h" +#include +#include + +template void test_incomplete_cholesky_T() +{ + typedef SparseMatrix SparseMatrixType; + ConjugateGradient > > cg_illt_lower_amd; + ConjugateGradient > > cg_illt_lower_nat; + ConjugateGradient > > cg_illt_upper_amd; + ConjugateGradient > > cg_illt_upper_nat; + ConjugateGradient > > cg_illt_uplo_amd; + + + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_amd) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_nat) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_amd) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_nat) ); + CALL_SUBTEST( check_sparse_spd_solving(cg_illt_uplo_amd) ); +} + +void test_incomplete_cholesky() +{ + CALL_SUBTEST_1(( test_incomplete_cholesky_T() )); + CALL_SUBTEST_2(( test_incomplete_cholesky_T, int>() )); + CALL_SUBTEST_3(( test_incomplete_cholesky_T() )); + +#ifdef EIGEN_TEST_PART_1 + // regression for bug 1150 + for(int N = 1; N<20; ++N) + { + Eigen::MatrixXd b( N, N ); + b.setOnes(); + + Eigen::SparseMatrix m( N, N ); + m.reserve(Eigen::VectorXi::Constant(N,4)); + for( int i = 0; i < N; ++i ) + { + m.insert( i, i ) = 1; + m.coeffRef( i, i / 2 ) = 2; + m.coeffRef( i, i / 3 ) = 2; + m.coeffRef( i, i / 4 ) = 2; + } + + Eigen::SparseMatrix A; + A = m * m.transpose(); + + Eigen::ConjugateGradient, + Eigen::Lower | Eigen::Upper, + Eigen::IncompleteCholesky > solver( A ); + VERIFY(solver.preconditioner().info() == Eigen::Success); + VERIFY(solver.info() == Eigen::Success); + } +#endif +} diff --git a/gtsam/3rdparty/Eigen/test/inplace_decomposition.cpp b/gtsam/3rdparty/Eigen/test/inplace_decomposition.cpp new file mode 100644 index 000000000..92d0d91b6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/inplace_decomposition.cpp @@ -0,0 +1,110 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" +#include +#include +#include + +// This file test inplace decomposition through Ref<>, as supported by Cholesky, LU, and QR decompositions. + +template void inplace(bool square = false, bool SPD = false) +{ + typedef typename MatrixType::Scalar Scalar; + typedef Matrix RhsType; + typedef Matrix ResType; + + Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random(2,EIGEN_TEST_MAX_SIZE/2) : Index(MatrixType::RowsAtCompileTime); + Index cols = MatrixType::ColsAtCompileTime==Dynamic ? (square?rows:internal::random(2,rows)) : Index(MatrixType::ColsAtCompileTime); + + MatrixType A = MatrixType::Random(rows,cols); + RhsType b = RhsType::Random(rows); + ResType x(cols); + + if(SPD) + { + assert(square); + A.topRows(cols) = A.topRows(cols).adjoint() * A.topRows(cols); + A.diagonal().array() += 1e-3; + } + + MatrixType A0 = A; + MatrixType A1 = A; + + DecType dec(A); + + // Check that the content of A has been modified + VERIFY_IS_NOT_APPROX( A, A0 ); + + // Check that the decomposition is correct: + if(rows==cols) + { + VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } + + // Check that modifying A breaks the current dec: + A.setRandom(); + if(rows==cols) + { + VERIFY_IS_NOT_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_NOT_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } + + // Check that calling compute(A1) does not modify A1: + A = A0; + dec.compute(A1); + VERIFY_IS_EQUAL(A0,A1); + VERIFY_IS_NOT_APPROX( A, A0 ); + if(rows==cols) + { + VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b ); + } + else + { + VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b ); + } +} + + +void test_inplace_decomposition() +{ + EIGEN_UNUSED typedef Matrix Matrix43d; + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(( inplace >, MatrixXd>(true,true) )); + CALL_SUBTEST_1(( inplace >, Matrix4d>(true,true) )); + + CALL_SUBTEST_2(( inplace >, MatrixXd>(true,true) )); + CALL_SUBTEST_2(( inplace >, Matrix4d>(true,true) )); + + CALL_SUBTEST_3(( inplace >, MatrixXd>(true,false) )); + CALL_SUBTEST_3(( inplace >, Matrix4d>(true,false) )); + + CALL_SUBTEST_4(( inplace >, MatrixXd>(true,false) )); + CALL_SUBTEST_4(( inplace >, Matrix4d>(true,false) )); + + CALL_SUBTEST_5(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_5(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_6(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_6(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_7(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_7(( inplace >, Matrix43d>(false,false) )); + + CALL_SUBTEST_8(( inplace >, MatrixXd>(false,false) )); + CALL_SUBTEST_8(( inplace >, Matrix43d>(false,false) )); + } +} diff --git a/gtsam/3rdparty/Eigen/test/integer_types.cpp b/gtsam/3rdparty/Eigen/test/integer_types.cpp index 950f8e9be..a21f73a81 100644 --- a/gtsam/3rdparty/Eigen/test/integer_types.cpp +++ b/gtsam/3rdparty/Eigen/test/integer_types.cpp @@ -158,4 +158,12 @@ void test_integer_types() CALL_SUBTEST_8( integer_type_tests(Matrix(1, 5)) ); } +#ifdef EIGEN_TEST_PART_9 + VERIFY_IS_EQUAL(internal::scalar_div_cost::value, 8); + VERIFY_IS_EQUAL(internal::scalar_div_cost::value, 8); + if(sizeof(long)>sizeof(int)) { + VERIFY(internal::scalar_div_cost::value > internal::scalar_div_cost::value); + VERIFY(internal::scalar_div_cost::value > internal::scalar_div_cost::value); + } +#endif } diff --git a/gtsam/3rdparty/Eigen/test/inverse.cpp b/gtsam/3rdparty/Eigen/test/inverse.cpp index 8187b088d..5c6777a18 100644 --- a/gtsam/3rdparty/Eigen/test/inverse.cpp +++ b/gtsam/3rdparty/Eigen/test/inverse.cpp @@ -68,6 +68,15 @@ template void inverse(const MatrixType& m) VERIFY_IS_MUCH_SMALLER_THAN(abs(det-m3.determinant()), RealScalar(1)); m3.computeInverseWithCheck(m4, invertible); VERIFY( rows==1 ? invertible : !invertible ); + + // check with submatrices + { + Matrix m5; + m5.setRandom(); + m5.topLeftCorner(rows,rows) = m1; + m2 = m5.template topLeftCorner().inverse(); + VERIFY_IS_APPROX( (m5.template topLeftCorner()), m2.inverse() ); + } #endif // check in-place inversion @@ -93,12 +102,16 @@ void test_inverse() CALL_SUBTEST_3( inverse(Matrix3f()) ); CALL_SUBTEST_4( inverse(Matrix4f()) ); CALL_SUBTEST_4( inverse(Matrix()) ); + s = internal::random(50,320); CALL_SUBTEST_5( inverse(MatrixXf(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(25,100); CALL_SUBTEST_6( inverse(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + CALL_SUBTEST_7( inverse(Matrix4d()) ); CALL_SUBTEST_7( inverse(Matrix()) ); } - TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/is_same_dense.cpp b/gtsam/3rdparty/Eigen/test/is_same_dense.cpp new file mode 100644 index 000000000..2c7838ce9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/is_same_dense.cpp @@ -0,0 +1,33 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +using internal::is_same_dense; + +void test_is_same_dense() +{ + typedef Matrix ColMatrixXd; + ColMatrixXd m1(10,10); + Ref ref_m1(m1); + Ref const_ref_m1(m1); + VERIFY(is_same_dense(m1,m1)); + VERIFY(is_same_dense(m1,ref_m1)); + VERIFY(is_same_dense(const_ref_m1,m1)); + VERIFY(is_same_dense(const_ref_m1,ref_m1)); + + VERIFY(is_same_dense(m1.block(0,0,m1.rows(),m1.cols()),m1)); + VERIFY(!is_same_dense(m1.row(0),m1.col(0))); + + Ref const_ref_m1_row(m1.row(1)); + VERIFY(!is_same_dense(m1.row(1),const_ref_m1_row)); + + Ref const_ref_m1_col(m1.col(1)); + VERIFY(is_same_dense(m1.col(1),const_ref_m1_col)); +} diff --git a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp index 12c556e59..7f5f71562 100644 --- a/gtsam/3rdparty/Eigen/test/jacobisvd.cpp +++ b/gtsam/3rdparty/Eigen/test/jacobisvd.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2008-2014 Gael Guennebaud // Copyright (C) 2009 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -14,279 +14,47 @@ #include "main.h" #include -template -void jacobisvd_check_full(const MatrixType& m, const JacobiSVD& svd) -{ - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime - }; - - typedef typename MatrixType::Scalar Scalar; - typedef Matrix MatrixUType; - typedef Matrix MatrixVType; - - MatrixType sigma = MatrixType::Zero(rows,cols); - sigma.diagonal() = svd.singularValues().template cast(); - MatrixUType u = svd.matrixU(); - MatrixVType v = svd.matrixV(); - - VERIFY_IS_APPROX(m, u * sigma * v.adjoint()); - VERIFY_IS_UNITARY(u); - VERIFY_IS_UNITARY(v); -} - -template -void jacobisvd_compare_to_full(const MatrixType& m, - unsigned int computationOptions, - const JacobiSVD& referenceSvd) -{ - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - Index diagSize = (std::min)(rows, cols); - - JacobiSVD svd(m, computationOptions); - - VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues()); - if(computationOptions & ComputeFullU) - VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU()); - if(computationOptions & ComputeThinU) - VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize)); - if(computationOptions & ComputeFullV) - VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV()); - if(computationOptions & ComputeThinV) - VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize)); -} - -template -void jacobisvd_solve(const MatrixType& m, unsigned int computationOptions) -{ - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; - Index rows = m.rows(); - Index cols = m.cols(); - - enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, - ColsAtCompileTime = MatrixType::ColsAtCompileTime - }; - - typedef Matrix RhsType; - typedef Matrix SolutionType; - - RhsType rhs = RhsType::Random(rows, internal::random(1, cols)); - JacobiSVD svd(m, computationOptions); - - if(internal::is_same::value) svd.setThreshold(1e-8); - else if(internal::is_same::value) svd.setThreshold(1e-4); - - SolutionType x = svd.solve(rhs); - - RealScalar residual = (m*x-rhs).norm(); - // Check that there is no significantly better solution in the neighborhood of x - if(!test_isMuchSmallerThan(residual,rhs.norm())) - { - // If the residual is very small, then we have an exact solution, so we are already good. - for(int k=0;k::epsilon(); - RealScalar residual_y = (m*y-rhs).norm(); - VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); - - y.row(k) = x.row(k).array() - 2*NumTraits::epsilon(); - residual_y = (m*y-rhs).norm(); - VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); - } - } - - // evaluate normal equation which works also for least-squares solutions - if(internal::is_same::value) - { - // This test is not stable with single precision. - // This is probably because squaring m signicantly affects the precision. - VERIFY_IS_APPROX(m.adjoint()*m*x,m.adjoint()*rhs); - } - - // check minimal norm solutions - { - // generate a full-rank m x n problem with m MatrixType2; - typedef Matrix RhsType2; - typedef Matrix MatrixType2T; - Index rank = RankAtCompileTime2==Dynamic ? internal::random(1,cols) : Index(RankAtCompileTime2); - MatrixType2 m2(rank,cols); - int guard = 0; - do { - m2.setRandom(); - } while(m2.jacobiSvd().setThreshold(test_precision()).rank()!=rank && (++guard)<10); - VERIFY(guard<10); - RhsType2 rhs2 = RhsType2::Random(rank); - // use QR to find a reference minimal norm solution - HouseholderQR qr(m2.adjoint()); - Matrix tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView().adjoint().solve(rhs2); - tmp.conservativeResize(cols); - tmp.tail(cols-rank).setZero(); - SolutionType x21 = qr.householderQ() * tmp; - // now check with SVD - JacobiSVD svd2(m2, computationOptions); - SolutionType x22 = svd2.solve(rhs2); - VERIFY_IS_APPROX(m2*x21, rhs2); - VERIFY_IS_APPROX(m2*x22, rhs2); - VERIFY_IS_APPROX(x21, x22); - - // Now check with a rank deficient matrix - typedef Matrix MatrixType3; - typedef Matrix RhsType3; - Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random(rank+1,2*cols) : Index(RowsAtCompileTime3); - Matrix C = Matrix::Random(rows3,rank); - MatrixType3 m3 = C * m2; - RhsType3 rhs3 = C * rhs2; - JacobiSVD svd3(m3, computationOptions); - SolutionType x3 = svd3.solve(rhs3); - if(svd3.rank()!=rank) { - std::cout << m3 << "\n\n"; - std::cout << svd3.singularValues().transpose() << "\n"; - std::cout << svd3.rank() << " == " << rank << "\n"; - std::cout << x21.norm() << " == " << x3.norm() << "\n"; - } -// VERIFY_IS_APPROX(m3*x3, rhs3); - VERIFY_IS_APPROX(m3*x21, rhs3); - VERIFY_IS_APPROX(m2*x3, rhs2); - - VERIFY_IS_APPROX(x21, x3); - } -} - -template -void jacobisvd_test_all_computation_options(const MatrixType& m) -{ - if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols()) - return; - JacobiSVD fullSvd(m, ComputeFullU|ComputeFullV); - CALL_SUBTEST(( jacobisvd_check_full(m, fullSvd) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeFullV) )); - - #if defined __INTEL_COMPILER - // remark #111: statement is unreachable - #pragma warning disable 111 - #endif - if(QRPreconditioner == FullPivHouseholderQRPreconditioner) - return; - - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, 0, fullSvd) )); - - if (MatrixType::ColsAtCompileTime == Dynamic) { - // thin U/V are only available with dynamic number of columns - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU , fullSvd) )); - CALL_SUBTEST(( jacobisvd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeFullU | ComputeThinV) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeFullV) )); - CALL_SUBTEST(( jacobisvd_solve(m, ComputeThinU | ComputeThinV) )); - - // test reconstruction - typedef typename MatrixType::Index Index; - Index diagSize = (std::min)(m.rows(), m.cols()); - JacobiSVD svd(m, ComputeThinU | ComputeThinV); - VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint()); - } -} +#define SVD_DEFAULT(M) JacobiSVD +#define SVD_FOR_MIN_NORM(M) JacobiSVD +#include "svd_common.h" +// Check all variants of JacobiSVD template void jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true) { MatrixType m = a; if(pickrandom) - { - typedef typename MatrixType::Scalar Scalar; - typedef typename MatrixType::RealScalar RealScalar; - typedef typename MatrixType::Index Index; - Index diagSize = (std::min)(a.rows(), a.cols()); - RealScalar s = std::numeric_limits::max_exponent10/4; - s = internal::random(1,s); - Matrix d = Matrix::Random(diagSize); - for(Index k=0; k(-s,s)); - m = Matrix::Random(a.rows(),diagSize) * d.asDiagonal() * Matrix::Random(diagSize,a.cols()); - // cancel some coeffs - Index n = internal::random(0,m.size()-1); - for(Index i=0; i(0,m.rows()-1), internal::random(0,m.cols()-1)) = Scalar(0); - } + svd_fill_random(m); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); - CALL_SUBTEST(( jacobisvd_test_all_computation_options(m) )); + CALL_SUBTEST(( svd_test_all_computation_options >(m, true) )); // check full only + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); + if(m.rows()==m.cols()) + CALL_SUBTEST(( svd_test_all_computation_options >(m, false) )); } template void jacobisvd_verify_assert(const MatrixType& m) { - typedef typename MatrixType::Scalar Scalar; + svd_verify_assert >(m); typedef typename MatrixType::Index Index; Index rows = m.rows(); Index cols = m.cols(); enum { - RowsAtCompileTime = MatrixType::RowsAtCompileTime, ColsAtCompileTime = MatrixType::ColsAtCompileTime }; - typedef Matrix RhsType; - - RhsType rhs(rows); - - JacobiSVD svd; - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.singularValues()) - VERIFY_RAISES_ASSERT(svd.matrixV()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) MatrixType a = MatrixType::Zero(rows, cols); a.setZero(); - svd.compute(a, 0); - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.matrixV()) - svd.singularValues(); - VERIFY_RAISES_ASSERT(svd.solve(rhs)) if (ColsAtCompileTime == Dynamic) { - svd.compute(a, ComputeThinU); - svd.matrixU(); - VERIFY_RAISES_ASSERT(svd.matrixV()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) - - svd.compute(a, ComputeThinV); - svd.matrixV(); - VERIFY_RAISES_ASSERT(svd.matrixU()) - VERIFY_RAISES_ASSERT(svd.solve(rhs)) - JacobiSVD svd_fullqr; VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeFullU|ComputeThinV)) VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeThinV)) VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeFullV)) } - else - { - VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU)) - VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV)) - } } template @@ -302,126 +70,17 @@ void jacobisvd_method() VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).solve(m), m); } -// work around stupid msvc error when constructing at compile time an expression that involves -// a division by zero, even if the numeric type has floating point -template -EIGEN_DONT_INLINE Scalar zero() { return Scalar(0); } - -// workaround aggressive optimization in ICC -template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } - -template -void jacobisvd_inf_nan() -{ - // all this function does is verify we don't iterate infinitely on nan/inf values - - JacobiSVD svd; - typedef typename MatrixType::Scalar Scalar; - Scalar some_inf = Scalar(1) / zero(); - VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf)); - svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV); - - Scalar nan = std::numeric_limits::quiet_NaN(); - VERIFY(nan != nan); - svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV); - - MatrixType m = MatrixType::Zero(10,10); - m(internal::random(0,9), internal::random(0,9)) = some_inf; - svd.compute(m, ComputeFullU | ComputeFullV); - - m = MatrixType::Zero(10,10); - m(internal::random(0,9), internal::random(0,9)) = nan; - svd.compute(m, ComputeFullU | ComputeFullV); - - // regression test for bug 791 - m.resize(3,3); - m << 0, 2*NumTraits::epsilon(), 0.5, - 0, -0.5, 0, - nan, 0, 0; - svd.compute(m, ComputeFullU | ComputeFullV); -} - -// Regression test for bug 286: JacobiSVD loops indefinitely with some -// matrices containing denormal numbers. -void jacobisvd_bug286() -{ -#if defined __INTEL_COMPILER -// shut up warning #239: floating point underflow -#pragma warning push -#pragma warning disable 239 -#endif - Matrix2d M; - M << -7.90884e-313, -4.94e-324, - 0, 5.60844e-313; -#if defined __INTEL_COMPILER -#pragma warning pop -#endif - JacobiSVD svd; - svd.compute(M); // just check we don't loop indefinitely -} - -void jacobisvd_preallocate() -{ - Vector3f v(3.f, 2.f, 1.f); - MatrixXf m = v.asDiagonal(); - - internal::set_is_malloc_allowed(false); - VERIFY_RAISES_ASSERT(VectorXf tmp(10);) - JacobiSVD svd; - internal::set_is_malloc_allowed(true); - svd.compute(m); - VERIFY_IS_APPROX(svd.singularValues(), v); - - JacobiSVD svd2(3,3); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - VERIFY_IS_APPROX(svd2.singularValues(), v); - VERIFY_RAISES_ASSERT(svd2.matrixU()); - VERIFY_RAISES_ASSERT(svd2.matrixV()); - svd2.compute(m, ComputeFullU | ComputeFullV); - VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); - VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - - JacobiSVD svd3(3,3,ComputeFullU|ComputeFullV); - internal::set_is_malloc_allowed(false); - svd2.compute(m); - internal::set_is_malloc_allowed(true); - VERIFY_IS_APPROX(svd2.singularValues(), v); - VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); - VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); - internal::set_is_malloc_allowed(false); - svd2.compute(m, ComputeFullU|ComputeFullV); - internal::set_is_malloc_allowed(true); -} - void test_jacobisvd() { CALL_SUBTEST_3(( jacobisvd_verify_assert(Matrix3f()) )); CALL_SUBTEST_4(( jacobisvd_verify_assert(Matrix4d()) )); CALL_SUBTEST_7(( jacobisvd_verify_assert(MatrixXf(10,12)) )); CALL_SUBTEST_8(( jacobisvd_verify_assert(MatrixXcd(7,5)) )); + + CALL_SUBTEST_11(svd_all_trivial_2x2(jacobisvd)); + CALL_SUBTEST_12(svd_all_trivial_2x2(jacobisvd)); for(int i = 0; i < g_repeat; i++) { - Matrix2cd m; - m << 0, 1, - 0, 1; - CALL_SUBTEST_1(( jacobisvd(m, false) )); - m << 1, 0, - 1, 0; - CALL_SUBTEST_1(( jacobisvd(m, false) )); - - Matrix2d n; - n << 0, 0, - 0, 0; - CALL_SUBTEST_2(( jacobisvd(n, false) )); - n << 0, 0, - 0, 1; - CALL_SUBTEST_2(( jacobisvd(n, false) )); - CALL_SUBTEST_3(( jacobisvd() )); CALL_SUBTEST_4(( jacobisvd() )); CALL_SUBTEST_5(( jacobisvd >() )); @@ -440,8 +99,14 @@ void test_jacobisvd() (void) c; // Test on inf/nan matrix - CALL_SUBTEST_7( jacobisvd_inf_nan() ); - CALL_SUBTEST_10( jacobisvd_inf_nan() ); + CALL_SUBTEST_7( (svd_inf_nan, MatrixXf>()) ); + CALL_SUBTEST_10( (svd_inf_nan, MatrixXd>()) ); + + // bug1395 test compile-time vectors as input + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix()) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix()) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix(r)) )); + CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix(c)) )); } CALL_SUBTEST_7(( jacobisvd(MatrixXf(internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2), internal::random(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) )); @@ -455,8 +120,7 @@ void test_jacobisvd() CALL_SUBTEST_7( JacobiSVD(10,10) ); // Check that preallocation avoids subsequent mallocs - CALL_SUBTEST_9( jacobisvd_preallocate() ); + CALL_SUBTEST_9( svd_preallocate() ); - // Regression check for bug 286 - CALL_SUBTEST_2( jacobisvd_bug286() ); + CALL_SUBTEST_2( svd_underoverflow() ); } diff --git a/gtsam/3rdparty/Eigen/test/linearstructure.cpp b/gtsam/3rdparty/Eigen/test/linearstructure.cpp index 618984d5c..17474af10 100644 --- a/gtsam/3rdparty/Eigen/test/linearstructure.cpp +++ b/gtsam/3rdparty/Eigen/test/linearstructure.cpp @@ -2,11 +2,15 @@ // for linear algebra. // // Copyright (C) 2006-2008 Benoit Jacob +// Copyright (C) 2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static bool g_called; +#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same::value); } + #include "main.h" template void linearStructure(const MatrixType& m) @@ -17,6 +21,7 @@ template void linearStructure(const MatrixType& m) */ typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; Index rows = m.rows(); Index cols = m.cols(); @@ -28,7 +33,7 @@ template void linearStructure(const MatrixType& m) m3(rows, cols); Scalar s1 = internal::random(); - while (abs(s1)<1e-3) s1 = internal::random(); + while (abs(s1)(); Index r = internal::random(0, rows-1), c = internal::random(0, cols-1); @@ -68,8 +73,48 @@ template void linearStructure(const MatrixType& m) VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1); } +// Make sure that complex * real and real * complex are properly optimized +template void real_complex(DenseIndex rows = MatrixType::RowsAtCompileTime, DenseIndex cols = MatrixType::ColsAtCompileTime) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + RealScalar s = internal::random(); + MatrixType m1 = MatrixType::Random(rows, cols); + + g_called = false; + VERIFY_IS_APPROX(s*m1, Scalar(s)*m1); + VERIFY(g_called && "real * matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1*s, m1*Scalar(s)); + VERIFY(g_called && "matrix * real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1/s, m1/Scalar(s)); + VERIFY(g_called && "matrix / real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(s+m1.array(), Scalar(s)+m1.array()); + VERIFY(g_called && "real + matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1.array()+s, m1.array()+Scalar(s)); + VERIFY(g_called && "matrix + real not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(s-m1.array(), Scalar(s)-m1.array()); + VERIFY(g_called && "real - matrix not properly optimized"); + + g_called = false; + VERIFY_IS_APPROX(m1.array()-s, m1.array()-Scalar(s)); + VERIFY(g_called && "matrix - real not properly optimized"); +} + void test_linearstructure() { + g_called = true; + VERIFY(g_called); // avoid `unneeded-internal-declaration` warning. for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( linearStructure(Matrix()) ); CALL_SUBTEST_2( linearStructure(Matrix2f()) ); @@ -80,5 +125,25 @@ void test_linearstructure() CALL_SUBTEST_7( linearStructure(MatrixXi (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); CALL_SUBTEST_8( linearStructure(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_9( linearStructure(ArrayXXf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_10( linearStructure(ArrayXXcf (internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + + CALL_SUBTEST_11( real_complex() ); + CALL_SUBTEST_11( real_complex(10,10) ); + CALL_SUBTEST_11( real_complex(10,10) ); } + +#ifdef EIGEN_TEST_PART_4 + { + // make sure that /=scalar and /scalar do not overflow + // rational: 1.0/4.94e-320 overflow, but m/4.94e-320 should not + Matrix4d m2, m3; + m3 = m2 = Matrix4d::Random()*1e-20; + m2 = m2 / 4.9e-320; + VERIFY_IS_APPROX(m2.cwiseQuotient(m2), Matrix4d::Ones()); + m3 /= 4.9e-320; + VERIFY_IS_APPROX(m3.cwiseQuotient(m3), Matrix4d::Ones()); + + + } +#endif } diff --git a/gtsam/3rdparty/Eigen/test/lscg.cpp b/gtsam/3rdparty/Eigen/test/lscg.cpp new file mode 100644 index 000000000..d49ee00c3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/lscg.cpp @@ -0,0 +1,37 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2011 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "sparse_solver.h" +#include + +template void test_lscg_T() +{ + LeastSquaresConjugateGradient > lscg_colmajor_diag; + LeastSquaresConjugateGradient, IdentityPreconditioner> lscg_colmajor_I; + LeastSquaresConjugateGradient > lscg_rowmajor_diag; + LeastSquaresConjugateGradient, IdentityPreconditioner> lscg_rowmajor_I; + + CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_diag) ); + CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_I) ); + + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_diag) ); + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_I) ); + + CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_diag) ); + CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_I) ); + + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_diag) ); + CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_I) ); +} + +void test_lscg() +{ + CALL_SUBTEST_1(test_lscg_T()); + CALL_SUBTEST_2(test_lscg_T >()); +} diff --git a/gtsam/3rdparty/Eigen/test/lu.cpp b/gtsam/3rdparty/Eigen/test/lu.cpp index 374652694..9787f4d86 100644 --- a/gtsam/3rdparty/Eigen/test/lu.cpp +++ b/gtsam/3rdparty/Eigen/test/lu.cpp @@ -11,6 +11,11 @@ #include using namespace std; +template +typename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) { + return m.cwiseAbs().colwise().sum().maxCoeff(); +} + template void lu_non_invertible() { typedef typename MatrixType::Index Index; @@ -92,6 +97,26 @@ template void lu_non_invertible() // test that the code, which does resize(), may be applied to an xpr m2.block(0,0,m2.rows(),m2.cols()) = lu.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + // test solve with transposed + m3 = MatrixType::Random(rows,cols2); + m2 = m1.transpose()*m3; + m3 = MatrixType::Random(rows,cols2); + lu.template _solve_impl_transposed(m2, m3); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + m3 = MatrixType::Random(rows,cols2); + m3 = lu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + m3 = MatrixType::Random(rows,cols2); + m2 = m1.adjoint()*m3; + m3 = MatrixType::Random(rows,cols2); + lu.template _solve_impl_transposed(m2, m3); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); + m3 = MatrixType::Random(rows,cols2); + m3 = lu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); } template void lu_invertible() @@ -100,9 +125,9 @@ template void lu_invertible() LU.h */ typedef typename NumTraits::Real RealScalar; - DenseIndex size = MatrixType::RowsAtCompileTime; + Index size = MatrixType::RowsAtCompileTime; if( size==Dynamic) - size = internal::random(1,EIGEN_TEST_MAX_SIZE); + size = internal::random(1,EIGEN_TEST_MAX_SIZE); MatrixType m1(size, size), m2(size, size), m3(size, size); FullPivLU lu; @@ -123,7 +148,28 @@ template void lu_invertible() m3 = MatrixType::Random(size,size); m2 = lu.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); - VERIFY_IS_APPROX(m2, lu.inverse()*m3); + MatrixType m1_inverse = lu.inverse(); + VERIFY_IS_APPROX(m2, m1_inverse*m3); + + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse); + const RealScalar rcond_est = lu.rcond(); + // Verify that the estimated condition number is within a factor of 10 of the + // truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + // test solve with transposed + lu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.transpose()*m2); + m3 = MatrixType::Random(size,size); + m3 = lu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + lu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.adjoint()*m2); + m3 = MatrixType::Random(size,size); + m3 = lu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); // Regression test for Bug 302 MatrixType m4 = MatrixType::Random(size,size); @@ -136,14 +182,39 @@ template void lu_partial_piv() PartialPivLU.h */ typedef typename MatrixType::Index Index; - Index rows = internal::random(1,4); - Index cols = rows; + typedef typename NumTraits::Real RealScalar; + Index size = internal::random(1,4); - MatrixType m1(cols, rows); + MatrixType m1(size, size), m2(size, size), m3(size, size); m1.setRandom(); PartialPivLU plu(m1); VERIFY_IS_APPROX(m1, plu.reconstructedMatrix()); + + m3 = MatrixType::Random(size,size); + m2 = plu.solve(m3); + VERIFY_IS_APPROX(m3, m1*m2); + MatrixType m1_inverse = plu.inverse(); + VERIFY_IS_APPROX(m2, m1_inverse*m3); + + RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse); + const RealScalar rcond_est = plu.rcond(); + // Verify that the estimate is within a factor of 10 of the truth. + VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10); + + // test solve with transposed + plu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.transpose()*m2); + m3 = MatrixType::Random(size,size); + m3 = plu.transpose().solve(m2); + VERIFY_IS_APPROX(m2, m1.transpose()*m3); + + // test solve with conjugate transposed + plu.template _solve_impl_transposed(m3, m2); + VERIFY_IS_APPROX(m3, m1.adjoint()*m2); + m3 = MatrixType::Random(size,size); + m3 = plu.adjoint().solve(m2); + VERIFY_IS_APPROX(m2, m1.adjoint()*m3); } template void lu_verify_assert() diff --git a/gtsam/3rdparty/Eigen/test/main.h b/gtsam/3rdparty/Eigen/test/main.h index 664204866..bd5325196 100644 --- a/gtsam/3rdparty/Eigen/test/main.h +++ b/gtsam/3rdparty/Eigen/test/main.h @@ -41,7 +41,14 @@ #include #include #include +#include #include +#if __cplusplus >= 201103L +#include +#ifdef EIGEN_USE_THREADS +#include +#endif +#endif // To test that all calls from Eigen code to std::min() and std::max() are // protected by parenthesis against macro expansion, the min()/max() macros @@ -49,14 +56,48 @@ // compiler error. #define min(A,B) please_protect_your_min_with_parentheses #define max(A,B) please_protect_your_max_with_parentheses +#define isnan(X) please_protect_your_isnan_with_parentheses +#define isinf(X) please_protect_your_isinf_with_parentheses +#define isfinite(X) please_protect_your_isfinite_with_parentheses +#ifdef M_PI +#undef M_PI +#endif +#define M_PI please_use_EIGEN_PI_instead_of_M_PI #define FORBIDDEN_IDENTIFIER (this_identifier_is_forbidden_to_avoid_clashes) this_identifier_is_forbidden_to_avoid_clashes // B0 is defined in POSIX header termios.h #define B0 FORBIDDEN_IDENTIFIER +// Unit tests calling Eigen's blas library must preserve the default blocking size +// to avoid troubles. +#ifndef EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS +#define EIGEN_DEBUG_SMALL_PRODUCT_BLOCKS +#endif // shuts down ICC's remark #593: variable "XXX" was set but never used -#define TEST_SET_BUT_UNUSED_VARIABLE(X) X = X + 0; +#define TEST_SET_BUT_UNUSED_VARIABLE(X) EIGEN_UNUSED_VARIABLE(X) + +#ifdef TEST_ENABLE_TEMPORARY_TRACKING + +static long int nb_temporaries; +static long int nb_temporaries_on_assert = -1; + +inline void on_temporary_creation(long int size) { + // here's a great place to set a breakpoint when debugging failures in this test! + if(size!=0) nb_temporaries++; + if(nb_temporaries_on_assert>0) assert(nb_temporaries g_test_stack; + // level == 0 <=> abort if test fail + // level >= 1 <=> warning message to std::cerr if test fail + static int g_test_level = 0; static int g_repeat; static unsigned int g_seed; static bool g_has_set_repeat, g_has_set_seed; } +#define TRACK std::cerr << __FILE__ << " " << __LINE__ << std::endl +// #define TRACK while() + #define EI_PP_MAKE_STRING2(S) #S #define EI_PP_MAKE_STRING(S) EI_PP_MAKE_STRING2(S) #define EIGEN_DEFAULT_IO_FORMAT IOFormat(4, 0, " ", "\n", "", "", "", "") +#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) + #define EIGEN_EXCEPTIONS +#endif + #ifndef EIGEN_NO_ASSERTION_CHECKING namespace Eigen @@ -135,33 +186,35 @@ namespace Eigen if(report_on_cerr_on_assert_failure) \ std::cerr << #a << " " __FILE__ << "(" << __LINE__ << ")\n"; \ Eigen::no_more_assert = true; \ - throw Eigen::eigen_assert_exception(); \ + EIGEN_THROW_X(Eigen::eigen_assert_exception()); \ } \ else if (Eigen::internal::push_assert) \ { \ eigen_assert_list.push_back(std::string(EI_PP_MAKE_STRING(__FILE__) " (" EI_PP_MAKE_STRING(__LINE__) ") : " #a) ); \ } + #ifdef EIGEN_EXCEPTIONS #define VERIFY_RAISES_ASSERT(a) \ { \ Eigen::no_more_assert = false; \ - Eigen::eigen_assert_list.clear(); \ - Eigen::internal::push_assert = true; \ + Eigen::eigen_assert_list.clear(); \ + Eigen::internal::push_assert = true; \ Eigen::report_on_cerr_on_assert_failure = false; \ try { \ a; \ std::cerr << "One of the following asserts should have been triggered:\n"; \ - for (uint ai=0 ; ai0) + std::cerr << "WARNING: "; std::cerr << "Test " << testname << " failed in " << file << " (" << line << ")" << std::endl << " " << condition_as_string << std::endl; std::cerr << "Stack:\n"; @@ -208,14 +271,20 @@ inline void verify_impl(bool condition, const char *testname, const char *file, for(int i=test_stack_size-1; i>=0; --i) std::cerr << " - " << Eigen::g_test_stack[i] << "\n"; std::cerr << "\n"; - abort(); + if(Eigen::g_test_level==0) + abort(); } } #define VERIFY(a) ::verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a)) -#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b)) -#define VERIFY_IS_APPROX(a, b) VERIFY(test_isApprox(a, b)) +#define VERIFY_GE(a, b) ::verify_impl(a >= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a >= b)) +#define VERIFY_LE(a, b) ::verify_impl(a <= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EI_PP_MAKE_STRING(a <= b)) + + +#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b, true)) +#define VERIFY_IS_NOT_EQUAL(a, b) VERIFY(test_is_equal(a, b, false)) +#define VERIFY_IS_APPROX(a, b) VERIFY(verifyIsApprox(a, b)) #define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_isApprox(a, b)) #define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_isMuchSmallerThan(a, b)) #define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_isMuchSmallerThan(a, b)) @@ -236,9 +305,21 @@ namespace Eigen { template inline typename NumTraits::Real test_precision() { return NumTraits::dummy_precision(); } template<> inline float test_precision() { return 1e-3f; } template<> inline double test_precision() { return 1e-6; } +template<> inline long double test_precision() { return 1e-6l; } template<> inline float test_precision >() { return test_precision(); } template<> inline double test_precision >() { return test_precision(); } -template<> inline long double test_precision() { return 1e-6; } +template<> inline long double test_precision >() { return test_precision(); } + +inline bool test_isApprox(const short& a, const short& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isApprox(const unsigned short& a, const unsigned short& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isApprox(const unsigned int& a, const unsigned int& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isApprox(const long& a, const long& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isApprox(const unsigned long& a, const unsigned long& b) +{ return internal::isApprox(a, b, test_precision()); } inline bool test_isApprox(const int& a, const int& b) { return internal::isApprox(a, b, test_precision()); } @@ -253,14 +334,15 @@ inline bool test_isMuchSmallerThan(const float& a, const float& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const float& a, const float& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } + inline bool test_isApprox(const double& a, const double& b) { return internal::isApprox(a, b, test_precision()); } - inline bool test_isMuchSmallerThan(const double& a, const double& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const double& a, const double& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } +#ifndef EIGEN_TEST_NO_COMPLEX inline bool test_isApprox(const std::complex& a, const std::complex& b) { return internal::isApprox(a, b, test_precision >()); } inline bool test_isMuchSmallerThan(const std::complex& a, const std::complex& b) @@ -271,6 +353,15 @@ inline bool test_isApprox(const std::complex& a, const std::complex& a, const std::complex& b) { return internal::isMuchSmallerThan(a, b, test_precision >()); } +#ifndef EIGEN_TEST_NO_LONGDOUBLE +inline bool test_isApprox(const std::complex& a, const std::complex& b) +{ return internal::isApprox(a, b, test_precision >()); } +inline bool test_isMuchSmallerThan(const std::complex& a, const std::complex& b) +{ return internal::isMuchSmallerThan(a, b, test_precision >()); } +#endif +#endif + +#ifndef EIGEN_TEST_NO_LONGDOUBLE inline bool test_isApprox(const long double& a, const long double& b) { bool ret = internal::isApprox(a, b, test_precision()); @@ -284,13 +375,127 @@ inline bool test_isMuchSmallerThan(const long double& a, const long double& b) { return internal::isMuchSmallerThan(a, b, test_precision()); } inline bool test_isApproxOrLessThan(const long double& a, const long double& b) { return internal::isApproxOrLessThan(a, b, test_precision()); } +#endif // EIGEN_TEST_NO_LONGDOUBLE + +inline bool test_isApprox(const half& a, const half& b) +{ return internal::isApprox(a, b, test_precision()); } +inline bool test_isMuchSmallerThan(const half& a, const half& b) +{ return internal::isMuchSmallerThan(a, b, test_precision()); } +inline bool test_isApproxOrLessThan(const half& a, const half& b) +{ return internal::isApproxOrLessThan(a, b, test_precision()); } + +// test_relative_error returns the relative difference between a and b as a real scalar as used in isApprox. +template +typename NumTraits::NonInteger test_relative_error(const EigenBase &a, const EigenBase &b) +{ + using std::sqrt; + typedef typename NumTraits::NonInteger RealScalar; + typename internal::nested_eval::type ea(a.derived()); + typename internal::nested_eval::type eb(b.derived()); + return sqrt(RealScalar((ea-eb).cwiseAbs2().sum()) / RealScalar((std::min)(eb.cwiseAbs2().sum(),ea.cwiseAbs2().sum()))); +} + +template +typename T1::RealScalar test_relative_error(const T1 &a, const T2 &b, const typename T1::Coefficients* = 0) +{ + return test_relative_error(a.coeffs(), b.coeffs()); +} + +template +typename T1::Scalar test_relative_error(const T1 &a, const T2 &b, const typename T1::MatrixType* = 0) +{ + return test_relative_error(a.matrix(), b.matrix()); +} + +template +S test_relative_error(const Translation &a, const Translation &b) +{ + return test_relative_error(a.vector(), b.vector()); +} + +template +S test_relative_error(const ParametrizedLine &a, const ParametrizedLine &b) +{ + return (std::max)(test_relative_error(a.origin(), b.origin()), test_relative_error(a.origin(), b.origin())); +} + +template +S test_relative_error(const AlignedBox &a, const AlignedBox &b) +{ + return (std::max)(test_relative_error((a.min)(), (b.min)()), test_relative_error((a.max)(), (b.max)())); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const MatrixBase &a, const SparseMatrixBase &b) +{ + return test_relative_error(a,b.toDense()); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const SparseMatrixBase &a, const MatrixBase &b) +{ + return test_relative_error(a.toDense(),b); +} + +template class SparseMatrixBase; +template +typename T1::RealScalar test_relative_error(const SparseMatrixBase &a, const SparseMatrixBase &b) +{ + return test_relative_error(a.toDense(),b.toDense()); +} + +template +typename NumTraits::Real>::NonInteger test_relative_error(const T1 &a, const T2 &b, typename internal::enable_if::Real>::value, T1>::type* = 0) +{ + typedef typename NumTraits::Real>::NonInteger RealScalar; + return numext::sqrt(RealScalar(numext::abs2(a-b))/RealScalar((numext::mini)(numext::abs2(a),numext::abs2(b)))); +} + +template +T test_relative_error(const Rotation2D &a, const Rotation2D &b) +{ + return test_relative_error(a.angle(), b.angle()); +} + +template +T test_relative_error(const AngleAxis &a, const AngleAxis &b) +{ + return (std::max)(test_relative_error(a.angle(), b.angle()), test_relative_error(a.axis(), b.axis())); +} template -inline bool test_isApprox(const Type1& a, const Type2& b) +inline bool test_isApprox(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only { return a.isApprox(b, test_precision()); } +// get_test_precision is a small wrapper to test_precision allowing to return the scalar precision for either scalars or expressions +template +typename NumTraits::Real get_test_precision(const T&, const typename T::Scalar* = 0) +{ + return test_precision::Real>(); +} + +template +typename NumTraits::Real get_test_precision(const T&,typename internal::enable_if::Real>::value, T>::type* = 0) +{ + return test_precision::Real>(); +} + +// verifyIsApprox is a wrapper to test_isApprox that outputs the relative difference magnitude if the test fails. +template +inline bool verifyIsApprox(const Type1& a, const Type2& b) +{ + bool ret = test_isApprox(a,b); + if(!ret) + { + std::cerr << "Difference too large wrt tolerance " << get_test_precision(a) << ", relative error is: " << test_relative_error(a,b) << std::endl; + } + return ret; +} + // The idea behind this function is to compare the two scalars a and b where // the scalar ref is a hint about the expected order of magnitude of a and b. // WARNING: the scalar a and b must be positive @@ -326,17 +531,17 @@ inline bool test_isUnitary(const MatrixBase& m) // Forward declaration to avoid ICC warning template -bool test_is_equal(const T& actual, const U& expected); +bool test_is_equal(const T& actual, const U& expected, bool expect_equal=true); template -bool test_is_equal(const T& actual, const U& expected) +bool test_is_equal(const T& actual, const U& expected, bool expect_equal) { - if (actual==expected) + if ((actual==expected) == expect_equal) return true; // false: std::cerr - << std::endl << " actual = " << actual - << std::endl << " expected = " << expected << std::endl << std::endl; + << "\n actual = " << actual + << "\n expected " << (expect_equal ? "= " : "!=") << expected << "\n\n"; return false; } @@ -347,11 +552,10 @@ bool test_is_equal(const T& actual, const U& expected) */ // Forward declaration to avoid ICC warning template -void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typename MatrixType::Index rows, typename MatrixType::Index cols, MatrixType& m); +void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m); template -void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typename MatrixType::Index rows, typename MatrixType::Index cols, MatrixType& m) +void createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m) { - typedef typename internal::traits::Index Index; typedef typename internal::traits::Scalar Scalar; enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime }; @@ -388,11 +592,10 @@ void createRandomPIMatrixOfRank(typename MatrixType::Index desired_rank, typenam // Forward declaration to avoid ICC warning template -void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size); +void randomPermutationVector(PermutationVectorType& v, Index size); template -void randomPermutationVector(PermutationVectorType& v, typename PermutationVectorType::Index size) +void randomPermutationVector(PermutationVectorType& v, Index size) { - typedef typename PermutationVectorType::Index Index; typedef typename PermutationVectorType::Scalar Scalar; v.resize(size); for(Index i = 0; i < size; ++i) v(i) = Scalar(i); @@ -411,12 +614,7 @@ template bool isNotNaN(const T& x) return x==x; } -template bool isNaN(const T& x) -{ - return x!=x; -} - -template bool isInf(const T& x) +template bool isPlusInf(const T& x) { return x > NumTraits::highest(); } @@ -437,13 +635,15 @@ template struct GetDifferentType > // Forward declaration to avoid ICC warning template std::string type_name(); -template std::string type_name() { return "other"; } -template<> std::string type_name() { return "float"; } -template<> std::string type_name() { return "double"; } -template<> std::string type_name() { return "int"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } -template<> std::string type_name >() { return "complex"; } +template std::string type_name() { return "other"; } +template<> std::string type_name() { return "float"; } +template<> std::string type_name() { return "double"; } +template<> std::string type_name() { return "long double"; } +template<> std::string type_name() { return "int"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } +template<> std::string type_name >() { return "complex"; } // forward declaration of the main test function void EIGEN_CAT(test_,EIGEN_TEST_FUNC)(); @@ -550,3 +750,8 @@ int main(int argc, char *argv[]) // remark #1572: floating-point equality and inequality comparisons are unreliable #pragma warning disable 279 383 1418 1572 #endif + +#ifdef _MSC_VER + // 4503 - decorated name length exceeded, name was truncated + #pragma warning( disable : 4503) +#endif diff --git a/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp b/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp index 58904fa37..6a84c5897 100644 --- a/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp +++ b/gtsam/3rdparty/Eigen/test/mapped_matrix.cpp @@ -13,6 +13,8 @@ #include "main.h" +#define EIGEN_TESTMAP_MAX_SIZE 256 + template void map_class_vector(const VectorType& m) { typedef typename VectorType::Index Index; @@ -20,23 +22,26 @@ template void map_class_vector(const VectorType& m) Index size = m.size(); - // test Map.h Scalar* array1 = internal::aligned_new(size); Scalar* array2 = internal::aligned_new(size); Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; + Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3; + Scalar array4[EIGEN_TESTMAP_MAX_SIZE]; - Map(array1, size) = VectorType::Random(size); - Map(array2, size) = Map(array1, size); + Map(array1, size) = VectorType::Random(size); + Map(array2, size) = Map(array1, size); Map(array3unaligned, size) = Map(array1, size); - VectorType ma1 = Map(array1, size); - VectorType ma2 = Map(array2, size); + Map(array4, size) = Map(array1, size); + VectorType ma1 = Map(array1, size); + VectorType ma2 = Map(array2, size); VectorType ma3 = Map(array3unaligned, size); + VectorType ma4 = Map(array4, size); VERIFY_IS_EQUAL(ma1, ma2); VERIFY_IS_EQUAL(ma1, ma3); + VERIFY_IS_EQUAL(ma1, ma4); #ifdef EIGEN_VECTORIZE - if(internal::packet_traits::Vectorizable) - VERIFY_RAISES_ASSERT((Map(array3unaligned, size))) + if(internal::packet_traits::Vectorizable && size>=AlignedMax) + VERIFY_RAISES_ASSERT((Map(array3unaligned, size))) #endif internal::aligned_delete(array1, size); @@ -50,23 +55,64 @@ template void map_class_matrix(const MatrixType& m) typedef typename MatrixType::Scalar Scalar; Index rows = m.rows(), cols = m.cols(), size = rows*cols; + Scalar s1 = internal::random(); - // test Map.h + // array1 and array2 -> aligned heap allocation Scalar* array1 = internal::aligned_new(size); for(int i = 0; i < size; i++) array1[i] = Scalar(1); Scalar* array2 = internal::aligned_new(size); for(int i = 0; i < size; i++) array2[i] = Scalar(1); + // array3unaligned -> unaligned pointer to heap Scalar* array3 = new Scalar[size+1]; for(int i = 0; i < size+1; i++) array3[i] = Scalar(1); - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; - Map(array1, rows, cols) = MatrixType::Ones(rows,cols); - Map(array2, rows, cols) = Map(array1, rows, cols); - Map(array3unaligned, rows, cols) = Map(array1, rows, cols); - MatrixType ma1 = Map(array1, rows, cols); - MatrixType ma2 = Map(array2, rows, cols); + Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3; + Scalar array4[256]; + if(size<=256) + for(int i = 0; i < size; i++) array4[i] = Scalar(1); + + Map map1(array1, rows, cols); + Map map2(array2, rows, cols); + Map map3(array3unaligned, rows, cols); + Map map4(array4, rows, cols); + + VERIFY_IS_EQUAL(map1, MatrixType::Ones(rows,cols)); + VERIFY_IS_EQUAL(map2, MatrixType::Ones(rows,cols)); + VERIFY_IS_EQUAL(map3, MatrixType::Ones(rows,cols)); + map1 = MatrixType::Random(rows,cols); + map2 = map1; + map3 = map1; + MatrixType ma1 = map1; + MatrixType ma2 = map2; + MatrixType ma3 = map3; + VERIFY_IS_EQUAL(map1, map2); + VERIFY_IS_EQUAL(map1, map3); VERIFY_IS_EQUAL(ma1, ma2); - MatrixType ma3 = Map(array3unaligned, rows, cols); VERIFY_IS_EQUAL(ma1, ma3); + VERIFY_IS_EQUAL(ma1, map3); + + VERIFY_IS_APPROX(s1*map1, s1*map2); + VERIFY_IS_APPROX(s1*ma1, s1*ma2); + VERIFY_IS_EQUAL(s1*ma1, s1*ma3); + VERIFY_IS_APPROX(s1*map1, s1*map3); + + map2 *= s1; + map3 *= s1; + VERIFY_IS_APPROX(s1*map1, map2); + VERIFY_IS_APPROX(s1*map1, map3); + + if(size<=256) + { + VERIFY_IS_EQUAL(map4, MatrixType::Ones(rows,cols)); + map4 = map1; + MatrixType ma4 = map4; + VERIFY_IS_EQUAL(map1, map4); + VERIFY_IS_EQUAL(ma1, map4); + VERIFY_IS_EQUAL(ma1, ma4); + VERIFY_IS_APPROX(s1*map1, s1*map4); + + map4 *= s1; + VERIFY_IS_APPROX(s1*map1, map4); + } internal::aligned_delete(array1, size); internal::aligned_delete(array2, size); @@ -80,11 +126,10 @@ template void map_static_methods(const VectorType& m) Index size = m.size(); - // test Map.h Scalar* array1 = internal::aligned_new(size); Scalar* array2 = internal::aligned_new(size); Scalar* array3 = new Scalar[size+1]; - Scalar* array3unaligned = size_t(array3)%16 == 0 ? array3+1 : array3; + Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3; VectorType::MapAligned(array1, size) = VectorType::Random(size); VectorType::Map(array2, size) = VectorType::Map(array1, size); @@ -109,9 +154,9 @@ template void check_const_correctness(const PlainObjec // verify that map-to-const don't have LvalueBit typedef typename internal::add_const::type ConstPlainObjectType; VERIFY( !(internal::traits >::Flags & LvalueBit) ); - VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(internal::traits >::Flags & LvalueBit) ); VERIFY( !(Map::Flags & LvalueBit) ); - VERIFY( !(Map::Flags & LvalueBit) ); + VERIFY( !(Map::Flags & LvalueBit) ); } template @@ -142,6 +187,7 @@ void test_mapped_matrix() CALL_SUBTEST_1( map_class_vector(Matrix()) ); CALL_SUBTEST_1( check_const_correctness(Matrix()) ); CALL_SUBTEST_2( map_class_vector(Vector4d()) ); + CALL_SUBTEST_2( map_class_vector(VectorXd(13)) ); CALL_SUBTEST_2( check_const_correctness(Matrix4d()) ); CALL_SUBTEST_3( map_class_vector(RowVector4f()) ); CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) ); diff --git a/gtsam/3rdparty/Eigen/test/mapstaticmethods.cpp b/gtsam/3rdparty/Eigen/test/mapstaticmethods.cpp index 5b512bde4..06272d106 100644 --- a/gtsam/3rdparty/Eigen/test/mapstaticmethods.cpp +++ b/gtsam/3rdparty/Eigen/test/mapstaticmethods.cpp @@ -69,7 +69,8 @@ struct mapstaticmethods_impl { static void run(const PlainObjectType& m) { - int rows = m.rows(), cols = m.cols(); + typedef typename PlainObjectType::Index Index; + Index rows = m.rows(), cols = m.cols(); int i = internal::random(2,5), j = internal::random(2,5); @@ -115,7 +116,8 @@ struct mapstaticmethods_impl { static void run(const PlainObjectType& v) { - int size = v.size(); + typedef typename PlainObjectType::Index Index; + Index size = v.size(); int i = internal::random(2,5); diff --git a/gtsam/3rdparty/Eigen/test/mapstride.cpp b/gtsam/3rdparty/Eigen/test/mapstride.cpp index b1dc9de2a..4858f8fea 100644 --- a/gtsam/3rdparty/Eigen/test/mapstride.cpp +++ b/gtsam/3rdparty/Eigen/test/mapstride.cpp @@ -23,7 +23,7 @@ template void map_class_vector(const VectorTy Scalar* a_array = internal::aligned_new(arraysize+1); Scalar* array = a_array; if(Alignment!=Aligned) - array = (Scalar*)(ptrdiff_t(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + array = (Scalar*)(internal::IntPtr(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); { Map > map(array, size); @@ -56,16 +56,30 @@ template void map_class_matrix(const MatrixTy Index rows = _m.rows(), cols = _m.cols(); MatrixType m = MatrixType::Random(rows,cols); + Scalar s1 = internal::random(); Index arraysize = 2*(rows+4)*(cols+4); - Scalar* a_array = internal::aligned_new(arraysize+1); - Scalar* array = a_array; + Scalar* a_array1 = internal::aligned_new(arraysize+1); + Scalar* array1 = a_array1; if(Alignment!=Aligned) - array = (Scalar*)(ptrdiff_t(a_array) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + array1 = (Scalar*)(internal::IntPtr(a_array1) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + Scalar a_array2[256]; + Scalar* array2 = a_array2; + if(Alignment!=Aligned) + array2 = (Scalar*)(internal::IntPtr(a_array2) + (internal::packet_traits::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits::Real))); + else + array2 = (Scalar*)(((internal::UIntPtr(a_array2)+EIGEN_MAX_ALIGN_BYTES-1)/EIGEN_MAX_ALIGN_BYTES)*EIGEN_MAX_ALIGN_BYTES); + Index maxsize2 = a_array2 - array2 + 256; + // test no inner stride and some dynamic outer stride + for(int k=0; k<2; ++k) { + if(k==1 && (m.innerSize()+1)*m.outerSize() > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + Map > map(array, rows, cols, OuterStride(m.innerSize()+1)); map = m; VERIFY(map.outerStride() == map.innerSize()+1); @@ -75,11 +89,19 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } // test no inner stride and an outer stride of +4. This is quite important as for fixed-size matrices, // this allows to hit the special case where it's vectorizable. + for(int k=0; k<2; ++k) { + if(k==1 && (m.innerSize()+4)*m.outerSize() > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + enum { InnerSize = MatrixType::InnerSizeAtCompileTime, OuterStrideAtCompileTime = InnerSize==Dynamic ? Dynamic : InnerSize+4 @@ -94,10 +116,18 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } // test both inner stride and outer stride + for(int k=0; k<2; ++k) { + if(k==1 && (2*m.innerSize()+1)*(m.outerSize()*2) > maxsize2) + break; + Scalar* array = (k==0 ? array1 : array2); + Map > map(array, rows, cols, Stride(2*m.innerSize()+1, 2)); map = m; VERIFY(map.outerStride() == 2*map.innerSize()+1); @@ -108,9 +138,12 @@ template void map_class_matrix(const MatrixTy VERIFY(array[map.outerStride()*i+map.innerStride()*j] == m.coeffByOuterInner(i,j)); VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j)); } + VERIFY_IS_APPROX(s1*map,s1*m); + map *= s1; + VERIFY_IS_APPROX(map,s1*m); } - internal::aligned_delete(a_array, arraysize+1); + internal::aligned_delete(a_array1, arraysize+1); } void test_mapstride() diff --git a/gtsam/3rdparty/Eigen/test/meta.cpp b/gtsam/3rdparty/Eigen/test/meta.cpp index 3302c5887..b8dea68e8 100644 --- a/gtsam/3rdparty/Eigen/test/meta.cpp +++ b/gtsam/3rdparty/Eigen/test/meta.cpp @@ -9,6 +9,12 @@ #include "main.h" +template +bool check_is_convertible(const From&, const To&) +{ + return internal::is_convertible::value; +} + void test_meta() { VERIFY((internal::conditional<(3<4),internal::true_type, internal::false_type>::type::value)); @@ -52,6 +58,24 @@ void test_meta() VERIFY(( internal::is_same::type >::value)); VERIFY(( internal::is_same::type >::value)); + VERIFY(( internal::is_convertible::value )); + VERIFY(( internal::is_convertible::value )); + VERIFY(( internal::is_convertible::value )); + VERIFY((!internal::is_convertible,double>::value )); + VERIFY(( internal::is_convertible::value )); +// VERIFY((!internal::is_convertible::value )); //does not work because the conversion is prevented by a static assertion + VERIFY((!internal::is_convertible::value )); + VERIFY((!internal::is_convertible::value )); + { + float f; + MatrixXf A, B; + VectorXf a, b; + VERIFY(( check_is_convertible(a.dot(b), f) )); + VERIFY(( check_is_convertible(a.transpose()*b, f) )); + VERIFY((!check_is_convertible(A*B, f) )); + VERIFY(( check_is_convertible(A*B, A) )); + } + VERIFY(internal::meta_sqrt<1>::ret == 1); #define VERIFY_META_SQRT(X) VERIFY(internal::meta_sqrt::ret == int(std::sqrt(double(X)))) VERIFY_META_SQRT(2); diff --git a/gtsam/3rdparty/Eigen/test/metis_support.cpp b/gtsam/3rdparty/Eigen/test/metis_support.cpp index 932b04074..d87c56a13 100644 --- a/gtsam/3rdparty/Eigen/test/metis_support.cpp +++ b/gtsam/3rdparty/Eigen/test/metis_support.cpp @@ -3,24 +3,10 @@ // // Copyright (C) 2012 Désiré Nuentsa-Wakam // -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + #include "sparse_solver.h" #include #include diff --git a/gtsam/3rdparty/Eigen/test/mixingtypes.cpp b/gtsam/3rdparty/Eigen/test/mixingtypes.cpp index 6c2f74875..ad9c2c652 100644 --- a/gtsam/3rdparty/Eigen/test/mixingtypes.cpp +++ b/gtsam/3rdparty/Eigen/test/mixingtypes.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2008-2015 Gael Guennebaud // Copyright (C) 2008 Benoit Jacob // // This Source Code Form is subject to the terms of the Mozilla @@ -15,14 +15,26 @@ #define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them #endif -// #ifndef EIGEN_DONT_VECTORIZE -// #define EIGEN_DONT_VECTORIZE // SSE intrinsics aren't designed to allow mixing types -// #endif +#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_3) + +#ifndef EIGEN_DONT_VECTORIZE +#define EIGEN_DONT_VECTORIZE +#endif + +#endif + +static bool g_called; +#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same::value); } #include "main.h" using namespace std; +#define VERIFY_MIX_SCALAR(XPR,REF) \ + g_called = false; \ + VERIFY_IS_APPROX(XPR,REF); \ + VERIFY( g_called && #XPR" not properly optimized"); + template void mixingtypes(int size = SizeAtCompileType) { typedef std::complex CF; @@ -38,8 +50,10 @@ template void mixingtypes(int size = SizeAtCompileType) Mat_f mf = Mat_f::Random(size,size); Mat_d md = mf.template cast(); + //Mat_d rd = md; Mat_cf mcf = Mat_cf::Random(size,size); Mat_cd mcd = mcf.template cast >(); + Mat_cd rcd = mcd; Vec_f vf = Vec_f::Random(size,1); Vec_d vd = vf.template cast(); Vec_cf vcf = Vec_cf::Random(size,1); @@ -49,19 +63,59 @@ template void mixingtypes(int size = SizeAtCompileType) complex scf = internal::random >(); complex scd = internal::random >(); - mf+mf; - VERIFY_RAISES_ASSERT(mf+md); - VERIFY_RAISES_ASSERT(mf+mcf); + + float epsf = std::sqrt(std::numeric_limits ::min EIGEN_EMPTY ()); + double epsd = std::sqrt(std::numeric_limits::min EIGEN_EMPTY ()); + + while(std::abs(sf )(); + while(std::abs(sd )(); + while(std::abs(scf)(); + while(std::abs(scd)(); + +// VERIFY_RAISES_ASSERT(mf+md); // does not even compile + +#ifdef EIGEN_DONT_VECTORIZE VERIFY_RAISES_ASSERT(vf=vd); VERIFY_RAISES_ASSERT(vf+=vd); - VERIFY_RAISES_ASSERT(mcd=md); - +#endif + // check scalar products - VERIFY_IS_APPROX(vcf * sf , vcf * complex(sf)); - VERIFY_IS_APPROX(sd * vcd, complex(sd) * vcd); - VERIFY_IS_APPROX(vf * scf , vf.template cast >() * scf); - VERIFY_IS_APPROX(scd * vd, scd * vd.template cast >()); + VERIFY_MIX_SCALAR(vcf * sf , vcf * complex(sf)); + VERIFY_MIX_SCALAR(sd * vcd , complex(sd) * vcd); + VERIFY_MIX_SCALAR(vf * scf , vf.template cast >() * scf); + VERIFY_MIX_SCALAR(scd * vd , scd * vd.template cast >()); + + VERIFY_MIX_SCALAR(vcf * 2 , vcf * complex(2)); + VERIFY_MIX_SCALAR(vcf * 2.1 , vcf * complex(2.1)); + VERIFY_MIX_SCALAR(2 * vcf, vcf * complex(2)); + VERIFY_MIX_SCALAR(2.1 * vcf , vcf * complex(2.1)); + + // check scalar quotients + VERIFY_MIX_SCALAR(vcf / sf , vcf / complex(sf)); + VERIFY_MIX_SCALAR(vf / scf , vf.template cast >() / scf); + VERIFY_MIX_SCALAR(vf.array() / scf, vf.template cast >().array() / scf); + VERIFY_MIX_SCALAR(scd / vd.array() , scd / vd.template cast >().array()); + + // check scalar increment + VERIFY_MIX_SCALAR(vcf.array() + sf , vcf.array() + complex(sf)); + VERIFY_MIX_SCALAR(sd + vcd.array(), complex(sd) + vcd.array()); + VERIFY_MIX_SCALAR(vf.array() + scf, vf.template cast >().array() + scf); + VERIFY_MIX_SCALAR(scd + vd.array() , scd + vd.template cast >().array()); + + // check scalar subtractions + VERIFY_MIX_SCALAR(vcf.array() - sf , vcf.array() - complex(sf)); + VERIFY_MIX_SCALAR(sd - vcd.array(), complex(sd) - vcd.array()); + VERIFY_MIX_SCALAR(vf.array() - scf, vf.template cast >().array() - scf); + VERIFY_MIX_SCALAR(scd - vd.array() , scd - vd.template cast >().array()); + + // check scalar powers + VERIFY_MIX_SCALAR( pow(vcf.array(), sf), Eigen::pow(vcf.array(), complex(sf)) ); + VERIFY_MIX_SCALAR( vcf.array().pow(sf) , Eigen::pow(vcf.array(), complex(sf)) ); + VERIFY_MIX_SCALAR( pow(sd, vcd.array()), Eigen::pow(complex(sd), vcd.array()) ); + VERIFY_MIX_SCALAR( Eigen::pow(vf.array(), scf), Eigen::pow(vf.template cast >().array(), scf) ); + VERIFY_MIX_SCALAR( vf.array().pow(scf) , Eigen::pow(vf.template cast >().array(), scf) ); + VERIFY_MIX_SCALAR( Eigen::pow(scd, vd.array()), Eigen::pow(scd, vd.template cast >().array()) ); // check dot product vf.dot(vf); @@ -75,6 +129,7 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(vcd.asDiagonal() * md, vcd.asDiagonal() * md.template cast >()); VERIFY_IS_APPROX(mcf * vf.asDiagonal(), mcf * vf.template cast >().asDiagonal()); VERIFY_IS_APPROX(md * vcd.asDiagonal(), md.template cast >() * vcd.asDiagonal()); + // vd.asDiagonal() * mf; // does not even compile // vcd.asDiagonal() * mf; // does not even compile @@ -92,7 +147,6 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(mcd.array() *= md.array(), mcd2.array() *= md.array().template cast >()); // check matrix-matrix products - VERIFY_IS_APPROX(sd*md*mcd, (sd*md).template cast().eval()*mcd); VERIFY_IS_APPROX(sd*mcd*md, sd*mcd*md.template cast()); VERIFY_IS_APPROX(scd*md*mcd, scd*md.template cast().eval()*mcd); @@ -103,6 +157,20 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(scf*mf*mcf, scf*mf.template cast()*mcf); VERIFY_IS_APPROX(scf*mcf*mf, scf*mcf*mf.template cast()); + VERIFY_IS_APPROX(sd*md.adjoint()*mcd, (sd*md).template cast().eval().adjoint()*mcd); + VERIFY_IS_APPROX(sd*mcd.adjoint()*md, sd*mcd.adjoint()*md.template cast()); + VERIFY_IS_APPROX(sd*md.adjoint()*mcd.adjoint(), (sd*md).template cast().eval().adjoint()*mcd.adjoint()); + VERIFY_IS_APPROX(sd*mcd.adjoint()*md.adjoint(), sd*mcd.adjoint()*md.template cast().adjoint()); + VERIFY_IS_APPROX(sd*md*mcd.adjoint(), (sd*md).template cast().eval()*mcd.adjoint()); + VERIFY_IS_APPROX(sd*mcd*md.adjoint(), sd*mcd*md.template cast().adjoint()); + + VERIFY_IS_APPROX(sf*mf.adjoint()*mcf, (sf*mf).template cast().eval().adjoint()*mcf); + VERIFY_IS_APPROX(sf*mcf.adjoint()*mf, sf*mcf.adjoint()*mf.template cast()); + VERIFY_IS_APPROX(sf*mf.adjoint()*mcf.adjoint(), (sf*mf).template cast().eval().adjoint()*mcf.adjoint()); + VERIFY_IS_APPROX(sf*mcf.adjoint()*mf.adjoint(), sf*mcf.adjoint()*mf.template cast().adjoint()); + VERIFY_IS_APPROX(sf*mf*mcf.adjoint(), (sf*mf).template cast().eval()*mcf.adjoint()); + VERIFY_IS_APPROX(sf*mcf*mf.adjoint(), sf*mcf*mf.template cast().adjoint()); + VERIFY_IS_APPROX(sf*mf*vcf, (sf*mf).template cast().eval()*vcf); VERIFY_IS_APPROX(scf*mf*vcf,(scf*mf.template cast()).eval()*vcf); VERIFY_IS_APPROX(sf*mcf*vf, sf*mcf*vf.template cast()); @@ -122,11 +190,111 @@ template void mixingtypes(int size = SizeAtCompileType) VERIFY_IS_APPROX(scd*vcd.adjoint()*md, scd*vcd.adjoint()*md.template cast().eval()); VERIFY_IS_APPROX(sd*vd.adjoint()*mcd, sd*vd.adjoint().template cast().eval()*mcd); VERIFY_IS_APPROX(scd*vd.adjoint()*mcd, scd*vd.adjoint().template cast().eval()*mcd); + + VERIFY_IS_APPROX( sd*vcd.adjoint()*md.template triangularView(), sd*vcd.adjoint()*md.template cast().eval().template triangularView()); + VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template triangularView(), scd*vcd.adjoint()*md.template cast().eval().template triangularView()); + VERIFY_IS_APPROX( sd*vcd.adjoint()*md.transpose().template triangularView(), sd*vcd.adjoint()*md.transpose().template cast().eval().template triangularView()); + VERIFY_IS_APPROX(scd*vcd.adjoint()*md.transpose().template triangularView(), scd*vcd.adjoint()*md.transpose().template cast().eval().template triangularView()); + VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.template triangularView(), sd*vd.adjoint().template cast().eval()*mcd.template triangularView()); + VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template triangularView(), scd*vd.adjoint().template cast().eval()*mcd.template triangularView()); + VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.transpose().template triangularView(), sd*vd.adjoint().template cast().eval()*mcd.transpose().template triangularView()); + VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.transpose().template triangularView(), scd*vd.adjoint().template cast().eval()*mcd.transpose().template triangularView()); + + // Not supported yet: trmm +// VERIFY_IS_APPROX(sd*mcd*md.template triangularView(), sd*mcd*md.template cast().eval().template triangularView()); +// VERIFY_IS_APPROX(scd*mcd*md.template triangularView(), scd*mcd*md.template cast().eval().template triangularView()); +// VERIFY_IS_APPROX(sd*md*mcd.template triangularView(), sd*md.template cast().eval()*mcd.template triangularView()); +// VERIFY_IS_APPROX(scd*md*mcd.template triangularView(), scd*md.template cast().eval()*mcd.template triangularView()); + + // Not supported yet: symv +// VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView(), sd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView(), scd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView(), sd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); +// VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView(), scd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); + + // Not supported yet: symm +// VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView(), sd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView(), scd*vcd.adjoint()*md.template cast().eval().template selfadjointView()); +// VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView(), sd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); +// VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView(), scd*vd.adjoint().template cast().eval()*mcd.template selfadjointView()); + + rcd.setZero(); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = sd * mcd * md), + Mat_cd((sd * mcd * md.template cast().eval()).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = sd * md * mcd), + Mat_cd((sd * md.template cast().eval() * mcd).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = scd * mcd * md), + Mat_cd((scd * mcd * md.template cast().eval()).template triangularView())); + VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView() = scd * md * mcd), + Mat_cd((scd * md.template cast().eval() * mcd).template triangularView())); + + + VERIFY_IS_APPROX( md.array() * mcd.array(), md.template cast().eval().array() * mcd.array() ); + VERIFY_IS_APPROX( mcd.array() * md.array(), mcd.array() * md.template cast().eval().array() ); + + VERIFY_IS_APPROX( md.array() + mcd.array(), md.template cast().eval().array() + mcd.array() ); + VERIFY_IS_APPROX( mcd.array() + md.array(), mcd.array() + md.template cast().eval().array() ); + + VERIFY_IS_APPROX( md.array() - mcd.array(), md.template cast().eval().array() - mcd.array() ); + VERIFY_IS_APPROX( mcd.array() - md.array(), mcd.array() - md.template cast().eval().array() ); + + if(mcd.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( md.array() / mcd.array(), md.template cast().eval().array() / mcd.array() ); + } + if(md.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( mcd.array() / md.array(), mcd.array() / md.template cast().eval().array() ); + } + + if(md.array().abs().minCoeff()>epsd || mcd.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( md.array().pow(mcd.array()), md.template cast().eval().array().pow(mcd.array()) ); + VERIFY_IS_APPROX( mcd.array().pow(md.array()), mcd.array().pow(md.template cast().eval().array()) ); + + VERIFY_IS_APPROX( pow(md.array(),mcd.array()), md.template cast().eval().array().pow(mcd.array()) ); + VERIFY_IS_APPROX( pow(mcd.array(),md.array()), mcd.array().pow(md.template cast().eval().array()) ); + } + + rcd = mcd; + VERIFY_IS_APPROX( rcd = md, md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd += md, mcd + md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd -= md, mcd - md.template cast().eval() ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.array() *= md.array(), mcd.array() * md.template cast().eval().array() ); + rcd = mcd; + if(md.array().abs().minCoeff()>epsd) + { + VERIFY_IS_APPROX( rcd.array() /= md.array(), mcd.array() / md.template cast().eval().array() ); + } + + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += md + mcd*md, mcd + (md.template cast().eval()) + mcd*(md.template cast().eval())); + + VERIFY_IS_APPROX( rcd.noalias() = md*md, ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += md*md, mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() -= md*md, mcd - ((md*md).eval().template cast()) ); + + VERIFY_IS_APPROX( rcd.noalias() = mcd + md*md, mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() += mcd + md*md, mcd + mcd + ((md*md).eval().template cast()) ); + rcd = mcd; + VERIFY_IS_APPROX( rcd.noalias() -= mcd + md*md, - ((md*md).eval().template cast()) ); } void test_mixingtypes() { - CALL_SUBTEST_1(mixingtypes<3>()); - CALL_SUBTEST_2(mixingtypes<4>()); - CALL_SUBTEST_3(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1(mixingtypes<3>()); + CALL_SUBTEST_2(mixingtypes<4>()); + CALL_SUBTEST_3(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + + CALL_SUBTEST_4(mixingtypes<3>()); + CALL_SUBTEST_5(mixingtypes<4>()); + CALL_SUBTEST_6(mixingtypes(internal::random(1,EIGEN_TEST_MAX_SIZE))); + } } diff --git a/gtsam/3rdparty/Eigen/test/mpl2only.cpp b/gtsam/3rdparty/Eigen/test/mpl2only.cpp new file mode 100644 index 000000000..7d04d6bba --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/mpl2only.cpp @@ -0,0 +1,22 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#define EIGEN_MPL2_ONLY +#include +#include +#include +#include +#include +#include +#include + +int main() +{ + return 0; +} diff --git a/gtsam/3rdparty/Eigen/test/nesting_ops.cpp b/gtsam/3rdparty/Eigen/test/nesting_ops.cpp index 1e8523283..a419b0e44 100644 --- a/gtsam/3rdparty/Eigen/test/nesting_ops.cpp +++ b/gtsam/3rdparty/Eigen/test/nesting_ops.cpp @@ -2,16 +2,37 @@ // for linear algebra. // // Copyright (C) 2010 Hauke Heibel +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING + #include "main.h" -template void run_nesting_ops(const MatrixType& _m) +template +void use_n_times(const XprType &xpr) { - typename MatrixType::Nested m(_m); + typename internal::nested_eval::type mat(xpr); + typename XprType::PlainObject res(mat.rows(), mat.cols()); + nb_temporaries--; // remove res + res.setZero(); + for(int i=0; i +bool verify_eval_type(const XprType &, const ReferenceType&) +{ + typedef typename internal::nested_eval::type EvalType; + return internal::is_same::type, typename internal::remove_all::type>::value; +} + +template void run_nesting_ops_1(const MatrixType& _m) +{ + typename internal::nested_eval::type m(_m); // Make really sure that we are in debug mode! VERIFY_RAISES_ASSERT(eigen_assert(false)); @@ -24,10 +45,63 @@ template void run_nesting_ops(const MatrixType& _m) VERIFY_IS_APPROX( (m.transpose() * m).array().abs().sum(), (m.transpose() * m).array().abs().sum() ); } +template void run_nesting_ops_2(const MatrixType& _m) +{ + typedef typename MatrixType::Scalar Scalar; + Index rows = _m.rows(); + Index cols = _m.cols(); + MatrixType m1 = MatrixType::Random(rows,cols); + Matrix m2; + + if((MatrixType::SizeAtCompileTime==Dynamic)) + { + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1 + m1*m1), 1 ); + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1 + m1*m1), 1 ); + + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.template triangularView().solve(m1.col(0))), 1 ); + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.template triangularView().solve(m1.col(0))), 1 ); + + VERIFY_EVALUATION_COUNT( use_n_times<1>(Scalar(2)*m1.template triangularView().solve(m1.col(0))), 2 ); // FIXME could be one by applying the scaling in-place on the solve result + VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.col(0)+m1.template triangularView().solve(m1.col(0))), 2 ); // FIXME could be one by adding m1.col() inplace + VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.col(0)+m1.template triangularView().solve(m1.col(0))), 2 ); + } + + { + VERIFY( verify_eval_type<10>(m1, m1) ); + if(!NumTraits::IsComplex) + { + VERIFY( verify_eval_type<3>(2*m1, 2*m1) ); + VERIFY( verify_eval_type<4>(2*m1, m1) ); + } + else + { + VERIFY( verify_eval_type<2>(2*m1, 2*m1) ); + VERIFY( verify_eval_type<3>(2*m1, m1) ); + } + VERIFY( verify_eval_type<2>(m1+m1, m1+m1) ); + VERIFY( verify_eval_type<3>(m1+m1, m1) ); + VERIFY( verify_eval_type<1>(m1*m1.transpose(), m2) ); + VERIFY( verify_eval_type<1>(m1*(m1+m1).transpose(), m2) ); + VERIFY( verify_eval_type<2>(m1*m1.transpose(), m2) ); + VERIFY( verify_eval_type<1>(m1+m1*m1, m1) ); + + VERIFY( verify_eval_type<1>(m1.template triangularView().solve(m1), m1) ); + VERIFY( verify_eval_type<1>(m1+m1.template triangularView().solve(m1), m1) ); + } +} + + void test_nesting_ops() { - CALL_SUBTEST_1(run_nesting_ops(MatrixXf::Random(25,25))); - CALL_SUBTEST_2(run_nesting_ops(MatrixXd::Random(25,25))); - CALL_SUBTEST_3(run_nesting_ops(Matrix4f::Random())); - CALL_SUBTEST_4(run_nesting_ops(Matrix4d::Random())); + CALL_SUBTEST_1(run_nesting_ops_1(MatrixXf::Random(25,25))); + CALL_SUBTEST_2(run_nesting_ops_1(MatrixXcd::Random(25,25))); + CALL_SUBTEST_3(run_nesting_ops_1(Matrix4f::Random())); + CALL_SUBTEST_4(run_nesting_ops_1(Matrix2d::Random())); + + Index s = internal::random(1,EIGEN_TEST_MAX_SIZE); + CALL_SUBTEST_1( run_nesting_ops_2(MatrixXf(s,s)) ); + CALL_SUBTEST_2( run_nesting_ops_2(MatrixXcd(s,s)) ); + CALL_SUBTEST_3( run_nesting_ops_2(Matrix4f()) ); + CALL_SUBTEST_4( run_nesting_ops_2(Matrix2d()) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/nomalloc.cpp b/gtsam/3rdparty/Eigen/test/nomalloc.cpp index 8e0402358..50756c2fb 100644 --- a/gtsam/3rdparty/Eigen/test/nomalloc.cpp +++ b/gtsam/3rdparty/Eigen/test/nomalloc.cpp @@ -8,20 +8,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -// this hack is needed to make this file compiles with -pedantic (gcc) -#ifdef __GNUC__ -#define throw(X) -#endif - -#ifdef __INTEL_COMPILER - // disable "warning #76: argument to macro is empty" produced by the above hack - #pragma warning disable 76 -#endif - // discard stack allocation as that too bypasses malloc #define EIGEN_STACK_ALLOCATION_LIMIT 0 -// any heap allocation will raise an assert -#define EIGEN_NO_MALLOC +// heap allocation will raise an assert if enabled at runtime +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include @@ -88,14 +78,15 @@ template void nomalloc(const MatrixType& m) VERIFY_IS_APPROX(m2,m2); m2.template selfadjointView().rankUpdate(m1.col(0),-1); - m2.template selfadjointView().rankUpdate(m1.row(0),-1); + m2.template selfadjointView().rankUpdate(m1.row(0),-1); + m2.template selfadjointView().rankUpdate(m1.col(0), m1.col(0)); // rank-2 // The following fancy matrix-matrix products are not safe yet regarding static allocation -// m1 += m1.template triangularView() * m2.col(; -// m1.template selfadjointView().rankUpdate(m2); -// m1 += m1.template triangularView() * m2; -// m1 += m1.template selfadjointView() * m2; -// VERIFY_IS_APPROX(m1,m1); + m2.template selfadjointView().rankUpdate(m1); + m2 += m2.template triangularView() * m1; + m2.template triangularView() = m2 * m2; + m1 += m1.template selfadjointView() * m2; + VERIFY_IS_APPROX(m2,m2); } template @@ -171,7 +162,7 @@ void test_zerosized() { Eigen::VectorXd v; // explicit zero-sized: Eigen::ArrayXXd A0(0,0); - Eigen::ArrayXd v0(std::ptrdiff_t(0)); // FIXME ArrayXd(0) is ambiguous + Eigen::ArrayXd v0(0); // assigning empty objects to each other: A=A0; @@ -183,9 +174,11 @@ template void test_reference(const MatrixType& m) { enum { Flag = MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor}; enum { TransposeFlag = !MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor}; typename MatrixType::Index rows = m.rows(), cols=m.cols(); + typedef Eigen::Matrix MatrixX; + typedef Eigen::Matrix MatrixXT; // Dynamic reference: - typedef Eigen::Ref > Ref; - typedef Eigen::Ref > RefT; + typedef Eigen::Ref Ref; + typedef Eigen::Ref RefT; Ref r1(m); Ref r2(m.block(rows/3, cols/4, rows/2, cols/2)); @@ -195,10 +188,30 @@ template void test_reference(const MatrixType& m) { VERIFY_RAISES_ASSERT(RefT r5(m)); VERIFY_RAISES_ASSERT(Ref r6(m.transpose())); VERIFY_RAISES_ASSERT(Ref r7(Scalar(2) * m)); + + // Copy constructors shall also never malloc + Ref r8 = r1; + RefT r9 = r3; + + // Initializing from a compatible Ref shall also never malloc + Eigen::Ref > r10=r8, r11=m; + + // Initializing from an incompatible Ref will malloc: + typedef Eigen::Ref RefAligned; + VERIFY_RAISES_ASSERT(RefAligned r12=r10); + VERIFY_RAISES_ASSERT(Ref r13=r10); // r10 has more dynamic strides + } void test_nomalloc() { + // create some dynamic objects + Eigen::MatrixXd M1 = MatrixXd::Random(3,3); + Ref R1 = 2.0*M1; // Ref requires temporary + + // from here on prohibit malloc: + Eigen::internal::set_is_malloc_allowed(false); + // check that our operator new is indeed called: VERIFY_RAISES_ASSERT(MatrixXd dummy(MatrixXd::Random(3,3))); CALL_SUBTEST_1(nomalloc(Matrix()) ); @@ -207,6 +220,10 @@ void test_nomalloc() // Check decomposition modules with dynamic matrices that have a known compile-time max size (ctms) CALL_SUBTEST_4(ctms_decompositions()); + CALL_SUBTEST_5(test_zerosized()); + CALL_SUBTEST_6(test_reference(Matrix())); + CALL_SUBTEST_7(test_reference(R1)); + CALL_SUBTEST_8(Ref R2 = M1.topRows<2>(); test_reference(R2)); } diff --git a/gtsam/3rdparty/Eigen/test/nullary.cpp b/gtsam/3rdparty/Eigen/test/nullary.cpp index fbc721a1a..acd55506e 100644 --- a/gtsam/3rdparty/Eigen/test/nullary.cpp +++ b/gtsam/3rdparty/Eigen/test/nullary.cpp @@ -2,6 +2,7 @@ // for linear algebra. // // Copyright (C) 2010-2011 Jitse Niesen +// Copyright (C) 2016 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -12,7 +13,6 @@ template bool equalsIdentity(const MatrixType& A) { - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; Scalar zero = static_cast(0); @@ -30,13 +30,41 @@ bool equalsIdentity(const MatrixType& A) bool diagOK = (A.diagonal().array() == 1).all(); return offDiagOK && diagOK; + +} + +template +void check_extremity_accuracy(const VectorType &v, const typename VectorType::Scalar &low, const typename VectorType::Scalar &high) +{ + typedef typename VectorType::Scalar Scalar; + typedef typename VectorType::RealScalar RealScalar; + + RealScalar prec = internal::is_same::value ? NumTraits::dummy_precision()*10 : NumTraits::dummy_precision()/10; + Index size = v.size(); + + if(size<20) + return; + + for (int i=0; isize-6) + { + Scalar ref = (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1); + if(std::abs(ref)>1) + { + if(!internal::isApprox(v(i), ref, prec)) + std::cout << v(i) << " != " << ref << " ; relative error: " << std::abs((v(i)-ref)/ref) << " ; required precision: " << prec << " ; range: " << low << "," << high << " ; i: " << i << "\n"; + VERIFY(internal::isApprox(v(i), (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1), prec)); + } + } + } } template void testVectorType(const VectorType& base) { - typedef typename internal::traits::Index Index; - typedef typename internal::traits::Scalar Scalar; + typedef typename VectorType::Scalar Scalar; + typedef typename VectorType::RealScalar RealScalar; const Index size = base.size(); @@ -44,36 +72,61 @@ void testVectorType(const VectorType& base) Scalar low = (size == 1 ? high : internal::random(-500,500)); if (low>high) std::swap(low,high); + // check low==high + if(internal::random(0.f,1.f)<0.05f) + low = high; + // check abs(low) >> abs(high) + else if(size>2 && std::numeric_limits::max_exponent10>0 && internal::random(0.f,1.f)<0.1f) + low = -internal::random(1,2) * RealScalar(std::pow(RealScalar(10),std::numeric_limits::max_exponent10/2)); + const Scalar step = ((size == 1) ? 1 : (high-low)/(size-1)); // check whether the result yields what we expect it to do VectorType m(base); m.setLinSpaced(size,low,high); - VectorType n(size); - for (int i=0; i::IsInteger) + { + VectorType n(size); + for (int i=0; i::IsInteger) || ((high-low)>=size && (Index(high-low)%(size-1))==0) || (Index(high-low+1)::IsInteger) || (high-low>=size)) + for (int i=0; i::epsilon() ); + // random access version + m = VectorType::LinSpaced(size,low,high); + VERIFY_IS_APPROX(m,n); + VERIFY( internal::isApprox(m(m.size()-1),high) ); + VERIFY( size==1 || internal::isApprox(m(0),low) ); + VERIFY_IS_EQUAL(m(m.size()-1) , high); + if(!NumTraits::IsInteger) + CALL_SUBTEST( check_extremity_accuracy(m, low, high) ); + } - // These guys sometimes fail! This is not good. Any ideas how to fix them!? - //VERIFY( m(m.size()-1) == high ); - //VERIFY( m(0) == low ); + VERIFY( m(m.size()-1) <= high ); + VERIFY( (m.array() <= high).all() ); + VERIFY( (m.array() >= low).all() ); - // sequential access version - m = VectorType::LinSpaced(Sequential,size,low,high); - VERIFY_IS_APPROX(m,n); - // These guys sometimes fail! This is not good. Any ideas how to fix them!? - //VERIFY( m(m.size()-1) == high ); - //VERIFY( m(0) == low ); + VERIFY( m(m.size()-1) >= low ); + if(size>=1) + { + VERIFY( internal::isApprox(m(0),low) ); + VERIFY_IS_EQUAL(m(0) , low); + } // check whether everything works with row and col major vectors Matrix row_vector(size); @@ -95,23 +148,77 @@ void testVectorType(const VectorType& base) VERIFY_IS_APPROX( ScalarMatrix::LinSpaced(1,low,high), ScalarMatrix::Constant(high) ); // regression test for bug 526 (linear vectorized transversal) - if (size > 1) { + if (size > 1 && (!NumTraits::IsInteger)) { m.tail(size-1).setLinSpaced(low, high); VERIFY_IS_APPROX(m(size-1), high); } + + // regression test for bug 1383 (LinSpaced with empty size/range) + { + Index n0 = VectorType::SizeAtCompileTime==Dynamic ? 0 : VectorType::SizeAtCompileTime; + low = internal::random(); + m = VectorType::LinSpaced(n0,low,low-1); + VERIFY(m.size()==n0); + + if(VectorType::SizeAtCompileTime==Dynamic) + { + VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,0,Scalar(n0-1)).sum(),Scalar(0)); + VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,low,low-1).sum(),Scalar(0)); + } + + m.setLinSpaced(n0,0,Scalar(n0-1)); + VERIFY(m.size()==n0); + m.setLinSpaced(n0,low,low-1); + VERIFY(m.size()==n0); + + // empty range only: + VERIFY_IS_APPROX(VectorType::LinSpaced(size,low,low),VectorType::Constant(size,low)); + m.setLinSpaced(size,low,low); + VERIFY_IS_APPROX(m,VectorType::Constant(size,low)); + + if(NumTraits::IsInteger) + { + VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,Scalar(low+size-1)), VectorType::LinSpaced(size,Scalar(low+size-1),low).reverse() ); + + if(VectorType::SizeAtCompileTime==Dynamic) + { + // Check negative multiplicator path: + for(Index k=1; k<5; ++k) + VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,Scalar(low+(size-1)*k)), VectorType::LinSpaced(size,Scalar(low+(size-1)*k),low).reverse() ); + // Check negative divisor path: + for(Index k=1; k<5; ++k) + VERIFY_IS_APPROX( VectorType::LinSpaced(size*k,low,Scalar(low+size-1)), VectorType::LinSpaced(size*k,Scalar(low+size-1),low).reverse() ); + } + } + } } template void testMatrixType(const MatrixType& m) { - typedef typename MatrixType::Index Index; + using std::abs; const Index rows = m.rows(); const Index cols = m.cols(); + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + Scalar s1; + do { + s1 = internal::random(); + } while(abs(s1)::IsInteger)); MatrixType A; A.setIdentity(rows, cols); VERIFY(equalsIdentity(A)); VERIFY(equalsIdentity(MatrixType::Identity(rows, cols))); + + + A = MatrixType::Constant(rows,cols,s1); + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1)(i,j), s1 ); + VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1).coeff(i,j), s1 ); + VERIFY_IS_APPROX( A(i,j), s1 ); } void test_nullary() @@ -120,12 +227,78 @@ void test_nullary() CALL_SUBTEST_2( testMatrixType(MatrixXcf(internal::random(1,300),internal::random(1,300))) ); CALL_SUBTEST_3( testMatrixType(MatrixXf(internal::random(1,300),internal::random(1,300))) ); - for(int i = 0; i < g_repeat; i++) { - CALL_SUBTEST_4( testVectorType(VectorXd(internal::random(1,300))) ); + for(int i = 0; i < g_repeat*10; i++) { + CALL_SUBTEST_4( testVectorType(VectorXd(internal::random(1,30000))) ); CALL_SUBTEST_5( testVectorType(Vector4d()) ); // regression test for bug 232 CALL_SUBTEST_6( testVectorType(Vector3d()) ); - CALL_SUBTEST_7( testVectorType(VectorXf(internal::random(1,300))) ); + CALL_SUBTEST_7( testVectorType(VectorXf(internal::random(1,30000))) ); CALL_SUBTEST_8( testVectorType(Vector3f()) ); + CALL_SUBTEST_8( testVectorType(Vector4f()) ); + CALL_SUBTEST_8( testVectorType(Matrix()) ); CALL_SUBTEST_8( testVectorType(Matrix()) ); + + CALL_SUBTEST_9( testVectorType(VectorXi(internal::random(1,10))) ); + CALL_SUBTEST_9( testVectorType(VectorXi(internal::random(9,300))) ); + CALL_SUBTEST_9( testVectorType(Matrix()) ); } + +#ifdef EIGEN_TEST_PART_6 + // Assignment of a RowVectorXd to a MatrixXd (regression test for bug #79). + VERIFY( (MatrixXd(RowVectorXd::LinSpaced(3, 0, 1)) - RowVector3d(0, 0.5, 1)).norm() < std::numeric_limits::epsilon() ); +#endif + +#ifdef EIGEN_TEST_PART_9 + // Check possible overflow issue + { + int n = 60000; + ArrayXi a1(n), a2(n); + a1.setLinSpaced(n, 0, n-1); + for(int i=0; i >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( internal::has_binary_operator >::value )); + VERIFY(( !internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + // Regression unit test for a weird MSVC bug. + // Search "nullary_wrapper_workaround_msvc" in CoreEvaluators.h for the details. + // See also traits::match. + { + MatrixXf A = MatrixXf::Random(3,3); + Ref R = 2.0*A; + VERIFY_IS_APPROX(R, A+A); + + Ref R1 = MatrixXf::Random(3,3)+A; + + VectorXi V = VectorXi::Random(3); + Ref R2 = VectorXi::LinSpaced(3,1,3)+V; + VERIFY_IS_APPROX(R2, V+Vector3i(1,2,3)); + + VERIFY(( internal::has_nullary_operator >::value )); + VERIFY(( !internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + + VERIFY(( !internal::has_nullary_operator >::value )); + VERIFY(( internal::has_unary_operator >::value )); + VERIFY(( !internal::has_binary_operator >::value )); + VERIFY(( internal::functor_has_linear_access >::ret )); + } +#endif } diff --git a/gtsam/3rdparty/Eigen/test/numext.cpp b/gtsam/3rdparty/Eigen/test/numext.cpp new file mode 100644 index 000000000..3de33e2f9 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/numext.cpp @@ -0,0 +1,53 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2017 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +template +void check_abs() { + typedef typename NumTraits::Real Real; + + if(NumTraits::IsSigned) + VERIFY_IS_EQUAL(numext::abs(-T(1)), T(1)); + VERIFY_IS_EQUAL(numext::abs(T(0)), T(0)); + VERIFY_IS_EQUAL(numext::abs(T(1)), T(1)); + + for(int k=0; k(); + if(!internal::is_same::value) + x = x/Real(2); + if(NumTraits::IsSigned) + { + VERIFY_IS_EQUAL(numext::abs(x), numext::abs(-x)); + VERIFY( numext::abs(-x) >= Real(0)); + } + VERIFY( numext::abs(x) >= Real(0)); + VERIFY_IS_APPROX( numext::abs2(x), numext::abs2(numext::abs(x)) ); + } +} + +void test_numext() { + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + CALL_SUBTEST( check_abs() ); + + CALL_SUBTEST( check_abs >() ); + CALL_SUBTEST( check_abs >() ); +} diff --git a/gtsam/3rdparty/Eigen/test/packetmath.cpp b/gtsam/3rdparty/Eigen/test/packetmath.cpp index bac7b02d1..7821a1738 100644 --- a/gtsam/3rdparty/Eigen/test/packetmath.cpp +++ b/gtsam/3rdparty/Eigen/test/packetmath.cpp @@ -9,16 +9,28 @@ // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. #include "main.h" +#include "unsupported/Eigen/SpecialFunctions" +#if defined __GNUC__ && __GNUC__>=6 + #pragma GCC diagnostic ignored "-Wignored-attributes" +#endif // using namespace Eigen; +#ifdef EIGEN_VECTORIZE_SSE +const bool g_vectorize_sse = true; +#else +const bool g_vectorize_sse = false; +#endif + namespace Eigen { namespace internal { template T negate(const T& x) { return -x; } } } -template bool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits::Real& refvalue) +// NOTE: we disbale inlining for this function to workaround a GCC issue when using -O3 and the i387 FPU. +template EIGEN_DONT_INLINE +bool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits::Real& refvalue) { return internal::isMuchSmallerThan(a-b, refvalue); } @@ -29,7 +41,7 @@ template bool areApproxAbs(const Scalar* a, const Scalar* b, in { if (!isApproxAbs(a[i],b[i],refvalue)) { - std::cout << "[" << Map >(a,size) << "]" << " != " << Map >(b,size) << "\n"; + std::cout << "ref: [" << Map >(a,size) << "]" << " != vec: [" << Map >(b,size) << "]\n"; return false; } } @@ -42,21 +54,13 @@ template bool areApprox(const Scalar* a, const Scalar* b, int s { if (a[i]!=b[i] && !internal::isApprox(a[i],b[i])) { - std::cout << "[" << Map >(a,size) << "]" << " != " << Map >(b,size) << "\n"; + std::cout << "ref: [" << Map >(a,size) << "]" << " != vec: [" << Map >(b,size) << "]\n"; return false; } } return true; } - -#define CHECK_CWISE2(REFOP, POP) { \ - for (int i=0; i(data1), internal::pload(data1+PacketSize))); \ - VERIFY(areApprox(ref, data2, PacketSize) && #POP); \ -} - #define CHECK_CWISE1(REFOP, POP) { \ for (int i=0; i VERIFY(areApprox(ref, data2, PacketSize) && #POP); \ } +#define CHECK_CWISE2_IF(COND, REFOP, POP) if(COND) { \ + packet_helper h; \ + for (int i=0; i template void packetmath() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; typedef typename NumTraits::Real RealScalar; - const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Packet packets[PacketSize*2]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; + const int max_size = PacketSize > 4 ? PacketSize : 4; + const int size = PacketSize*max_size; + EIGEN_ALIGN_MAX Scalar data1[size]; + EIGEN_ALIGN_MAX Scalar data2[size]; + EIGEN_ALIGN_MAX Packet packets[PacketSize*2]; + EIGEN_ALIGN_MAX Scalar ref[size]; RealScalar refvalue = 0; for (int i=0; i void packetmath() else if (offset==1) internal::palign<1>(packets[0], packets[1]); else if (offset==2) internal::palign<2>(packets[0], packets[1]); else if (offset==3) internal::palign<3>(packets[0], packets[1]); + else if (offset==4) internal::palign<4>(packets[0], packets[1]); + else if (offset==5) internal::palign<5>(packets[0], packets[1]); + else if (offset==6) internal::palign<6>(packets[0], packets[1]); + else if (offset==7) internal::palign<7>(packets[0], packets[1]); + else if (offset==8) internal::palign<8>(packets[0], packets[1]); + else if (offset==9) internal::palign<9>(packets[0], packets[1]); + else if (offset==10) internal::palign<10>(packets[0], packets[1]); + else if (offset==11) internal::palign<11>(packets[0], packets[1]); + else if (offset==12) internal::palign<12>(packets[0], packets[1]); + else if (offset==13) internal::palign<13>(packets[0], packets[1]); + else if (offset==14) internal::palign<14>(packets[0], packets[1]); + else if (offset==15) internal::palign<15>(packets[0], packets[1]); internal::pstore(data2, packets[0]); for (int i=0; i void packetmath() VERIFY(areApprox(ref, data2, PacketSize) && "internal::palign"); } - CHECK_CWISE2(REF_ADD, internal::padd); - CHECK_CWISE2(REF_SUB, internal::psub); - CHECK_CWISE2(REF_MUL, internal::pmul); - #ifndef EIGEN_VECTORIZE_ALTIVEC - if (!internal::is_same::value) - CHECK_CWISE2(REF_DIV, internal::pdiv); - #endif + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasAdd); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasSub); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMul); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasNegate); + VERIFY((internal::is_same::value) || (!PacketTraits::Vectorizable) || PacketTraits::HasDiv); + + CHECK_CWISE2_IF(PacketTraits::HasAdd, REF_ADD, internal::padd); + CHECK_CWISE2_IF(PacketTraits::HasSub, REF_SUB, internal::psub); + CHECK_CWISE2_IF(PacketTraits::HasMul, REF_MUL, internal::pmul); + CHECK_CWISE2_IF(PacketTraits::HasDiv, REF_DIV, internal::pdiv); + CHECK_CWISE1(internal::negate, internal::pnegate); CHECK_CWISE1(numext::conj, internal::pconj); @@ -165,9 +195,31 @@ template void packetmath() internal::pstore(data2, internal::pset1(data1[offset])); VERIFY(areApprox(ref, data2, PacketSize) && "internal::pset1"); } - + + { + for (int i=0; i(data1, A0, A1, A2, A3); + internal::pstore(data2+0*PacketSize, A0); + internal::pstore(data2+1*PacketSize, A1); + internal::pstore(data2+2*PacketSize, A2); + internal::pstore(data2+3*PacketSize, A3); + VERIFY(areApprox(ref, data2, 4*PacketSize) && "internal::pbroadcast4"); + } + + { + for (int i=0; i(data1, A0, A1); + internal::pstore(data2+0*PacketSize, A0); + internal::pstore(data2+1*PacketSize, A1); + VERIFY(areApprox(ref, data2, 2*PacketSize) && "internal::pbroadcast2"); + } + VERIFY(internal::isApprox(data1[0], internal::pfirst(internal::pload(data1))) && "internal::pfirst"); - + if(PacketSize>1) { for(int offset=0;offset<4;++offset) @@ -179,11 +231,31 @@ template void packetmath() } } + if(PacketSize>2) + { + for(int offset=0;offset<4;++offset) + { + for(int i=0;i(data1+offset)); + VERIFY(areApprox(ref, data2, PacketSize) && "ploadquad"); + } + } + ref[0] = 0; for (int i=0; i(data1)), refvalue) && "internal::predux"); + { + for (int i=0; i<4; ++i) + ref[i] = 0; + for (int i=0; i(data1))); + VERIFY(areApprox(ref, data2, PacketSize>4?PacketSize/2:PacketSize) && "internal::predux_downto4"); + } + ref[0] = 1; for (int i=0; i void packetmath() ref[i] = data1[PacketSize-i-1]; internal::pstore(data2, internal::preverse(internal::pload(data1))); VERIFY(areApprox(ref, data2, PacketSize) && "internal::preverse"); + + internal::PacketBlock kernel; + for (int i=0; i(data1+i*PacketSize); + } + ptranspose(kernel); + for (int i=0; i(data1); + Packet elsePacket = internal::pload(data2); + EIGEN_ALIGN_MAX internal::Selector selector; + for (int i = 0; i < PacketSize; ++i) { + selector.select[i] = i; + } + + Packet blend = internal::pblend(selector, thenPacket, elsePacket); + EIGEN_ALIGN_MAX Scalar result[size]; + internal::pstore(result, blend); + for (int i = 0; i < PacketSize; ++i) { + VERIFY(isApproxAbs(result[i], (selector.select[i] ? data1[i] : data2[i]), refvalue)); + } + } + + if (PacketTraits::HasBlend || g_vectorize_sse) { + // pinsertfirst + for (int i=0; i(); + ref[0] = s; + internal::pstore(data2, internal::pinsertfirst(internal::pload(data1),s)); + VERIFY(areApprox(ref, data2, PacketSize) && "internal::pinsertfirst"); + } + + if (PacketTraits::HasBlend || g_vectorize_sse) { + // pinsertlast + for (int i=0; i(); + ref[PacketSize-1] = s; + internal::pstore(data2, internal::pinsertlast(internal::pload(data1),s)); + VERIFY(areApprox(ref, data2, PacketSize) && "internal::pinsertlast"); + } } template void packetmath_real() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; + EIGEN_ALIGN_MAX Scalar data1[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketTraits::size*4]; for (int i=0; i(-1,1) * std::pow(Scalar(10), internal::random(-3,3)); data2[i] = internal::random(-1,1) * std::pow(Scalar(10), internal::random(-3,3)); } - CHECK_CWISE1_IF(internal::packet_traits::HasSin, std::sin, internal::psin); - CHECK_CWISE1_IF(internal::packet_traits::HasCos, std::cos, internal::pcos); - CHECK_CWISE1_IF(internal::packet_traits::HasTan, std::tan, internal::ptan); - + CHECK_CWISE1_IF(PacketTraits::HasSin, std::sin, internal::psin); + CHECK_CWISE1_IF(PacketTraits::HasCos, std::cos, internal::pcos); + CHECK_CWISE1_IF(PacketTraits::HasTan, std::tan, internal::ptan); + + CHECK_CWISE1_IF(PacketTraits::HasRound, numext::round, internal::pround); + CHECK_CWISE1_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil); + CHECK_CWISE1_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor); + for (int i=0; i(-1,1); data2[i] = internal::random(-1,1); } - CHECK_CWISE1_IF(internal::packet_traits::HasASin, std::asin, internal::pasin); - CHECK_CWISE1_IF(internal::packet_traits::HasACos, std::acos, internal::pacos); + CHECK_CWISE1_IF(PacketTraits::HasASin, std::asin, internal::pasin); + CHECK_CWISE1_IF(PacketTraits::HasACos, std::acos, internal::pacos); for (int i=0; i(-87,88); data2[i] = internal::random(-87,88); } - CHECK_CWISE1_IF(internal::packet_traits::HasExp, std::exp, internal::pexp); + CHECK_CWISE1_IF(PacketTraits::HasExp, std::exp, internal::pexp); + for (int i=0; i(-1,1) * std::pow(Scalar(10), internal::random(-6,6)); + data2[i] = internal::random(-1,1) * std::pow(Scalar(10), internal::random(-6,6)); + } + CHECK_CWISE1_IF(PacketTraits::HasTanh, std::tanh, internal::ptanh); + if(PacketTraits::HasExp && PacketTraits::size>=2) { data1[0] = std::numeric_limits::quiet_NaN(); - packet_helper::HasExp,Packet> h; - h.store(data2, internal::pexp(h.load(data1))); - VERIFY(isNaN(data2[0])); + data1[1] = std::numeric_limits::epsilon(); + packet_helper h; + h.store(data2, internal::pexp(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::exp(std::numeric_limits::epsilon()), data2[1]); + + data1[0] = -std::numeric_limits::epsilon(); + data1[1] = 0; + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp(-std::numeric_limits::epsilon()), data2[0]); + VERIFY_IS_EQUAL(std::exp(Scalar(0)), data2[1]); + + data1[0] = (std::numeric_limits::min)(); + data1[1] = -(std::numeric_limits::min)(); + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp((std::numeric_limits::min)()), data2[0]); + VERIFY_IS_EQUAL(std::exp(-(std::numeric_limits::min)()), data2[1]); + + data1[0] = std::numeric_limits::denorm_min(); + data1[1] = -std::numeric_limits::denorm_min(); + h.store(data2, internal::pexp(h.load(data1))); + VERIFY_IS_EQUAL(std::exp(std::numeric_limits::denorm_min()), data2[0]); + VERIFY_IS_EQUAL(std::exp(-std::numeric_limits::denorm_min()), data2[1]); } + if (PacketTraits::HasTanh) { + // NOTE this test migh fail with GCC prior to 6.3, see MathFunctionsImpl.h for details. + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasTanh,Packet> h; + h.store(data2, internal::ptanh(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + +#if EIGEN_HAS_C99_MATH + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasLGamma,Packet> h; + h.store(data2, internal::plgamma(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasErf,Packet> h; + h.store(data2, internal::perf(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } + { + data1[0] = std::numeric_limits::quiet_NaN(); + packet_helper::HasErfc,Packet> h; + h.store(data2, internal::perfc(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); + } +#endif // EIGEN_HAS_C99_MATH + for (int i=0; i(0,1) * std::pow(Scalar(10), internal::random(-6,6)); data2[i] = internal::random(0,1) * std::pow(Scalar(10), internal::random(-6,6)); } - if(internal::random(0,1)<0.1) + + if(internal::random(0,1)<0.1f) data1[internal::random(0, PacketSize)] = 0; - CHECK_CWISE1_IF(internal::packet_traits::HasSqrt, std::sqrt, internal::psqrt); - CHECK_CWISE1_IF(internal::packet_traits::HasLog, std::log, internal::plog); + CHECK_CWISE1_IF(PacketTraits::HasSqrt, std::sqrt, internal::psqrt); + CHECK_CWISE1_IF(PacketTraits::HasLog, std::log, internal::plog); +#if EIGEN_HAS_C99_MATH && (__cplusplus > 199711L) + CHECK_CWISE1_IF(PacketTraits::HasLog1p, std::log1p, internal::plog1p); + CHECK_CWISE1_IF(internal::packet_traits::HasLGamma, std::lgamma, internal::plgamma); + CHECK_CWISE1_IF(internal::packet_traits::HasErf, std::erf, internal::perf); + CHECK_CWISE1_IF(internal::packet_traits::HasErfc, std::erfc, internal::perfc); +#endif + + if(PacketTraits::HasLog && PacketTraits::size>=2) { data1[0] = std::numeric_limits::quiet_NaN(); - packet_helper::HasLog,Packet> h; + data1[1] = std::numeric_limits::epsilon(); + packet_helper h; h.store(data2, internal::plog(h.load(data1))); - VERIFY(isNaN(data2[0])); - data1[0] = -1.0f; + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::log(std::numeric_limits::epsilon()), data2[1]); + + data1[0] = -std::numeric_limits::epsilon(); + data1[1] = 0; h.store(data2, internal::plog(h.load(data1))); - VERIFY(isNaN(data2[0])); -#if !EIGEN_FAST_MATH + VERIFY((numext::isnan)(data2[0])); + VERIFY_IS_EQUAL(std::log(Scalar(0)), data2[1]); + + data1[0] = (std::numeric_limits::min)(); + data1[1] = -(std::numeric_limits::min)(); + h.store(data2, internal::plog(h.load(data1))); + VERIFY_IS_EQUAL(std::log((std::numeric_limits::min)()), data2[0]); + VERIFY((numext::isnan)(data2[1])); + + data1[0] = std::numeric_limits::denorm_min(); + data1[1] = -std::numeric_limits::denorm_min(); + h.store(data2, internal::plog(h.load(data1))); + // VERIFY_IS_EQUAL(std::log(std::numeric_limits::denorm_min()), data2[0]); + VERIFY((numext::isnan)(data2[1])); + + data1[0] = Scalar(-1.0f); + h.store(data2, internal::plog(h.load(data1))); + VERIFY((numext::isnan)(data2[0])); h.store(data2, internal::psqrt(h.load(data1))); - VERIFY(isNaN(data2[0])); - VERIFY(isNaN(data2[1])); -#endif + VERIFY((numext::isnan)(data2[0])); + VERIFY((numext::isnan)(data2[1])); } } template void packetmath_notcomplex() { using std::abs; - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; - EIGEN_ALIGN16 Scalar data1[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar data2[internal::packet_traits::size*4]; - EIGEN_ALIGN16 Scalar ref[internal::packet_traits::size*4]; - - Array::Map(data1, internal::packet_traits::size*4).setRandom(); + EIGEN_ALIGN_MAX Scalar data1[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketTraits::size*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketTraits::size*4]; + + Array::Map(data1, PacketTraits::size*4).setRandom(); ref[0] = data1[0]; for (int i=0; i(data1))) && "internal::predux_min"); - CHECK_CWISE2((std::min), internal::pmin); - CHECK_CWISE2((std::max), internal::pmax); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMin); + VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMax); + + CHECK_CWISE2_IF(PacketTraits::HasMin, (std::min), internal::pmin); + CHECK_CWISE2_IF(PacketTraits::HasMax, (std::max), internal::pmax); CHECK_CWISE1(abs, internal::pabs); ref[0] = data1[0]; for (int i=0; i(data1))) && "internal::predux_max"); - + for (int i=0; i(data1[0])); VERIFY(areApprox(ref, data2, PacketSize) && "internal::plset"); } template void test_conj_helper(Scalar* data1, Scalar* data2, Scalar* ref, Scalar* pval) { - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; - + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; + internal::conj_if cj0; internal::conj_if cj1; internal::conj_helper cj; internal::conj_helper pcj; - + for(int i=0;i void test_conj_helper(Scalar } internal::pstore(pval,pcj.pmul(internal::pload(data1),internal::pload(data2))); VERIFY(areApprox(ref, pval, PacketSize) && "conj_helper pmul"); - + for(int i=0;i(data1),internal::pload(data2),internal::pload(pval))); VERIFY(areApprox(ref, pval, PacketSize) && "conj_helper pmadd"); } template void packetmath_complex() { - typedef typename internal::packet_traits::type Packet; - const int PacketSize = internal::packet_traits::size; + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + const int PacketSize = PacketTraits::size; const int size = PacketSize*4; - EIGEN_ALIGN16 Scalar data1[PacketSize*4]; - EIGEN_ALIGN16 Scalar data2[PacketSize*4]; - EIGEN_ALIGN16 Scalar ref[PacketSize*4]; - EIGEN_ALIGN16 Scalar pval[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar data1[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar data2[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar ref[PacketSize*4]; + EIGEN_ALIGN_MAX Scalar pval[PacketSize*4]; for (int i=0; i() * Scalar(1e2); data2[i] = internal::random() * Scalar(1e2); } - + test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); test_conj_helper (data1,data2,ref,pval); - + { for(int i=0;i(data1))); VERIFY(areApprox(ref, pval, PacketSize) && "pcplxflip"); } - - +} + +template void packetmath_scatter_gather() +{ + typedef internal::packet_traits PacketTraits; + typedef typename PacketTraits::type Packet; + typedef typename NumTraits::Real RealScalar; + const int PacketSize = PacketTraits::size; + EIGEN_ALIGN_MAX Scalar data1[PacketSize]; + RealScalar refvalue = 0; + for (int i=0; i()/RealScalar(PacketSize); + } + + int stride = internal::random(1,20); + + EIGEN_ALIGN_MAX Scalar buffer[PacketSize*20]; + memset(buffer, 0, 20*PacketSize*sizeof(Scalar)); + Packet packet = internal::pload(data1); + internal::pscatter(buffer, packet, stride); + + for (int i = 0; i < PacketSize*20; ++i) { + if ((i%stride) == 0 && i()/RealScalar(PacketSize); + } + packet = internal::pgather(buffer, 7); + internal::pstore(data1, packet); + for (int i = 0; i < PacketSize; ++i) { + VERIFY(isApproxAbs(data1[i], buffer[i*7], refvalue) && "pgather"); + } } void test_packetmath() @@ -370,17 +619,23 @@ void test_packetmath() CALL_SUBTEST_1( packetmath() ); CALL_SUBTEST_2( packetmath() ); CALL_SUBTEST_3( packetmath() ); - CALL_SUBTEST_1( packetmath >() ); - CALL_SUBTEST_2( packetmath >() ); + CALL_SUBTEST_4( packetmath >() ); + CALL_SUBTEST_5( packetmath >() ); CALL_SUBTEST_1( packetmath_notcomplex() ); CALL_SUBTEST_2( packetmath_notcomplex() ); CALL_SUBTEST_3( packetmath_notcomplex() ); - + CALL_SUBTEST_1( packetmath_real() ); CALL_SUBTEST_2( packetmath_real() ); - CALL_SUBTEST_1( packetmath_complex >() ); - CALL_SUBTEST_2( packetmath_complex >() ); + CALL_SUBTEST_4( packetmath_complex >() ); + CALL_SUBTEST_5( packetmath_complex >() ); + + CALL_SUBTEST_1( packetmath_scatter_gather() ); + CALL_SUBTEST_2( packetmath_scatter_gather() ); + CALL_SUBTEST_3( packetmath_scatter_gather() ); + CALL_SUBTEST_4( packetmath_scatter_gather >() ); + CALL_SUBTEST_5( packetmath_scatter_gather >() ); } } diff --git a/gtsam/3rdparty/Eigen/test/pastix_support.cpp b/gtsam/3rdparty/Eigen/test/pastix_support.cpp index 14da0944b..b62f85739 100644 --- a/gtsam/3rdparty/Eigen/test/pastix_support.cpp +++ b/gtsam/3rdparty/Eigen/test/pastix_support.cpp @@ -7,6 +7,8 @@ // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include #include @@ -25,6 +27,14 @@ template void test_pastix_T() check_sparse_spd_solving(pastix_llt_upper); check_sparse_spd_solving(pastix_ldlt_upper); check_sparse_square_solving(pastix_lu); + + // Some compilation check: + pastix_llt_lower.iparm(); + pastix_llt_lower.dparm(); + pastix_ldlt_lower.iparm(); + pastix_ldlt_lower.dparm(); + pastix_lu.iparm(); + pastix_lu.dparm(); } // There is no support for selfadjoint matrices with PaStiX. diff --git a/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp b/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp index 7b0dbc763..db1266579 100644 --- a/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp +++ b/gtsam/3rdparty/Eigen/test/permutationmatrices.cpp @@ -7,6 +7,8 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING + #include "main.h" using namespace std; @@ -33,7 +35,9 @@ template void permutationmatrices(const MatrixType& m) RightPermutationVectorType rv; randomPermutationVector(rv, cols); RightPermutationType rp(rv); - MatrixType m_permuted = lp * m_original * rp; + MatrixType m_permuted = MatrixType::Random(rows,cols); + + VERIFY_EVALUATION_COUNT(m_permuted = lp * m_original * rp, 1); // 1 temp for sub expression "lp * m_original" for (int i=0; i void permutationmatrices(const MatrixType& m) Matrix rm(rp); VERIFY_IS_APPROX(m_permuted, lm*m_original*rm); - + + m_permuted = m_original; + VERIFY_EVALUATION_COUNT(m_permuted = lp * m_permuted * rp, 1); + VERIFY_IS_APPROX(m_permuted, lm*m_original*rm); + VERIFY_IS_APPROX(lp.inverse()*m_permuted*rp.inverse(), m_original); VERIFY_IS_APPROX(lv.asPermutation().inverse()*m_permuted*rv.asPermutation().inverse(), m_original); VERIFY_IS_APPROX(MapLeftPerm(lv.data(),lv.size()).inverse()*m_permuted*MapRightPerm(rv.data(),rv.size()).inverse(), m_original); @@ -63,22 +71,22 @@ template void permutationmatrices(const MatrixType& m) LeftPermutationType identityp; identityp.setIdentity(rows); VERIFY_IS_APPROX(m_original, identityp*m_original); - + // check inplace permutations m_permuted = m_original; - m_permuted = lp.inverse() * m_permuted; + VERIFY_EVALUATION_COUNT(m_permuted.noalias()= lp.inverse() * m_permuted, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, lp.inverse()*m_original); - + m_permuted = m_original; - m_permuted = m_permuted * rp.inverse(); + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp.inverse(), 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, m_original*rp.inverse()); - + m_permuted = m_original; - m_permuted = lp * m_permuted; + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = lp * m_permuted, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, lp*m_original); - + m_permuted = m_original; - m_permuted = m_permuted * rp; + VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp, 1); // 1 temp to allocate the mask VERIFY_IS_APPROX(m_permuted, m_original*rp); if(rows>1 && cols>1) @@ -99,7 +107,38 @@ template void permutationmatrices(const MatrixType& m) rm = rp; rm.col(i).swap(rm.col(j)); VERIFY_IS_APPROX(rm, rp2.toDenseMatrix().template cast()); - } + } + + { + // simple compilation check + Matrix A = rp; + Matrix B = rp.transpose(); + VERIFY_IS_APPROX(A, B.transpose()); + } +} + +template +void bug890() +{ + typedef Matrix MatrixType; + typedef Matrix VectorType; + typedef Stride S; + typedef Map MapType; + typedef PermutationMatrix Perm; + + VectorType v1(2), v2(2), op(4), rhs(2); + v1 << 666,667; + op << 1,0,0,1; + rhs << 42,42; + + Perm P(2); + P.indices() << 1, 0; + + MapType(v1.data(),2,1,S(1,1)) = P * MapType(rhs.data(),2,1,S(1,1)); + VERIFY_IS_APPROX(v1, (P * rhs).eval()); + + MapType(v1.data(),2,1,S(1,1)) = P.inverse() * MapType(rhs.data(),2,1,S(1,1)); + VERIFY_IS_APPROX(v1, (P.inverse() * rhs).eval()); } void test_permutationmatrices() @@ -113,4 +152,5 @@ void test_permutationmatrices() CALL_SUBTEST_6( permutationmatrices(Matrix(20, 30)) ); CALL_SUBTEST_7( permutationmatrices(MatrixXcf(15, 10)) ); } + CALL_SUBTEST_5( bug890() ); } diff --git a/gtsam/3rdparty/Eigen/test/product.h b/gtsam/3rdparty/Eigen/test/product.h index 397af24ae..3b6511270 100644 --- a/gtsam/3rdparty/Eigen/test/product.h +++ b/gtsam/3rdparty/Eigen/test/product.h @@ -22,7 +22,6 @@ template void product(const MatrixType& m) /* this test covers the following files: Identity.h Product.h */ - typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef Matrix RowVectorType; typedef Matrix ColVectorType; @@ -112,6 +111,23 @@ template void product(const MatrixType& m) vcres.noalias() -= m1.transpose() * v1; VERIFY_IS_APPROX(vcres, vc2 - m1.transpose() * v1); + // test d ?= a+b*c rules + res.noalias() = square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); + res.noalias() += square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, 2*(square + m1 * m2.transpose())); + res.noalias() -= square + m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square + m1 * m2.transpose()); + + // test d ?= a-b*c rules + res.noalias() = square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square - m1 * m2.transpose()); + res.noalias() += square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, 2*(square - m1 * m2.transpose())); + res.noalias() -= square - m1 * m2.transpose(); + VERIFY_IS_APPROX(res, square - m1 * m2.transpose()); + + tm1 = m1; VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1); VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1); @@ -152,19 +168,44 @@ template void product(const MatrixType& m) VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2, (ref2.row(0) = m1.row(0) * square2)); } + // vector.block() (see bug 1283) + { + RowVectorType w1(rows); + VERIFY_IS_APPROX(square * v1.block(0,0,rows,1), square * v1); + VERIFY_IS_APPROX(w1.noalias() = square * v1.block(0,0,rows,1), square * v1); + VERIFY_IS_APPROX(w1.block(0,0,rows,1).noalias() = square * v1.block(0,0,rows,1), square * v1); + + Matrix w2(cols); + VERIFY_IS_APPROX(vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + + vc2 = square2.block(0,0,1,cols).transpose(); + VERIFY_IS_APPROX(square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2); + + vc2 = square2.block(0,0,cols,1); + VERIFY_IS_APPROX(square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2); + } + // inner product { Scalar x = square2.row(c) * square2.col(c2); VERIFY_IS_APPROX(x, square2.row(c).transpose().cwiseProduct(square2.col(c2)).sum()); } - + // outer product - VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose()); - VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols)); - VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols)); + { + VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose()); + VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols)); + VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols)); + } // Aliasing { @@ -186,4 +227,5 @@ template void product(const MatrixType& m) VERIFY_IS_APPROX(square * (s1*(square*square)), s1 * square * square * square); VERIFY_IS_APPROX(square * (square*square).conjugate(), square * square.conjugate() * square.conjugate()); } + } diff --git a/gtsam/3rdparty/Eigen/test/product_extra.cpp b/gtsam/3rdparty/Eigen/test/product_extra.cpp index ea2486937..e2b855bff 100644 --- a/gtsam/3rdparty/Eigen/test/product_extra.cpp +++ b/gtsam/3rdparty/Eigen/test/product_extra.cpp @@ -98,6 +98,16 @@ template void product_extra(const MatrixType& m) // regression test MatrixType tmp = m1 * m1.adjoint() * s1; VERIFY_IS_APPROX(tmp, m1 * m1.adjoint() * s1); + + // regression test for bug 1343, assignment to arrays + Array a1 = m1 * vc2; + VERIFY_IS_APPROX(a1.matrix(),m1*vc2); + Array a2 = s1 * (m1 * vc2); + VERIFY_IS_APPROX(a2.matrix(),s1*m1*vc2); + Array a3 = v1 * m1; + VERIFY_IS_APPROX(a3.matrix(),v1*m1); + Array a4 = m1 * m2.adjoint(); + VERIFY_IS_APPROX(a4.matrix(),m1*m2.adjoint()); } // Regression test for bug reported at http://forum.kde.org/viewtopic.php?f=74&t=96947 @@ -116,8 +126,8 @@ void zero_sized_objects(const MatrixType& m) typedef typename MatrixType::Scalar Scalar; const int PacketSize = internal::packet_traits::size; const int PacketSize1 = PacketSize>1 ? PacketSize-1 : 1; - DenseIndex rows = m.rows(); - DenseIndex cols = m.cols(); + Index rows = m.rows(); + Index cols = m.cols(); { MatrixType res, a(rows,0), b(0,cols); @@ -169,6 +179,7 @@ void zero_sized_objects(const MatrixType& m) } } +template void bug_127() { // Bug 127 @@ -193,6 +204,16 @@ void bug_127() a*b; } +template void bug_817() +{ + ArrayXXf B = ArrayXXf::Random(10,10), C; + VectorXf x = VectorXf::Random(10); + C = (x.transpose()*B.matrix()); + B = (x.transpose()*B.matrix()); + VERIFY_IS_APPROX(B,C); +} + +template void unaligned_objects() { // Regression test for the bug reported here: @@ -222,6 +243,116 @@ void unaligned_objects() } } +template +EIGEN_DONT_INLINE +Index test_compute_block_size(Index m, Index n, Index k) +{ + Index mc(m), nc(n), kc(k); + internal::computeProductBlockingSizes(kc, mc, nc); + return kc+mc+nc; +} + +template +Index compute_block_size() +{ + Index ret = 0; + ret += test_compute_block_size(0,1,1); + ret += test_compute_block_size(1,0,1); + ret += test_compute_block_size(1,1,0); + ret += test_compute_block_size(0,0,1); + ret += test_compute_block_size(0,1,0); + ret += test_compute_block_size(1,0,0); + ret += test_compute_block_size(0,0,0); + return ret; +} + +template +void aliasing_with_resize() +{ + Index m = internal::random(10,50); + Index n = internal::random(10,50); + MatrixXd A, B, C(m,n), D(m,m); + VectorXd a, b, c(n); + C.setRandom(); + D.setRandom(); + c.setRandom(); + double s = internal::random(1,10); + + A = C; + B = A * A.transpose(); + A = A * A.transpose(); + VERIFY_IS_APPROX(A,B); + + A = C; + B = (A * A.transpose())/s; + A = (A * A.transpose())/s; + VERIFY_IS_APPROX(A,B); + + A = C; + B = (A * A.transpose()) + D; + A = (A * A.transpose()) + D; + VERIFY_IS_APPROX(A,B); + + A = C; + B = D + (A * A.transpose()); + A = D + (A * A.transpose()); + VERIFY_IS_APPROX(A,B); + + A = C; + B = s * (A * A.transpose()); + A = s * (A * A.transpose()); + VERIFY_IS_APPROX(A,B); + + A = C; + a = c; + b = (A * a)/s; + a = (A * a)/s; + VERIFY_IS_APPROX(a,b); +} + +template +void bug_1308() +{ + int n = 10; + MatrixXd r(n,n); + VectorXd v = VectorXd::Random(n); + r = v * RowVectorXd::Ones(n); + VERIFY_IS_APPROX(r, v.rowwise().replicate(n)); + r = VectorXd::Ones(n) * v.transpose(); + VERIFY_IS_APPROX(r, v.rowwise().replicate(n).transpose()); + + Matrix4d ones44 = Matrix4d::Ones(); + Matrix4d m44 = Matrix4d::Ones() * Matrix4d::Ones(); + VERIFY_IS_APPROX(m44,Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + + typedef Matrix RMatrix4d; + RMatrix4d r44 = Matrix4d::Ones() * Matrix4d::Ones(); + VERIFY_IS_APPROX(r44,Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44*RMatrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*RMatrix4d::Ones(), Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44, Matrix4d::Constant(4)); + VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4)); + +// RowVector4d r4; + m44.setOnes(); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += m44.row(0).transpose() * RowVector4d::Ones(), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += m44.col(0) * RowVector4d::Ones(), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.row(0), ones44); + r44.setZero(); + VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.col(0).transpose(), ones44); +} + void test_product_extra() { for(int i = 0; i < g_repeat; i++) { @@ -232,6 +363,13 @@ void test_product_extra() CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random(1,EIGEN_TEST_MAX_SIZE/2), internal::random(1,EIGEN_TEST_MAX_SIZE/2))) ); CALL_SUBTEST_1( zero_sized_objects(MatrixXf(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } - CALL_SUBTEST_5( bug_127() ); - CALL_SUBTEST_6( unaligned_objects() ); + CALL_SUBTEST_5( bug_127<0>() ); + CALL_SUBTEST_5( bug_817<0>() ); + CALL_SUBTEST_5( bug_1308<0>() ); + CALL_SUBTEST_6( unaligned_objects<0>() ); + CALL_SUBTEST_7( compute_block_size() ); + CALL_SUBTEST_7( compute_block_size() ); + CALL_SUBTEST_7( compute_block_size >() ); + CALL_SUBTEST_8( aliasing_with_resize() ); + } diff --git a/gtsam/3rdparty/Eigen/test/product_large.cpp b/gtsam/3rdparty/Eigen/test/product_large.cpp index 6bb4d1ad1..845cd40ca 100644 --- a/gtsam/3rdparty/Eigen/test/product_large.cpp +++ b/gtsam/3rdparty/Eigen/test/product_large.cpp @@ -21,12 +21,12 @@ void test_aliasing() VectorType y(rows); y.setZero(); MatrixType A(rows,cols); A.setRandom(); // CwiseBinaryOp - VERIFY_IS_APPROX(x = y + A*x, A*z); + VERIFY_IS_APPROX(x = y + A*x, A*z); // OK because "y + A*x" is marked as "assume-aliasing" x = z; // CwiseUnaryOp - VERIFY_IS_APPROX(x = T(1.)*(A*x), A*z); + VERIFY_IS_APPROX(x = T(1.)*(A*x), A*z); // OK because 1*(A*x) is replaced by (1*A*x) which is a Product<> expression x = z; - VERIFY_IS_APPROX(x = y+(-(A*x)), -A*z); + // VERIFY_IS_APPROX(x = y-A*x, -A*z); // Not OK in 3.3 because x is resized before A*x gets evaluated x = z; } @@ -62,15 +62,16 @@ void test_product_large() // check the functions to setup blocking sizes compile and do not segfault // FIXME check they do what they are supposed to do !! std::ptrdiff_t l1 = internal::random(10000,20000); - std::ptrdiff_t l2 = internal::random(1000000,2000000); - setCpuCacheSizes(l1,l2); + std::ptrdiff_t l2 = internal::random(100000,200000); + std::ptrdiff_t l3 = internal::random(1000000,2000000); + setCpuCacheSizes(l1,l2,l3); VERIFY(l1==l1CacheSize()); VERIFY(l2==l2CacheSize()); std::ptrdiff_t k1 = internal::random(10,100)*16; std::ptrdiff_t m1 = internal::random(10,100)*16; std::ptrdiff_t n1 = internal::random(10,100)*16; // only makes sure it compiles fine - internal::computeProductBlockingSizes(k1,m1,n1); + internal::computeProductBlockingSizes(k1,m1,n1,1); } { @@ -83,5 +84,24 @@ void test_product_large() MatrixXf r2 = mat1.row(2)*mat2; VERIFY_IS_APPROX(r2, (mat1.row(2)*mat2).eval()); } + + { + Eigen::MatrixXd A(10,10), B, C; + A.setRandom(); + C = A; + for(int k=0; k<79; ++k) + C = C * A; + B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))) + * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))); + VERIFY_IS_APPROX(B,C); + } +#endif + + // Regression test for bug 714: +#if defined EIGEN_HAS_OPENMP + omp_set_dynamic(1); + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_6( product(Matrix(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + } #endif } diff --git a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp index aeba009f4..d3e24b012 100644 --- a/gtsam/3rdparty/Eigen/test/product_mmtr.cpp +++ b/gtsam/3rdparty/Eigen/test/product_mmtr.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2010 Gael Guennebaud +// Copyright (C) 2010-2017 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -10,11 +10,19 @@ #include "main.h" #define CHECK_MMTR(DEST, TRI, OP) { \ + ref3 = DEST; \ ref2 = ref1 = DEST; \ DEST.template triangularView() OP; \ ref1 OP; \ - ref2.template triangularView() = ref1; \ + ref2.template triangularView() \ + = ref1.template triangularView(); \ VERIFY_IS_APPROX(DEST,ref2); \ + \ + DEST = ref3; \ + ref3 = ref2; \ + ref3.diagonal() = DEST.diagonal(); \ + DEST.template triangularView() OP; \ + VERIFY_IS_APPROX(DEST,ref3); \ } template void mmtr(int size) @@ -26,12 +34,14 @@ template void mmtr(int size) MatrixColMaj matc = MatrixColMaj::Zero(size, size); MatrixRowMaj matr = MatrixRowMaj::Zero(size, size); - MatrixColMaj ref1(size, size), ref2(size, size); + MatrixColMaj ref1(size, size), ref2(size, size), ref3(size,size); MatrixColMaj soc(size,othersize); soc.setRandom(); MatrixColMaj osc(othersize,size); osc.setRandom(); MatrixRowMaj sor(size,othersize); sor.setRandom(); MatrixRowMaj osr(othersize,size); osr.setRandom(); + MatrixColMaj sqc(size,size); sqc.setRandom(); + MatrixRowMaj sqr(size,size); sqr.setRandom(); Scalar s = internal::random(); @@ -49,6 +59,29 @@ template void mmtr(int size) CHECK_MMTR(matc, Upper, -= s*(osc.transpose()*osc.conjugate())); CHECK_MMTR(matr, Lower, -= s*soc*soc.adjoint()); CHECK_MMTR(matr, Upper, -= soc*(s*soc.adjoint())); + + CHECK_MMTR(matc, Lower, -= s*sqr*sqc.template triangularView()); + CHECK_MMTR(matc, Upper, = s*sqc*sqr.template triangularView()); + CHECK_MMTR(matc, Lower, += s*sqr*sqc.template triangularView()); + CHECK_MMTR(matc, Upper, = s*sqc*sqc.template triangularView()); + + CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView()*sqc); + CHECK_MMTR(matc, Upper, -= (s*sqc).template triangularView()*sqc); + CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView()*sqc); + CHECK_MMTR(matc, Upper, += (s*sqc).template triangularView()*sqc); + + // check aliasing + ref2 = ref1 = matc; + ref1 = sqc.adjoint() * matc * sqc; + ref2.template triangularView() = ref1.template triangularView(); + matc.template triangularView() = sqc.adjoint() * matc * sqc; + VERIFY_IS_APPROX(matc, ref2); + + ref2 = ref1 = matc; + ref1 = sqc * matc * sqc.adjoint(); + ref2.template triangularView() = ref1.template triangularView(); + matc.template triangularView() = sqc * matc * sqc.adjoint(); + VERIFY_IS_APPROX(matc, ref2); } void test_product_mmtr() diff --git a/gtsam/3rdparty/Eigen/test/product_notemporary.cpp b/gtsam/3rdparty/Eigen/test/product_notemporary.cpp index 5599d268d..30592b79e 100644 --- a/gtsam/3rdparty/Eigen/test/product_notemporary.cpp +++ b/gtsam/3rdparty/Eigen/test/product_notemporary.cpp @@ -7,25 +7,10 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -static int nb_temporaries; - -inline void on_temporary_creation(int size) { - // here's a great place to set a breakpoint when debugging failures in this test! - if(size!=0) nb_temporaries++; -} - - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } - template void product_notemporary(const MatrixType& m) { /* This test checks the number of temporaries created @@ -62,14 +47,19 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( m3.noalias() = m1 * m2.adjoint(), 0); VERIFY_EVALUATION_COUNT( m3 = s1 * (m1 * m2.transpose()), 1); - VERIFY_EVALUATION_COUNT( m3 = m3 + s1 * (m1 * m2.transpose()), 1); +// VERIFY_EVALUATION_COUNT( m3 = m3 + s1 * (m1 * m2.transpose()), 1); VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * (m1 * m2.transpose()), 0); VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()), 1); + VERIFY_EVALUATION_COUNT( m3 = m3 - (m1 * m2.adjoint()), 1); + VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()).transpose(), 1); - VERIFY_EVALUATION_COUNT( m3.noalias() = m3 + m1 * m2.transpose(), 1); // 0 in 3.3 - VERIFY_EVALUATION_COUNT( m3.noalias() += m3 + m1 * m2.transpose(), 1); // 0 in 3.3 - VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 + m1 * m2.transpose(), 1); // 0 in 3.3 + VERIFY_EVALUATION_COUNT( m3.noalias() = m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() += m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 + m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() = m3 - m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() += m3 - m1 * m2.transpose(), 0); + VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 - m1 * m2.transpose(), 0); VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * m2.adjoint(), 0); VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * (m1*s3+m2*s2).adjoint(), 1); @@ -86,7 +76,7 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).template triangularView() * m2, 0); VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView() * (m2+m2), 1); VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView() * m2.adjoint(), 0); - + VERIFY_EVALUATION_COUNT( m3.template triangularView() = (m1 * m2.adjoint()), 0); VERIFY_EVALUATION_COUNT( m3.template triangularView() -= (m1 * m2.adjoint()), 0); @@ -123,8 +113,7 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) / (m3.transpose() * m3).diagonal().array().abs().sum(), 0 ); // Zero temporaries for ... CoeffBasedProductMode - // - does not work with GCC because of the <..>, we'ld need variadic macros ... - //VERIFY_EVALUATION_COUNT( m3.col(0).head<5>() * m3.col(0).transpose() + m3.col(0).head<5>() * m3.col(0).transpose(), 0 ); + VERIFY_EVALUATION_COUNT( m3.col(0).template head<5>() * m3.col(0).transpose() + m3.col(0).template head<5>() * m3.col(0).transpose(), 0 ); // Check matrix * vectors VERIFY_EVALUATION_COUNT( cvres.noalias() = m1 * cv1, 0 ); @@ -132,6 +121,26 @@ template void product_notemporary(const MatrixType& m) VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.col(0), 0 ); VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * rv1.adjoint(), 0 ); VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.row(0).transpose(), 0 ); + + VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * cv1, 0 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * cv1, 0 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * (m1*cv1), 1 ); + VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * (m1*cv1), 1 ); + + // Check outer products + m3 = cv1 * rv1; + VERIFY_EVALUATION_COUNT( m3.noalias() = cv1 * rv1, 0 ); + VERIFY_EVALUATION_COUNT( m3.noalias() = (cv1+cv1) * (rv1+rv1), 1 ); + VERIFY_EVALUATION_COUNT( m3.noalias() = (m1*cv1) * (rv1), 1 ); + VERIFY_EVALUATION_COUNT( m3.noalias() += (m1*cv1) * (rv1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1) * (rv1 * m1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() -= (cv1) * (rv1 * m1), 1 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() = (m1*cv1) * (rv1 * m1), 2 ); + VERIFY_EVALUATION_COUNT( rm3.noalias() += (m1*cv1) * (rv1 * m1), 2 ); + + // Check nested products + VERIFY_EVALUATION_COUNT( cvres.noalias() = m1.adjoint() * m1 * cv1, 1 ); + VERIFY_EVALUATION_COUNT( rvres.noalias() = rv1 * (m1 * m2.adjoint()), 1 ); } void test_product_notemporary() @@ -140,11 +149,12 @@ void test_product_notemporary() for(int i = 0; i < g_repeat; i++) { s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( product_notemporary(MatrixXf(s, s)) ); - s = internal::random(16,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( product_notemporary(MatrixXd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( product_notemporary(MatrixXcf(s,s)) ); - s = internal::random(16,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_notemporary(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } } diff --git a/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp index 374e2393b..3d768aa7e 100644 --- a/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/product_selfadjoint.cpp @@ -67,14 +67,21 @@ void test_product_selfadjoint() CALL_SUBTEST_1( product_selfadjoint(Matrix()) ); CALL_SUBTEST_2( product_selfadjoint(Matrix()) ); CALL_SUBTEST_3( product_selfadjoint(Matrix3d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( product_selfadjoint(MatrixXcf(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( product_selfadjoint(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( product_selfadjoint(MatrixXd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_7( product_selfadjoint(Matrix(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } - TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/product_small.cpp b/gtsam/3rdparty/Eigen/test/product_small.cpp index 8b132abb6..fdfdd9f6c 100644 --- a/gtsam/3rdparty/Eigen/test/product_small.cpp +++ b/gtsam/3rdparty/Eigen/test/product_small.cpp @@ -9,8 +9,10 @@ #define EIGEN_NO_STATIC_ASSERT #include "product.h" +#include // regression test for bug 447 +template void product1x1() { Matrix matAstatic; @@ -28,16 +30,237 @@ void product1x1() matAdynamic.cwiseProduct(matBdynamic.transpose()).sum() ); } +template +const TC& ref_prod(TC &C, const TA &A, const TB &B) +{ + for(Index i=0;i +typename internal::enable_if::type +test_lazy_single(int rows, int cols, int depth) +{ + Matrix A(rows,depth); A.setRandom(); + Matrix B(depth,cols); B.setRandom(); + Matrix C(rows,cols); C.setRandom(); + Matrix D(C); + VERIFY_IS_APPROX(C+=A.lazyProduct(B), ref_prod(D,A,B)); +} + +template +typename internal::enable_if< ( (Rows ==1&&Depth!=1&&OA==ColMajor) + || (Depth==1&&Rows !=1&&OA==RowMajor) + || (Cols ==1&&Depth!=1&&OB==RowMajor) + || (Depth==1&&Cols !=1&&OB==ColMajor) + || (Rows ==1&&Cols !=1&&OC==ColMajor) + || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type +test_lazy_single(int, int, int) +{ +} + +template +void test_lazy_all_layout(int rows=Rows, int cols=Cols, int depth=Depth) +{ + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); + CALL_SUBTEST(( test_lazy_single(rows,cols,depth) )); +} + +template +void test_lazy_l1() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + + // Inner + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(1,1,depth) )); + + // Outer + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(4,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(7,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,cols) )); +} + +template +void test_lazy_l2() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + + // mat-vec + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(4,1,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,1,depth) )); + + // vec-mat + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(1,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(1,4,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(1,cols,depth) )); +} + +template +void test_lazy_l3() +{ + int rows = internal::random(1,12); + int cols = internal::random(1,12); + int depth = internal::random(1,12); + // mat-mat + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(rows) )); + CALL_SUBTEST(( test_lazy_all_layout(4,3,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(rows,6,depth) )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout() )); + CALL_SUBTEST(( test_lazy_all_layout(8,cols) )); + CALL_SUBTEST(( test_lazy_all_layout(3,4,depth) )); + CALL_SUBTEST(( test_lazy_all_layout(4,cols,depth) )); +} + +template +void test_linear_but_not_vectorizable() +{ + // Check tricky cases for which the result of the product is a vector and thus must exhibit the LinearBit flag, + // but is not vectorizable along the linear dimension. + Index n = N==Dynamic ? internal::random(1,32) : N; + Index m = M==Dynamic ? internal::random(1,32) : M; + Index k = K==Dynamic ? internal::random(1,32) : K; + + { + Matrix A; A.setRandom(n,m+1); + Matrix B; B.setRandom(m*2,k); + Matrix C; + Matrix R; + + C.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows()+B.template bottomRows()); + R.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows()+B.template bottomRows()).eval(); + VERIFY_IS_APPROX(C,R); + } + + { + Matrix A; A.setRandom(m+1,n); + Matrix B; B.setRandom(k,m*2); + Matrix C; + Matrix R; + + C.noalias() = (B.template leftCols()+B.template rightCols()) * A.template topLeftCorner(); + R.noalias() = (B.template leftCols()+B.template rightCols()).eval() * A.template topLeftCorner(); + VERIFY_IS_APPROX(C,R); + } +} + +template +void bug_1311() +{ + Matrix< double, Rows, 2 > A; A.setRandom(); + Vector2d b = Vector2d::Random() ; + Matrix res; + res.noalias() = 1. * (A * b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = 1.*A * b; + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (1.*A).lazyProduct(b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (1.*A).lazyProduct(1.*b); + VERIFY_IS_APPROX(res, A*b); + res.noalias() = (A).lazyProduct(1.*b); + VERIFY_IS_APPROX(res, A*b); +} void test_product_small() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( product(Matrix()) ); - CALL_SUBTEST_2( product(Matrix()) ); + CALL_SUBTEST_2( product(Matrix()) ); + CALL_SUBTEST_8( product(Matrix()) ); CALL_SUBTEST_3( product(Matrix3d()) ); CALL_SUBTEST_4( product(Matrix4d()) ); CALL_SUBTEST_5( product(Matrix4f()) ); - CALL_SUBTEST_6( product1x1() ); + CALL_SUBTEST_6( product1x1<0>() ); + + CALL_SUBTEST_11( test_lazy_l1() ); + CALL_SUBTEST_12( test_lazy_l2() ); + CALL_SUBTEST_13( test_lazy_l3() ); + + CALL_SUBTEST_21( test_lazy_l1() ); + CALL_SUBTEST_22( test_lazy_l2() ); + CALL_SUBTEST_23( test_lazy_l3() ); + + CALL_SUBTEST_31( test_lazy_l1 >() ); + CALL_SUBTEST_32( test_lazy_l2 >() ); + CALL_SUBTEST_33( test_lazy_l3 >() ); + + CALL_SUBTEST_41( test_lazy_l1 >() ); + CALL_SUBTEST_42( test_lazy_l2 >() ); + CALL_SUBTEST_43( test_lazy_l3 >() ); + + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + CALL_SUBTEST_7(( test_linear_but_not_vectorizable() )); + + CALL_SUBTEST_6( bug_1311<3>() ); + CALL_SUBTEST_6( bug_1311<5>() ); } #ifdef EIGEN_TEST_PART_6 @@ -46,5 +269,25 @@ void test_product_small() Vector3f v = Vector3f::Random(); VERIFY_IS_APPROX( (v * v.transpose()) * v, (v * v.transpose()).eval() * v); } + + { + // regression test for pull-request #93 + Eigen::Matrix A; A.setRandom(); + Eigen::Matrix B; B.setRandom(); + Eigen::Matrix C; C.setRandom(); + VERIFY_IS_APPROX(B * A.inverse(), B * A.inverse()[0]); + VERIFY_IS_APPROX(A.inverse() * C, A.inverse()[0] * C); + } + + { + Eigen::Matrix A, B, C; + A.setRandom(); + C = A; + for(int k=0; k<79; ++k) + C = C * A; + B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))) + * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))); + VERIFY_IS_APPROX(B,C); + } #endif } diff --git a/gtsam/3rdparty/Eigen/test/product_symm.cpp b/gtsam/3rdparty/Eigen/test/product_symm.cpp index 74d7329b1..8c44383f9 100644 --- a/gtsam/3rdparty/Eigen/test/product_symm.cpp +++ b/gtsam/3rdparty/Eigen/test/product_symm.cpp @@ -39,6 +39,24 @@ template void symm(int size = Size, in VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView() * (s2*rhs1), rhs13 = (s1*m1) * (s2*rhs1)); + VERIFY_IS_APPROX(rhs12 = (s1*m2).transpose().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1.transpose()) * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().transpose() * (s2*rhs1), + rhs13 = (s1*m1.transpose()) * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).conjugate().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1).conjugate() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().conjugate() * (s2*rhs1), + rhs13 = (s1*m1).conjugate() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).adjoint().template selfadjointView() * (s2*rhs1), + rhs13 = (s1*m1).adjoint() * (s2*rhs1)); + + VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView().adjoint() * (s2*rhs1), + rhs13 = (s1*m1).adjoint() * (s2*rhs1)); + m2 = m1.template triangularView(); rhs12.setRandom(); rhs13 = rhs12; m3 = m2.template selfadjointView(); VERIFY_IS_EQUAL(m1, m3); diff --git a/gtsam/3rdparty/Eigen/test/product_syrk.cpp b/gtsam/3rdparty/Eigen/test/product_syrk.cpp index 73c95000c..e10f0f2f2 100644 --- a/gtsam/3rdparty/Eigen/test/product_syrk.cpp +++ b/gtsam/3rdparty/Eigen/test/product_syrk.cpp @@ -125,11 +125,12 @@ void test_product_syrk() int s; s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( syrk(MatrixXf(s, s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_2( syrk(MatrixXd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_3( syrk(MatrixXcf(s, s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( syrk(MatrixXcd(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } } diff --git a/gtsam/3rdparty/Eigen/test/product_trmm.cpp b/gtsam/3rdparty/Eigen/test/product_trmm.cpp index d715b9a36..12e554410 100644 --- a/gtsam/3rdparty/Eigen/test/product_trmm.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trmm.cpp @@ -9,10 +9,18 @@ #include "main.h" +template +int get_random_size() +{ + const int factor = NumTraits::ReadCost; + const int max_test_size = EIGEN_TEST_MAX_SIZE>2*factor ? EIGEN_TEST_MAX_SIZE/factor : EIGEN_TEST_MAX_SIZE; + return internal::random(1,max_test_size); +} + template -void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), - int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), - int otherCols = OtherCols==Dynamic?internal::random(1,EIGEN_TEST_MAX_SIZE):OtherCols) +void trmm(int rows=get_random_size(), + int cols=get_random_size(), + int otherCols = OtherCols==Dynamic?get_random_size():OtherCols) { typedef Matrix TriMatrix; typedef Matrix OnTheRight; @@ -42,13 +50,13 @@ void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView() * ge_right, tri * ge_right); VERIFY_IS_APPROX( ge_sx.noalias() = ge_left * mat.template triangularView(), ge_left * tri); - + VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.transpose()), s1*triTr.conjugate() * (s2*ge_left.transpose())); VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.transpose() * mat.adjoint().template triangularView(), ge_right.transpose() * triTr.conjugate()); VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()), s1*triTr.conjugate() * (s2*ge_left.adjoint())); VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.adjoint() * mat.adjoint().template triangularView(), ge_right.adjoint() * triTr.conjugate()); - + ge_xs_save = ge_xs; VERIFY_IS_APPROX( (ge_xs_save + s1*triTr.conjugate() * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.adjoint()).template triangularView() * (s2*ge_left.adjoint()) ); ge_sx.setRandom(); @@ -61,13 +69,13 @@ void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), } template -void trmv(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE)) +void trmv(int rows=get_random_size(), int cols=get_random_size()) { trmm(rows,cols,1); } template -void trmm(int rows=internal::random(1,EIGEN_TEST_MAX_SIZE), int cols=internal::random(1,EIGEN_TEST_MAX_SIZE), int otherCols = internal::random(1,EIGEN_TEST_MAX_SIZE)) +void trmm(int rows=get_random_size(), int cols=get_random_size(), int otherCols = get_random_size()) { trmm(rows,cols,otherCols); } diff --git a/gtsam/3rdparty/Eigen/test/product_trmv.cpp b/gtsam/3rdparty/Eigen/test/product_trmv.cpp index 4c3c435c2..57a202afc 100644 --- a/gtsam/3rdparty/Eigen/test/product_trmv.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trmv.cpp @@ -78,12 +78,14 @@ void test_product_trmv() CALL_SUBTEST_1( trmv(Matrix()) ); CALL_SUBTEST_2( trmv(Matrix()) ); CALL_SUBTEST_3( trmv(Matrix3d()) ); + s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_4( trmv(MatrixXcf(s,s)) ); - s = internal::random(1,EIGEN_TEST_MAX_SIZE/2); CALL_SUBTEST_5( trmv(MatrixXcd(s,s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) + s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_6( trmv(Matrix(s, s)) ); + TEST_SET_BUT_UNUSED_VARIABLE(s) } - TEST_SET_BUT_UNUSED_VARIABLE(s); } diff --git a/gtsam/3rdparty/Eigen/test/product_trsolve.cpp b/gtsam/3rdparty/Eigen/test/product_trsolve.cpp index 69892b3a8..4b97fa9d6 100644 --- a/gtsam/3rdparty/Eigen/test/product_trsolve.cpp +++ b/gtsam/3rdparty/Eigen/test/product_trsolve.cpp @@ -84,10 +84,18 @@ void test_product_trsolve() CALL_SUBTEST_4((trsolve,Dynamic,Dynamic>(internal::random(1,EIGEN_TEST_MAX_SIZE/2),internal::random(1,EIGEN_TEST_MAX_SIZE/2)))); // vectors - CALL_SUBTEST_1((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); - CALL_SUBTEST_5((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); - CALL_SUBTEST_6((trsolve())); - CALL_SUBTEST_7((trsolve())); - CALL_SUBTEST_8((trsolve,4,1>())); + CALL_SUBTEST_5((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_6((trsolve(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_7((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + CALL_SUBTEST_8((trsolve,Dynamic,1>(internal::random(1,EIGEN_TEST_MAX_SIZE)))); + + // meta-unrollers + CALL_SUBTEST_9((trsolve())); + CALL_SUBTEST_10((trsolve())); + CALL_SUBTEST_11((trsolve,4,1>())); + CALL_SUBTEST_12((trsolve())); + CALL_SUBTEST_13((trsolve())); + CALL_SUBTEST_14((trsolve())); + } } diff --git a/gtsam/3rdparty/Eigen/test/qr.cpp b/gtsam/3rdparty/Eigen/test/qr.cpp index a79e0dd34..dfcc1e8f9 100644 --- a/gtsam/3rdparty/Eigen/test/qr.cpp +++ b/gtsam/3rdparty/Eigen/test/qr.cpp @@ -54,6 +54,8 @@ template void qr_invertible() { using std::log; using std::abs; + using std::pow; + using std::max; typedef typename NumTraits::Real RealScalar; typedef typename MatrixType::Scalar Scalar; @@ -65,7 +67,7 @@ template void qr_invertible() if (internal::is_same::value) { // let's build a matrix more stable to inverse - MatrixType a = MatrixType::Random(size,size*2); + MatrixType a = MatrixType::Random(size,size*4); m1 += a * a.adjoint(); } @@ -81,8 +83,11 @@ template void qr_invertible() m3 = qr.householderQ(); // get a unitary m1 = m3 * m1 * m3; qr.compute(m1); - VERIFY_IS_APPROX(absdet, qr.absDeterminant()); VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant()); + // This test is tricky if the determinant becomes too small. + // Since we generate random numbers with magnitude rrange [0,1], the average determinant is 0.5^size + VERIFY_IS_MUCH_SMALLER_THAN( abs(absdet-qr.absDeterminant()), numext::maxi(RealScalar(pow(0.5,size)),numext::maxi(abs(absdet),abs(qr.absDeterminant()))) ); + } template void qr_verify_assert() diff --git a/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp b/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp index eb3feac01..26ed27f5c 100644 --- a/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp +++ b/gtsam/3rdparty/Eigen/test/qr_colpivoting.cpp @@ -10,21 +10,103 @@ #include "main.h" #include +#include + +template +void cod() { + typedef typename MatrixType::Index Index; + + Index rows = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index cols = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index cols2 = internal::random(2, EIGEN_TEST_MAX_SIZE); + Index rank = internal::random(1, (std::min)(rows, cols) - 1); + + typedef typename MatrixType::Scalar Scalar; + typedef Matrix + MatrixQType; + MatrixType matrix; + createRandomPIMatrixOfRank(rank, rows, cols, matrix); + CompleteOrthogonalDecomposition cod(matrix); + VERIFY(rank == cod.rank()); + VERIFY(cols - cod.rank() == cod.dimensionOfKernel()); + VERIFY(!cod.isInjective()); + VERIFY(!cod.isInvertible()); + VERIFY(!cod.isSurjective()); + + MatrixQType q = cod.householderQ(); + VERIFY_IS_UNITARY(q); + + MatrixType z = cod.matrixZ(); + VERIFY_IS_UNITARY(z); + + MatrixType t; + t.setZero(rows, cols); + t.topLeftCorner(rank, rank) = + cod.matrixT().topLeftCorner(rank, rank).template triangularView(); + + MatrixType c = q * t * z * cod.colsPermutation().inverse(); + VERIFY_IS_APPROX(matrix, c); + + MatrixType exact_solution = MatrixType::Random(cols, cols2); + MatrixType rhs = matrix * exact_solution; + MatrixType cod_solution = cod.solve(rhs); + VERIFY_IS_APPROX(rhs, matrix * cod_solution); + + // Verify that we get the same minimum-norm solution as the SVD. + JacobiSVD svd(matrix, ComputeThinU | ComputeThinV); + MatrixType svd_solution = svd.solve(rhs); + VERIFY_IS_APPROX(cod_solution, svd_solution); + + MatrixType pinv = cod.pseudoInverse(); + VERIFY_IS_APPROX(cod_solution, pinv * rhs); +} + +template +void cod_fixedsize() { + enum { + Rows = MatrixType::RowsAtCompileTime, + Cols = MatrixType::ColsAtCompileTime + }; + typedef typename MatrixType::Scalar Scalar; + int rank = internal::random(1, (std::min)(int(Rows), int(Cols)) - 1); + Matrix matrix; + createRandomPIMatrixOfRank(rank, Rows, Cols, matrix); + CompleteOrthogonalDecomposition > cod(matrix); + VERIFY(rank == cod.rank()); + VERIFY(Cols - cod.rank() == cod.dimensionOfKernel()); + VERIFY(cod.isInjective() == (rank == Rows)); + VERIFY(cod.isSurjective() == (rank == Cols)); + VERIFY(cod.isInvertible() == (cod.isInjective() && cod.isSurjective())); + + Matrix exact_solution; + exact_solution.setRandom(Cols, Cols2); + Matrix rhs = matrix * exact_solution; + Matrix cod_solution = cod.solve(rhs); + VERIFY_IS_APPROX(rhs, matrix * cod_solution); + + // Verify that we get the same minimum-norm solution as the SVD. + JacobiSVD svd(matrix, ComputeFullU | ComputeFullV); + Matrix svd_solution = svd.solve(rhs); + VERIFY_IS_APPROX(cod_solution, svd_solution); +} template void qr() { + using std::sqrt; typedef typename MatrixType::Index Index; Index rows = internal::random(2,EIGEN_TEST_MAX_SIZE), cols = internal::random(2,EIGEN_TEST_MAX_SIZE), cols2 = internal::random(2,EIGEN_TEST_MAX_SIZE); Index rank = internal::random(1, (std::min)(rows, cols)-1); typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; typedef Matrix MatrixQType; MatrixType m1; createRandomPIMatrixOfRank(rank,rows,cols,m1); ColPivHouseholderQR qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(cols - qr.rank() == qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel()); VERIFY(!qr.isInjective()); VERIFY(!qr.isInvertible()); VERIFY(!qr.isSurjective()); @@ -36,26 +118,59 @@ template void qr() MatrixType c = q * r * qr.colsPermutation().inverse(); VERIFY_IS_APPROX(m1, c); + // Verify that the absolute value of the diagonal elements in R are + // non-increasing until they reach the singularity threshold. + RealScalar threshold = + sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(rows, cols); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << rank + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } + MatrixType m2 = MatrixType::Random(cols,cols2); MatrixType m3 = m1*m2; m2 = MatrixType::Random(cols,cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + { + Index size = rows; + do { + m1 = MatrixType::Random(size,size); + qr.compute(m1); + } while(!qr.isInvertible()); + MatrixType m1_inv = qr.inverse(); + m3 = m1 * MatrixType::Random(size,cols2); + m2 = qr.solve(m3); + VERIFY_IS_APPROX(m2, m1_inv*m3); + } } template void qr_fixedsize() { + using std::sqrt; + using std::abs; enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime }; typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; int rank = internal::random(1, (std::min)(int(Rows), int(Cols))-1); Matrix m1; createRandomPIMatrixOfRank(rank,Rows,Cols,m1); ColPivHouseholderQR > qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(Cols - qr.rank() == qr.dimensionOfKernel()); - VERIFY(qr.isInjective() == (rank == Rows)); - VERIFY(qr.isSurjective() == (rank == Cols)); - VERIFY(qr.isInvertible() == (qr.isInjective() && qr.isSurjective())); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(Cols - qr.rank(), qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(qr.isInjective(), (rank == Rows)); + VERIFY_IS_EQUAL(qr.isSurjective(), (rank == Cols)); + VERIFY_IS_EQUAL(qr.isInvertible(), (qr.isInjective() && qr.isSurjective())); Matrix r = qr.matrixQR().template triangularView(); Matrix c = qr.householderQ() * r * qr.colsPermutation().inverse(); @@ -66,6 +181,71 @@ template void qr_fixedsize() m2 = Matrix::Random(Cols,Cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + // Verify that the absolute value of the diagonal elements in R are + // non-increasing until they reache the singularity threshold. + RealScalar threshold = + sqrt(RealScalar(Rows)) * (std::abs)(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(int(Rows), int(Cols)) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(int(Rows), int(Cols)); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << rank + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } +} + +// This test is meant to verify that pivots are chosen such that +// even for a graded matrix, the diagonal of R falls of roughly +// monotonically until it reaches the threshold for singularity. +// We use the so-called Kahan matrix, which is a famous counter-example +// for rank-revealing QR. See +// http://www.netlib.org/lapack/lawnspdf/lawn176.pdf +// page 3 for more detail. +template void qr_kahan_matrix() +{ + using std::sqrt; + using std::abs; + typedef typename MatrixType::Index Index; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + + Index rows = 300, cols = rows; + + MatrixType m1; + m1.setZero(rows,cols); + RealScalar s = std::pow(NumTraits::epsilon(), 1.0 / rows); + RealScalar c = std::sqrt(1 - s*s); + RealScalar pow_s_i(1.0); // pow(s,i) + for (Index i = 0; i < rows; ++i) { + m1(i, i) = pow_s_i; + m1.row(i).tail(rows - i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows - i - 1); + pow_s_i *= s; + } + m1 = (m1 + m1.transpose()).eval(); + ColPivHouseholderQR qr(m1); + MatrixType r = qr.matrixQR().template triangularView(); + + RealScalar threshold = + std::sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits::epsilon(); + for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) { + RealScalar x = numext::abs(r(i, i)); + RealScalar y = numext::abs(r(i + 1, i + 1)); + if (x < threshold && y < threshold) continue; + if (!test_isApproxOrLessThan(y, x)) { + for (Index j = 0; j < (std::min)(rows, cols); ++j) { + std::cout << "i = " << j << ", |r_ii| = " << numext::abs(r(j, j)) << std::endl; + } + std::cout << "Failure at i=" << i << ", rank=" << qr.rank() + << ", threshold=" << threshold << std::endl; + } + VERIFY_IS_APPROX_OR_LESS_THAN(y, x); + } } template void qr_invertible() @@ -131,6 +311,15 @@ void test_qr_colpivoting() CALL_SUBTEST_5(( qr_fixedsize, 1 >() )); } + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( cod() ); + CALL_SUBTEST_2( cod() ); + CALL_SUBTEST_3( cod() ); + CALL_SUBTEST_4(( cod_fixedsize, 4 >() )); + CALL_SUBTEST_5(( cod_fixedsize, 3 >() )); + CALL_SUBTEST_5(( cod_fixedsize, 1 >() )); + } + for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( qr_invertible() ); CALL_SUBTEST_2( qr_invertible() ); @@ -147,4 +336,7 @@ void test_qr_colpivoting() // Test problem size constructors CALL_SUBTEST_9(ColPivHouseholderQR(10, 20)); + + CALL_SUBTEST_1( qr_kahan_matrix() ); + CALL_SUBTEST_2( qr_kahan_matrix() ); } diff --git a/gtsam/3rdparty/Eigen/test/qr_fullpivoting.cpp b/gtsam/3rdparty/Eigen/test/qr_fullpivoting.cpp index 511f2473f..70e89c198 100644 --- a/gtsam/3rdparty/Eigen/test/qr_fullpivoting.cpp +++ b/gtsam/3rdparty/Eigen/test/qr_fullpivoting.cpp @@ -15,16 +15,20 @@ template void qr() { typedef typename MatrixType::Index Index; - Index rows = internal::random(20,200), cols = internal::random(20,200), cols2 = internal::random(20,200); - Index rank = internal::random(1, (std::min)(rows, cols)-1); + Index max_size = EIGEN_TEST_MAX_SIZE; + Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10); + Index rows = internal::random(min_size,max_size), + cols = internal::random(min_size,max_size), + cols2 = internal::random(min_size,max_size), + rank = internal::random(1, (std::min)(rows, cols)-1); typedef typename MatrixType::Scalar Scalar; typedef Matrix MatrixQType; MatrixType m1; createRandomPIMatrixOfRank(rank,rows,cols,m1); FullPivHouseholderQR qr(m1); - VERIFY(rank == qr.rank()); - VERIFY(cols - qr.rank() == qr.dimensionOfKernel()); + VERIFY_IS_EQUAL(rank, qr.rank()); + VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel()); VERIFY(!qr.isInjective()); VERIFY(!qr.isInvertible()); VERIFY(!qr.isSurjective()); @@ -40,12 +44,28 @@ template void qr() MatrixType c = qr.matrixQ() * r * qr.colsPermutation().inverse(); VERIFY_IS_APPROX(m1, c); - + + // stress the ReturnByValue mechanism + MatrixType tmp; + VERIFY_IS_APPROX(tmp.noalias() = qr.matrixQ() * r, (qr.matrixQ() * r).eval()); + MatrixType m2 = MatrixType::Random(cols,cols2); MatrixType m3 = m1*m2; m2 = MatrixType::Random(cols,cols2); m2 = qr.solve(m3); VERIFY_IS_APPROX(m3, m1*m2); + + { + Index size = rows; + do { + m1 = MatrixType::Random(size,size); + qr.compute(m1); + } while(!qr.isInvertible()); + MatrixType m1_inv = qr.inverse(); + m3 = m1 * MatrixType::Random(size,cols2); + m2 = qr.solve(m3); + VERIFY_IS_APPROX(m2, m1_inv*m3); + } } template void qr_invertible() @@ -55,7 +75,9 @@ template void qr_invertible() typedef typename NumTraits::Real RealScalar; typedef typename MatrixType::Scalar Scalar; - int size = internal::random(10,50); + Index max_size = numext::mini(50,EIGEN_TEST_MAX_SIZE); + Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10); + Index size = internal::random(min_size,max_size); MatrixType m1(size, size), m2(size, size), m3(size, size); m1 = MatrixType::Random(size,size); diff --git a/gtsam/3rdparty/Eigen/test/rand.cpp b/gtsam/3rdparty/Eigen/test/rand.cpp new file mode 100644 index 000000000..51cf01773 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/rand.cpp @@ -0,0 +1,118 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +typedef long long int64; + +template Scalar check_in_range(Scalar x, Scalar y) +{ + Scalar r = internal::random(x,y); + VERIFY(r>=x); + if(y>=x) + { + VERIFY(r<=y); + } + return r; +} + +template void check_all_in_range(Scalar x, Scalar y) +{ + Array mask(y-x+1); + mask.fill(0); + long n = (y-x+1)*32; + for(long k=0; k0).all() ); +} + +template void check_histogram(Scalar x, Scalar y, int bins) +{ + Array hist(bins); + hist.fill(0); + int f = 100000; + int n = bins*f; + int64 range = int64(y)-int64(x); + int divisor = int((range+1)/bins); + assert(((range+1)%bins)==0); + for(int k=0; k()/double(f))-1.0).abs()<0.02).all() ); +} + +void test_rand() +{ + long long_ref = NumTraits::highest()/10; + signed char char_offset = (std::min)(g_repeat,64); + signed char short_offset = (std::min)(g_repeat,16000); + + for(int i = 0; i < g_repeat*10000; i++) { + CALL_SUBTEST(check_in_range(10,11)); + CALL_SUBTEST(check_in_range(1.24234523,1.24234523)); + CALL_SUBTEST(check_in_range(-1,1)); + CALL_SUBTEST(check_in_range(-1432.2352,-1432.2352)); + + CALL_SUBTEST(check_in_range(10,11)); + CALL_SUBTEST(check_in_range(1.24234523,1.24234523)); + CALL_SUBTEST(check_in_range(-1,1)); + CALL_SUBTEST(check_in_range(-1432.2352,-1432.2352)); + + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(0,-1)); + CALL_SUBTEST(check_in_range(-673456,673456)); + CALL_SUBTEST(check_in_range(-RAND_MAX+10,RAND_MAX-10)); + CALL_SUBTEST(check_in_range(-24345,24345)); + CALL_SUBTEST(check_in_range(-long_ref,long_ref)); + } + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+char_offset)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-char_offset,-11)); + CALL_SUBTEST(check_all_in_range(-126,-126+char_offset)); + CALL_SUBTEST(check_all_in_range(126-char_offset,126)); + CALL_SUBTEST(check_all_in_range(-126,126)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+short_offset)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-short_offset,-11)); + CALL_SUBTEST(check_all_in_range(-24345,-24345+short_offset)); + CALL_SUBTEST(check_all_in_range(24345,24345+short_offset)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+g_repeat)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-g_repeat,-11)); + CALL_SUBTEST(check_all_in_range(-673456,-673456+g_repeat)); + CALL_SUBTEST(check_all_in_range(673456,673456+g_repeat)); + + CALL_SUBTEST(check_all_in_range(11,11)); + CALL_SUBTEST(check_all_in_range(11,11+g_repeat)); + CALL_SUBTEST(check_all_in_range(-5,5)); + CALL_SUBTEST(check_all_in_range(-11-g_repeat,-11)); + CALL_SUBTEST(check_all_in_range(-long_ref,-long_ref+g_repeat)); + CALL_SUBTEST(check_all_in_range( long_ref, long_ref+g_repeat)); + + CALL_SUBTEST(check_histogram(-5,5,11)); + int bins = 100; + CALL_SUBTEST(check_histogram(-3333,-3333+bins*(3333/bins)-1,bins)); + bins = 1000; + CALL_SUBTEST(check_histogram(-RAND_MAX+10,-RAND_MAX+10+bins*(RAND_MAX/bins)-1,bins)); + CALL_SUBTEST(check_histogram(-RAND_MAX+10,-int64(RAND_MAX)+10+bins*(2*int64(RAND_MAX)/bins)-1,bins)); +} diff --git a/gtsam/3rdparty/Eigen/test/real_qz.cpp b/gtsam/3rdparty/Eigen/test/real_qz.cpp index a1766c6d9..99ac31235 100644 --- a/gtsam/3rdparty/Eigen/test/real_qz.cpp +++ b/gtsam/3rdparty/Eigen/test/real_qz.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_RUNTIME_NO_MALLOC #include "main.h" #include #include @@ -41,7 +42,11 @@ template void real_qz(const MatrixType& m) break; } - RealQZ qz(A,B); + RealQZ qz(dim); + // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition + //Eigen::internal::set_is_malloc_allowed(false); + qz.compute(A,B); + //Eigen::internal::set_is_malloc_allowed(true); VERIFY_IS_EQUAL(qz.info(), Success); // check for zeros @@ -49,11 +54,20 @@ template void real_qz(const MatrixType& m) for (Index i=0; i void matrixRedux(const MatrixType& m) @@ -21,7 +24,7 @@ template void matrixRedux(const MatrixType& m) MatrixType m1 = MatrixType::Random(rows, cols); // The entries of m1 are uniformly distributed in [0,1], so m1.prod() is very small. This may lead to test - // failures if we underflow into denormals. Thus, we scale so that entires are close to 1. + // failures if we underflow into denormals. Thus, we scale so that entries are close to 1. MatrixType m1_for_prod = MatrixType::Ones(rows, cols) + RealScalar(0.2) * m1; VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1)); @@ -65,6 +68,12 @@ template void matrixRedux(const MatrixType& m) // test empty objects VERIFY_IS_APPROX(m1.block(r0,c0,0,0).sum(), Scalar(0)); VERIFY_IS_APPROX(m1.block(r0,c0,0,0).prod(), Scalar(1)); + + // test nesting complex expression + VERIFY_EVALUATION_COUNT( (m1.matrix()*m1.matrix().transpose()).sum(), (MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1) ); + Matrix m2(rows,rows); + m2.setRandom(); + VERIFY_EVALUATION_COUNT( ((m1.matrix()*m1.matrix().transpose())+m2).sum(),(MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1)); } template void vectorRedux(const VectorType& w) @@ -147,8 +156,10 @@ void test_redux() CALL_SUBTEST_1( matrixRedux(Array()) ); CALL_SUBTEST_2( matrixRedux(Matrix2f()) ); CALL_SUBTEST_2( matrixRedux(Array2f()) ); + CALL_SUBTEST_2( matrixRedux(Array22f()) ); CALL_SUBTEST_3( matrixRedux(Matrix4d()) ); CALL_SUBTEST_3( matrixRedux(Array4d()) ); + CALL_SUBTEST_3( matrixRedux(Array44d()) ); CALL_SUBTEST_4( matrixRedux(MatrixXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); CALL_SUBTEST_4( matrixRedux(ArrayXXcf(internal::random(1,maxsize), internal::random(1,maxsize))) ); CALL_SUBTEST_5( matrixRedux(MatrixXd (internal::random(1,maxsize), internal::random(1,maxsize))) ); diff --git a/gtsam/3rdparty/Eigen/test/ref.cpp b/gtsam/3rdparty/Eigen/test/ref.cpp index 8297e263a..769db0414 100644 --- a/gtsam/3rdparty/Eigen/test/ref.cpp +++ b/gtsam/3rdparty/Eigen/test/ref.cpp @@ -12,26 +12,10 @@ #undef EIGEN_DEFAULT_TO_ROW_MAJOR #endif -static int nb_temporaries; - -inline void on_temporary_creation(int) { - // here's a great place to set a breakpoint when debugging failures in this test! - nb_temporaries++; -} - - -#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); } +#define TEST_ENABLE_TEMPORARY_TRACKING #include "main.h" -#define VERIFY_EVALUATION_COUNT(XPR,N) {\ - nb_temporaries = 0; \ - XPR; \ - if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ - VERIFY( (#XPR) && nb_temporaries==N ); \ - } - - // test Ref.h // Deal with i387 extended precision @@ -248,6 +232,12 @@ int test_ref_overload_fun1(Ref ) { return 3; } int test_ref_overload_fun2(Ref ) { return 4; } int test_ref_overload_fun2(Ref ) { return 5; } +void test_ref_ambiguous(const Ref &A, Ref B) +{ + B = A; + B = A - A; +} + // See also bug 969 void test_ref_overloads() { @@ -260,6 +250,9 @@ void test_ref_overloads() VERIFY( test_ref_overload_fun2(Ad)==4 ); VERIFY( test_ref_overload_fun2(Ad+Bd)==4 ); VERIFY( test_ref_overload_fun2(Af+Bf)==5 ); + + ArrayXd A, B; + test_ref_ambiguous(A, B); } void test_ref() diff --git a/gtsam/3rdparty/Eigen/test/runtest.sh b/gtsam/3rdparty/Eigen/test/runtest.sh deleted file mode 100755 index 2be250819..000000000 --- a/gtsam/3rdparty/Eigen/test/runtest.sh +++ /dev/null @@ -1,20 +0,0 @@ -#!/bin/bash - -black='\E[30m' -red='\E[31m' -green='\E[32m' -yellow='\E[33m' -blue='\E[34m' -magenta='\E[35m' -cyan='\E[36m' -white='\E[37m' - -if ! ./$1 > /dev/null 2> .runtest.log ; then - echo -e $red Test $1 failed: $black - echo -e $blue - cat .runtest.log - echo -e $black - exit 1 -else -echo -e $green Test $1 passed$black -fi diff --git a/gtsam/3rdparty/Eigen/test/rvalue_types.cpp b/gtsam/3rdparty/Eigen/test/rvalue_types.cpp new file mode 100644 index 000000000..8887f1b1b --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/rvalue_types.cpp @@ -0,0 +1,64 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include + +using internal::UIntPtr; + +#if EIGEN_HAS_RVALUE_REFERENCES +template +void rvalue_copyassign(const MatrixType& m) +{ + + typedef typename internal::traits::Scalar Scalar; + + // create a temporary which we are about to destroy by moving + MatrixType tmp = m; + UIntPtr src_address = reinterpret_cast(tmp.data()); + + // move the temporary to n + MatrixType n = std::move(tmp); + UIntPtr dst_address = reinterpret_cast(n.data()); + + if (MatrixType::RowsAtCompileTime==Dynamic|| MatrixType::ColsAtCompileTime==Dynamic) + { + // verify that we actually moved the guts + VERIFY_IS_EQUAL(src_address, dst_address); + } + + // verify that the content did not change + Scalar abs_diff = (m-n).array().abs().sum(); + VERIFY_IS_EQUAL(abs_diff, Scalar(0)); +} +#else +template +void rvalue_copyassign(const MatrixType&) {} +#endif + +void test_rvalue_types() +{ + CALL_SUBTEST_1(rvalue_copyassign( MatrixXf::Random(50,50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( ArrayXXf::Random(50,50).eval() )); + + CALL_SUBTEST_1(rvalue_copyassign( Matrix::Random(50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( Array::Random(50).eval() )); + + CALL_SUBTEST_1(rvalue_copyassign( Matrix::Random(50).eval() )); + CALL_SUBTEST_1(rvalue_copyassign( Array::Random(50).eval() )); + + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); + CALL_SUBTEST_2(rvalue_copyassign( Array::Random().eval() )); +} diff --git a/gtsam/3rdparty/Eigen/test/schur_complex.cpp b/gtsam/3rdparty/Eigen/test/schur_complex.cpp index 5e869790f..deb78e44e 100644 --- a/gtsam/3rdparty/Eigen/test/schur_complex.cpp +++ b/gtsam/3rdparty/Eigen/test/schur_complex.cpp @@ -25,7 +25,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim ComplexMatrixType T = schurOfA.matrixT(); for(int row = 1; row < size; ++row) { for(int col = 0; col < row; ++col) { - VERIFY(T(row,col) == (typename MatrixType::Scalar)0); + VERIFY(T(row,col) == (typename MatrixType::Scalar)0); } } VERIFY_IS_APPROX(A.template cast(), U * T * U.adjoint()); @@ -70,7 +70,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim VERIFY_IS_EQUAL(cs1.matrixT(), csOnlyT.matrixT()); VERIFY_RAISES_ASSERT(csOnlyT.matrixU()); - if (size > 1) + if (size > 1 && size < 20) { // Test matrix with NaN A(0,0) = std::numeric_limits::quiet_NaN(); diff --git a/gtsam/3rdparty/Eigen/test/schur_real.cpp b/gtsam/3rdparty/Eigen/test/schur_real.cpp index 36b9c24d1..4aede87df 100644 --- a/gtsam/3rdparty/Eigen/test/schur_real.cpp +++ b/gtsam/3rdparty/Eigen/test/schur_real.cpp @@ -82,7 +82,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim Atriangular.template triangularView().setZero(); rs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations VERIFY_IS_EQUAL(rs3.info(), Success); - VERIFY_IS_EQUAL(rs3.matrixT(), Atriangular); + VERIFY_IS_APPROX(rs3.matrixT(), Atriangular); // approx because of scaling... VERIFY_IS_EQUAL(rs3.matrixU(), MatrixType::Identity(size, size)); // Test computation of only T, not U @@ -91,7 +91,7 @@ template void schur(int size = MatrixType::ColsAtCompileTim VERIFY_IS_EQUAL(rs1.matrixT(), rsOnlyT.matrixT()); VERIFY_RAISES_ASSERT(rsOnlyT.matrixU()); - if (size > 2) + if (size > 2 && size < 20) { // Test matrix with NaN A(0,0) = std::numeric_limits::quiet_NaN(); diff --git a/gtsam/3rdparty/Eigen/test/selfadjoint.cpp b/gtsam/3rdparty/Eigen/test/selfadjoint.cpp index 76dab6d64..92401e506 100644 --- a/gtsam/3rdparty/Eigen/test/selfadjoint.cpp +++ b/gtsam/3rdparty/Eigen/test/selfadjoint.cpp @@ -21,7 +21,9 @@ template void selfadjoint(const MatrixType& m) Index cols = m.cols(); MatrixType m1 = MatrixType::Random(rows, cols), - m3(rows, cols); + m2 = MatrixType::Random(rows, cols), + m3(rows, cols), + m4(rows, cols); m1.diagonal() = m1.diagonal().real().template cast(); @@ -30,10 +32,19 @@ template void selfadjoint(const MatrixType& m) VERIFY_IS_APPROX(MatrixType(m3.template triangularView()), MatrixType(m1.template triangularView())); VERIFY_IS_APPROX(m3, m3.adjoint()); - m3 = m1.template selfadjointView(); VERIFY_IS_APPROX(MatrixType(m3.template triangularView()), MatrixType(m1.template triangularView())); VERIFY_IS_APPROX(m3, m3.adjoint()); + + m3 = m1.template selfadjointView(); + m4 = m2; + m4 += m1.template selfadjointView(); + VERIFY_IS_APPROX(m4, m2+m3); + + m3 = m1.template selfadjointView(); + m4 = m2; + m4 -= m1.template selfadjointView(); + VERIFY_IS_APPROX(m4, m2-m3); } void bug_159() diff --git a/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp index 786468421..649c817b4 100644 --- a/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp +++ b/gtsam/3rdparty/Eigen/test/simplicial_cholesky.cpp @@ -9,16 +9,17 @@ #include "sparse_solver.h" -template void test_simplicial_cholesky_T() +template void test_simplicial_cholesky_T() { - SimplicialCholesky, Lower> chol_colmajor_lower_amd; - SimplicialCholesky, Upper> chol_colmajor_upper_amd; - SimplicialLLT, Lower> llt_colmajor_lower_amd; - SimplicialLLT, Upper> llt_colmajor_upper_amd; - SimplicialLDLT, Lower> ldlt_colmajor_lower_amd; - SimplicialLDLT, Upper> ldlt_colmajor_upper_amd; - SimplicialLDLT, Lower, NaturalOrdering > ldlt_colmajor_lower_nat; - SimplicialLDLT, Upper, NaturalOrdering > ldlt_colmajor_upper_nat; + typedef SparseMatrix SparseMatrixType; + SimplicialCholesky chol_colmajor_lower_amd; + SimplicialCholesky chol_colmajor_upper_amd; + SimplicialLLT< SparseMatrixType, Lower> llt_colmajor_lower_amd; + SimplicialLLT< SparseMatrixType, Upper> llt_colmajor_upper_amd; + SimplicialLDLT< SparseMatrixType, Lower> ldlt_colmajor_lower_amd; + SimplicialLDLT< SparseMatrixType, Upper> ldlt_colmajor_upper_amd; + SimplicialLDLT< SparseMatrixType, Lower, NaturalOrdering > ldlt_colmajor_lower_nat; + SimplicialLDLT< SparseMatrixType, Upper, NaturalOrdering > ldlt_colmajor_upper_nat; check_sparse_spd_solving(chol_colmajor_lower_amd); check_sparse_spd_solving(chol_colmajor_upper_amd); @@ -34,12 +35,13 @@ template void test_simplicial_cholesky_T() check_sparse_spd_determinant(ldlt_colmajor_lower_amd); check_sparse_spd_determinant(ldlt_colmajor_upper_amd); - check_sparse_spd_solving(ldlt_colmajor_lower_nat); - check_sparse_spd_solving(ldlt_colmajor_upper_nat); + check_sparse_spd_solving(ldlt_colmajor_lower_nat, 300, 1000); + check_sparse_spd_solving(ldlt_colmajor_upper_nat, 300, 1000); } void test_simplicial_cholesky() { - CALL_SUBTEST_1(test_simplicial_cholesky_T()); - CALL_SUBTEST_2(test_simplicial_cholesky_T >()); + CALL_SUBTEST_1(( test_simplicial_cholesky_T() )); + CALL_SUBTEST_2(( test_simplicial_cholesky_T, int>() )); + CALL_SUBTEST_3(( test_simplicial_cholesky_T() )); } diff --git a/gtsam/3rdparty/Eigen/test/sizeof.cpp b/gtsam/3rdparty/Eigen/test/sizeof.cpp index d9ad35620..03ad20453 100644 --- a/gtsam/3rdparty/Eigen/test/sizeof.cpp +++ b/gtsam/3rdparty/Eigen/test/sizeof.cpp @@ -13,14 +13,27 @@ template void verifySizeOf(const MatrixType&) { typedef typename MatrixType::Scalar Scalar; if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic) - VERIFY(std::ptrdiff_t(sizeof(MatrixType))==std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime)); + VERIFY_IS_EQUAL(std::ptrdiff_t(sizeof(MatrixType)),std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime)); else - VERIFY(sizeof(MatrixType)==sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); + VERIFY_IS_EQUAL(sizeof(MatrixType),sizeof(Scalar*) + 2 * sizeof(typename MatrixType::Index)); } void test_sizeof() { CALL_SUBTEST(verifySizeOf(Matrix()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Array()) ); + CALL_SUBTEST(verifySizeOf(Vector2d()) ); + CALL_SUBTEST(verifySizeOf(Vector4f()) ); CALL_SUBTEST(verifySizeOf(Matrix4d()) ); CALL_SUBTEST(verifySizeOf(Matrix()) ); CALL_SUBTEST(verifySizeOf(Matrix()) ); diff --git a/gtsam/3rdparty/Eigen/test/sizeoverflow.cpp b/gtsam/3rdparty/Eigen/test/sizeoverflow.cpp index 16d6f8d04..240d22294 100644 --- a/gtsam/3rdparty/Eigen/test/sizeoverflow.cpp +++ b/gtsam/3rdparty/Eigen/test/sizeoverflow.cpp @@ -18,8 +18,6 @@ VERIFY(threw && "should have thrown bad_alloc: " #a); \ } -typedef DenseIndex Index; - template void triggerMatrixBadAlloc(Index rows, Index cols) { diff --git a/gtsam/3rdparty/Eigen/test/sparse.h b/gtsam/3rdparty/Eigen/test/sparse.h index e19a76316..9912e1e24 100644 --- a/gtsam/3rdparty/Eigen/test/sparse.h +++ b/gtsam/3rdparty/Eigen/test/sparse.h @@ -53,15 +53,15 @@ enum { * \param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero, * and zero coefficients respectively. */ -template void +template void initSparse(double density, Matrix& refMat, - SparseMatrix& sparseMat, + SparseMatrix& sparseMat, int flags = 0, - std::vector >* zeroCoords = 0, - std::vector >* nonzeroCoords = 0) + std::vector >* zeroCoords = 0, + std::vector >* nonzeroCoords = 0) { - enum { IsRowMajor = SparseMatrix::IsRowMajor }; + enum { IsRowMajor = SparseMatrix::IsRowMajor }; sparseMat.setZero(); //sparseMat.reserve(int(refMat.rows()*refMat.cols()*density)); sparseMat.reserve(VectorXi::Constant(IsRowMajor ? refMat.rows() : refMat.cols(), int((1.5*density)*(IsRowMajor?refMat.cols():refMat.rows())))); @@ -71,14 +71,17 @@ initSparse(double density, //sparseMat.startVec(j); for(Index i=0; i(0,1) < density) ? internal::random() : Scalar(0); if ((flags&ForceNonZeroDiag) && (i==j)) { + // FIXME: the following is too conservative v = internal::random()*Scalar(3.); - v = v*v + Scalar(5.); + v = v*v; + if(numext::real(v)>0) v += Scalar(5); + else v -= Scalar(5); } if ((flags & MakeLowerTriangular) && aj>ai) v = Scalar(0); @@ -93,11 +96,11 @@ initSparse(double density, //sparseMat.insertBackByOuterInner(j,i) = v; sparseMat.insertByOuterInner(j,i) = v; if (nonzeroCoords) - nonzeroCoords->push_back(Matrix (ai,aj)); + nonzeroCoords->push_back(Matrix (ai,aj)); } else if (zeroCoords) { - zeroCoords->push_back(Matrix (ai,aj)); + zeroCoords->push_back(Matrix (ai,aj)); } refMat(ai,aj) = v; } @@ -163,7 +166,7 @@ initSparse(double density, { sparseVec.reserve(int(refVec.size()*density)); sparseVec.setZero(); - for(Index i=0; i(0,1) < density) ? internal::random() : Scalar(0); if (v!=Scalar(0)) diff --git a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp index 2df7b63a7..384985028 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_basic.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_basic.cpp @@ -9,22 +9,28 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static long g_realloc_count = 0; +#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++; + #include "sparse.h" template void sparse_basic(const SparseMatrixType& ref) { - typedef typename SparseMatrixType::Index Index; - typedef Matrix Vector2; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef Matrix Vector2; const Index rows = ref.rows(); const Index cols = ref.cols(); + //const Index inner = ref.innerSize(); + //const Index outer = ref.outerSize(); + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::RealScalar RealScalar; enum { Flags = SparseMatrixType::Flags }; double density = (std::max)(8./(rows*cols), 0.01); typedef Matrix DenseMatrix; typedef Matrix DenseVector; - typedef Matrix RowDenseVector; Scalar eps = 1e-6; Scalar s1 = internal::random(); @@ -37,94 +43,22 @@ template void sparse_basic(const SparseMatrixType& re std::vector nonzeroCoords; initSparse(density, refMat, m, 0, &zeroCoords, &nonzeroCoords); - if (zeroCoords.size()==0 || nonzeroCoords.size()==0) - return; - // test coeff and coeffRef - for (int i=0; i<(int)zeroCoords.size(); ++i) + for (std::size_t i=0; i >::value) - VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 ); + VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[i].x(),zeroCoords[i].y()) = 5 ); } VERIFY_IS_APPROX(m, refMat); - m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); - refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + if(!nonzeroCoords.empty()) { + m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5); + } VERIFY_IS_APPROX(m, refMat); - - // test InnerIterators and Block expressions - for (int t=0; t<10; ++t) - { - int j = internal::random(0,cols-1); - int i = internal::random(0,rows-1); - int w = internal::random(1,cols-j-1); - int h = internal::random(1,rows-i-1); - VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); - for(int c=0; c void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - if(internal::random()%2) - m2.reserve(VectorXi::Constant(m2.outerSize(), 2)); + bool call_reserve = internal::random()%2; + Index nnz = internal::random(1,int(rows)/2); + if(call_reserve) + { + if(internal::random()%2) + m2.reserve(VectorXi::Constant(m2.outerSize(), int(nnz))); + else + m2.reserve(m2.outerSize() * nnz); + } + g_realloc_count = 0; for (Index j=0; j(0,rows-1); if (m1.coeff(i,j)==Scalar(0)) m2.insert(i,j) = m1(i,j) = internal::random(); } } + + if(call_reserve && !SparseMatrixType::IsRowMajor) + { + VERIFY(g_realloc_count==0); + } + m2.finalize(); VERIFY_IS_APPROX(m2,m1); } @@ -179,9 +127,9 @@ template void sparse_basic(const SparseMatrixType& re DenseMatrix m1(rows,cols); m1.setZero(); SparseMatrixType m2(rows,cols); - VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? m2.innerSize() : std::max(1,m2.innerSize()/8))); + VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? int(m2.innerSize()) : std::max(1,int(m2.innerSize())/8))); m2.reserve(r); - for (int k=0; k(0,rows-1); Index j = internal::random(0,cols-1); @@ -195,111 +143,39 @@ template void sparse_basic(const SparseMatrixType& re VERIFY_IS_APPROX(m2,m1); } - // test innerVector() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - Index j0 = internal::random(0,rows-1); - Index j1 = internal::random(0,rows-1); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.row(j0)); - else - VERIFY_IS_APPROX(m2.innerVector(j0), refMat2.col(j0)); - - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.row(j0)+refMat2.row(j1)); - else - VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), refMat2.col(j0)+refMat2.col(j1)); - - SparseMatrixType m3(rows,rows); - m3.reserve(VectorXi::Constant(rows,rows/2)); - for(Index j=0; j0) - VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); - } - m3.makeCompressed(); - for(Index j=0; j0) - VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); - } - - //m2.innerVector(j0) = 2*m2.innerVector(j1); - //refMat2.col(j0) = 2*refMat2.col(j1); - //VERIFY_IS_APPROX(m2, refMat2); - } - - // test innerVectors() - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - if(internal::random(0,1)>0.5) m2.makeCompressed(); - - Index j0 = internal::random(0,rows-2); - Index j1 = internal::random(0,rows-2); - Index n0 = internal::random(1,rows-(std::max)(j0,j1)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0)); - else - VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - - VERIFY_IS_APPROX(m2, refMat2); - - m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); - if(SparseMatrixType::IsRowMajor) - refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval(); - else - refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval(); - - VERIFY_IS_APPROX(m2, refMat2); - - } - // test basic computations { - DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM2 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM3 = DenseMatrix::Zero(rows, rows); - DenseMatrix refM4 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m1(rows, rows); - SparseMatrixType m2(rows, rows); - SparseMatrixType m3(rows, rows); - SparseMatrixType m4(rows, rows); + DenseMatrix refM1 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM2 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM3 = DenseMatrix::Zero(rows, cols); + DenseMatrix refM4 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m1(rows, cols); + SparseMatrixType m2(rows, cols); + SparseMatrixType m3(rows, cols); + SparseMatrixType m4(rows, cols); initSparse(density, refM1, m1); initSparse(density, refM2, m2); initSparse(density, refM3, m3); initSparse(density, refM4, m4); + if(internal::random()) + m1.makeCompressed(); + + Index m1_nnz = m1.nonZeros(); + + VERIFY_IS_APPROX(m1*s1, refM1*s1); VERIFY_IS_APPROX(m1+m2, refM1+refM2); VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3); VERIFY_IS_APPROX(m3.cwiseProduct(m1+m2), refM3.cwiseProduct(refM1+refM2)); VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2); - - VERIFY_IS_APPROX(m1*=s1, refM1*=s1); - VERIFY_IS_APPROX(m1/=s1, refM1/=s1); - - VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); - VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); + VERIFY_IS_APPROX(m4=m1/s1, refM1/s1); + VERIFY_IS_EQUAL(m4.nonZeros(), m1_nnz); if(SparseMatrixType::IsRowMajor) VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.row(0).dot(refM2.row(0))); else - VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.col(0).dot(refM2.row(0))); - + VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.col(0)), refM1.col(0).dot(refM2.col(0))); + DenseVector rv = DenseVector::Random(m1.cols()); DenseVector cv = DenseVector::Random(m1.rows()); Index r = internal::random(0,m1.rows()-2); @@ -318,103 +194,163 @@ template void sparse_basic(const SparseMatrixType& re VERIFY_IS_APPROX(refM4.cwiseProduct(m3), refM4.cwiseProduct(refM3)); // VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4); + VERIFY_IS_APPROX(refM4 + m3, refM4 + refM3); + VERIFY_IS_APPROX(m3 + refM4, refM3 + refM4); + VERIFY_IS_APPROX(refM4 - m3, refM4 - refM3); + VERIFY_IS_APPROX(m3 - refM4, refM3 - refM4); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3.cwiseProduct(m3)).eval(), RealScalar(0.5)*refM4 + refM3.cwiseProduct(refM3)); + + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + VERIFY_IS_APPROX(((refM3+m3)+RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM3 + (refM3+refM3)); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (refM3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+refM3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3)); + + + VERIFY_IS_APPROX(m1.sum(), refM1.sum()); + + m4 = m1; refM4 = m4; + + VERIFY_IS_APPROX(m1*=s1, refM1*=s1); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + VERIFY_IS_APPROX(m1/=s1, refM1/=s1); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + + VERIFY_IS_APPROX(m1+=m2, refM1+=refM2); + VERIFY_IS_APPROX(m1-=m2, refM1-=refM2); + + if (rows>=2 && cols>=2) + { + VERIFY_RAISES_ASSERT( m1 += m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( m1 -= m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( refM1 -= m1.innerVector(0) ); + VERIFY_RAISES_ASSERT( refM1 += m1.innerVector(0) ); + m1 = m4; refM1 = refM4; + } + // test aliasing VERIFY_IS_APPROX((m1 = -m1), (refM1 = -refM1)); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 = m1.transpose()), (refM1 = refM1.transpose().eval())); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 = -m1.transpose()), (refM1 = -refM1.transpose().eval())); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; VERIFY_IS_APPROX((m1 += -m1), (refM1 += -refM1)); + VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz); + m1 = m4; refM1 = refM4; + + if(m1.isCompressed()) + { + VERIFY_IS_APPROX(m1.coeffs().sum(), m1.sum()); + m1.coeffs() += s1; + for(Index j = 0; j SpBool; + SpBool mb1 = m1.real().template cast(); + SpBool mb2 = m2.real().template cast(); + VERIFY_IS_EQUAL(mb1.template cast().sum(), refM1.real().template cast().count()); + VERIFY_IS_EQUAL((mb1 && mb2).template cast().sum(), (refM1.real().template cast() && refM2.real().template cast()).count()); + VERIFY_IS_EQUAL((mb1 || mb2).template cast().sum(), (refM1.real().template cast() || refM2.real().template cast()).count()); + SpBool mb3 = mb1 && mb2; + if(mb1.coeffs().all() && mb2.coeffs().all()) + { + VERIFY_IS_EQUAL(mb3.nonZeros(), (refM1.real().template cast() && refM2.real().template cast()).count()); + } + } + } + + // test reverse iterators + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + std::vector ref_value(m2.innerSize()); + std::vector ref_index(m2.innerSize()); + if(internal::random()) + m2.makeCompressed(); + for(Index j = 0; j(density, refMat2, m2); VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval()); VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose()); VERIFY_IS_APPROX(SparseMatrixType(m2.adjoint()), refMat2.adjoint()); - } - - - - // test generic blocks - { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); - initSparse(density, refMat2, m2); - Index j0 = internal::random(0,rows-2); - Index j1 = internal::random(0,rows-2); - Index n0 = internal::random(1,rows-(std::max)(j0,j1)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0)); - if(SparseMatrixType::IsRowMajor) - VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols), - refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols)); - else - VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0), - refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); - - Index i = internal::random(0,m2.outerSize()-1); - if(SparseMatrixType::IsRowMajor) { - m2.innerVector(i) = m2.innerVector(i) * s1; - refMat2.row(i) = refMat2.row(i) * s1; - VERIFY_IS_APPROX(m2,refMat2); - } else { - m2.innerVector(i) = m2.innerVector(i) * s1; - refMat2.col(i) = refMat2.col(i) * s1; - VERIFY_IS_APPROX(m2,refMat2); - } - - VERIFY_IS_APPROX(DenseVector(m2.col(j0)), refMat2.col(j0)); - VERIFY_IS_APPROX(m2.col(j0), refMat2.col(j0)); - - VERIFY_IS_APPROX(RowDenseVector(m2.row(j0)), refMat2.row(j0)); - VERIFY_IS_APPROX(m2.row(j0), refMat2.row(j0)); - - VERIFY_IS_APPROX(m2.block(j0,j1,n0,n0), refMat2.block(j0,j1,n0,n0)); - VERIFY_IS_APPROX((2*m2).block(j0,j1,n0,n0), (2*refMat2).block(j0,j1,n0,n0)); + // check isApprox handles opposite storage order + typename Transpose::PlainObject m3(m2); + VERIFY(m2.isApprox(m3)); } // test prune { - SparseMatrixType m2(rows, rows); - DenseMatrix refM2(rows, rows); + SparseMatrixType m2(rows, cols); + DenseMatrix refM2(rows, cols); refM2.setZero(); int countFalseNonZero = 0; int countTrueNonZero = 0; - for (Index j=0; j(0,1); - if (x<0.1) + if (x<0.1f) { // do nothing } - else if (x<0.5) + else if (x<0.5f) { countFalseNonZero++; - m2.insertBackByOuterInner(j,i) = Scalar(0); + m2.insert(i,j) = Scalar(0); } else { countTrueNonZero++; - m2.insertBackByOuterInner(j,i) = Scalar(1); - if(SparseMatrixType::IsRowMajor) - refM2(j,i) = Scalar(1); - else - refM2(i,j) = Scalar(1); + m2.insert(i,j) = Scalar(1); + refM2(i,j) = Scalar(1); } } } - m2.finalize(); + if(internal::random()) + m2.makeCompressed(); VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros()); - VERIFY_IS_APPROX(m2, refM2); + if(countTrueNonZero>0) + VERIFY_IS_APPROX(m2, refM2); m2.prune(Scalar(1)); VERIFY(countTrueNonZero==m2.nonZeros()); VERIFY_IS_APPROX(m2, refM2); @@ -422,29 +358,74 @@ template void sparse_basic(const SparseMatrixType& re // test setFromTriplets { - typedef Triplet TripletType; + typedef Triplet TripletType; std::vector triplets; - int ntriplets = rows*cols; + Index ntriplets = rows*cols; triplets.reserve(ntriplets); - DenseMatrix refMat(rows,cols); - refMat.setZero(); - for(int i=0;i(0,rows-1); - Index c = internal::random(0,cols-1); + StorageIndex r = internal::random(0,StorageIndex(rows-1)); + StorageIndex c = internal::random(0,StorageIndex(cols-1)); Scalar v = internal::random(); triplets.push_back(TripletType(r,c,v)); - refMat(r,c) += v; + refMat_sum(r,c) += v; + if(std::abs(refMat_prod(r,c))==0) + refMat_prod(r,c) = v; + else + refMat_prod(r,c) *= v; + refMat_last(r,c) = v; } SparseMatrixType m(rows,cols); m.setFromTriplets(triplets.begin(), triplets.end()); - VERIFY_IS_APPROX(m, refMat); + VERIFY_IS_APPROX(m, refMat_sum); + + m.setFromTriplets(triplets.begin(), triplets.end(), std::multiplies()); + VERIFY_IS_APPROX(m, refMat_prod); +#if (defined(__cplusplus) && __cplusplus >= 201103L) + m.setFromTriplets(triplets.begin(), triplets.end(), [] (Scalar,Scalar b) { return b; }); + VERIFY_IS_APPROX(m, refMat_last); +#endif + } + + // test Map + { + DenseMatrix refMat2(rows, cols), refMat3(rows, cols); + SparseMatrixType m2(rows, cols), m3(rows, cols); + initSparse(density, refMat2, m2); + initSparse(density, refMat3, m3); + { + Map mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + Map mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr()); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + } + { + MappedSparseMatrix mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + MappedSparseMatrix mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr()); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3); + } + + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + m2.coeffRef(i,j) = 123; + if(internal::random()) + m2.makeCompressed(); + Map mapMat2(rows, cols, m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr()); + VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(123)); + VERIFY_IS_EQUAL(mapMat2.coeff(i,j),Scalar(123)); + mapMat2.coeffRef(i,j) = -123; + VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(-123)); } // test triangularView { - DenseMatrix refMat2(rows, rows), refMat3(rows, rows); - SparseMatrixType m2(rows, rows), m3(rows, rows); + DenseMatrix refMat2(rows, cols), refMat3(rows, cols); + SparseMatrixType m2(rows, cols), m3(rows, cols); initSparse(density, refMat2, m2); refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); @@ -454,13 +435,15 @@ template void sparse_basic(const SparseMatrixType& re m3 = m2.template triangularView(); VERIFY_IS_APPROX(m3, refMat3); - refMat3 = refMat2.template triangularView(); - m3 = m2.template triangularView(); - VERIFY_IS_APPROX(m3, refMat3); + { + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); - refMat3 = refMat2.template triangularView(); - m3 = m2.template triangularView(); - VERIFY_IS_APPROX(m3, refMat3); + refMat3 = refMat2.template triangularView(); + m3 = m2.template triangularView(); + VERIFY_IS_APPROX(m3, refMat3); + } refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); @@ -469,6 +452,10 @@ template void sparse_basic(const SparseMatrixType& re refMat3 = refMat2.template triangularView(); m3 = m2.template triangularView(); VERIFY_IS_APPROX(m3, refMat3); + + // check sparse-triangular to dense + refMat3 = m2.template triangularView(); + VERIFY_IS_APPROX(refMat3, DenseMatrix(refMat2.template triangularView())); } // test selfadjointView @@ -480,6 +467,19 @@ template void sparse_basic(const SparseMatrixType& re refMat3 = refMat2.template selfadjointView(); m3 = m2.template selfadjointView(); VERIFY_IS_APPROX(m3, refMat3); + + refMat3 += refMat2.template selfadjointView(); + m3 += m2.template selfadjointView(); + VERIFY_IS_APPROX(m3, refMat3); + + refMat3 -= refMat2.template selfadjointView(); + m3 -= m2.template selfadjointView(); + VERIFY_IS_APPROX(m3, refMat3); + + // selfadjointView only works for square matrices: + SparseMatrixType m4(rows, rows+1); + VERIFY_RAISES_ASSERT(m4.template selfadjointView()); + VERIFY_RAISES_ASSERT(m4.template selfadjointView()); } // test sparseView @@ -488,28 +488,59 @@ template void sparse_basic(const SparseMatrixType& re SparseMatrixType m2(rows, rows); initSparse(density, refMat2, m2); VERIFY_IS_APPROX(m2.eval(), refMat2.sparseView().eval()); + + // sparse view on expressions: + VERIFY_IS_APPROX((s1*m2).eval(), (s1*refMat2).sparseView().eval()); + VERIFY_IS_APPROX((m2+m2).eval(), (refMat2+refMat2).sparseView().eval()); + VERIFY_IS_APPROX((m2*m2).eval(), (refMat2.lazyProduct(refMat2)).sparseView().eval()); + VERIFY_IS_APPROX((m2*m2).eval(), (refMat2*refMat2).sparseView().eval()); } // test diagonal { - DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows); - SparseMatrixType m2(rows, rows); + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); initSparse(density, refMat2, m2); VERIFY_IS_APPROX(m2.diagonal(), refMat2.diagonal().eval()); + DenseVector d = m2.diagonal(); + VERIFY_IS_APPROX(d, refMat2.diagonal().eval()); + d = m2.diagonal().array(); + VERIFY_IS_APPROX(d, refMat2.diagonal().eval()); + VERIFY_IS_APPROX(const_cast(m2).diagonal(), refMat2.diagonal().eval()); + + initSparse(density, refMat2, m2, ForceNonZeroDiag); + m2.diagonal() += refMat2.diagonal(); + refMat2.diagonal() += refMat2.diagonal(); + VERIFY_IS_APPROX(m2, refMat2); + } + + // test diagonal to sparse + { + DenseVector d = DenseVector::Random(rows); + DenseMatrix refMat2 = d.asDiagonal(); + SparseMatrixType m2(rows, rows); + m2 = d.asDiagonal(); + VERIFY_IS_APPROX(m2, refMat2); + SparseMatrixType m3(d.asDiagonal()); + VERIFY_IS_APPROX(m3, refMat2); + refMat2 += d.asDiagonal(); + m2 += d.asDiagonal(); + VERIFY_IS_APPROX(m2, refMat2); } // test conservative resize { - std::vector< std::pair > inc; - inc.push_back(std::pair(-3,-2)); - inc.push_back(std::pair(0,0)); - inc.push_back(std::pair(3,2)); - inc.push_back(std::pair(3,0)); - inc.push_back(std::pair(0,3)); + std::vector< std::pair > inc; + if(rows > 3 && cols > 2) + inc.push_back(std::pair(-3,-2)); + inc.push_back(std::pair(0,0)); + inc.push_back(std::pair(3,2)); + inc.push_back(std::pair(3,0)); + inc.push_back(std::pair(0,3)); for(size_t i = 0; i< inc.size(); i++) { - Index incRows = inc[i].first; - Index incCols = inc[i].second; + StorageIndex incRows = inc[i].first; + StorageIndex incCols = inc[i].second; SparseMatrixType m1(rows, cols); DenseMatrix refMat1 = DenseMatrix::Zero(rows, cols); initSparse(density, refMat1, m1); @@ -554,21 +585,104 @@ template void sparse_basic(const SparseMatrixType& re refMat1.setIdentity(); VERIFY_IS_APPROX(m1, refMat1); } + + // test array/vector of InnerIterator + { + typedef typename SparseMatrixType::InnerIterator IteratorType; + + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + IteratorType static_array[2]; + static_array[0] = IteratorType(m2,0); + static_array[1] = IteratorType(m2,m2.outerSize()-1); + VERIFY( static_array[0] || m2.innerVector(static_array[0].outer()).nonZeros() == 0 ); + VERIFY( static_array[1] || m2.innerVector(static_array[1].outer()).nonZeros() == 0 ); + if(static_array[0] && static_array[1]) + { + ++(static_array[1]); + static_array[1] = IteratorType(m2,0); + VERIFY( static_array[1] ); + VERIFY( static_array[1].index() == static_array[0].index() ); + VERIFY( static_array[1].outer() == static_array[0].outer() ); + VERIFY( static_array[1].value() == static_array[0].value() ); + } + + std::vector iters(2); + iters[0] = IteratorType(m2,0); + iters[1] = IteratorType(m2,m2.outerSize()-1); + } } + +template +void big_sparse_triplet(Index rows, Index cols, double density) { + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef typename SparseMatrixType::Scalar Scalar; + typedef Triplet TripletType; + std::vector triplets; + double nelements = density * rows*cols; + VERIFY(nelements>=0 && nelements < NumTraits::highest()); + Index ntriplets = Index(nelements); + triplets.reserve(ntriplets); + Scalar sum = Scalar(0); + for(Index i=0;i(0,rows-1); + Index c = internal::random(0,cols-1); + Scalar v = internal::random(); + triplets.push_back(TripletType(r,c,v)); + sum += v; + } + SparseMatrixType m(rows,cols); + m.setFromTriplets(triplets.begin(), triplets.end()); + VERIFY(m.nonZeros() <= ntriplets); + VERIFY_IS_APPROX(sum, m.sum()); +} + + void test_sparse_basic() { for(int i = 0; i < g_repeat; i++) { - int s = Eigen::internal::random(1,50); - EIGEN_UNUSED_VARIABLE(s); + int r = Eigen::internal::random(1,200), c = Eigen::internal::random(1,200); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(1, 1)) )); CALL_SUBTEST_1(( sparse_basic(SparseMatrix(8, 8)) )); - CALL_SUBTEST_2(( sparse_basic(SparseMatrix, ColMajor>(s, s)) )); - CALL_SUBTEST_2(( sparse_basic(SparseMatrix, RowMajor>(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(s, s)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, ColMajor>(r, c)) )); + CALL_SUBTEST_2(( sparse_basic(SparseMatrix, RowMajor>(r, c)) )); + CALL_SUBTEST_1(( sparse_basic(SparseMatrix(r, c)) )); + CALL_SUBTEST_5(( sparse_basic(SparseMatrix(r, c)) )); + CALL_SUBTEST_5(( sparse_basic(SparseMatrix(r, c)) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(short(s), short(s))) )); - CALL_SUBTEST_1(( sparse_basic(SparseMatrix(short(s), short(s))) )); + r = Eigen::internal::random(1,100); + c = Eigen::internal::random(1,100); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + + CALL_SUBTEST_6(( sparse_basic(SparseMatrix(short(r), short(c))) )); + CALL_SUBTEST_6(( sparse_basic(SparseMatrix(short(r), short(c))) )); } + + // Regression test for bug 900: (manually insert higher values here, if you have enough RAM): + CALL_SUBTEST_3((big_sparse_triplet >(10000, 10000, 0.125))); + CALL_SUBTEST_4((big_sparse_triplet >(10000, 10000, 0.125))); + + // Regression test for bug 1105 +#ifdef EIGEN_TEST_PART_7 + { + int n = Eigen::internal::random(200,600); + SparseMatrix,0, long> mat(n, n); + std::complex val; + + for(int i=0; i +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "sparse.h" + +template +typename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==RowMajorBit, typename T::RowXpr>::type +innervec(T& A, Index i) +{ + return A.row(i); +} + +template +typename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==0, typename T::ColXpr>::type +innervec(T& A, Index i) +{ + return A.col(i); +} + +template void sparse_block(const SparseMatrixType& ref) +{ + const Index rows = ref.rows(); + const Index cols = ref.cols(); + const Index inner = ref.innerSize(); + const Index outer = ref.outerSize(); + + typedef typename SparseMatrixType::Scalar Scalar; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + + double density = (std::max)(8./(rows*cols), 0.01); + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + typedef Matrix RowDenseVector; + typedef SparseVector SparseVectorType; + + Scalar s1 = internal::random(); + { + SparseMatrixType m(rows, cols); + DenseMatrix refMat = DenseMatrix::Zero(rows, cols); + initSparse(density, refMat, m); + + VERIFY_IS_APPROX(m, refMat); + + // test InnerIterators and Block expressions + for (int t=0; t<10; ++t) + { + Index j = internal::random(0,cols-2); + Index i = internal::random(0,rows-2); + Index w = internal::random(1,cols-j); + Index h = internal::random(1,rows-i); + + VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w)); + for(Index c=0; c(density, refMat2, m2); + Index j0 = internal::random(0,outer-1); + Index j1 = internal::random(0,outer-1); + Index r0 = internal::random(0,rows-1); + Index c0 = internal::random(0,cols-1); + + VERIFY_IS_APPROX(m2.innerVector(j0), innervec(refMat2,j0)); + VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), innervec(refMat2,j0)+innervec(refMat2,j1)); + + m2.innerVector(j0) *= Scalar(2); + innervec(refMat2,j0) *= Scalar(2); + VERIFY_IS_APPROX(m2, refMat2); + + m2.row(r0) *= Scalar(3); + refMat2.row(r0) *= Scalar(3); + VERIFY_IS_APPROX(m2, refMat2); + + m2.col(c0) *= Scalar(4); + refMat2.col(c0) *= Scalar(4); + VERIFY_IS_APPROX(m2, refMat2); + + m2.row(r0) /= Scalar(3); + refMat2.row(r0) /= Scalar(3); + VERIFY_IS_APPROX(m2, refMat2); + + m2.col(c0) /= Scalar(4); + refMat2.col(c0) /= Scalar(4); + VERIFY_IS_APPROX(m2, refMat2); + + SparseVectorType v1; + VERIFY_IS_APPROX(v1 = m2.col(c0) * 4, refMat2.col(c0)*4); + VERIFY_IS_APPROX(v1 = m2.row(r0) * 4, refMat2.row(r0).transpose()*4); + + SparseMatrixType m3(rows,cols); + m3.reserve(VectorXi::Constant(outer,int(inner/2))); + for(Index j=0; j(k+1); + for(Index j=0; j<(std::min)(outer, inner); ++j) + { + VERIFY(j==numext::real(m3.innerVector(j).nonZeros())); + if(j>0) + VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); + } + m3.makeCompressed(); + for(Index j=0; j<(std::min)(outer, inner); ++j) + { + VERIFY(j==numext::real(m3.innerVector(j).nonZeros())); + if(j>0) + VERIFY(j==numext::real(m3.innerVector(j).lastCoeff())); + } + + VERIFY(m3.innerVector(j0).nonZeros() == m3.transpose().innerVector(j0).nonZeros()); + +// m2.innerVector(j0) = 2*m2.innerVector(j1); +// refMat2.col(j0) = 2*refMat2.col(j1); +// VERIFY_IS_APPROX(m2, refMat2); + } + + // test innerVectors() + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + if(internal::random(0,1)>0.5f) m2.makeCompressed(); + Index j0 = internal::random(0,outer-2); + Index j1 = internal::random(0,outer-2); + Index n0 = internal::random(1,outer-(std::max)(j0,j1)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0)); + else + VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0), + refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); + + VERIFY_IS_APPROX(m2, refMat2); + + VERIFY(m2.innerVectors(j0,n0).nonZeros() == m2.transpose().innerVectors(j0,n0).nonZeros()); + + m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0); + if(SparseMatrixType::IsRowMajor) + refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval(); + else + refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval(); + + VERIFY_IS_APPROX(m2, refMat2); + } + + // test generic blocks + { + DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols); + SparseMatrixType m2(rows, cols); + initSparse(density, refMat2, m2); + Index j0 = internal::random(0,outer-2); + Index j1 = internal::random(0,outer-2); + Index n0 = internal::random(1,outer-(std::max)(j0,j1)); + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0)); + + if(SparseMatrixType::IsRowMajor) + VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols), + refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols)); + else + VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0), + refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0)); + + Index i = internal::random(0,m2.outerSize()-1); + if(SparseMatrixType::IsRowMajor) { + m2.innerVector(i) = m2.innerVector(i) * s1; + refMat2.row(i) = refMat2.row(i) * s1; + VERIFY_IS_APPROX(m2,refMat2); + } else { + m2.innerVector(i) = m2.innerVector(i) * s1; + refMat2.col(i) = refMat2.col(i) * s1; + VERIFY_IS_APPROX(m2,refMat2); + } + + Index r0 = internal::random(0,rows-2); + Index c0 = internal::random(0,cols-2); + Index r1 = internal::random(1,rows-r0); + Index c1 = internal::random(1,cols-c0); + + VERIFY_IS_APPROX(DenseVector(m2.col(c0)), refMat2.col(c0)); + VERIFY_IS_APPROX(m2.col(c0), refMat2.col(c0)); + + VERIFY_IS_APPROX(RowDenseVector(m2.row(r0)), refMat2.row(r0)); + VERIFY_IS_APPROX(m2.row(r0), refMat2.row(r0)); + + VERIFY_IS_APPROX(m2.block(r0,c0,r1,c1), refMat2.block(r0,c0,r1,c1)); + VERIFY_IS_APPROX((2*m2).block(r0,c0,r1,c1), (2*refMat2).block(r0,c0,r1,c1)); + + if(m2.nonZeros()>0) + { + VERIFY_IS_APPROX(m2, refMat2); + SparseMatrixType m3(rows, cols); + DenseMatrix refMat3(rows, cols); refMat3.setZero(); + Index n = internal::random(1,10); + for(Index k=0; k(0,outer-1); + Index o2 = internal::random(0,outer-1); + if(SparseMatrixType::IsRowMajor) + { + m3.innerVector(o1) = m2.row(o2); + refMat3.row(o1) = refMat2.row(o2); + } + else + { + m3.innerVector(o1) = m2.col(o2); + refMat3.col(o1) = refMat2.col(o2); + } + if(internal::random()) + m3.makeCompressed(); + } + if(m3.nonZeros()>0) + VERIFY_IS_APPROX(m3, refMat3); + } + } +} + +void test_sparse_block() +{ + for(int i = 0; i < g_repeat; i++) { + int r = Eigen::internal::random(1,200), c = Eigen::internal::random(1,200); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(1, 1)) )); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(8, 8)) )); + CALL_SUBTEST_1(( sparse_block(SparseMatrix(r, c)) )); + CALL_SUBTEST_2(( sparse_block(SparseMatrix, ColMajor>(r, c)) )); + CALL_SUBTEST_2(( sparse_block(SparseMatrix, RowMajor>(r, c)) )); + + CALL_SUBTEST_3(( sparse_block(SparseMatrix(r, c)) )); + CALL_SUBTEST_3(( sparse_block(SparseMatrix(r, c)) )); + + r = Eigen::internal::random(1,100); + c = Eigen::internal::random(1,100); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + + CALL_SUBTEST_4(( sparse_block(SparseMatrix(short(r), short(c))) )); + CALL_SUBTEST_4(( sparse_block(SparseMatrix(short(r), short(c))) )); + } +} diff --git a/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp b/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp index e4ce1d679..b82cceff8 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_permutations.cpp @@ -1,25 +1,57 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2011 Gael Guennebaud +// Copyright (C) 2011-2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +static long int nb_transposed_copies; +#define EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN {nb_transposed_copies++;} +#define VERIFY_TRANSPOSITION_COUNT(XPR,N) {\ + nb_transposed_copies = 0; \ + XPR; \ + if(nb_transposed_copies!=N) std::cerr << "nb_transposed_copies == " << nb_transposed_copies << "\n"; \ + VERIFY( (#XPR) && nb_transposed_copies==N ); \ + } + #include "sparse.h" +template +bool is_sorted(const T& mat) { + for(Index k = 0; k=it.index()) + return false; + prev = it.index(); + } + } + return true; +} + +template +typename internal::nested_eval::type eval(const T &xpr) +{ + VERIFY( int(internal::nested_eval::type::Flags&RowMajorBit) == int(internal::evaluator::Flags&RowMajorBit) ); + return xpr; +} + template void sparse_permutations(const SparseMatrixType& ref) { - typedef typename SparseMatrixType::Index Index; - const Index rows = ref.rows(); const Index cols = ref.cols(); typedef typename SparseMatrixType::Scalar Scalar; - typedef typename SparseMatrixType::Index Index; - typedef SparseMatrix OtherSparseMatrixType; + typedef typename SparseMatrixType::StorageIndex StorageIndex; + typedef SparseMatrix OtherSparseMatrixType; typedef Matrix DenseMatrix; - typedef Matrix VectorI; + typedef Matrix VectorI; +// bool IsRowMajor1 = SparseMatrixType::IsRowMajor; +// bool IsRowMajor2 = OtherSparseMatrixType::IsRowMajor; double density = (std::max)(8./(rows*cols), 0.01); @@ -44,58 +76,69 @@ template void sparse_permutations(c randomPermutationVector(pi, cols); p.indices() = pi; - res = mat*p; + VERIFY( is_sorted( ::eval(mat*p) )); + VERIFY( is_sorted( res = mat*p )); + VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p), 0); + //VERIFY_TRANSPOSITION_COUNT( res = mat*p, IsRowMajor ? 1 : 0 ); res_d = mat_d*p; VERIFY(res.isApprox(res_d) && "mat*p"); - res = p*mat; + VERIFY( is_sorted( ::eval(p*mat) )); + VERIFY( is_sorted( res = p*mat )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p*mat), 0); res_d = p*mat_d; VERIFY(res.isApprox(res_d) && "p*mat"); - res = mat*p.inverse(); + VERIFY( is_sorted( (mat*p).eval() )); + VERIFY( is_sorted( res = mat*p.inverse() )); + VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p.inverse()), 0); res_d = mat*p.inverse(); VERIFY(res.isApprox(res_d) && "mat*inv(p)"); - res = p.inverse()*mat; + VERIFY( is_sorted( (p*mat+p*mat).eval() )); + VERIFY( is_sorted( res = p.inverse()*mat )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p.inverse()*mat), 0); res_d = p.inverse()*mat_d; VERIFY(res.isApprox(res_d) && "inv(p)*mat"); - res = mat.twistedBy(p); + VERIFY( is_sorted( (p * mat * p.inverse()).eval() )); + VERIFY( is_sorted( res = mat.twistedBy(p) )); + VERIFY_TRANSPOSITION_COUNT( ::eval(p * mat * p.inverse()), 0); res_d = (p * mat_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "p*mat*inv(p)"); - res = mat.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p_null) )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); - res = mat.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p_null) )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); - res = up.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = up.template selfadjointView().twistedBy(p_null) )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); - res = lo.template selfadjointView().twistedBy(p_null); + VERIFY( is_sorted( res = lo.template selfadjointView().twistedBy(p_null) )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); - res = mat.template selfadjointView(); + VERIFY( is_sorted( res = mat.template selfadjointView() )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint upper to full"); - res = mat.template selfadjointView(); + VERIFY( is_sorted( res = mat.template selfadjointView() )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "full selfadjoint lower to full"); - res = up.template selfadjointView(); + VERIFY( is_sorted( res = up.template selfadjointView() )); res_d = up_sym_d; VERIFY(res.isApprox(res_d) && "upper selfadjoint to full"); - res = lo.template selfadjointView(); + VERIFY( is_sorted( res = lo.template selfadjointView() )); res_d = lo_sym_d; VERIFY(res.isApprox(res_d) && "lower selfadjoint full"); @@ -152,19 +195,19 @@ template void sparse_permutations(c VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to lower"); - res = mat.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p) )); res_d = (p * up_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "full selfadjoint upper twisted to full"); - res = mat.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = mat.template selfadjointView().twistedBy(p) )); res_d = (p * lo_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "full selfadjoint lower twisted to full"); - res = up.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = up.template selfadjointView().twistedBy(p) )); res_d = (p * up_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "upper selfadjoint twisted to full"); - res = lo.template selfadjointView().twistedBy(p); + VERIFY( is_sorted( res = lo.template selfadjointView().twistedBy(p) )); res_d = (p * lo_sym_d) * p.inverse(); VERIFY(res.isApprox(res_d) && "lower selfadjoint twisted to full"); } @@ -184,4 +227,10 @@ void test_sparse_permutations() CALL_SUBTEST_1(( sparse_permutations_all(s) )); CALL_SUBTEST_2(( sparse_permutations_all >(s) )); } + + VERIFY((internal::is_same,OnTheRight,false,SparseShape>::ReturnType, + internal::nested_eval,PermutationMatrix,AliasFreeProduct>,1>::type>::value)); + + VERIFY((internal::is_same,OnTheLeft,false,SparseShape>::ReturnType, + internal::nested_eval,SparseMatrix,AliasFreeProduct>,1>::type>::value)); } diff --git a/gtsam/3rdparty/Eigen/test/sparse_product.cpp b/gtsam/3rdparty/Eigen/test/sparse_product.cpp index a2ea9d5b7..197586741 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_product.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_product.cpp @@ -7,37 +7,29 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +static long int nb_temporaries; + +inline void on_temporary_creation() { + // here's a great place to set a breakpoint when debugging failures in this test! + nb_temporaries++; +} + +#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); } + #include "sparse.h" -template struct test_outer; - -template struct test_outer { - static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { - typedef typename SparseMatrixType::Index Index; - Index c = internal::random(0,m2.cols()-1); - Index c1 = internal::random(0,m2.cols()-1); - VERIFY_IS_APPROX(m4=m2.col(c)*refMat2.col(c1).transpose(), refMat4=refMat2.col(c)*refMat2.col(c1).transpose()); - VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.col(c).transpose(), refMat4=refMat2.col(c1)*refMat2.col(c).transpose()); +#define VERIFY_EVALUATION_COUNT(XPR,N) {\ + nb_temporaries = 0; \ + CALL_SUBTEST( XPR ); \ + if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ + VERIFY( (#XPR) && nb_temporaries==N ); \ } -}; -template struct test_outer { - static void run(SparseMatrixType& m2, SparseMatrixType& m4, DenseMatrix& refMat2, DenseMatrix& refMat4) { - typedef typename SparseMatrixType::Index Index; - Index r = internal::random(0,m2.rows()-1); - Index c1 = internal::random(0,m2.cols()-1); - VERIFY_IS_APPROX(m4=m2.row(r).transpose()*refMat2.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*refMat2.col(c1).transpose()); - VERIFY_IS_APPROX(m4=refMat2.col(c1)*m2.row(r), refMat4=refMat2.col(c1)*refMat2.row(r)); - } -}; -// (m2,m4,refMat2,refMat4,dv1); -// VERIFY_IS_APPROX(m4=m2.innerVector(c)*dv1.transpose(), refMat4=refMat2.colVector(c)*dv1.transpose()); -// VERIFY_IS_APPROX(m4=dv1*mcm.col(c).transpose(), refMat4=dv1*refMat2.col(c).transpose()); template void sparse_product() { - typedef typename SparseMatrixType::Index Index; + typedef typename SparseMatrixType::StorageIndex StorageIndex; Index n = 100; const Index rows = internal::random(1,n); const Index cols = internal::random(1,n); @@ -45,12 +37,12 @@ template void sparse_product() typedef typename SparseMatrixType::Scalar Scalar; enum { Flags = SparseMatrixType::Flags }; - double density = (std::max)(8./(rows*cols), 0.1); + double density = (std::max)(8./(rows*cols), 0.2); typedef Matrix DenseMatrix; typedef Matrix DenseVector; typedef Matrix RowDenseVector; - typedef SparseVector ColSpVector; - typedef SparseVector RowSpVector; + typedef SparseVector ColSpVector; + typedef SparseVector RowSpVector; Scalar s1 = internal::random(); Scalar s2 = internal::random(); @@ -93,33 +85,124 @@ template void sparse_product() VERIFY_IS_APPROX(m4 = m2*m3/s1, refMat4 = refMat2*refMat3/s1); VERIFY_IS_APPROX(m4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1); VERIFY_IS_APPROX(m4 = s2*m2*m3*s1, refMat4 = s2*refMat2*refMat3*s1); + VERIFY_IS_APPROX(m4 = (m2+m2)*m3, refMat4 = (refMat2+refMat2)*refMat3); + VERIFY_IS_APPROX(m4 = m2*m3.leftCols(cols/2), refMat4 = refMat2*refMat3.leftCols(cols/2)); + VERIFY_IS_APPROX(m4 = m2*(m3+m3).leftCols(cols/2), refMat4 = refMat2*(refMat3+refMat3).leftCols(cols/2)); VERIFY_IS_APPROX(m4=(m2*m3).pruned(0), refMat4=refMat2*refMat3); VERIFY_IS_APPROX(m4=(m2t.transpose()*m3).pruned(0), refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(m4=(m2t.transpose()*m3t.transpose()).pruned(0), refMat4=refMat2t.transpose()*refMat3t.transpose()); VERIFY_IS_APPROX(m4=(m2*m3t.transpose()).pruned(0), refMat4=refMat2*refMat3t.transpose()); + // make sure the right product implementation is called: + if((!SparseMatrixType::IsRowMajor) && m2.rows()<=m3.cols()) + { + VERIFY_EVALUATION_COUNT(m4 = m2*m3, 3); // 1 temp for the result + 2 for transposing and get a sorted result. + VERIFY_EVALUATION_COUNT(m4 = (m2*m3).pruned(0), 1); + VERIFY_EVALUATION_COUNT(m4 = (m2*m3).eval().pruned(0), 4); + } + + // and that pruning is effective: + { + DenseMatrix Ad(2,2); + Ad << -1, 1, 1, 1; + SparseMatrixType As(Ad.sparseView()), B(2,2); + VERIFY_IS_EQUAL( (As*As.transpose()).eval().nonZeros(), 4); + VERIFY_IS_EQUAL( (Ad*Ad.transpose()).eval().sparseView().eval().nonZeros(), 2); + VERIFY_IS_EQUAL( (As*As.transpose()).pruned(1e-6).eval().nonZeros(), 2); + } + + // dense ?= sparse * sparse + VERIFY_IS_APPROX(dm4 =m2*m3, refMat4 =refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=m2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=m2*m3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3, refMat4 =refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3, refMat4+=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3, refMat4-=refMat2t.transpose()*refMat3); + VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3t.transpose(), refMat4 =refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3t.transpose(), refMat4+=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3t.transpose(), refMat4-=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4 =m2*m3t.transpose(), refMat4 =refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4+=m2*m3t.transpose(), refMat4+=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4-=m2*m3t.transpose(), refMat4-=refMat2*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1); + // test aliasing m4 = m2; refMat4 = refMat2; VERIFY_IS_APPROX(m4=m4*m3, refMat4=refMat4*refMat3); - // sparse * dense + // sparse * dense matrix VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); VERIFY_IS_APPROX(dm4=m2*refMat3t.transpose(), refMat4=refMat2*refMat3t.transpose()); VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3, refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); + VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3); + VERIFY_IS_APPROX(dm4=dm4+m2*refMat3, refMat4=refMat4+refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=m2*refMat3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=m2*refMat3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()+=m2*refMat3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()-=m2*refMat3, refMat4-=refMat2*refMat3); VERIFY_IS_APPROX(dm4=m2*(refMat3+refMat3), refMat4=refMat2*(refMat3+refMat3)); VERIFY_IS_APPROX(dm4=m2t.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2t.transpose()*(refMat3+refMat5)*0.5); + + // sparse * dense vector + VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3.col(0), refMat4.col(0)=refMat2*refMat3.col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3t.transpose().col(0), refMat4.col(0)=refMat2*refMat3t.transpose().col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3.col(0), refMat4.col(0)=refMat2t.transpose()*refMat3.col(0)); + VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3t.transpose().col(0), refMat4.col(0)=refMat2t.transpose()*refMat3t.transpose().col(0)); // dense * sparse VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3); + VERIFY_IS_APPROX(dm4=dm4+refMat2*m3, refMat4=refMat4+refMat2*refMat3); + VERIFY_IS_APPROX(dm4+=refMat2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4-=refMat2*m3, refMat4-=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()+=refMat2*m3, refMat4+=refMat2*refMat3); + VERIFY_IS_APPROX(dm4.noalias()-=refMat2*m3, refMat4-=refMat2*refMat3); VERIFY_IS_APPROX(dm4=refMat2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose()); VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3); VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose()); // sparse * dense and dense * sparse outer product - test_outer::run(m2,m4,refMat2,refMat4); + { + Index c = internal::random(0,depth-1); + Index r = internal::random(0,rows-1); + Index c1 = internal::random(0,cols-1); + Index r1 = internal::random(0,depth-1); + DenseMatrix dm5 = DenseMatrix::Random(depth, cols); + + VERIFY_IS_APPROX( m4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=m2.middleCols(c,1)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose()); + + VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.middleCols(c,1).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose()); + + VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose()); + + VERIFY_IS_APPROX( m4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=m2.middleRows(r,1).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose()); + + VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.middleRows(r,1), refMat4=dm5.col(c1)*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r)); + + VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r)); + VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count()); + VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r)); + } VERIFY_IS_APPROX(m6=m6*m6, refMat6=refMat6*refMat6); @@ -131,11 +214,11 @@ template void sparse_product() RowSpVector rv0(depth), rv1; RowDenseVector drv0(depth), drv1(rv1); initSparse(2*density,drv0, rv0); - - VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3); + + VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0); VERIFY_IS_APPROX(rv1=rv0*m3, drv1=drv0*refMat3); - VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0); VERIFY_IS_APPROX(cv1=m3t.adjoint()*cv0, dcv1=refMat3t.adjoint()*dcv0); + VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3); VERIFY_IS_APPROX(rv1=m3*cv0, drv1=refMat3*dcv0); } @@ -158,12 +241,16 @@ template void sparse_product() // also check with a SparseWrapper: DenseVector v1 = DenseVector::Random(cols); DenseVector v2 = DenseVector::Random(rows); + DenseVector v3 = DenseVector::Random(rows); VERIFY_IS_APPROX(m3=m2*v1.asDiagonal(), refM3=refM2*v1.asDiagonal()); VERIFY_IS_APPROX(m3=m2.transpose()*v2.asDiagonal(), refM3=refM2.transpose()*v2.asDiagonal()); VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2, refM3=v2.asDiagonal()*refM2); VERIFY_IS_APPROX(m3=v1.asDiagonal()*m2.transpose(), refM3=v1.asDiagonal()*refM2.transpose()); VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2*v1.asDiagonal(), refM3=v2.asDiagonal()*refM2*v1.asDiagonal()); + + VERIFY_IS_APPROX(v2=m2*v1.asDiagonal()*v1, refM2*v1.asDiagonal()*v1); + VERIFY_IS_APPROX(v3=v2.asDiagonal()*m2*v1, v2.asDiagonal()*refM2*v1); // evaluate to a dense matrix to check the .row() and .col() iterator functions VERIFY_IS_APPROX(d3=m2*d1, refM3=refM2*d1); @@ -172,7 +259,7 @@ template void sparse_product() VERIFY_IS_APPROX(d3=d1*m2.transpose(), refM3=d1*refM2.transpose()); } - // test self adjoint products + // test self-adjoint and triangular-view products { DenseMatrix b = DenseMatrix::Random(rows, rows); DenseMatrix x = DenseMatrix::Random(rows, rows); @@ -180,9 +267,12 @@ template void sparse_product() DenseMatrix refUp = DenseMatrix::Zero(rows, rows); DenseMatrix refLo = DenseMatrix::Zero(rows, rows); DenseMatrix refS = DenseMatrix::Zero(rows, rows); + DenseMatrix refA = DenseMatrix::Zero(rows, rows); SparseMatrixType mUp(rows, rows); SparseMatrixType mLo(rows, rows); SparseMatrixType mS(rows, rows); + SparseMatrixType mA(rows, rows); + initSparse(density, refA, mA); do { initSparse(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular); } while (refUp.isZero()); @@ -195,26 +285,45 @@ template void sparse_product() for (int k=0; k()*b, refX=refS*b); VERIFY_IS_APPROX(x=mLo.template selfadjointView()*b, refX=refS*b); VERIFY_IS_APPROX(x=mS.template selfadjointView()*b, refX=refS*b); + + VERIFY_IS_APPROX(x=b * mUp.template selfadjointView(), refX=b*refS); + VERIFY_IS_APPROX(x=b * mLo.template selfadjointView(), refX=b*refS); + VERIFY_IS_APPROX(x=b * mS.template selfadjointView(), refX=b*refS); + + VERIFY_IS_APPROX(x.noalias()+=mUp.template selfadjointView()*b, refX+=refS*b); + VERIFY_IS_APPROX(x.noalias()-=mLo.template selfadjointView()*b, refX-=refS*b); + VERIFY_IS_APPROX(x.noalias()+=mS.template selfadjointView()*b, refX+=refS*b); - // sparse selfadjointView * sparse + // sparse selfadjointView with sparse matrices SparseMatrixType mSres(rows,rows); VERIFY_IS_APPROX(mSres = mLo.template selfadjointView()*mS, refX = refLo.template selfadjointView()*refS); - // sparse * sparse selfadjointview VERIFY_IS_APPROX(mSres = mS * mLo.template selfadjointView(), refX = refS * refLo.template selfadjointView()); + + // sparse triangularView with dense matrices + VERIFY_IS_APPROX(x=mA.template triangularView()*b, refX=refA.template triangularView()*b); + VERIFY_IS_APPROX(x=mA.template triangularView()*b, refX=refA.template triangularView()*b); + VERIFY_IS_APPROX(x=b*mA.template triangularView(), refX=b*refA.template triangularView()); + VERIFY_IS_APPROX(x=b*mA.template triangularView(), refX=b*refA.template triangularView()); + + // sparse triangularView with sparse matrices + VERIFY_IS_APPROX(mSres = mA.template triangularView()*mS, refX = refA.template triangularView()*refS); + VERIFY_IS_APPROX(mSres = mS * mA.template triangularView(), refX = refS * refA.template triangularView()); + VERIFY_IS_APPROX(mSres = mA.template triangularView()*mS, refX = refA.template triangularView()*refS); + VERIFY_IS_APPROX(mSres = mS * mA.template triangularView(), refX = refS * refA.template triangularView()); } - } // New test for Bug in SparseTimeDenseProduct @@ -239,11 +348,35 @@ template void sparse_produc VERIFY_IS_APPROX( m4(0,0), 0.0 ); } +template +void bug_942() +{ + typedef Matrix Vector; + typedef SparseMatrix ColSpMat; + typedef SparseMatrix RowSpMat; + ColSpMat cmA(1,1); + cmA.insert(0,0) = 1; + + RowSpMat rmA(1,1); + rmA.insert(0,0) = 1; + + Vector d(1); + d[0] = 2; + + double res = 2; + + VERIFY_IS_APPROX( ( cmA*d.asDiagonal() ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( d.asDiagonal()*rmA ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( rmA*d.asDiagonal() ).eval().coeff(0,0), res ); + VERIFY_IS_APPROX( ( d.asDiagonal()*cmA ).eval().coeff(0,0), res ); +} + void test_sparse_product() { for(int i = 0; i < g_repeat; i++) { CALL_SUBTEST_1( (sparse_product >()) ); CALL_SUBTEST_1( (sparse_product >()) ); + CALL_SUBTEST_1( (bug_942()) ); CALL_SUBTEST_2( (sparse_product, ColMajor > >()) ); CALL_SUBTEST_2( (sparse_product, RowMajor > >()) ); CALL_SUBTEST_3( (sparse_product >()) ); diff --git a/gtsam/3rdparty/Eigen/test/sparse_ref.cpp b/gtsam/3rdparty/Eigen/test/sparse_ref.cpp new file mode 100644 index 000000000..5e9607234 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/sparse_ref.cpp @@ -0,0 +1,139 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 20015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +#undef EIGEN_DEFAULT_TO_ROW_MAJOR +#endif + +static long int nb_temporaries; + +inline void on_temporary_creation() { + // here's a great place to set a breakpoint when debugging failures in this test! + nb_temporaries++; +} + +#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); } + +#include "main.h" +#include + +#define VERIFY_EVALUATION_COUNT(XPR,N) {\ + nb_temporaries = 0; \ + CALL_SUBTEST( XPR ); \ + if(nb_temporaries!=N) std::cerr << "nb_temporaries == " << nb_temporaries << "\n"; \ + VERIFY( (#XPR) && nb_temporaries==N ); \ + } + +template void check_const_correctness(const PlainObjectType&) +{ + // verify that ref-to-const don't have LvalueBit + typedef typename internal::add_const::type ConstPlainObjectType; + VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(internal::traits >::Flags & LvalueBit) ); + VERIFY( !(Ref::Flags & LvalueBit) ); + VERIFY( !(Ref::Flags & LvalueBit) ); +} + +template +EIGEN_DONT_INLINE void call_ref_1(Ref > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_2(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_3(const Ref, StandardCompressedFormat>& a, const B &b) { + VERIFY(a.isCompressed()); + VERIFY_IS_EQUAL(a.toDense(),b.toDense()); +} + +template +EIGEN_DONT_INLINE void call_ref_4(Ref > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +template +EIGEN_DONT_INLINE void call_ref_5(const Ref >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); } + +void call_ref() +{ + SparseMatrix A = MatrixXf::Random(10,10).sparseView(0.5,1); + SparseMatrix B = MatrixXf::Random(10,10).sparseView(0.5,1); + SparseMatrix C = MatrixXf::Random(10,10).sparseView(0.5,1); + C.reserve(VectorXi::Constant(C.outerSize(), 2)); + const SparseMatrix& Ac(A); + Block > Ab(A,0,1, 3,3); + const Block > Abc(A,0,1,3,3); + SparseVector vc = VectorXf::Random(10).sparseView(0.5,1); + SparseVector vr = VectorXf::Random(10).sparseView(0.5,1); + SparseMatrix AA = A*A; + + + VERIFY_EVALUATION_COUNT( call_ref_1(A, A), 0); +// VERIFY_EVALUATION_COUNT( call_ref_1(Ac, Ac), 0); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_2(A, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(A, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A.transpose(), A.transpose()), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(A.transpose(), A.transpose()), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(Ac,Ac), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(Ac,Ac), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A+A,2*Ac), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(A+A,2*Ac), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(B, B), 1); + VERIFY_EVALUATION_COUNT( call_ref_3(B, B), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(B.transpose(), B.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_3(B.transpose(), B.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(A*A, AA), 3); + VERIFY_EVALUATION_COUNT( call_ref_3(A*A, AA), 3); + + VERIFY(!C.isCompressed()); + VERIFY_EVALUATION_COUNT( call_ref_3(C, C), 1); + + Ref > Ar(A); + VERIFY_IS_APPROX(Ar+Ar, A+A); + VERIFY_EVALUATION_COUNT( call_ref_1(Ar, A), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(Ar, A), 0); + + Ref > Br(B); + VERIFY_EVALUATION_COUNT( call_ref_1(Br.transpose(), Br.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(Br, Br), 1); + VERIFY_EVALUATION_COUNT( call_ref_2(Br.transpose(), Br.transpose()), 0); + + Ref > Arc(A); +// VERIFY_EVALUATION_COUNT( call_ref_1(Arc, Arc), 0); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_2(Arc, Arc), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.middleCols(1,3), A.middleCols(1,3)), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.col(2), A.col(2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vr.transpose(), vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_2(vr, vr.transpose()), 0); + + VERIFY_EVALUATION_COUNT( call_ref_2(A.block(1,1,3,3), A.block(1,1,3,3)), 1); // should be 0 (allocate starts/nnz only) + + VERIFY_EVALUATION_COUNT( call_ref_4(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(vr, vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(vc, vc), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(vr, vr.transpose()), 0); + VERIFY_EVALUATION_COUNT( call_ref_4(A.col(2), A.col(2)), 0); + VERIFY_EVALUATION_COUNT( call_ref_5(A.col(2), A.col(2)), 0); + // VERIFY_EVALUATION_COUNT( call_ref_4(A.row(2), A.row(2).transpose()), 1); // does not compile on purpose + VERIFY_EVALUATION_COUNT( call_ref_5(A.row(2), A.row(2).transpose()), 1); +} + +void test_sparse_ref() +{ + for(int i = 0; i < g_repeat; i++) { + CALL_SUBTEST_1( check_const_correctness(SparseMatrix()) ); + CALL_SUBTEST_1( check_const_correctness(SparseMatrix()) ); + CALL_SUBTEST_2( call_ref() ); + + CALL_SUBTEST_3( check_const_correctness(SparseVector()) ); + CALL_SUBTEST_3( check_const_correctness(SparseVector()) ); + } +} diff --git a/gtsam/3rdparty/Eigen/test/sparse_solver.h b/gtsam/3rdparty/Eigen/test/sparse_solver.h index e1619d62a..5145bc3eb 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_solver.h +++ b/gtsam/3rdparty/Eigen/test/sparse_solver.h @@ -9,68 +9,123 @@ #include "sparse.h" #include +#include + +template +void solve_with_guess(IterativeSolverBase& solver, const MatrixBase& b, const Guess& g, Result &x) { + if(internal::random()) + { + // With a temporary through evaluator + x = solver.derived().solveWithGuess(b,g) + Result::Zero(x.rows(), x.cols()); + } + else + { + // direct evaluation within x through Assignment + x = solver.derived().solveWithGuess(b.derived(),g); + } +} + +template +void solve_with_guess(SparseSolverBase& solver, const MatrixBase& b, const Guess& , Result& x) { + if(internal::random()) + x = solver.derived().solve(b) + Result::Zero(x.rows(), x.cols()); + else + x = solver.derived().solve(b); +} + +template +void solve_with_guess(SparseSolverBase& solver, const SparseMatrixBase& b, const Guess& , Result& x) { + x = solver.derived().solve(b); +} template void check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; + typedef typename Mat::StorageIndex StorageIndex; - DenseRhs refX = dA.lu().solve(db); + DenseRhs refX = dA.householderQr().solve(db); { - Rhs x(b.rows(), b.cols()); + Rhs x(A.cols(), b.cols()); Rhs oldb = b; solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; - exit(0); - return; + std::cerr << "ERROR | sparse solver testing, factorization failed (" << typeid(Solver).name() << ")\n"; + VERIFY(solver.info() == Success); } x = solver.solve(b); if (solver.info() != Success) { - std::cerr << "sparse solver testing: solving failed\n"; + std::cerr << "WARNING | sparse solver testing: solving failed (" << typeid(Solver).name() << ")\n"; return; } VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); + + x.setZero(); + solve_with_guess(solver, b, x, x); + VERIFY(solver.info() == Success && "solving failed when using analyzePattern/factorize API"); + VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(x.isApprox(refX,test_precision())); + x.setZero(); // test the analyze/factorize API solver.analyzePattern(A); solver.factorize(A); - if (solver.info() != Success) - { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving)\n"; - exit(0); - return; - } + VERIFY(solver.info() == Success && "factorization failed when using analyzePattern/factorize API"); x = solver.solve(b); - if (solver.info() != Success) - { - std::cerr << "sparse solver testing: solving failed\n"; - return; - } + VERIFY(solver.info() == Success && "solving failed when using analyzePattern/factorize API"); VERIFY(oldb.isApprox(b) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); + + x.setZero(); + // test with Map + MappedSparseMatrix Am(A.rows(), A.cols(), A.nonZeros(), const_cast(A.outerIndexPtr()), const_cast(A.innerIndexPtr()), const_cast(A.valuePtr())); + solver.compute(Am); + VERIFY(solver.info() == Success && "factorization failed when using Map"); + DenseRhs dx(refX); + dx.setZero(); + Map xm(dx.data(), dx.rows(), dx.cols()); + Map bm(db.data(), db.rows(), db.cols()); + xm = solver.solve(bm); + VERIFY(solver.info() == Success && "solving failed when using Map"); + VERIFY(oldb.isApprox(bm) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(xm.isApprox(refX,test_precision())); } - // test dense Block as the result and rhs: - { - DenseRhs x(db.rows(), db.cols()); - DenseRhs oldb(db); - x.setZero(); - x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols())); - VERIFY(oldb.isApprox(db) && "sparse solver testing: the rhs should not be modified!"); - VERIFY(x.isApprox(refX,test_precision())); - } - // if not too large, do some extra check: if(A.rows()<2000) { + // test initialization ctor + { + Rhs x(b.rows(), b.cols()); + Solver solver2(A); + VERIFY(solver2.info() == Success); + x = solver2.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + } + + // test dense Block as the result and rhs: + { + DenseRhs x(refX.rows(), refX.cols()); + DenseRhs oldb(db); + x.setZero(); + x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols())); + VERIFY(oldb.isApprox(db) && "sparse solver testing: the rhs should not be modified!"); + VERIFY(x.isApprox(refX,test_precision())); + } + + // test uncompressed inputs + { + Mat A2 = A; + A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast().eval()); + solver.compute(A2); + Rhs x = solver.solve(b); + VERIFY(x.isApprox(refX,test_precision())); + } // test expression as input { @@ -86,41 +141,35 @@ void check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, } template -void check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const Rhs& refX) +void check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const typename Solver::MatrixType& fullA, const Rhs& refX) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; typedef typename Mat::RealScalar RealScalar; - Rhs x(b.rows(), b.cols()); - + Rhs x(A.cols(), b.cols()); + solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_solving_real_cases)\n"; - exit(0); - return; + std::cerr << "ERROR | sparse solver testing, factorization failed (" << typeid(Solver).name() << ")\n"; + VERIFY(solver.info() == Success); } x = solver.solve(b); + if (solver.info() != Success) { - std::cerr << "sparse solver testing: solving failed\n"; + std::cerr << "WARNING | sparse solver testing, solving failed (" << typeid(Solver).name() << ")\n"; return; } - RealScalar res_error; - // Compute the norm of the relative error - if(refX.size() != 0) - res_error = (refX - x).norm()/refX.norm(); - else - { - // Compute the relative residual norm - res_error = (b - A * x).norm()/b.norm(); - } - if (res_error > test_precision() ){ - std::cerr << "Test " << g_test_stack.back() << " failed in "EI_PP_MAKE_STRING(__FILE__) - << " (" << EI_PP_MAKE_STRING(__LINE__) << ")" << std::endl << std::endl; - abort(); + RealScalar res_error = (fullA*x-b).norm()/b.norm(); + VERIFY( (res_error <= test_precision() ) && "sparse solver failed without noticing it"); + + + if(refX.size() != 0 && (refX - x).norm()/refX.norm() > test_precision()) + { + std::cerr << "WARNING | found solution is different from the provided reference one\n"; } } @@ -133,7 +182,7 @@ void check_sparse_determinant(Solver& solver, const typename Solver::MatrixType& solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_determinant)\n"; + std::cerr << "WARNING | sparse solver testing: factorization failed (check_sparse_determinant)\n"; return; } @@ -150,7 +199,7 @@ void check_sparse_abs_determinant(Solver& solver, const typename Solver::MatrixT solver.compute(A); if (solver.info() != Success) { - std::cerr << "sparse solver testing: factorization failed (check_sparse_abs_determinant)\n"; + std::cerr << "WARNING | sparse solver testing: factorization failed (check_sparse_abs_determinant)\n"; return; } @@ -197,13 +246,33 @@ inline std::string get_matrixfolder() mat_folder = mat_folder + static_cast("/real/"); return mat_folder; } +std::string sym_to_string(int sym) +{ + if(sym==Symmetric) return "Symmetric "; + if(sym==SPD) return "SPD "; + return ""; +} +template +std::string solver_stats(const IterativeSolverBase &solver) +{ + std::stringstream ss; + ss << solver.iterations() << " iters, error: " << solver.error(); + return ss.str(); +} +template +std::string solver_stats(const SparseSolverBase &/*solver*/) +{ + return ""; +} #endif -template void check_sparse_spd_solving(Solver& solver) +template void check_sparse_spd_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - typedef SparseMatrix SpMat; + typedef typename Mat::StorageIndex StorageIndex; + typedef SparseMatrix SpMat; + typedef SparseVector SpVec; typedef Matrix DenseMatrix; typedef Matrix DenseVector; @@ -211,7 +280,7 @@ template void check_sparse_spd_solving(Solver& solver) Mat A, halfA; DenseMatrix dA; for (int i = 0; i < g_repeat; i++) { - int size = generate_sparse_spd_problem(solver, A, halfA, dA); + int size = generate_sparse_spd_problem(solver, A, halfA, dA, maxSize); // generate the right hand sides int rhsCols = internal::random(1,16); @@ -220,13 +289,17 @@ template void check_sparse_spd_solving(Solver& solver) DenseVector b = DenseVector::Random(size); DenseMatrix dB(size,rhsCols); initSparse(density, dB, B, ForceNonZeroDiag); + SpVec c = B.col(0); + DenseVector dc = dB.col(0); - check_sparse_solving(solver, A, b, dA, b); - check_sparse_solving(solver, halfA, b, dA, b); - check_sparse_solving(solver, A, dB, dA, dB); - check_sparse_solving(solver, halfA, dB, dA, dB); - check_sparse_solving(solver, A, B, dA, dB); - check_sparse_solving(solver, halfA, B, dA, dB); + CALL_SUBTEST( check_sparse_solving(solver, A, b, dA, b) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, b, dA, b) ); + CALL_SUBTEST( check_sparse_solving(solver, A, dB, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, dB, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, A, B, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, B, dA, dB) ); + CALL_SUBTEST( check_sparse_solving(solver, A, c, dA, dc) ); + CALL_SUBTEST( check_sparse_solving(solver, halfA, c, dA, dc) ); // check only once if(i==0) @@ -237,25 +310,44 @@ template void check_sparse_spd_solving(Solver& solver) } // First, get the folder -#ifdef TEST_REAL_CASES - if (internal::is_same::value - || internal::is_same >::value) - return ; - - std::string mat_folder = get_matrixfolder(); - MatrixMarketIterator it(mat_folder); - for (; it; ++it) +#ifdef TEST_REAL_CASES + // Test real problems with double precision only + if (internal::is_same::Real, double>::value) { - if (it.sym() == SPD){ - Mat halfA; - PermutationMatrix pnull; - halfA.template selfadjointView() = it.matrix().template triangularView().twistedBy(pnull); - - std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; - check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); - check_sparse_solving_real_cases(solver, halfA, it.rhs(), it.refX()); + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + if (it.sym() == SPD){ + A = it.matrix(); + if(A.diagonal().size() <= maxRealWorldSize) + { + DenseVector b = it.rhs(); + DenseVector refX = it.refX(); + PermutationMatrix pnull; + halfA.resize(A.rows(), A.cols()); + if(Solver::UpLo == (Lower|Upper)) + halfA = A; + else + halfA.template selfadjointView() = A.template triangularView().twistedBy(pnull); + + std::cout << "INFO | Testing " << sym_to_string(it.sym()) << "sparse problem " << it.matname() + << " (" << A.rows() << "x" << A.cols() << ") using " << typeid(Solver).name() << "..." << std::endl; + CALL_SUBTEST( check_sparse_solving_real_cases(solver, A, b, A, refX) ); + std::string stats = solver_stats(solver); + if(stats.size()>0) + std::cout << "INFO | " << stats << std::endl; + CALL_SUBTEST( check_sparse_solving_real_cases(solver, halfA, b, A, refX) ); + } + else + { + std::cout << "INFO | Skip sparse problem \"" << it.matname() << "\" (too large)" << std::endl; + } + } } } +#else + EIGEN_UNUSED_VARIABLE(maxRealWorldSize); #endif } @@ -277,37 +369,39 @@ template void check_sparse_spd_determinant(Solver& solver) } template -int generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300) +Index generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - int size = internal::random(1,maxSize); + Index size = internal::random(1,maxSize); double density = (std::max)(8./(size*size), 0.01); A.resize(size,size); dA.resize(size,size); - initSparse(density, dA, A, ForceNonZeroDiag); + initSparse(density, dA, A, options); return size; } struct prune_column { - int m_col; - prune_column(int col) : m_col(col) {} + Index m_col; + prune_column(Index col) : m_col(col) {} template - bool operator()(int, int col, const Scalar&) const { + bool operator()(Index, Index col, const Scalar&) const { return col != m_col; } }; -template void check_sparse_square_solving(Solver& solver, bool checkDeficient = false) + +template void check_sparse_square_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000, bool checkDeficient = false) { typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; - typedef SparseMatrix SpMat; + typedef SparseMatrix SpMat; + typedef SparseVector SpVec; typedef Matrix DenseMatrix; typedef Matrix DenseVector; @@ -316,7 +410,7 @@ template void check_sparse_square_solving(Solver& solver, bool Mat A; DenseMatrix dA; for (int i = 0; i < g_repeat; i++) { - int size = generate_sparse_square_problem(solver, A, dA); + Index size = generate_sparse_square_problem(solver, A, dA, maxSize); A.makeCompressed(); DenseVector b = DenseVector::Random(size); @@ -325,9 +419,12 @@ template void check_sparse_square_solving(Solver& solver, bool double density = (std::max)(8./(size*rhsCols), 0.1); initSparse(density, dB, B, ForceNonZeroDiag); B.makeCompressed(); - check_sparse_solving(solver, A, b, dA, b); - check_sparse_solving(solver, A, dB, dA, dB); - check_sparse_solving(solver, A, B, dA, dB); + SpVec c = B.col(0); + DenseVector dc = dB.col(0); + CALL_SUBTEST(check_sparse_solving(solver, A, b, dA, b)); + CALL_SUBTEST(check_sparse_solving(solver, A, dB, dA, dB)); + CALL_SUBTEST(check_sparse_solving(solver, A, B, dA, dB)); + CALL_SUBTEST(check_sparse_solving(solver, A, c, dA, dc)); // check only once if(i==0) @@ -337,7 +434,7 @@ template void check_sparse_square_solving(Solver& solver, bool } // regression test for Bug 792 (structurally rank deficient matrices): if(checkDeficient && size>1) { - int col = internal::random(0,size-1); + Index col = internal::random(0,int(size-1)); A.prune(prune_column(col)); solver.compute(A); VERIFY_IS_EQUAL(solver.info(), NumericalIssue); @@ -346,17 +443,33 @@ template void check_sparse_square_solving(Solver& solver, bool // First, get the folder #ifdef TEST_REAL_CASES - if (internal::is_same::value - || internal::is_same >::value) - return ; - - std::string mat_folder = get_matrixfolder(); - MatrixMarketIterator it(mat_folder); - for (; it; ++it) + // Test real problems with double precision only + if (internal::is_same::Real, double>::value) { - std::cout<< " ==== SOLVING WITH MATRIX " << it.matname() << " ==== \n"; - check_sparse_solving_real_cases(solver, it.matrix(), it.rhs(), it.refX()); + std::string mat_folder = get_matrixfolder(); + MatrixMarketIterator it(mat_folder); + for (; it; ++it) + { + A = it.matrix(); + if(A.diagonal().size() <= maxRealWorldSize) + { + DenseVector b = it.rhs(); + DenseVector refX = it.refX(); + std::cout << "INFO | Testing " << sym_to_string(it.sym()) << "sparse problem " << it.matname() + << " (" << A.rows() << "x" << A.cols() << ") using " << typeid(Solver).name() << "..." << std::endl; + CALL_SUBTEST(check_sparse_solving_real_cases(solver, A, b, A, refX)); + std::string stats = solver_stats(solver); + if(stats.size()>0) + std::cout << "INFO | " << stats << std::endl; + } + else + { + std::cout << "INFO | SKIP sparse problem \"" << it.matname() << "\" (too large)" << std::endl; + } + } } +#else + EIGEN_UNUSED_VARIABLE(maxRealWorldSize); #endif } @@ -366,13 +479,20 @@ template void check_sparse_square_determinant(Solver& solver) typedef typename Solver::MatrixType Mat; typedef typename Mat::Scalar Scalar; typedef Matrix DenseMatrix; - - // generate the problem - Mat A; - DenseMatrix dA; - generate_sparse_square_problem(solver, A, dA, 30); - A.makeCompressed(); + for (int i = 0; i < g_repeat; i++) { + // generate the problem + Mat A; + DenseMatrix dA; + + int size = internal::random(1,30); + dA.setRandom(size,size); + + dA = (dA.array().abs()<0.3).select(0,dA); + dA.diagonal() = (dA.diagonal().array()==0).select(1,dA.diagonal()); + A = dA.sparseView(); + A.makeCompressed(); + check_sparse_determinant(solver, A, dA); } } @@ -383,13 +503,63 @@ template void check_sparse_square_abs_determinant(Solver& solve typedef typename Mat::Scalar Scalar; typedef Matrix DenseMatrix; - // generate the problem - Mat A; - DenseMatrix dA; - generate_sparse_square_problem(solver, A, dA, 30); - A.makeCompressed(); for (int i = 0; i < g_repeat; i++) { + // generate the problem + Mat A; + DenseMatrix dA; + generate_sparse_square_problem(solver, A, dA, 30); + A.makeCompressed(); check_sparse_abs_determinant(solver, A, dA); } } +template +void generate_sparse_leastsquare_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + + int rows = internal::random(1,maxSize); + int cols = internal::random(1,rows); + double density = (std::max)(8./(rows*cols), 0.01); + + A.resize(rows,cols); + dA.resize(rows,cols); + + initSparse(density, dA, A, options); +} + +template void check_sparse_leastsquare_solving(Solver& solver) +{ + typedef typename Solver::MatrixType Mat; + typedef typename Mat::Scalar Scalar; + typedef SparseMatrix SpMat; + typedef Matrix DenseMatrix; + typedef Matrix DenseVector; + + int rhsCols = internal::random(1,16); + + Mat A; + DenseMatrix dA; + for (int i = 0; i < g_repeat; i++) { + generate_sparse_leastsquare_problem(solver, A, dA); + + A.makeCompressed(); + DenseVector b = DenseVector::Random(A.rows()); + DenseMatrix dB(A.rows(),rhsCols); + SpMat B(A.rows(),rhsCols); + double density = (std::max)(8./(A.rows()*rhsCols), 0.1); + initSparse(density, dB, B, ForceNonZeroDiag); + B.makeCompressed(); + check_sparse_solving(solver, A, b, dA, b); + check_sparse_solving(solver, A, dB, dA, dB); + check_sparse_solving(solver, A, B, dA, dB); + + // check only once + if(i==0) + { + b = DenseVector::Zero(A.rows()); + check_sparse_solving(solver, A, b, dA, b); + } + } +} diff --git a/gtsam/3rdparty/Eigen/test/sparse_vector.cpp b/gtsam/3rdparty/Eigen/test/sparse_vector.cpp index 0c9476803..b3e1dda25 100644 --- a/gtsam/3rdparty/Eigen/test/sparse_vector.cpp +++ b/gtsam/3rdparty/Eigen/test/sparse_vector.cpp @@ -9,22 +9,22 @@ #include "sparse.h" -template void sparse_vector(int rows, int cols) +template void sparse_vector(int rows, int cols) { double densityMat = (std::max)(8./(rows*cols), 0.01); - double densityVec = (std::max)(8./float(rows), 0.1); + double densityVec = (std::max)(8./(rows), 0.1); typedef Matrix DenseMatrix; typedef Matrix DenseVector; - typedef SparseVector SparseVectorType; - typedef SparseMatrix SparseMatrixType; + typedef SparseVector SparseVectorType; + typedef SparseMatrix SparseMatrixType; Scalar eps = 1e-6; SparseMatrixType m1(rows,rows); SparseVectorType v1(rows), v2(rows), v3(rows); DenseMatrix refM1 = DenseMatrix::Zero(rows, rows); DenseVector refV1 = DenseVector::Random(rows), - refV2 = DenseVector::Random(rows), - refV3 = DenseVector::Random(rows); + refV2 = DenseVector::Random(rows), + refV3 = DenseVector::Random(rows); std::vector zerocoords, nonzerocoords; initSparse(densityVec, refV1, v1, &zerocoords, &nonzerocoords); @@ -52,6 +52,20 @@ template void sparse_vector(int rows, int cols) } } VERIFY_IS_APPROX(v1, refV1); + + // test coeffRef with reallocation + { + SparseVectorType v4(rows); + DenseVector v5 = DenseVector::Zero(rows); + for(int k=0; k(0,rows-1); + Scalar v = internal::random(); + v4.coeffRef(i) += v; + v5.coeffRef(i) += v; + } + VERIFY_IS_APPROX(v4,v5); + } v1.coeffRef(nonzerocoords[0]) = Scalar(5); refV1.coeffRef(nonzerocoords[0]) = Scalar(5); @@ -71,9 +85,12 @@ template void sparse_vector(int rows, int cols) VERIFY_IS_APPROX(v1.dot(v2), refV1.dot(refV2)); VERIFY_IS_APPROX(v1.dot(refV2), refV1.dot(refV2)); + VERIFY_IS_APPROX(m1*v2, refM1*refV2); VERIFY_IS_APPROX(v1.dot(m1*v2), refV1.dot(refM1*refV2)); - int i = internal::random(0,rows-1); - VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i))); + { + int i = internal::random(0,rows-1); + VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i))); + } VERIFY_IS_APPROX(v1.squaredNorm(), refV1.squaredNorm()); @@ -96,15 +113,51 @@ template void sparse_vector(int rows, int cols) VERIFY_IS_APPROX(refV3 = v1.transpose(),v1.toDense()); VERIFY_IS_APPROX(DenseVector(v1),v1.toDense()); + // test conservative resize + { + std::vector inc; + if(rows > 3) + inc.push_back(-3); + inc.push_back(0); + inc.push_back(3); + inc.push_back(1); + inc.push_back(10); + + for(std::size_t i = 0; i< inc.size(); i++) { + StorageIndex incRows = inc[i]; + SparseVectorType vec1(rows); + DenseVector refVec1 = DenseVector::Zero(rows); + initSparse(densityVec, refVec1, vec1); + + vec1.conservativeResize(rows+incRows); + refVec1.conservativeResize(rows+incRows); + if (incRows > 0) refVec1.tail(incRows).setZero(); + + VERIFY_IS_APPROX(vec1, refVec1); + + // Insert new values + if (incRows > 0) + vec1.insert(vec1.rows()-1) = refVec1(refVec1.rows()-1) = 1; + + VERIFY_IS_APPROX(vec1, refVec1); + } + } + } void test_sparse_vector() { for(int i = 0; i < g_repeat; i++) { + int r = Eigen::internal::random(1,500), c = Eigen::internal::random(1,500); + if(Eigen::internal::random(0,4) == 0) { + r = c; // check square matrices in 25% of tries + } + EIGEN_UNUSED_VARIABLE(r+c); + CALL_SUBTEST_1(( sparse_vector(8, 8) )); - CALL_SUBTEST_2(( sparse_vector, int>(16, 16) )); - CALL_SUBTEST_1(( sparse_vector(299, 535) )); - CALL_SUBTEST_1(( sparse_vector(299, 535) )); + CALL_SUBTEST_2(( sparse_vector, int>(r, c) )); + CALL_SUBTEST_1(( sparse_vector(r, c) )); + CALL_SUBTEST_1(( sparse_vector(r, c) )); } } diff --git a/gtsam/3rdparty/Eigen/test/sparselu.cpp b/gtsam/3rdparty/Eigen/test/sparselu.cpp index b3d67aea8..bd000baf1 100644 --- a/gtsam/3rdparty/Eigen/test/sparselu.cpp +++ b/gtsam/3rdparty/Eigen/test/sparselu.cpp @@ -3,25 +3,9 @@ // // Copyright (C) 2012 Désiré Nuentsa-Wakam // -// Eigen is free software; you can redistribute it and/or -// modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation; either -// version 3 of the License, or (at your option) any later version. -// -// Alternatively, you can redistribute it and/or -// modify it under the terms of the GNU General Public License as -// published by the Free Software Foundation; either version 2 of -// the License, or (at your option) any later version. -// -// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY -// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS -// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the -// GNU General Public License for more details. -// -// You should have received a copy of the GNU Lesser General Public -// License and a copy of the GNU General Public License along with -// Eigen. If not, see . - +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. // SparseLU solve does not accept column major matrices for the destination. // However, as expected, the generic check_sparse_square_solving routines produces row-major @@ -41,9 +25,9 @@ template void test_sparselu_T() SparseLU, AMDOrdering > sparselu_amd; SparseLU, NaturalOrdering > sparselu_natural; - check_sparse_square_solving(sparselu_colamd, true); - check_sparse_square_solving(sparselu_amd, true); - check_sparse_square_solving(sparselu_natural,true); + check_sparse_square_solving(sparselu_colamd, 300, 100000, true); + check_sparse_square_solving(sparselu_amd, 300, 10000, true); + check_sparse_square_solving(sparselu_natural, 300, 2000, true); check_sparse_square_abs_determinant(sparselu_colamd); check_sparse_square_abs_determinant(sparselu_amd); diff --git a/gtsam/3rdparty/Eigen/test/sparseqr.cpp b/gtsam/3rdparty/Eigen/test/sparseqr.cpp index 451c0e7f8..e8605fd21 100644 --- a/gtsam/3rdparty/Eigen/test/sparseqr.cpp +++ b/gtsam/3rdparty/Eigen/test/sparseqr.cpp @@ -10,11 +10,12 @@ #include template -int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300) +int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150) { + eigen_assert(maxRows >= maxCols); typedef typename MatrixType::Scalar Scalar; int rows = internal::random(1,maxRows); - int cols = internal::random(1,rows); + int cols = internal::random(1,maxCols); double density = (std::max)(8./(rows*cols), 0.01); A.resize(rows,cols); @@ -53,7 +54,7 @@ template void test_sparseqr_scalar() b = dA * DenseVector::Random(A.cols()); solver.compute(A); - if(internal::random(0,1)>0.5) + if(internal::random(0,1)>0.5f) solver.factorize(A); // this checks that calling analyzePattern is not needed if the pattern do not change. if (solver.info() != Success) { @@ -88,6 +89,11 @@ template void test_sparseqr_scalar() QtQ = Q * Q.adjoint(); idM.resize(Q.rows(), Q.rows()); idM.setIdentity(); VERIFY(idM.isApprox(QtQ)); + + // Q to dense + DenseMat dQ; + dQ = solver.matrixQ(); + VERIFY_IS_APPROX(Q, dQ); } void test_sparseqr() { diff --git a/gtsam/3rdparty/Eigen/test/spqr_support.cpp b/gtsam/3rdparty/Eigen/test/spqr_support.cpp index b8980e081..81e63b6a5 100644 --- a/gtsam/3rdparty/Eigen/test/spqr_support.cpp +++ b/gtsam/3rdparty/Eigen/test/spqr_support.cpp @@ -5,6 +5,8 @@ // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed + +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse.h" #include @@ -18,8 +20,8 @@ int generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows int cols = internal::random(1,rows); double density = (std::max)(8./(rows*cols), 0.01); - A.resize(rows,rows); - dA.resize(rows,rows); + A.resize(rows,cols); + dA.resize(rows,cols); initSparse(density, dA, A,ForceNonZeroDiag); A.makeCompressed(); return rows; @@ -35,7 +37,7 @@ template void test_spqr_scalar() SPQR solver; generate_sparse_rectangular_problem(A,dA); - int m = A.rows(); + Index m = A.rows(); b = DenseVector::Random(m); solver.compute(A); if (solver.info() != Success) diff --git a/gtsam/3rdparty/Eigen/test/stable_norm.cpp b/gtsam/3rdparty/Eigen/test/stable_norm.cpp index 231dd9189..c3eb5ff31 100644 --- a/gtsam/3rdparty/Eigen/test/stable_norm.cpp +++ b/gtsam/3rdparty/Eigen/test/stable_norm.cpp @@ -1,7 +1,7 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2009 Gael Guennebaud +// Copyright (C) 2009-2014 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed @@ -9,14 +9,6 @@ #include "main.h" -// workaround aggressive optimization in ICC -template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } - -template bool isFinite(const T& x) -{ - return isNotNaN(sub(x,x)); -} - template EIGEN_DONT_INLINE T copy(const T& x) { return x; @@ -32,6 +24,8 @@ template void stable_norm(const MatrixType& m) typedef typename MatrixType::Index Index; typedef typename MatrixType::Scalar Scalar; typedef typename NumTraits::Real RealScalar; + + bool complex_real_product_ok = true; // Check the basic machine-dependent constants. { @@ -44,6 +38,16 @@ template void stable_norm(const MatrixType& m) VERIFY( (!(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5) || (it<=4 && ibeta <= 3 ) || it<2)) && "the stable norm algorithm cannot be guaranteed on this computer"); + + Scalar inf = std::numeric_limits::infinity(); + if(NumTraits::IsComplex && (numext::isnan)(inf*RealScalar(1)) ) + { + complex_real_product_ok = false; + static bool first = true; + if(first) + std::cerr << "WARNING: compiler mess up complex*real product, " << inf << " * " << 1.0 << " = " << inf*RealScalar(1) << std::endl; + first = false; + } } @@ -76,19 +80,19 @@ template void stable_norm(const MatrixType& m) RealScalar size = static_cast(m.size()); - // test isFinite - VERIFY(!isFinite( std::numeric_limits::infinity())); - VERIFY(!isFinite(sqrt(-abs(big)))); + // test numext::isfinite + VERIFY(!(numext::isfinite)( std::numeric_limits::infinity())); + VERIFY(!(numext::isfinite)(sqrt(-abs(big)))); // test overflow - VERIFY(isFinite(sqrt(size)*abs(big))); + VERIFY((numext::isfinite)(sqrt(size)*abs(big))); VERIFY_IS_NOT_APPROX(sqrt(copy(vbig.squaredNorm())), abs(sqrt(size)*big)); // here the default norm must fail VERIFY_IS_APPROX(vbig.stableNorm(), sqrt(size)*abs(big)); VERIFY_IS_APPROX(vbig.blueNorm(), sqrt(size)*abs(big)); VERIFY_IS_APPROX(vbig.hypotNorm(), sqrt(size)*abs(big)); // test underflow - VERIFY(isFinite(sqrt(size)*abs(small))); + VERIFY((numext::isfinite)(sqrt(size)*abs(small))); VERIFY_IS_NOT_APPROX(sqrt(copy(vsmall.squaredNorm())), abs(sqrt(size)*small)); // here the default norm must fail VERIFY_IS_APPROX(vsmall.stableNorm(), sqrt(size)*abs(small)); VERIFY_IS_APPROX(vsmall.blueNorm(), sqrt(size)*abs(small)); @@ -101,6 +105,79 @@ template void stable_norm(const MatrixType& m) VERIFY_IS_APPROX(vrand.rowwise().stableNorm(), vrand.rowwise().norm()); VERIFY_IS_APPROX(vrand.rowwise().blueNorm(), vrand.rowwise().norm()); VERIFY_IS_APPROX(vrand.rowwise().hypotNorm(), vrand.rowwise().norm()); + + // test NaN, +inf, -inf + MatrixType v; + Index i = internal::random(0,rows-1); + Index j = internal::random(0,cols-1); + + // NaN + { + v = vrand; + v(i,j) = std::numeric_limits::quiet_NaN(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY((numext::isnan)(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY((numext::isnan)(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); VERIFY((numext::isnan)(v.stableNorm())); + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY((numext::isnan)(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY((numext::isnan)(v.hypotNorm())); + } + + // +inf + { + v = vrand; + v(i,j) = std::numeric_limits::infinity(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY(isPlusInf(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY(isPlusInf(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); + if(complex_real_product_ok){ + VERIFY(isPlusInf(v.stableNorm())); + } + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY(isPlusInf(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY(isPlusInf(v.hypotNorm())); + } + + // -inf + { + v = vrand; + v(i,j) = -std::numeric_limits::infinity(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY(isPlusInf(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY(isPlusInf(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); + if(complex_real_product_ok) { + VERIFY(isPlusInf(v.stableNorm())); + } + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY(isPlusInf(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY(isPlusInf(v.hypotNorm())); + } + + // mix + { + Index i2 = internal::random(0,rows-1); + Index j2 = internal::random(0,cols-1); + v = vrand; + v(i,j) = -std::numeric_limits::infinity(); + v(i2,j2) = std::numeric_limits::quiet_NaN(); + VERIFY(!(numext::isfinite)(v.squaredNorm())); VERIFY((numext::isnan)(v.squaredNorm())); + VERIFY(!(numext::isfinite)(v.norm())); VERIFY((numext::isnan)(v.norm())); + VERIFY(!(numext::isfinite)(v.stableNorm())); VERIFY((numext::isnan)(v.stableNorm())); + VERIFY(!(numext::isfinite)(v.blueNorm())); VERIFY((numext::isnan)(v.blueNorm())); + VERIFY(!(numext::isfinite)(v.hypotNorm())); VERIFY((numext::isnan)(v.hypotNorm())); + } + + // stableNormalize[d] + { + VERIFY_IS_APPROX(vrand.stableNormalized(), vrand.normalized()); + MatrixType vcopy(vrand); + vcopy.stableNormalize(); + VERIFY_IS_APPROX(vcopy, vrand.normalized()); + VERIFY_IS_APPROX((vrand.stableNormalized()).norm(), RealScalar(1)); + VERIFY_IS_APPROX(vcopy.norm(), RealScalar(1)); + VERIFY_IS_APPROX((vbig.stableNormalized()).norm(), RealScalar(1)); + VERIFY_IS_APPROX((vsmall.stableNormalized()).norm(), RealScalar(1)); + RealScalar big_scaling = ((std::numeric_limits::max)() * RealScalar(1e-4)); + VERIFY_IS_APPROX(vbig/big_scaling, (vbig.stableNorm() * vbig.stableNormalized()).eval()/big_scaling); + VERIFY_IS_APPROX(vsmall, vsmall.stableNorm() * vsmall.stableNormalized()); + } } void test_stable_norm() diff --git a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_newstdvector.cpp b/gtsam/3rdparty/Eigen/test/stddeque_overload.cpp similarity index 56% rename from gtsam/3rdparty/Eigen/test/eigen2/eigen2_newstdvector.cpp rename to gtsam/3rdparty/Eigen/test/stddeque_overload.cpp index 5f9009901..4da618bbf 100644 --- a/gtsam/3rdparty/Eigen/test/eigen2/eigen2_newstdvector.cpp +++ b/gtsam/3rdparty/Eigen/test/stddeque_overload.cpp @@ -2,23 +2,36 @@ // for linear algebra. // // Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2010 Hauke Heibel // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. -#define EIGEN_USE_NEW_STDVECTOR #include "main.h" -#include + +#include #include +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Vector4f) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix2f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4d) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3f) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3d) + +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaternionf) +EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaterniond) + template -void check_stdvector_matrix(const MatrixType& m) +void check_stddeque_matrix(const MatrixType& m) { - int rows = m.rows(); - int cols = m.cols(); + typename MatrixType::Index rows = m.rows(); + typename MatrixType::Index cols = m.cols(); MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); - std::vector > v(10, MatrixType(rows,cols)), w(20, y); + std::deque v(10, MatrixType(rows,cols)), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -35,9 +48,8 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(MatrixType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) MatrixType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -49,11 +61,11 @@ void check_stdvector_matrix(const MatrixType& m) } template -void check_stdvector_transform(const TransformType&) +void check_stddeque_transform(const TransformType&) { typedef typename TransformType::MatrixType MatrixType; TransformType x(MatrixType::Random()), y(MatrixType::Random()); - std::vector > v(10), w(20, y); + std::deque v(10), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -70,9 +82,8 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(TransformType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) TransformType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -84,11 +95,11 @@ void check_stdvector_transform(const TransformType&) } template -void check_stdvector_quaternion(const QuaternionType&) +void check_stddeque_quaternion(const QuaternionType&) { typedef typename QuaternionType::Coefficients Coefficients; QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); - std::vector > v(10), w(20, y); + std::deque v(10), w(20, y); v[5] = x; w[6] = v[5]; VERIFY_IS_APPROX(w[6], v[5]); @@ -105,9 +116,8 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((std::size_t)&(v[22]) == (std::size_t)&(v[21]) + sizeof(QuaternionType)); - // do a lot of push_back such that the vector gets internally resized + // do a lot of push_back such that the deque gets internally resized // (with memory reallocation) QuaternionType* ref = &w[0]; for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i) @@ -118,32 +128,31 @@ void check_stdvector_quaternion(const QuaternionType&) } } -void test_eigen2_newstdvector() +void test_stddeque_overload() { // some non vectorizable fixed sizes - CALL_SUBTEST_1(check_stdvector_matrix(Vector2f())); - CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f())); - CALL_SUBTEST_1(check_stdvector_matrix(Matrix3d())); + CALL_SUBTEST_1(check_stddeque_matrix(Vector2f())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f())); + CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d())); // some vectorizable fixed sizes - CALL_SUBTEST_2(check_stdvector_matrix(Matrix2f())); - CALL_SUBTEST_2(check_stdvector_matrix(Vector4f())); - CALL_SUBTEST_2(check_stdvector_matrix(Matrix4f())); - CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f())); + CALL_SUBTEST_1(check_stddeque_matrix(Vector4f())); + CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f())); + CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d())); // some dynamic sizes - CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1))); - CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20))); - CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20))); - CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10))); + CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1))); + CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20))); + CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20))); + CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10))); // some Transform - CALL_SUBTEST_4(check_stdvector_transform(Transform2f())); - CALL_SUBTEST_4(check_stdvector_transform(Transform3f())); - CALL_SUBTEST_4(check_stdvector_transform(Transform3d())); - //CALL_SUBTEST(check_stdvector_transform(Transform4d())); + CALL_SUBTEST_4(check_stddeque_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9 + CALL_SUBTEST_4(check_stddeque_transform(Affine3f())); + CALL_SUBTEST_4(check_stddeque_transform(Affine3d())); // some Quaternion - CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf())); - CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond())); + CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf())); + CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond())); } diff --git a/gtsam/3rdparty/Eigen/test/stdlist_overload.cpp b/gtsam/3rdparty/Eigen/test/stdlist_overload.cpp new file mode 100644 index 000000000..bb910bd43 --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/stdlist_overload.cpp @@ -0,0 +1,192 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2010 Hauke Heibel +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#include "main.h" + +#include +#include + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Vector4f) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix2f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4d) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3f) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3d) + +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaternionf) +EIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaterniond) + +template +typename Container::iterator get(Container & c, Position position) +{ + typename Container::iterator it = c.begin(); + std::advance(it, position); + return it; +} + +template +void set(Container & c, Position position, const Value & value) +{ + typename Container::iterator it = c.begin(); + std::advance(it, position); + *it = value; +} + +template +void check_stdlist_matrix(const MatrixType& m) +{ + typename MatrixType::Index rows = m.rows(); + typename MatrixType::Index cols = m.cols(); + MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols); + std::list v(10, MatrixType(rows,cols)), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + MatrixType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; i +void check_stdlist_transform(const TransformType&) +{ + typedef typename TransformType::MatrixType MatrixType; + TransformType x(MatrixType::Random()), y(MatrixType::Random()); + std::list v(10), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + TransformType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; imatrix()==get(w, (i-23)%w.size())->matrix()); + } +} + +template +void check_stdlist_quaternion(const QuaternionType&) +{ + typedef typename QuaternionType::Coefficients Coefficients; + QuaternionType x(Coefficients::Random()), y(Coefficients::Random()); + std::list v(10), w(20, y); + typename std::list::iterator itv = get(v, 5); + typename std::list::iterator itw = get(w, 6); + *itv = x; + *itw = *itv; + VERIFY_IS_APPROX(*itw, *itv); + v = w; + itv = v.begin(); + itw = w.begin(); + for(int i = 0; i < 20; i++) + { + VERIFY_IS_APPROX(*itw, *itv); + ++itv; + ++itw; + } + + v.resize(21); + set(v, 20, x); + VERIFY_IS_APPROX(*get(v, 20), x); + v.resize(22,y); + VERIFY_IS_APPROX(*get(v, 21), y); + v.push_back(x); + VERIFY_IS_APPROX(*get(v, 22), x); + + // do a lot of push_back such that the list gets internally resized + // (with memory reallocation) + QuaternionType* ref = &(*get(w, 0)); + for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i) + v.push_back(*get(w, i%w.size())); + for(unsigned int i=23; icoeffs()==get(w, (i-23)%w.size())->coeffs()); + } +} + +void test_stdlist_overload() +{ + // some non vectorizable fixed sizes + CALL_SUBTEST_1(check_stdlist_matrix(Vector2f())); + CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f())); + CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d())); + + // some vectorizable fixed sizes + CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f())); + CALL_SUBTEST_1(check_stdlist_matrix(Vector4f())); + CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f())); + CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d())); + + // some dynamic sizes + CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1))); + CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20))); + CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20))); + CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10))); + + // some Transform + CALL_SUBTEST_4(check_stdlist_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9 + CALL_SUBTEST_4(check_stdlist_transform(Affine3f())); + CALL_SUBTEST_4(check_stdlist_transform(Affine3d())); + + // some Quaternion + CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf())); + CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond())); +} diff --git a/gtsam/3rdparty/Eigen/test/stdvector.cpp b/gtsam/3rdparty/Eigen/test/stdvector.cpp index 6e173c678..50cb3341d 100644 --- a/gtsam/3rdparty/Eigen/test/stdvector.cpp +++ b/gtsam/3rdparty/Eigen/test/stdvector.cpp @@ -34,7 +34,7 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -69,7 +69,7 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -104,7 +104,7 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) diff --git a/gtsam/3rdparty/Eigen/test/stdvector_overload.cpp b/gtsam/3rdparty/Eigen/test/stdvector_overload.cpp index 736ff0ee7..959665954 100644 --- a/gtsam/3rdparty/Eigen/test/stdvector_overload.cpp +++ b/gtsam/3rdparty/Eigen/test/stdvector_overload.cpp @@ -48,7 +48,7 @@ void check_stdvector_matrix(const MatrixType& m) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -83,7 +83,7 @@ void check_stdvector_transform(const TransformType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) @@ -118,7 +118,7 @@ void check_stdvector_quaternion(const QuaternionType&) VERIFY_IS_APPROX(v[21], y); v.push_back(x); VERIFY_IS_APPROX(v[22], x); - VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType)); + VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType)); // do a lot of push_back such that the vector gets internally resized // (with memory reallocation) diff --git a/gtsam/3rdparty/Eigen/test/superlu_support.cpp b/gtsam/3rdparty/Eigen/test/superlu_support.cpp index 3b16135bc..98a7bc5c8 100644 --- a/gtsam/3rdparty/Eigen/test/superlu_support.cpp +++ b/gtsam/3rdparty/Eigen/test/superlu_support.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include diff --git a/gtsam/3rdparty/Eigen/test/svd_common.h b/gtsam/3rdparty/Eigen/test/svd_common.h new file mode 100644 index 000000000..605d5dfef --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/svd_common.h @@ -0,0 +1,483 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2008-2014 Gael Guennebaud +// Copyright (C) 2009 Benoit Jacob +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef SVD_DEFAULT +#error a macro SVD_DEFAULT(MatrixType) must be defined prior to including svd_common.h +#endif + +#ifndef SVD_FOR_MIN_NORM +#error a macro SVD_FOR_MIN_NORM(MatrixType) must be defined prior to including svd_common.h +#endif + +#include "svd_fill.h" + +// Check that the matrix m is properly reconstructed and that the U and V factors are unitary +// The SVD must have already been computed. +template +void svd_check_full(const MatrixType& m, const SvdType& svd) +{ + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef Matrix MatrixUType; + typedef Matrix MatrixVType; + + MatrixType sigma = MatrixType::Zero(rows,cols); + sigma.diagonal() = svd.singularValues().template cast(); + MatrixUType u = svd.matrixU(); + MatrixVType v = svd.matrixV(); + RealScalar scaling = m.cwiseAbs().maxCoeff(); + if(scaling<(std::numeric_limits::min)()) + { + VERIFY(sigma.cwiseAbs().maxCoeff() <= (std::numeric_limits::min)()); + } + else + { + VERIFY_IS_APPROX(m/scaling, u * (sigma/scaling) * v.adjoint()); + } + VERIFY_IS_UNITARY(u); + VERIFY_IS_UNITARY(v); +} + +// Compare partial SVD defined by computationOptions to a full SVD referenceSvd +template +void svd_compare_to_full(const MatrixType& m, + unsigned int computationOptions, + const SvdType& referenceSvd) +{ + typedef typename MatrixType::RealScalar RealScalar; + Index rows = m.rows(); + Index cols = m.cols(); + Index diagSize = (std::min)(rows, cols); + RealScalar prec = test_precision(); + + SvdType svd(m, computationOptions); + + VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues()); + + if(computationOptions & (ComputeFullV|ComputeThinV)) + { + VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) ); + VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(), + referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint()); + } + + if(computationOptions & (ComputeFullU|ComputeThinU)) + { + VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) ); + VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(), + referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint()); + } + + // The following checks are not critical. + // For instance, with Dived&Conquer SVD, if only the factor 'V' is computedt then different matrix-matrix product implementation will be used + // and the resulting 'V' factor might be significantly different when the SVD decomposition is not unique, especially with single precision float. + ++g_test_level; + if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU()); + if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize)); + if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(svd.matrixV().cwiseAbs(), referenceSvd.matrixV().cwiseAbs()); + if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize)); + --g_test_level; +} + +// +template +void svd_least_square(const MatrixType& m, unsigned int computationOptions) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix RhsType; + typedef Matrix SolutionType; + + RhsType rhs = RhsType::Random(rows, internal::random(1, cols)); + SvdType svd(m, computationOptions); + + if(internal::is_same::value) svd.setThreshold(1e-8); + else if(internal::is_same::value) svd.setThreshold(2e-4); + + SolutionType x = svd.solve(rhs); + + RealScalar residual = (m*x-rhs).norm(); + RealScalar rhs_norm = rhs.norm(); + if(!test_isMuchSmallerThan(residual,rhs.norm())) + { + // ^^^ If the residual is very small, then we have an exact solution, so we are already good. + + // evaluate normal equation which works also for least-squares solutions + if(internal::is_same::value || svd.rank()==m.diagonal().size()) + { + using std::sqrt; + // This test is not stable with single precision. + // This is probably because squaring m signicantly affects the precision. + if(internal::is_same::value) ++g_test_level; + + VERIFY_IS_APPROX(m.adjoint()*(m*x),m.adjoint()*rhs); + + if(internal::is_same::value) --g_test_level; + } + + // Check that there is no significantly better solution in the neighborhood of x + for(Index k=0;k::epsilon())*x.row(k); + RealScalar residual_y = (m*y-rhs).norm(); + VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y ); + if(internal::is_same::value) ++g_test_level; + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + if(internal::is_same::value) --g_test_level; + + y.row(k) = (RealScalar(1)-2*NumTraits::epsilon())*x.row(k); + residual_y = (m*y-rhs).norm(); + VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y ); + if(internal::is_same::value) ++g_test_level; + VERIFY( test_isApprox(residual_y,residual) || residual < residual_y ); + if(internal::is_same::value) --g_test_level; + } + } +} + +// check minimal norm solutions, the inoput matrix m is only used to recover problem size +template +void svd_min_norm(const MatrixType& m, unsigned int computationOptions) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + Index cols = m.cols(); + + enum { + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix SolutionType; + + // generate a full-rank m x n problem with m MatrixType2; + typedef Matrix RhsType2; + typedef Matrix MatrixType2T; + Index rank = RankAtCompileTime2==Dynamic ? internal::random(1,cols) : Index(RankAtCompileTime2); + MatrixType2 m2(rank,cols); + int guard = 0; + do { + m2.setRandom(); + } while(SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision()).rank()!=rank && (++guard)<10); + VERIFY(guard<10); + + RhsType2 rhs2 = RhsType2::Random(rank); + // use QR to find a reference minimal norm solution + HouseholderQR qr(m2.adjoint()); + Matrix tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView().adjoint().solve(rhs2); + tmp.conservativeResize(cols); + tmp.tail(cols-rank).setZero(); + SolutionType x21 = qr.householderQ() * tmp; + // now check with SVD + SVD_FOR_MIN_NORM(MatrixType2) svd2(m2, computationOptions); + SolutionType x22 = svd2.solve(rhs2); + VERIFY_IS_APPROX(m2*x21, rhs2); + VERIFY_IS_APPROX(m2*x22, rhs2); + VERIFY_IS_APPROX(x21, x22); + + // Now check with a rank deficient matrix + typedef Matrix MatrixType3; + typedef Matrix RhsType3; + Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random(rank+1,2*cols) : Index(RowsAtCompileTime3); + Matrix C = Matrix::Random(rows3,rank); + MatrixType3 m3 = C * m2; + RhsType3 rhs3 = C * rhs2; + SVD_FOR_MIN_NORM(MatrixType3) svd3(m3, computationOptions); + SolutionType x3 = svd3.solve(rhs3); + VERIFY_IS_APPROX(m3*x3, rhs3); + VERIFY_IS_APPROX(m3*x21, rhs3); + VERIFY_IS_APPROX(m2*x3, rhs2); + VERIFY_IS_APPROX(x21, x3); +} + +// Check full, compare_to_full, least_square, and min_norm for all possible compute-options +template +void svd_test_all_computation_options(const MatrixType& m, bool full_only) +{ +// if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols()) +// return; + SvdType fullSvd(m, ComputeFullU|ComputeFullV); + CALL_SUBTEST(( svd_check_full(m, fullSvd) )); + CALL_SUBTEST(( svd_least_square(m, ComputeFullU | ComputeFullV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeFullV) )); + + #if defined __INTEL_COMPILER + // remark #111: statement is unreachable + #pragma warning disable 111 + #endif + if(full_only) + return; + + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, 0, fullSvd) )); + + if (MatrixType::ColsAtCompileTime == Dynamic) { + // thin U/V are only available with dynamic number of columns + CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU , fullSvd) )); + CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) )); + + CALL_SUBTEST(( svd_least_square(m, ComputeFullU | ComputeThinV) )); + CALL_SUBTEST(( svd_least_square(m, ComputeThinU | ComputeFullV) )); + CALL_SUBTEST(( svd_least_square(m, ComputeThinU | ComputeThinV) )); + + CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeThinV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeFullV) )); + CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeThinV) )); + + // test reconstruction + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(m.rows(), m.cols()); + SvdType svd(m, ComputeThinU | ComputeThinV); + VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint()); + } +} + + +// work around stupid msvc error when constructing at compile time an expression that involves +// a division by zero, even if the numeric type has floating point +template +EIGEN_DONT_INLINE Scalar zero() { return Scalar(0); } + +// workaround aggressive optimization in ICC +template EIGEN_DONT_INLINE T sub(T a, T b) { return a - b; } + +// all this function does is verify we don't iterate infinitely on nan/inf values +template +void svd_inf_nan() +{ + SvdType svd; + typedef typename MatrixType::Scalar Scalar; + Scalar some_inf = Scalar(1) / zero(); + VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf)); + svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV); + + Scalar nan = std::numeric_limits::quiet_NaN(); + VERIFY(nan != nan); + svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV); + + MatrixType m = MatrixType::Zero(10,10); + m(internal::random(0,9), internal::random(0,9)) = some_inf; + svd.compute(m, ComputeFullU | ComputeFullV); + + m = MatrixType::Zero(10,10); + m(internal::random(0,9), internal::random(0,9)) = nan; + svd.compute(m, ComputeFullU | ComputeFullV); + + // regression test for bug 791 + m.resize(3,3); + m << 0, 2*NumTraits::epsilon(), 0.5, + 0, -0.5, 0, + nan, 0, 0; + svd.compute(m, ComputeFullU | ComputeFullV); + + m.resize(4,4); + m << 1, 0, 0, 0, + 0, 3, 1, 2e-308, + 1, 0, 1, nan, + 0, nan, nan, 0; + svd.compute(m, ComputeFullU | ComputeFullV); +} + +// Regression test for bug 286: JacobiSVD loops indefinitely with some +// matrices containing denormal numbers. +template +void svd_underoverflow() +{ +#if defined __INTEL_COMPILER +// shut up warning #239: floating point underflow +#pragma warning push +#pragma warning disable 239 +#endif + Matrix2d M; + M << -7.90884e-313, -4.94e-324, + 0, 5.60844e-313; + SVD_DEFAULT(Matrix2d) svd; + svd.compute(M,ComputeFullU|ComputeFullV); + CALL_SUBTEST( svd_check_full(M,svd) ); + + // Check all 2x2 matrices made with the following coefficients: + VectorXd value_set(9); + value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223; + Array4i id(0,0,0,0); + int k = 0; + do + { + M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3)); + svd.compute(M,ComputeFullU|ComputeFullV); + CALL_SUBTEST( svd_check_full(M,svd) ); + + id(k)++; + if(id(k)>=value_set.size()) + { + while(k<3 && id(k)>=value_set.size()) id(++k)++; + id.head(k).setZero(); + k=0; + } + + } while((id +void svd_all_trivial_2x2( void (*cb)(const MatrixType&,bool) ) +{ + MatrixType M; + VectorXd value_set(3); + value_set << 0, 1, -1; + Array4i id(0,0,0,0); + int k = 0; + do + { + M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3)); + + cb(M,false); + + id(k)++; + if(id(k)>=value_set.size()) + { + while(k<3 && id(k)>=value_set.size()) id(++k)++; + id.head(k).setZero(); + k=0; + } + + } while((id +void svd_preallocate() +{ + Vector3f v(3.f, 2.f, 1.f); + MatrixXf m = v.asDiagonal(); + + internal::set_is_malloc_allowed(false); + VERIFY_RAISES_ASSERT(VectorXf tmp(10);) + SVD_DEFAULT(MatrixXf) svd; + internal::set_is_malloc_allowed(true); + svd.compute(m); + VERIFY_IS_APPROX(svd.singularValues(), v); + + SVD_DEFAULT(MatrixXf) svd2(3,3); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + VERIFY_IS_APPROX(svd2.singularValues(), v); + VERIFY_RAISES_ASSERT(svd2.matrixU()); + VERIFY_RAISES_ASSERT(svd2.matrixV()); + svd2.compute(m, ComputeFullU | ComputeFullV); + VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); + VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + + SVD_DEFAULT(MatrixXf) svd3(3,3,ComputeFullU|ComputeFullV); + internal::set_is_malloc_allowed(false); + svd2.compute(m); + internal::set_is_malloc_allowed(true); + VERIFY_IS_APPROX(svd2.singularValues(), v); + VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity()); + VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity()); + internal::set_is_malloc_allowed(false); + svd2.compute(m, ComputeFullU|ComputeFullV); + internal::set_is_malloc_allowed(true); +} + +template +void svd_verify_assert(const MatrixType& m) +{ + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::Index Index; + Index rows = m.rows(); + Index cols = m.cols(); + + enum { + RowsAtCompileTime = MatrixType::RowsAtCompileTime, + ColsAtCompileTime = MatrixType::ColsAtCompileTime + }; + + typedef Matrix RhsType; + RhsType rhs(rows); + SvdType svd; + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.singularValues()) + VERIFY_RAISES_ASSERT(svd.matrixV()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + MatrixType a = MatrixType::Zero(rows, cols); + a.setZero(); + svd.compute(a, 0); + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.matrixV()) + svd.singularValues(); + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + + if (ColsAtCompileTime == Dynamic) + { + svd.compute(a, ComputeThinU); + svd.matrixU(); + VERIFY_RAISES_ASSERT(svd.matrixV()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + svd.compute(a, ComputeThinV); + svd.matrixV(); + VERIFY_RAISES_ASSERT(svd.matrixU()) + VERIFY_RAISES_ASSERT(svd.solve(rhs)) + } + else + { + VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU)) + VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV)) + } +} + +#undef SVD_DEFAULT +#undef SVD_FOR_MIN_NORM diff --git a/gtsam/3rdparty/Eigen/test/svd_fill.h b/gtsam/3rdparty/Eigen/test/svd_fill.h new file mode 100644 index 000000000..3877c0c7e --- /dev/null +++ b/gtsam/3rdparty/Eigen/test/svd_fill.h @@ -0,0 +1,119 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014-2015 Gael Guennebaud +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +template +Array four_denorms(); + +template<> +Array4f four_denorms() { return Array4f(5.60844e-39f, -5.60844e-39f, 4.94e-44f, -4.94e-44f); } +template<> +Array4d four_denorms() { return Array4d(5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324); } +template +Array four_denorms() { return four_denorms().cast(); } + +template +void svd_fill_random(MatrixType &m, int Option = 0) +{ + using std::pow; + typedef typename MatrixType::Scalar Scalar; + typedef typename MatrixType::RealScalar RealScalar; + typedef typename MatrixType::Index Index; + Index diagSize = (std::min)(m.rows(), m.cols()); + RealScalar s = std::numeric_limits::max_exponent10/4; + s = internal::random(1,s); + Matrix d = Matrix::Random(diagSize); + for(Index k=0; k(-s,s)); + + bool dup = internal::random(0,10) < 3; + bool unit_uv = internal::random(0,10) < (dup?7:3); // if we duplicate some diagonal entries, then increase the chance to preserve them using unitary U and V factors + + // duplicate some singular values + if(dup) + { + Index n = internal::random(0,d.size()-1); + for(Index i=0; i(0,d.size()-1)) = d(internal::random(0,d.size()-1)); + } + + Matrix U(m.rows(),diagSize); + Matrix VT(diagSize,m.cols()); + if(unit_uv) + { + // in very rare cases let's try with a pure diagonal matrix + if(internal::random(0,10) < 1) + { + U.setIdentity(); + VT.setIdentity(); + } + else + { + createRandomPIMatrixOfRank(diagSize,U.rows(), U.cols(), U); + createRandomPIMatrixOfRank(diagSize,VT.rows(), VT.cols(), VT); + } + } + else + { + U.setRandom(); + VT.setRandom(); + } + + Matrix samples(9); + samples << 0, four_denorms(), + -RealScalar(1)/NumTraits::highest(), RealScalar(1)/NumTraits::highest(), (std::numeric_limits::min)(), pow((std::numeric_limits::min)(),0.8); + + if(Option==Symmetric) + { + m = U * d.asDiagonal() * U.transpose(); + + // randomly nullify some rows/columns + { + Index count = internal::random(-diagSize,diagSize); + for(Index k=0; k(0,diagSize-1); + m.row(i).setZero(); + m.col(i).setZero(); + } + if(count<0) + // (partly) cancel some coeffs + if(!(dup && unit_uv)) + { + + Index n = internal::random(0,m.size()-1); + for(Index k=0; k(0,m.rows()-1); + Index j = internal::random(0,m.cols()-1); + m(j,i) = m(i,j) = samples(internal::random(0,samples.size()-1)); + if(NumTraits::IsComplex) + *(&numext::real_ref(m(j,i))+1) = *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random(0,samples.size()-1)); + } + } + } + } + else + { + m = U * d.asDiagonal() * VT; + // (partly) cancel some coeffs + if(!(dup && unit_uv)) + { + Index n = internal::random(0,m.size()-1); + for(Index k=0; k(0,m.rows()-1); + Index j = internal::random(0,m.cols()-1); + m(i,j) = samples(internal::random(0,samples.size()-1)); + if(NumTraits::IsComplex) + *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random(0,samples.size()-1)); + } + } + } +} + diff --git a/gtsam/3rdparty/Eigen/test/swap.cpp b/gtsam/3rdparty/Eigen/test/swap.cpp index 36b353148..f76e3624d 100644 --- a/gtsam/3rdparty/Eigen/test/swap.cpp +++ b/gtsam/3rdparty/Eigen/test/swap.cpp @@ -41,9 +41,15 @@ template void swap(const MatrixType& m) OtherMatrixType m3_copy = m3; // test swapping 2 matrices of same type + Scalar *d1=m1.data(), *d2=m2.data(); m1.swap(m2); VERIFY_IS_APPROX(m1,m2_copy); VERIFY_IS_APPROX(m2,m1_copy); + if(MatrixType::SizeAtCompileTime==Dynamic) + { + VERIFY(m1.data()==d2); + VERIFY(m2.data()==d1); + } m1 = m1_copy; m2 = m2_copy; @@ -68,16 +74,21 @@ template void swap(const MatrixType& m) m1 = m1_copy; m3 = m3_copy; - // test assertion on mismatching size -- matrix case - VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); - // test assertion on mismatching size -- xpr case - VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); + if(m1.rows()>1) + { + // test assertion on mismatching size -- matrix case + VERIFY_RAISES_ASSERT(m1.swap(m1.row(0))); + // test assertion on mismatching size -- xpr case + VERIFY_RAISES_ASSERT(m1.row(0).swap(m1)); + } } void test_swap() { + int s = internal::random(1,EIGEN_TEST_MAX_SIZE); CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization CALL_SUBTEST_2( swap(Matrix4d()) ); // fixed size, possible vectorization - CALL_SUBTEST_3( swap(MatrixXd(3,3)) ); // dyn size, no vectorization - CALL_SUBTEST_4( swap(MatrixXf(30,30)) ); // dyn size, possible vectorization + CALL_SUBTEST_3( swap(MatrixXd(s,s)) ); // dyn size, no vectorization + CALL_SUBTEST_4( swap(MatrixXf(s,s)) ); // dyn size, possible vectorization + TEST_SET_BUT_UNUSED_VARIABLE(s) } diff --git a/gtsam/3rdparty/Eigen/test/testsuite.cmake b/gtsam/3rdparty/Eigen/test/testsuite.cmake deleted file mode 100644 index 3bec56b3f..000000000 --- a/gtsam/3rdparty/Eigen/test/testsuite.cmake +++ /dev/null @@ -1,229 +0,0 @@ - -#################################################################### -# -# Usage: -# - create a new folder, let's call it cdash -# - in that folder, do: -# ctest -S path/to/eigen/test/testsuite.cmake[,option1=value1[,option2=value2]] -# -# Options: -# - EIGEN_CXX: compiler, eg.: g++-4.2 -# default: default c++ compiler -# - EIGEN_SITE: eg, INRIA-Bdx_pc-gael, or the name of the contributor, etc. -# default: hostname -# - EIGEN_BUILD_STRING: a string which identify the system/compiler. It should be formed like that: -# --- -# with: -# = opensuse, debian, osx, windows, cygwin, freebsd, solaris, etc. -# = 11.1, XP, vista, leopard, etc. -# = i386, x86_64, ia64, powerpc, etc. -# = gcc-4.3.2, icc-11.0, MSVC-2008, etc. -# - EIGEN_EXPLICIT_VECTORIZATION: novec, SSE2, Altivec -# default: SSE2 for x86_64 systems, novec otherwise -# Its value is automatically appended to EIGEN_BUILD_STRING -# - EIGEN_CMAKE_DIR: path to cmake executable -# - EIGEN_MODE: dashboard model, can be Experimental, Nightly, or Continuous -# default: Nightly -# - EIGEN_WORK_DIR: directory used to download the source files and make the builds -# default: folder which contains this script -# - EIGEN_CMAKE_ARGS: additional arguments passed to cmake -# - EIGEN_GENERATOR_TYPE: allows to overwrite the generator type -# default: nmake (windows -# See http://www.cmake.org/cmake/help/cmake2.6docs.html#section_Generators for a complete -# list of supported generators. -# - EIGEN_NO_UPDATE: allows to submit dash boards from local repositories -# This might be interesting in case you want to submit dashboards -# including local changes. -# - CTEST_SOURCE_DIRECTORY: path to eigen's src (use a new and empty folder, not the one you are working on) -# default: /src -# - CTEST_BINARY_DIRECTORY: build directory -# default: /nightly- -# -# Here is an example running several compilers on a linux system: -# #!/bin/bash -# ARCH=`uname -m` -# SITE=`hostname` -# VERSION=opensuse-11.1 -# WORK_DIR=/home/gael/Coding/eigen/cdash -# # get the last version of the script -# wget http://bitbucket.org/eigen/eigen/raw/tip/test/testsuite.cmake -o $WORK_DIR/testsuite.cmake -# COMMON="ctest -S $WORK_DIR/testsuite.cmake,EIGEN_WORK_DIR=$WORK_DIR,EIGEN_SITE=$SITE,EIGEN_MODE=$1,EIGEN_BUILD_STRING=$OS_VERSION-$ARCH" -# $COMMON-gcc-3.4.6,EIGEN_CXX=g++-3.4 -# $COMMON-gcc-4.0.1,EIGEN_CXX=g++-4.0.1 -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=novec -# $COMMON-gcc-4.3.2,EIGEN_CXX=g++-4.3,EIGEN_EXPLICIT_VECTORIZATION=SSE2 -# $COMMON-icc-11.0,EIGEN_CXX=icpc -# -#################################################################### - -# process the arguments - -set(ARGLIST ${CTEST_SCRIPT_ARG}) -while(${ARGLIST} MATCHES ".+.*") - - # pick first - string(REGEX MATCH "([^,]*)(,.*)?" DUMMY ${ARGLIST}) - SET(TOP ${CMAKE_MATCH_1}) - - # remove first - string(REGEX MATCHALL "[^,]*,(.*)" DUMMY ${ARGLIST}) - SET(ARGLIST ${CMAKE_MATCH_1}) - - # decompose as a pair key=value - string(REGEX MATCH "([^=]*)(=.*)?" DUMMY ${TOP}) - SET(KEY ${CMAKE_MATCH_1}) - - string(REGEX MATCH "[^=]*=(.*)" DUMMY ${TOP}) - SET(VALUE ${CMAKE_MATCH_1}) - - # set the variable to the specified value - if(VALUE) - SET(${KEY} ${VALUE}) - else(VALUE) - SET(${KEY} ON) - endif(VALUE) - -endwhile(${ARGLIST} MATCHES ".+.*") - -#################################################################### -# Automatically set some user variables if they have not been defined manually -#################################################################### -cmake_minimum_required(VERSION 2.6 FATAL_ERROR) - -if(NOT EIGEN_SITE) - site_name(EIGEN_SITE) -endif(NOT EIGEN_SITE) - -if(NOT EIGEN_CMAKE_DIR) - SET(EIGEN_CMAKE_DIR "") -endif(NOT EIGEN_CMAKE_DIR) - -if(NOT EIGEN_BUILD_STRING) - - # let's try to find all information we need to make the build string ourself - - # OS - build_name(EIGEN_OS_VERSION) - - # arch - set(EIGEN_ARCH ${CMAKE_SYSTEM_PROCESSOR}) - if(WIN32) - set(EIGEN_ARCH $ENV{PROCESSOR_ARCHITECTURE}) - else(WIN32) - execute_process(COMMAND uname -m OUTPUT_VARIABLE EIGEN_ARCH OUTPUT_STRIP_TRAILING_WHITESPACE) - endif(WIN32) - - set(EIGEN_BUILD_STRING ${EIGEN_OS_VERSION}${EIGEN_ARCH}-${EIGEN_CXX}) - -endif(NOT EIGEN_BUILD_STRING) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - set(EIGEN_BUILD_STRING ${EIGEN_BUILD_STRING}-${EIGEN_EXPLICIT_VECTORIZATION}) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(NOT EIGEN_WORK_DIR) - set(EIGEN_WORK_DIR ${CTEST_SCRIPT_DIRECTORY}) -endif(NOT EIGEN_WORK_DIR) - -if(NOT CTEST_SOURCE_DIRECTORY) - SET (CTEST_SOURCE_DIRECTORY "${EIGEN_WORK_DIR}/src") -endif(NOT CTEST_SOURCE_DIRECTORY) - -if(NOT CTEST_BINARY_DIRECTORY) - SET (CTEST_BINARY_DIRECTORY "${EIGEN_WORK_DIR}/nightly_${EIGEN_CXX}") -endif(NOT CTEST_BINARY_DIRECTORY) - -if(NOT EIGEN_MODE) - set(EIGEN_MODE Nightly) -endif(NOT EIGEN_MODE) - -## mandatory variables (the default should be ok in most cases): - -if(NOT EIGEN_NO_UPDATE) - SET (CTEST_CVS_COMMAND "hg") - SET (CTEST_CVS_CHECKOUT "${CTEST_CVS_COMMAND} clone http://bitbucket.org/eigen/eigen \"${CTEST_SOURCE_DIRECTORY}\"") - SET(CTEST_BACKUP_AND_RESTORE TRUE) # the backup is CVS related ... -endif(NOT EIGEN_NO_UPDATE) - -# which ctest command to use for running the dashboard -SET (CTEST_COMMAND "${EIGEN_CMAKE_DIR}ctest -D ${EIGEN_MODE} --no-compress-output") -if($ENV{EIGEN_CTEST_ARGS}) -SET (CTEST_COMMAND "${CTEST_COMMAND} $ENV{EIGEN_CTEST_ARGS}") -endif($ENV{EIGEN_CTEST_ARGS}) -# what cmake command to use for configuring this dashboard -SET (CTEST_CMAKE_COMMAND "${EIGEN_CMAKE_DIR}cmake -DEIGEN_LEAVE_TEST_IN_ALL_TARGET=ON") - -#################################################################### -# The values in this section are optional you can either -# have them or leave them commented out -#################################################################### - -# this make sure we get consistent outputs -SET($ENV{LC_MESSAGES} "en_EN") - -# should ctest wipe the binary tree before running -SET(CTEST_START_WITH_EMPTY_BINARY_DIRECTORY TRUE) - -# raise the warning/error limit -set(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_WARNINGS "33331") -set(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_ERRORS "33331") - -# this is the initial cache to use for the binary tree, be careful to escape -# any quotes inside of this string if you use it -if(WIN32 AND NOT UNIX) - #message(SEND_ERROR "win32") - if(EIGEN_GENERATOR_TYPE) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"${EIGEN_GENERATOR_TYPE}\"") - SET (CTEST_INITIAL_CACHE " - CMAKE_BUILD_TYPE:STRING=Release - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") - else(EIGEN_GENERATOR_TYPE) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -G \"NMake Makefiles\" -DCMAKE_MAKE_PROGRAM=nmake") - SET (CTEST_INITIAL_CACHE " - MAKECOMMAND:STRING=nmake /i - CMAKE_MAKE_PROGRAM:FILEPATH=nmake - CMAKE_GENERATOR:INTERNAL=NMake Makefiles - CMAKE_BUILD_TYPE:STRING=Release - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") - endif(EIGEN_GENERATOR_TYPE) -else(WIN32 AND NOT UNIX) - SET (CTEST_INITIAL_CACHE " - BUILDNAME:STRING=${EIGEN_BUILD_STRING} - SITE:STRING=${EIGEN_SITE} - ") -endif(WIN32 AND NOT UNIX) - -# set any extra environment variables to use during the execution of the script here: -# setting this variable on windows machines causes trouble ... - -if(EIGEN_CXX AND NOT WIN32) - set(CTEST_ENVIRONMENT "CXX=${EIGEN_CXX}") -endif(EIGEN_CXX AND NOT WIN32) - -if(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - if(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSSE3) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE4_1) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON -DEIGEN_TEST_SSE4_1=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE4_2) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_SSE2=ON -DEIGEN_TEST_SSE3=ON -DEIGEN_TEST_SSSE3=ON -DEIGEN_TEST_SSE4_1=ON -DEIGEN_TEST_SSE4_2=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES Altivec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_ALTIVEC=ON") - elseif(EIGEN_EXPLICIT_VECTORIZATION MATCHES novec) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} -DEIGEN_TEST_NO_EXPLICIT_VECTORIZATION=ON") - else(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) - message(FATAL_ERROR "Invalid value for EIGEN_EXPLICIT_VECTORIZATION (${EIGEN_EXPLICIT_VECTORIZATION}), must be: novec, SSE2, SSE3, Altivec") - endif(EIGEN_EXPLICIT_VECTORIZATION MATCHES SSE2) -endif(DEFINED EIGEN_EXPLICIT_VECTORIZATION) - -if(DEFINED EIGEN_CMAKE_ARGS) - set(CTEST_CMAKE_COMMAND "${CTEST_CMAKE_COMMAND} ${EIGEN_CMAKE_ARGS}") -endif(DEFINED EIGEN_CMAKE_ARGS) diff --git a/gtsam/3rdparty/Eigen/test/triangular.cpp b/gtsam/3rdparty/Eigen/test/triangular.cpp index 54320390b..b96856486 100644 --- a/gtsam/3rdparty/Eigen/test/triangular.cpp +++ b/gtsam/3rdparty/Eigen/test/triangular.cpp @@ -65,7 +65,7 @@ template void triangular_square(const MatrixType& m) m1 = MatrixType::Random(rows, cols); for (int i=0; i(); + while (numext::abs2(m1(i,i))(); Transpose trm4(m4); // test back and forward subsitution with a vector as the rhs @@ -78,7 +78,7 @@ template void triangular_square(const MatrixType& m) m3 = m1.template triangularView(); VERIFY(v2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView().solve(v2)), largerEps)); - // test back and forward subsitution with a matrix as the rhs + // test back and forward substitution with a matrix as the rhs m3 = m1.template triangularView(); VERIFY(m2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView().solve(m2)), largerEps)); m3 = m1.template triangularView(); @@ -113,6 +113,21 @@ template void triangular_square(const MatrixType& m) m3.setZero(); m3.template triangularView().setOnes(); VERIFY_IS_APPROX(m2,m3); + + m1.setRandom(); + m3 = m1.template triangularView(); + Matrix m5(cols, internal::random(1,20)); m5.setRandom(); + Matrix m6(internal::random(1,20), rows); m6.setRandom(); + VERIFY_IS_APPROX(m1.template triangularView() * m5, m3*m5); + VERIFY_IS_APPROX(m6*m1.template triangularView(), m6*m3); + + m1up = m1.template triangularView(); + VERIFY_IS_APPROX(m1.template selfadjointView().template triangularView().toDenseMatrix(), m1up); + VERIFY_IS_APPROX(m1up.template selfadjointView().template triangularView().toDenseMatrix(), m1up); + VERIFY_IS_APPROX(m1.template selfadjointView().template triangularView().toDenseMatrix(), m1up.adjoint()); + VERIFY_IS_APPROX(m1up.template selfadjointView().template triangularView().toDenseMatrix(), m1up.adjoint()); + + VERIFY_IS_APPROX(m1.template selfadjointView().diagonal(), m1.diagonal()); } diff --git a/gtsam/3rdparty/Eigen/test/umfpack_support.cpp b/gtsam/3rdparty/Eigen/test/umfpack_support.cpp index 9eb84c14b..37ab11f0b 100644 --- a/gtsam/3rdparty/Eigen/test/umfpack_support.cpp +++ b/gtsam/3rdparty/Eigen/test/umfpack_support.cpp @@ -7,6 +7,7 @@ // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS #include "sparse_solver.h" #include diff --git a/gtsam/3rdparty/Eigen/test/unalignedassert.cpp b/gtsam/3rdparty/Eigen/test/unalignedassert.cpp index 601dbf214..731a08977 100644 --- a/gtsam/3rdparty/Eigen/test/unalignedassert.cpp +++ b/gtsam/3rdparty/Eigen/test/unalignedassert.cpp @@ -2,13 +2,39 @@ // for linear algebra. // // Copyright (C) 2008 Benoit Jacob +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#if defined(EIGEN_TEST_PART_1) + // default +#elif defined(EIGEN_TEST_PART_2) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 16 + #define EIGEN_MAX_ALIGN_BYTES 16 +#elif defined(EIGEN_TEST_PART_3) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 32 + #define EIGEN_MAX_ALIGN_BYTES 32 +#elif defined(EIGEN_TEST_PART_4) + #define EIGEN_MAX_STATIC_ALIGN_BYTES 64 + #define EIGEN_MAX_ALIGN_BYTES 64 +#endif + #include "main.h" +typedef Matrix Vector6f; +typedef Matrix Vector8f; +typedef Matrix Vector12f; + +typedef Matrix Vector5d; +typedef Matrix Vector6d; +typedef Matrix Vector7d; +typedef Matrix Vector8d; +typedef Matrix Vector9d; +typedef Matrix Vector10d; +typedef Matrix Vector12d; + struct TestNew1 { MatrixXd m; // good: m will allocate its own array, taking care of alignment. @@ -36,7 +62,7 @@ struct TestNew4 struct TestNew5 { EIGEN_MAKE_ALIGNED_OPERATOR_NEW - float f; // try the f at first -- the EIGEN_ALIGN16 attribute of m should make that still work + float f; // try the f at first -- the EIGEN_ALIGN_MAX attribute of m should make that still work Matrix4f m; }; @@ -63,13 +89,13 @@ void check_unalignedassert_good() delete[] y; } -#if EIGEN_ALIGN_STATICALLY +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 template void construct_at_boundary(int boundary) { char buf[sizeof(T)+256]; - size_t _buf = reinterpret_cast(buf); - _buf += (16 - (_buf % 16)); // make 16-byte aligned + size_t _buf = reinterpret_cast(buf); + _buf += (EIGEN_MAX_ALIGN_BYTES - (_buf % EIGEN_MAX_ALIGN_BYTES)); // make 16/32/...-byte aligned _buf += boundary; // make exact boundary-aligned T *x = ::new(reinterpret_cast(_buf)) T; x[0].setZero(); // just in order to silence warnings @@ -79,26 +105,36 @@ void construct_at_boundary(int boundary) void unalignedassert() { - #if EIGEN_ALIGN_STATICALLY +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 construct_at_boundary(4); construct_at_boundary(4); construct_at_boundary(16); + construct_at_boundary(4); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(16); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(4); + construct_at_boundary(16); + construct_at_boundary(4); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(4); + construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); construct_at_boundary(4); - construct_at_boundary(16); + construct_at_boundary(EIGEN_MAX_ALIGN_BYTES); construct_at_boundary(16); - #endif +#endif check_unalignedassert_good(); check_unalignedassert_good(); @@ -109,15 +145,32 @@ void unalignedassert() check_unalignedassert_good(); check_unalignedassert_good >(); -#if EIGEN_ALIGN_STATICALLY - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); - VERIFY_RAISES_ASSERT(construct_at_boundary(8)); +#if EIGEN_MAX_STATIC_ALIGN_BYTES>0 + if(EIGEN_MAX_ALIGN_BYTES>=16) + { + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + // Complexes are disabled because the compiler might aggressively vectorize + // the initialization of complex coeffs to 0 before we can check for alignedness + //VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + VERIFY_RAISES_ASSERT(construct_at_boundary(8)); + } + for(int b=8; b(b)); + if(b<64) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + if(b<128) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + //if(b<32) VERIFY_RAISES_ASSERT(construct_at_boundary(b)); + } #endif } diff --git a/gtsam/3rdparty/Eigen/test/unalignedcount.cpp b/gtsam/3rdparty/Eigen/test/unalignedcount.cpp index ca7e159f3..d6ffeafdf 100644 --- a/gtsam/3rdparty/Eigen/test/unalignedcount.cpp +++ b/gtsam/3rdparty/Eigen/test/unalignedcount.cpp @@ -30,7 +30,14 @@ static int nb_storeu; void test_unalignedcount() { - #ifdef EIGEN_VECTORIZE_SSE + #if defined(EIGEN_VECTORIZE_AVX) + VectorXf a(40), b(40); + VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 10, 0, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 5, 5, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 5, 5, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 5, 0, 5, 0); + VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 5, 0, 5, 0); + #elif defined(EIGEN_VECTORIZE_SSE) VectorXf a(40), b(40); VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 20, 0, 10, 0); VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 10, 10, 10, 0); diff --git a/gtsam/3rdparty/Eigen/test/upperbidiagonalization.cpp b/gtsam/3rdparty/Eigen/test/upperbidiagonalization.cpp index d15bf588b..847b34b55 100644 --- a/gtsam/3rdparty/Eigen/test/upperbidiagonalization.cpp +++ b/gtsam/3rdparty/Eigen/test/upperbidiagonalization.cpp @@ -35,7 +35,7 @@ void test_upperbidiagonalization() CALL_SUBTEST_1( upperbidiag(MatrixXf(3,3)) ); CALL_SUBTEST_2( upperbidiag(MatrixXd(17,12)) ); CALL_SUBTEST_3( upperbidiag(MatrixXcf(20,20)) ); - CALL_SUBTEST_4( upperbidiag(MatrixXcd(16,15)) ); + CALL_SUBTEST_4( upperbidiag(Matrix,Dynamic,Dynamic,RowMajor>(16,15)) ); CALL_SUBTEST_5( upperbidiag(Matrix()) ); CALL_SUBTEST_6( upperbidiag(Matrix()) ); CALL_SUBTEST_7( upperbidiag(Matrix()) ); diff --git a/gtsam/3rdparty/Eigen/test/vectorization_logic.cpp b/gtsam/3rdparty/Eigen/test/vectorization_logic.cpp index aee68a87f..83c1439ad 100644 --- a/gtsam/3rdparty/Eigen/test/vectorization_logic.cpp +++ b/gtsam/3rdparty/Eigen/test/vectorization_logic.cpp @@ -1,72 +1,47 @@ // This file is part of Eigen, a lightweight C++ template library // for linear algebra. // -// Copyright (C) 2008 Gael Guennebaud +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#ifdef EIGEN_TEST_PART_1 +#define EIGEN_UNALIGNED_VECTORIZE 1 +#endif + +#ifdef EIGEN_TEST_PART_2 +#define EIGEN_UNALIGNED_VECTORIZE 0 +#endif + +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +#undef EIGEN_DEFAULT_TO_ROW_MAJOR +#endif #define EIGEN_DEBUG_ASSIGN #include "main.h" #include -std::string demangle_traversal(int t) -{ - if(t==DefaultTraversal) return "DefaultTraversal"; - if(t==LinearTraversal) return "LinearTraversal"; - if(t==InnerVectorizedTraversal) return "InnerVectorizedTraversal"; - if(t==LinearVectorizedTraversal) return "LinearVectorizedTraversal"; - if(t==SliceVectorizedTraversal) return "SliceVectorizedTraversal"; - return "?"; -} -std::string demangle_unrolling(int t) -{ - if(t==NoUnrolling) return "NoUnrolling"; - if(t==InnerUnrolling) return "InnerUnrolling"; - if(t==CompleteUnrolling) return "CompleteUnrolling"; - return "?"; -} +using internal::demangle_flags; +using internal::demangle_traversal; +using internal::demangle_unrolling; template bool test_assign(const Dst&, const Src&, int traversal, int unrolling) { - internal::assign_traits::debug(); - bool res = internal::assign_traits::Traversal==traversal - && internal::assign_traits::Unrolling==unrolling; - if(!res) - { - std::cerr << " Expected Traversal == " << demangle_traversal(traversal) - << " got " << demangle_traversal(internal::assign_traits::Traversal) << "\n"; - std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) - << " got " << demangle_unrolling(internal::assign_traits::Unrolling) << "\n"; - } - return res; -} - -template -bool test_assign(int traversal, int unrolling) -{ - internal::assign_traits::debug(); - bool res = internal::assign_traits::Traversal==traversal - && internal::assign_traits::Unrolling==unrolling; - if(!res) - { - std::cerr << " Expected Traversal == " << demangle_traversal(traversal) - << " got " << demangle_traversal(internal::assign_traits::Traversal) << "\n"; - std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) - << " got " << demangle_unrolling(internal::assign_traits::Unrolling) << "\n"; - } - return res; -} - -template -bool test_redux(const Xpr&, int traversal, int unrolling) -{ - typedef internal::redux_traits,Xpr> traits; - bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + typedef internal::copy_using_evaluator_traits,internal::evaluator, internal::assign_op > traits; + bool res = traits::Traversal==traversal; + if(unrolling==InnerUnrolling+CompleteUnrolling) + res = res && (int(traits::Unrolling)==InnerUnrolling || int(traits::Unrolling)==CompleteUnrolling); + else + res = res && int(traits::Unrolling)==unrolling; if(!res) { + std::cerr << "Src: " << demangle_flags(Src::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + std::cerr << "Dst: " << demangle_flags(Dst::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); std::cerr << " Expected Traversal == " << demangle_traversal(traversal) << " got " << demangle_traversal(traits::Traversal) << "\n"; std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) @@ -75,10 +50,57 @@ bool test_redux(const Xpr&, int traversal, int unrolling) return res; } -template::Vectorizable> struct vectorization_logic +template +bool test_assign(int traversal, int unrolling) { + typedef internal::copy_using_evaluator_traits,internal::evaluator, internal::assign_op > traits; + bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + if(!res) + { + std::cerr << "Src: " << demangle_flags(Src::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + std::cerr << "Dst: " << demangle_flags(Dst::Flags) << std::endl; + std::cerr << " " << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); + std::cerr << " Expected Traversal == " << demangle_traversal(traversal) + << " got " << demangle_traversal(traits::Traversal) << "\n"; + std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) + << " got " << demangle_unrolling(traits::Unrolling) << "\n"; + } + return res; +} + +template +bool test_redux(const Xpr&, int traversal, int unrolling) +{ + typedef typename Xpr::Scalar Scalar; + typedef internal::redux_traits,internal::redux_evaluator > traits; + + bool res = traits::Traversal==traversal && traits::Unrolling==unrolling; + if(!res) + { + std::cerr << demangle_flags(Xpr::Flags) << std::endl; + std::cerr << demangle_flags(internal::evaluator::Flags) << std::endl; + traits::debug(); + + std::cerr << " Expected Traversal == " << demangle_traversal(traversal) + << " got " << demangle_traversal(traits::Traversal) << "\n"; + std::cerr << " Expected Unrolling == " << demangle_unrolling(unrolling) + << " got " << demangle_unrolling(traits::Unrolling) << "\n"; + } + return res; +} + +template::Vectorizable> +struct vectorization_logic +{ + typedef internal::packet_traits PacketTraits; + + typedef typename internal::packet_traits::type PacketType; + typedef typename internal::unpacket_traits::half HalfPacketType; enum { - PacketSize = internal::packet_traits::size + PacketSize = internal::unpacket_traits::size, + HalfPacketSize = internal::unpacket_traits::size }; static void run() { @@ -90,8 +112,8 @@ template::Vectori typedef Matrix Matrix22; typedef Matrix Matrix44; typedef Matrix Matrix44u; - typedef Matrix Matrix44c; - typedef Matrix Matrix44r; + typedef Matrix Matrix44c; + typedef Matrix Matrix44r; typedef Matrix::Vectori InnerVectorizedTraversal,InnerUnrolling)); VERIFY(test_assign(Matrix44u(),Matrix44()+Matrix44(), - LinearTraversal,NoUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal, + EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling)); + + VERIFY(test_assign(Matrix1(),Matrix1()+Matrix1(), + (Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal, + CompleteUnrolling)); VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) + : LinearTraversal, CompleteUnrolling)); VERIFY(test_assign(Matrix44c().col(1),Matrix44c().col(2)+Matrix44c().col(3), InnerVectorizedTraversal,CompleteUnrolling)); - + VERIFY(test_assign(Matrix44r().row(2),Matrix44r().row(1)+Matrix44r().row(1), InnerVectorizedTraversal,CompleteUnrolling)); - + if(PacketSize>1) { typedef Matrix Matrix33c; + typedef Matrix Vector3; VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1), LinearTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector3(),Vector3()+Vector3(), + EIGEN_UNALIGNED_VECTORIZE ? (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearTraversal), CompleteUnrolling)); VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1), - LinearTraversal,CompleteUnrolling)); - - VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()), + EIGEN_UNALIGNED_VECTORIZE ? (HalfPacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : (HalfPacketSize==1 ? SliceVectorizedTraversal : LinearTraversal), + ((!EIGEN_UNALIGNED_VECTORIZE) && HalfPacketSize==1) ? NoUnrolling : CompleteUnrolling)); + + VERIFY(test_assign(Matrix3(),Matrix3().cwiseProduct(Matrix3()), LinearVectorizedTraversal,CompleteUnrolling)); VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,NoUnrolling)); + HalfPacketSize==1 ? InnerVectorizedTraversal : + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : + LinearTraversal, + NoUnrolling)); - VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(10,4), - DefaultTraversal,CompleteUnrolling)); + VERIFY(test_assign(Matrix11(), Matrix11()+Matrix11(),InnerVectorizedTraversal,CompleteUnrolling)); + + + VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(8,4), + (EIGEN_UNALIGNED_VECTORIZE) ? InnerVectorizedTraversal : DefaultTraversal, CompleteUnrolling|InnerUnrolling)); + + VERIFY(test_assign(Vector1(),Matrix11()*Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()), + InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling)); } - + + VERIFY(test_redux(Vector1(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix(), + LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_redux(Matrix3(), LinearVectorizedTraversal,CompleteUnrolling)); @@ -174,18 +224,19 @@ template::Vectori VERIFY(test_redux(Matrix44r().template block<1,2*PacketSize>(2,1), LinearVectorizedTraversal,CompleteUnrolling)); - + VERIFY((test_assign< - Map >, + Map >, Matrix22 >(InnerVectorizedTraversal,CompleteUnrolling))); VERIFY((test_assign< - Map >, - Matrix22 - >(DefaultTraversal,CompleteUnrolling))); + Map, AlignedMax, InnerStride<3*PacketSize> >, + Matrix + >(DefaultTraversal,PacketSize>=8?InnerUnrolling:CompleteUnrolling))); - VERIFY((test_assign(Matrix11(), Matrix11()*Matrix11(), InnerVectorizedTraversal, CompleteUnrolling))); + VERIFY((test_assign(Matrix11(), Matrix()*Matrix(), + InnerVectorizedTraversal, CompleteUnrolling))); #endif VERIFY(test_assign(MatrixXX(10,10),MatrixXX(20,20).block(10,10,2,3), @@ -193,8 +244,6 @@ template::Vectori VERIFY(test_redux(VectorX(10), LinearVectorizedTraversal,NoUnrolling)); - - } }; @@ -203,32 +252,167 @@ template struct vectorization_logic static void run() {} }; +template::type>::half, + typename internal::packet_traits::type>::value > +struct vectorization_logic_half +{ + typedef internal::packet_traits PacketTraits; + typedef typename internal::unpacket_traits::type>::half PacketType; + enum { + PacketSize = internal::unpacket_traits::size + }; + static void run() + { + + typedef Matrix Vector1; + typedef Matrix Matrix11; + typedef Matrix Matrix57; + typedef Matrix Matrix35; + typedef Matrix Matrix57u; +// typedef Matrix Matrix44; +// typedef Matrix Matrix44u; +// typedef Matrix Matrix44c; +// typedef Matrix Matrix44r; + + typedef Matrix Matrix1; + + typedef Matrix Matrix1u; + + // this type is made such that it can only be vectorized when viewed as a linear 1D vector + typedef Matrix Matrix3; + + #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT + VERIFY(test_assign(Vector1(),Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1()+Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().template segment(0).derived(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Scalar(2.1)*Vector1()-Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),(Scalar(2.1)*Vector1().template segment(0)-Vector1().template segment(0)).derived(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().template cast(), + InnerVectorizedTraversal,CompleteUnrolling)); + + + VERIFY(test_assign(Vector1(),Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1()+Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix57(),Matrix57()+Matrix57(), + InnerVectorizedTraversal,InnerUnrolling)); + + VERIFY(test_assign(Matrix57u(),Matrix57()+Matrix57(), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal, + EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling)); + + VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(), + EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling)); + + if(PacketSize>1) + { + typedef Matrix Matrix33c; + VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1), + LinearTraversal,CompleteUnrolling)); + VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1), + EIGEN_UNALIGNED_VECTORIZE ? (PacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()), + PacketTraits::HasDiv ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix(),Matrix()+Matrix(), + EIGEN_UNALIGNED_VECTORIZE ? (PacketSize==1 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal, + NoUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix().template block(2,3)+Matrix().template block(8,4), + EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : DefaultTraversal,PacketSize>4?InnerUnrolling:CompleteUnrolling)); + + VERIFY(test_assign(Vector1(),Matrix11()*Vector1(), + InnerVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()), + InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling)); + } + + VERIFY(test_redux(Vector1(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix3(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix35(), + LinearVectorizedTraversal,CompleteUnrolling)); + + VERIFY(test_redux(Matrix57().template block(1,0), + DefaultTraversal,CompleteUnrolling)); + + VERIFY((test_assign< + Map, AlignedMax, InnerStride<3*PacketSize> >, + Matrix + >(DefaultTraversal,CompleteUnrolling))); + + VERIFY((test_assign(Matrix57(), Matrix()*Matrix(), + InnerVectorizedTraversal, InnerUnrolling|CompleteUnrolling))); + #endif + } +}; + +template struct vectorization_logic_half +{ + static void run() {} +}; + void test_vectorization_logic() { #ifdef EIGEN_VECTORIZE + CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic::run() ); CALL_SUBTEST( vectorization_logic >::run() ); CALL_SUBTEST( vectorization_logic >::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half::run() ); + CALL_SUBTEST( vectorization_logic_half >::run() ); + CALL_SUBTEST( vectorization_logic_half >::run() ); + if(internal::packet_traits::Vectorizable) { VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); VERIFY(test_redux(Matrix(), - DefaultTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling)); } if(internal::packet_traits::Vectorizable) { VERIFY(test_assign(Matrix(),Matrix()+Matrix(), - LinearTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling)); VERIFY(test_redux(Matrix(), - DefaultTraversal,CompleteUnrolling)); + EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling)); } #endif // EIGEN_VECTORIZE diff --git a/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp index d32fd10cc..f3ab561ee 100644 --- a/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp +++ b/gtsam/3rdparty/Eigen/test/vectorwiseop.cpp @@ -2,11 +2,13 @@ // for linear algebra. // // Copyright (C) 2011 Benoit Jacob +// Copyright (C) 2015 Gael Guennebaud // // This Source Code Form is subject to the terms of the Mozilla // Public License v. 2.0. If a copy of the MPL was not distributed // with this file, You can obtain one at http://mozilla.org/MPL/2.0/. +#define TEST_ENABLE_TEMPORARY_TRACKING #define EIGEN_NO_STATIC_ASSERT #include "main.h" @@ -101,11 +103,11 @@ template void vectorwiseop_array(const ArrayType& m) VERIFY_RAISES_ASSERT(m2.rowwise() /= rowvec.transpose()); VERIFY_RAISES_ASSERT(m1.rowwise() / rowvec.transpose()); - + m2 = m1; // yes, there might be an aliasing issue there but ".rowwise() /=" - // is suppposed to evaluate " m2.colwise().sum()" into to temporary to avoid - // evaluating the reducions multiple times + // is supposed to evaluate " m2.colwise().sum()" into a temporary to avoid + // evaluating the reduction multiple times if(ArrayType::RowsAtCompileTime>2 || ArrayType::RowsAtCompileTime==Dynamic) { m2.rowwise() /= m2.colwise().sum(); @@ -156,16 +158,22 @@ template void vectorwiseop_matrix(const MatrixType& m) VERIFY_IS_APPROX(m2, m1.colwise() + colvec); VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec); - VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); - VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + if(rows>1) + { + VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose()); + } m2 = m1; m2.rowwise() += rowvec; VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec); VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec); - VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); - VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + if(cols>1) + { + VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose()); + } // test substraction @@ -174,29 +182,43 @@ template void vectorwiseop_matrix(const MatrixType& m) VERIFY_IS_APPROX(m2, m1.colwise() - colvec); VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec); - VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); - VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + if(rows>1) + { + VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose()); + VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose()); + } m2 = m1; m2.rowwise() -= rowvec; VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec); VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec); - VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); - VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); - + if(cols>1) + { + VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose()); + VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose()); + } + // test norm rrres = m1.colwise().norm(); VERIFY_IS_APPROX(rrres(c), m1.col(c).norm()); rcres = m1.rowwise().norm(); VERIFY_IS_APPROX(rcres(r), m1.row(r).norm()); - + + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum(), m1.colwise().template lpNorm<1>()); + VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().sum(), m1.rowwise().template lpNorm<1>()); + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().maxCoeff(), m1.colwise().template lpNorm()); + VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().maxCoeff(), m1.rowwise().template lpNorm()); + + // regression for bug 1158 + VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum().x(), m1.col(0).cwiseAbs().sum()); + // test normalized m2 = m1.colwise().normalized(); VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized()); m2 = m1.rowwise().normalized(); VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized()); - + // test normalize m2 = m1; m2.colwise().normalize(); @@ -204,14 +226,27 @@ template void vectorwiseop_matrix(const MatrixType& m) m2 = m1; m2.rowwise().normalize(); VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized()); + + // test with partial reduction of products + Matrix m1m1 = m1 * m1.transpose(); + VERIFY_IS_APPROX( (m1 * m1.transpose()).colwise().sum(), m1m1.colwise().sum()); + Matrix tmp(rows); + VERIFY_EVALUATION_COUNT( tmp = (m1 * m1.transpose()).colwise().sum(), 1); + + m2 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())).eval(); + m1 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())); + VERIFY_IS_APPROX( m1, m2 ); + VERIFY_EVALUATION_COUNT( m2 = (m1.rowwise() - m1.colwise().sum()/RealScalar(m1.rows())), (MatrixType::RowsAtCompileTime!=1 ? 1 : 0) ); } void test_vectorwiseop() { - CALL_SUBTEST_1(vectorwiseop_array(Array22cd())); - CALL_SUBTEST_2(vectorwiseop_array(Array())); - CALL_SUBTEST_3(vectorwiseop_array(ArrayXXf(3, 4))); - CALL_SUBTEST_4(vectorwiseop_matrix(Matrix4cf())); - CALL_SUBTEST_5(vectorwiseop_matrix(Matrix())); - CALL_SUBTEST_6(vectorwiseop_matrix(MatrixXd(7,2))); + CALL_SUBTEST_1( vectorwiseop_array(Array22cd()) ); + CALL_SUBTEST_2( vectorwiseop_array(Array()) ); + CALL_SUBTEST_3( vectorwiseop_array(ArrayXXf(3, 4)) ); + CALL_SUBTEST_4( vectorwiseop_matrix(Matrix4cf()) ); + CALL_SUBTEST_5( vectorwiseop_matrix(Matrix()) ); + CALL_SUBTEST_6( vectorwiseop_matrix(MatrixXd(internal::random(1,EIGEN_TEST_MAX_SIZE), internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( vectorwiseop_matrix(VectorXd(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); + CALL_SUBTEST_7( vectorwiseop_matrix(RowVectorXd(internal::random(1,EIGEN_TEST_MAX_SIZE))) ); } diff --git a/gtsam/3rdparty/Eigen/test/zerosized.cpp b/gtsam/3rdparty/Eigen/test/zerosized.cpp index da7dd0481..477ff0070 100644 --- a/gtsam/3rdparty/Eigen/test/zerosized.cpp +++ b/gtsam/3rdparty/Eigen/test/zerosized.cpp @@ -25,6 +25,7 @@ template void zeroReduction(const MatrixType& m) { template void zeroSizedMatrix() { MatrixType t1; + typedef typename MatrixType::Scalar Scalar; if (MatrixType::SizeAtCompileTime == Dynamic || MatrixType::SizeAtCompileTime == 0) { @@ -37,7 +38,7 @@ template void zeroSizedMatrix() if (MatrixType::RowsAtCompileTime == Dynamic && MatrixType::ColsAtCompileTime == Dynamic) { - MatrixType t2(0, 0); + MatrixType t2(0, 0), t3(t1); VERIFY(t2.rows() == 0); VERIFY(t2.cols() == 0); @@ -45,6 +46,23 @@ template void zeroSizedMatrix() VERIFY(t1==t2); } } + + if(MatrixType::MaxColsAtCompileTime!=0 && MatrixType::MaxRowsAtCompileTime!=0) + { + Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random(1,10) : Index(MatrixType::RowsAtCompileTime); + Index cols = MatrixType::ColsAtCompileTime==Dynamic ? internal::random(1,10) : Index(MatrixType::ColsAtCompileTime); + MatrixType m(rows,cols); + zeroReduction(m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols)); + zeroReduction(m.template block(0,0,rows,0)); + zeroReduction(m.template block<0,1>(0,0)); + zeroReduction(m.template block<1,0>(0,0)); + Matrix prod = m.template block(0,0,rows,0) * m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols); + VERIFY(prod.rows()==rows && prod.cols()==cols); + VERIFY(prod.isZero()); + prod = m.template block<1,0>(0,0) * m.template block<0,1>(0,0); + VERIFY(prod.size()==1); + VERIFY(prod.isZero()); + } } template void zeroSizedVector() diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward b/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward index 2627decd0..15f5f0731 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/AdolcForward @@ -25,7 +25,7 @@ #ifndef NUMBER_DIRECTIONS # define NUMBER_DIRECTIONS 2 #endif -#include +#include // adolc defines some very stupid macros: #if defined(malloc) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/AlignedVector3 b/gtsam/3rdparty/Eigen/unsupported/Eigen/AlignedVector3 index 29d5c90fb..47a86d4c0 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/AlignedVector3 +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/AlignedVector3 @@ -57,6 +57,11 @@ template class AlignedVector3 inline Index rows() const { return 3; } inline Index cols() const { return 1; } + + Scalar* data() { return m_coeffs.data(); } + const Scalar* data() const { return m_coeffs.data(); } + Index innerStride() const { return 1; } + Index outerStride() const { return 3; } inline const Scalar& coeff(Index row, Index col) const { return m_coeffs.coeff(row, col); } @@ -100,7 +105,7 @@ template class AlignedVector3 }; template - inline explicit AlignedVector3(const MatrixBase& other) + inline AlignedVector3(const MatrixBase& other) { generic_assign_selector::run(*this,other.derived()); } @@ -108,6 +113,12 @@ template class AlignedVector3 inline AlignedVector3& operator=(const AlignedVector3& other) { m_coeffs = other.m_coeffs; return *this; } + template + inline AlignedVector3& operator=(const MatrixBase& other) + { + generic_assign_selector::run(*this,other.derived()); + return *this; + } inline AlignedVector3 operator+(const AlignedVector3& other) const { return AlignedVector3(m_coeffs + other.m_coeffs); } @@ -148,7 +159,7 @@ template class AlignedVector3 m_coeffs /= norm(); } - inline AlignedVector3 normalized() + inline AlignedVector3 normalized() const { return AlignedVector3(m_coeffs / norm()); } @@ -181,8 +192,31 @@ template class AlignedVector3 { return m_coeffs.template head<3>().isApprox(other,eps); } + + CoeffType& coeffs() { return m_coeffs; } + const CoeffType& coeffs() const { return m_coeffs; } }; +namespace internal { + +template +struct eval, Dense> +{ + typedef const AlignedVector3<_Scalar>& type; +}; + +template +struct evaluator > + : evaluator > +{ + typedef AlignedVector3 XprType; + typedef evaluator > Base; + + evaluator(const XprType &m) : Base(m.coeffs()) {} +}; + +} + //@} } diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt index e1fbf97e2..631a06014 100644 --- a/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CMakeLists.txt @@ -1,11 +1,32 @@ -set(Eigen_HEADERS AdolcForward AlignedVector3 ArpackSupport AutoDiff BVH FFT IterativeSolvers KroneckerProduct LevenbergMarquardt - MatrixFunctions MoreVectorization MPRealSupport NonLinearOptimization NumericalDiff OpenGLSupport Polynomials - Skyline SparseExtra Splines - ) +set(Eigen_HEADERS + AdolcForward + AlignedVector3 + ArpackSupport + AutoDiff + BVH + EulerAngles + FFT + IterativeSolvers + KroneckerProduct + LevenbergMarquardt + MatrixFunctions + MoreVectorization + MPRealSupport + NonLinearOptimization + NumericalDiff + OpenGLSupport + Polynomials + Skyline + SparseExtra + SpecialFunctions + Splines + ) install(FILES ${Eigen_HEADERS} DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel ) -add_subdirectory(src) +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel FILES_MATCHING PATTERN "*.h") + +add_subdirectory(CXX11) diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/CMakeLists.txt b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/CMakeLists.txt new file mode 100644 index 000000000..385ed240c --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/CMakeLists.txt @@ -0,0 +1,8 @@ +set(Eigen_CXX11_HEADERS Tensor TensorSymmetry ThreadPool) + +install(FILES + ${Eigen_CXX11_HEADERS} + DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel + ) + +install(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel FILES_MATCHING PATTERN "*.h") diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/Tensor b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/Tensor new file mode 100644 index 000000000..7ecb4c74d --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/Tensor @@ -0,0 +1,152 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +//#ifndef EIGEN_CXX11_TENSOR_MODULE +//#define EIGEN_CXX11_TENSOR_MODULE + +#include "../../../Eigen/Core" + +#ifdef EIGEN_USE_SYCL +#undef min +#undef max +#undef isnan +#undef isinf +#undef isfinite +#include +#include +#include +#include +#endif + +#include + +#include "../SpecialFunctions" +#include "src/util/CXX11Meta.h" +#include "src/util/MaxSizeVector.h" + +/** \defgroup CXX11_Tensor_Module Tensor Module + * + * This module provides a Tensor class for storing arbitrarily indexed + * objects. + * + * \code + * #include + * \endcode + */ + +#include +#include +#include + +#ifdef _WIN32 +typedef __int16 int16_t; +typedef unsigned __int16 uint16_t; +typedef __int32 int32_t; +typedef unsigned __int32 uint32_t; +typedef __int64 int64_t; +typedef unsigned __int64 uint64_t; +#else +#include +#endif + +#if __cplusplus > 199711 || EIGEN_COMP_MSVC >= 1900 +#include +#endif + +#ifdef _WIN32 +#include +#elif defined(__APPLE__) +#include +#else +#include +#endif + +#ifdef EIGEN_USE_THREADS +#include "ThreadPool" +#endif + +#ifdef EIGEN_USE_GPU +#include +#include +#if __cplusplus >= 201103L +#include +#include +#endif +#endif + +#include "src/Tensor/TensorMacros.h" +#include "src/Tensor/TensorForwardDeclarations.h" +#include "src/Tensor/TensorMeta.h" +#include "src/Tensor/TensorFunctors.h" +#include "src/Tensor/TensorCostModel.h" +#include "src/Tensor/TensorDeviceDefault.h" +#include "src/Tensor/TensorDeviceThreadPool.h" +#include "src/Tensor/TensorDeviceCuda.h" +#include "src/Tensor/TensorDeviceSycl.h" +#include "src/Tensor/TensorIndexList.h" +#include "src/Tensor/TensorDimensionList.h" +#include "src/Tensor/TensorDimensions.h" +#include "src/Tensor/TensorInitializer.h" +#include "src/Tensor/TensorTraits.h" +#include "src/Tensor/TensorRandom.h" +#include "src/Tensor/TensorUInt128.h" +#include "src/Tensor/TensorIntDiv.h" +#include "src/Tensor/TensorGlobalFunctions.h" + +#include "src/Tensor/TensorBase.h" + +#include "src/Tensor/TensorEvaluator.h" +#include "src/Tensor/TensorExpr.h" +#include "src/Tensor/TensorReduction.h" +#include "src/Tensor/TensorReductionCuda.h" +#include "src/Tensor/TensorArgMax.h" +#include "src/Tensor/TensorConcatenation.h" +#include "src/Tensor/TensorContractionMapper.h" +#include "src/Tensor/TensorContractionBlocking.h" +#include "src/Tensor/TensorContraction.h" +#include "src/Tensor/TensorContractionThreadPool.h" +#include "src/Tensor/TensorContractionCuda.h" +#include "src/Tensor/TensorConversion.h" +#include "src/Tensor/TensorConvolution.h" +#include "src/Tensor/TensorFFT.h" +#include "src/Tensor/TensorPatch.h" +#include "src/Tensor/TensorImagePatch.h" +#include "src/Tensor/TensorVolumePatch.h" +#include "src/Tensor/TensorBroadcasting.h" +#include "src/Tensor/TensorChipping.h" +#include "src/Tensor/TensorInflation.h" +#include "src/Tensor/TensorLayoutSwap.h" +#include "src/Tensor/TensorMorphing.h" +#include "src/Tensor/TensorPadding.h" +#include "src/Tensor/TensorReverse.h" +#include "src/Tensor/TensorShuffling.h" +#include "src/Tensor/TensorStriding.h" +#include "src/Tensor/TensorCustomOp.h" +#include "src/Tensor/TensorEvalTo.h" +#include "src/Tensor/TensorForcedEval.h" +#include "src/Tensor/TensorGenerator.h" +#include "src/Tensor/TensorAssign.h" +#include "src/Tensor/TensorScan.h" + +#include "src/Tensor/TensorSycl.h" +#include "src/Tensor/TensorExecutor.h" +#include "src/Tensor/TensorDevice.h" + +#include "src/Tensor/TensorStorage.h" +#include "src/Tensor/Tensor.h" +#include "src/Tensor/TensorFixedSize.h" +#include "src/Tensor/TensorMap.h" +#include "src/Tensor/TensorRef.h" + +#include "src/Tensor/TensorIO.h" + +#include + +//#endif // EIGEN_CXX11_TENSOR_MODULE diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/TensorSymmetry b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/TensorSymmetry new file mode 100644 index 000000000..fb1b0c0fb --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/TensorSymmetry @@ -0,0 +1,42 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSORSYMMETRY_MODULE +#define EIGEN_CXX11_TENSORSYMMETRY_MODULE + +#include + +#include + +#include "src/util/CXX11Meta.h" + +/** \defgroup CXX11_TensorSymmetry_Module Tensor Symmetry Module + * + * This module provides a classes that allow for the definition of + * symmetries w.r.t. tensor indices. + * + * Including this module will implicitly include the Tensor module. + * + * \code + * #include + * \endcode + */ + +#include "src/TensorSymmetry/util/TemplateGroupTheory.h" +#include "src/TensorSymmetry/Symmetry.h" +#include "src/TensorSymmetry/StaticSymmetry.h" +#include "src/TensorSymmetry/DynamicSymmetry.h" + +#include + +#endif // EIGEN_CXX11_TENSORSYMMETRY_MODULE + +/* + * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle; + */ diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/ThreadPool b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/ThreadPool new file mode 100644 index 000000000..09d637e9a --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/ThreadPool @@ -0,0 +1,65 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_THREADPOOL_MODULE +#define EIGEN_CXX11_THREADPOOL_MODULE + +#include "../../../Eigen/Core" + +#include + +/** \defgroup CXX11_ThreadPool_Module C++11 ThreadPool Module + * + * This module provides 2 threadpool implementations + * - a simple reference implementation + * - a faster non blocking implementation + * + * This module requires C++11. + * + * \code + * #include + * \endcode + */ + + +// The code depends on CXX11, so only include the module if the +// compiler supports it. +#if __cplusplus > 199711L || EIGEN_COMP_MSVC >= 1900 +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "src/util/CXX11Meta.h" +#include "src/util/MaxSizeVector.h" + +#include "src/ThreadPool/ThreadLocal.h" +#include "src/ThreadPool/ThreadYield.h" +#include "src/ThreadPool/EventCount.h" +#include "src/ThreadPool/RunQueue.h" +#include "src/ThreadPool/ThreadPoolInterface.h" +#include "src/ThreadPool/ThreadEnvironment.h" +#include "src/ThreadPool/SimpleThreadPool.h" +#include "src/ThreadPool/NonBlockingThreadPool.h" + +#endif + +#include + +#endif // EIGEN_CXX11_THREADPOOL_MODULE + diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/README.md b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/README.md new file mode 100644 index 000000000..98e83811b --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/README.md @@ -0,0 +1,1757 @@ +# Eigen Tensors + +Tensors are multidimensional arrays of elements. Elements are typically scalars, +but more complex types such as strings are also supported. + +[TOC] + +## Tensor Classes + +You can manipulate a tensor with one of the following classes. They all are in +the namespace ```::Eigen.``` + + +### Class Tensor + +This is the class to use to create a tensor and allocate memory for it. The +class is templatized with the tensor datatype, such as float or int, and the +tensor rank. The rank is the number of dimensions, for example rank 2 is a +matrix. + +Tensors of this class are resizable. For example, if you assign a tensor of a +different size to a Tensor, that tensor is resized to match its new value. + +#### Constructor Tensor(size0, size1, ...) + +Constructor for a Tensor. The constructor must be passed ```rank``` integers +indicating the sizes of the instance along each of the the ```rank``` +dimensions. + + // Create a tensor of rank 3 of sizes 2, 3, 4. This tensor owns + // memory to hold 24 floating point values (24 = 2 x 3 x 4). + Tensor t_3d(2, 3, 4); + + // Resize t_3d by assigning a tensor of different sizes, but same rank. + t_3d = Tensor(3, 4, 3); + +#### Constructor Tensor(size_array) + +Constructor where the sizes for the constructor are specified as an array of +values instead of an explicitly list of parameters. The array type to use is +```Eigen::array```. The array can be constructed automatically +from an initializer list. + + // Create a tensor of strings of rank 2 with sizes 5, 7. + Tensor t_2d({5, 7}); + + +### Class TensorFixedSize> + +Class to use for tensors of fixed size, where the size is known at compile +time. Fixed sized tensors can provide very fast computations because all their +dimensions are known by the compiler. FixedSize tensors are not resizable. + +If the total number of elements in a fixed size tensor is small enough the +tensor data is held onto the stack and does not cause heap allocation and free. + + // Create a 4 x 3 tensor of floats. + TensorFixedSize> t_4x3; + +### Class TensorMap> + +This is the class to use to create a tensor on top of memory allocated and +owned by another part of your code. It allows to view any piece of allocated +memory as a Tensor. Instances of this class do not own the memory where the +data are stored. + +A TensorMap is not resizable because it does not own the memory where its data +are stored. + +#### Constructor TensorMap>(data, size0, size1, ...) + +Constructor for a Tensor. The constructor must be passed a pointer to the +storage for the data, and "rank" size attributes. The storage has to be +large enough to hold all the data. + + // Map a tensor of ints on top of stack-allocated storage. + int storage[128]; // 2 x 4 x 2 x 8 = 128 + TensorMap> t_4d(storage, 2, 4, 2, 8); + + // The same storage can be viewed as a different tensor. + // You can also pass the sizes as an array. + TensorMap> t_2d(storage, 16, 8); + + // You can also map fixed-size tensors. Here we get a 1d view of + // the 2d fixed-size tensor. + Tensor> t_4x3; + TensorMap> t_12(t_4x3, 12); + + +#### Class TensorRef + +See Assigning to a TensorRef below. + +## Accessing Tensor Elements + +#### tensor(index0, index1...) + +Return the element at position ```(index0, index1...)``` in tensor +```tensor```. You must pass as many parameters as the rank of ```tensor```. +The expression can be used as an l-value to set the value of the element at the +specified position. The value returned is of the datatype of the tensor. + + // Set the value of the element at position (0, 1, 0); + Tensor t_3d(2, 3, 4); + t_3d(0, 1, 0) = 12.0f; + + // Initialize all elements to random values. + for (int i = 0; i < 2; ++i) { + for (int j = 0; j < 3; ++j) { + for (int k = 0; k < 4; ++k) { + t_3d(i, j, k) = ...some random value...; + } + } + } + + // Print elements of a tensor. + for (int i = 0; i < 2; ++i) { + LOG(INFO) << t_3d(i, 0, 0); + } + + +## TensorLayout + +The tensor library supports 2 layouts: ```ColMajor``` (the default) and +```RowMajor```. Only the default column major layout is currently fully +supported, and it is therefore not recommended to attempt to use the row major +layout at the moment. + +The layout of a tensor is optionally specified as part of its type. If not +specified explicitly column major is assumed. + + Tensor col_major; // equivalent to Tensor + TensorMap > row_major(data, ...); + +All the arguments to an expression must use the same layout. Attempting to mix +different layouts will result in a compilation error. + +It is possible to change the layout of a tensor or an expression using the +```swap_layout()``` method. Note that this will also reverse the order of the +dimensions. + + Tensor col_major(2, 4); + Tensor row_major(2, 4); + + Tensor col_major_result = col_major; // ok, layouts match + Tensor col_major_result = row_major; // will not compile + + // Simple layout swap + col_major_result = row_major.swap_layout(); + eigen_assert(col_major_result.dimension(0) == 4); + eigen_assert(col_major_result.dimension(1) == 2); + + // Swap the layout and preserve the order of the dimensions + array shuffle(1, 0); + col_major_result = row_major.swap_layout().shuffle(shuffle); + eigen_assert(col_major_result.dimension(0) == 2); + eigen_assert(col_major_result.dimension(1) == 4); + + +## Tensor Operations + +The Eigen Tensor library provides a vast library of operations on Tensors: +numerical operations such as addition and multiplication, geometry operations +such as slicing and shuffling, etc. These operations are available as methods +of the Tensor classes, and in some cases as operator overloads. For example +the following code computes the elementwise addition of two tensors: + + Tensor t1(2, 3, 4); + ...set some values in t1... + Tensor t2(2, 3, 4); + ...set some values in t2... + // Set t3 to the element wise sum of t1 and t2 + Tensor t3 = t1 + t2; + +While the code above looks easy enough, it is important to understand that the +expression ```t1 + t2``` is not actually adding the values of the tensors. The +expression instead constructs a "tensor operator" object of the class +TensorCwiseBinaryOp, which has references to the tensors +```t1``` and ```t2```. This is a small C++ object that knows how to add +```t1``` and ```t2```. It is only when the value of the expression is assigned +to the tensor ```t3``` that the addition is actually performed. Technically, +this happens through the overloading of ```operator=()``` in the Tensor class. + +This mechanism for computing tensor expressions allows for lazy evaluation and +optimizations which are what make the tensor library very fast. + +Of course, the tensor operators do nest, and the expression ```t1 + t2 * +0.3f``` is actually represented with the (approximate) tree of operators: + + TensorCwiseBinaryOp(t1, TensorCwiseUnaryOp(t2, 0.3f)) + + +### Tensor Operations and C++ "auto" + +Because Tensor operations create tensor operators, the C++ ```auto``` keyword +does not have its intuitive meaning. Consider these 2 lines of code: + + Tensor t3 = t1 + t2; + auto t4 = t1 + t2; + +In the first line we allocate the tensor ```t3``` and it will contain the +result of the addition of ```t1``` and ```t2```. In the second line, ```t4``` +is actually the tree of tensor operators that will compute the addition of +```t1``` and ```t2```. In fact, ```t4``` is *not* a tensor and you cannot get +the values of its elements: + + Tensor t3 = t1 + t2; + cout << t3(0, 0, 0); // OK prints the value of t1(0, 0, 0) + t2(0, 0, 0) + + auto t4 = t1 + t2; + cout << t4(0, 0, 0); // Compilation error! + +When you use ```auto``` you do not get a Tensor as a result but instead a +non-evaluated expression. So only use ```auto``` to delay evaluation. + +Unfortunately, there is no single underlying concrete type for holding +non-evaluated expressions, hence you have to use auto in the case when you do +want to hold non-evaluated expressions. + +When you need the results of set of tensor computations you have to assign the +result to a Tensor that will be capable of holding onto them. This can be +either a normal Tensor, a fixed size Tensor, or a TensorMap on an existing +piece of memory. All the following will work: + + auto t4 = t1 + t2; + + Tensor result = t4; // Could also be: result(t4); + cout << result(0, 0, 0); + + TensorMap result(, , ...) = t4; + cout << result(0, 0, 0); + + TensorFixedSize> result = t4; + cout << result(0, 0, 0); + +Until you need the results, you can keep the operation around, and even reuse +it for additional operations. As long as you keep the expression as an +operation, no computation is performed. + + // One way to compute exp((t1 + t2) * 0.2f); + auto t3 = t1 + t2; + auto t4 = t3 * 0.2f; + auto t5 = t4.exp(); + Tensor result = t5; + + // Another way, exactly as efficient as the previous one: + Tensor result = ((t1 + t2) * 0.2f).exp(); + +### Controlling When Expression are Evaluated + +There are several ways to control when expressions are evaluated: + +* Assignment to a Tensor, TensorFixedSize, or TensorMap. +* Use of the eval() method. +* Assignment to a TensorRef. + +#### Assigning to a Tensor, TensorFixedSize, or TensorMap. + +The most common way to evaluate an expression is to assign it to a Tensor. In +the example below, the ```auto``` declarations make the intermediate values +"Operations", not Tensors, and do not cause the expressions to be evaluated. +The assignment to the Tensor ```result``` causes the evaluation of all the +operations. + + auto t3 = t1 + t2; // t3 is an Operation. + auto t4 = t3 * 0.2f; // t4 is an Operation. + auto t5 = t4.exp(); // t5 is an Operation. + Tensor result = t5; // The operations are evaluated. + +If you know the ranks and sizes of the Operation value you can assign the +Operation to a TensorFixedSize instead of a Tensor, which is a bit more +efficient. + + // We know that the result is a 4x4x2 tensor! + TensorFixedSize result = t5; + +Simiarly, assigning an expression to a TensorMap causes its evaluation. Like +tensors of type TensorFixedSize, TensorMaps cannot be resized so they have to +have the rank and sizes of the expression that are assigned to them. + +#### Calling eval(). + +When you compute large composite expressions, you sometimes want to tell Eigen +that an intermediate value in the expression tree is worth evaluating ahead of +time. This is done by inserting a call to the ```eval()``` method of the +expression Operation. + + // The previous example could have been written: + Tensor result = ((t1 + t2) * 0.2f).exp(); + + // If you want to compute (t1 + t2) once ahead of time you can write: + Tensor result = ((t1 + t2).eval() * 0.2f).exp(); + +Semantically, calling ```eval()``` is equivalent to materializing the value of +the expression in a temporary Tensor of the right size. The code above in +effect does: + + // .eval() knows the size! + TensorFixedSize tmp = t1 + t2; + Tensor result = (tmp * 0.2f).exp(); + +Note that the return value of ```eval()``` is itself an Operation, so the +following code does not do what you may think: + + // Here t3 is an evaluation Operation. t3 has not been evaluated yet. + auto t3 = (t1 + t2).eval(); + + // You can use t3 in another expression. Still no evaluation. + auto t4 = (t3 * 0.2f).exp(); + + // The value is evaluated when you assign the Operation to a Tensor, using + // an intermediate tensor to represent t3.x + Tensor result = t4; + +While in the examples above calling ```eval()``` does not make a difference in +performance, in other cases it can make a huge difference. In the expression +below the ```broadcast()``` expression causes the ```X.maximum()``` expression +to be evaluated many times: + + Tensor<...> X ...; + Tensor<...> Y = ((X - X.maximum(depth_dim).reshape(dims2d).broadcast(bcast)) + * beta).exp(); + +Inserting a call to ```eval()``` between the ```maximum()``` and +```reshape()``` calls guarantees that maximum() is only computed once and +greatly speeds-up execution: + + Tensor<...> Y = + ((X - X.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast)) + * beta).exp(); + +In the other example below, the tensor ```Y``` is both used in the expression +and its assignment. This is an aliasing problem and if the evaluation is not +done in the right order Y will be updated incrementally during the evaluation +resulting in bogus results: + + Tensor<...> Y ...; + Y = Y / (Y.sum(depth_dim).reshape(dims2d).broadcast(bcast)); + +Inserting a call to ```eval()``` between the ```sum()``` and ```reshape()``` +expressions ensures that the sum is computed before any updates to ```Y``` are +done. + + Y = Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast)); + +Note that an eval around the full right hand side expression is not needed +because the generated has to compute the i-th value of the right hand side +before assigning it to the left hand side. + +However, if you were assigning the expression value to a shuffle of ```Y``` +then you would need to force an eval for correctness by adding an ```eval()``` +call for the right hand side: + + Y.shuffle(...) = + (Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast))).eval(); + + +#### Assigning to a TensorRef. + +If you need to access only a few elements from the value of an expression you +can avoid materializing the value in a full tensor by using a TensorRef. + +A TensorRef is a small wrapper class for any Eigen Operation. It provides +overloads for the ```()``` operator that let you access individual values in +the expression. TensorRef is convenient, because the Operation themselves do +not provide a way to access individual elements. + + // Create a TensorRef for the expression. The expression is not + // evaluated yet. + TensorRef > ref = ((t1 + t2) * 0.2f).exp(); + + // Use "ref" to access individual elements. The expression is evaluated + // on the fly. + float at_0 = ref(0, 0, 0); + cout << ref(0, 1, 0); + +Only use TensorRef when you need a subset of the values of the expression. +TensorRef only computes the values you access. However note that if you are +going to access all the values it will be much faster to materialize the +results in a Tensor first. + +In some cases, if the full Tensor result would be very large, you may save +memory by accessing it as a TensorRef. But not always. So don't count on it. + + +### Controlling How Expressions Are Evaluated + +The tensor library provides several implementations of the various operations +such as contractions and convolutions. The implementations are optimized for +different environments: single threaded on CPU, multi threaded on CPU, or on a +GPU using cuda. Additional implementations may be added later. + +You can choose which implementation to use with the ```device()``` call. If +you do not choose an implementation explicitly the default implementation that +uses a single thread on the CPU is used. + +The default implementation has been optimized for recent Intel CPUs, taking +advantage of SSE, AVX, and FMA instructions. Work is ongoing to tune the +library on ARM CPUs. Note that you need to pass compiler-dependent flags +to enable the use of SSE, AVX, and other instructions. + +For example, the following code adds two tensors using the default +single-threaded CPU implementation: + + Tensor a(30, 40); + Tensor b(30, 40); + Tensor c = a + b; + +To choose a different implementation you have to insert a ```device()``` call +before the assignment of the result. For technical C++ reasons this requires +that the Tensor for the result be declared on its own. This means that you +have to know the size of the result. + + Eigen::Tensor c(30, 40); + c.device(...) = a + b; + +The call to ```device()``` must be the last call on the left of the operator=. + +You must pass to the ```device()``` call an Eigen device object. There are +presently three devices you can use: DefaultDevice, ThreadPoolDevice and +GpuDevice. + + +#### Evaluating With the DefaultDevice + +This is exactly the same as not inserting a ```device()``` call. + + DefaultDevice my_device; + c.device(my_device) = a + b; + +#### Evaluating with a Thread Pool + + // Create the Eigen ThreadPoolDevice. + Eigen::ThreadPoolDevice my_device(4 /* number of threads to use */); + + // Now just use the device when evaluating expressions. + Eigen::Tensor c(30, 50); + c.device(my_device) = a.contract(b, dot_product_dims); + + +#### Evaluating On GPU + +This is presently a bit more complicated than just using a thread pool device. +You need to create a GPU device but you also need to explicitly allocate the +memory for tensors with cuda. + + +## API Reference + +### Datatypes + +In the documentation of the tensor methods and Operation we mention datatypes +that are tensor-type specific: + +#### ::Dimensions + +Acts like an array of ints. Has an ```int size``` attribute, and can be +indexed like an array to access individual values. Used to represent the +dimensions of a tensor. See ```dimensions()```. + +#### ::Index + +Acts like an ```int```. Used for indexing tensors along their dimensions. See +```operator()```, ```dimension()```, and ```size()```. + +#### ::Scalar + +Represents the datatype of individual tensor elements. For example, for a +```Tensor```, ```Scalar``` is the type ```float```. See +```setConstant()```. + +#### + +We use this pseudo type to indicate that a tensor Operation is returned by a +method. We indicate in the text the type and dimensions of the tensor that the +Operation returns after evaluation. + +The Operation will have to be evaluated, for example by assigning it to a +tensor, before you can access the values of the resulting tensor. You can also +access the values through a TensorRef. + + +## Built-in Tensor Methods + +These are usual C++ methods that act on tensors immediately. They are not +Operations which provide delayed evaluation of their results. Unless specified +otherwise, all the methods listed below are available on all tensor classes: +Tensor, TensorFixedSize, and TensorMap. + +## Metadata + +### int NumDimensions + +Constant value indicating the number of dimensions of a Tensor. This is also +known as the tensor "rank". + + Eigen::Tensor a(3, 4); + cout << "Dims " << a.NumDimensions; + => Dims 2 + +### Dimensions dimensions() + +Returns an array-like object representing the dimensions of the tensor. +The actual type of the dimensions() result is ::Dimensions. + + Eigen::Tensor a(3, 4); + const Eigen::Tensor::Dimensions& d = a.dimensions(); + cout << "Dim size: " << d.size << ", dim 0: " << d[0] + << ", dim 1: " << d[1]; + => Dim size: 2, dim 0: 3, dim 1: 4 + +If you use a C++11 compiler, you can use ```auto``` to simplify the code: + + const auto& d = a.dimensions(); + cout << "Dim size: " << d.size << ", dim 0: " << d[0] + << ", dim 1: " << d[1]; + => Dim size: 2, dim 0: 3, dim 1: 4 + +### Index dimension(Index n) + +Returns the n-th dimension of the tensor. The actual type of the +```dimension()``` result is ```::Index```, but you can +always use it like an int. + + Eigen::Tensor a(3, 4); + int dim1 = a.dimension(1); + cout << "Dim 1: " << dim1; + => Dim 1: 4 + +### Index size() + +Returns the total number of elements in the tensor. This is the product of all +the tensor dimensions. The actual type of the ```size()``` result is +```::Index```, but you can always use it like an int. + + Eigen::Tensor a(3, 4); + cout << "Size: " << a.size(); + => Size: 12 + + +### Getting Dimensions From An Operation + +A few operations provide ```dimensions()``` directly, +e.g. ```TensorReslicingOp```. Most operations defer calculating dimensions +until the operation is being evaluated. If you need access to the dimensions +of a deferred operation, you can wrap it in a TensorRef (see Assigning to a +TensorRef above), which provides ```dimensions()``` and ```dimension()``` as +above. + +TensorRef can also wrap the plain Tensor types, so this is a useful idiom in +templated contexts where the underlying object could be either a raw Tensor +or some deferred operation (e.g. a slice of a Tensor). In this case, the +template code can wrap the object in a TensorRef and reason about its +dimensionality while remaining agnostic to the underlying type. + + +## Constructors + +### Tensor + +Creates a tensor of the specified size. The number of arguments must be equal +to the rank of the tensor. The content of the tensor is not initialized. + + Eigen::Tensor a(3, 4); + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + +### TensorFixedSize + +Creates a tensor of the specified size. The number of arguments in the Size<> +template parameter determines the rank of the tensor. The content of the tensor +is not initialized. + + Eigen::TensorFixedSize> a; + cout << "Rank: " << a.rank() << endl; + => Rank: 2 + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + +### TensorMap + +Creates a tensor mapping an existing array of data. The data must not be freed +until the TensorMap is discarded, and the size of the data must be large enough +to accomodate of the coefficients of the tensor. + + float data[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; + Eigen::TensorMap a(data, 3, 4); + cout << "NumRows: " << a.dimension(0) << " NumCols: " << a.dimension(1) << endl; + => NumRows: 3 NumCols: 4 + cout << "a(1, 2): " << a(1, 2) << endl; + => a(1, 2): 9 + + +## Contents Initialization + +When a new Tensor or a new TensorFixedSize are created, memory is allocated to +hold all the tensor elements, but the memory is not initialized. Similarly, +when a new TensorMap is created on top of non-initialized memory the memory its +contents are not initialized. + +You can use one of the methods below to initialize the tensor memory. These +have an immediate effect on the tensor and return the tensor itself as a +result. These are not tensor Operations which delay evaluation. + +### setConstant(const Scalar& val) + +Sets all elements of the tensor to the constant value ```val```. ```Scalar``` +is the type of data stored in the tensor. You can pass any value that is +convertible to that type. + +Returns the tensor itself in case you want to chain another call. + + a.setConstant(12.3f); + cout << "Constant: " << endl << a << endl << endl; + => + Constant: + 12.3 12.3 12.3 12.3 + 12.3 12.3 12.3 12.3 + 12.3 12.3 12.3 12.3 + +Note that ```setConstant()``` can be used on any tensor where the element type +has a copy constructor and an ```operator=()```: + + Eigen::Tensor a(2, 3); + a.setConstant("yolo"); + cout << "String tensor: " << endl << a << endl << endl; + => + String tensor: + yolo yolo yolo + yolo yolo yolo + + +### setZero() + +Fills the tensor with zeros. Equivalent to ```setConstant(Scalar(0))```. +Returns the tensor itself in case you want to chain another call. + + a.setZero(); + cout << "Zeros: " << endl << a << endl << endl; + => + Zeros: + 0 0 0 0 + 0 0 0 0 + 0 0 0 0 + + +### setValues({..initializer_list}) + +Fills the tensor with explicit values specified in a std::initializer_list. +The type of the initializer list depends on the type and rank of the tensor. + +If the tensor has rank N, the initializer list must be nested N times. The +most deeply nested lists must contains P scalars of the Tensor type where P is +the size of the last dimension of the Tensor. + +For example, for a ```TensorFixedSize``` the initializer list must +contains 2 lists of 3 floats each. + +```setValues()``` returns the tensor itself in case you want to chain another +call. + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}}); + cout << "a" << endl << a << endl << endl; + => + a + 0 1 2 + 3 4 5 + +If a list is too short, the corresponding elements of the tensor will not be +changed. This is valid at each level of nesting. For example the following +code only sets the values of the first row of the tensor. + + Eigen::Tensor a(2, 3); + a.setConstant(1000); + a.setValues({{10, 20, 30}}); + cout << "a" << endl << a << endl << endl; + => + a + 10 20 30 + 1000 1000 1000 + +### setRandom() + +Fills the tensor with random values. Returns the tensor itself in case you +want to chain another call. + + a.setRandom(); + cout << "Random: " << endl << a << endl << endl; + => + Random: + 0.680375 0.59688 -0.329554 0.10794 + -0.211234 0.823295 0.536459 -0.0452059 + 0.566198 -0.604897 -0.444451 0.257742 + +You can customize ```setRandom()``` by providing your own random number +generator as a template argument: + + a.setRandom(); + +Here, ```MyRandomGenerator``` must be a struct with the following member +functions, where Scalar and Index are the same as ```::Scalar``` +and ```::Index```. + +See ```struct UniformRandomGenerator``` in TensorFunctors.h for an example. + + // Custom number generator for use with setRandom(). + struct MyRandomGenerator { + // Default and copy constructors. Both are needed + MyRandomGenerator() { } + MyRandomGenerator(const MyRandomGenerator& ) { } + + // Return a random value to be used. "element_location" is the + // location of the entry to set in the tensor, it can typically + // be ignored. + Scalar operator()(Eigen::DenseIndex element_location, + Eigen::DenseIndex /*unused*/ = 0) const { + return ; + } + + // Same as above but generates several numbers at a time. + typename internal::packet_traits::type packetOp( + Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const { + return ; + } + }; + +You can also use one of the 2 random number generators that are part of the +tensor library: +* UniformRandomGenerator +* NormalRandomGenerator + + +## Data Access + +The Tensor, TensorFixedSize, and TensorRef classes provide the following +accessors to access the tensor coefficients: + + const Scalar& operator()(const array& indices) + const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + Scalar& operator()(const array& indices) + Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + +The number of indices must be equal to the rank of the tensor. Moreover, these +accessors are not available on tensor expressions. In order to access the +values of a tensor expression, the expression must either be evaluated or +wrapped in a TensorRef. + + +### Scalar* data() and const Scalar* data() const + +Returns a pointer to the storage for the tensor. The pointer is const if the +tensor was const. This allows direct access to the data. The layout of the +data depends on the tensor layout: RowMajor or ColMajor. + +This access is usually only needed for special cases, for example when mixing +Eigen Tensor code with other libraries. + +Scalar is the type of data stored in the tensor. + + Eigen::Tensor a(3, 4); + float* a_data = a.data(); + a_data[0] = 123.45f; + cout << "a(0, 0): " << a(0, 0); + => a(0, 0): 123.45 + + +## Tensor Operations + +All the methods documented below return non evaluated tensor ```Operations```. +These can be chained: you can apply another Tensor Operation to the value +returned by the method. + +The chain of Operation is evaluated lazily, typically when it is assigned to a +tensor. See "Controlling when Expression are Evaluated" for more details about +their evaluation. + +### constant(const Scalar& val) + +Returns a tensor of the same type and dimensions as the original tensor but +where all elements have the value ```val```. + +This is useful, for example, when you want to add or subtract a constant from a +tensor, or multiply every element of a tensor by a scalar. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = a + a.constant(2.0f); + Eigen::Tensor c = b * b.constant(0.2f); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + cout << "c" << endl << c << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + 3 3 3 + 3 3 3 + + c + 0.6 0.6 0.6 + 0.6 0.6 0.6 + +### random() + +Returns a tensor of the same type and dimensions as the current tensor +but where all elements have random values. + +This is for example useful to add random values to an existing tensor. +The generation of random values can be customized in the same manner +as for ```setRandom()```. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = a + a.random(); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + 1.68038 1.5662 1.82329 + 0.788766 1.59688 0.395103 + + +## Unary Element Wise Operations + +All these operations take a single input tensor as argument and return a tensor +of the same type and dimensions as the tensor to which they are applied. The +requested operations are applied to each element independently. + +### operator-() + +Returns a tensor of the same type and dimensions as the original tensor +containing the opposite values of the original tensor. + + Eigen::Tensor a(2, 3); + a.setConstant(1.0f); + Eigen::Tensor b = -a; + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 1 1 + 1 1 1 + + b + -1 -1 -1 + -1 -1 -1 + +### sqrt() + +Returns a tensor of the same type and dimensions as the original tensor +containing the square roots of the original tensor. + +### rsqrt() + +Returns a tensor of the same type and dimensions as the original tensor +containing the inverse square roots of the original tensor. + +### square() + +Returns a tensor of the same type and dimensions as the original tensor +containing the squares of the original tensor values. + +### inverse() + +Returns a tensor of the same type and dimensions as the original tensor +containing the inverse of the original tensor values. + +### exp() + +Returns a tensor of the same type and dimensions as the original tensor +containing the exponential of the original tensor. + +### log() + +Returns a tensor of the same type and dimensions as the original tensor +containing the natural logarithms of the original tensor. + +### abs() + +Returns a tensor of the same type and dimensions as the original tensor +containing the absolute values of the original tensor. + +### pow(Scalar exponent) + +Returns a tensor of the same type and dimensions as the original tensor +containing the coefficients of the original tensor to the power of the +exponent. + +The type of the exponent, Scalar, is always the same as the type of the +tensor coefficients. For example, only integer exponents can be used in +conjuntion with tensors of integer values. + +You can use cast() to lift this restriction. For example this computes +cubic roots of an int Tensor: + + Eigen::Tensor a(2, 3); + a.setValues({{0, 1, 8}, {27, 64, 125}}); + Eigen::Tensor b = a.cast().pow(1.0 / 3.0); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 0 1 8 + 27 64 125 + + b + 0 1 2 + 3 4 5 + +### operator * (Scalar scale) + +Multiplies all the coefficients of the input tensor by the provided scale. + +### cwiseMax(Scalar threshold) +TODO + +### cwiseMin(Scalar threshold) +TODO + +### unaryExpr(const CustomUnaryOp& func) +TODO + + +## Binary Element Wise Operations + +These operations take two input tensors as arguments. The 2 input tensors should +be of the same type and dimensions. The result is a tensor of the same +dimensions as the tensors to which they are applied, and unless otherwise +specified it is also of the same type. The requested operations are applied to +each pair of elements independently. + +### operator+(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise sums of the inputs. + +### operator-(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise differences of the inputs. + +### operator*(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise products of the inputs. + +### operator/(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise quotients of the inputs. + +This operator is not supported for integer types. + +### cwiseMax(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise maximums of the inputs. + +### cwiseMin(const OtherDerived& other) + +Returns a tensor of the same type and dimensions as the input tensors +containing the coefficient wise mimimums of the inputs. + +### Logical operators + +The following logical operators are supported as well: + +* operator&&(const OtherDerived& other) +* operator||(const OtherDerived& other) +* operator<(const OtherDerived& other) +* operator<=(const OtherDerived& other) +* operator>(const OtherDerived& other) +* operator>=(const OtherDerived& other) +* operator==(const OtherDerived& other) +* operator!=(const OtherDerived& other) + +They all return a tensor of boolean values. + + +## Selection (select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) + +Selection is a coefficient-wise ternary operator that is the tensor equivalent +to the if-then-else operation. + + Tensor if = ...; + Tensor then = ...; + Tensor else = ...; + Tensor result = if.select(then, else); + +The 3 arguments must be of the same dimensions, which will also be the dimension +of the result. The 'if' tensor must be of type boolean, the 'then' and the +'else' tensor must be of the same type, which will also be the type of the +result. + +Each coefficient in the result is equal to the corresponding coefficient in the +'then' tensor if the corresponding value in the 'if' tensor is true. If not, the +resulting coefficient will come from the 'else' tensor. + + +## Contraction + +Tensor *contractions* are a generalization of the matrix product to the +multidimensional case. + + // Create 2 matrices using tensors of rank 2 + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {6, 5, 4}}); + Eigen::Tensor b(3, 2); + a.setValues({{1, 2}, {4, 5}, {5, 6}}); + + // Compute the traditional matrix product + array, 1> product_dims = { IndexPair(1, 0) }; + Eigen::Tensor AB = a.contract(b, product_dims); + + // Compute the product of the transpose of the matrices + array, 1> transpose_product_dims = { IndexPair(0, 1) }; + Eigen::Tensor AtBt = a.contract(b, transposed_product_dims); + + +## Reduction Operations + +A *Reduction* operation returns a tensor with fewer dimensions than the +original tensor. The values in the returned tensor are computed by applying a +*reduction operator* to slices of values from the original tensor. You specify +the dimensions along which the slices are made. + +The Eigen Tensor library provides a set of predefined reduction operators such +as ```maximum()``` and ```sum()``` and lets you define additional operators by +implementing a few methods from a reductor template. + +### Reduction Dimensions + +All reduction operations take a single parameter of type +```::Dimensions``` which can always be specified as an array of +ints. These are called the "reduction dimensions." The values are the indices +of the dimensions of the input tensor over which the reduction is done. The +parameter can have at most as many element as the rank of the input tensor; +each element must be less than the tensor rank, as it indicates one of the +dimensions to reduce. + +Each dimension of the input tensor should occur at most once in the reduction +dimensions as the implementation does not remove duplicates. + +The order of the values in the reduction dimensions does not affect the +results, but the code may execute faster if you list the dimensions in +increasing order. + +Example: Reduction along one dimension. + + // Create a tensor of 2 dimensions + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {6, 5, 4}}); + // Reduce it along the second dimension (1)... + Eigen::array dims({1 /* dimension to reduce */}); + // ...using the "maximum" operator. + // The result is a tensor with one dimension. The size of + // that dimension is the same as the first (non-reduced) dimension of a. + Eigen::Tensor b = a.maximum(dims); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 2 3 + 6 5 4 + + b + 3 + 6 + +Example: Reduction along two dimensions. + + Eigen::Tensor a(2, 3, 4); + a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f}, + {7.0f, 6.0f, 5.0f, 4.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}, + {{12.0f, 13.0f, 14.0f, 15.0f}, + {19.0f, 18.0f, 17.0f, 16.0f}, + {20.0f, 21.0f, 22.0f, 23.0f}}}); + // The tensor a has 3 dimensions. We reduce along the + // first 2, resulting in a tensor with a single dimension + // of size 4 (the last dimension of a.) + // Note that we pass the array of reduction dimensions + // directly to the maximum() call. + Eigen::Tensor b = + a.maximum(Eigen::array({0, 1})); + cout << "b" << endl << b << endl << endl; + => + b + 20 + 21 + 22 + 23 + +#### Reduction along all dimensions + +As a special case, if you pass no parameter to a reduction operation the +original tensor is reduced along *all* its dimensions. The result is a +scalar, represented as a zero-dimension tensor. + + Eigen::Tensor a(2, 3, 4); + a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f}, + {7.0f, 6.0f, 5.0f, 4.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}, + {{12.0f, 13.0f, 14.0f, 15.0f}, + {19.0f, 18.0f, 17.0f, 16.0f}, + {20.0f, 21.0f, 22.0f, 23.0f}}}); + // Reduce along all dimensions using the sum() operator. + Eigen::Tensor b = a.sum(); + cout << "b" << endl << b << endl << endl; + => + b + 276 + + +### sum(const Dimensions& new_dims) +### sum() + +Reduce a tensor using the sum() operator. The resulting values +are the sum of the reduced values. + +### mean(const Dimensions& new_dims) +### mean() + +Reduce a tensor using the mean() operator. The resulting values +are the mean of the reduced values. + +### maximum(const Dimensions& new_dims) +### maximum() + +Reduce a tensor using the maximum() operator. The resulting values are the +largest of the reduced values. + +### minimum(const Dimensions& new_dims) +### minimum() + +Reduce a tensor using the minimum() operator. The resulting values +are the smallest of the reduced values. + +### prod(const Dimensions& new_dims) +### prod() + +Reduce a tensor using the prod() operator. The resulting values +are the product of the reduced values. + +### all(const Dimensions& new_dims) +### all() +Reduce a tensor using the all() operator. Casts tensor to bool and then checks +whether all elements are true. Runs through all elements rather than +short-circuiting, so may be significantly inefficient. + +### any(const Dimensions& new_dims) +### any() +Reduce a tensor using the any() operator. Casts tensor to bool and then checks +whether any element is true. Runs through all elements rather than +short-circuiting, so may be significantly inefficient. + + +### reduce(const Dimensions& new_dims, const Reducer& reducer) + +Reduce a tensor using a user-defined reduction operator. See ```SumReducer``` +in TensorFunctors.h for information on how to implement a reduction operator. + + +## Scan Operations + +A *Scan* operation returns a tensor with the same dimensions as the original +tensor. The operation performs an inclusive scan along the specified +axis, which means it computes a running total along the axis for a given +reduction operation. +If the reduction operation corresponds to summation, then this computes the +prefix sum of the tensor along the given axis. + +Example: +dd a comment to this line + + // Create a tensor of 2 dimensions + Eigen::Tensor a(2, 3); + a.setValues({{1, 2, 3}, {4, 5, 6}}); + // Scan it along the second dimension (1) using summation + Eigen::Tensor b = a.cumsum(1); + // The result is a tensor with the same size as the input + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 1 2 3 + 6 5 4 + + b + 1 3 6 + 4 9 15 + +### cumsum(const Index& axis) + +Perform a scan by summing consecutive entries. + +### cumprod(const Index& axis) + +Perform a scan by multiplying consecutive entries. + + +## Convolutions + +### convolve(const Kernel& kernel, const Dimensions& dims) + +Returns a tensor that is the output of the convolution of the input tensor with the kernel, +along the specified dimensions of the input tensor. The dimension size for dimensions of the output tensor +which were part of the convolution will be reduced by the formula: +output_dim_size = input_dim_size - kernel_dim_size + 1 (requires: input_dim_size >= kernel_dim_size). +The dimension sizes for dimensions that were not part of the convolution will remain the same. +Performance of the convolution can depend on the length of the stride(s) of the input tensor dimension(s) along which the +convolution is computed (the first dimension has the shortest stride for ColMajor, whereas RowMajor's shortest stride is +for the last dimension). + + // Compute convolution along the second and third dimension. + Tensor input(3, 3, 7, 11); + Tensor kernel(2, 2); + Tensor output(3, 2, 6, 11); + input.setRandom(); + kernel.setRandom(); + + Eigen::array dims({1, 2}); // Specify second and third dimension for convolution. + output = input.convolve(kernel, dims); + + for (int i = 0; i < 3; ++i) { + for (int j = 0; j < 2; ++j) { + for (int k = 0; k < 6; ++k) { + for (int l = 0; l < 11; ++l) { + const float result = output(i,j,k,l); + const float expected = input(i,j+0,k+0,l) * kernel(0,0) + + input(i,j+1,k+0,l) * kernel(1,0) + + input(i,j+0,k+1,l) * kernel(0,1) + + input(i,j+1,k+1,l) * kernel(1,1); + VERIFY_IS_APPROX(result, expected); + } + } + } + } + + +## Geometrical Operations + +These operations return a Tensor with different dimensions than the original +Tensor. They can be used to access slices of tensors, see them with different +dimensions, or pad tensors with additional data. + +### reshape(const Dimensions& new_dims) + +Returns a view of the input tensor that has been reshaped to the specified +new dimensions. The argument new_dims is an array of Index values. The +rank of the resulting tensor is equal to the number of elements in new_dims. + +The product of all the sizes in the new dimension array must be equal to +the number of elements in the input tensor. + + // Increase the rank of the input tensor by introducing a new dimension + // of size 1. + Tensor input(7, 11); + array three_dims{{7, 11, 1}}; + Tensor result = input.reshape(three_dims); + + // Decrease the rank of the input tensor by merging 2 dimensions; + array one_dim{{7 * 11}}; + Tensor result = input.reshape(one_dim); + +This operation does not move any data in the input tensor, so the resulting +contents of a reshaped Tensor depend on the data layout of the original Tensor. + +For example this is what happens when you ```reshape()``` a 2D ColMajor tensor +to one dimension: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array one_dim({3 * 2}); + Eigen::Tensor b = a.reshape(one_dim); + cout << "b" << endl << b << endl; + => + b + 0 + 300 + 100 + 400 + 200 + 500 + +This is what happens when the 2D Tensor is RowMajor: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array one_dim({3 * 2}); + Eigen::Tensor b = a.reshape(one_dim); + cout << "b" << endl << b << endl; + => + b + 0 + 100 + 200 + 300 + 400 + 500 + +The reshape operation is a lvalue. In other words, it can be used on the left +side of the assignment operator. + +The previous example can be rewritten as follow: + + Eigen::Tensor a(2, 3); + a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}}); + Eigen::array two_dim({2, 3}); + Eigen::Tensor b; + b.reshape(two_dim) = a; + cout << "b" << endl << b << endl; + => + b + 0 + 300 + 100 + 400 + 200 + 500 + +Note that "b" itself was not reshaped but that instead the assignment is done to +the reshape view of b. + + +### shuffle(const Shuffle& shuffle) + +Returns a copy of the input tensor whose dimensions have been +reordered according to the specified permutation. The argument shuffle +is an array of Index values. Its size is the rank of the input +tensor. It must contain a permutation of 0, 1, ..., rank - 1. The i-th +dimension of the output tensor equals to the size of the shuffle[i]-th +dimension of the input tensor. For example: + + // Shuffle all dimensions to the left by 1. + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output = input.shuffle({1, 2, 0}) + + eigen_assert(output.dimension(0) == 30); + eigen_assert(output.dimension(1) == 50); + eigen_assert(output.dimension(2) == 20); + +Indices into the output tensor are shuffled accordingly to formulate +indices into the input tensor. For example, one can assert in the above +code snippet that: + + eigen_assert(output(3, 7, 11) == input(11, 3, 7)); + +In general, one can assert that + + eigen_assert(output(..., indices[shuffle[i]], ...) == + input(..., indices[i], ...)) + +The shuffle operation results in a lvalue, which means that it can be assigned +to. In other words, it can be used on the left side of the assignment operator. + +Let's rewrite the previous example to take advantage of this feature: + + // Shuffle all dimensions to the left by 1. + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output(30, 50, 20); + output.shuffle({2, 0, 1}) = input; + + +### stride(const Strides& strides) + +Returns a view of the input tensor that strides (skips stride-1 +elements) along each of the dimensions. The argument strides is an +array of Index values. The dimensions of the resulting tensor are +ceil(input_dimensions[i] / strides[i]). + +For example this is what happens when you ```stride()``` a 2D tensor: + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array strides({3, 2}); + Eigen::Tensor b = a.stride(strides); + cout << "b" << endl << b << endl; + => + b + 0 200 + 900 1100 + +It is possible to assign a tensor to a stride: + Tensor input(20, 30, 50); + // ... set some values in input. + Tensor output(40, 90, 200); + output.stride({2, 3, 4}) = input; + + +### slice(const StartIndices& offsets, const Sizes& extents) + +Returns a sub-tensor of the given tensor. For each dimension i, the slice is +made of the coefficients stored between offset[i] and offset[i] + extents[i] in +the input tensor. + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array offsets = {1, 0}; + Eigen::array extents = {2, 2}; + Eigen::Tensor slice = a.slice(offsets, extents); + cout << "a" << endl << a << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + cout << "slice" << endl << slice << endl; + => + slice + 300 400 + 600 700 + + +### chip(const Index offset, const Index dim) + +A chip is a special kind of slice. It is the subtensor at the given offset in +the dimension dim. The returned tensor has one fewer dimension than the input +tensor: the dimension dim is removed. + +For example, a matrix chip would be either a row or a column of the input +matrix. + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::Tensor row_3 = a.chip(2, 0); + Eigen::Tensor col_2 = a.chip(1, 1); + cout << "a" << endl << a << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + cout << "row_3" << endl << row_3 << endl; + => + row_3 + 600 700 800 + cout << "col_2" << endl << col_2 << endl; + => + col_2 + 100 400 700 1000 + +It is possible to assign values to a tensor chip since the chip operation is a +lvalue. For example: + + Eigen::Tensor a(3); + a.setValues({{100, 200, 300}}); + Eigen::Tensor b(2, 3); + b.setZero(); + b.chip(0, 0) = a; + cout << "a" << endl << a << endl; + => + a + 100 + 200 + 300 + cout << "b" << endl << b << endl; + => + b + 100 200 300 + 0 0 0 + + +### reverse(const ReverseDimensions& reverse) + +Returns a view of the input tensor that reverses the order of the coefficients +along a subset of the dimensions. The argument reverse is an array of boolean +values that indicates whether or not the order of the coefficients should be +reversed along each of the dimensions. This operation preserves the dimensions +of the input tensor. + +For example this is what happens when you ```reverse()``` the first dimension +of a 2D tensor: + + Eigen::Tensor a(4, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}, + {600, 700, 800}, {900, 1000, 1100}}); + Eigen::array reverse({true, false}); + Eigen::Tensor b = a.reverse(reverse); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + 600 700 800 + 900 1000 1100 + b + 900 1000 1100 + 600 700 800 + 300 400 500 + 0 100 200 + + +### broadcast(const Broadcast& broadcast) + +Returns a view of the input tensor in which the input is replicated one to many +times. +The broadcast argument specifies how many copies of the input tensor need to be +made in each of the dimensions. + + Eigen::Tensor a(2, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}}); + Eigen::array bcast({3, 2}); + Eigen::Tensor b = a.broadcast(bcast); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + b + 0 100 200 0 100 200 + 300 400 500 300 400 500 + 0 100 200 0 100 200 + 300 400 500 300 400 500 + 0 100 200 0 100 200 + 300 400 500 300 400 500 + +### concatenate(const OtherDerived& other, Axis axis) + +TODO + +### pad(const PaddingDimensions& padding) + +Returns a view of the input tensor in which the input is padded with zeros. + + Eigen::Tensor a(2, 3); + a.setValues({{0, 100, 200}, {300, 400, 500}}); + Eigen::array, 2> paddings; + paddings[0] = make_pair(0, 1); + paddings[1] = make_pair(2, 3); + Eigen::Tensor b = a.pad(paddings); + cout << "a" << endl << a << endl << "b" << endl << b << endl; + => + a + 0 100 200 + 300 400 500 + b + 0 0 0 0 + 0 0 0 0 + 0 100 200 0 + 300 400 500 0 + 0 0 0 0 + 0 0 0 0 + 0 0 0 0 + + +### extract_patches(const PatchDims& patch_dims) + +Returns a tensor of coefficient patches extracted from the input tensor, where +each patch is of dimension specified by 'patch_dims'. The returned tensor has +one greater dimension than the input tensor, which is used to index each patch. +The patch index in the output tensor depends on the data layout of the input +tensor: the patch index is the last dimension ColMajor layout, and the first +dimension in RowMajor layout. + +For example, given the following input tensor: + + Eigen::Tensor tensor(3,4); + tensor.setValues({{0.0f, 1.0f, 2.0f, 3.0f}, + {4.0f, 5.0f, 6.0f, 7.0f}, + {8.0f, 9.0f, 10.0f, 11.0f}}); + + cout << "tensor: " << endl << tensor << endl; +=> +tensor: + 0 1 2 3 + 4 5 6 7 + 8 9 10 11 + +Six 2x2 patches can be extracted and indexed using the following code: + + Eigen::Tensor patch; + Eigen::array patch_dims; + patch_dims[0] = 2; + patch_dims[1] = 2; + patch = tensor.extract_patches(patch_dims); + for (int k = 0; k < 6; ++k) { + cout << "patch index: " << k << endl; + for (int i = 0; i < 2; ++i) { + for (int j = 0; j < 2; ++j) { + if (DataLayout == ColMajor) { + cout << patch(i, j, k) << " "; + } else { + cout << patch(k, i, j) << " "; + } + } + cout << endl; + } + } + +This code results in the following output when the data layout is ColMajor: + +patch index: 0 +0 1 +4 5 +patch index: 1 +4 5 +8 9 +patch index: 2 +1 2 +5 6 +patch index: 3 +5 6 +9 10 +patch index: 4 +2 3 +6 7 +patch index: 5 +6 7 +10 11 + +This code results in the following output when the data layout is RowMajor: +(NOTE: the set of patches is the same as in ColMajor, but are indexed differently). + +patch index: 0 +0 1 +4 5 +patch index: 1 +1 2 +5 6 +patch index: 2 +2 3 +6 7 +patch index: 3 +4 5 +8 9 +patch index: 4 +5 6 +9 10 +patch index: 5 +6 7 +10 11 + +### extract_image_patches(const Index patch_rows, const Index patch_cols, + const Index row_stride, const Index col_stride, + const PaddingType padding_type) + +Returns a tensor of coefficient image patches extracted from the input tensor, +which is expected to have dimensions ordered as follows (depending on the data +layout of the input tensor, and the number of additional dimensions 'N'): + +*) ColMajor +1st dimension: channels (of size d) +2nd dimension: rows (of size r) +3rd dimension: columns (of size c) +4th-Nth dimension: time (for video) or batch (for bulk processing). + +*) RowMajor (reverse order of ColMajor) +1st-Nth dimension: time (for video) or batch (for bulk processing). +N+1'th dimension: columns (of size c) +N+2'th dimension: rows (of size r) +N+3'th dimension: channels (of size d) + +The returned tensor has one greater dimension than the input tensor, which is +used to index each patch. The patch index in the output tensor depends on the +data layout of the input tensor: the patch index is the 4'th dimension in +ColMajor layout, and the 4'th from the last dimension in RowMajor layout. + +For example, given the following input tensor with the following dimension +sizes: + *) depth: 2 + *) rows: 3 + *) columns: 5 + *) batch: 7 + + Tensor tensor(2,3,5,7); + Tensor tensor_row_major = tensor.swap_layout(); + +2x2 image patches can be extracted and indexed using the following code: + +*) 2D patch: ColMajor (patch indexed by second-to-last dimension) + Tensor twod_patch; + twod_patch = tensor.extract_image_patches<2, 2>(); + // twod_patch.dimension(0) == 2 + // twod_patch.dimension(1) == 2 + // twod_patch.dimension(2) == 2 + // twod_patch.dimension(3) == 3*5 + // twod_patch.dimension(4) == 7 + +*) 2D patch: RowMajor (patch indexed by the second dimension) + Tensor twod_patch_row_major; + twod_patch_row_major = tensor_row_major.extract_image_patches<2, 2>(); + // twod_patch_row_major.dimension(0) == 7 + // twod_patch_row_major.dimension(1) == 3*5 + // twod_patch_row_major.dimension(2) == 2 + // twod_patch_row_major.dimension(3) == 2 + // twod_patch_row_major.dimension(4) == 2 + +## Special Operations + +### cast() + +Returns a tensor of type T with the same dimensions as the original tensor. +The returned tensor contains the values of the original tensor converted to +type T. + + Eigen::Tensor a(2, 3); + Eigen::Tensor b = a.cast(); + +This can be useful for example if you need to do element-wise division of +Tensors of integers. This is not currently supported by the Tensor library +but you can easily cast the tensors to floats to do the division: + + Eigen::Tensor a(2, 3); + a.setValues({{0, 1, 2}, {3, 4, 5}}); + Eigen::Tensor b = + (a.cast() / a.constant(2).cast()).cast(); + cout << "a" << endl << a << endl << endl; + cout << "b" << endl << b << endl << endl; + => + a + 0 1 2 + 3 4 5 + + b + 0 0 1 + 1 2 2 + + +### eval() + +TODO + + +## Representation of scalar values + +Scalar values are often represented by tensors of size 1 and rank 1. It would be +more logical and user friendly to use tensors of rank 0 instead. For example +Tensor::maximum() currently returns a Tensor. Similarly, the inner +product of 2 1d tensors (through contractions) returns a 1d tensor. In the +future these operations might be updated to return 0d tensors instead. + +## Limitations + +* The number of tensor dimensions is currently limited to 250 when using a + compiler that supports cxx11. It is limited to only 5 for older compilers. +* The IndexList class requires a cxx11 compliant compiler. You can use an + array of indices instead if you don't have access to a modern compiler. +* On GPUs only floating point values are properly tested and optimized for. +* Complex and integer values are known to be broken on GPUs. If you try to use + them you'll most likely end up triggering a static assertion failure such as + EIGEN_STATIC_ASSERT(packetSize > 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + + diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h new file mode 100644 index 000000000..1940a9692 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h @@ -0,0 +1,527 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2013 Christian Seiler +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_H + +namespace Eigen { + +/** \class Tensor + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor class. + * + * The %Tensor class is the work-horse for all \em dense tensors within Eigen. + * + * The %Tensor class encompasses only dynamic-size objects so far. + * + * The first two template parameters are required: + * \tparam Scalar_ \anchor tensor_tparam_scalar Numeric type, e.g. float, double, int or std::complex. + * User defined scalar types are supported as well (see \ref user_defined_scalars "here"). + * \tparam NumIndices_ Number of indices (i.e. rank of the tensor) + * + * The remaining template parameters are optional -- in most cases you don't have to worry about them. + * \tparam Options_ \anchor tensor_tparam_options A combination of either \b #RowMajor or \b #ColMajor, and of either + * \b #AutoAlign or \b #DontAlign. + * The former controls \ref TopicStorageOrders "storage order", and defaults to column-major. The latter controls alignment, which is required + * for vectorization. It defaults to aligning tensors. Note that tensors currently do not support any operations that profit from vectorization. + * Support for such operations (i.e. adding two tensors etc.) is planned. + * + * You can access elements of tensors using normal subscripting: + * + * \code + * Eigen::Tensor t(10, 10, 10, 10); + * t(0, 1, 2, 3) = 42.0; + * \endcode + * + * This class can be extended with the help of the plugin mechanism described on the page + * \ref TopicCustomizingEigen by defining the preprocessor symbol \c EIGEN_TENSOR_PLUGIN. + * + * Some notes: + * + *

+ *
Relation to other parts of Eigen:
+ *
The midterm developement goal for this class is to have a similar hierarchy as Eigen uses for matrices, so that + * taking blocks or using tensors in expressions is easily possible, including an interface with the vector/matrix code + * by providing .asMatrix() and .asVector() (or similar) methods for rank 2 and 1 tensors. However, currently, the %Tensor + * class does not provide any of these features and is only available as a stand-alone class that just allows for + * coefficient access. Also, when fixed-size tensors are implemented, the number of template arguments is likely to + * change dramatically.
+ *
+ * + * \ref TopicStorageOrders + */ + +template +class Tensor : public TensorBase > +{ + public: + typedef Tensor Self; + typedef TensorBase > Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef Scalar_ Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + enum { + IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0) & !(Options_&DontAlign), + Layout = Options_ & RowMajor ? RowMajor : ColMajor, + CoordAccess = true, + RawAccess = true + }; + + static const int Options = Options_; + static const int NumIndices = NumIndices_; + typedef DSizes Dimensions; + + protected: + TensorStorage m_storage; + +#ifdef EIGEN_HAS_SFINAE + template + struct isOfNormalIndex{ + static const bool is_array = internal::is_base_of, CustomIndices>::value; + static const bool is_int = NumTraits::IsInteger; + static const bool value = is_array | is_int; + }; +#endif + + public: + // Metadata + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const { return NumIndices; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index dimension(std::size_t n) const { return m_storage.dimensions()[n]; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_storage.dimensions(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_storage.size(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } + + // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + // work, because that uses base().coeffRef() - and we don't yet + // implement a similar class hierarchy + inline Self& base() { return *this; } + inline const Self& base() const { return *this; } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC inline const Scalar& coeff(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeff(array{{firstIndex, secondIndex, otherIndices...}}); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(const array& indices) const + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(CustomIndices& indices) const + { + return coeff(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline Scalar& coeffRef(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(array{{firstIndex, secondIndex, otherIndices...}}); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(const array& indices) + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(CustomIndices& indices) + { + return coeffRef(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return this->operator()(array{{firstIndex, secondIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + return coeff(array(i0, i1)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + return coeff(array(i0, i1, i2)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + return coeff(array(i0, i1, i2, i3)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + return coeff(array(i0, i1, i2, i3, i4)); + } +#endif + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(CustomIndices& indices) const + { + return coeff(internal::customIndices2Array(indices)); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + return coeff(indices); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return coeff(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const + { + // The bracket operator is only for vectors, use the parenthesis operator instead. + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(index); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + inline Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return operator()(array{{firstIndex, secondIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + return coeffRef(array(i0, i1)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + return coeffRef(array(i0, i1, i2)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + return coeffRef(array(i0, i1, i2, i3)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + return coeffRef(array(i0, i1, i2, i3, i4)); + } +#endif + + // normal indices + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + return coeffRef(indices); + } + + // custom indices +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(CustomIndices& indices) + { + return coeffRef(internal::customIndices2Array(indices)); + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_assert(index >= 0 && index < size()); + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeffRef(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator[](Index index) + { + // The bracket operator is only for vectors, use the parenthesis operator instead + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor() + : m_storage() + { + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const Self& other) + : m_storage(other.m_storage) + { + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index firstDimension, IndexTypes... otherDimensions) + : m_storage(firstDimension, otherDimensions...) + { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(Index dim1) + : m_storage(dim1, array(dim1)) + { + EIGEN_STATIC_ASSERT(1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2) + : m_storage(dim1*dim2, array(dim1, dim2)) + { + EIGEN_STATIC_ASSERT(2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3) + : m_storage(dim1*dim2*dim3, array(dim1, dim2, dim3)) + { + EIGEN_STATIC_ASSERT(3 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4) + : m_storage(dim1*dim2*dim3*dim4, array(dim1, dim2, dim3, dim4)) + { + EIGEN_STATIC_ASSERT(4 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) + : m_storage(dim1*dim2*dim3*dim4*dim5, array(dim1, dim2, dim3, dim4, dim5)) + { + EIGEN_STATIC_ASSERT(5 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#endif + + /** Normal Dimension */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(const array& dimensions) + : m_storage(internal::array_prod(dimensions), dimensions) + { + EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor& operator=(const Tensor& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Tensor& operator=(const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + resize(TensorEvaluator(assign, DefaultDevice()).dimensions()); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + void resize(Index firstDimension, IndexTypes... otherDimensions) + { + // The number of dimensions used to resize a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + resize(array{{firstDimension, otherDimensions...}}); + } +#endif + + /** Normal Dimension */ + EIGEN_DEVICE_FUNC void resize(const array& dimensions) + { + int i; + Index size = Index(1); + for (i = 0; i < NumIndices; i++) { + internal::check_rows_cols_for_overflow::run(size, dimensions[i]); + size *= dimensions[i]; + } + #ifdef EIGEN_INITIALIZE_COEFFS + bool size_changed = size != this->size(); + m_storage.resize(size, dimensions); + if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + #else + m_storage.resize(size, dimensions); + #endif + } + + // Why this overload, DSizes is derived from array ??? // + EIGEN_DEVICE_FUNC void resize(const DSizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = dimensions[i]; + } + resize(dims); + } + + EIGEN_DEVICE_FUNC + void resize() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + // Nothing to do: rank 0 tensors have fixed size + } + + /** Custom Dimension */ +#ifdef EIGEN_HAS_SFINAE + template::value) ) + > + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(CustomDimension& dimensions) + { + resize(internal::customIndices2Array(dimensions)); + } +#endif + +#ifndef EIGEN_EMULATE_CXX11_META_H + template + EIGEN_DEVICE_FUNC + void resize(const Sizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = static_cast(dimensions[i]); + } + resize(dims); + } +#else + template + EIGEN_DEVICE_FUNC + void resize(const Sizes& dimensions) { + array dims; + for (int i = 0; i < NumIndices; ++i) { + dims[i] = static_cast(dimensions[i]); + } + resize(dims); + } +#endif + + protected: + + bool checkIndexRange(const array& indices) const + { + using internal::array_apply_and_reduce; + using internal::array_zip_and_reduce; + using internal::greater_equal_zero_op; + using internal::logical_and_op; + using internal::lesser_op; + + return + // check whether the indices are all >= 0 + array_apply_and_reduce(indices) && + // check whether the indices fit in the dimensions + array_zip_and_reduce(indices, m_storage.dimensions()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index linearizedIndex(const array& indices) const + { + if (Options&RowMajor) { + return m_storage.dimensions().IndexOfRowMajor(indices); + } else { + return m_storage.dimensions().IndexOfColMajor(indices); + } + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h new file mode 100644 index 000000000..d06f40cd8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h @@ -0,0 +1,299 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Eugene Brevdo +// Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H +#define EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H + +namespace Eigen { +namespace internal { + +/** \class TensorIndexTuple + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor + Index Tuple class. + * + * + */ +template +struct traits > : public traits +{ + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef Tuple Scalar; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorIndexTupleOp& type; +}; + +template +struct nested, 1, + typename eval >::type> +{ + typedef TensorIndexTupleOp type; +}; + +} // end namespace internal + +template +class TensorIndexTupleOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + typedef Tuple CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIndexTupleOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorIndexTupleOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = /*TensorEvaluator::PacketAccess*/ false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return CoeffReturnType(index, m_impl.coeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, 1); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + TensorEvaluator m_impl; +}; + +namespace internal { + +/** \class TensorTupleIndex + * \ingroup CXX11_Tensor_Module + * + * \brief Converts to Tensor > and reduces to Tensor. + * + */ +template +struct traits > : public traits +{ + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef Index Scalar; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions - array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorTupleReducerOp& type; +}; + +template +struct nested, 1, + typename eval >::type> +{ + typedef TensorTupleReducerOp type; +}; + +} // end namespace internal + +template +class TensorTupleReducerOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + typedef Index CoeffReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTupleReducerOp(const XprType& expr, + const ReduceOp& reduce_op, + const int return_dim, + const Dims& reduce_dims) + : m_xpr(expr), m_reduce_op(reduce_op), m_return_dim(return_dim), m_reduce_dims(reduce_dims) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + const ReduceOp& reduce_op() const { return m_reduce_op; } + + EIGEN_DEVICE_FUNC + const Dims& reduce_dims() const { return m_reduce_dims; } + + EIGEN_DEVICE_FUNC + int return_dim() const { return m_return_dim; } + + protected: + typename XprType::Nested m_xpr; + const ReduceOp m_reduce_op; + const int m_return_dim; + const Dims m_reduce_dims; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorTupleReducerOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename TensorIndexTupleOp::CoeffReturnType TupleType; + typedef typename TensorEvaluator >, Device>::Dimensions Dimensions; + typedef typename TensorEvaluator , Device>::Dimensions InputDimensions; + static const int NumDims = internal::array_size::value; + typedef array StrideDims; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = /*TensorEvaluator::PacketAccess*/ false, + BlockAccess = false, + Layout = TensorEvaluator >, Device>::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_orig_impl(op.expression(), device), + m_impl(op.expression().index_tuples().reduce(op.reduce_dims(), op.reduce_op()), device), + m_return_dim(op.return_dim()) { + + gen_strides(m_orig_impl.dimensions(), m_strides); + if (Layout == static_cast(ColMajor)) { + const Index total_size = internal::array_prod(m_orig_impl.dimensions()); + m_stride_mod = (m_return_dim < NumDims - 1) ? m_strides[m_return_dim + 1] : total_size; + } else { + const Index total_size = internal::array_prod(m_orig_impl.dimensions()); + m_stride_mod = (m_return_dim > 0) ? m_strides[m_return_dim - 1] : total_size; + } + m_stride_div = m_strides[m_return_dim]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + const TupleType v = m_impl.coeff(index); + return (m_return_dim < 0) ? v.first : (v.first % m_stride_mod) / m_stride_div; + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double compute_cost = 1.0 + + (m_return_dim < 0 ? 0.0 : (TensorOpCost::ModCost() + TensorOpCost::DivCost())); + return m_orig_impl.costPerCoeff(vectorized) + + m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, compute_cost); + } + + private: + EIGEN_DEVICE_FUNC void gen_strides(const InputDimensions& dims, StrideDims& strides) { + if (m_return_dim < 0) { + return; // Won't be using the strides. + } + eigen_assert(m_return_dim < NumDims && + "Asking to convert index to a dimension outside of the rank"); + + // Calculate m_stride_div and m_stride_mod, which are used to + // calculate the value of an index w.r.t. the m_return_dim. + if (Layout == static_cast(ColMajor)) { + strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + strides[i] = strides[i-1] * dims[i-1]; + } + } else { + strides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + strides[i] = strides[i+1] * dims[i+1]; + } + } + } + + protected: + TensorEvaluator, Device> m_orig_impl; + TensorEvaluator >, Device> m_impl; + const int m_return_dim; + StrideDims m_strides; + Index m_stride_mod; + Index m_stride_div; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h new file mode 100644 index 000000000..166be200c --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h @@ -0,0 +1,181 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H +#define EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H + +namespace Eigen { + +/** \class TensorAssign + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor assignment class. + * + * This class is represents the assignment of the values resulting from the evaluation of + * the rhs expression to the memory locations denoted by the lhs expression. + */ +namespace internal { +template +struct traits > +{ + typedef typename LhsXprType::Scalar Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const std::size_t NumDimensions = internal::traits::NumDimensions; + static const int Layout = internal::traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorAssignOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorAssignOp type; +}; + +} // end namespace internal + + + +template +class TensorAssignOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename LhsXprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorAssignOp(LhsXprType& lhs, const RhsXprType& rhs) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs) {} + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + typename internal::remove_all::type& + lhsExpression() const { return *((typename internal::remove_all::type*)&m_lhs_xpr); } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename internal::remove_all::type& m_lhs_xpr; + const typename internal::remove_all::type& m_rhs_xpr; +}; + + +template +struct TensorEvaluator, Device> +{ + typedef TensorAssignOp XprType; + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + m_leftImpl(op.lhsExpression(), device), + m_rightImpl(op.rhsExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + } + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // The dimensions of the lhs and the rhs tensors should be equal to prevent + // overflows and ensure the result is fully initialized. + // TODO: use left impl instead if right impl dimensions are known at compile time. + return m_rightImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions())); + m_leftImpl.evalSubExprsIfNeeded(NULL); + // If the lhs provides raw access to its storage area (i.e. if m_leftImpl.data() returns a non + // null value), attempt to evaluate the rhs expression in place. Returns true iff in place + // evaluation isn't supported and the caller still needs to manually assign the values generated + // by the rhs to the lhs. + return m_rightImpl.evalSubExprsIfNeeded(m_leftImpl.data()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) { + m_leftImpl.coeffRef(i) = m_rightImpl.coeff(i); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) { + const int LhsStoreMode = TensorEvaluator::IsAligned ? Aligned : Unaligned; + const int RhsLoadMode = TensorEvaluator::IsAligned ? Aligned : Unaligned; + m_leftImpl.template writePacket(i, m_rightImpl.template packet(i)); + } + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_leftImpl.coeff(index); + } + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const + { + return m_leftImpl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // We assume that evalPacket or evalScalar is called to perform the + // assignment and account for the cost of the write here, but reduce left + // cost by one load because we are using m_leftImpl.coeffRef. + TensorOpCost left = m_leftImpl.costPerCoeff(vectorized); + return m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost( + numext::maxi(0.0, left.bytes_loaded() - sizeof(CoeffReturnType)), + left.bytes_stored(), left.compute_cycles()) + + TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize); + } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& left_impl() const { return m_leftImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& right_impl() const { return m_rightImpl; } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_leftImpl.data(); } + + private: + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; +}; + +} + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h new file mode 100644 index 000000000..7a45a5cf4 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h @@ -0,0 +1,1010 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_BASE_H +#define EIGEN_CXX11_TENSOR_TENSOR_BASE_H + +// clang-format off + +namespace Eigen { + +/** \class TensorBase + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor base class. + * + * This class is the common parent of the Tensor and TensorMap class, thus + * making it possible to use either class interchangably in expressions. + */ + +template +class TensorBase +{ + public: + typedef internal::traits DerivedTraits; + typedef typename DerivedTraits::Scalar Scalar; + typedef typename DerivedTraits::Index Index; + typedef typename internal::remove_const::type CoeffReturnType; + static const int NumDimensions = DerivedTraits::NumDimensions; + + // Generic nullary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp + nullaryExpr(const CustomNullaryOp& func) const { + return TensorCwiseNullaryOp(derived(), func); + } + + // Coefficient-wise nullary operators + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp, const Derived> + constant(const Scalar& value) const { + return nullaryExpr(internal::scalar_constant_op(value)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp, const Derived> + random() const { + return nullaryExpr(internal::UniformRandomGenerator()); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseNullaryOp + random(const RandomGenerator& gen = RandomGenerator()) const { + return nullaryExpr(gen); + } + + // Tensor generation + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorGeneratorOp + generate(const Generator& generator) const { + return TensorGeneratorOp(derived(), generator); + } + + // Generic unary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp + unaryExpr(const CustomUnaryOp& func) const { + return TensorCwiseUnaryOp(derived(), func); + } + + // Coefficient-wise unary operators + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + operator-() const { + return unaryExpr(internal::scalar_opposite_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sqrt() const { + return unaryExpr(internal::scalar_sqrt_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sign() const { + return unaryExpr(internal::scalar_sign_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + rsqrt() const { + return unaryExpr(internal::scalar_rsqrt_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + square() const { + return unaryExpr(internal::scalar_square_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + cube() const { + return unaryExpr(internal::scalar_cube_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + inverse() const { + return unaryExpr(internal::scalar_inverse_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + tanh() const { + return unaryExpr(internal::scalar_tanh_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + lgamma() const { + return unaryExpr(internal::scalar_lgamma_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + digamma() const { + return unaryExpr(internal::scalar_digamma_op()); + } + + // igamma(a = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + igamma(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_igamma_op()); + } + + // igammac(a = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + igammac(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_igammac_op()); + } + + // zeta(x = this, q = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + zeta(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_zeta_op()); + } + + // polygamma(n = this, x = other) + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + polygamma(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_polygamma_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + erf() const { + return unaryExpr(internal::scalar_erf_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + erfc() const { + return unaryExpr(internal::scalar_erfc_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + sigmoid() const { + return unaryExpr(internal::scalar_sigmoid_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + exp() const { + return unaryExpr(internal::scalar_exp_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + log() const { + return unaryExpr(internal::scalar_log_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + log1p() const { + return unaryExpr(internal::scalar_log1p_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + abs() const { + return unaryExpr(internal::scalar_abs_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + conjugate() const { + return unaryExpr(internal::scalar_conjugate_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + pow(Scalar exponent) const { + return unaryExpr(internal::bind2nd_op >(exponent)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + real() const { + return unaryExpr(internal::scalar_real_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + imag() const { + return unaryExpr(internal::scalar_imag_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator+ (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator+ (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator- (Scalar rhs) const { + EIGEN_STATIC_ASSERT((NumTraits::IsSigned || internal::is_same >::value), YOU_MADE_A_PROGRAMMING_MISTAKE); + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator- (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator* (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator* (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp >, const Derived> + operator/ (Scalar rhs) const { + return unaryExpr(internal::bind2nd_op >(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE friend + const TensorCwiseUnaryOp >, const Derived> + operator/ (Scalar lhs, const Derived& rhs) { + return rhs.unaryExpr(internal::bind1st_op >(lhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + operator% (Scalar rhs) const { + EIGEN_STATIC_ASSERT(NumTraits::IsInteger, YOU_MADE_A_PROGRAMMING_MISTAKE_TRY_MOD); + return unaryExpr(internal::scalar_mod_op(rhs)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + cwiseMax(Scalar threshold) const { + return cwiseMax(constant(threshold)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + cwiseMin(Scalar threshold) const { + return cwiseMin(constant(threshold)); + } + + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorConversionOp + cast() const { + return TensorConversionOp(derived()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + round() const { + return unaryExpr(internal::scalar_round_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + ceil() const { + return unaryExpr(internal::scalar_ceil_op()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + floor() const { + return unaryExpr(internal::scalar_floor_op()); + } + + // Generic binary operation support. + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp + binaryExpr(const OtherDerived& other, const CustomBinaryOp& func) const { + return TensorCwiseBinaryOp(derived(), other, func); + } + + // Coefficient-wise binary operators. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator+(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_sum_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator-(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_difference_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator*(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_product_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator/(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_quotient_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + cwiseMax(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_max_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + cwiseMin(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_min_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator&&(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_and_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator||(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_or_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp + operator^(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_boolean_xor_op()); + } + + // Comparisons and tests. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator<(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator<=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator>(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator>=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator==(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCwiseBinaryOp, const Derived, const OtherDerived> + operator!=(const OtherDerived& other) const { + return binaryExpr(other.derived(), internal::scalar_cmp_op()); + } + + // comparisons and tests for Scalars + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator<(Scalar threshold) const { + return operator<(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator<=(Scalar threshold) const { + return operator<=(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator>(Scalar threshold) const { + return operator>(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator>=(Scalar threshold) const { + return operator>=(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator==(Scalar threshold) const { + return operator==(constant(threshold)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseBinaryOp, const Derived, const TensorCwiseNullaryOp, const Derived> > + operator!=(Scalar threshold) const { + return operator!=(constant(threshold)); + } + + // Checks + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isnan)() const { + return unaryExpr(internal::scalar_isnan_op()); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isinf)() const { + return unaryExpr(internal::scalar_isinf_op()); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const TensorCwiseUnaryOp, const Derived> + (isfinite)() const { + return unaryExpr(internal::scalar_isfinite_op()); + } + + // Coefficient-wise ternary operators. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSelectOp + select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) const { + return TensorSelectOp(derived(), thenTensor.derived(), elseTensor.derived()); + } + + // Contractions. + typedef Eigen::IndexPair DimensionPair; + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorContractionOp + contract(const OtherDerived& other, const Dimensions& dims) const { + return TensorContractionOp(derived(), other.derived(), dims); + } + + // Convolutions. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConvolutionOp + convolve(const KernelDerived& kernel, const Dimensions& dims) const { + return TensorConvolutionOp(derived(), kernel.derived(), dims); + } + + // Fourier transforms + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorFFTOp + fft(const FFT& fft) const { + return TensorFFTOp(derived(), fft); + } + + // Scan. + typedef TensorScanOp, const Derived> TensorScanSumOp; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanSumOp + cumsum(const Index& axis, bool exclusive = false) const { + return TensorScanSumOp(derived(), axis, exclusive); + } + + typedef TensorScanOp, const Derived> TensorScanProdOp; + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanProdOp + cumprod(const Index& axis, bool exclusive = false) const { + return TensorScanProdOp(derived(), axis, exclusive); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorScanOp + scan(const Index& axis, const Reducer& reducer, bool exclusive = false) const { + return TensorScanOp(derived(), axis, exclusive, reducer); + } + + // Reductions. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + sum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::SumReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + sum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::SumReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + mean(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MeanReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + mean() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MeanReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + prod(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::ProdReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + prod() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::ProdReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + maximum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MaxReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + maximum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MaxReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const Dims, const Derived> + minimum(const Dims& dims) const { + return TensorReductionOp, const Dims, const Derived>(derived(), dims, internal::MinReducer()); + } + + const TensorReductionOp, const DimensionList, const Derived> + minimum() const { + DimensionList in_dims; + return TensorReductionOp, const DimensionList, const Derived>(derived(), in_dims, internal::MinReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp > + all(const Dims& dims) const { + return cast().reduce(dims, internal::AndReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const TensorConversionOp > + all() const { + DimensionList in_dims; + return cast().reduce(in_dims, internal::AndReducer()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp > + any(const Dims& dims) const { + return cast().reduce(dims, internal::OrReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp, const TensorConversionOp > + any() const { + DimensionList in_dims; + return cast().reduce(in_dims, internal::OrReducer()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, const Derived> + argmax() const { + array in_dims; + for (int d = 0; d < NumDimensions; ++d) in_dims[d] = d; + return TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMaxTupleReducer >(), -1, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, const Derived> + argmin() const { + array in_dims; + for (int d = 0; d < NumDimensions; ++d) in_dims[d] = d; + return TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMinTupleReducer >(), -1, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, const Derived> + argmax(const int return_dim) const { + array in_dims; + in_dims[0] = return_dim; + return TensorTupleReducerOp< + internal::ArgMaxTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMaxTupleReducer >(), return_dim, in_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, const Derived> + argmin(const int return_dim) const { + array in_dims; + in_dims[0] = return_dim; + return TensorTupleReducerOp< + internal::ArgMinTupleReducer >, + const array, + const Derived>(derived(), internal::ArgMinTupleReducer >(), return_dim, in_dims); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReductionOp + reduce(const Dims& dims, const Reducer& reducer) const { + return TensorReductionOp(derived(), dims, reducer); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorBroadcastingOp + broadcast(const Broadcast& broadcast) const { + return TensorBroadcastingOp(derived(), broadcast); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConcatenationOp + concatenate(const OtherDerived& other, Axis axis) const { + return TensorConcatenationOp(derived(), other.derived(), axis); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPatchOp + extract_patches(const PatchDims& patch_dims) const { + return TensorPatchOp(derived(), patch_dims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorImagePatchOp + extract_image_patches(const Index patch_rows = 1, const Index patch_cols = 1, + const Index row_stride = 1, const Index col_stride = 1, + const Index in_row_stride = 1, const Index in_col_stride = 1, + const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const { + return TensorImagePatchOp(derived(), patch_rows, patch_cols, row_stride, col_stride, + in_row_stride, in_col_stride, 1, 1, padding_type, padding_value); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorImagePatchOp + extract_image_patches(const Index patch_rows, const Index patch_cols, + const Index row_stride, const Index col_stride, + const Index in_row_stride, const Index in_col_stride, + const Index row_inflate_stride, const Index col_inflate_stride, + const Index padding_top, const Index padding_bottom, + const Index padding_left,const Index padding_right, + const Scalar padding_value) const { + return TensorImagePatchOp(derived(), patch_rows, patch_cols, row_stride, col_stride, + in_row_stride, in_col_stride, row_inflate_stride, col_inflate_stride, + padding_top, padding_bottom, padding_left, padding_right, padding_value); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorVolumePatchOp + extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols, + const Index plane_stride = 1, const Index row_stride = 1, const Index col_stride = 1, + const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const { + return TensorVolumePatchOp(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, 1, 1, 1, padding_type, padding_value); + } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorVolumePatchOp + extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols, + const Index plane_stride, const Index row_stride, const Index col_stride, + const Index plane_inflate_stride, const Index row_inflate_stride, const Index col_inflate_stride, + const Index padding_top_z, const Index padding_bottom_z, + const Index padding_top, const Index padding_bottom, + const Index padding_left, const Index padding_right, const Scalar padding_value = Scalar(0)) const { + return TensorVolumePatchOp(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, plane_inflate_stride, row_inflate_stride, col_inflate_stride, padding_top_z, padding_bottom_z, padding_top, padding_bottom, padding_left, padding_right, padding_value); + } + + // Morphing operators. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorLayoutSwapOp + swap_layout() const { + return TensorLayoutSwapOp(derived()); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReshapingOp + reshape(const NewDimensions& newDimensions) const { + return TensorReshapingOp(derived(), newDimensions); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) const { + return TensorSlicingOp(derived(), startIndices, sizes); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset) const { + return TensorChippingOp(derived(), offset, DimId); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset, const Index dim) const { + return TensorChippingOp(derived(), offset, dim); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReverseOp + reverse(const ReverseDimensions& rev) const { + return TensorReverseOp(derived(), rev); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPaddingOp + pad(const PaddingDimensions& padding) const { + return TensorPaddingOp(derived(), padding, internal::scalar_cast_op()(0)); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorPaddingOp + pad(const PaddingDimensions& padding, const Scalar padding_value) const { + return TensorPaddingOp(derived(), padding, padding_value); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorShufflingOp + shuffle(const Shuffle& shuffle) const { + return TensorShufflingOp(derived(), shuffle); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingOp + stride(const Strides& strides) const { + return TensorStridingOp(derived(), strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorInflationOp + inflate(const Strides& strides) const { + return TensorInflationOp(derived(), strides); + } + + // Returns a tensor containing index/value tuples + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorIndexTupleOp + index_tuples() const { + return TensorIndexTupleOp(derived()); + } + + // Support for custom unary and binary operations + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCustomUnaryOp customOp(const CustomUnaryFunc& op) const { + return TensorCustomUnaryOp(derived(), op); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorCustomBinaryOp customOp(const OtherDerived& other, const CustomBinaryFunc& op) const { + return TensorCustomBinaryOp(derived(), other, op); + } + + // Force the evaluation of the expression. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorForcedEvalOp eval() const { + return TensorForcedEvalOp(derived()); + } + + protected: + template friend class Tensor; + template friend class TensorFixedSize; + template friend class TensorBase; + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast(this); } +}; + +template::value> +class TensorBase : public TensorBase { + public: + typedef internal::traits DerivedTraits; + typedef typename DerivedTraits::Scalar Scalar; + typedef typename DerivedTraits::Index Index; + typedef Scalar CoeffReturnType; + static const int NumDimensions = DerivedTraits::NumDimensions; + + template friend class Tensor; + template friend class TensorFixedSize; + template friend class TensorBase; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setZero() { + return setConstant(Scalar(0)); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setConstant(const Scalar& val) { + return derived() = this->constant(val); + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setRandom() { + return derived() = this->random(); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setRandom() { + return derived() = this->template random(); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& setValues( + const typename internal::Initializer::InitList& vals) { + TensorEvaluator eval(derived(), DefaultDevice()); + internal::initialize_tensor(eval, vals); + return derived(); + } +#endif // EIGEN_HAS_VARIADIC_TEMPLATES + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator+=(const OtherDerived& other) { + return derived() = derived() + other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator-=(const OtherDerived& other) { + return derived() = derived() - other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator*=(const OtherDerived& other) { + return derived() = derived() * other.derived(); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Derived& operator/=(const OtherDerived& other) { + return derived() = derived() / other.derived(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorLayoutSwapOp + swap_layout() const { + return TensorLayoutSwapOp(derived()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorLayoutSwapOp + swap_layout() { + return TensorLayoutSwapOp(derived()); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorConcatenationOp + concatenate(const OtherDerived& other, const Axis& axis) const { + return TensorConcatenationOp(derived(), other, axis); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorConcatenationOp + concatenate(const OtherDerived& other, const Axis& axis) { + return TensorConcatenationOp(derived(), other, axis); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReshapingOp + reshape(const NewDimensions& newDimensions) const { + return TensorReshapingOp(derived(), newDimensions); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReshapingOp + reshape(const NewDimensions& newDimensions) { + return TensorReshapingOp(derived(), newDimensions); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) const { + return TensorSlicingOp(derived(), startIndices, sizes); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorSlicingOp + slice(const StartIndices& startIndices, const Sizes& sizes) { + return TensorSlicingOp(derived(), startIndices, sizes); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorStridingSlicingOp + stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) { + return TensorStridingSlicingOp(derived(), startIndices, stopIndices, strides); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset) const { + return TensorChippingOp(derived(), offset, DimId); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorChippingOp + chip(const Index offset) { + return TensorChippingOp(derived(), offset, DimId); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorChippingOp + chip(const Index offset, const Index dim) const { + return TensorChippingOp(derived(), offset, dim); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorChippingOp + chip(const Index offset, const Index dim) { + return TensorChippingOp(derived(), offset, dim); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorReverseOp + reverse(const ReverseDimensions& rev) const { + return TensorReverseOp(derived(), rev); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReverseOp + reverse(const ReverseDimensions& rev) { + return TensorReverseOp(derived(), rev); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorShufflingOp + shuffle(const Shuffle& shuffle) const { + return TensorShufflingOp(derived(), shuffle); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorShufflingOp + shuffle(const Shuffle& shuffle) { + return TensorShufflingOp(derived(), shuffle); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const TensorStridingOp + stride(const Strides& strides) const { + return TensorStridingOp(derived(), strides); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorStridingOp + stride(const Strides& strides) { + return TensorStridingOp(derived(), strides); + } + + // Select the device on which to evaluate the expression. + template + TensorDevice device(const DeviceType& device) { + return TensorDevice(device, derived()); + } + + protected: + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Derived& derived() { return *static_cast(this); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast(this); } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_BASE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h new file mode 100644 index 000000000..4cfe300eb --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h @@ -0,0 +1,392 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H +#define EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H + +namespace Eigen { + +/** \class TensorBroadcasting + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor broadcasting class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorBroadcastingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorBroadcastingOp type; +}; + +template +struct is_input_scalar { + static const bool value = false; +}; +template <> +struct is_input_scalar > { + static const bool value = true; +}; +#ifndef EIGEN_EMULATE_CXX11_META_H +template +struct is_input_scalar > { + static const bool value = (Sizes::total_size == 1); +}; +#endif + +} // end namespace internal + + + +template +class TensorBroadcastingOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBroadcastingOp(const XprType& expr, const Broadcast& broadcast) + : m_xpr(expr), m_broadcast(broadcast) {} + + EIGEN_DEVICE_FUNC + const Broadcast& broadcast() const { return m_broadcast; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Broadcast m_broadcast; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorBroadcastingOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions InputDimensions; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_broadcast(op.broadcast()),m_impl(op.expression(), device) + { + // The broadcasting op doesn't change the rank of the tensor. One can't broadcast a scalar + // and store the result in a scalar. Instead one should reshape the scalar into a a N-D + // tensor with N >= 1 of 1 element first and then broadcast. + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + const InputDimensions& input_dims = m_impl.dimensions(); + const Broadcast& broadcast = op.broadcast(); + for (int i = 0; i < NumDims; ++i) { + eigen_assert(input_dims[i] > 0); + m_dimensions[i] = input_dims[i] * broadcast[i]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + } else { + m_inputStrides[NumDims-1] = 1; + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims-2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const + { + if (internal::is_input_scalar::type>::value) { + return m_impl.coeff(0); + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + return coeffColMajor(index); + } else { + return coeffRowMajor(index); + } + } + + // TODO: attempt to speed this up. The integer divisions and modulo are slow + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffColMajor(Index index) const + { + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index < m_impl.dimensions()[0]); + inputIndex += index; + } else { + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index % m_impl.dimensions()[0] == 0); + } else { + inputIndex += (index % m_impl.dimensions()[0]); + } + } + return m_impl.coeff(inputIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffRowMajor(Index index) const + { + Index inputIndex = 0; + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index < m_impl.dimensions()[NumDims-1]); + inputIndex += index; + } else { + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0); + } else { + inputIndex += (index % m_impl.dimensions()[NumDims-1]); + } + } + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType packet(Index index) const + { + if (internal::is_input_scalar::type>::value) { + return internal::pset1(m_impl.coeff(0)); + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + return packetColMajor(index); + } else { + return packetRowMajor(index); + } + } + + // Ignore the LoadMode and always use unaligned loads since we can't guarantee + // the alignment at compile time. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index originalIndex = index; + + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + Index innermostLoc; + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index < m_impl.dimensions()[0]); + innermostLoc = index; + } else { + if (internal::index_statically_eq(0, 1)) { + eigen_assert(index % m_impl.dimensions()[0] == 0); + innermostLoc = 0; + } else { + innermostLoc = index % m_impl.dimensions()[0]; + } + } + inputIndex += innermostLoc; + + // Todo: this could be extended to the second dimension if we're not + // broadcasting alongside the first dimension, and so on. + if (innermostLoc + PacketSize <= m_impl.dimensions()[0]) { + return m_impl.template packet(inputIndex); + } else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + values[0] = m_impl.coeff(inputIndex); + for (int i = 1; i < PacketSize; ++i) { + values[i] = coeffColMajor(originalIndex+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index originalIndex = index; + + Index inputIndex = 0; + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx < m_impl.dimensions()[i]); + inputIndex += idx * m_inputStrides[i]; + } else { + if (internal::index_statically_eq(i, 1)) { + eigen_assert(idx % m_impl.dimensions()[i] == 0); + } else { + inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i]; + } + } + index -= idx * m_outputStrides[i]; + } + Index innermostLoc; + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index < m_impl.dimensions()[NumDims-1]); + innermostLoc = index; + } else { + if (internal::index_statically_eq(NumDims-1, 1)) { + eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0); + innermostLoc = 0; + } else { + innermostLoc = index % m_impl.dimensions()[NumDims-1]; + } + } + inputIndex += innermostLoc; + + // Todo: this could be extended to the second dimension if we're not + // broadcasting alongside the first dimension, and so on. + if (innermostLoc + PacketSize <= m_impl.dimensions()[NumDims-1]) { + return m_impl.template packet(inputIndex); + } else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + values[0] = m_impl.coeff(inputIndex); + for (int i = 1; i < PacketSize; ++i) { + values[i] = coeffRowMajor(originalIndex+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + double compute_cost = TensorOpCost::AddCost(); + if (NumDims > 0) { + for (int i = NumDims - 1; i > 0; --i) { + compute_cost += TensorOpCost::DivCost(); + if (internal::index_statically_eq(i, 1)) { + compute_cost += + TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } else { + if (!internal::index_statically_eq(i, 1)) { + compute_cost += TensorOpCost::MulCost() + + TensorOpCost::ModCost() + + TensorOpCost::AddCost(); + } + } + compute_cost += + TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } + } + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + const TensorEvaluator& impl() const { return m_impl; } + + Broadcast functor() const { return m_broadcast; } + + protected: + const Broadcast m_broadcast; + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h new file mode 100644 index 000000000..1ba7ef170 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h @@ -0,0 +1,384 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H +#define EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H + +namespace Eigen { + +/** \class TensorKChippingReshaping + * \ingroup CXX11_Tensor_Module + * + * \brief A chip is a thin slice, corresponding to a column or a row in a 2-d tensor. + * + * + */ + +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions - 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorChippingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorChippingOp type; +}; + +template +struct DimensionId +{ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) { + eigen_assert(dim == DimId); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const { + return DimId; + } +}; +template <> +struct DimensionId +{ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) : actual_dim(dim) { + eigen_assert(dim >= 0); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const { + return actual_dim; + } + private: + const DenseIndex actual_dim; +}; + + +} // end namespace internal + + + +template +class TensorChippingOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorChippingOp(const XprType& expr, const Index offset, const Index dim) + : m_xpr(expr), m_offset(offset), m_dim(dim) { + } + + EIGEN_DEVICE_FUNC + const Index offset() const { return m_offset; } + EIGEN_DEVICE_FUNC + const Index dim() const { return m_dim.actualDim(); } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorChippingOp& operator = (const TensorChippingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorChippingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const Index m_offset; + const internal::DimensionId m_dim; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorChippingOp XprType; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims-1; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets. + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_dim(op.dim()), m_device(device) + { + EIGEN_STATIC_ASSERT((NumInputDims >= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(NumInputDims > m_dim.actualDim()); + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + eigen_assert(op.offset() < input_dims[m_dim.actualDim()]); + + int j = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (i != m_dim.actualDim()) { + m_dimensions[j] = input_dims[i]; + ++j; + } + } + + m_stride = 1; + m_inputStride = 1; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < m_dim.actualDim(); ++i) { + m_stride *= input_dims[i]; + m_inputStride *= input_dims[i]; + } + } else { + for (int i = NumInputDims-1; i > m_dim.actualDim(); --i) { + m_stride *= input_dims[i]; + m_inputStride *= input_dims[i]; + } + } + m_inputStride *= input_dims[m_dim.actualDim()]; + m_inputOffset = m_stride * op.offset(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(m_stride == 1); + Index inputIndex = index * m_inputStride + m_inputOffset; + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = m_impl.coeff(inputIndex); + inputIndex += m_inputStride; + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } else if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumInputDims - 1) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(m_stride > index); + return m_impl.template packet(index + m_inputOffset); + } else { + const Index idx = index / m_stride; + const Index rem = index - idx * m_stride; + if (rem + PacketSize <= m_stride) { + Index inputIndex = idx * m_inputStride + m_inputOffset + rem; + return m_impl.template packet(inputIndex); + } else { + // Cross the stride boundary. Fallback to slow path. + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index); + ++index; + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + double cost = 0; + if ((static_cast(Layout) == static_cast(ColMajor) && + m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && + m_dim.actualDim() == NumInputDims - 1)) { + cost += TensorOpCost::MulCost() + TensorOpCost::AddCost(); + } else if ((static_cast(Layout) == static_cast(ColMajor) && + m_dim.actualDim() == NumInputDims - 1) || + (static_cast(Layout) == static_cast(RowMajor) && + m_dim.actualDim() == 0)) { + cost += TensorOpCost::AddCost(); + } else { + cost += 3 * TensorOpCost::MulCost() + TensorOpCost::DivCost() + + 3 * TensorOpCost::AddCost(); + } + + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { + CoeffReturnType* result = const_cast(m_impl.data()); + if (((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumDims) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) && + result) { + return result + m_inputOffset; + } else { + return NULL; + } + } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex; + if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == 0) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(m_stride == 1); + inputIndex = index * m_inputStride + m_inputOffset; + } else if ((static_cast(Layout) == static_cast(ColMajor) && m_dim.actualDim() == NumInputDims-1) || + (static_cast(Layout) == static_cast(RowMajor) && m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(m_stride > index); + inputIndex = index + m_inputOffset; + } else { + const Index idx = index / m_stride; + inputIndex = idx * m_inputStride + m_inputOffset; + index -= idx * m_stride; + inputIndex += index; + } + return inputIndex; + } + + Dimensions m_dimensions; + Index m_stride; + Index m_inputOffset; + Index m_inputStride; + TensorEvaluator m_impl; + const internal::DimensionId m_dim; + const Device& m_device; +}; + + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorChippingOp XprType; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims-1; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + + if ((static_cast(this->Layout) == static_cast(ColMajor) && this->m_dim.actualDim() == 0) || + (static_cast(this->Layout) == static_cast(RowMajor) && this->m_dim.actualDim() == NumInputDims-1)) { + // m_stride is equal to 1, so let's avoid the integer division. + eigen_assert(this->m_stride == 1); + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + internal::pstore(values, x); + Index inputIndex = index * this->m_inputStride + this->m_inputOffset; + for (int i = 0; i < PacketSize; ++i) { + this->m_impl.coeffRef(inputIndex) = values[i]; + inputIndex += this->m_inputStride; + } + } else if ((static_cast(this->Layout) == static_cast(ColMajor) && this->m_dim.actualDim() == NumInputDims-1) || + (static_cast(this->Layout) == static_cast(RowMajor) && this->m_dim.actualDim() == 0)) { + // m_stride is aways greater than index, so let's avoid the integer division. + eigen_assert(this->m_stride > index); + this->m_impl.template writePacket(index + this->m_inputOffset, x); + } else { + const Index idx = index / this->m_stride; + const Index rem = index - idx * this->m_stride; + if (rem + PacketSize <= this->m_stride) { + const Index inputIndex = idx * this->m_inputStride + this->m_inputOffset + rem; + this->m_impl.template writePacket(inputIndex, x); + } else { + // Cross stride boundary. Fallback to slow path. + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + internal::pstore(values, x); + for (int i = 0; i < PacketSize; ++i) { + this->coeffRef(index) = values[i]; + ++index; + } + } + } + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h new file mode 100644 index 000000000..59bf90d93 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h @@ -0,0 +1,361 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H + +namespace Eigen { + +/** \class TensorConcatenationOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor concatenation class. + * + * + */ +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename promote_storage_type::ret Scalar; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + enum { Flags = 0 }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConcatenationOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConcatenationOp type; +}; + +} // end namespace internal + + +template +class TensorConcatenationOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::nested::type Nested; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename NumTraits::Real RealScalar; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConcatenationOp(const LhsXprType& lhs, const RhsXprType& rhs, Axis axis) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_axis(axis) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + EIGEN_DEVICE_FUNC const Axis& axis() const { return m_axis; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorConcatenationOp& operator = (const TensorConcatenationOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorConcatenationOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const Axis m_axis; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorConcatenationOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + static const int RightNumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_leftImpl(op.lhsExpression(), device), m_rightImpl(op.rhsExpression(), device), m_axis(op.axis()) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || NumDims == 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((NumDims == RightNumDims), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + + eigen_assert(0 <= m_axis && m_axis < NumDims); + const Dimensions& lhs_dims = m_leftImpl.dimensions(); + const Dimensions& rhs_dims = m_rightImpl.dimensions(); + { + int i = 0; + for (; i < m_axis; ++i) { + eigen_assert(lhs_dims[i] > 0); + eigen_assert(lhs_dims[i] == rhs_dims[i]); + m_dimensions[i] = lhs_dims[i]; + } + eigen_assert(lhs_dims[i] > 0); // Now i == m_axis. + eigen_assert(rhs_dims[i] > 0); + m_dimensions[i] = lhs_dims[i] + rhs_dims[i]; + for (++i; i < NumDims; ++i) { + eigen_assert(lhs_dims[i] > 0); + eigen_assert(lhs_dims[i] == rhs_dims[i]); + m_dimensions[i] = lhs_dims[i]; + } + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_leftStrides[0] = 1; + m_rightStrides[0] = 1; + m_outputStrides[0] = 1; + + for (int j = 1; j < NumDims; ++j) { + m_leftStrides[j] = m_leftStrides[j-1] * lhs_dims[j-1]; + m_rightStrides[j] = m_rightStrides[j-1] * rhs_dims[j-1]; + m_outputStrides[j] = m_outputStrides[j-1] * m_dimensions[j-1]; + } + } else { + m_leftStrides[NumDims - 1] = 1; + m_rightStrides[NumDims - 1] = 1; + m_outputStrides[NumDims - 1] = 1; + + for (int j = NumDims - 2; j >= 0; --j) { + m_leftStrides[j] = m_leftStrides[j+1] * lhs_dims[j+1]; + m_rightStrides[j] = m_rightStrides[j+1] * rhs_dims[j+1]; + m_outputStrides[j] = m_outputStrides[j+1] * m_dimensions[j+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + // TODO(phli): Add short-circuit memcpy evaluation if underlying data are linear? + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) + { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() + { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + // TODO(phli): attempt to speed this up. The integer divisions and modulo are slow. + // See CL/76180724 comments for more ideas. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + // Collect dimension-wise indices (subs). + array subs; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + subs[i] = index / m_outputStrides[i]; + index -= subs[i] * m_outputStrides[i]; + } + subs[0] = index; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + subs[i] = index / m_outputStrides[i]; + index -= subs[i] * m_outputStrides[i]; + } + subs[NumDims - 1] = index; + } + + const Dimensions& left_dims = m_leftImpl.dimensions(); + if (subs[m_axis] < left_dims[m_axis]) { + Index left_index; + if (static_cast(Layout) == static_cast(ColMajor)) { + left_index = subs[0]; + for (int i = 1; i < NumDims; ++i) { + left_index += (subs[i] % left_dims[i]) * m_leftStrides[i]; + } + } else { + left_index = subs[NumDims - 1]; + for (int i = NumDims - 2; i >= 0; --i) { + left_index += (subs[i] % left_dims[i]) * m_leftStrides[i]; + } + } + return m_leftImpl.coeff(left_index); + } else { + subs[m_axis] -= left_dims[m_axis]; + const Dimensions& right_dims = m_rightImpl.dimensions(); + Index right_index; + if (static_cast(Layout) == static_cast(ColMajor)) { + right_index = subs[0]; + for (int i = 1; i < NumDims; ++i) { + right_index += (subs[i] % right_dims[i]) * m_rightStrides[i]; + } + } else { + right_index = subs[NumDims - 1]; + for (int i = NumDims - 2; i >= 0; --i) { + right_index += (subs[i] % right_dims[i]) * m_rightStrides[i]; + } + } + return m_rightImpl.coeff(right_index); + } + } + + // TODO(phli): Add a real vectorization. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + packetSize - 1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + for (int i = 0; i < packetSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (2 * TensorOpCost::AddCost() + + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost() + + TensorOpCost::ModCost()); + const double lhs_size = m_leftImpl.dimensions().TotalSize(); + const double rhs_size = m_rightImpl.dimensions().TotalSize(); + return (lhs_size / (lhs_size + rhs_size)) * + m_leftImpl.costPerCoeff(vectorized) + + (rhs_size / (lhs_size + rhs_size)) * + m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_leftStrides; + array m_rightStrides; + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; + const Axis m_axis; +}; + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorConcatenationOp XprType; + typedef typename Base::Dimensions Dimensions; + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(XprType& op, const Device& device) + : Base(op, device) + { + EIGEN_STATIC_ASSERT((static_cast(Layout) == static_cast(ColMajor)), YOU_MADE_A_PROGRAMMING_MISTAKE); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + // Collect dimension-wise indices (subs). + array subs; + for (int i = Base::NumDims - 1; i > 0; --i) { + subs[i] = index / this->m_outputStrides[i]; + index -= subs[i] * this->m_outputStrides[i]; + } + subs[0] = index; + + const Dimensions& left_dims = this->m_leftImpl.dimensions(); + if (subs[this->m_axis] < left_dims[this->m_axis]) { + Index left_index = subs[0]; + for (int i = 1; i < Base::NumDims; ++i) { + left_index += (subs[i] % left_dims[i]) * this->m_leftStrides[i]; + } + return this->m_leftImpl.coeffRef(left_index); + } else { + subs[this->m_axis] -= left_dims[this->m_axis]; + const Dimensions& right_dims = this->m_rightImpl.dimensions(); + Index right_index = subs[0]; + for (int i = 1; i < Base::NumDims; ++i) { + right_index += (subs[i] % right_dims[i]) * this->m_rightStrides[i]; + } + return this->m_rightImpl.coeffRef(right_index); + } + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + packetSize - 1 < this->dimensions().TotalSize()); + + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + internal::pstore(values, x); + for (int i = 0; i < packetSize; ++i) { + coeffRef(index+i) = values[i]; + } + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h new file mode 100644 index 000000000..20b29e5fd --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h @@ -0,0 +1,628 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H + +namespace Eigen { + +/** \class TensorContraction + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor contraction class. + * + * + */ +namespace internal { + +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename gebp_traits::type, + typename remove_const::type>::ResScalar Scalar; + + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + + // From NumDims below. + static const int NumDimensions = traits::NumDimensions + traits::NumDimensions - 2 * array_size::value; + static const int Layout = traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorContractionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorContractionOp type; +}; + +template +struct traits, Device_> > { + typedef Indices_ Indices; + typedef LeftArgType_ LeftArgType; + typedef RightArgType_ RightArgType; + typedef Device_ Device; + + // From NumDims below. + static const int NumDimensions = traits::NumDimensions + traits::NumDimensions - 2 * array_size::value; +}; + +} // end namespace internal + +template +class TensorContractionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename internal::gebp_traits::ResScalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionOp( + const LhsXprType& lhs, const RhsXprType& rhs, const Indices& dims) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_indices(dims) {} + + EIGEN_DEVICE_FUNC + const Indices& indices() const { return m_indices; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const Indices m_indices; +}; + + +template +struct TensorContractionEvaluatorBase +{ + typedef typename internal::traits::Indices Indices; + typedef typename internal::traits::LeftArgType LeftArgType; + typedef typename internal::traits::RightArgType RightArgType; + typedef typename internal::traits::Device Device; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + IsAligned = true, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = true + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + typedef DSizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorContractionEvaluatorBase(const XprType& op, const Device& device) + : m_leftImpl(choose(Cond(Layout) == static_cast(ColMajor)>(), + op.lhsExpression(), op.rhsExpression()), device), + m_rightImpl(choose(Cond(Layout) == static_cast(ColMajor)>(), + op.rhsExpression(), op.lhsExpression()), device), + m_device(device), + m_result(NULL) { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == + static_cast(TensorEvaluator::Layout)), + YOU_MADE_A_PROGRAMMING_MISTAKE); + + + DSizes eval_left_dims; + DSizes eval_right_dims; + array, ContractDims> eval_op_indices; + if (static_cast(Layout) == static_cast(ColMajor)) { + // For ColMajor, we keep using the existing dimensions + for (int i = 0; i < LDims; i++) { + eval_left_dims[i] = m_leftImpl.dimensions()[i]; + } + for (int i = 0; i < RDims; i++) { + eval_right_dims[i] = m_rightImpl.dimensions()[i]; + } + // We keep the pairs of contracting indices. + for (int i = 0; i < ContractDims; i++) { + eval_op_indices[i].first = op.indices()[i].first; + eval_op_indices[i].second = op.indices()[i].second; + } + } else { + // For RowMajor, we need to reverse the existing dimensions + for (int i = 0; i < LDims; i++) { + eval_left_dims[i] = m_leftImpl.dimensions()[LDims - i - 1]; + } + for (int i = 0; i < RDims; i++) { + eval_right_dims[i] = m_rightImpl.dimensions()[RDims - i - 1]; + } + // We need to flip all the pairs of contracting indices as well as + // reversing the dimensions. + for (int i = 0; i < ContractDims; i++) { + eval_op_indices[i].first = LDims - 1 - op.indices()[ContractDims - 1 - i].second; + eval_op_indices[i].second = RDims - 1 - op.indices()[ContractDims - 1 - i].first; + } + } + + // Check for duplicate axes and make sure the first index in eval_op_indices + // is increasing. Using O(n^2) sorting is OK since ContractDims is small + for (int i = 0; i < ContractDims; i++) { + for (int j = i + 1; j < ContractDims; j++) { + eigen_assert(eval_op_indices[j].first != eval_op_indices[i].first && + eval_op_indices[j].second != eval_op_indices[i].second && + "contraction axes should be unique"); + if (eval_op_indices[j].first < eval_op_indices[i].first) { + numext::swap(eval_op_indices[j], eval_op_indices[i]); + } + } + } + + array lhs_strides; + lhs_strides[0] = 1; + for (int i = 0; i < LDims-1; ++i) { + lhs_strides[i+1] = lhs_strides[i] * eval_left_dims[i]; + } + + array rhs_strides; + rhs_strides[0] = 1; + for (int i = 0; i < RDims-1; ++i) { + rhs_strides[i+1] = rhs_strides[i] * eval_right_dims[i]; + } + + if (m_i_strides.size() > 0) m_i_strides[0] = 1; + if (m_j_strides.size() > 0) m_j_strides[0] = 1; + if (m_k_strides.size() > 0) m_k_strides[0] = 1; + + m_i_size = 1; + m_j_size = 1; + m_k_size = 1; + + // To compute the dimension, we simply concatenate the non-contracting + // dimensions of the left and then the right tensor. Additionally, we also + // compute the strides corresponding to the left non-contracting + // dimensions and right non-contracting dimensions. + m_lhs_inner_dim_contiguous = true; + int dim_idx = 0; + unsigned int nocontract_idx = 0; + + for (int i = 0; i < LDims; i++) { + // find if we are contracting on index i of left tensor + bool contracting = false; + for (int j = 0; j < ContractDims; j++) { + if (eval_op_indices[j].first == i) { + contracting = true; + break; + } + } + if (!contracting) { + // add dimension size to output dimensions + m_dimensions[dim_idx] = eval_left_dims[i]; + m_left_nocontract_strides[nocontract_idx] = lhs_strides[i]; + if (dim_idx != i) { + m_lhs_inner_dim_contiguous = false; + } + if (nocontract_idx+1 < internal::array_size::value) { + m_i_strides[nocontract_idx+1] = + m_i_strides[nocontract_idx] * eval_left_dims[i]; + } else { + m_i_size = m_i_strides[nocontract_idx] * eval_left_dims[i]; + } + dim_idx++; + nocontract_idx++; + } + } + + nocontract_idx = 0; + for (int i = 0; i < RDims; i++) { + bool contracting = false; + // find if we are contracting on index i of right tensor + for (int j = 0; j < ContractDims; j++) { + if (eval_op_indices[j].second == i) { + contracting = true; + break; + } + } + if (!contracting) { + m_dimensions[dim_idx] = eval_right_dims[i]; + if (nocontract_idx+1 < internal::array_size::value) { + m_j_strides[nocontract_idx+1] = + m_j_strides[nocontract_idx] * eval_right_dims[i]; + } else { + m_j_size = m_j_strides[nocontract_idx] * eval_right_dims[i]; + } + m_right_nocontract_strides[nocontract_idx] = rhs_strides[i]; + dim_idx++; + nocontract_idx++; + } + } + + // Now compute the strides corresponding to the contracting dimensions. We + // assumed above that non-contracting axes are represented in the same order + // in the matrix as they are in the tensor. This is not the case for + // contracting axes. As the contracting axes must be of the same size in + // each tensor, we'll only look at the first tensor here. + m_rhs_inner_dim_contiguous = true; + m_rhs_inner_dim_reordered = false; + for (int i = 0; i < ContractDims; i++) { + Index left = eval_op_indices[i].first; + Index right = eval_op_indices[i].second; + + Index size = eval_left_dims[left]; + eigen_assert(size == eval_right_dims[right] && + "Contraction axes must be same size"); + + if (i+1 < static_cast(internal::array_size::value)) { + m_k_strides[i+1] = m_k_strides[i] * size; + } else { + m_k_size = m_k_strides[i] * size; + } + m_left_contracting_strides[i] = lhs_strides[left]; + m_right_contracting_strides[i] = rhs_strides[right]; + + if (i > 0 && right < eval_op_indices[i-1].second) { + m_rhs_inner_dim_reordered = true; + } + if (right != i) { + m_rhs_inner_dim_contiguous = false; + } + } + + // If the layout is RowMajor, we need to reverse the m_dimensions + if (static_cast(Layout) == static_cast(RowMajor)) { + for (int i = 0, j = NumDims - 1; i < j; i++, j--) { + numext::swap(m_dimensions[i], m_dimensions[j]); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC void evalTo(Scalar* buffer) const { + if (this->m_lhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + } + else { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + static_cast(this)->template evalProduct(buffer); + } + else { + static_cast(this)->template evalProduct(buffer); + } + } + } + } + + template + EIGEN_DEVICE_FUNC void evalGemv(Scalar* buffer) const { + const Index rows = m_i_size; + const Index cols = m_k_size; + + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + const Index lhs_packet_size = internal::unpacket_traits::size; + const Index rhs_packet_size = internal::unpacket_traits::size; + const int lhs_alignment = LeftEvaluator::IsAligned ? Aligned : Unaligned; + const int rhs_alignment = RightEvaluator::IsAligned ? Aligned : Unaligned; + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + LhsMapper lhs(m_leftImpl, m_left_nocontract_strides, m_i_strides, + m_left_contracting_strides, m_k_strides); + RhsMapper rhs(m_rightImpl, m_right_nocontract_strides, m_j_strides, + m_right_contracting_strides, m_k_strides); + + const Scalar alpha(1); + const Index resIncr(1); + + // zero out the result buffer (which must be of size at least rows * sizeof(Scalar) + m_device.memset(buffer, 0, rows * sizeof(Scalar)); + + internal::general_matrix_vector_product::run( + rows, cols, lhs, rhs, + buffer, resIncr, alpha); + } + + template + EIGEN_DEVICE_FUNC void evalGemm(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + // define mr, nr, and all of my data mapper types + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef typename internal::gebp_traits Traits; + + const Index nr = Traits::nr; + const Index mr = Traits::mr; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + const Index lhs_packet_size = internal::unpacket_traits::size; + const Index rhs_packet_size = internal::unpacket_traits::size; + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + // Declare GEBP packing and kernel structs + internal::gemm_pack_lhs pack_lhs; + internal::gemm_pack_rhs pack_rhs; + + internal::gebp_kernel gebp; + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + // Sizes of the blocks to load in cache. See the Goto paper for details. + internal::TensorContractionBlocking blocking(k, m, n, 1); + const Index kc = blocking.kc(); + const Index mc = numext::mini(m, blocking.mc()); + const Index nc = numext::mini(n, blocking.nc()); + const Index sizeA = mc * kc; + const Index sizeB = kc * nc; + + LhsScalar* blockA = static_cast(this->m_device.allocate(sizeA * sizeof(LhsScalar))); + RhsScalar* blockB = static_cast(this->m_device.allocate(sizeB * sizeof(RhsScalar))); + + for(Index i2=0; i2m_device.deallocate(blockA); + this->m_device.deallocate(blockB); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { return m_result; } + + protected: + // Prevent assignment + TensorContractionEvaluatorBase& operator = (const TensorContractionEvaluatorBase&); + Dimensions m_dimensions; + + contract_t m_k_strides; + contract_t m_left_contracting_strides; + contract_t m_right_contracting_strides; + + bool m_lhs_inner_dim_contiguous; + bool m_rhs_inner_dim_contiguous; + bool m_rhs_inner_dim_reordered; + + left_nocontract_t m_i_strides; + right_nocontract_t m_j_strides; + left_nocontract_t m_left_nocontract_strides; + right_nocontract_t m_right_nocontract_strides; + + Index m_i_size; + Index m_j_size; + Index m_k_size; + + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; + const Device& m_device; + Scalar* m_result; +}; + + +// evaluator for default device +template +struct TensorEvaluator, Device> : + public TensorContractionEvaluatorBase< + TensorEvaluator, Device> > { + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + // Could we use NumDimensions here? + typedef DSizes Dimensions; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) { } + + template + EIGEN_DEVICE_FUNC void evalProduct(Scalar* buffer) const { + if (this->m_j_size == 1) { + this->template evalGemv(buffer); + return; + } + + this->template evalGemm(buffer); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h new file mode 100644 index 000000000..5cf7b4f71 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h @@ -0,0 +1,56 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H + + +namespace Eigen { +namespace internal { + +enum { + ShardByRow = 0, + ShardByCol = 1 +}; + + +// Default Blocking Strategy +template +class TensorContractionBlocking { + public: + + typedef typename LhsMapper::Scalar LhsScalar; + typedef typename RhsMapper::Scalar RhsScalar; + + EIGEN_DEVICE_FUNC TensorContractionBlocking(Index k, Index m, Index n, Index num_threads = 1) : + kc_(k), mc_(m), nc_(n) + { + if (ShardingType == ShardByCol) { + computeProductBlockingSizes(kc_, mc_, nc_, num_threads); + } + else { + computeProductBlockingSizes(kc_, nc_, mc_, num_threads); + } + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index kc() const { return kc_; } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index mc() const { return mc_; } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index nc() const { return nc_; } + + private: + Index kc_; + Index mc_; + Index nc_; +}; + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h new file mode 100644 index 000000000..d65dbb40f --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h @@ -0,0 +1,1391 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014-2015 Benoit Steiner +// Copyright (C) 2015 Navdeep Jaitly +// Copyright (C) 2014 Eric Martin +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + +namespace Eigen { + +template +__device__ EIGEN_STRONG_INLINE void +EigenContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, Scalar* lhs_shmem, Scalar* rhs_shmem, + const Index m_size, const Index n_size, const Index k_size) { + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + // declare and initialize 64 registers for output 8x8 block + + // prefetch registers + Scalar lhs_pf0; + Scalar lhs_pf1; + Scalar lhs_pf2; + Scalar lhs_pf3; + Scalar lhs_pf4; + Scalar lhs_pf5; + Scalar lhs_pf6; + Scalar lhs_pf7; + + Scalar rhs_pf0; + Scalar rhs_pf1; + Scalar rhs_pf2; + Scalar rhs_pf3; + Scalar rhs_pf4; + Scalar rhs_pf5; + Scalar rhs_pf6; + Scalar rhs_pf7; + + // shared memory is formatted + // (contract idx in block, nocontract idx in block, block idx) + // where block idx is column major. This transposition limits the number of + // bank conflicts when reading the LHS. The core idea is that since the contracting + // index is shared by both sides, then the contracting index should be in threadIdx.x. + + // On the LHS, we pad each row inside of each block with an extra element. This makes + // each block 8 rows of 9 elements, which is 72 elements. This gives no bank conflicts + // on writes and very few 2-way conflicts on reads. There is an 8x8 grid of these blocks. + + // On the RHS we just add 8 padding elements to the end of each block. This gives no bank + // conflicts on writes and also none on reads. + + // storage indices + const Index lhs_store_idx_base = threadIdx.y * 72 + threadIdx.x * 9 + threadIdx.z; + const Index rhs_store_idx_base = threadIdx.y * 72 + threadIdx.z * 8 + threadIdx.x; + + const Index lhs_store_idx_0 = lhs_store_idx_base + 576 * 0; + const Index lhs_store_idx_1 = lhs_store_idx_base + 576 * 1; + const Index lhs_store_idx_2 = lhs_store_idx_base + 576 * 2; + const Index lhs_store_idx_3 = lhs_store_idx_base + 576 * 3; + const Index lhs_store_idx_4 = lhs_store_idx_base + 576 * 4; + const Index lhs_store_idx_5 = lhs_store_idx_base + 576 * 5; + const Index lhs_store_idx_6 = lhs_store_idx_base + 576 * 6; + const Index lhs_store_idx_7 = lhs_store_idx_base + 576 * 7; + + const Index rhs_store_idx_0 = rhs_store_idx_base + 576 * 0; + const Index rhs_store_idx_1 = rhs_store_idx_base + 576 * 1; + const Index rhs_store_idx_2 = rhs_store_idx_base + 576 * 2; + const Index rhs_store_idx_3 = rhs_store_idx_base + 576 * 3; + const Index rhs_store_idx_4 = rhs_store_idx_base + 576 * 4; + const Index rhs_store_idx_5 = rhs_store_idx_base + 576 * 5; + const Index rhs_store_idx_6 = rhs_store_idx_base + 576 * 6; + const Index rhs_store_idx_7 = rhs_store_idx_base + 576 * 7; + + // in the loading code, the following variables are important: + // threadIdx.x: the vertical position in an 8x8 block + // threadIdx.y: the vertical index of the 8x8 block in the grid + // threadIdx.z: the horizontal position in an 8x8 block + // k: the horizontal index of the 8x8 block in the grid + // + // The k parameter is implicit (it was the loop counter for a loop that went + // from 0 to <8, but now that loop is unrolled in the below code. + + const Index load_idx_vert = threadIdx.x + 8 * threadIdx.y; + const Index lhs_vert = base_m + load_idx_vert; + +#define prefetchIntoRegisters(base_k) \ + { \ + lhs_pf0 = conv(0); \ + lhs_pf1 = conv(0); \ + lhs_pf2 = conv(0); \ + lhs_pf3 = conv(0); \ + lhs_pf4 = conv(0); \ + lhs_pf5 = conv(0); \ + lhs_pf6 = conv(0); \ + lhs_pf7 = conv(0); \ + \ + rhs_pf0 = conv(0); \ + rhs_pf1 = conv(0); \ + rhs_pf2 = conv(0); \ + rhs_pf3 = conv(0); \ + rhs_pf4 = conv(0); \ + rhs_pf5 = conv(0); \ + rhs_pf6 = conv(0); \ + rhs_pf7 = conv(0); \ + \ + if (!needs_edge_check || lhs_vert < m_size) { \ + const Index lhs_horiz_0 = base_k + threadIdx.z + 0 * 8; \ + const Index lhs_horiz_1 = base_k + threadIdx.z + 1 * 8; \ + const Index lhs_horiz_2 = base_k + threadIdx.z + 2 * 8; \ + const Index lhs_horiz_3 = base_k + threadIdx.z + 3 * 8; \ + const Index lhs_horiz_4 = base_k + threadIdx.z + 4 * 8; \ + const Index lhs_horiz_5 = base_k + threadIdx.z + 5 * 8; \ + const Index lhs_horiz_6 = base_k + threadIdx.z + 6 * 8; \ + const Index lhs_horiz_7 = base_k + threadIdx.z + 7 * 8; \ + \ + if (!needs_edge_check || lhs_horiz_7 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + lhs_pf6 = lhs(lhs_vert, lhs_horiz_6); \ + lhs_pf7 = lhs(lhs_vert, lhs_horiz_7); \ + } else if (lhs_horiz_6 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + lhs_pf6 = lhs(lhs_vert, lhs_horiz_6); \ + } else if (lhs_horiz_5 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + lhs_pf5 = lhs(lhs_vert, lhs_horiz_5); \ + } else if (lhs_horiz_4 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + lhs_pf4 = lhs(lhs_vert, lhs_horiz_4); \ + } else if (lhs_horiz_3 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + lhs_pf3 = lhs(lhs_vert, lhs_horiz_3); \ + } else if (lhs_horiz_2 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + lhs_pf2 = lhs(lhs_vert, lhs_horiz_2); \ + } else if (lhs_horiz_1 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + lhs_pf1 = lhs(lhs_vert, lhs_horiz_1); \ + } else if (lhs_horiz_0 < k_size) { \ + lhs_pf0 = lhs(lhs_vert, lhs_horiz_0); \ + } \ + } \ + \ + const Index rhs_vert = base_k + load_idx_vert; \ + if (!needs_edge_check || rhs_vert < k_size) { \ + const Index rhs_horiz_0 = base_n + threadIdx.z + 0 * 8; \ + const Index rhs_horiz_1 = base_n + threadIdx.z + 1 * 8; \ + const Index rhs_horiz_2 = base_n + threadIdx.z + 2 * 8; \ + const Index rhs_horiz_3 = base_n + threadIdx.z + 3 * 8; \ + const Index rhs_horiz_4 = base_n + threadIdx.z + 4 * 8; \ + const Index rhs_horiz_5 = base_n + threadIdx.z + 5 * 8; \ + const Index rhs_horiz_6 = base_n + threadIdx.z + 6 * 8; \ + const Index rhs_horiz_7 = base_n + threadIdx.z + 7 * 8; \ + \ + if (rhs_horiz_7 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + rhs_pf6 = rhs(rhs_vert, rhs_horiz_6); \ + rhs_pf7 = rhs(rhs_vert, rhs_horiz_7); \ + } else if (rhs_horiz_6 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + rhs_pf6 = rhs(rhs_vert, rhs_horiz_6); \ + } else if (rhs_horiz_5 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + rhs_pf5 = rhs(rhs_vert, rhs_horiz_5); \ + } else if (rhs_horiz_4 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + rhs_pf4 = rhs(rhs_vert, rhs_horiz_4); \ + } else if (rhs_horiz_3 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + rhs_pf3 = rhs(rhs_vert, rhs_horiz_3); \ + } else if (rhs_horiz_2 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + rhs_pf2 = rhs(rhs_vert, rhs_horiz_2); \ + } else if (rhs_horiz_1 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + rhs_pf1 = rhs(rhs_vert, rhs_horiz_1); \ + } else if (rhs_horiz_0 < n_size) { \ + rhs_pf0 = rhs(rhs_vert, rhs_horiz_0); \ + } \ + } \ + } \ + +#define writeRegToShmem(_) \ + lhs_shmem[lhs_store_idx_0] = lhs_pf0; \ + rhs_shmem[rhs_store_idx_0] = rhs_pf0; \ + \ + lhs_shmem[lhs_store_idx_1] = lhs_pf1; \ + rhs_shmem[rhs_store_idx_1] = rhs_pf1; \ + \ + lhs_shmem[lhs_store_idx_2] = lhs_pf2; \ + rhs_shmem[rhs_store_idx_2] = rhs_pf2; \ + \ + lhs_shmem[lhs_store_idx_3] = lhs_pf3; \ + rhs_shmem[rhs_store_idx_3] = rhs_pf3; \ + \ + lhs_shmem[lhs_store_idx_4] = lhs_pf4; \ + rhs_shmem[rhs_store_idx_4] = rhs_pf4; \ + \ + lhs_shmem[lhs_store_idx_5] = lhs_pf5; \ + rhs_shmem[rhs_store_idx_5] = rhs_pf5; \ + \ + lhs_shmem[lhs_store_idx_6] = lhs_pf6; \ + rhs_shmem[rhs_store_idx_6] = rhs_pf6; \ + \ + lhs_shmem[lhs_store_idx_7] = lhs_pf7; \ + rhs_shmem[rhs_store_idx_7] = rhs_pf7; \ + + // declare and initialize result array +#define res(i, j) _res_##i##j +#define initResultRow(i) \ + Scalar res(i, 0) = conv(0); \ + Scalar res(i, 1) = conv(0); \ + Scalar res(i, 2) = conv(0); \ + Scalar res(i, 3) = conv(0); \ + Scalar res(i, 4) = conv(0); \ + Scalar res(i, 5) = conv(0); \ + Scalar res(i, 6) = conv(0); \ + Scalar res(i, 7) = conv(0); \ + + internal::scalar_cast_op conv; + initResultRow(0); + initResultRow(1); + initResultRow(2); + initResultRow(3); + initResultRow(4); + initResultRow(5); + initResultRow(6); + initResultRow(7); +#undef initResultRow + + for (Index base_k = 0; base_k < k_size; base_k += 64) { + // wait for previous iteration to finish with shmem. Despite common sense, + // the code is a bit faster with this here then at bottom of loop + __syncthreads(); + + prefetchIntoRegisters(base_k); + writeRegToShmem(); + + #undef prefetchIntoRegisters + #undef writeRegToShmem + + // wait for shared mem packing to be done before starting computation + __syncthreads(); + + // compute 8x8 matrix product by outer product. This involves packing one column + // of LHS and one row of RHS into registers (takes 16 registers). + +#define lcol(i) _lcol##i + Scalar lcol(0); + Scalar lcol(1); + Scalar lcol(2); + Scalar lcol(3); + Scalar lcol(4); + Scalar lcol(5); + Scalar lcol(6); + Scalar lcol(7); + +#define rrow(j) _rrow##j + Scalar rrow(0); + Scalar rrow(1); + Scalar rrow(2); + Scalar rrow(3); + Scalar rrow(4); + Scalar rrow(5); + Scalar rrow(6); + Scalar rrow(7); + + // Now x corresponds to k, y to m, and z to n + const Scalar* lhs_block = &lhs_shmem[threadIdx.x + 9 * threadIdx.y]; + const Scalar* rhs_block = &rhs_shmem[threadIdx.x + 8 * threadIdx.z]; + +#define lhs_element(i, j) lhs_block[72 * ((i) + 8 * (j))] +#define rhs_element(i, j) rhs_block[72 * ((i) + 8 * (j))] + +#define loadData(i, j) \ + lcol(0) = lhs_element(0, j); \ + rrow(0) = rhs_element(i, 0); \ + lcol(1) = lhs_element(1, j); \ + rrow(1) = rhs_element(i, 1); \ + lcol(2) = lhs_element(2, j); \ + rrow(2) = rhs_element(i, 2); \ + lcol(3) = lhs_element(3, j); \ + rrow(3) = rhs_element(i, 3); \ + lcol(4) = lhs_element(4, j); \ + rrow(4) = rhs_element(i, 4); \ + lcol(5) = lhs_element(5, j); \ + rrow(5) = rhs_element(i, 5); \ + lcol(6) = lhs_element(6, j); \ + rrow(6) = rhs_element(i, 6); \ + lcol(7) = lhs_element(7, j); \ + rrow(7) = rhs_element(i, 7); \ + +#define computeCol(j) \ + res(0, j) += lcol(0) * rrow(j); \ + res(1, j) += lcol(1) * rrow(j); \ + res(2, j) += lcol(2) * rrow(j); \ + res(3, j) += lcol(3) * rrow(j); \ + res(4, j) += lcol(4) * rrow(j); \ + res(5, j) += lcol(5) * rrow(j); \ + res(6, j) += lcol(6) * rrow(j); \ + res(7, j) += lcol(7) * rrow(j); \ + +#define computePass(i) \ + loadData(i, i); \ + \ + computeCol(0); \ + computeCol(1); \ + computeCol(2); \ + computeCol(3); \ + computeCol(4); \ + computeCol(5); \ + computeCol(6); \ + computeCol(7); \ + + computePass(0); + computePass(1); + computePass(2); + computePass(3); + computePass(4); + computePass(5); + computePass(6); + computePass(7); + +#undef lcol +#undef rrow +#undef lhs_element +#undef rhs_element +#undef loadData +#undef computeCol +#undef computePass + } // end loop over k + + // we've now iterated over all of the large (ie width 64) k blocks and + // accumulated results in registers. At this point thread (x, y, z) contains + // the sum across all big k blocks of the product of little k block of index (x, y) + // with block of index (y, z). To compute the final output, we need to reduce + // the 8 threads over y by summation. +#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor(res(i, j), mask) + +#define reduceRow(i, mask) \ + shuffleInc(i, 0, mask); \ + shuffleInc(i, 1, mask); \ + shuffleInc(i, 2, mask); \ + shuffleInc(i, 3, mask); \ + shuffleInc(i, 4, mask); \ + shuffleInc(i, 5, mask); \ + shuffleInc(i, 6, mask); \ + shuffleInc(i, 7, mask); \ + +#define reduceMatrix(mask) \ + reduceRow(0, mask); \ + reduceRow(1, mask); \ + reduceRow(2, mask); \ + reduceRow(3, mask); \ + reduceRow(4, mask); \ + reduceRow(5, mask); \ + reduceRow(6, mask); \ + reduceRow(7, mask); \ + + // actually perform the reduction, now each thread of index (_, y, z) + // contains the correct values in its registers that belong in the output + // block + reduceMatrix(1); + reduceMatrix(2); + reduceMatrix(4); + +#undef shuffleInc +#undef reduceRow +#undef reduceMatrix + + // now we need to copy the 64 values into main memory. We can't split work + // among threads because all variables are in registers. There's 2 ways + // to do this: + // (1) have 1 thread do 64 writes from registers into global memory + // (2) have 1 thread do 64 writes into shared memory, and then 8 threads + // each do 8 writes into global memory. We can just overwrite the shared + // memory from the problem we just solved. + // (2) is slightly faster than (1) due to less branching and more ILP + + // TODO: won't yield much gain, but could just use currently unused shared mem + // and then we won't have to sync + // wait for shared mem to be out of use + __syncthreads(); + +#define writeResultShmem(i, j) \ + lhs_shmem[i + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j] = res(i, j); \ + +#define writeRow(i) \ + writeResultShmem(i, 0); \ + writeResultShmem(i, 1); \ + writeResultShmem(i, 2); \ + writeResultShmem(i, 3); \ + writeResultShmem(i, 4); \ + writeResultShmem(i, 5); \ + writeResultShmem(i, 6); \ + writeResultShmem(i, 7); \ + + if (threadIdx.x == 0) { + writeRow(0); + writeRow(1); + writeRow(2); + writeRow(3); + writeRow(4); + writeRow(5); + writeRow(6); + writeRow(7); + } +#undef writeResultShmem +#undef writeRow + + const int max_i_write = numext::mini((int)((m_size - base_m - threadIdx.y + 7) / 8), 8); + const int max_j_write = numext::mini((int)((n_size - base_n - threadIdx.z + 7) / 8), 8); + + if (threadIdx.x < max_i_write) { + if (max_j_write == 8) { + // TODO: can i trade bank conflicts for coalesced writes? + Scalar val0 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 0]; + Scalar val1 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 1]; + Scalar val2 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 2]; + Scalar val3 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 3]; + Scalar val4 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 4]; + Scalar val5 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 5]; + Scalar val6 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 6]; + Scalar val7 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 7]; + + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 0) = val0; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 1) = val1; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 2) = val2; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 3) = val3; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 4) = val4; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 5) = val5; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 6) = val6; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 7) = val7; + } else { +#pragma unroll 7 + for (int j = 0; j < max_j_write; j++) { + Scalar val = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j]; + output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * j) = val; + } + } + } +#undef res +} + + +template +__global__ void +__launch_bounds__(512) +EigenContractionKernel(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ Scalar lhs_shmem[72 * 64]; + __shared__ Scalar rhs_shmem[72 * 64]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + if (base_m + 63 < m_size && base_n + 63 < n_size) { + EigenContractionKernelInternal(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size); + } else { + EigenContractionKernelInternal(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size); + } +} + + +template +__device__ EIGEN_STRONG_INLINE void +EigenFloatContractionKernelInternal16x16(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, float2 lhs_shmem2[][16], + float2 rhs_shmem2[][8], const Index m_size, + const Index n_size, const Index k_size, + const Index base_m, const Index base_n) { + typedef float Scalar; + + // prefetch registers + float4 lhs_pf0, rhs_pf0; + + float4 results[4]; + for (int i=0; i < 4; i++) { + results[i].x = results[i].y = results[i].z = results[i].w = 0; + } + + +#define prefetch_lhs(reg, row, col) \ + if (!CHECK_LHS_BOUNDARY) { \ + if (col < k_size) { \ + reg =lhs.loadPacket(row, col); \ + } \ + } else { \ + if (col < k_size) { \ + if (row + 3 < m_size) { \ + reg =lhs.loadPacket(row, col); \ + } else if (row + 2 < m_size) { \ + reg.x =lhs(row + 0, col); \ + reg.y =lhs(row + 1, col); \ + reg.z =lhs(row + 2, col); \ + } else if (row + 1 < m_size) { \ + reg.x =lhs(row + 0, col); \ + reg.y =lhs(row + 1, col); \ + } else if (row < m_size) { \ + reg.x =lhs(row + 0, col); \ + } \ + } \ + } \ + + + Index lhs_vert = base_m+threadIdx.x*4; + + for (Index k = 0; k < k_size; k += 16) { + lhs_pf0 = internal::pset1(0); + rhs_pf0 = internal::pset1(0); + + Index lhs_horiz = threadIdx.y+k; + prefetch_lhs(lhs_pf0, lhs_vert, lhs_horiz) + + Index rhs_vert = k+(threadIdx.x%4)*4; + Index rhs_horiz0 = (threadIdx.x>>2)+threadIdx.y*4+base_n; + + if (!CHECK_RHS_BOUNDARY) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.loadPacket(rhs_vert, rhs_horiz0); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if (rhs_vert + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } else { + if (rhs_horiz0 < n_size) { + if ((rhs_vert + 3) < k_size) { + rhs_pf0 = rhs.loadPacket(rhs_vert, rhs_horiz0); + } else if ((rhs_vert + 2) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if ((rhs_vert + 1) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } + } + float x1, x2 ; + // the following can be a bitwise operation..... some day. + if((threadIdx.x%8) < 4) { + x1 = rhs_pf0.y; + x2 = rhs_pf0.w; + } else { + x1 = rhs_pf0.x; + x2 = rhs_pf0.z; + } + x1 = __shfl_xor(x1, 4); + x2 = __shfl_xor(x2, 4); + if((threadIdx.x%8) < 4) { + rhs_pf0.y = x1; + rhs_pf0.w = x2; + } else { + rhs_pf0.x = x1; + rhs_pf0.z = x2; + } + + // We have 64 features. + // Row 0 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 0, 1. + // Row 1 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 2, 3. + // ... + // Row 31 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 62, 63 + // Row 32 -> times (2, 6, 10, 14, 3, 7, 11, 15) for features 0, 1 + // ... + rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2][threadIdx.x%8] = make_float2(rhs_pf0.x, rhs_pf0.y); + rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2+32][threadIdx.x%8] = make_float2(rhs_pf0.z, rhs_pf0.w); + + // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // ... + // Row 15 (time 15) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) + // Row 16 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) + // ... + + lhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(lhs_pf0.x, lhs_pf0.y); + lhs_shmem2[threadIdx.y+16][threadIdx.x] = make_float2(lhs_pf0.z, lhs_pf0.w); + + +#define add_vals(fl1, fl2, fr1, fr2)\ + results[0].x += fl1.x * fr1.x;\ + results[0].y += fl1.y * fr1.x;\ + results[0].z += fl2.x * fr1.x;\ + results[0].w += fl2.y * fr1.x;\ +\ + results[1].x += fl1.x * fr1.y;\ + results[1].y += fl1.y * fr1.y;\ + results[1].z += fl2.x * fr1.y;\ + results[1].w += fl2.y * fr1.y;\ +\ + results[2].x += fl1.x * fr2.x;\ + results[2].y += fl1.y * fr2.x;\ + results[2].z += fl2.x * fr2.x;\ + results[2].w += fl2.y * fr2.x;\ +\ + results[3].x += fl1.x * fr2.y;\ + results[3].y += fl1.y * fr2.y;\ + results[3].z += fl2.x * fr2.y;\ + results[3].w += fl2.y * fr2.y;\ + + __syncthreads(); + + // Do the multiplies. + #pragma unroll + for (int koff = 0; koff < 16; koff ++) { + // 32 x threads. + float2 fl1 = lhs_shmem2[koff][threadIdx.x]; + float2 fl2 = lhs_shmem2[koff + 16][threadIdx.x]; + + int start_feature = threadIdx.y * 4; + float2 fr1 = rhs_shmem2[(start_feature>>1) + 32*((koff%4)/2)][koff/4 + (koff%2)*4]; + float2 fr2 = rhs_shmem2[(start_feature>>1) + 1 + 32*((koff%4)/2)][koff/4 + (koff%2)*4]; + + add_vals(fl1, fl2, fr1, fr2) + } + __syncthreads(); + } + +#undef prefetch_lhs +#undef add_vals + + Index horiz_base = threadIdx.y*4+base_n; + if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (!CHECK_RHS_BOUNDARY) { + // CHECK LHS + if (lhs_vert + 3 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (lhs_vert + 2 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + } + } else if (lhs_vert + 1 < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + } + } else if (lhs_vert < m_size) { + for (int i = 0; i < 4; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + } + } + } else if (!CHECK_LHS_BOUNDARY) { + // CHECK RHS + /* + int ncols_rem = fminf(n_size- horiz_base, 4); + for (int i = 0; i < ncols_rem; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + }*/ + for (int i = 0; i < 4; i++) { + if (horiz_base+i < n_size) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } else { + // CHECK both boundaries. + for (int i = 0; i < 4; i++) { + if (horiz_base+i < n_size) { + if (lhs_vert < m_size) + output(lhs_vert, horiz_base + i) = results[i].x; + if (lhs_vert + 1 < m_size) + output(lhs_vert + 1, horiz_base + i) = results[i].y; + if (lhs_vert + 2 < m_size) + output(lhs_vert + 2, horiz_base + i) = results[i].z; + if (lhs_vert + 3 < m_size) + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } +} + + +template +__device__ EIGEN_STRONG_INLINE void +EigenFloatContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, float2 lhs_shmem2[][32], + float2 rhs_shmem2[][8], const Index m_size, + const Index n_size, const Index k_size, + const Index base_m, const Index base_n) { + typedef float Scalar; + + // prefetch registers + float4 lhs_pf0, lhs_pf1, lhs_pf2, lhs_pf3; + float4 rhs_pf0, rhs_pf1; + + float4 results[8]; + for (int i=0; i < 8; i++) { + results[i].x = results[i].y = results[i].z = results[i].w = 0; + } + + + Index lhs_vert = base_m+threadIdx.x*4+(threadIdx.y%4)*32; + for (Index k = 0; k < k_size; k += 32) { + lhs_pf0 = internal::pset1(0); + lhs_pf1 = internal::pset1(0); + lhs_pf2 = internal::pset1(0); + lhs_pf3 = internal::pset1(0); + + rhs_pf0 = internal::pset1(0); + rhs_pf1 = internal::pset1(0); + + if (!CHECK_LHS_BOUNDARY) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + lhs_pf3 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + } + } else { + // just CHECK_LHS_BOUNDARY + if (lhs_vert + 3 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + lhs_pf3 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + lhs_pf2 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + lhs_pf1 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0 =lhs.loadPacket(lhs_vert, (threadIdx.y/4+k)); + } + } else if (lhs_vert + 2 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24)); + lhs_pf3.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k)); + } + } else if (lhs_vert + 1 < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k)); + } + } else if (lhs_vert < m_size) { + if ((threadIdx.y/4+k+24) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24)); + } else if ((threadIdx.y/4+k+16) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16)); + } else if ((threadIdx.y/4+k+8) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8)); + } else if ((threadIdx.y/4+k) < k_size) { + lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k)); + } + } + } + __syncthreads(); + Index rhs_vert = k+threadIdx.x*4; + Index rhs_horiz0 = threadIdx.y*2+base_n; + Index rhs_horiz1 = threadIdx.y*2+1+base_n; + if (!CHECK_RHS_BOUNDARY) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.loadPacket(rhs_vert, rhs_horiz0); + rhs_pf1 = rhs.loadPacket(rhs_vert, rhs_horiz1); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1); + } else if (rhs_vert + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + } + } else { + if (rhs_horiz1 < n_size) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.loadPacket(rhs_vert, rhs_horiz0); + rhs_pf1 = rhs.loadPacket(rhs_vert, rhs_horiz1); + } else if (rhs_vert + 2 < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1); + } else if (k+threadIdx.x*4 + 1 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1); + } else if (k+threadIdx.x*4 < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf1.x = rhs(rhs_vert, rhs_horiz1); + } + } else if (rhs_horiz0 < n_size) { + if ((rhs_vert + 3) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0 = rhs.loadPacket(rhs_vert, rhs_horiz0); + } else if ((rhs_vert + 2) < k_size) { + // just CHECK_RHS_BOUNDARY + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0); + } else if ((rhs_vert + 1) < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0); + } else if (rhs_vert < k_size) { + rhs_pf0.x = rhs(rhs_vert, rhs_horiz0); + } + } + } + __syncthreads(); + // Loaded. Do computation + // Row 0 -> times (0, 4, 8, .. 28) for features 0, 1. + // Row 1 -> times (0, 4, 8, .. 28) for features 2, 3. + // .. + // Row 31 -> times (0, 4, 8, .. 28) for features 62, 63 + rhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(rhs_pf0.x, rhs_pf1.x); + // Row 32 -> times (1, 5, 9, .. 29) for features 0, 1. + // Row 33 -> times (1, 5, 9, .. 29) for features 2, 3. + // .. + rhs_shmem2[threadIdx.y+32][threadIdx.x] = make_float2(rhs_pf0.y, rhs_pf1.y); + // Row 64 -> times (2, 6, 10, .. 30) for features 0, 1. + // Row 65 -> times (2, 6, 10, .. 30) for features 2, 3. + rhs_shmem2[threadIdx.y+64][threadIdx.x] = make_float2(rhs_pf0.z, rhs_pf1.z); + // Row 96 -> times (3, 7, 11, .. 31) for features 0, 1. + // Row 97 -> times (3, 7, 11, .. 31) for features 2, 3. + rhs_shmem2[threadIdx.y+96][threadIdx.x] = make_float2(rhs_pf0.w, rhs_pf1.w); + + // LHS. + // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) .. (124, 125) + // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), .. (60, 61) .. (124, 125) + // ... + // Row 8 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) .. (126, 127) + // Row 15 (time 7) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), .. (62, 63) .. (126, 127) + + +#define add_vals(a_feat1, a_feat2, f1, f2, f3, f4)\ + results[0].x += a_feat1.x * f1.x;\ + results[1].x += a_feat1.x * f1.y;\ + results[2].x += a_feat1.x * f2.x;\ + results[3].x += a_feat1.x * f2.y;\ + results[4].x += a_feat1.x * f3.x;\ + results[5].x += a_feat1.x * f3.y;\ + results[6].x += a_feat1.x * f4.x;\ + results[7].x += a_feat1.x * f4.y;\ +\ + results[0].y += a_feat1.y * f1.x;\ + results[1].y += a_feat1.y * f1.y;\ + results[2].y += a_feat1.y * f2.x;\ + results[3].y += a_feat1.y * f2.y;\ + results[4].y += a_feat1.y * f3.x;\ + results[5].y += a_feat1.y * f3.y;\ + results[6].y += a_feat1.y * f4.x;\ + results[7].y += a_feat1.y * f4.y;\ +\ + results[0].z += a_feat2.x * f1.x;\ + results[1].z += a_feat2.x * f1.y;\ + results[2].z += a_feat2.x * f2.x;\ + results[3].z += a_feat2.x * f2.y;\ + results[4].z += a_feat2.x * f3.x;\ + results[5].z += a_feat2.x * f3.y;\ + results[6].z += a_feat2.x * f4.x;\ + results[7].z += a_feat2.x * f4.y;\ +\ + results[0].w += a_feat2.y * f1.x;\ + results[1].w += a_feat2.y * f1.y;\ + results[2].w += a_feat2.y * f2.x;\ + results[3].w += a_feat2.y * f2.y;\ + results[4].w += a_feat2.y * f3.x;\ + results[5].w += a_feat2.y * f3.y;\ + results[6].w += a_feat2.y * f4.x;\ + results[7].w += a_feat2.y * f4.y;\ + + lhs_shmem2[threadIdx.y/4][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.x, lhs_pf0.y); + lhs_shmem2[threadIdx.y/4+8][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.x, lhs_pf1.y); + lhs_shmem2[threadIdx.y/4+16][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.x, lhs_pf2.y); + lhs_shmem2[threadIdx.y/4+24][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.x, lhs_pf3.y); + + lhs_shmem2[threadIdx.y/4 + 32][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.z, lhs_pf0.w); + lhs_shmem2[threadIdx.y/4 + 40][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.z, lhs_pf1.w); + lhs_shmem2[threadIdx.y/4 + 48][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.z, lhs_pf2.w); + lhs_shmem2[threadIdx.y/4 + 56][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.z, lhs_pf3.w); + + __syncthreads(); + + // Do the multiplies. + #pragma unroll + for (int koff = 0; koff < 32; koff ++) { + float2 a3 = lhs_shmem2[koff][threadIdx.x + (threadIdx.y % 4) * 8]; + float2 a4 = lhs_shmem2[koff + 32][threadIdx.x + (threadIdx.y % 4) * 8]; + + // first feature is at (threadIdx.y/4) * 8 last is at start + 8. + int start_feature = (threadIdx.y / 4) * 8; + + float2 br1 = rhs_shmem2[start_feature/2 + (koff % 4) * 32][koff/4]; + float2 br2 = rhs_shmem2[start_feature/2 + 1 + (koff % 4) * 32][koff/4]; + float2 br3 = rhs_shmem2[start_feature/2 + 2 + (koff % 4) * 32][koff/4]; + float2 br4 = rhs_shmem2[start_feature/2 + 3 + (koff % 4) * 32][koff/4]; + + add_vals(a3, a4, br1, br2, br3, br4) + } + __syncthreads(); + } // end loop over k + + + __syncthreads(); + Index horiz_base = (threadIdx.y/4)*8+base_n; + if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (!CHECK_RHS_BOUNDARY) { + if (lhs_vert + 3 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } else if (lhs_vert + 2 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + } + } else if (lhs_vert + 1 < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + } + } else if (lhs_vert < m_size) { + for (int i = 0; i < 8; i++) { + output(lhs_vert, horiz_base + i) = results[i].x; + } + } + } else if (!CHECK_LHS_BOUNDARY) { + // CHECK BOUNDARY_B + for (int i = 0; i < 8; i++) { + if (horiz_base + i < n_size) { + output(lhs_vert, horiz_base + i) = results[i].x; + output(lhs_vert + 1, horiz_base + i) = results[i].y; + output(lhs_vert + 2, horiz_base + i) = results[i].z; + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } else { + // CHECK both boundaries. + for (int i = 0; i < 8; i++) { + if (horiz_base + i < n_size) { + if (lhs_vert < m_size) + output(lhs_vert, horiz_base + i) = results[i].x; + if (lhs_vert + 1 < m_size) + output(lhs_vert + 1, horiz_base + i) = results[i].y; + if (lhs_vert + 2 < m_size) + output(lhs_vert + 2, horiz_base + i) = results[i].z; + if (lhs_vert + 3 < m_size) + output(lhs_vert + 3, horiz_base + i) = results[i].w; + } + } + } +} + + +template +__global__ void +__launch_bounds__(256) +EigenFloatContractionKernel(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ float2 lhs_shmem[64*32]; + __shared__ float2 rhs_shmem[128*8]; + + typedef float2 LHS_MEM[64][32]; + typedef float2 RHS_MEM[128][8]; + + typedef float2 LHS_MEM16x16[32][16]; + typedef float2 RHS_MEM16x16[64][8]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 128 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + bool check_rhs = (base_n + 63) >= n_size; + bool check_lhs128 = (base_m + 127) >= m_size; + + if (!check_rhs) { + if (!check_lhs128) { + // >= 128 rows left + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } + } else { + if (!check_lhs128) { + // >= 128 rows left + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal( + lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n); + } + } +} + +template +__global__ void +__launch_bounds__(256) +EigenFloatContractionKernel16x16(const LhsMapper lhs, const RhsMapper rhs, + const OutputMapper output, + const Index m_size, const Index n_size, const Index k_size) { + __shared__ float2 lhs_shmem[32][16]; + __shared__ float2 rhs_shmem[64][8]; + + const Index m_block_idx = blockIdx.x; + const Index n_block_idx = blockIdx.y; + + const Index base_m = 64 * m_block_idx; + const Index base_n = 64 * n_block_idx; + + if (base_m + 63 < m_size) { + if (base_n + 63 < n_size) { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } + } else { + if (base_n + 63 < n_size) { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } else { + EigenFloatContractionKernelInternal16x16(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n); + } + } +} + + +template +struct TensorEvaluator, GpuDevice> : + public TensorContractionEvaluatorBase, GpuDevice> > { + + typedef GpuDevice Device; + + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout, + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array left_dim_mapper_t; + typedef array right_dim_mapper_t; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef DSizes Dimensions; + + // typedefs needed in evalTo + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + typedef typename LeftEvaluator::Dimensions LeftDimensions; + typedef typename RightEvaluator::Dimensions RightDimensions; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) {} + + // We need to redefine this method to make nvcc happy + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + this->m_leftImpl.evalSubExprsIfNeeded(NULL); + this->m_rightImpl.evalSubExprsIfNeeded(NULL); + if (data) { + evalTo(data); + return false; + } else { + this->m_result = static_cast(this->m_device.allocate(this->dimensions().TotalSize() * sizeof(Scalar))); + evalTo(this->m_result); + return true; + } + } + + void evalTo(Scalar* buffer) const { + if (this->m_lhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + else { + if (this->m_rhs_inner_dim_contiguous) { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + else { + if (this->m_rhs_inner_dim_reordered) { + evalTyped(buffer); + } + else { + evalTyped(buffer); + } + } + } + } + + template struct LaunchKernels { + static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) { + const Index m_blocks = (m + 63) / 64; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(8, 8, 8); + LAUNCH_CUDA_KERNEL((EigenContractionKernel), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } + }; + + template struct LaunchKernels { + static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) { + if (m < 768 || n < 768) { + const Index m_blocks = (m + 63) / 64; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(16, 16, 1); + LAUNCH_CUDA_KERNEL((EigenFloatContractionKernel16x16), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } else { + const Index m_blocks = (m + 127) / 128; + const Index n_blocks = (n + 63) / 64; + const dim3 num_blocks(m_blocks, n_blocks, 1); + const dim3 block_size(8, 32, 1); + LAUNCH_CUDA_KERNEL((EigenFloatContractionKernel), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k); + } + } + }; + + template + void evalTyped(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + EIGEN_UNUSED_VARIABLE(k) + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + setCudaSharedMemConfig(cudaSharedMemBankSizeEightByte); + LaunchKernels::Run(lhs, rhs, output, m, n, k, this->m_device); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_USE_GPU and __CUDACC__ +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_CUDA_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h new file mode 100644 index 000000000..9b2cb3ff6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h @@ -0,0 +1,467 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H + +namespace Eigen { + +namespace internal { + +enum { + Rhs = 0, + Lhs = 1 +}; + +/* + * Implementation of the Eigen blas_data_mapper class for tensors. + */ + +template struct CoeffLoader { + enum { + DirectOffsets = false + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_tensor(tensor) { } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index) { + eigen_assert(false && "unsupported"); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return m_tensor.coeff(index); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename Tensor::PacketReturnType packet(typename Tensor::Index index) const + { + return m_tensor.template packet(index); + } + + + private: + const Tensor m_tensor; +}; + +template struct CoeffLoader { + enum { + DirectOffsets = true + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_data(tensor.data()) {} + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) { + m_data += offset; + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return loadConstant(m_data+index); } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + typename Tensor::PacketReturnType packet(typename Tensor::Index index) const + { + return internal::ploadt_ro(m_data + index); + } + private: + typedef typename Tensor::Scalar Scalar; + const Scalar* m_data; +}; + +template +class SimpleTensorContractionMapper { + public: + EIGEN_DEVICE_FUNC + SimpleTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + m_tensor(tensor), + m_nocontract_strides(nocontract_strides), + m_ij_strides(ij_strides), + m_contract_strides(contract_strides), + m_k_strides(k_strides) { } + + enum { + DirectOffsets = CoeffLoader::DirectOffsets + }; + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) { + m_tensor.offsetBuffer(offset); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE void prefetch(Index /*i*/) { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar operator()(Index row) const { + // column major assumption + return operator()(row, 0); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar operator()(Index row, Index col) const { + return m_tensor.coeff(computeIndex(row, col)); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index computeIndex(Index row, Index col) const { + const bool left = (side == Lhs); + Index nocontract_val = left ? row : col; + Index linidx = 0; + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx = nocontract_val / m_ij_strides[i]; + linidx += idx * m_nocontract_strides[i]; + nocontract_val -= idx * m_ij_strides[i]; + } + if (array_size::value > array_size::value) { + if (side == Lhs && inner_dim_contiguous) { + eigen_assert(m_nocontract_strides[0] == 1); + linidx += nocontract_val; + } else { + linidx += nocontract_val * m_nocontract_strides[0]; + } + } + + Index contract_val = left ? col : row; + if(array_size::value > 0) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx = contract_val / m_k_strides[i]; + linidx += idx * m_contract_strides[i]; + contract_val -= idx * m_k_strides[i]; + } + + if (side == Rhs && inner_dim_contiguous) { + eigen_assert(m_contract_strides[0] == 1); + linidx += contract_val; + } else { + linidx += contract_val * m_contract_strides[0]; + } + } + + return linidx; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE IndexPair computeIndexPair(Index row, Index col, const Index distance) const { + const bool left = (side == Lhs); + Index nocontract_val[2] = {left ? row : col, left ? row + distance : col}; + Index linidx[2] = {0, 0}; + if (array_size::value > array_size::value) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx0 = nocontract_val[0] / m_ij_strides[i]; + const Index idx1 = nocontract_val[1] / m_ij_strides[i]; + linidx[0] += idx0 * m_nocontract_strides[i]; + linidx[1] += idx1 * m_nocontract_strides[i]; + nocontract_val[0] -= idx0 * m_ij_strides[i]; + nocontract_val[1] -= idx1 * m_ij_strides[i]; + } + if (side == Lhs && inner_dim_contiguous) { + eigen_assert(m_nocontract_strides[0] == 1); + linidx[0] += nocontract_val[0]; + linidx[1] += nocontract_val[1]; + } else { + linidx[0] += nocontract_val[0] * m_nocontract_strides[0]; + linidx[1] += nocontract_val[1] * m_nocontract_strides[0]; + } + } + + Index contract_val[2] = {left ? col : row, left ? col : row + distance}; + if (array_size::value> 0) { + for (int i = static_cast(array_size::value) - 1; i > 0; i--) { + const Index idx0 = contract_val[0] / m_k_strides[i]; + const Index idx1 = contract_val[1] / m_k_strides[i]; + linidx[0] += idx0 * m_contract_strides[i]; + linidx[1] += idx1 * m_contract_strides[i]; + contract_val[0] -= idx0 * m_k_strides[i]; + contract_val[1] -= idx1 * m_k_strides[i]; + } + + if (side == Rhs && inner_dim_contiguous) { + eigen_assert(m_contract_strides[0] == 1); + linidx[0] += contract_val[0]; + linidx[1] += contract_val[1]; + } else { + linidx[0] += contract_val[0] * m_contract_strides[0]; + linidx[1] += contract_val[1] * m_contract_strides[0]; + } + } + return IndexPair(linidx[0], linidx[1]); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index firstAligned(Index size) const { + // Only claim alignment when we can compute the actual stride (ie when we're + // dealing with the lhs with inner_dim_contiguous. This is because the + // matrix-vector product relies on the stride when dealing with aligned inputs. + return (Alignment == Aligned) && (side == Lhs) && inner_dim_contiguous ? 0 : size; + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index stride() const { + return ((side == Lhs) && inner_dim_contiguous && array_size::value > 0) ? m_contract_strides[0] : 1; + } + + protected: + CoeffLoader m_tensor; + const nocontract_t m_nocontract_strides; + const nocontract_t m_ij_strides; + const contract_t m_contract_strides; + const contract_t m_k_strides; +}; + + +template +class BaseTensorContractionMapper : public SimpleTensorContractionMapper +{ + public: + typedef SimpleTensorContractionMapper ParentMapper; + + EIGEN_DEVICE_FUNC + BaseTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + typedef typename Tensor::PacketReturnType Packet; + typedef typename unpacket_traits::half HalfPacket; + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadPacket(Index i, Index j) const { + // whole method makes column major assumption + + // don't need to add offsets for now (because operator handles that) + // current code assumes packet size must be a multiple of 2 + EIGEN_STATIC_ASSERT(packet_size % 2 == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + + if (Tensor::PacketAccess && inner_dim_contiguous && !inner_dim_reordered) { + const Index index = this->computeIndex(i, j); + eigen_assert(this->computeIndex(i+packet_size-1, j) == index + packet_size-1); + return this->m_tensor.template packet(index); + } + + const IndexPair indexPair = this->computeIndexPair(i, j, packet_size - 1); + const Index first = indexPair.first; + const Index last = indexPair.second; + + // We can always do optimized packet reads from left hand side right now, because + // the vertical matrix dimension on the left hand side is never contracting. + // On the right hand side we need to check if the contracting dimensions may have + // been shuffled first. + if (Tensor::PacketAccess && + (side == Lhs || internal::array_size::value <= 1 || !inner_dim_reordered) && + (last - first) == (packet_size - 1)) { + + return this->m_tensor.template packet(first); + } + + EIGEN_ALIGN_MAX Scalar data[packet_size]; + + data[0] = this->m_tensor.coeff(first); + for (Index k = 1; k < packet_size - 1; k += 2) { + const IndexPair internal_pair = this->computeIndexPair(i + k, j, 1); + data[k] = this->m_tensor.coeff(internal_pair.first); + data[k + 1] = this->m_tensor.coeff(internal_pair.second); + } + data[packet_size - 1] = this->m_tensor.coeff(last); + + return pload(data); + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE HalfPacket loadHalfPacket(Index i, Index j) const { + // whole method makes column major assumption + + // don't need to add offsets for now (because operator handles that) + const Index half_packet_size = unpacket_traits::size; + if (half_packet_size == packet_size) { + return loadPacket(i, j); + } + EIGEN_ALIGN_MAX Scalar data[half_packet_size]; + for (Index k = 0; k < half_packet_size; k++) { + data[k] = operator()(i + k, j); + } + return pload(data); + } +}; + + +template +class BaseTensorContractionMapper : public SimpleTensorContractionMapper +{ + public: + typedef SimpleTensorContractionMapper ParentMapper; + + EIGEN_DEVICE_FUNC + BaseTensorContractionMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) : + ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + typedef typename Tensor::PacketReturnType Packet; + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadPacket(Index i, Index j) const { + EIGEN_ALIGN_MAX Scalar data[1]; + data[0] = this->m_tensor.coeff(this->computeIndex(i, j)); + return pload(data); + } + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Packet loadHalfPacket(Index i, Index j) const { + return loadPacket(i, j); + } +}; + + +template +class TensorContractionSubMapper { + public: + typedef typename Tensor::PacketReturnType Packet; + typedef typename unpacket_traits::half HalfPacket; + + typedef BaseTensorContractionMapper ParentMapper; + typedef TensorContractionSubMapper Self; + typedef Self LinearMapper; + + enum { + // We can use direct offsets iff the parent mapper supports then and we can compute the strides. + // TODO: we should also enable direct offsets for the Rhs case. + UseDirectOffsets = ParentMapper::DirectOffsets && (side == Lhs) && inner_dim_contiguous && (array_size::value > 0) + }; + + EIGEN_DEVICE_FUNC TensorContractionSubMapper(const ParentMapper& base_mapper, Index vert_offset, Index horiz_offset) + : m_base_mapper(base_mapper), m_vert_offset(vert_offset), m_horiz_offset(horiz_offset) { + // Bake the offsets into the buffer used by the base mapper whenever possible. This avoids the need to recompute + // this offset every time we attempt to access a coefficient. + if (UseDirectOffsets) { + Index stride = m_base_mapper.stride(); + m_base_mapper.offsetBuffer(vert_offset + horiz_offset * stride); + } + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper(i, 0); + } + return m_base_mapper(i + m_vert_offset, m_horiz_offset); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i, Index j) const { + if (UseDirectOffsets) { + return m_base_mapper(i, j); + } + return m_base_mapper(i + m_vert_offset, j + m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, 0); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, m_horiz_offset); + } + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Packet loadPacket(Index i, Index j) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, j); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, j + m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HalfPacket loadHalfPacket(Index i) const { + if (UseDirectOffsets) { + return m_base_mapper.template loadHalfPacket(i, 0); + } + return m_base_mapper.template loadHalfPacket(i + m_vert_offset, m_horiz_offset); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, Packet p) const { + if (UseDirectOffsets) { + m_base_mapper.storePacket(i, 0, p); + } + m_base_mapper.storePacket(i + m_vert_offset, m_horiz_offset, p); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LinearMapper getLinearMapper(Index i, Index j) const { + if (UseDirectOffsets) { + return LinearMapper(m_base_mapper, i, j); + } + return LinearMapper(m_base_mapper, i + m_vert_offset, j + m_horiz_offset); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT load(Index i) const { + EIGEN_STATIC_ASSERT((internal::is_same::value), YOU_MADE_A_PROGRAMMING_MISTAKE); + const int ActualAlignment = (AlignmentType == Aligned) && (Alignment == Aligned) ? Aligned : Unaligned; + if (UseDirectOffsets) { + return m_base_mapper.template loadPacket(i, 0); + } + return m_base_mapper.template loadPacket(i + m_vert_offset, m_horiz_offset); + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool aligned(Index) const { + return false; + } + + private: + ParentMapper m_base_mapper; + const Index m_vert_offset; + const Index m_horiz_offset; +}; + + +template +class TensorContractionInputMapper + : public BaseTensorContractionMapper { + + public: + typedef Scalar_ Scalar; + typedef BaseTensorContractionMapper Base; + typedef TensorContractionSubMapper SubMapper; + typedef SubMapper VectorMapper; + + EIGEN_DEVICE_FUNC TensorContractionInputMapper(const Tensor& tensor, + const nocontract_t& nocontract_strides, + const nocontract_t& ij_strides, + const contract_t& contract_strides, + const contract_t& k_strides) + : Base(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE SubMapper getSubMapper(Index i, Index j) const { + return SubMapper(*this, i, j); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE VectorMapper getVectorMapper(Index i, Index j) const { + return VectorMapper(*this, i, j); + } +}; + + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h new file mode 100644 index 000000000..ee16cde9b --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h @@ -0,0 +1,1052 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H + +// evaluator for thread pool device +#ifdef EIGEN_USE_THREADS + +namespace Eigen { + +#ifdef EIGEN_USE_SIMPLE_THREAD_POOL +namespace internal { + +template +struct packLhsArg { + LhsScalar* blockA; + const LhsMapper& lhs; + const Index m_start; + const Index k_start; + const Index mc; + const Index kc; +}; + +template +struct packRhsAndKernelArg { + const MaxSizeVector* blockAs; + RhsScalar* blockB; + const RhsMapper& rhs; + OutputMapper& output; + const Index m; + const Index k; + const Index n; + const Index mc; + const Index kc; + const Index nc; + const Index num_threads; + const Index num_blockAs; + const Index max_m; + const Index k_block_idx; + const Index m_block_idx; + const Index n_block_idx; + const Index m_blocks; + const Index n_blocks; + MaxSizeVector* kernel_notifications; + const MaxSizeVector* lhs_notifications; + const bool need_to_pack; +}; + +} // end namespace internal +#endif // EIGEN_USE_SIMPLE_THREAD_POOL + +template +struct TensorEvaluator, ThreadPoolDevice> : + public TensorContractionEvaluatorBase, ThreadPoolDevice> > { + + typedef ThreadPoolDevice Device; + + typedef TensorEvaluator, Device> Self; + typedef TensorContractionEvaluatorBase Base; + + typedef TensorContractionOp XprType; + typedef typename internal::remove_const::type Scalar; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + enum { + Layout = TensorEvaluator::Layout, + }; + + // Most of the code is assuming that both input tensors are ColMajor. If the + // inputs are RowMajor, we will "cheat" by swapping the LHS and RHS: + // If we want to compute A * B = C, where A is LHS and B is RHS, the code + // will pretend B is LHS and A is RHS. + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType; + typedef typename internal::conditional< + static_cast(Layout) == static_cast(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType; + + static const int LDims = + internal::array_size::Dimensions>::value; + static const int RDims = + internal::array_size::Dimensions>::value; + static const int ContractDims = internal::array_size::value; + + typedef array left_dim_mapper_t; + typedef array right_dim_mapper_t; + + typedef array contract_t; + typedef array left_nocontract_t; + typedef array right_nocontract_t; + + static const int NumDims = LDims + RDims - 2 * ContractDims; + + typedef DSizes Dimensions; + + // typedefs needed in evalTo + typedef typename internal::remove_const::type LhsScalar; + typedef typename internal::remove_const::type RhsScalar; + typedef typename internal::gebp_traits Traits; + + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + + TensorEvaluator(const XprType& op, const Device& device) : + Base(op, device) {} + +#ifndef EIGEN_USE_SIMPLE_THREAD_POOL + template + void evalProduct(Scalar* buffer) const { + typedef + typename internal::remove_const::type + LhsScalar; + typedef + typename internal::remove_const::type + RhsScalar; + typedef typename internal::gebp_traits Traits; + typedef TensorEvaluator LeftEvaluator; + typedef TensorEvaluator RightEvaluator; + typedef internal::TensorContractionInputMapper< + LhsScalar, Index, internal::Lhs, LeftEvaluator, left_nocontract_t, + contract_t, internal::packet_traits::size, + lhs_inner_dim_contiguous, false, Unaligned> + LhsMapper; + typedef internal::TensorContractionInputMapper< + RhsScalar, Index, internal::Rhs, RightEvaluator, right_nocontract_t, + contract_t, internal::packet_traits::size, + rhs_inner_dim_contiguous, rhs_inner_dim_reordered, Unaligned> + RhsMapper; + typedef internal::blas_data_mapper OutputMapper; + typedef internal::gemm_pack_lhs + LhsPacker; + typedef internal::gemm_pack_rhs< + RhsScalar, Index, typename RhsMapper::SubMapper, Traits::nr, ColMajor> + RhsPacker; + typedef internal::gebp_kernel + GebpKernel; + + const Index m = this->m_i_size; + const Index n = this->m_j_size; + const Index k = this->m_k_size; + if (m == 0 || n == 0 || k == 0) return; + + // Compute a set of algorithm parameters: + // - kernel block sizes (bm, bn, bk) + // - task grain sizes (number of kernels executed per task: gm, gn) + // - number of threads + // - sharding by row/column + // - parallel packing or first lhs then rhs + // and some derived parameters: + // - number of tasks (nm, nn, nk) + // - number of kernels (nm0, nn0) + // Unfortunately, all these parameters are tightly interdependent. + // So in some cases we first compute approximate values, then compute other + // values based on these approximations and then refine the approximations. + + // There are lots of heuristics here. There is some reasoning behind them, + // but ultimately they are just tuned on contraction benchmarks for + // different input configurations, thread counts and instruction sets. + // So feel free to question any of them. + + // Compute whether we want to shard by row or by column. + // This is a first approximation, it will be refined later. Since we don't + // know number of threads yet we use 2, because what's we are most + // interested in at this point is whether it makes sense to use + // parallelization at all or not. + bool shard_by_col = shardByCol(m, n, 2); + + // First approximation of kernel blocking sizes. + // Again, we don't know number of threads yet, so we use 2. + Index bm, bn, bk; + if (shard_by_col) { + internal::TensorContractionBlocking + blocking(k, m, n, 2); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } else { + internal::TensorContractionBlocking + blocking(k, m, n, 2); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } + + // Compute optimal number of threads. + // Note: we use bk instead of k here because we are interested in amount of + // _parallelizable_ computations, and computations are not parallelizable + // across k dimension. + const TensorOpCost cost = + contractionCost(m, n, bm, bn, bk, shard_by_col, false); + int num_threads = TensorCostModel::numThreads( + static_cast(n) * m, cost, this->m_device.numThreads()); + + // TODO(dvyukov): this is a stop-gap to prevent regressions while the cost + // model is not tuned. Remove this when the cost model is tuned. + if (n == 1) num_threads = 1; + + if (num_threads == 1) { + // The single-threaded algorithm should be faster in this case. + if (n == 1) + this->template evalGemv(buffer); + else + this->template evalGemm(buffer); + return; + } + + // Now that we know number of threads, recalculate sharding and blocking. + shard_by_col = shardByCol(m, n, num_threads); + if (shard_by_col) { + internal::TensorContractionBlocking + blocking(k, m, n, num_threads); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } else { + internal::TensorContractionBlocking + blocking(k, m, n, num_threads); + bm = blocking.mc(); + bn = blocking.nc(); + bk = blocking.kc(); + } + + // Number of kernels for each dimension. + Index nm0 = divup(m, bm); + Index nn0 = divup(n, bn); + Index nk = divup(k, bk); + + // Calculate task grain size (number of kernels executed per task). + // This task size coarsening serves two purposes: + // 1. It reduces per-task overheads including synchronization overheads. + // 2. It allows to use caches better (reuse the same packed rhs in several + // consecutive kernels). + Index gm = 1; + Index gn = 1; + // If we are sharding by column, then we prefer to reduce rows first. + if (shard_by_col) { + gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col); + gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col); + } else { + gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col); + gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col); + } + // Number of tasks in each dimension. + Index nm = divup(nm0, gm); + Index nn = divup(nn0, gn); + + // Last by not least, decide whether we want to issue both lhs and rhs + // packing in parallel; or issue lhs packing first, and then issue rhs + // packing when lhs packing completes (for !shard_by_col lhs and rhs are + // swapped). Parallel packing allows more parallelism (for both packing and + // kernels), while sequential packing provides better locality (once + // a thread finishes rhs packing it proceed to kernels with that rhs). + // First, we are interested in parallel packing if there are few tasks. + bool parallel_pack = num_threads >= nm * nn; + // Also do parallel packing if all data fits into L2$. + if (m * bk * Index(sizeof(LhsScalar)) + n * bk * Index(sizeof(RhsScalar)) <= + l2CacheSize() * num_threads) + parallel_pack = true; + // But don't do it if we will use each rhs only once. Locality seems to be + // more important in this case. + if ((shard_by_col ? nm : nn) == 1) parallel_pack = false; + + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, + this->m_i_strides, this->m_left_contracting_strides, + this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, + this->m_j_strides, this->m_right_contracting_strides, + this->m_k_strides); + + Context(this->m_device, num_threads, lhs, rhs, buffer, m, n, + k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, nn0, + shard_by_col, parallel_pack) + .run(); + } + + // Context coordinates a single parallel gemm operation. + template + class Context { + public: + Context(const Device& device, int num_threads, LhsMapper& lhs, + RhsMapper& rhs, Scalar* buffer, Index tm, Index tn, Index tk, Index bm, + Index bn, Index bk, Index nm, Index nn, Index nk, Index gm, + Index gn, Index nm0, Index nn0, bool shard_by_col, + bool parallel_pack) + : device_(device), + lhs_(lhs), + rhs_(rhs), + buffer_(buffer), + output_(buffer, tm), + num_threads_(num_threads), + shard_by_col_(shard_by_col), + parallel_pack_(parallel_pack), + m_(tm), + n_(tn), + k_(tk), + bm_(bm), + bn_(bn), + bk_(bk), + nm_(nm), + nn_(nn), + nk_(nk), + gm_(gm), + gn_(gn), + nm0_(nm0), + nn0_(nn0) + { + for (Index x = 0; x < P; x++) { + // Normal number of notifications for k slice switch is + // nm_ + nn_ + nm_ * nn_. However, first P - 1 slices will receive only + // nm_ + nn_ notifications, because they will not receive notifications + // from preceeding kernels. + state_switch_[x] = + x == 0 + ? 1 + : (parallel_pack_ ? nn_ + nm_ : (shard_by_col_ ? nn_ : nm_)) + + (x == P - 1 ? nm_ * nn_ : 0); + state_packing_ready_[x] = + parallel_pack_ ? 0 : (shard_by_col_ ? nm_ : nn_); + state_kernel_[x] = new std::atomic*[nm_]; + for (Index m = 0; m < nm_; m++) { + state_kernel_[x][m] = new std::atomic[nn_]; + // Kernels generally receive 3 notifications (previous kernel + 2 + // packing), but the first slice won't get notifications from previous + // kernels. + for (Index n = 0; n < nn_; n++) + state_kernel_[x][m][n].store( + (x == 0 ? 0 : 1) + (parallel_pack_ ? 2 : 1), + std::memory_order_relaxed); + } + } + + // Allocate memory for packed rhs/lhs matrices. + size_t align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1); + size_t lhs_size = + divup(bm_ * bk_ * sizeof(LhsScalar), align) * align; + size_t rhs_size = + divup(bn_ * bk_ * sizeof(RhsScalar), align) * align; + packed_mem_ = static_cast(internal::aligned_malloc( + (nm0_ * lhs_size + nn0_ * rhs_size) * std::min(nk_, P - 1))); + char* mem = static_cast(packed_mem_); + for (Index x = 0; x < numext::mini(nk_, P - 1); x++) { + packed_lhs_[x].resize(nm0_); + for (Index m = 0; m < nm0_; m++) { + packed_lhs_[x][m] = reinterpret_cast(mem); + mem += lhs_size; + } + packed_rhs_[x].resize(nn0_); + for (Index n = 0; n < nn0_; n++) { + packed_rhs_[x][n] = reinterpret_cast(mem); + mem += rhs_size; + } + } + } + + ~Context() { + for (Index x = 0; x < P; x++) { + for (Index m = 0; m < nm_; m++) delete[] state_kernel_[x][m]; + delete[] state_kernel_[x]; + } + internal::aligned_free(packed_mem_); + } + + void run() { + // Kick off packing of the first slice. + signal_switch(0, 1); + // Wait for overall completion. + // TODO(dvyukov): this wait can lead to deadlock. + // If nthreads contractions are concurrently submitted from worker + // threads, this wait will block all worker threads and the system will + // deadlock. + done_.Wait(); + } + + private: + Notification done_; + const Device& device_; + LhsMapper& lhs_; + RhsMapper& rhs_; + Scalar* const buffer_; + OutputMapper output_; + const int num_threads_; + const bool shard_by_col_; + const bool parallel_pack_; + // Matrix sizes. + const Index m_; + const Index n_; + const Index k_; + // Block sizes. + const Index bm_; + const Index bn_; + const Index bk_; + // Number of tasks. + const Index nm_; + const Index nn_; + const Index nk_; + // Task grain sizes (number of kernels executed per task). + const Index gm_; + const Index gn_; + // Number of blocks (this is different from ni_/nn_ because of task size + // coarsening). + const Index nm0_; + const Index nn0_; + + // Parallelization strategy. + // + // Blocks related to the same k block can run in parallel because they write + // to different output blocks. So we parallelize within k slices, this + // gives us parallelism level of m x n. Before we can start any kernels + // related to k-th slice, we need to issue m lhs packing tasks and n rhs + // packing tasks. + // + // However, there is a bottleneck when we are finishing kernels for k-th + // slice (at the very end there is only 1 runnable kernel). To mitigate this + // bottleneck we allow kernels from k-th and k+1-th slices to run in + // parallel. Note that (m, n, k) and (m, n, k+1) kernels write to the same + // output block, so they must not run in parallel. + // + // This gives us the following dependency graph. + // On each k slice we have m x n kernel tasks, m lhs paking tasks and n rhs + // packing tasks. + // Kernel (m, n, k) can start when: + // - kernel (m, n, k-1) has finished + // - lhs packing (m, k) has finished + // - rhs packing (n, k) has finished + // Lhs/rhs packing can start when: + // - all k-1 packing has finished (artificially imposed to limit amount of + // parallel packing) + // + // On top of that we limit runnable tasks to two consecutive k slices. + // This is done to limit amount of memory we need for packed lhs/rhs + // (for each k slice we need m*bk + n*bk memory in packed_lhs_/packed_rhs_). + // + // state_switch_ tracks when we are ready to switch to the next k slice. + // state_kernel_[m][n] tracks when we are ready to kick off kernel (m, n). + // These variable are rolling over 3 consecutive k slices: first two we are + // actively executing + one to track completion of kernels in the second + // slice. + static const Index P = 3; + void* packed_mem_; + std::vector packed_lhs_[P - 1]; + std::vector packed_rhs_[P - 1]; + std::atomic** state_kernel_[P]; + // state_switch_ is frequently modified by worker threads, while other + // fields are read-only after constructor. Let's move it to a separate cache + // line to reduce cache-coherency traffic. + char pad_[128]; + std::atomic state_packing_ready_[P]; + std::atomic state_switch_[P]; + + void pack_lhs(Index m, Index k) { + const Index mend = m * gm_ + gm(m); + for (Index m1 = m * gm_; m1 < mend; m1++) + LhsPacker()(packed_lhs_[k % (P - 1)][m1], + lhs_.getSubMapper(m1 * bm_, k * bk_), bk(k), bm(m1)); + + if (!parallel_pack_ && shard_by_col_) { + signal_packing(k); + } else { + signal_switch(k + 1); + for (Index n = nn_ - 1; n >= 0; n--) signal_kernel(m, n, k, n == 0); + } + } + + void pack_rhs(Index n, Index k) { + const Index nend = n * gn_ + gn(n); + for (Index n1 = n * gn_; n1 < nend; n1++) { + if (k == 0) { + // Zero the output memory in parallel. + // On 10000x2x10000 mm zeroing can easily take half of time. + // Zero (bn x m) row. Safe to do here because all kernels that will + // write to this memory depend on completion of this task. + // Note: don't call device_.memset() here. device_.memset() blocks on + // thread pool worker thread, which can lead to underutilization and + // deadlocks. + memset(buffer_ + n1 * bn_ * m_, 0, bn(n1) * m_ * sizeof(Scalar)); + } + RhsPacker()(packed_rhs_[k % (P - 1)][n1], + rhs_.getSubMapper(k * bk_, n1 * bn_), bk(k), bn(n1)); + } + + if (parallel_pack_ || shard_by_col_) { + signal_switch(k + 1); + for (Index m = nm_ - 1; m >= 0; m--) signal_kernel(m, n, k, m == 0); + } else { + signal_packing(k); + } + } + + void kernel(Index m, Index n, Index k) { + // Note: order of iteration matters here. Iteration over m is innermost + // because we want to reuse the same packed rhs in consequetive tasks + // (rhs fits into L2$ while lhs only into L3$). + const Index nend = n * gn_ + gn(n); + const Index mend = m * gm_ + gm(m); + if (shard_by_col_) { + for (Index n1 = n * gn_; n1 < nend; n1++) { + for (Index m1 = m * gm_; m1 < mend; m1++) + GebpKernel()(output_.getSubMapper(m1 * bm_, n1 * bn_), + packed_lhs_[k % (P - 1)][m1], + packed_rhs_[k % (P - 1)][n1], bm(m1), bk(k), bn(n1), + Scalar(1), -1, -1, 0, 0); + } + } else { + for (Index m1 = m * gm_; m1 < mend; m1++) + for (Index n1 = n * gn_; n1 < nend; n1++) { + GebpKernel()(output_.getSubMapper(m1 * bm_, n1 * bn_), + packed_lhs_[k % (P - 1)][m1], + packed_rhs_[k % (P - 1)][n1], bm(m1), bk(k), bn(n1), + Scalar(1), -1, -1, 0, 0); + } + } + signal_kernel(m, n, k + 1, false); + signal_switch(k + 2); + } + + void signal_packing(Index k) { + eigen_assert(!parallel_pack_); + Index s = state_packing_ready_[k % P].fetch_sub(1); + eigen_assert(s > 0); + if (s != 1) return; + state_packing_ready_[k % P] = shard_by_col_ ? nm_ : nn_; + enqueue_packing(k, shard_by_col_); + } + + void signal_kernel(Index m, Index n, Index k, bool sync) { + std::atomic* state = &state_kernel_[k % P][m][n]; + Index s = state->load(); + eigen_assert(s > 0); + if (s != 1 && state->fetch_sub(1) != 1) return; + state->store(parallel_pack_ ? 3 : 2, std::memory_order_relaxed); + if (sync) + kernel(m, n, k); + else + device_.enqueueNoNotification([=]() { kernel(m, n, k); }); + } + + void signal_switch(Index k, Index v = 1) { + Index s = state_switch_[k % P].fetch_sub(v); + eigen_assert(s >= v); + if (s != v) return; + + // Ready to switch to the next k slice. + // Reset counter for the next iteration. + state_switch_[k % P] = + (parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)) + + nm_ * nn_; + if (k < nk_) { + // Issue lhs/rhs packing. Their completion will in turn kick off + // kernels. + if (parallel_pack_) { + enqueue_packing(k, !shard_by_col_); + enqueue_packing(k, shard_by_col_); + } else if (shard_by_col_) { + enqueue_packing(k, false); + } else { + enqueue_packing(k, true); + } + + // Termination handling. + // Because kernel completion signals k + 2 switch, we need to finish nk + // + 2 slices without issuing any tasks on nk + 1 slice. So here we + // pretend that all nk + 1 packing tasks just finish instantly; so that + // nk + 2 switch only waits for completion of nk kernels. + } else if (k == nk_) { + signal_switch(k + 1, + parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)); + } else { + done_.Notify(); + } + } + + // Enqueue all rhs/lhs packing for k-th slice. + void enqueue_packing(Index k, bool rhs) { + enqueue_packing_helper(0, rhs ? nn_ : nm_, k, rhs); + } + + void enqueue_packing_helper(Index start, Index end, Index k, bool rhs) { + if (end - start == 1) { + if (rhs) + pack_rhs(start, k); + else + pack_lhs(start, k); + } else { + Index mid = (start + end) / 2; + device_.enqueueNoNotification( + [=]() { enqueue_packing_helper(mid, end, k, rhs); }); + device_.enqueueNoNotification( + [=]() { enqueue_packing_helper(start, mid, k, rhs); }); + } + } + + // Block sizes with accounting for potentially incomplete last block. + Index bm(Index m) const { return m + 1 < nm0_ ? bm_ : m_ + bm_ - bm_ * nm0_; } + Index bn(Index n) const { return n + 1 < nn0_ ? bn_ : n_ + bn_ - bn_ * nn0_; } + Index bk(Index k) const { return k + 1 < nk_ ? bk_ : k_ + bk_ - bk_ * nk_; } + // Task grain sizes accounting for potentially incomplete last task. + Index gm(Index m) const { return m + 1 < nm_ ? gm_ : nm0_ + gm_ - gm_ * nm_; } + Index gn(Index n) const { return n + 1 < nn_ ? gn_ : nn0_ + gn_ - gn_ * nn_; } + + Context(const Context&) = delete; + void operator=(const Context&) = delete; + }; + + // Decide whether we want to shard m x n contraction by columns or by rows. + static bool shardByCol(Index m, Index n, Index num_threads) { + // Note: we are comparing both n and m against Traits::nr, it is not + // a mistake. We are trying to figure out how both n and m will fit into + // the main sharding dimension. + + // Sharding by column is the default + // ... unless there is enough data for vectorization over rows + if (m / num_threads >= Traits::nr && + // and not enough data for vectorization over columns + (n / num_threads < Traits::nr || + // ... or barely enough data for vectorization over columns, + // but it is not evenly dividable across threads + (n / num_threads < 4 * Traits::nr && + (n % (num_threads * Traits::nr)) != 0 && + // ... and it is evenly dividable across threads for rows + ((m % (num_threads * Traits::nr)) == 0 || + // .. or it is not evenly dividable for both dimensions but + // there is much more data over rows so that corner effects are + // mitigated. + (m / n >= 6))))) + return false; + // Wait, or if matrices are just substantially prolonged over the other + // dimension. + if (n / num_threads < 16 * Traits::nr && m > n * 32) return false; + return true; + } + + Index coarsenM(Index m, Index n, Index bm, Index bn, Index bk, Index gn, + int num_threads, bool shard_by_col) const { + Index gm = 1; + Index gm1 = 1; + Index nm0 = divup(m, bm); + Index nm1 = nm0; + for (;;) { + // Find the next candidate for m grain size. It needs to result in + // different number of blocks. E.g. if we have 10 kernels, we want to try + // 5 and 10, but not 6, 7, 8 and 9. + while (gm1 <= nm0 && nm1 == divup(nm0, gm1)) gm1++; + if (gm1 > nm0) break; + // Check the candidate. + int res = checkGrain(m, n, bm, bn, bk, gm1, gn, gm, gn, num_threads, + shard_by_col); + if (res < 0) break; + nm1 = divup(nm0, gm1); + if (res == 0) continue; + // Commit new grain size. + gm = gm1; + } + return gm; + } + + Index coarsenN(Index m, Index n, Index bm, Index bn, Index bk, Index gm, + int num_threads, bool shard_by_col) const { + Index gn = 1; + Index gn1 = 1; + Index nn0 = divup(n, bn); + Index nn1 = nn0; + for (;;) { + while (gn1 <= nn0 && nn1 == divup(nn0, gn1)) gn1++; + if (gn1 > nn0) break; + int res = checkGrain(m, n, bm, bn, bk, gm, gn1, gm, gn, num_threads, + shard_by_col); + if (res < 0) break; + nn1 = divup(nn0, gn1); + if (res == 0) continue; + gn = gn1; + } + return gn; + } + + // checkGrain checks whether grain (gm, gn) is suitable and is better than + // (oldgm, oldgn). + int checkGrain(Index m, Index n, Index bm, Index bn, Index bk, Index gm, + Index gn, Index oldgm, Index oldgn, int num_threads, + bool shard_by_col) const { + const TensorOpCost cost = + contractionCost(bm * gm, bn * gn, bm, bn, bk, shard_by_col, true); + double taskSize = TensorCostModel::taskSize( + static_cast(bm) * gm * bn * gn, cost); + // If the task is too small, then we agree on it regardless of anything + // else. Otherwise synchronization overheads will dominate. + if (taskSize < 1) return 1; + // If it is too large, then we reject it and all larger tasks. + if (taskSize > 2) return -1; + // Now we are in presumably good task size range. + // The main deciding factor here is parallelism. Consider that we have 12 + // kernels and 4 threads. Grains of 2, 3 and 4 all yield good task sizes. + // But 2/4 yield 6/3 tasks, which gives us parallelism of 0.75 (at most 3/4 + // of cores will be busy). While grain size 3 gives us 4 tasks, which gives + // us parallelism of 1 (we can load all cores). + Index nm0 = divup(m, bm); + Index nn0 = divup(n, bn); + Index new_tasks = divup(nm0, gm) * divup(nn0, gn); + double new_parallelism = static_cast(new_tasks) / + (divup(new_tasks, num_threads) * num_threads); + Index old_tasks = divup(nm0, oldgm) * divup(nn0, oldgn); + double old_parallelism = static_cast(old_tasks) / + (divup(old_tasks, num_threads) * num_threads); + if (new_parallelism > old_parallelism || new_parallelism == 1) return 1; + return 0; + } + +#else // EIGEN_USE_SIMPLE_THREAD_POOL + + template + void evalProduct(Scalar* buffer) const { + if (this->m_j_size == 1) { + this->template evalGemv(buffer); + return; + } + + evalGemm(buffer); + } + + template + void evalGemm(Scalar* buffer) const { + // columns in left side, rows in right side + const Index k = this->m_k_size; + + // rows in left side + const Index m = this->m_i_size; + + // columns in right side + const Index n = this->m_j_size; + + // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar) + this->m_device.memset(buffer, 0, m * n * sizeof(Scalar)); + + + const int lhs_packet_size = internal::unpacket_traits::size; + const int rhs_packet_size = internal::unpacket_traits::size; + + typedef internal::TensorContractionInputMapper LhsMapper; + + typedef internal::TensorContractionInputMapper RhsMapper; + + typedef internal::blas_data_mapper OutputMapper; + + // TODO: packing could be faster sometimes if we supported row major tensor mappers + typedef internal::gemm_pack_lhs LhsPacker; + typedef internal::gemm_pack_rhs RhsPacker; + + // TODO: replace false, false with conjugate values? + typedef internal::gebp_kernel GebpKernel; + + typedef internal::packLhsArg packLArg; + typedef internal::packRhsAndKernelArg packRKArg; + + // initialize data mappers + LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides, + this->m_left_contracting_strides, this->m_k_strides); + + RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides, + this->m_right_contracting_strides, this->m_k_strides); + + OutputMapper output(buffer, m); + + // compute block sizes (which depend on number of threads) + const Index num_threads = this->m_device.numThreads(); + internal::TensorContractionBlocking blocking(k, m, n, num_threads); + Index mc = blocking.mc(); + Index nc = blocking.nc(); + Index kc = blocking.kc(); + eigen_assert(mc <= m); + eigen_assert(nc <= n); + eigen_assert(kc <= k); + +#define CEIL_DIV(a, b) (((a) + (b) - 1) / (b)) + const Index k_blocks = CEIL_DIV(k, kc); + const Index n_blocks = CEIL_DIV(n, nc); + const Index m_blocks = CEIL_DIV(m, mc); + const Index sizeA = mc * kc; + const Index sizeB = kc * nc; + + /* cout << "m: " << m << " n: " << n << " k: " << k << endl; + cout << "mc: " << mc << " nc: " << nc << " kc: " << kc << endl; + cout << "m_blocks: " << m_blocks << " n_blocks: " << n_blocks << " k_blocks: " << k_blocks << endl; + cout << "num threads: " << num_threads << endl; + */ + + // note: m_device.allocate should return 16 byte aligned pointers, but if blockA and blockB + // aren't 16 byte aligned segfaults will happen due to SIMD instructions + // note: You can get away with allocating just a single blockA and offsets and meet the + // the alignment requirements with the assumption that + // (Traits::mr * sizeof(ResScalar)) % 16 == 0 + const Index numBlockAs = numext::mini(num_threads, m_blocks); + MaxSizeVector blockAs(num_threads); + for (int i = 0; i < num_threads; i++) { + blockAs.push_back(static_cast(this->m_device.allocate(sizeA * sizeof(LhsScalar)))); + } + + // To circumvent alignment issues, I'm just going to separately allocate the memory for each thread + // TODO: is this too much memory to allocate? This simplifies coding a lot, but is wasteful. + // Other options: (1) reuse memory when a thread finishes. con: tricky + // (2) allocate block B memory in each thread. con: overhead + MaxSizeVector blockBs(n_blocks); + for (int i = 0; i < n_blocks; i++) { + blockBs.push_back(static_cast(this->m_device.allocate(sizeB * sizeof(RhsScalar)))); + } + + // lhs_notifications starts with all null Notifications + MaxSizeVector lhs_notifications(num_threads, nullptr); + + // this should really be numBlockAs * n_blocks; + const Index num_kernel_notifications = num_threads * n_blocks; + MaxSizeVector kernel_notifications(num_kernel_notifications, + nullptr); + + for (Index k_block_idx = 0; k_block_idx < k_blocks; k_block_idx++) { + const Index k_start = k_block_idx * kc; + // make sure we don't overshoot right edge of left matrix + const Index actual_kc = numext::mini(k_start + kc, k) - k_start; + + for (Index m_block_idx = 0; m_block_idx < m_blocks; m_block_idx += numBlockAs) { + const Index num_blocks = numext::mini(m_blocks-m_block_idx, numBlockAs); + + for (Index mt_block_idx = m_block_idx; mt_block_idx < m_block_idx+num_blocks; mt_block_idx++) { + const Index m_start = mt_block_idx * mc; + const Index actual_mc = numext::mini(m_start + mc, m) - m_start; + eigen_assert(actual_mc > 0); + + Index blockAId = (k_block_idx * m_blocks + mt_block_idx) % num_threads; + + for (int i = 0; i < n_blocks; ++i) { + Index notification_id = (blockAId * n_blocks + i); + // Wait for any current kernels using this slot to complete + // before using it. + if (kernel_notifications[notification_id]) { + wait_until_ready(kernel_notifications[notification_id]); + delete kernel_notifications[notification_id]; + } + kernel_notifications[notification_id] = new Notification(); + } + const packLArg arg = { + blockAs[blockAId], // blockA + lhs, // lhs + m_start, // m + k_start, // k + actual_mc, // mc + actual_kc, // kc + }; + + // Delete any existing notification since we may be + // replacing it. The algorithm should ensure that there are + // no existing waiters on this notification. + delete lhs_notifications[blockAId]; + lhs_notifications[blockAId] = + this->m_device.enqueue(&Self::packLhs, arg); + } + + // now start kernels. + const Index m_base_start = m_block_idx * mc; + const bool need_to_pack = m_block_idx == 0; + + for (Index n_block_idx = 0; n_block_idx < n_blocks; n_block_idx++) { + const Index n_start = n_block_idx * nc; + const Index actual_nc = numext::mini(n_start + nc, n) - n_start; + + // first make sure the previous kernels are all done before overwriting rhs. Also wait if + // we're going to start new k. In both cases need_to_pack is true. + if (need_to_pack) { + for (Index i = num_blocks; i < num_threads; ++i) { + Index blockAId = (k_block_idx * m_blocks + i + m_block_idx) % num_threads; + Index future_id = (blockAId * n_blocks + n_block_idx); + wait_until_ready(kernel_notifications[future_id]); + } + } + + packRKArg arg = { + &blockAs, // blockA + blockBs[n_block_idx], // blockB + rhs, // rhs + output, // output + m_base_start, // m + k_start, // k + n_start, // n + mc, // mc + actual_kc, // kc + actual_nc, // nc + num_threads, + numBlockAs, + m, + k_block_idx, + m_block_idx, + n_block_idx, // n_block_idx + m_blocks, // m_blocks + n_blocks, // n_blocks + &kernel_notifications, // kernel notifications + &lhs_notifications, // lhs notifications + need_to_pack, // need_to_pack + }; + + // We asynchronously kick off this function, which ends up + // notifying the appropriate kernel_notifications objects, + // which this thread waits on before exiting. + this->m_device.enqueueNoNotification(&Self::packRhsAndKernel, arg); + } + } + } + + // Make sure all the kernels are done. + for (size_t i = 0; i < kernel_notifications.size(); ++i) { + wait_until_ready(kernel_notifications[i]); + delete kernel_notifications[i]; + } + + // No need to wait for lhs notifications since they should have + // already been waited on. Just clean them up. + for (size_t i = 0; i < lhs_notifications.size(); ++i) { + delete lhs_notifications[i]; + } + + // deallocate all of the memory for both A and B's + for (size_t i = 0; i < blockAs.size(); i++) { + this->m_device.deallocate(blockAs[i]); + } + for (size_t i = 0; i < blockBs.size(); i++) { + this->m_device.deallocate(blockBs[i]); + } + +#undef CEIL_DIV + } + + /* + * Packs a LHS block of size (mt, kc) starting at lhs(m, k). Before packing + * the LHS block, check that all of the kernels that worked on the same + * mt_block_idx in the previous m_block are done. + */ + template + static void packLhs(const packLArg arg) { + // perform actual packing + LhsPacker pack_lhs; + pack_lhs(arg.blockA, arg.lhs.getSubMapper(arg.m_start, arg.k_start), arg.kc, arg.mc); + } + + /* + * Packs a RHS block of size (kc, nc) starting at (k, n) after checking that + * all kernels in the previous block are done. + * Then for each LHS future, we wait on the future and then call GEBP + * on the area packed by the future (which starts at + * blockA + future_idx * mt * kc) on the LHS and with the full packed + * RHS block. + * The output of this GEBP is written to output(m + i * mt, n). + */ + template + static void packRhsAndKernel(packRKArg arg) { + if (arg.need_to_pack) { + RhsPacker pack_rhs; + pack_rhs(arg.blockB, arg.rhs.getSubMapper(arg.k, arg.n), arg.kc, arg.nc); + } + + GebpKernel gebp; + for (Index mt_block_idx = 0; mt_block_idx < arg.num_blockAs; mt_block_idx++) { + const Index m_base_start = arg.m + arg.mc*mt_block_idx; + if (m_base_start < arg.max_m) { + Index blockAId = (arg.k_block_idx * arg.m_blocks + mt_block_idx + arg.m_block_idx) % arg.num_threads; + wait_until_ready((*arg.lhs_notifications)[blockAId]); + const Index actual_mc = numext::mini(m_base_start + arg.mc, arg.max_m) - m_base_start; + gebp(arg.output.getSubMapper(m_base_start, arg.n), + (*arg.blockAs)[blockAId], arg.blockB, + actual_mc, arg.kc, arg.nc, Scalar(1), -1, -1, 0, 0); + + // Notify that the kernel is done. + const Index set_idx = blockAId * arg.n_blocks + arg.n_block_idx; + (*arg.kernel_notifications)[set_idx]->Notify(); + } + } + } +#endif // EIGEN_USE_SIMPLE_THREAD_POOL + + TensorOpCost contractionCost(Index m, Index n, Index bm, Index bn, Index bk, + bool shard_by_col, bool prepacked) const { + const int packed_size = std::min(PacketType::size, + PacketType::size); + const int output_packet_size = internal::unpacket_traits::size; + const double kd = static_cast(bk); + // Peak VFMA bandwidth is 0.5. However if we have not enough data for + // vectorization bandwidth drops. The 4.0 and 2.0 bandwidth is determined + // experimentally. + double computeBandwidth = bk == 1 ? 4.0 : + (shard_by_col ? bn : bm) < Traits::nr || + (shard_by_col ? bm : bn) < Traits::mr ? 2.0 : 0.5; +#ifndef EIGEN_VECTORIZE_FMA + // Bandwidth of all of VFMA/MULPS/ADDPS is 0.5 on latest Intel processors. + // However for MULPS/ADDPS we have dependent sequence of 2 such instructions, + // so overall bandwidth is 1.0. + if (computeBandwidth == 0.5) computeBandwidth = 1.0; +#endif + // Computations. + TensorOpCost cost = TensorOpCost(0, 0, kd * computeBandwidth, true, packed_size); + // Output stores. + cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size); + if (prepacked) { + // Packing and kernels are executed in different tasks. When we calculate + // task grain size we look only at kernel cost assuming that kernel + // is more expensive than packing. + return cost; + } + // Lhs/rhs loads + computations. + TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * (kd / n); + TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * (kd / m); + // Lhs packing memory cost does not contribute considerably to overall + // execution time because lhs is prefetched early and accessed sequentially. + if (shard_by_col) + lhsCost.dropMemoryCost(); + else + rhsCost.dropMemoryCost(); + return cost + lhsCost + rhsCost; + } +}; + +} // end namespace Eigen + +#endif // EIGEN_USE_THREADS +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h new file mode 100644 index 000000000..860a6949a --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h @@ -0,0 +1,279 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H + +namespace Eigen { + +/** \class TensorConversionOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor conversion class. This class makes it possible to vectorize + * type casting operations when the number of scalars per packet in the source + * and the destination type differ + */ +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef TargetType Scalar; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + enum { Flags = 0 }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConversionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConversionOp type; +}; + +} // end namespace internal + + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + return internal::pcast(m_impl.template packet(index)); + } + + private: + const TensorEvaluator& m_impl; +}; + + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + + SrcPacket src1 = m_impl.template packet(index); + SrcPacket src2 = m_impl.template packet(index + SrcPacketSize); + TgtPacket result = internal::pcast(src1, src2); + return result; + } + + private: + const TensorEvaluator& m_impl; +}; + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + + SrcPacket src1 = m_impl.template packet(index); + SrcPacket src2 = m_impl.template packet(index + SrcPacketSize); + SrcPacket src3 = m_impl.template packet(index + 2 * SrcPacketSize); + SrcPacket src4 = m_impl.template packet(index + 3 * SrcPacketSize); + TgtPacket result = internal::pcast(src1, src2, src3, src4); + return result; + } + + private: + const TensorEvaluator& m_impl; +}; + +template +struct PacketConverter { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketConverter(const TensorEvaluator& impl) + : m_impl(impl), m_maxIndex(impl.dimensions().TotalSize()) {} + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const { + const int SrcPacketSize = internal::unpacket_traits::size; + // Only call m_impl.packet() when we have direct access to the underlying data. This + // ensures that we don't compute the subexpression twice. We may however load some + // coefficients twice, but in practice this doesn't negatively impact performance. + if (m_impl.data() && (index + SrcPacketSize < m_maxIndex)) { + // Force unaligned memory loads since we can't ensure alignment anymore + return internal::pcast(m_impl.template packet(index)); + } else { + const int TgtPacketSize = internal::unpacket_traits::size; + typedef typename internal::unpacket_traits::type SrcType; + typedef typename internal::unpacket_traits::type TgtType; + internal::scalar_cast_op converter; + EIGEN_ALIGN_MAX typename internal::unpacket_traits::type values[TgtPacketSize]; + for (int i = 0; i < TgtPacketSize; ++i) { + values[i] = converter(m_impl.coeff(index+i)); + } + TgtPacket rslt = internal::pload(values); + return rslt; + } + } + + private: + const TensorEvaluator& m_impl; + const typename TensorEvaluator::Index m_maxIndex; +}; + +template +class TensorConversionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::nested::type Nested; + typedef Scalar CoeffReturnType; + typedef typename NumTraits::Real RealScalar; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConversionOp(const XprType& xpr) + : m_xpr(xpr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + +template struct ConversionSubExprEval { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, Scalar*) { + impl.evalSubExprsIfNeeded(NULL); + return true; + } +}; + +template struct ConversionSubExprEval { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, Scalar* data) { + return impl.evalSubExprsIfNeeded(data); + } +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorConversionOp XprType; + typedef typename XprType::Index Index; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef TargetType Scalar; + typedef TargetType CoeffReturnType; + typedef typename internal::remove_all::Scalar>::type SrcType; + typedef typename PacketType::type PacketReturnType; + typedef typename PacketType::type PacketSourceType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = true, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) + { + return ConversionSubExprEval::value, TensorEvaluator, Scalar>::run(m_impl, data); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() + { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + internal::scalar_cast_op converter; + return converter(m_impl.coeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const bool Vectorizable = TensorEvaluator::PacketAccess & + internal::type_casting_traits::VectorizedCast; + return PacketConv::run(m_impl, index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double cast_cost = TensorOpCost::CastCost(); + if (vectorized) { + const double SrcCoeffRatio = + internal::type_casting_traits::SrcCoeffRatio; + const double TgtCoeffRatio = + internal::type_casting_traits::TgtCoeffRatio; + return m_impl.costPerCoeff(vectorized) * (SrcCoeffRatio / PacketSize) + + TensorOpCost(0, 0, TgtCoeffRatio * (cast_cost / PacketSize)); + } else { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, cast_cost); + } + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + template + struct PacketConv { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType run(const TensorEvaluator& impl, Index index) { + internal::scalar_cast_op converter; + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = converter(impl.coeff(index+i)); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + }; + + template + struct PacketConv { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType run(const TensorEvaluator& impl, Index index) { + const int SrcCoeffRatio = internal::type_casting_traits::SrcCoeffRatio; + const int TgtCoeffRatio = internal::type_casting_traits::TgtCoeffRatio; + PacketConverter, PacketSourceType, PacketReturnType, + SrcCoeffRatio, TgtCoeffRatio> converter(impl); + return converter.template packet(index); + } + }; + + TensorEvaluator m_impl; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h new file mode 100644 index 000000000..abdf742c6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h @@ -0,0 +1,1104 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H + +namespace Eigen { + +/** \class TensorConvolution + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor convolution class. + * + * + */ +namespace internal { + +template +class IndexMapper { + public: + IndexMapper(const InputDims& input_dims, const array& kernel_dims, + const array& indices) { + + array dimensions = input_dims; + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = indices[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + dimensions[index] = result_dim; + } + + array inputStrides; + array outputStrides; + if (static_cast(Layout) == static_cast(ColMajor)) { + inputStrides[0] = 1; + outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + inputStrides[i] = inputStrides[i-1] * input_dims[i-1]; + outputStrides[i] = outputStrides[i-1] * dimensions[i-1]; + } + } else { + inputStrides[NumDims - 1] = 1; + outputStrides[NumDims - 1] = 1; + for (int i = static_cast(NumDims) - 2; i >= 0; --i) { + inputStrides[i] = inputStrides[i + 1] * input_dims[i + 1]; + outputStrides[i] = outputStrides[i + 1] * dimensions[i + 1]; + } + } + + array cudaInputDimensions; + array cudaOutputDimensions; + array tmp = dimensions; + array ordering; + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = i + offset; + ordering[index] = indices[i]; + tmp[indices[i]] = -1; + cudaInputDimensions[index] = input_dims[indices[i]]; + cudaOutputDimensions[index] = dimensions[indices[i]]; + } + + int written = static_cast(Layout) == static_cast(ColMajor) + ? NumKernelDims + : 0; + for (int i = 0; i < NumDims; ++i) { + if (tmp[i] >= 0) { + ordering[written] = i; + cudaInputDimensions[written] = input_dims[i]; + cudaOutputDimensions[written] = dimensions[i]; + ++written; + } + } + + for (int i = 0; i < NumDims; ++i) { + m_inputStrides[i] = inputStrides[ordering[i]]; + m_outputStrides[i] = outputStrides[ordering[i]]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + if (i > NumKernelDims) { + m_cudaInputStrides[i] = + m_cudaInputStrides[i - 1] * cudaInputDimensions[i - 1]; + m_cudaOutputStrides[i] = + m_cudaOutputStrides[i - 1] * cudaOutputDimensions[i - 1]; + } else { + m_cudaInputStrides[i] = 1; + m_cudaOutputStrides[i] = 1; + } + } + } else { + for (int i = NumDims - 1; i >= 0; --i) { + if (i + 1 < offset) { + m_cudaInputStrides[i] = + m_cudaInputStrides[i + 1] * cudaInputDimensions[i + 1]; + m_cudaOutputStrides[i] = + m_cudaOutputStrides[i + 1] * cudaOutputDimensions[i + 1]; + } else { + m_cudaInputStrides[i] = 1; + m_cudaOutputStrides[i] = 1; + } + } + } + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputPlaneToTensorInputOffset(Index p) const { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int d = NumDims - 1; d > NumKernelDims; --d) { + const Index idx = p / m_cudaInputStrides[d]; + inputIndex += idx * m_inputStrides[d]; + p -= idx * m_cudaInputStrides[d]; + } + inputIndex += p * m_inputStrides[NumKernelDims]; + } else { + std::ptrdiff_t limit = 0; + if (NumKernelDims < NumDims) { + limit = NumDims - NumKernelDims - 1; + } + for (int d = 0; d < limit; ++d) { + const Index idx = p / m_cudaInputStrides[d]; + inputIndex += idx * m_inputStrides[d]; + p -= idx * m_cudaInputStrides[d]; + } + inputIndex += p * m_inputStrides[limit]; + } + return inputIndex; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputPlaneToTensorOutputOffset(Index p) const { + Index outputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int d = NumDims - 1; d > NumKernelDims; --d) { + const Index idx = p / m_cudaOutputStrides[d]; + outputIndex += idx * m_outputStrides[d]; + p -= idx * m_cudaOutputStrides[d]; + } + outputIndex += p * m_outputStrides[NumKernelDims]; + } else { + std::ptrdiff_t limit = 0; + if (NumKernelDims < NumDims) { + limit = NumDims - NumKernelDims - 1; + } + for (int d = 0; d < limit; ++d) { + const Index idx = p / m_cudaOutputStrides[d]; + outputIndex += idx * m_outputStrides[d]; + p -= idx * m_cudaOutputStrides[d]; + } + outputIndex += p * m_outputStrides[limit]; + } + return outputIndex; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i, Index j) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i, Index j) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaInputKernelToTensorInputOffset(Index i, Index j, Index k) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1] + + k * m_inputStrides[offset + 2]; + } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapCudaOutputKernelToTensorOutputOffset(Index i, Index j, Index k) const { + const size_t offset = static_cast(Layout) == static_cast(ColMajor) + ? 0 + : NumDims - NumKernelDims; + return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1] + + k * m_outputStrides[offset + 2]; + } + + private: + static const int NumDims = internal::array_size::value; + array m_inputStrides; + array m_outputStrides; + array m_cudaInputStrides; + array m_cudaOutputStrides; +}; + + + +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename promote_storage_type::ret Scalar; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename InputXprType::Nested LhsNested; + typedef typename KernelXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorConvolutionOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorConvolutionOp type; +}; + +} // end namespace internal + + + +template +class TensorConvolutionOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConvolutionOp(const InputXprType& input, const KernelXprType& kernel, const Indices& dims) + : m_input_xpr(input), m_kernel_xpr(kernel), m_indices(dims) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Indices& indices() const { return m_indices; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& + inputExpression() const { return m_input_xpr; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const typename internal::remove_all::type& + kernelExpression() const { return m_kernel_xpr; } + + protected: + typename InputXprType::Nested m_input_xpr; + typename KernelXprType::Nested m_kernel_xpr; + const Indices m_indices; +}; + + +template +struct TensorEvaluator, Device> +{ + typedef TensorConvolutionOp XprType; + + static const int NumDims = internal::array_size::Dimensions>::value; + static const int NumKernelDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_kernel(NULL), m_local_kernel(false), m_device(device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + + const typename TensorEvaluator::Dimensions& input_dims = m_inputImpl.dimensions(); + const typename TensorEvaluator::Dimensions& kernel_dims = m_kernelImpl.dimensions(); + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStride[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStride[i] = m_inputStride[i - 1] * input_dims[i - 1]; + } + } else { + m_inputStride[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStride[i] = m_inputStride[i + 1] * input_dims[i + 1]; + } + } + + m_dimensions = m_inputImpl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + if (i > 0) { + m_kernelStride[i] = m_kernelStride[i - 1] * kernel_dims[i - 1]; + } else { + m_kernelStride[0] = 1; + } + m_indexStride[i] = m_inputStride[index]; + } + + m_outputStride[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStride[i] = m_outputStride[i - 1] * m_dimensions[i - 1]; + } + } else { + for (int i = NumKernelDims - 1; i >= 0; --i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + if (i < NumKernelDims - 1) { + m_kernelStride[i] = m_kernelStride[i + 1] * kernel_dims[i + 1]; + } else { + m_kernelStride[NumKernelDims - 1] = 1; + } + m_indexStride[i] = m_inputStride[index]; + } + + m_outputStride[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStride[i] = m_outputStride[i + 1] * m_dimensions[i + 1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_inputImpl.evalSubExprsIfNeeded(NULL); + preloadKernel(); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_inputImpl.cleanup(); + if (m_local_kernel) { + m_device.deallocate((void*)m_kernel); + m_local_kernel = false; + } + m_kernel = NULL; + } + + void evalTo(typename XprType::Scalar* buffer) { + evalSubExprsIfNeeded(NULL); + for (int i = 0; i < dimensions().TotalSize(); ++i) { + buffer[i] += coeff(i); + } + cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + CoeffReturnType result = CoeffReturnType(0); + convolve(firstInput(index), 0, NumKernelDims-1, result); + return result; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(const Index index) const + { + Index indices[2] = {index, index+PacketSize-1}; + Index startInputs[2] = {0, 0}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / m_outputStride[i]; + const Index idx1 = indices[1] / m_outputStride[i]; + startInputs[0] += idx0 * m_inputStride[i]; + startInputs[1] += idx1 * m_inputStride[i]; + indices[0] -= idx0 * m_outputStride[i]; + indices[1] -= idx1 * m_outputStride[i]; + } + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / m_outputStride[i]; + const Index idx1 = indices[1] / m_outputStride[i]; + startInputs[0] += idx0 * m_inputStride[i]; + startInputs[1] += idx1 * m_inputStride[i]; + indices[0] -= idx0 * m_outputStride[i]; + indices[1] -= idx1 * m_outputStride[i]; + } + } + startInputs[0] += indices[0]; + startInputs[1] += indices[1]; + + if (startInputs[1]-startInputs[0] == PacketSize-1) { + PacketReturnType result = internal::pset1(0); + convolvePacket(startInputs[0], 0, NumKernelDims-1, result); + return result; + } else { + EIGEN_ALIGN_MAX Scalar data[PacketSize]; + data[0] = Scalar(0); + convolve(startInputs[0], 0, NumKernelDims-1, data[0]); + for (int i = 1; i < PacketSize-1; ++i) { + data[i] = Scalar(0); + convolve(firstInput(index+i), 0, NumKernelDims-1, data[i]); + } + data[PacketSize-1] = Scalar(0); + convolve(startInputs[1], 0, NumKernelDims-1, data[PacketSize-1]); + return internal::pload(data); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double kernel_size = m_kernelImpl.dimensions().TotalSize(); + // We ignore the use of fused multiply-add. + const double convolve_compute_cost = + TensorOpCost::AddCost() + TensorOpCost::MulCost(); + const double firstIndex_compute_cost = + NumDims * + (2 * TensorOpCost::AddCost() + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost()); + return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) + + kernel_size * (m_inputImpl.costPerCoeff(vectorized) + + m_kernelImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, convolve_compute_cost, vectorized, + PacketSize)); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const { + Index startInput = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStride[i]; + startInput += idx * m_inputStride[i]; + index -= idx * m_outputStride[i]; + } + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStride[i]; + startInput += idx * m_inputStride[i]; + index -= idx * m_outputStride[i]; + } + } + startInput += index; + return startInput; + } + + EIGEN_DEVICE_FUNC void convolve(Index firstIndex, Index firstKernel, int DimIndex, CoeffReturnType& accum) const { + for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) { + const Index input = firstIndex + j * m_indexStride[DimIndex]; + const Index kernel = firstKernel + j * m_kernelStride[DimIndex]; + if (DimIndex > 0) { + convolve(input, kernel, DimIndex-1, accum); + } else { + accum += m_inputImpl.coeff(input) * m_kernel[kernel]; + } + } + } + + template + EIGEN_DEVICE_FUNC void convolvePacket(Index firstIndex, Index firstKernel, int DimIndex, Packet& accum) const { + for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) { + const Index input = firstIndex + j * m_indexStride[DimIndex]; + const Index kernel = firstKernel + j * m_kernelStride[DimIndex]; + if (DimIndex > 0) { + convolvePacket(input, kernel, DimIndex-1, accum); + } else { + accum = internal::pmadd(m_inputImpl.template packet(input), internal::pset1(m_kernel[kernel]), accum); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() { + // Don't make a local copy of the kernel unless we have to (i.e. it's an + // expression that needs to be evaluated) + const Scalar* in_place = m_kernelImpl.data(); + if (in_place) { + m_kernel = in_place; + m_local_kernel = false; + } else { + size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar); + Scalar* local = (Scalar*)m_device.allocate(kernel_sz); + typedef TensorEvalToOp EvalTo; + EvalTo evalToTmp(local, m_kernelArg); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::run(evalToTmp, m_device); + + m_kernel = local; + m_local_kernel = true; + } + } + + array m_inputStride; + array m_outputStride; + + array m_indexStride; + array m_kernelStride; + TensorEvaluator m_inputImpl; + TensorEvaluator m_kernelImpl; + Dimensions m_dimensions; + + KernelArgType m_kernelArg; + const Scalar* m_kernel; + bool m_local_kernel; + const Device& m_device; +}; + + + + +// Use an optimized implementation of the evaluation code for GPUs whenever possible. +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + +template +struct GetKernelSize { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int /*kernelSize*/) const { + return StaticKernelSize; + } +}; +template <> +struct GetKernelSize { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int kernelSize) const { + return kernelSize; + } +}; + +template +__global__ void EigenConvolutionKernel1D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const int numPlanes, const int numX, + const int maxX, const int kernelSize, float* buffer) { + extern __shared__ float s[]; + + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + GetKernelSize()(kernelSize); + const int num_x_output = last_x - first_x + 1; + + const int first_plane = blockIdx.y * blockDim.y; + const int plane_stride = blockDim.y * gridDim.y; + + for (int p = first_plane + threadIdx.y; p < numPlanes; p += plane_stride) { + // Load inputs to shared memory + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = threadIdx.y * num_x_input; + #pragma unroll + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x); + s[i + plane_kernel_offset] = eval.coeff(tensor_index); + } + + __syncthreads(); + + // Compute the convolution + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + #pragma unroll + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + const int kernel_offset = plane_kernel_offset + i; + float result = 0.0f; + #pragma unroll + for (int k = 0; k < GetKernelSize()(kernelSize); ++k) { + result += s[k + kernel_offset] * kernel[k]; + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x); + buffer[tensor_index] = result; + } + __syncthreads(); + } +}; + +template +__global__ void EigenConvolutionKernel2D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const int numPlanes, const int numX, + const int maxX, const int numY, const int maxY, const int kernelSizeX, + const int kernelSizeY, float* buffer) { + extern __shared__ float s[]; + + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + GetKernelSize()(kernelSizeX); + const int num_x_output = last_x - first_x + 1; + + const int first_y = blockIdx.y * maxY; + const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1; + const int num_y_input = last_y - first_y + GetKernelSize()(kernelSizeY); + const int num_y_output = last_y - first_y + 1; + + const int first_plane = blockIdx.z * blockDim.z; + const int plane_stride = blockDim.z * gridDim.z; + + for (int p = first_plane + threadIdx.z; p < numPlanes; p += plane_stride) { + + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = threadIdx.z * num_y_input; + + // Load inputs to shared memory + #pragma unroll + for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) { + const int input_offset = num_x_input * (j + plane_kernel_offset); + #pragma unroll + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x, j+first_y); + s[i + input_offset] = eval.coeff(tensor_index); + } + } + + __syncthreads(); + + // Convolution + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + #pragma unroll + for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) { + #pragma unroll + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + float result = 0.0f; + #pragma unroll + for (int l = 0; l < GetKernelSize()(kernelSizeY); ++l) { + const int kernel_offset = kernelSizeX * l; + const int input_offset = i + num_x_input * (j + l + plane_kernel_offset); + #pragma unroll + for (int k = 0; k < GetKernelSize()(kernelSizeX); ++k) { + result += s[k + input_offset] * kernel[k + kernel_offset]; + } + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x, j+first_y); + buffer[tensor_index] = result; + } + } + + __syncthreads(); + } +}; + +template +__global__ void EigenConvolutionKernel3D( + InputEvaluator eval, + const internal::IndexMapper + indexMapper, + const float* __restrict kernel, const size_t numPlanes, const size_t numX, + const size_t maxX, const size_t numY, const size_t maxY, const size_t numZ, + const size_t maxZ, const size_t kernelSizeX, const size_t kernelSizeY, + const size_t kernelSizeZ, float* buffer) { + extern __shared__ float s[]; + + // Load inputs to shared memory + const int first_x = blockIdx.x * maxX; + const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1; + const int num_x_input = last_x - first_x + kernelSizeX; + + const int first_y = blockIdx.y * maxY; + const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1; + const int num_y_input = last_y - first_y + kernelSizeY; + + const int first_z = blockIdx.z * maxZ; + const int last_z = (first_z + maxZ < numZ ? first_z + maxZ : numZ) - 1; + const int num_z_input = last_z - first_z + kernelSizeZ; + + for (int p = 0; p < numPlanes; ++p) { + + const int plane_input_offset = indexMapper.mapCudaInputPlaneToTensorInputOffset(p); + const int plane_kernel_offset = 0; + + for (int k = threadIdx.z; k < num_z_input; k += blockDim.z) { + for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) { + for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) { + const int tensor_index = plane_input_offset + indexMapper.mapCudaInputKernelToTensorInputOffset(i+first_x, j+first_y, k+first_z); + s[i + num_x_input * (j + num_y_input * (k + plane_kernel_offset))] = eval.coeff(tensor_index); + } + } + } + + __syncthreads(); + + // Convolution + const int num_z_output = last_z - first_z + 1; + const int num_y_output = last_y - first_y + 1; + const int num_x_output = last_x - first_x + 1; + const int plane_output_offset = indexMapper.mapCudaOutputPlaneToTensorOutputOffset(p); + + for (int k = threadIdx.z; k < num_z_output; k += blockDim.z) { + for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) { + for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) { + float result = 0.0f; + for (int n = 0; n < kernelSizeZ; ++n) { + for (int m = 0; m < kernelSizeY; ++m) { + for (int l = 0; l < kernelSizeX; ++l) { + result += s[i + l + num_x_input * (j + m + num_y_input * (k + n + plane_kernel_offset))] * kernel[l + kernelSizeX * (m + kernelSizeY * n)]; + } + } + } + const int tensor_index = plane_output_offset + indexMapper.mapCudaOutputKernelToTensorOutputOffset(i+first_x, j+first_y, k+first_z); + buffer[tensor_index] = result; + } + } + } + __syncthreads(); + } +}; + + + +template +struct TensorEvaluator, GpuDevice> +{ + typedef TensorConvolutionOp XprType; + + static const int NumDims = internal::array_size::Dimensions>::value; + static const int NumKernelDims = internal::array_size::value; + typedef typename XprType::Index Index; + typedef DSizes Dimensions; + typedef typename TensorEvaluator::Dimensions KernelDimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const GpuDevice& device) + : m_inputImpl(op.inputExpression(), device), m_kernelArg(op.kernelExpression()), m_kernelImpl(op.kernelExpression(), device), m_indices(op.indices()), m_buf(NULL), m_kernel(NULL), m_local_kernel(false), m_device(device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + + const typename TensorEvaluator::Dimensions& input_dims = m_inputImpl.dimensions(); + const typename TensorEvaluator::Dimensions& kernel_dims = m_kernelImpl.dimensions(); + + m_dimensions = m_inputImpl.dimensions(); + for (int i = 0; i < NumKernelDims; ++i) { + const Index index = op.indices()[i]; + const Index input_dim = input_dims[index]; + const Index kernel_dim = kernel_dims[i]; + const Index result_dim = input_dim - kernel_dim + 1; + m_dimensions[index] = result_dim; + } + } + + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename InputArgType::Scalar Scalar; + static const int PacketSize = internal::unpacket_traits::size; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) { + preloadKernel(); + m_inputImpl.evalSubExprsIfNeeded(NULL); + if (data) { + executeEval(data); + return false; + } else { + m_buf = (Scalar*)m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)); + executeEval(m_buf); + return true; + } + } + + EIGEN_STRONG_INLINE void cleanup() { + m_inputImpl.cleanup(); + if (m_buf) { + m_device.deallocate(m_buf); + m_buf = NULL; + } + if (m_local_kernel) { + m_device.deallocate((void*)m_kernel); + m_local_kernel = false; + } + m_kernel = NULL; + } + + EIGEN_STRONG_INLINE void preloadKernel() { + // Don't make a local copy of the kernel unless we have to (i.e. it's an + // expression that needs to be evaluated) + const Scalar* in_place = m_kernelImpl.data(); + if (in_place) { + m_kernel = in_place; + m_local_kernel = false; + } else { + size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar); + Scalar* local = (Scalar*)m_device.allocate(kernel_sz); + typedef TensorEvalToOp EvalTo; + EvalTo evalToTmp(local, m_kernelArg); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::run(evalToTmp, m_device); + + m_kernel = local; + m_local_kernel = true; + } + } + + static unsigned int ceil(unsigned int num, unsigned int denom) { + const unsigned int rounded_toward_zero = num / denom; + if (num > rounded_toward_zero * denom) { + return rounded_toward_zero + 1; + } + return rounded_toward_zero; + } + + void executeEval(Scalar* data) const { + typedef typename TensorEvaluator::Dimensions InputDims; + + const int maxSharedMem = m_device.sharedMemPerBlock(); + const int maxThreadsPerBlock = m_device.maxCudaThreadsPerBlock(); + const int maxBlocksPerProcessor = m_device.maxCudaThreadsPerMultiProcessor() / maxThreadsPerBlock; + const int numMultiProcessors = m_device.getNumCudaMultiProcessors(); + const int warpSize = 32; + + switch (NumKernelDims) { + case 1: { + const int kernel_size = m_kernelImpl.dimensions().TotalSize(); + + const int numX = dimensions()[m_indices[0]]; + const int numP = dimensions().TotalSize() / numX; + int maxX; + dim3 block_size; + + const int single_stride_dim = + static_cast(Layout) == static_cast(ColMajor) + ? 0 + : m_inputImpl.dimensions().rank() - 1; + if (m_indices[0] == single_stride_dim) { + // Maximum the reuse + const int inner_dim = ((maxSharedMem / (sizeof(Scalar)) - kernel_size + 1 + 31) / 32) * 32; + maxX = numext::mini(inner_dim, numX); + const int maxP = numext::mini(maxSharedMem / ((kernel_size - 1 + maxX) * sizeof(Scalar)), numP); + block_size.x = numext::mini(maxThreadsPerBlock, maxX); + block_size.y = numext::mini(maxThreadsPerBlock / block_size.x, maxP); + } + else { + // Read as much as possible alongside the inner most dimension, that is the plane + const int inner_dim = maxSharedMem / ((warpSize + kernel_size) * sizeof(Scalar)); + const int maxP = numext::mini(inner_dim, numP); + maxX = numext::mini(maxSharedMem / (inner_dim * sizeof(Scalar)) - kernel_size + 1, numX); + + block_size.x = numext::mini(warpSize, maxX); + block_size.y = numext::mini(maxThreadsPerBlock/block_size.x, maxP); + } + + const int shared_mem = block_size.y * (maxX + kernel_size - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + const int num_x_blocks = ceil(numX, maxX); + const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem); + const int num_y_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks); + + dim3 num_blocks(num_x_blocks, numext::mini(num_y_blocks, ceil(numP, block_size.y))); + + + //cout << "launching 1D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " maxX: " << maxX << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + + const array indices(m_indices[0]); + const array kernel_dims(m_kernelImpl.dimensions()[0]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + switch(kernel_size) { + case 4: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 4, data); + break; + } + case 7: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 7, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel1D, Index, InputDims, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, kernel_size, data); + } + } + break; + } + + case 2: { + const int idxX = + static_cast(Layout) == static_cast(ColMajor) ? 0 : 1; + const int idxY = + static_cast(Layout) == static_cast(ColMajor) ? 1 : 0; + const int kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const int kernel_size_y = m_kernelImpl.dimensions()[idxY]; + + const int numX = dimensions()[m_indices[idxX]]; + const int numY = dimensions()[m_indices[idxY]]; + const int numP = dimensions().TotalSize() / (numX*numY); + + const float scaling_factor = sqrtf(static_cast(maxSharedMem) / (sizeof(Scalar) * kernel_size_y * kernel_size_x)); + + // Snap maxX to warp size + int inner_dim = ((static_cast(scaling_factor * kernel_size_x) - kernel_size_x + 1 + 32) / 32) * 32; + const int maxX = numext::mini(inner_dim, numX); + const int maxY = numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1)) - kernel_size_y + 1, numY); + const int maxP = numext::mini(maxSharedMem / ((kernel_size_x - 1 + maxX) * (kernel_size_y - 1 + maxY) * sizeof(Scalar)), numP); + + dim3 block_size; + block_size.x = numext::mini(1024, maxX); + block_size.y = numext::mini(1024/block_size.x, maxY); + block_size.z = numext::mini(1024/(block_size.x*block_size.y), maxP); + + const int shared_mem = block_size.z * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + const int num_x_blocks = ceil(numX, maxX); + const int num_y_blocks = ceil(numY, maxY); + const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem); + const int num_z_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks * num_y_blocks); + + dim3 num_blocks(num_x_blocks, num_y_blocks, numext::mini(num_z_blocks, ceil(numP, block_size.z))); + + + //cout << "launching 2D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " block_size.z: " << block_size.z << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " num_blocks.z: " << num_blocks.z << " maxX: " << maxX << " maxY: " << maxY << " maxP: " << maxP << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + + const array indices(m_indices[idxX], m_indices[idxY]); + const array kernel_dims(m_kernelImpl.dimensions()[idxX], + m_kernelImpl.dimensions()[idxY]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + switch (kernel_size_x) { + case 4: { + switch (kernel_size_y) { + case 7: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 4, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, 7, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 4, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, kernel_size_y, data); + break; + } + } + break; + } + case 7: { + switch (kernel_size_y) { + case 4: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 7, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, 4, data); + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, 7, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, kernel_size_y, data); + break; + } + } + break; + } + default: { + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel2D, Index, InputDims, Dynamic, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, kernel_size_x, kernel_size_y, data); + break; + } + } + break; + } + + case 3: { + const int idxX = + static_cast(Layout) == static_cast(ColMajor) ? 0 : 2; + const int idxY = + static_cast(Layout) == static_cast(ColMajor) ? 1 : 1; + const int idxZ = + static_cast(Layout) == static_cast(ColMajor) ? 2 : 0; + + const int kernel_size_x = m_kernelImpl.dimensions()[idxX]; + const int kernel_size_y = m_kernelImpl.dimensions()[idxY]; + const int kernel_size_z = m_kernelImpl.dimensions()[idxZ]; + + const int numX = dimensions()[m_indices[idxX]]; + const int numY = dimensions()[m_indices[idxY]]; + const int numZ = dimensions()[m_indices[idxZ]]; + const int numP = dimensions().TotalSize() / (numX*numY*numZ); + + const int maxX = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * kernel_size_y * kernel_size_z) - kernel_size_x + 1, numX)); + const int maxY = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * kernel_size_z) - kernel_size_y + 1, numY)); + const int maxZ = numext::mini(128, numext::mini(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1)) - kernel_size_z + 1, numZ)); + + dim3 block_size; + block_size.x = numext::mini(32, maxX); + block_size.y = numext::mini(32, maxY); + block_size.z = numext::mini(1024/(block_size.x*block_size.y), maxZ); + dim3 num_blocks(ceil(numX, maxX), ceil(numY, maxY), ceil(numZ, maxZ)); + + const int shared_mem = (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * (maxZ + kernel_size_z - 1) * sizeof(Scalar); + assert(shared_mem <= maxSharedMem); + + //cout << "launching 3D kernel with block_size.x: " << block_size.x << " block_size.y: " << block_size.y << " block_size.z: " << block_size.z << " num_blocks.x: " << num_blocks.x << " num_blocks.y: " << num_blocks.y << " num_blocks.z: " << num_blocks.z << " shared_mem: " << shared_mem << " in stream " << m_device.stream() << endl; + const array indices(m_indices[idxX], m_indices[idxY], + m_indices[idxZ]); + const array kernel_dims(m_kernelImpl.dimensions()[idxX], + m_kernelImpl.dimensions()[idxY], + m_kernelImpl.dimensions()[idxZ]); + internal::IndexMapper indexMapper( + m_inputImpl.dimensions(), kernel_dims, indices); + + LAUNCH_CUDA_KERNEL((EigenConvolutionKernel3D, Index, InputDims>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, numZ, maxZ, kernel_size_x, kernel_size_y, kernel_size_z, data); + break; + } + + default: { + EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3), THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE); + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return m_buf[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const + { + eigen_assert(m_buf); + eigen_assert(index < m_dimensions.TotalSize()); + return internal::ploadt(m_buf+index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost + // model. + const double kernel_size = m_kernelImpl.dimensions().TotalSize(); + // We ignore the use of fused multiply-add. + const double convolve_compute_cost = + TensorOpCost::AddCost() + TensorOpCost::MulCost(); + const double firstIndex_compute_cost = + NumDims * + (2 * TensorOpCost::AddCost() + 2 * TensorOpCost::MulCost() + + TensorOpCost::DivCost()); + return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) + + kernel_size * (m_inputImpl.costPerCoeff(vectorized) + + m_kernelImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, convolve_compute_cost, vectorized, + PacketSize)); + } + + private: + // No assignment (copies are needed by the kernels) + TensorEvaluator& operator = (const TensorEvaluator&); + + TensorEvaluator m_inputImpl; + TensorEvaluator m_kernelImpl; + KernelArgType m_kernelArg; + Indices m_indices; + Dimensions m_dimensions; + Scalar* m_buf; + const Scalar* m_kernel; + bool m_local_kernel; + + const GpuDevice& m_device; +}; +#endif + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h new file mode 100644 index 000000000..83c449cf1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h @@ -0,0 +1,212 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Rasmus Munk Larsen +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H +#define EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H + +namespace Eigen { + +/** \class TensorEvaluator + * \ingroup CXX11_Tensor_Module + * + * \brief A cost model used to limit the number of threads used for evaluating + * tensor expression. + * + */ + +// Class storing the cost of evaluating a tensor expression in terms of the +// estimated number of operand bytes loads, bytes stored, and compute cycles. +class TensorOpCost { + public: + // TODO(rmlarsen): Fix the scalar op costs in Eigen proper. Even a simple + // model based on minimal reciprocal throughput numbers from Intel or + // Agner Fog's tables would be better than what is there now. + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int MulCost() { + return internal::functor_traits< + internal::scalar_product_op >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int AddCost() { + return internal::functor_traits >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int DivCost() { + return internal::functor_traits< + internal::scalar_quotient_op >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int ModCost() { + return internal::functor_traits >::Cost; + } + template + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int CastCost() { + return internal::functor_traits< + internal::scalar_cast_op >::Cost; + } + + EIGEN_DEVICE_FUNC + TensorOpCost() : bytes_loaded_(0), bytes_stored_(0), compute_cycles_(0) {} + EIGEN_DEVICE_FUNC + TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles) + : bytes_loaded_(bytes_loaded), + bytes_stored_(bytes_stored), + compute_cycles_(compute_cycles) {} + + EIGEN_DEVICE_FUNC + TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles, + bool vectorized, double packet_size) + : bytes_loaded_(bytes_loaded), + bytes_stored_(bytes_stored), + compute_cycles_(vectorized ? compute_cycles / packet_size + : compute_cycles) { + eigen_assert(bytes_loaded >= 0 && (numext::isfinite)(bytes_loaded)); + eigen_assert(bytes_stored >= 0 && (numext::isfinite)(bytes_stored)); + eigen_assert(compute_cycles >= 0 && (numext::isfinite)(compute_cycles)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_loaded() const { + return bytes_loaded_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_stored() const { + return bytes_stored_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double compute_cycles() const { + return compute_cycles_; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double total_cost( + double load_cost, double store_cost, double compute_cost) const { + return load_cost * bytes_loaded_ + store_cost * bytes_stored_ + + compute_cost * compute_cycles_; + } + + // Drop memory access component. Intended for cases when memory accesses are + // sequential or are completely masked by computations. + EIGEN_DEVICE_FUNC void dropMemoryCost() { + bytes_loaded_ = 0; + bytes_stored_ = 0; + } + + // TODO(rmlarsen): Define min in terms of total cost, not elementwise. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMin( + const TensorOpCost& rhs) const { + double bytes_loaded = numext::mini(bytes_loaded_, rhs.bytes_loaded()); + double bytes_stored = numext::mini(bytes_stored_, rhs.bytes_stored()); + double compute_cycles = numext::mini(compute_cycles_, rhs.compute_cycles()); + return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles); + } + + // TODO(rmlarsen): Define max in terms of total cost, not elementwise. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMax( + const TensorOpCost& rhs) const { + double bytes_loaded = numext::maxi(bytes_loaded_, rhs.bytes_loaded()); + double bytes_stored = numext::maxi(bytes_stored_, rhs.bytes_stored()); + double compute_cycles = numext::maxi(compute_cycles_, rhs.compute_cycles()); + return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator+=( + const TensorOpCost& rhs) { + bytes_loaded_ += rhs.bytes_loaded(); + bytes_stored_ += rhs.bytes_stored(); + compute_cycles_ += rhs.compute_cycles(); + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator*=(double rhs) { + bytes_loaded_ *= rhs; + bytes_stored_ *= rhs; + compute_cycles_ *= rhs; + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator+( + TensorOpCost lhs, const TensorOpCost& rhs) { + lhs += rhs; + return lhs; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*( + TensorOpCost lhs, double rhs) { + lhs *= rhs; + return lhs; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*( + double lhs, TensorOpCost rhs) { + rhs *= lhs; + return rhs; + } + + friend std::ostream& operator<<(std::ostream& os, const TensorOpCost& tc) { + return os << "[bytes_loaded = " << tc.bytes_loaded() + << ", bytes_stored = " << tc.bytes_stored() + << ", compute_cycles = " << tc.compute_cycles() << "]"; + } + + private: + double bytes_loaded_; + double bytes_stored_; + double compute_cycles_; +}; + +// TODO(rmlarsen): Implement a policy that chooses an "optimal" number of theads +// in [1:max_threads] instead of just switching multi-threading off for small +// work units. +template +class TensorCostModel { + public: + // Scaling from Eigen compute cost to device cycles. + static const int kDeviceCyclesPerComputeCycle = 1; + + // Costs in device cycles. + static const int kStartupCycles = 100000; + static const int kPerThreadCycles = 100000; + static const int kTaskSize = 40000; + + // Returns the number of threads in [1:max_threads] to use for + // evaluating an expression with the given output size and cost per + // coefficient. + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int numThreads( + double output_size, const TensorOpCost& cost_per_coeff, int max_threads) { + double cost = totalCost(output_size, cost_per_coeff); + int threads = (cost - kStartupCycles) / kPerThreadCycles + 0.9; + return numext::mini(max_threads, numext::maxi(1, threads)); + } + + // taskSize assesses parallel task size. + // Value of 1.0 means ideal parallel task size. Values < 1.0 mean that task + // granularity needs to be increased to mitigate parallelization overheads. + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double taskSize( + double output_size, const TensorOpCost& cost_per_coeff) { + return totalCost(output_size, cost_per_coeff) / kTaskSize; + } + + private: + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double totalCost( + double output_size, const TensorOpCost& cost_per_coeff) { + // Cost of memory fetches from L2 cache. 64 is typical cache line size. + // 11 is L2 cache latency on Haswell. + // We don't know whether data is in L1, L2 or L3. But we are most interested + // in single-threaded computational time around 100us-10ms (smaller time + // is too small for parallelization, larger time is not intersting + // either because we are probably using all available threads already). + // And for the target time range, L2 seems to be what matters. Data set + // fitting into L1 is too small to take noticeable time. Data set fitting + // only into L3 presumably will take more than 10ms to load and process. + const double kLoadCycles = 1.0 / 64 * 11; + const double kStoreCycles = 1.0 / 64 * 11; + // Scaling from Eigen compute cost to device cycles. + return output_size * + cost_per_coeff.total_cost(kLoadCycles, kStoreCycles, + kDeviceCyclesPerComputeCycle); + } +}; + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h new file mode 100644 index 000000000..e020d076f --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h @@ -0,0 +1,313 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H +#define EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H + +namespace Eigen { + +/** \class TensorCustomUnaryOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor custom class. + * + * + */ +namespace internal { +template +struct traits > +{ + typedef typename XprType::Scalar Scalar; + typedef typename XprType::StorageKind StorageKind; + typedef typename XprType::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCustomUnaryOp& type; +}; + +template +struct nested > +{ + typedef TensorCustomUnaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCustomUnaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomUnaryOp(const XprType& expr, const CustomUnaryFunc& func) + : m_expr(expr), m_func(func) {} + + EIGEN_DEVICE_FUNC + const CustomUnaryFunc& func() const { return m_func; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_expr; } + + protected: + typename XprType::Nested m_expr; + const CustomUnaryFunc m_func; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorCustomUnaryOp ArgType; + typedef typename internal::traits::Index Index; + static const int NumDims = internal::traits::NumDimensions; + typedef DSizes Dimensions; + typedef typename internal::remove_const::type Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = (internal::packet_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const ArgType& op, const Device& device) + : m_op(op), m_device(device), m_result(NULL) + { + m_dimensions = op.func().dimensions(op.expression()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast( + m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): Extend CustomOp API to return its cost estimate. + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_result; } + + protected: + EIGEN_DEVICE_FUNC void evalTo(Scalar* data) { + TensorMap > result( + data, m_dimensions); + m_op.func().eval(m_op.expression(), result, m_device); + } + + Dimensions m_dimensions; + const ArgType m_op; + const Device& m_device; + CoeffReturnType* m_result; +}; + + + +/** \class TensorCustomBinaryOp + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor custom class. + * + * + */ +namespace internal { +template +struct traits > +{ + typedef typename internal::promote_storage_type::ret Scalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = traits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCustomBinaryOp& type; +}; + +template +struct nested > +{ + typedef TensorCustomBinaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCustomBinaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::traits::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const CustomBinaryFunc& func) + + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_func(func) {} + + EIGEN_DEVICE_FUNC + const CustomBinaryFunc& func() const { return m_func; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const CustomBinaryFunc m_func; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorCustomBinaryOp XprType; + typedef typename internal::traits::Index Index; + static const int NumDims = internal::traits::NumDimensions; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = (internal::packet_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_op(op), m_device(device), m_result(NULL) + { + m_dimensions = op.func().dimensions(op.lhsExpression(), op.rhsExpression()); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (data) { + evalTo(data); + return false; + } else { + m_result = static_cast(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar))); + evalTo(m_result); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_result != NULL) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + return m_result[index]; + } + + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const { + return internal::ploadt(m_result + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // TODO(rmlarsen): Extend CustomOp API to return its cost estimate. + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return m_result; } + + protected: + EIGEN_DEVICE_FUNC void evalTo(Scalar* data) { + TensorMap > result(data, m_dimensions); + m_op.func().eval(m_op.lhsExpression(), m_op.rhsExpression(), result, m_device); + } + + Dimensions m_dimensions; + const XprType m_op; + const Device& m_device; + CoeffReturnType* m_result; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h new file mode 100644 index 000000000..29e50a3b2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h @@ -0,0 +1,68 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H + +namespace Eigen { + +/** \class TensorDevice + * \ingroup CXX11_Tensor_Module + * + * \brief Pseudo expression providing an operator = that will evaluate its argument + * on the specified computing 'device' (GPU, thread pool, ...) + * + * Example: + * C.device(EIGEN_GPU) = A + B; + * + * Todo: operator *= and /=. + */ + +template class TensorDevice { + public: + TensorDevice(const DeviceType& device, ExpressionType& expression) : m_device(device), m_expression(expression) {} + + template + EIGEN_STRONG_INLINE TensorDevice& operator=(const OtherDerived& other) { + typedef TensorAssignOp Assign; + Assign assign(m_expression, other); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + template + EIGEN_STRONG_INLINE TensorDevice& operator+=(const OtherDerived& other) { + typedef typename OtherDerived::Scalar Scalar; + typedef TensorCwiseBinaryOp, const ExpressionType, const OtherDerived> Sum; + Sum sum(m_expression, other); + typedef TensorAssignOp Assign; + Assign assign(m_expression, sum); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + template + EIGEN_STRONG_INLINE TensorDevice& operator-=(const OtherDerived& other) { + typedef typename OtherDerived::Scalar Scalar; + typedef TensorCwiseBinaryOp, const ExpressionType, const OtherDerived> Difference; + Difference difference(m_expression, other); + typedef TensorAssignOp Assign; + Assign assign(m_expression, difference); + internal::TensorExecutor::run(assign, m_device); + return *this; + } + + protected: + const DeviceType& m_device; + ExpressionType& m_expression; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h new file mode 100644 index 000000000..4f5767bc7 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h @@ -0,0 +1,337 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H + +namespace Eigen { + +static const int kCudaScratchSize = 1024; + +// This defines an interface that GPUDevice can take to use +// CUDA streams underneath. +class StreamInterface { + public: + virtual ~StreamInterface() {} + + virtual const cudaStream_t& stream() const = 0; + virtual const cudaDeviceProp& deviceProperties() const = 0; + + // Allocate memory on the actual device where the computation will run + virtual void* allocate(size_t num_bytes) const = 0; + virtual void deallocate(void* buffer) const = 0; + + // Return a scratchpad buffer of size 1k + virtual void* scratchpad() const = 0; + + // Return a semaphore. The semaphore is initially initialized to 0, and + // each kernel using it is responsible for resetting to 0 upon completion + // to maintain the invariant that the semaphore is always equal to 0 upon + // each kernel start. + virtual unsigned int* semaphore() const = 0; +}; + +static cudaDeviceProp* m_deviceProperties; +static bool m_devicePropInitialized = false; + +static void initializeDeviceProp() { + if (!m_devicePropInitialized) { + // Attempts to ensure proper behavior in the case of multiple threads + // calling this function simultaneously. This would be trivial to + // implement if we could use std::mutex, but unfortunately mutex don't + // compile with nvcc, so we resort to atomics and thread fences instead. + // Note that if the caller uses a compiler that doesn't support c++11 we + // can't ensure that the initialization is thread safe. +#if __cplusplus >= 201103L + static std::atomic first(true); + if (first.exchange(false)) { +#else + static bool first = true; + if (first) { + first = false; +#endif + // We're the first thread to reach this point. + int num_devices; + cudaError_t status = cudaGetDeviceCount(&num_devices); + if (status != cudaSuccess) { + std::cerr << "Failed to get the number of CUDA devices: " + << cudaGetErrorString(status) + << std::endl; + assert(status == cudaSuccess); + } + m_deviceProperties = new cudaDeviceProp[num_devices]; + for (int i = 0; i < num_devices; ++i) { + status = cudaGetDeviceProperties(&m_deviceProperties[i], i); + if (status != cudaSuccess) { + std::cerr << "Failed to initialize CUDA device #" + << i + << ": " + << cudaGetErrorString(status) + << std::endl; + assert(status == cudaSuccess); + } + } + +#if __cplusplus >= 201103L + std::atomic_thread_fence(std::memory_order_release); +#endif + m_devicePropInitialized = true; + } else { + // Wait for the other thread to inititialize the properties. + while (!m_devicePropInitialized) { +#if __cplusplus >= 201103L + std::atomic_thread_fence(std::memory_order_acquire); +#endif + sleep(1); + } + } + } +} + +static const cudaStream_t default_stream = cudaStreamDefault; + +class CudaStreamDevice : public StreamInterface { + public: + // Use the default stream on the current device + CudaStreamDevice() : stream_(&default_stream), scratch_(NULL), semaphore_(NULL) { + cudaGetDevice(&device_); + initializeDeviceProp(); + } + // Use the default stream on the specified device + CudaStreamDevice(int device) : stream_(&default_stream), device_(device), scratch_(NULL), semaphore_(NULL) { + initializeDeviceProp(); + } + // Use the specified stream. Note that it's the + // caller responsibility to ensure that the stream can run on + // the specified device. If no device is specified the code + // assumes that the stream is associated to the current gpu device. + CudaStreamDevice(const cudaStream_t* stream, int device = -1) + : stream_(stream), device_(device), scratch_(NULL), semaphore_(NULL) { + if (device < 0) { + cudaGetDevice(&device_); + } else { + int num_devices; + cudaError_t err = cudaGetDeviceCount(&num_devices); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + assert(device < num_devices); + device_ = device; + } + initializeDeviceProp(); + } + + virtual ~CudaStreamDevice() { + if (scratch_) { + deallocate(scratch_); + } + } + + const cudaStream_t& stream() const { return *stream_; } + const cudaDeviceProp& deviceProperties() const { + return m_deviceProperties[device_]; + } + virtual void* allocate(size_t num_bytes) const { + cudaError_t err = cudaSetDevice(device_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + void* result; + err = cudaMalloc(&result, num_bytes); + assert(err == cudaSuccess); + assert(result != NULL); + return result; + } + virtual void deallocate(void* buffer) const { + cudaError_t err = cudaSetDevice(device_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + assert(buffer != NULL); + err = cudaFree(buffer); + assert(err == cudaSuccess); + } + + virtual void* scratchpad() const { + if (scratch_ == NULL) { + scratch_ = allocate(kCudaScratchSize + sizeof(unsigned int)); + } + return scratch_; + } + + virtual unsigned int* semaphore() const { + if (semaphore_ == NULL) { + char* scratch = static_cast(scratchpad()) + kCudaScratchSize; + semaphore_ = reinterpret_cast(scratch); + cudaError_t err = cudaMemsetAsync(semaphore_, 0, sizeof(unsigned int), *stream_); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + return semaphore_; + } + + private: + const cudaStream_t* stream_; + int device_; + mutable void* scratch_; + mutable unsigned int* semaphore_; +}; + +struct GpuDevice { + // The StreamInterface is not owned: the caller is + // responsible for its initialization and eventual destruction. + explicit GpuDevice(const StreamInterface* stream) : stream_(stream), max_blocks_(INT_MAX) { + eigen_assert(stream); + } + explicit GpuDevice(const StreamInterface* stream, int num_blocks) : stream_(stream), max_blocks_(num_blocks) { + eigen_assert(stream); + } + // TODO(bsteiner): This is an internal API, we should not expose it. + EIGEN_STRONG_INLINE const cudaStream_t& stream() const { + return stream_->stream(); + } + + EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return stream_->allocate(num_bytes); + } + + EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + stream_->deallocate(buffer); + } + + EIGEN_STRONG_INLINE void* scratchpad() const { + return stream_->scratchpad(); + } + + EIGEN_STRONG_INLINE unsigned int* semaphore() const { + return stream_->semaphore(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { +#ifndef __CUDA_ARCH__ + cudaError_t err = cudaMemcpyAsync(dst, src, n, cudaMemcpyDeviceToDevice, + stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); +#else + eigen_assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + cudaError_t err = + cudaMemcpyAsync(dst, src, n, cudaMemcpyHostToDevice, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + + EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + cudaError_t err = + cudaMemcpyAsync(dst, src, n, cudaMemcpyDeviceToHost, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { +#ifndef __CUDA_ARCH__ + cudaError_t err = cudaMemsetAsync(buffer, c, n, stream_->stream()); + EIGEN_UNUSED_VARIABLE(err) + assert(err == cudaSuccess); +#else + eigen_assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE size_t numThreads() const { + // FIXME + return 32; + } + + EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { + // FIXME + return 48*1024; + } + + EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { + // We won't try to take advantage of the l2 cache for the time being, and + // there is no l3 cache on cuda devices. + return firstLevelCacheSize(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void synchronize() const { +#if defined(__CUDACC__) && !defined(__CUDA_ARCH__) + cudaError_t err = cudaStreamSynchronize(stream_->stream()); + if (err != cudaSuccess) { + std::cerr << "Error detected in CUDA stream: " + << cudaGetErrorString(err) + << std::endl; + assert(err == cudaSuccess); + } +#else + assert(false && "The default device should be used instead to generate kernel code"); +#endif + } + + EIGEN_STRONG_INLINE int getNumCudaMultiProcessors() const { + return stream_->deviceProperties().multiProcessorCount; + } + EIGEN_STRONG_INLINE int maxCudaThreadsPerBlock() const { + return stream_->deviceProperties().maxThreadsPerBlock; + } + EIGEN_STRONG_INLINE int maxCudaThreadsPerMultiProcessor() const { + return stream_->deviceProperties().maxThreadsPerMultiProcessor; + } + EIGEN_STRONG_INLINE int sharedMemPerBlock() const { + return stream_->deviceProperties().sharedMemPerBlock; + } + EIGEN_STRONG_INLINE int majorDeviceVersion() const { + return stream_->deviceProperties().major; + } + EIGEN_STRONG_INLINE int minorDeviceVersion() const { + return stream_->deviceProperties().minor; + } + + EIGEN_STRONG_INLINE int maxBlocks() const { + return max_blocks_; + } + + // This function checks if the CUDA runtime recorded an error for the + // underlying stream device. + inline bool ok() const { +#ifdef __CUDACC__ + cudaError_t error = cudaStreamQuery(stream_->stream()); + return (error == cudaSuccess) || (error == cudaErrorNotReady); +#else + return false; +#endif + } + + private: + const StreamInterface* stream_; + int max_blocks_; +}; + +#define LAUNCH_CUDA_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...) \ + (kernel) <<< (gridsize), (blocksize), (sharedmem), (device).stream() >>> (__VA_ARGS__); \ + assert(cudaGetLastError() == cudaSuccess); + + +// FIXME: Should be device and kernel specific. +#ifdef __CUDACC__ +static EIGEN_DEVICE_FUNC inline void setCudaSharedMemConfig(cudaSharedMemConfig config) { +#ifndef __CUDA_ARCH__ + cudaError_t status = cudaDeviceSetSharedMemConfig(config); + EIGEN_UNUSED_VARIABLE(status) + assert(status == cudaSuccess); +#else + EIGEN_UNUSED_VARIABLE(config) +#endif +} +#endif + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_CUDA_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h new file mode 100644 index 000000000..9d141395b --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h @@ -0,0 +1,81 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H + + +namespace Eigen { + +// Default device for the machine (typically a single cpu core) +struct DefaultDevice { + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return internal::aligned_malloc(num_bytes); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + internal::aligned_free(buffer); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { + ::memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { + ::memset(buffer, c, n); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t numThreads() const { +#ifndef __CUDA_ARCH__ + // Running on the host CPU + return 1; +#else + // Running on a CUDA device + return 32; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { +#ifndef __CUDA_ARCH__ + // Running on the host CPU + return l1CacheSize(); +#else + // Running on a CUDA device, return the amount of shared memory available. + return 48*1024; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { +#ifndef __CUDA_ARCH__ + // Running single threaded on the host CPU + return l3CacheSize(); +#else + // Running on a CUDA device + return firstLevelCacheSize(); +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const { +#ifndef __CUDA_ARCH__ + // Running single threaded on the host CPU + // Should return an enum that encodes the ISA supported by the CPU + return 1; +#else + // Running on a CUDA device + return __CUDA_ARCH__ / 100; +#endif + } +}; + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h new file mode 100644 index 000000000..7c039890e --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h @@ -0,0 +1,122 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Mehdi Goli Codeplay Software Ltd. +// Ralph Potter Codeplay Software Ltd. +// Luke Iwanski Codeplay Software Ltd. +// Contact: +// Copyright (C) 2016 Benoit Steiner + +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_SYCL) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H + +namespace Eigen { +struct SyclDevice { + /// class members + /// sycl queue + mutable cl::sycl::queue m_queue; + /// std::map is the container used to make sure that we create only one buffer + /// per pointer. The lifespan of the buffer now depends on the lifespan of SyclDevice. + /// If a non-read-only pointer is needed to be accessed on the host we should manually deallocate it. + mutable std::map> buffer_map; + /// creating device by using selector + template SyclDevice(dev_Selector s) + : +#ifdef EIGEN_EXCEPTIONS + m_queue(cl::sycl::queue(s, [=](cl::sycl::exception_list l) { + for (const auto& e : l) { + try { + std::rethrow_exception(e); + } catch (cl::sycl::exception e) { + std::cout << e.what() << std::endl; + } + } + })) +#else + m_queue(cl::sycl::queue(s)) +#endif + {} + // destructor + ~SyclDevice() { deallocate_all(); } + + template void deallocate(T *p) const { + auto it = buffer_map.find(p); + if (it != buffer_map.end()) { + buffer_map.erase(it); + internal::aligned_free(p); + } + } + void deallocate_all() const { + std::map>::iterator it=buffer_map.begin(); + while (it!=buffer_map.end()) { + auto p=it->first; + buffer_map.erase(it); + internal::aligned_free(const_cast(p)); + it=buffer_map.begin(); + } + buffer_map.clear(); + } + + /// creation of sycl accessor for a buffer. This function first tries to find + /// the buffer in the buffer_map. If found it gets the accessor from it, if not, + ///the function then adds an entry by creating a sycl buffer for that particular pointer. + template inline cl::sycl::accessor + get_sycl_accessor(size_t num_bytes, cl::sycl::handler &cgh, const T * ptr) const { + return (get_sycl_buffer(num_bytes, ptr)->template get_access(cgh)); + } + + template inline std::pair>::iterator,bool> add_sycl_buffer(const T *ptr, size_t num_bytes) const { + using Type = cl::sycl::buffer; + std::pair>::iterator,bool> ret = buffer_map.insert(std::pair>(ptr, std::shared_ptr(new Type(cl::sycl::range<1>(num_bytes)), + [](void *dataMem) { delete static_cast(dataMem); }))); + (static_cast(buffer_map.at(ptr).get()))->set_final_data(nullptr); + return ret; + } + + template inline cl::sycl::buffer* get_sycl_buffer(size_t num_bytes,const T * ptr) const { + return static_cast*>(add_sycl_buffer(ptr, num_bytes).first->second.get()); + } + + /// allocating memory on the cpu + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void *allocate(size_t) const { + return internal::aligned_malloc(8); + } + + // some runtime conditions that can be applied here + bool isDeviceSuitable() const { return true; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void *dst, const void *src, size_t n) const { + ::memcpy(dst, src, n); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyHostToDevice(T *dst, const T *src, size_t n) const { + auto host_acc= (static_cast*>(add_sycl_buffer(dst, n).first->second.get()))-> template get_access(); + memcpy(host_acc.get_pointer(), src, n); + } + /// whith the current implementation of sycl, the data is copied twice from device to host. This will be fixed soon. + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyDeviceToHost(T *dst, const T *src, size_t n) const { + auto it = buffer_map.find(src); + if (it != buffer_map.end()) { + auto host_acc= (static_cast*>(it->second.get()))-> template get_access(); + memcpy(dst,host_acc.get_pointer(), n); + } else{ + eigen_assert("no device memory found. The memory might be destroyed before creation"); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void *buffer, int c, size_t n) const { + ::memset(buffer, c, n); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const { + return 1; + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h new file mode 100644 index 000000000..069680a11 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h @@ -0,0 +1,279 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#if defined(EIGEN_USE_THREADS) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H) +#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H + +namespace Eigen { + +// Use the SimpleThreadPool by default. We'll switch to the new non blocking +// thread pool later. +#ifndef EIGEN_USE_SIMPLE_THREAD_POOL +template using ThreadPoolTempl = NonBlockingThreadPoolTempl; +typedef NonBlockingThreadPool ThreadPool; +#else +template using ThreadPoolTempl = SimpleThreadPoolTempl; +typedef SimpleThreadPool ThreadPool; +#endif + + +// Barrier is an object that allows one or more threads to wait until +// Notify has been called a specified number of times. +class Barrier { + public: + Barrier(unsigned int count) : state_(count << 1), notified_(false) { + eigen_assert(((count << 1) >> 1) == count); + } + ~Barrier() { + eigen_assert((state_>>1) == 0); + } + + void Notify() { + unsigned int v = state_.fetch_sub(2, std::memory_order_acq_rel) - 2; + if (v != 1) { + eigen_assert(((v + 2) & ~1) != 0); + return; // either count has not dropped to 0, or waiter is not waiting + } + std::unique_lock l(mu_); + eigen_assert(!notified_); + notified_ = true; + cv_.notify_all(); + } + + void Wait() { + unsigned int v = state_.fetch_or(1, std::memory_order_acq_rel); + if ((v >> 1) == 0) return; + std::unique_lock l(mu_); + while (!notified_) { + cv_.wait(l); + } + } + + private: + std::mutex mu_; + std::condition_variable cv_; + std::atomic state_; // low bit is waiter flag + bool notified_; +}; + + +// Notification is an object that allows a user to to wait for another +// thread to signal a notification that an event has occurred. +// +// Multiple threads can wait on the same Notification object, +// but only one caller must call Notify() on the object. +struct Notification : Barrier { + Notification() : Barrier(1) {}; +}; + + +// Runs an arbitrary function and then calls Notify() on the passed in +// Notification. +template struct FunctionWrapperWithNotification +{ + static void run(Notification* n, Function f, Args... args) { + f(args...); + if (n) { + n->Notify(); + } + } +}; + +template struct FunctionWrapperWithBarrier +{ + static void run(Barrier* b, Function f, Args... args) { + f(args...); + if (b) { + b->Notify(); + } + } +}; + +template +static EIGEN_STRONG_INLINE void wait_until_ready(SyncType* n) { + if (n) { + n->Wait(); + } +} + + +// Build a thread pool device on top the an existing pool of threads. +struct ThreadPoolDevice { + // The ownership of the thread pool remains with the caller. + ThreadPoolDevice(ThreadPoolInterface* pool, int num_cores) : pool_(pool), num_threads_(num_cores) { } + + EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const { + return internal::aligned_malloc(num_bytes); + } + + EIGEN_STRONG_INLINE void deallocate(void* buffer) const { + internal::aligned_free(buffer); + } + + EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const { + ::memcpy(dst, src, n); + } + EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const { + memcpy(dst, src, n); + } + + EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const { + ::memset(buffer, c, n); + } + + EIGEN_STRONG_INLINE int numThreads() const { + return num_threads_; + } + + EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { + return l1CacheSize(); + } + + EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const { + // The l3 cache size is shared between all the cores. + return l3CacheSize() / num_threads_; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const { + // Should return an enum that encodes the ISA supported by the CPU + return 1; + } + + template + EIGEN_STRONG_INLINE Notification* enqueue(Function&& f, Args&&... args) const { + Notification* n = new Notification(); + pool_->Schedule(std::bind(&FunctionWrapperWithNotification::run, n, f, args...)); + return n; + } + + template + EIGEN_STRONG_INLINE void enqueue_with_barrier(Barrier* b, + Function&& f, + Args&&... args) const { + pool_->Schedule(std::bind( + &FunctionWrapperWithBarrier::run, b, f, args...)); + } + + template + EIGEN_STRONG_INLINE void enqueueNoNotification(Function&& f, Args&&... args) const { + pool_->Schedule(std::bind(f, args...)); + } + + // Returns a logical thread index between 0 and pool_->NumThreads() - 1 if + // called from one of the threads in pool_. Returns -1 otherwise. + EIGEN_STRONG_INLINE int currentThreadId() const { + return pool_->CurrentThreadId(); + } + + // parallelFor executes f with [0, n) arguments in parallel and waits for + // completion. F accepts a half-open interval [first, last). + // Block size is choosen based on the iteration cost and resulting parallel + // efficiency. If block_align is not nullptr, it is called to round up the + // block size. + void parallelFor(Index n, const TensorOpCost& cost, + std::function block_align, + std::function f) const { + typedef TensorCostModel CostModel; + if (n <= 1 || numThreads() == 1 || + CostModel::numThreads(n, cost, static_cast(numThreads())) == 1) { + f(0, n); + return; + } + + // Calculate block size based on (1) the iteration cost and (2) parallel + // efficiency. We want blocks to be not too small to mitigate + // parallelization overheads; not too large to mitigate tail + // effect and potential load imbalance and we also want number + // of blocks to be evenly dividable across threads. + + double block_size_f = 1.0 / CostModel::taskSize(1, cost); + Index block_size = numext::mini(n, numext::maxi(1, block_size_f)); + const Index max_block_size = + numext::mini(n, numext::maxi(1, 2 * block_size_f)); + if (block_align) { + Index new_block_size = block_align(block_size); + eigen_assert(new_block_size >= block_size); + block_size = numext::mini(n, new_block_size); + } + Index block_count = divup(n, block_size); + // Calculate parallel efficiency as fraction of total CPU time used for + // computations: + double max_efficiency = + static_cast(block_count) / + (divup(block_count, numThreads()) * numThreads()); + // Now try to increase block size up to max_block_size as long as it + // doesn't decrease parallel efficiency. + for (Index prev_block_count = block_count; prev_block_count > 1;) { + // This is the next block size that divides size into a smaller number + // of blocks than the current block_size. + Index coarser_block_size = divup(n, prev_block_count - 1); + if (block_align) { + Index new_block_size = block_align(coarser_block_size); + eigen_assert(new_block_size >= coarser_block_size); + coarser_block_size = numext::mini(n, new_block_size); + } + if (coarser_block_size > max_block_size) { + break; // Reached max block size. Stop. + } + // Recalculate parallel efficiency. + const Index coarser_block_count = divup(n, coarser_block_size); + eigen_assert(coarser_block_count < prev_block_count); + prev_block_count = coarser_block_count; + const double coarser_efficiency = + static_cast(coarser_block_count) / + (divup(coarser_block_count, numThreads()) * numThreads()); + if (coarser_efficiency + 0.01 >= max_efficiency) { + // Taking it. + block_size = coarser_block_size; + block_count = coarser_block_count; + if (max_efficiency < coarser_efficiency) { + max_efficiency = coarser_efficiency; + } + } + } + + // Recursively divide size into halves until we reach block_size. + // Division code rounds mid to block_size, so we are guaranteed to get + // block_count leaves that do actual computations. + Barrier barrier(static_cast(block_count)); + std::function handleRange; + handleRange = [=, &handleRange, &barrier, &f](Index first, Index last) { + if (last - first <= block_size) { + // Single block or less, execute directly. + f(first, last); + barrier.Notify(); + return; + } + // Split into halves and submit to the pool. + Index mid = first + divup((last - first) / 2, block_size) * block_size; + pool_->Schedule([=, &handleRange]() { handleRange(mid, last); }); + pool_->Schedule([=, &handleRange]() { handleRange(first, mid); }); + }; + handleRange(0, n); + barrier.Wait(); + } + + // Convenience wrapper for parallelFor that does not align blocks. + void parallelFor(Index n, const TensorOpCost& cost, + std::function f) const { + parallelFor(n, cost, nullptr, std::move(f)); + } + + private: + ThreadPoolInterface* pool_; + int num_threads_; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h new file mode 100644 index 000000000..1a30e45fb --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h @@ -0,0 +1,236 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H +#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H + +namespace Eigen { + +/** \internal + * + * \class TensorDimensionList + * \ingroup CXX11_Tensor_Module + * + * \brief Special case of tensor index list used to list all the dimensions of a tensor of rank n. + * + * \sa Tensor + */ + +template struct DimensionList { + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + const Index operator[] (const Index i) const { return i; } +}; + +namespace internal { + +template struct array_size > { + static const size_t value = Rank; +}; +template struct array_size > { + static const size_t value = Rank; +}; + +template const Index array_get(DimensionList&) { + return n; +} +template const Index array_get(const DimensionList&) { + return n; +} + + +#if EIGEN_HAS_CONSTEXPR +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return true; + } +}; +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return true; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; + +template +struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; +template +struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return true; + } +}; + +template +struct index_statically_eq_impl > { + static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i == value; + } +}; +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i == value; + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i != value; + } +}; +template +struct index_statically_ne_impl > { + static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i != value; + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i > value; + } +}; +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i > value; + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i < value; + } +}; +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return i < value; + } +}; + +#else +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return true; + } +}; +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return true; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; + +template +struct indices_statically_known_to_increase_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; +template +struct indices_statically_known_to_increase_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return true; + } +}; + +template +struct index_statically_eq_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_eq_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex){ + return false; + } +}; +template +struct index_statically_ne_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_gt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +template +struct index_statically_lt_impl > { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) { + return false; + } +}; +#endif + +} // end namespace internal +} // end namespace Eigen + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h new file mode 100644 index 000000000..b24cdebf1 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h @@ -0,0 +1,428 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H + + +namespace Eigen { + +/** \internal + * + * \class TensorDimensions + * \ingroup CXX11_Tensor_Module + * + * \brief Set of classes used to encode and store the dimensions of a Tensor. + * + * The Sizes class encodes as part of the type the number of dimensions and the + * sizes corresponding to each dimension. It uses no storage space since it is + * entirely known at compile time. + * The DSizes class is its dynamic sibling: the number of dimensions is known + * at compile time but the sizes are set during execution. + * + * \sa Tensor + */ + +// Boilerplate code +namespace internal { + +template struct dget { + static const std::size_t value = get::value; +}; + + +template +struct fixed_size_tensor_index_linearization_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(array const& indices, + const Dimensions& dimensions) + { + return array_get(indices) + + dget::value * + fixed_size_tensor_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct fixed_size_tensor_index_linearization_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(array const&, const Dimensions&) + { + return 0; + } +}; + +template +struct fixed_size_tensor_index_extraction_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(const Index index, + const Dimensions& dimensions) + { + const Index mult = (index == n-1) ? 1 : 0; + return array_get(dimensions) * mult + + fixed_size_tensor_index_extraction_helper::run(index, dimensions); + } +}; + +template +struct fixed_size_tensor_index_extraction_helper +{ + template EIGEN_DEVICE_FUNC + static inline Index run(const Index, + const Dimensions&) + { + return 0; + } + }; + +} // end namespace internal + + +// Fixed size +#ifndef EIGEN_EMULATE_CXX11_META_H +template +struct Sizes : internal::numeric_list { + typedef internal::numeric_list Base; + static const std::ptrdiff_t total_size = internal::arg_prod(Indices...); + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t rank() const { + return Base::count; + } + + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t TotalSize() { + return internal::arg_prod(Indices...); + } + + EIGEN_DEVICE_FUNC Sizes() { } + template + explicit EIGEN_DEVICE_FUNC Sizes(const array& /*indices*/) { + // todo: add assertion + } +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC Sizes(DenseIndex...) { } + explicit EIGEN_DEVICE_FUNC Sizes(std::initializer_list /*l*/) { + // todo: add assertion + } +#endif + + template Sizes& operator = (const T& /*other*/) { + // add assertion failure if the size of other is different + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t operator[] (const std::size_t index) const { + return internal::fixed_size_tensor_index_extraction_helper::run(index, *this); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfColMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *static_cast(this)); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfRowMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *static_cast(this)); + } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes&) { + return Sizes::total_size; +} +} + +#else + +template +struct non_zero_size { + typedef internal::type2val type; +}; +template <> +struct non_zero_size<0> { + typedef internal::null_type type; +}; + +template struct Sizes { + typedef typename internal::make_type_list::type, typename non_zero_size::type, typename non_zero_size::type, typename non_zero_size::type, typename non_zero_size::type >::type Base; + static const size_t count = Base::count; + static const std::size_t total_size = internal::arg_prod::value; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t rank() const { + return count; + } + + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t TotalSize() { + return internal::arg_prod::value; + } + + Sizes() { } + template + explicit Sizes(const array& /*indices*/) { + // todo: add assertion + } + template Sizes& operator = (const T& /*other*/) { + // add assertion failure if the size of other is different + return *this; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template Sizes(DenseIndex... /*indices*/) { } + explicit Sizes(std::initializer_list) { + // todo: add assertion + } +#else + EIGEN_DEVICE_FUNC explicit Sizes(const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) { + } + EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) { + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex operator[] (const int index) const { + switch (index) { + case 0: + return internal::get<0, Base>::value; + case 1: + return internal::get<1, Base>::value; + case 2: + return internal::get<2, Base>::value; + case 3: + return internal::get<3, Base>::value; + case 4: + return internal::get<4, Base>::value; + default: + eigen_assert(false && "index overflow"); + return static_cast(-1); + } + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfColMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *reinterpret_cast(this)); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + size_t IndexOfRowMajor(const array& indices) const { + return internal::fixed_size_tensor_index_linearization_helper::run(indices, *reinterpret_cast(this)); + } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t array_prod(const Sizes&) { + return Sizes::total_size; +} +} + +#endif + +// Boilerplate +namespace internal { +template +struct tensor_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, array const& dimensions) + { + return array_get(indices) + + array_get(dimensions) * + tensor_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct tensor_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, array const&) + { + return array_get(indices); + } +}; +} // end namespace internal + + + +// Dynamic size +template +struct DSizes : array { + typedef array Base; + static const int count = NumDims; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t rank() const { + return NumDims; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex TotalSize() const { + return (NumDims == 0) ? 1 : internal::array_prod(*static_cast(this)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DSizes() { + for (int i = 0 ; i < NumDims; ++i) { + (*this)[i] = 0; + } + } + EIGEN_DEVICE_FUNC explicit DSizes(const array& a) : Base(a) { } + + EIGEN_DEVICE_FUNC explicit DSizes(const DenseIndex i0) { + eigen_assert(NumDims == 1); + (*this)[0] = i0; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE explicit DSizes(DenseIndex firstDimension, DenseIndex secondDimension, IndexTypes... otherDimensions) : Base({{firstDimension, secondDimension, otherDimensions...}}) { + EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 2 == NumDims, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1) { + eigen_assert(NumDims == 2); + (*this)[0] = i0; + (*this)[1] = i1; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2) { + eigen_assert(NumDims == 3); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3) { + eigen_assert(NumDims == 4); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + (*this)[3] = i3; + } + EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3, const DenseIndex i4) { + eigen_assert(NumDims == 5); + (*this)[0] = i0; + (*this)[1] = i1; + (*this)[2] = i2; + (*this)[3] = i3; + (*this)[4] = i4; + } +#endif + + EIGEN_DEVICE_FUNC DSizes& operator = (const array& other) { + *static_cast(this) = other; + return *this; + } + + // A constexpr would be so much better here + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfColMajor(const array& indices) const { + return internal::tensor_index_linearization_helper::run(indices, *static_cast(this)); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfRowMajor(const array& indices) const { + return internal::tensor_index_linearization_helper::run(indices, *static_cast(this)); + } +}; + + + + +// Boilerplate +namespace internal { +template +struct tensor_vsize_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, std::vector const& dimensions) + { + return array_get(indices) + + array_get(dimensions) * + tensor_vsize_index_linearization_helper::run(indices, dimensions); + } +}; + +template +struct tensor_vsize_index_linearization_helper +{ + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Index run(array const& indices, std::vector const&) + { + return array_get(indices); + } +}; +} // end namespace internal + + +namespace internal { + +template struct array_size > { + static const size_t value = NumDims; +}; +template struct array_size > { + static const size_t value = NumDims; +}; +#ifndef EIGEN_EMULATE_CXX11_META_H +template struct array_size > { +static const std::ptrdiff_t value = Sizes::count; +}; +template struct array_size > { +static const std::ptrdiff_t value = Sizes::count; +}; +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes&) { + return get >::value; +} +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<>&) { + eigen_assert(false && "should never be called"); + return -1; +} +#else +template struct array_size > { + static const size_t value = Sizes::count; +}; +template struct array_size > { + static const size_t value = Sizes::count; +}; +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::size_t array_get(const Sizes&) { + return get::Base>::value; +} + +#endif + + +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1&, Dims2&) { + return false; + } +}; +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1& dims1, Dims2& dims2) { + return (array_get(dims1) == array_get(dims2)) & + sizes_match_below_dim::run(dims1, dims2); + } +}; +template +struct sizes_match_below_dim { + static EIGEN_DEVICE_FUNC inline bool run(Dims1&, Dims2&) { + return true; + } +}; + +} // end namespace internal + + +template +EIGEN_DEVICE_FUNC bool dimensions_match(Dims1& dims1, Dims2& dims2) { + return internal::sizes_match_below_dim::value, internal::array_size::value>::run(dims1, dims2); +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h new file mode 100644 index 000000000..06987132b --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h @@ -0,0 +1,181 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H +#define EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H + +namespace Eigen { + +/** \class TensorForcedEval + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +namespace internal { +template class MakePointer_> +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; + template + struct MakePointer { + // Intermediate typedef to workaround MSVC issue. + typedef MakePointer_ MakePointerT; + typedef typename MakePointerT::Type Type; + }; +}; + +template class MakePointer_> +struct eval, Eigen::Dense> +{ + typedef const TensorEvalToOp& type; +}; + +template class MakePointer_> +struct nested, 1, typename eval >::type> +{ + typedef TensorEvalToOp type; +}; + +} // end namespace internal + + + + +template class MakePointer_> +class TensorEvalToOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename MakePointer_::Type PointerType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvalToOp(PointerType buffer, const XprType& expr) + : m_xpr(expr), m_buffer(buffer) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC PointerType buffer() const { return m_buffer; } + + protected: + typename XprType::Nested m_xpr; + PointerType m_buffer; +}; + + + +template class MakePointer_> +struct TensorEvaluator, Device> +{ + typedef TensorEvalToOp XprType; + typedef typename ArgType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef typename XprType::Index Index; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = true + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), + m_buffer(op.buffer()), m_op(op), m_expression(op.expression()) + { } + + // Used for accessor extraction in SYCL Managed TensorMap: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const XprType& op() const { + return m_op; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ~TensorEvaluator() { + } + + typedef typename internal::traits >::template MakePointer::Type DevicePointer; + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(DevicePointer scalar) { + EIGEN_UNUSED_VARIABLE(scalar); + eigen_assert(scalar == NULL); + return m_impl.evalSubExprsIfNeeded(m_buffer); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) { + m_buffer[i] = m_impl.coeff(i); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) { + internal::pstoret(m_buffer + i, m_impl.template packet::IsAligned ? Aligned : Unaligned>(i)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_buffer[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return internal::ploadt(m_buffer + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + // We assume that evalPacket or evalScalar is called to perform the + // assignment and account for the cost of the write here. + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC DevicePointer data() const { return m_buffer; } + ArgType expression() const { return m_expression; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_impl; } + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + + private: + TensorEvaluator m_impl; + const Device& m_device; + DevicePointer m_buffer; + const XprType& m_op; + const ArgType m_expression; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h new file mode 100644 index 000000000..834ce07df --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h @@ -0,0 +1,633 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H + +namespace Eigen { + +/** \class TensorEvaluator + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor evaluator classes. + * + * These classes are responsible for the evaluation of the tensor expression. + * + * TODO: add support for more types of expressions, in particular expressions + * leading to lvalues (slicing, reshaping, etc...) + */ + +// Generic evaluator +template +struct TensorEvaluator +{ + typedef typename Derived::Index Index; + typedef typename Derived::Scalar Scalar; + typedef typename Derived::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename Derived::Dimensions Dimensions; + + // NumDimensions is -1 for variable dim tensors + static const int NumCoords = internal::traits::NumDimensions > 0 ? + internal::traits::NumDimensions : 0; + + enum { + IsAligned = Derived::IsAligned, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = Derived::Layout, + CoordAccess = NumCoords > 0, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device) + : m_data(const_cast::template MakePointer::Type>(m.data())), m_dims(m.dimensions()), m_device(device), m_impl(m) + { } + + // Used for accessor extraction in SYCL Managed TensorMap: + const Derived& derived() const { return m_impl; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* dest) { + if (dest) { + m_device.memcpy((void*)dest, m_data, sizeof(Scalar) * m_dims.TotalSize()); + return false; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + eigen_assert(m_data); + return m_data[index]; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) { + eigen_assert(m_data); + return m_data[index]; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketReturnType packet(Index index) const + { + return internal::ploadt(m_data + index); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + return internal::pstoret(m_data + index, x); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array& coords) const { + eigen_assert(m_data); + if (static_cast(Layout) == static_cast(ColMajor)) { + return m_data[m_dims.IndexOfColMajor(coords)]; + } else { + return m_data[m_dims.IndexOfRowMajor(coords)]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(const array& coords) { + eigen_assert(m_data); + if (static_cast(Layout) == static_cast(ColMajor)) { + return m_data[m_dims.IndexOfColMajor(coords)]; + } else { + return m_data[m_dims.IndexOfRowMajor(coords)]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC typename internal::traits::template MakePointer::Type data() const { return m_data; } + + /// required by sycl in order to construct sycl buffer from raw pointer + const Device& device() const{return m_device;} + + protected: + typename internal::traits::template MakePointer::Type m_data; + Dimensions m_dims; + const Device& m_device; + const Derived& m_impl; +}; + +namespace { +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T loadConstant(const T* address) { + return *address; +} +// Use the texture cache on CUDA devices whenever possible +#if defined(__CUDA_ARCH__) && __CUDA_ARCH__ >= 350 +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +float loadConstant(const float* address) { + return __ldg(address); +} +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +double loadConstant(const double* address) { + return __ldg(address); +} +template <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +Eigen::half loadConstant(const Eigen::half* address) { + return Eigen::half(half_impl::raw_uint16_to_half(__ldg(&address->x))); +} +#endif +} + + +// Default evaluator for rvalues +template +struct TensorEvaluator +{ + typedef typename Derived::Index Index; + typedef typename Derived::Scalar Scalar; + typedef typename Derived::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef typename Derived::Dimensions Dimensions; + + // NumDimensions is -1 for variable dim tensors + static const int NumCoords = internal::traits::NumDimensions > 0 ? + internal::traits::NumDimensions : 0; + + enum { + IsAligned = Derived::IsAligned, + PacketAccess = (internal::unpacket_traits::size > 1), + Layout = Derived::Layout, + CoordAccess = NumCoords > 0, + RawAccess = true + }; + + // Used for accessor extraction in SYCL Managed TensorMap: + const Derived& derived() const { return m_impl; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device) + : m_data(m.data()), m_dims(m.dimensions()), m_device(device), m_impl(m) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + if (!NumTraits::type>::RequireInitialization && data) { + m_device.memcpy((void*)data, m_data, m_dims.TotalSize() * sizeof(Scalar)); + return false; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const { + eigen_assert(m_data); + return loadConstant(m_data+index); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + PacketReturnType packet(Index index) const + { + return internal::ploadt_ro(m_data + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array& coords) const { + eigen_assert(m_data); + const Index index = (static_cast(Layout) == static_cast(ColMajor)) ? m_dims.IndexOfColMajor(coords) + : m_dims.IndexOfRowMajor(coords); + return loadConstant(m_data+index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC typename internal::traits::template MakePointer::Type data() const { return m_data; } + + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + + protected: + typename internal::traits::template MakePointer::Type m_data; + Dimensions m_dims; + const Device& m_device; + const Derived& m_impl; +}; + + + + +// -------------------- CwiseNullaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseNullaryOp XprType; + + enum { + IsAligned = true, + PacketAccess = internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC + TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), m_argImpl(op.nestedExpression(), device), m_wrapper() + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { return true; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_wrapper(m_functor, index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_wrapper.template packetOp(m_functor, index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, + internal::unpacket_traits::size); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_argImpl; } + /// required by sycl in order to extract the accessor + NullaryOp functor() const { return m_functor; } + + + private: + const NullaryOp m_functor; + TensorEvaluator m_argImpl; + const internal::nullary_wrapper m_wrapper; +}; + + + +// -------------------- CwiseUnaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseUnaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_argImpl(op.nestedExpression(), device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_argImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_argImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_argImpl.coeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_argImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_argImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator & impl() const { return m_argImpl; } + /// added for sycl in order to construct the buffer from sycl device + UnaryOp functor() const { return m_functor; } + + + private: + const UnaryOp m_functor; + TensorEvaluator m_argImpl; +}; + + +// -------------------- CwiseBinaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseBinaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_leftImpl(op.lhsExpression(), device), + m_rightImpl(op.rhsExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || internal::traits::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use right impl instead if right impl dimensions are known at compile time. + return m_leftImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_leftImpl.evalSubExprsIfNeeded(NULL); + m_rightImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_leftImpl.cleanup(); + m_rightImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_leftImpl.coeff(index), m_rightImpl.coeff(index)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_leftImpl.template packet(index), m_rightImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_leftImpl.costPerCoeff(vectorized) + + m_rightImpl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& left_impl() const { return m_leftImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& right_impl() const { return m_rightImpl; } + /// required by sycl in order to extract the accessor + BinaryOp functor() const { return m_functor; } + + private: + const BinaryOp m_functor; + TensorEvaluator m_leftImpl; + TensorEvaluator m_rightImpl; +}; + +// -------------------- CwiseTernaryOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorCwiseTernaryOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::functor_traits::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_functor(op.functor()), + m_arg1Impl(op.arg1Expression(), device), + m_arg2Impl(op.arg2Expression(), device), + m_arg3Impl(op.arg3Expression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout) || internal::traits::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE); + + EIGEN_STATIC_ASSERT((internal::is_same::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::StorageKind, + typename internal::traits::StorageKind>::value), + STORAGE_KIND_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::Index, + typename internal::traits::Index>::value), + STORAGE_INDEX_MUST_MATCH) + EIGEN_STATIC_ASSERT((internal::is_same::Index, + typename internal::traits::Index>::value), + STORAGE_INDEX_MUST_MATCH) + + eigen_assert(dimensions_match(m_arg1Impl.dimensions(), m_arg2Impl.dimensions()) && dimensions_match(m_arg1Impl.dimensions(), m_arg3Impl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use arg2 or arg3 dimensions if they are known at compile time. + return m_arg1Impl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_arg1Impl.evalSubExprsIfNeeded(NULL); + m_arg2Impl.evalSubExprsIfNeeded(NULL); + m_arg3Impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_arg1Impl.cleanup(); + m_arg2Impl.cleanup(); + m_arg3Impl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_functor(m_arg1Impl.coeff(index), m_arg2Impl.coeff(index), m_arg3Impl.coeff(index)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_functor.packetOp(m_arg1Impl.template packet(index), + m_arg2Impl.template packet(index), + m_arg3Impl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + const double functor_cost = internal::functor_traits::Cost; + return m_arg1Impl.costPerCoeff(vectorized) + + m_arg2Impl.costPerCoeff(vectorized) + + m_arg3Impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, functor_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC CoeffReturnType* data() const { return NULL; } + + /// required by sycl in order to extract the accessor + const TensorEvaluator & arg1Impl() const { return m_arg1Impl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& arg2Impl() const { return m_arg2Impl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& arg3Impl() const { return m_arg3Impl; } + + private: + const TernaryOp m_functor; + TensorEvaluator m_arg1Impl; + TensorEvaluator m_arg2Impl; + TensorEvaluator m_arg3Impl; +}; + + +// -------------------- SelectOp -------------------- + +template +struct TensorEvaluator, Device> +{ + typedef TensorSelectOp XprType; + typedef typename XprType::Scalar Scalar; + + enum { + IsAligned = TensorEvaluator::IsAligned & TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess & TensorEvaluator::PacketAccess & + internal::packet_traits::HasBlend, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + : m_condImpl(op.ifExpression(), device), + m_thenImpl(op.thenExpression(), device), + m_elseImpl(op.elseExpression(), device) + { + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((static_cast(TensorEvaluator::Layout) == static_cast(TensorEvaluator::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE); + eigen_assert(dimensions_match(m_condImpl.dimensions(), m_thenImpl.dimensions())); + eigen_assert(dimensions_match(m_thenImpl.dimensions(), m_elseImpl.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename internal::traits::Scalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + typedef typename TensorEvaluator::Dimensions Dimensions; + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const + { + // TODO: use then or else impl instead if they happen to be known at compile time. + return m_condImpl.dimensions(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_condImpl.evalSubExprsIfNeeded(NULL); + m_thenImpl.evalSubExprsIfNeeded(NULL); + m_elseImpl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_condImpl.cleanup(); + m_thenImpl.cleanup(); + m_elseImpl.cleanup(); + } + + EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const + { + return m_condImpl.coeff(index) ? m_thenImpl.coeff(index) : m_elseImpl.coeff(index); + } + template + EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const + { + internal::Selector select; + for (Index i = 0; i < PacketSize; ++i) { + select.select[i] = m_condImpl.coeff(index+i); + } + return internal::pblend(select, + m_thenImpl.template packet(index), + m_elseImpl.template packet(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return m_condImpl.costPerCoeff(vectorized) + + m_thenImpl.costPerCoeff(vectorized) + .cwiseMax(m_elseImpl.costPerCoeff(vectorized)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType* data() const { return NULL; } + /// required by sycl in order to extract the accessor + const TensorEvaluator & cond_impl() const { return m_condImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& then_impl() const { return m_thenImpl; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& else_impl() const { return m_elseImpl; } + + private: + TensorEvaluator m_condImpl; + TensorEvaluator m_thenImpl; + TensorEvaluator m_elseImpl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h new file mode 100644 index 000000000..f01d77c0a --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h @@ -0,0 +1,288 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H + +namespace Eigen { + +/** \class TensorExecutor + * \ingroup CXX11_Tensor_Module + * + * \brief The tensor executor class. + * + * This class is responsible for launch the evaluation of the expression on + * the specified computing device. + */ +namespace internal { + +// Default strategy: the expression is evaluated with a single cpu thread. +template +class TensorExecutor +{ + public: + typedef typename Expression::Index Index; + EIGEN_DEVICE_FUNC + static inline void run(const Expression& expr, const Device& device = Device()) + { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); + for (Index i = 0; i < size; ++i) { + evaluator.evalScalar(i); + } + } + evaluator.cleanup(); + } +}; + + +template +class TensorExecutor +{ + public: + typedef typename Expression::Index Index; + EIGEN_DEVICE_FUNC + static inline void run(const Expression& expr, const DefaultDevice& device = DefaultDevice()) + { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); + const int PacketSize = unpacket_traits::PacketReturnType>::size; + // Give the compiler a strong hint to unroll the loop. But don't insist + // on unrolling, because if the function is expensive the compiler should not + // unroll the loop at the expense of inlining. + const Index UnrolledSize = (size / (4 * PacketSize)) * 4 * PacketSize; + for (Index i = 0; i < UnrolledSize; i += 4*PacketSize) { + for (Index j = 0; j < 4; j++) { + evaluator.evalPacket(i + j * PacketSize); + } + } + const Index VectorizedSize = (size / PacketSize) * PacketSize; + for (Index i = UnrolledSize; i < VectorizedSize; i += PacketSize) { + evaluator.evalPacket(i); + } + for (Index i = VectorizedSize; i < size; ++i) { + evaluator.evalScalar(i); + } + } + evaluator.cleanup(); + } +}; + + + +// Multicore strategy: the index space is partitioned and each partition is executed on a single core +#ifdef EIGEN_USE_THREADS +template +struct EvalRange { + static void run(Evaluator* evaluator_in, const Index first, const Index last) { + Evaluator evaluator = *evaluator_in; + eigen_assert(last >= first); + for (Index i = first; i < last; ++i) { + evaluator.evalScalar(i); + } + } + + static Index alignBlockSize(Index size) { + return size; + } +}; + +template +struct EvalRange { + static const int PacketSize = unpacket_traits::size; + + static void run(Evaluator* evaluator_in, const Index first, const Index last) { + Evaluator evaluator = *evaluator_in; + eigen_assert(last >= first); + Index i = first; + if (last - first >= PacketSize) { + eigen_assert(first % PacketSize == 0); + Index last_chunk_offset = last - 4 * PacketSize; + // Give the compiler a strong hint to unroll the loop. But don't insist + // on unrolling, because if the function is expensive the compiler should not + // unroll the loop at the expense of inlining. + for (; i <= last_chunk_offset; i += 4*PacketSize) { + for (Index j = 0; j < 4; j++) { + evaluator.evalPacket(i + j * PacketSize); + } + } + last_chunk_offset = last - PacketSize; + for (; i <= last_chunk_offset; i += PacketSize) { + evaluator.evalPacket(i); + } + } + for (; i < last; ++i) { + evaluator.evalScalar(i); + } + } + + static Index alignBlockSize(Index size) { + // Align block size to packet size and account for unrolling in run above. + if (size >= 16 * PacketSize) { + return (size + 4 * PacketSize - 1) & ~(4 * PacketSize - 1); + } + // Aligning to 4 * PacketSize would increase block size by more than 25%. + return (size + PacketSize - 1) & ~(PacketSize - 1); + } +}; + +template +class TensorExecutor { + public: + typedef typename Expression::Index Index; + static inline void run(const Expression& expr, const ThreadPoolDevice& device) + { + typedef TensorEvaluator Evaluator; + Evaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) + { + const Index size = array_prod(evaluator.dimensions()); +#if !defined(EIGEN_USE_SIMPLE_THREAD_POOL) + device.parallelFor(size, evaluator.costPerCoeff(Vectorizable), + EvalRange::alignBlockSize, + [&evaluator](Index first, Index last) { + EvalRange::run(&evaluator, first, last); + }); +#else + size_t num_threads = device.numThreads(); + if (num_threads > 1) { + num_threads = TensorCostModel::numThreads( + size, evaluator.costPerCoeff(Vectorizable), num_threads); + } + if (num_threads == 1) { + EvalRange::run(&evaluator, 0, size); + } else { + const Index PacketSize = Vectorizable ? unpacket_traits::size : 1; + Index blocksz = std::ceil(static_cast(size)/num_threads) + PacketSize - 1; + const Index blocksize = numext::maxi(PacketSize, (blocksz - (blocksz % PacketSize))); + const Index numblocks = size / blocksize; + + Barrier barrier(numblocks); + for (int i = 0; i < numblocks; ++i) { + device.enqueue_with_barrier( + &barrier, &EvalRange::run, + &evaluator, i * blocksize, (i + 1) * blocksize); + } + if (numblocks * blocksize < size) { + EvalRange::run( + &evaluator, numblocks * blocksize, size); + } + barrier.Wait(); + } +#endif // defined(!EIGEN_USE_SIMPLE_THREAD_POOL) + } + evaluator.cleanup(); + } +}; +#endif // EIGEN_USE_THREADS + + +// GPU: the evaluation of the expression is offloaded to a GPU. +#if defined(EIGEN_USE_GPU) + +template +class TensorExecutor { + public: + typedef typename Expression::Index Index; + static void run(const Expression& expr, const GpuDevice& device); +}; + + +#if defined(__CUDACC__) +template +struct EigenMetaKernelEval { + static __device__ EIGEN_ALWAYS_INLINE + void run(Evaluator& eval, Index first, Index last, Index step_size) { + for (Index i = first; i < last; i += step_size) { + eval.evalScalar(i); + } + } +}; + +template +struct EigenMetaKernelEval { + static __device__ EIGEN_ALWAYS_INLINE + void run(Evaluator& eval, Index first, Index last, Index step_size) { + const Index PacketSize = unpacket_traits::size; + const Index vectorized_size = (last / PacketSize) * PacketSize; + const Index vectorized_step_size = step_size * PacketSize; + + // Use the vector path + for (Index i = first * PacketSize; i < vectorized_size; + i += vectorized_step_size) { + eval.evalPacket(i); + } + for (Index i = vectorized_size + first; i < last; i += step_size) { + eval.evalScalar(i); + } + } +}; + +template +__global__ void +__launch_bounds__(1024) +EigenMetaKernel(Evaluator eval, Index size) { + + const Index first_index = blockIdx.x * blockDim.x + threadIdx.x; + const Index step_size = blockDim.x * gridDim.x; + + const bool vectorizable = Evaluator::PacketAccess & Evaluator::IsAligned; + EigenMetaKernelEval::run(eval, first_index, size, step_size); +} + +/*static*/ +template +inline void TensorExecutor::run( + const Expression& expr, const GpuDevice& device) { + TensorEvaluator evaluator(expr, device); + const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL); + if (needs_assign) { + const int block_size = device.maxCudaThreadsPerBlock(); + const int max_blocks = device.getNumCudaMultiProcessors() * + device.maxCudaThreadsPerMultiProcessor() / block_size; + const Index size = array_prod(evaluator.dimensions()); + // Create a least one block to ensure we won't crash when tensorflow calls with tensors of size 0. + const int num_blocks = numext::maxi(numext::mini(max_blocks, divup(size, block_size)), 1); + + LAUNCH_CUDA_KERNEL( + (EigenMetaKernel, Index>), + num_blocks, block_size, 0, device, evaluator, size); + } + evaluator.cleanup(); +} + +#endif // __CUDACC__ +#endif // EIGEN_USE_GPU + +// SYCL Executor policy +#ifdef EIGEN_USE_SYCL + +template +class TensorExecutor { +public: + static inline void run(const Expression &expr, const SyclDevice &device) { + // call TensorSYCL module + TensorSycl::run(expr, device); + } +}; + +#endif + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h new file mode 100644 index 000000000..85dfc7a69 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h @@ -0,0 +1,371 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXPR_H +#define EIGEN_CXX11_TENSOR_TENSOR_EXPR_H + +namespace Eigen { + +/** \class TensorExpr + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor expression classes. + * + * The TensorCwiseNullaryOp class applies a nullary operators to an expression. + * This is typically used to generate constants. + * + * The TensorCwiseUnaryOp class represents an expression where a unary operator + * (e.g. cwiseSqrt) is applied to an expression. + * + * The TensorCwiseBinaryOp class represents an expression where a binary + * operator (e.g. addition) is applied to a lhs and a rhs expression. + * + */ +namespace internal { +template +struct traits > + : traits +{ + typedef traits XprTraits; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +} // end namespace internal + + + +template +class TensorCwiseNullaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef TensorCwiseNullaryOp Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseNullaryOp(const XprType& xpr, const NullaryOp& func = NullaryOp()) + : m_xpr(xpr), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + const NullaryOp& functor() const { return m_functor; } + + protected: + typename XprType::Nested m_xpr; + const NullaryOp m_functor; +}; + + + +namespace internal { +template +struct traits > + : traits +{ + // TODO(phli): Add InputScalar, InputPacket. Check references to + // current Scalar/Packet to see if the intent is Input or Output. + typedef typename result_of::type Scalar; + typedef traits XprTraits; + typedef typename XprType::Nested XprTypeNested; + typedef typename remove_reference::type _XprTypeNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseUnaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseUnaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseUnaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + // TODO(phli): Add InputScalar, InputPacket. Check references to + // current Scalar/Packet to see if the intent is Input or Output. + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp()) + : m_xpr(xpr), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const UnaryOp& functor() const { return m_functor; } + + /** \returns the nested expression */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + nestedExpression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const UnaryOp m_functor; +}; + + +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs + // are different. + // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket. Check references to + // current Scalar/Packet to see if the intent is Inputs or Output. + typedef typename result_of< + BinaryOp(typename LhsXprType::Scalar, + typename RhsXprType::Scalar)>::type Scalar; + typedef traits XprTraits; + typedef typename promote_storage_type< + typename traits::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type< + typename traits::Index, + typename traits::Index>::type Index; + typedef typename LhsXprType::Nested LhsNested; + typedef typename RhsXprType::Nested RhsNested; + typedef typename remove_reference::type _LhsNested; + typedef typename remove_reference::type _RhsNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseBinaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseBinaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseBinaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket. Check references to + // current Scalar/Packet to see if the intent is Inputs or Output. + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const BinaryOp& func = BinaryOp()) + : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const BinaryOp& functor() const { return m_functor; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + lhsExpression() const { return m_lhs_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + rhsExpression() const { return m_rhs_xpr; } + + protected: + typename LhsXprType::Nested m_lhs_xpr; + typename RhsXprType::Nested m_rhs_xpr; + const BinaryOp m_functor; +}; + + +namespace internal { +template +struct traits > +{ + // Type promotion to handle the case where the types of the args are different. + typedef typename result_of< + TernaryOp(typename Arg1XprType::Scalar, + typename Arg2XprType::Scalar, + typename Arg3XprType::Scalar)>::type Scalar; + typedef traits XprTraits; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename Arg1XprType::Nested Arg1Nested; + typedef typename Arg2XprType::Nested Arg2Nested; + typedef typename Arg3XprType::Nested Arg3Nested; + typedef typename remove_reference::type _Arg1Nested; + typedef typename remove_reference::type _Arg2Nested; + typedef typename remove_reference::type _Arg3Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorCwiseTernaryOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorCwiseTernaryOp type; +}; + +} // end namespace internal + + + +template +class TensorCwiseTernaryOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef Scalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseTernaryOp(const Arg1XprType& arg1, const Arg2XprType& arg2, const Arg3XprType& arg3, const TernaryOp& func = TernaryOp()) + : m_arg1_xpr(arg1), m_arg2_xpr(arg2), m_arg3_xpr(arg3), m_functor(func) {} + + EIGEN_DEVICE_FUNC + const TernaryOp& functor() const { return m_functor; } + + /** \returns the nested expressions */ + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg1Expression() const { return m_arg1_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg2Expression() const { return m_arg2_xpr; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + arg3Expression() const { return m_arg3_xpr; } + + protected: + typename Arg1XprType::Nested m_arg1_xpr; + typename Arg2XprType::Nested m_arg2_xpr; + typename Arg3XprType::Nested m_arg3_xpr; + const TernaryOp m_functor; +}; + + +namespace internal { +template +struct traits > + : traits +{ + typedef typename traits::Scalar Scalar; + typedef traits XprTraits; + typedef typename promote_storage_type::StorageKind, + typename traits::StorageKind>::ret StorageKind; + typedef typename promote_index_type::Index, + typename traits::Index>::type Index; + typedef typename IfXprType::Nested IfNested; + typedef typename ThenXprType::Nested ThenNested; + typedef typename ElseXprType::Nested ElseNested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorSelectOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorSelectOp type; +}; + +} // end namespace internal + + +template +class TensorSelectOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::promote_storage_type::ret CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC + TensorSelectOp(const IfXprType& a_condition, + const ThenXprType& a_then, + const ElseXprType& a_else) + : m_condition(a_condition), m_then(a_then), m_else(a_else) + { } + + EIGEN_DEVICE_FUNC + const IfXprType& ifExpression() const { return m_condition; } + + EIGEN_DEVICE_FUNC + const ThenXprType& thenExpression() const { return m_then; } + + EIGEN_DEVICE_FUNC + const ElseXprType& elseExpression() const { return m_else; } + + protected: + typename IfXprType::Nested m_condition; + typename ThenXprType::Nested m_then; + typename ElseXprType::Nested m_else; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_EXPR_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h new file mode 100644 index 000000000..08eb5595a --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h @@ -0,0 +1,651 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Jianwei Cui +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FFT_H +#define EIGEN_CXX11_TENSOR_TENSOR_FFT_H + +// This code requires the ability to initialize arrays of constant +// values directly inside a class. +#if __cplusplus >= 201103L || EIGEN_COMP_MSVC >= 1900 + +namespace Eigen { + +/** \class TensorFFT + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor FFT class. + * + * TODO: + * Vectorize the Cooley Tukey and the Bluestein algorithm + * Add support for multithreaded evaluation + * Improve the performance on GPU + */ + +template struct MakeComplex { + template + EIGEN_DEVICE_FUNC + T operator() (const T& val) const { return val; } +}; + +template <> struct MakeComplex { + template + EIGEN_DEVICE_FUNC + std::complex operator() (const T& val) const { return std::complex(val, 0); } +}; + +template <> struct MakeComplex { + template + EIGEN_DEVICE_FUNC + std::complex operator() (const std::complex& val) const { return val; } +}; + +template struct PartOf { + template T operator() (const T& val) const { return val; } +}; + +template <> struct PartOf { + template T operator() (const std::complex& val) const { return val.real(); } +}; + +template <> struct PartOf { + template T operator() (const std::complex& val) const { return val.imag(); } +}; + +namespace internal { +template +struct traits > : public traits { + typedef traits XprTraits; + typedef typename NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename XprTraits::Scalar InputScalar; + typedef typename conditional::type OutputScalar; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> { + typedef const TensorFFTOp& type; +}; + +template +struct nested, 1, typename eval >::type> { + typedef TensorFFTOp type; +}; + +} // end namespace internal + +template +class TensorFFTOp : public TensorBase, ReadOnlyAccessors> { + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename internal::conditional::type OutputScalar; + typedef OutputScalar CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFFTOp(const XprType& expr, const FFT& fft) + : m_xpr(expr), m_fft(fft) {} + + EIGEN_DEVICE_FUNC + const FFT& fft() const { return m_fft; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& expression() const { + return m_xpr; + } + + protected: + typename XprType::Nested m_xpr; + const FFT m_fft; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> { + typedef TensorFFTOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename std::complex ComplexScalar; + typedef typename TensorEvaluator::Dimensions InputDimensions; + typedef internal::traits XprTraits; + typedef typename XprTraits::Scalar InputScalar; + typedef typename internal::conditional::type OutputScalar; + typedef OutputScalar CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = true, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) : m_fft(op.fft()), m_impl(op.expression(), device), m_data(NULL), m_device(device) { + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + for (int i = 0; i < NumDims; ++i) { + eigen_assert(input_dims[i] > 0); + m_dimensions[i] = input_dims[i]; + } + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_strides[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1]; + } + } + m_size = m_dimensions.TotalSize(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { + return m_dimensions; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(OutputScalar* data) { + m_impl.evalSubExprsIfNeeded(NULL); + if (data) { + evalToBuf(data); + return false; + } else { + m_data = (CoeffReturnType*)m_device.allocate(sizeof(CoeffReturnType) * m_size); + evalToBuf(m_data); + return true; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + if (m_data) { + m_device.deallocate(m_data); + m_data = NULL; + } + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const { + return m_data[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType + packet(Index index) const { + return internal::ploadt(m_data + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return m_data; } + + + private: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalToBuf(OutputScalar* data) { + const bool write_to_out = internal::is_same::value; + ComplexScalar* buf = write_to_out ? (ComplexScalar*)data : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * m_size); + + for (Index i = 0; i < m_size; ++i) { + buf[i] = MakeComplex::value>()(m_impl.coeff(i)); + } + + for (size_t i = 0; i < m_fft.size(); ++i) { + Index dim = m_fft[i]; + eigen_assert(dim >= 0 && dim < NumDims); + Index line_len = m_dimensions[dim]; + eigen_assert(line_len >= 1); + ComplexScalar* line_buf = (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * line_len); + const bool is_power_of_two = isPowerOfTwo(line_len); + const Index good_composite = is_power_of_two ? 0 : findGoodComposite(line_len); + const Index log_len = is_power_of_two ? getLog2(line_len) : getLog2(good_composite); + + ComplexScalar* a = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite); + ComplexScalar* b = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite); + ComplexScalar* pos_j_base_powered = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * (line_len + 1)); + if (!is_power_of_two) { + // Compute twiddle factors + // t_n = exp(sqrt(-1) * pi * n^2 / line_len) + // for n = 0, 1,..., line_len-1. + // For n > 2 we use the recurrence t_n = t_{n-1}^2 / t_{n-2} * t_1^2 + pos_j_base_powered[0] = ComplexScalar(1, 0); + if (line_len > 1) { + const RealScalar pi_over_len(EIGEN_PI / line_len); + const ComplexScalar pos_j_base = ComplexScalar( + std::cos(pi_over_len), std::sin(pi_over_len)); + pos_j_base_powered[1] = pos_j_base; + if (line_len > 2) { + const ComplexScalar pos_j_base_sq = pos_j_base * pos_j_base; + for (int j = 2; j < line_len + 1; ++j) { + pos_j_base_powered[j] = pos_j_base_powered[j - 1] * + pos_j_base_powered[j - 1] / + pos_j_base_powered[j - 2] * pos_j_base_sq; + } + } + } + } + + for (Index partial_index = 0; partial_index < m_size / line_len; ++partial_index) { + const Index base_offset = getBaseOffsetFromIndex(partial_index, dim); + + // get data into line_buf + const Index stride = m_strides[dim]; + if (stride == 1) { + memcpy(line_buf, &buf[base_offset], line_len*sizeof(ComplexScalar)); + } else { + Index offset = base_offset; + for (int j = 0; j < line_len; ++j, offset += stride) { + line_buf[j] = buf[offset]; + } + } + + // processs the line + if (is_power_of_two) { + processDataLineCooleyTukey(line_buf, line_len, log_len); + } + else { + processDataLineBluestein(line_buf, line_len, good_composite, log_len, a, b, pos_j_base_powered); + } + + // write back + if (FFTDir == FFT_FORWARD && stride == 1) { + memcpy(&buf[base_offset], line_buf, line_len*sizeof(ComplexScalar)); + } else { + Index offset = base_offset; + const ComplexScalar div_factor = ComplexScalar(1.0 / line_len, 0); + for (int j = 0; j < line_len; ++j, offset += stride) { + buf[offset] = (FFTDir == FFT_FORWARD) ? line_buf[j] : line_buf[j] * div_factor; + } + } + } + m_device.deallocate(line_buf); + if (!is_power_of_two) { + m_device.deallocate(a); + m_device.deallocate(b); + m_device.deallocate(pos_j_base_powered); + } + } + + if(!write_to_out) { + for (Index i = 0; i < m_size; ++i) { + data[i] = PartOf()(buf[i]); + } + m_device.deallocate(buf); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static bool isPowerOfTwo(Index x) { + eigen_assert(x > 0); + return !(x & (x - 1)); + } + + // The composite number for padding, used in Bluestein's FFT algorithm + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index findGoodComposite(Index n) { + Index i = 2; + while (i < 2 * n - 1) i *= 2; + return i; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index getLog2(Index m) { + Index log2m = 0; + while (m >>= 1) log2m++; + return log2m; + } + + // Call Cooley Tukey algorithm directly, data length must be power of 2 + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineCooleyTukey(ComplexScalar* line_buf, Index line_len, Index log_len) { + eigen_assert(isPowerOfTwo(line_len)); + scramble_FFT(line_buf, line_len); + compute_1D_Butterfly(line_buf, line_len, log_len); + } + + // Call Bluestein's FFT algorithm, m is a good composite number greater than (2 * n - 1), used as the padding length + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineBluestein(ComplexScalar* line_buf, Index line_len, Index good_composite, Index log_len, ComplexScalar* a, ComplexScalar* b, const ComplexScalar* pos_j_base_powered) { + Index n = line_len; + Index m = good_composite; + ComplexScalar* data = line_buf; + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + a[i] = data[i] * numext::conj(pos_j_base_powered[i]); + } + else { + a[i] = data[i] * pos_j_base_powered[i]; + } + } + for (Index i = n; i < m; ++i) { + a[i] = ComplexScalar(0, 0); + } + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + b[i] = pos_j_base_powered[i]; + } + else { + b[i] = numext::conj(pos_j_base_powered[i]); + } + } + for (Index i = n; i < m - n; ++i) { + b[i] = ComplexScalar(0, 0); + } + for (Index i = m - n; i < m; ++i) { + if(FFTDir == FFT_FORWARD) { + b[i] = pos_j_base_powered[m-i]; + } + else { + b[i] = numext::conj(pos_j_base_powered[m-i]); + } + } + + scramble_FFT(a, m); + compute_1D_Butterfly(a, m, log_len); + + scramble_FFT(b, m); + compute_1D_Butterfly(b, m, log_len); + + for (Index i = 0; i < m; ++i) { + a[i] *= b[i]; + } + + scramble_FFT(a, m); + compute_1D_Butterfly(a, m, log_len); + + //Do the scaling after ifft + for (Index i = 0; i < m; ++i) { + a[i] /= m; + } + + for (Index i = 0; i < n; ++i) { + if(FFTDir == FFT_FORWARD) { + data[i] = a[i] * numext::conj(pos_j_base_powered[i]); + } + else { + data[i] = a[i] * pos_j_base_powered[i]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void scramble_FFT(ComplexScalar* data, Index n) { + eigen_assert(isPowerOfTwo(n)); + Index j = 1; + for (Index i = 1; i < n; ++i){ + if (j > i) { + std::swap(data[j-1], data[i-1]); + } + Index m = n >> 1; + while (m >= 2 && j > m) { + j -= m; + m >>= 1; + } + j += m; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_2(ComplexScalar* data) { + ComplexScalar tmp = data[1]; + data[1] = data[0] - data[1]; + data[0] += tmp; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_4(ComplexScalar* data) { + ComplexScalar tmp[4]; + tmp[0] = data[0] + data[1]; + tmp[1] = data[0] - data[1]; + tmp[2] = data[2] + data[3]; + if (Dir == FFT_FORWARD) { + tmp[3] = ComplexScalar(0.0, -1.0) * (data[2] - data[3]); + } else { + tmp[3] = ComplexScalar(0.0, 1.0) * (data[2] - data[3]); + } + data[0] = tmp[0] + tmp[2]; + data[1] = tmp[1] + tmp[3]; + data[2] = tmp[0] - tmp[2]; + data[3] = tmp[1] - tmp[3]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_8(ComplexScalar* data) { + ComplexScalar tmp_1[8]; + ComplexScalar tmp_2[8]; + + tmp_1[0] = data[0] + data[1]; + tmp_1[1] = data[0] - data[1]; + tmp_1[2] = data[2] + data[3]; + if (Dir == FFT_FORWARD) { + tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, -1); + } else { + tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, 1); + } + tmp_1[4] = data[4] + data[5]; + tmp_1[5] = data[4] - data[5]; + tmp_1[6] = data[6] + data[7]; + if (Dir == FFT_FORWARD) { + tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, -1); + } else { + tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, 1); + } + tmp_2[0] = tmp_1[0] + tmp_1[2]; + tmp_2[1] = tmp_1[1] + tmp_1[3]; + tmp_2[2] = tmp_1[0] - tmp_1[2]; + tmp_2[3] = tmp_1[1] - tmp_1[3]; + tmp_2[4] = tmp_1[4] + tmp_1[6]; +// SQRT2DIV2 = sqrt(2)/2 +#define SQRT2DIV2 0.7071067811865476 + if (Dir == FFT_FORWARD) { + tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, -SQRT2DIV2); + tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, -1); + tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, -SQRT2DIV2); + } else { + tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, SQRT2DIV2); + tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, 1); + tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, SQRT2DIV2); + } + data[0] = tmp_2[0] + tmp_2[4]; + data[1] = tmp_2[1] + tmp_2[5]; + data[2] = tmp_2[2] + tmp_2[6]; + data[3] = tmp_2[3] + tmp_2[7]; + data[4] = tmp_2[0] - tmp_2[4]; + data[5] = tmp_2[1] - tmp_2[5]; + data[6] = tmp_2[2] - tmp_2[6]; + data[7] = tmp_2[3] - tmp_2[7]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_1D_merge( + ComplexScalar* data, Index n, Index n_power_of_2) { + // Original code: + // RealScalar wtemp = std::sin(M_PI/n); + // RealScalar wpi = -std::sin(2 * M_PI/n); + const RealScalar wtemp = m_sin_PI_div_n_LUT[n_power_of_2]; + const RealScalar wpi = (Dir == FFT_FORWARD) + ? m_minus_sin_2_PI_div_n_LUT[n_power_of_2] + : -m_minus_sin_2_PI_div_n_LUT[n_power_of_2]; + + const ComplexScalar wp(wtemp, wpi); + const ComplexScalar wp_one = wp + ComplexScalar(1, 0); + const ComplexScalar wp_one_2 = wp_one * wp_one; + const ComplexScalar wp_one_3 = wp_one_2 * wp_one; + const ComplexScalar wp_one_4 = wp_one_3 * wp_one; + const Index n2 = n / 2; + ComplexScalar w(1.0, 0.0); + for (Index i = 0; i < n2; i += 4) { + ComplexScalar temp0(data[i + n2] * w); + ComplexScalar temp1(data[i + 1 + n2] * w * wp_one); + ComplexScalar temp2(data[i + 2 + n2] * w * wp_one_2); + ComplexScalar temp3(data[i + 3 + n2] * w * wp_one_3); + w = w * wp_one_4; + + data[i + n2] = data[i] - temp0; + data[i] += temp0; + + data[i + 1 + n2] = data[i + 1] - temp1; + data[i + 1] += temp1; + + data[i + 2 + n2] = data[i + 2] - temp2; + data[i + 2] += temp2; + + data[i + 3 + n2] = data[i + 3] - temp3; + data[i + 3] += temp3; + } + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_1D_Butterfly( + ComplexScalar* data, Index n, Index n_power_of_2) { + eigen_assert(isPowerOfTwo(n)); + if (n > 8) { + compute_1D_Butterfly(data, n / 2, n_power_of_2 - 1); + compute_1D_Butterfly(data + n / 2, n / 2, n_power_of_2 - 1); + butterfly_1D_merge(data, n, n_power_of_2); + } else if (n == 8) { + butterfly_8(data); + } else if (n == 4) { + butterfly_4(data); + } else if (n == 2) { + butterfly_2(data); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getBaseOffsetFromIndex(Index index, Index omitted_dim) const { + Index result = 0; + + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > omitted_dim; --i) { + const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim]; + const Index idx = index / partial_m_stride; + index -= idx * partial_m_stride; + result += idx * m_strides[i]; + } + result += index; + } + else { + for (Index i = 0; i < omitted_dim; ++i) { + const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim]; + const Index idx = index / partial_m_stride; + index -= idx * partial_m_stride; + result += idx * m_strides[i]; + } + result += index; + } + // Value of index_coords[omitted_dim] is not determined to this step + return result; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getIndexFromOffset(Index base, Index omitted_dim, Index offset) const { + Index result = base + offset * m_strides[omitted_dim] ; + return result; + } + + protected: + Index m_size; + const FFT& m_fft; + Dimensions m_dimensions; + array m_strides; + TensorEvaluator m_impl; + CoeffReturnType* m_data; + const Device& m_device; + + // This will support a maximum FFT size of 2^32 for each dimension + // m_sin_PI_div_n_LUT[i] = (-2) * std::sin(M_PI / std::pow(2,i)) ^ 2; + const RealScalar m_sin_PI_div_n_LUT[32] = { + RealScalar(0.0), + RealScalar(-2), + RealScalar(-0.999999999999999), + RealScalar(-0.292893218813453), + RealScalar(-0.0761204674887130), + RealScalar(-0.0192147195967696), + RealScalar(-0.00481527332780311), + RealScalar(-0.00120454379482761), + RealScalar(-3.01181303795779e-04), + RealScalar(-7.52981608554592e-05), + RealScalar(-1.88247173988574e-05), + RealScalar(-4.70619042382852e-06), + RealScalar(-1.17654829809007e-06), + RealScalar(-2.94137117780840e-07), + RealScalar(-7.35342821488550e-08), + RealScalar(-1.83835707061916e-08), + RealScalar(-4.59589268710903e-09), + RealScalar(-1.14897317243732e-09), + RealScalar(-2.87243293150586e-10), + RealScalar( -7.18108232902250e-11), + RealScalar(-1.79527058227174e-11), + RealScalar(-4.48817645568941e-12), + RealScalar(-1.12204411392298e-12), + RealScalar(-2.80511028480785e-13), + RealScalar(-7.01277571201985e-14), + RealScalar(-1.75319392800498e-14), + RealScalar(-4.38298482001247e-15), + RealScalar(-1.09574620500312e-15), + RealScalar(-2.73936551250781e-16), + RealScalar(-6.84841378126949e-17), + RealScalar(-1.71210344531737e-17), + RealScalar(-4.28025861329343e-18) + }; + + // m_minus_sin_2_PI_div_n_LUT[i] = -std::sin(2 * M_PI / std::pow(2,i)); + const RealScalar m_minus_sin_2_PI_div_n_LUT[32] = { + RealScalar(0.0), + RealScalar(0.0), + RealScalar(-1.00000000000000e+00), + RealScalar(-7.07106781186547e-01), + RealScalar(-3.82683432365090e-01), + RealScalar(-1.95090322016128e-01), + RealScalar(-9.80171403295606e-02), + RealScalar(-4.90676743274180e-02), + RealScalar(-2.45412285229123e-02), + RealScalar(-1.22715382857199e-02), + RealScalar(-6.13588464915448e-03), + RealScalar(-3.06795676296598e-03), + RealScalar(-1.53398018628477e-03), + RealScalar(-7.66990318742704e-04), + RealScalar(-3.83495187571396e-04), + RealScalar(-1.91747597310703e-04), + RealScalar(-9.58737990959773e-05), + RealScalar(-4.79368996030669e-05), + RealScalar(-2.39684498084182e-05), + RealScalar(-1.19842249050697e-05), + RealScalar(-5.99211245264243e-06), + RealScalar(-2.99605622633466e-06), + RealScalar(-1.49802811316901e-06), + RealScalar(-7.49014056584716e-07), + RealScalar(-3.74507028292384e-07), + RealScalar(-1.87253514146195e-07), + RealScalar(-9.36267570730981e-08), + RealScalar(-4.68133785365491e-08), + RealScalar(-2.34066892682746e-08), + RealScalar(-1.17033446341373e-08), + RealScalar(-5.85167231706864e-09), + RealScalar(-2.92583615853432e-09) + }; +}; + +} // end namespace Eigen + +#endif // EIGEN_HAS_CONSTEXPR + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FFT_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h new file mode 100644 index 000000000..fcee5f60d --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h @@ -0,0 +1,389 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H +#define EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H + +namespace Eigen { + +/** \class TensorFixedSize + * \ingroup CXX11_Tensor_Module + * + * \brief The fixed sized version of the tensor class. + * + * The fixed sized equivalent of + * Eigen::Tensor t(3, 5, 7); + * is + * Eigen::TensorFixedSize> t; + */ + +template +class TensorFixedSize : public TensorBase > +{ + public: + typedef TensorFixedSize Self; + typedef TensorBase > Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef Scalar_ Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + static const int Options = Options_; + + enum { + IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0), + Layout = Options_ & RowMajor ? RowMajor : ColMajor, + CoordAccess = true, + RawAccess = true + }; + + typedef Dimensions_ Dimensions; + static const std::size_t NumIndices = Dimensions::count; + + protected: + TensorStorage m_storage; + + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const { return NumIndices; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index dimension(std::size_t n) const { return m_storage.dimensions()[n]; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_storage.dimensions(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_storage.size(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar *data() { return m_storage.data(); } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar *data() const { return m_storage.data(); } + + // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED + // work, because that uses base().coeffRef() - and we don't yet + // implement a similar class hierarchy + inline Self& base() { return *this; } + inline const Self& base() const { return *this; } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeff(array{{firstIndex, otherIndices...}}); + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff(const array& indices) const + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& coeff() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(array{{firstIndex, otherIndices...}}); + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef(const array& indices) + { + eigen_internal_assert(checkIndexRange(indices)); + return m_storage.data()[linearizedIndex(indices)]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_storage.data()[index]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& coeffRef() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return m_storage.data()[0]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) const + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return this->operator()(array{{firstIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + if (Options&RowMajor) { + const Index index = i1 + i0 * m_storage.dimensions()[1]; + return m_storage.data()[index]; + } else { + const Index index = i0 + i1 * m_storage.dimensions()[0]; + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + if (Options&RowMajor) { + const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + if (Options&RowMajor) { + const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3)); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + if (Options&RowMajor) { + const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0))); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4))); + return m_storage.data()[index]; + } + } +#endif + + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + eigen_assert(checkIndexRange(indices)); + return coeff(indices); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return coeff(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const + { + // The bracket operator is only for vectors, use the parenthesis operator instead. + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeff(index); + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) + { + // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + return operator()(array{{firstIndex, otherIndices...}}); + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + if (Options&RowMajor) { + const Index index = i1 + i0 * m_storage.dimensions()[1]; + return m_storage.data()[index]; + } else { + const Index index = i0 + i1 * m_storage.dimensions()[0]; + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + if (Options&RowMajor) { + const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + if (Options&RowMajor) { + const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3)); + return m_storage.data()[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + if (Options&RowMajor) { + const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0))); + return m_storage.data()[index]; + } else { + const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4))); + return m_storage.data()[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + eigen_assert(checkIndexRange(indices)); + return coeffRef(indices); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_assert(index >= 0 && index < size()); + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE); + return coeffRef(); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator[](Index index) + { + // The bracket operator is only for vectors, use the parenthesis operator instead + EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE) + return coeffRef(index); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize() + : m_storage() + { + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const Self& other) + : m_storage(other.m_storage) + { + } + +#if EIGEN_HAS_RVALUE_REFERENCES + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFixedSize(Self&& other) + : m_storage(other.m_storage) + { + } +#endif + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other.derived()); + internal::TensorExecutor::run(assign, DefaultDevice()); + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize& operator=(const TensorFixedSize& other) + { + // FIXME: check that the dimensions of other match the dimensions of *this. + // Unfortunately this isn't possible yet when the rhs is an expression. + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorFixedSize& operator=(const OtherDerived& other) + { + // FIXME: check that the dimensions of other match the dimensions of *this. + // Unfortunately this isn't possible yet when the rhs is an expression. + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE bool checkIndexRange(const array& /*indices*/) const + { + using internal::array_apply_and_reduce; + using internal::array_zip_and_reduce; + using internal::greater_equal_zero_op; + using internal::logical_and_op; + using internal::lesser_op; + + return true; + // check whether the indices are all >= 0 + /* array_apply_and_reduce(indices) && + // check whether the indices fit in the dimensions + array_zip_and_reduce(indices, m_storage.dimensions());*/ + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index linearizedIndex(const array& indices) const + { + if (Options&RowMajor) { + return m_storage.dimensions().IndexOfRowMajor(indices); + } else { + return m_storage.dimensions().IndexOfColMajor(indices); + } + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h new file mode 100644 index 000000000..bbd5eb374 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h @@ -0,0 +1,167 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H +#define EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H + +namespace Eigen { + +/** \class TensorForcedEval + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +/// template class MakePointer_ is added to convert the host pointer to the device pointer. +/// It is added due to the fact that for our device compiler T* is not allowed. +/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer T. +/// This is done through our MakePointer_ class. By default the Type in the MakePointer_ is T* . +/// Therefore, by adding the default value, we managed to convert the type and it does not break any +/// existing code as its default value is T*. +namespace internal { +template class MakePointer_> +struct traits > +{ + // Type promotion to handle the case where the types of the lhs and the rhs are different. + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename traits::StorageKind StorageKind; + typedef typename traits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; + + enum { + Flags = 0 + }; + template struct MakePointer { + // Intermediate typedef to workaround MSVC issue. + typedef MakePointer_ MakePointerT; + typedef typename MakePointerT::Type Type; + }; +}; + +template class MakePointer_> +struct eval, Eigen::Dense> +{ + typedef const TensorForcedEvalOp& type; +}; + +template class MakePointer_> +struct nested, 1, typename eval >::type> +{ + typedef TensorForcedEvalOp type; +}; + +} // end namespace internal + + + +template class MakePointer_> +class TensorForcedEvalOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorForcedEvalOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; +}; + + +template class MakePointer_> +struct TensorEvaluator, Device> +{ + typedef TensorForcedEvalOp XprType; + typedef typename ArgType::Scalar Scalar; + typedef typename TensorEvaluator::Dimensions Dimensions; + typedef typename XprType::Index Index; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = (PacketSize > 1), + Layout = TensorEvaluator::Layout, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) + /// op_ is used for sycl + : m_impl(op.expression(), device), m_op(op.expression()), m_device(device), m_buffer(NULL) + { } + + EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + const Index numValues = internal::array_prod(m_impl.dimensions()); + m_buffer = (CoeffReturnType*)m_device.allocate(numValues * sizeof(CoeffReturnType)); + // Should initialize the memory in case we're dealing with non POD types. + if (NumTraits::RequireInitialization) { + for (Index i = 0; i < numValues; ++i) { + new(m_buffer+i) CoeffReturnType(); + } + } + typedef TensorEvalToOp< const typename internal::remove_const::type > EvalTo; + EvalTo evalToTmp(m_buffer, m_op); + const bool PacketAccess = internal::IsVectorizable::value; + internal::TensorExecutor::type, PacketAccess>::run(evalToTmp, m_device); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_device.deallocate(m_buffer); + m_buffer = NULL; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_buffer[index]; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return internal::ploadt(m_buffer + index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC typename MakePointer::Type data() const { return m_buffer; } + + /// required by sycl in order to extract the sycl accessor + const TensorEvaluator& impl() { return m_impl; } + /// used by sycl in order to build the sycl buffer + const Device& device() const{return m_device;} + private: + TensorEvaluator m_impl; + const ArgType m_op; + const Device& m_device; + typename MakePointer::Type m_buffer; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h new file mode 100644 index 000000000..52b803d7f --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h @@ -0,0 +1,109 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H + +namespace Eigen { + +// MakePointer class is used as a container of the adress space of the pointer +// on the host and on the device. From the host side it generates the T* pointer +// and when EIGEN_USE_SYCL is used it construct a buffer with a map_allocator to +// T* m_data on the host. It is always called on the device. +// Specialisation of MakePointer class for creating the sycl buffer with +// map_allocator. +template struct MakePointer { + typedef T* Type; +}; + +template class MakePointer_ = MakePointer> class TensorMap; +template class Tensor; +template class TensorFixedSize; +template class TensorRef; +template class TensorBase; + +template class TensorCwiseNullaryOp; +template class TensorCwiseUnaryOp; +template class TensorCwiseBinaryOp; +template class TensorCwiseTernaryOp; +template class TensorSelectOp; +template class MakePointer_ = MakePointer > class TensorReductionOp; +template class TensorIndexTupleOp; +template class TensorTupleReducerOp; +template class TensorConcatenationOp; +template class TensorContractionOp; +template class TensorConversionOp; +template class TensorConvolutionOp; +template class TensorFFTOp; +template class TensorPatchOp; +template class TensorImagePatchOp; +template class TensorVolumePatchOp; +template class TensorBroadcastingOp; +template class TensorChippingOp; +template class TensorReshapingOp; +template class TensorLayoutSwapOp; +template class TensorSlicingOp; +template class TensorReverseOp; +template class TensorPaddingOp; +template class TensorShufflingOp; +template class TensorStridingOp; +template class TensorStridingSlicingOp; +template class TensorInflationOp; +template class TensorGeneratorOp; +template class TensorAssignOp; +template class TensorScanOp; + +template class TensorCustomUnaryOp; +template class TensorCustomBinaryOp; + +template class MakePointer_ = MakePointer> class TensorEvalToOp; +template class MakePointer_ = MakePointer> class TensorForcedEvalOp; + +template class TensorDevice; +template struct TensorEvaluator; + +struct DefaultDevice; +struct ThreadPoolDevice; +struct GpuDevice; +struct SyclDevice; + +enum FFTResultType { + RealPart = 0, + ImagPart = 1, + BothParts = 2 +}; + +enum FFTDirection { + FFT_FORWARD = 0, + FFT_REVERSE = 1 +}; + + +namespace internal { + +template +struct IsVectorizable { + static const bool value = TensorEvaluator::PacketAccess; +}; + +template +struct IsVectorizable { + static const bool value = TensorEvaluator::PacketAccess && + TensorEvaluator::IsAligned; +}; + +template ::value> +class TensorExecutor; + +} // end namespace internal + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h new file mode 100644 index 000000000..d73f6dc68 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h @@ -0,0 +1,489 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H +#define EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H + +namespace Eigen { +namespace internal { + + +/** \internal + * \brief Template functor to compute the modulo between an array and a scalar. + */ +template +struct scalar_mod_op { + EIGEN_DEVICE_FUNC scalar_mod_op(const Scalar& divisor) : m_divisor(divisor) {} + EIGEN_DEVICE_FUNC inline Scalar operator() (const Scalar& a) const { return a % m_divisor; } + const Scalar m_divisor; +}; +template +struct functor_traits > +{ enum { Cost = scalar_div_cost::value, PacketAccess = false }; }; + + +/** \internal + * \brief Template functor to compute the modulo between 2 arrays. + */ +template +struct scalar_mod2_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_mod2_op); + EIGEN_DEVICE_FUNC inline Scalar operator() (const Scalar& a, const Scalar& b) const { return a % b; } +}; +template +struct functor_traits > +{ enum { Cost = scalar_div_cost::value, PacketAccess = false }; }; + +template +struct scalar_fmod_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_fmod_op); + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar + operator()(const Scalar& a, const Scalar& b) const { + return numext::fmod(a, b); + } +}; +template +struct functor_traits > { + enum { Cost = 13, // Reciprocal throughput of FPREM on Haswell. + PacketAccess = false }; +}; + + +/** \internal + * \brief Template functor to compute the sigmoid of a scalar + * \sa class CwiseUnaryOp, ArrayBase::sigmoid() + */ +template +struct scalar_sigmoid_op { + EIGEN_EMPTY_STRUCT_CTOR(scalar_sigmoid_op) + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator()(const T& x) const { + const T one = T(1); + return one / (one + numext::exp(-x)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(const Packet& x) const { + const Packet one = pset1(T(1)); + return pdiv(one, padd(one, pexp(pnegate(x)))); + } +}; + +template +struct functor_traits > { + enum { + Cost = NumTraits::AddCost * 2 + NumTraits::MulCost * 6, + PacketAccess = packet_traits::HasAdd && packet_traits::HasDiv && + packet_traits::HasNegate && packet_traits::HasExp + }; +}; + + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + +// Standard reduction functors +template struct SumReducer +{ + static const bool PacketAccess = packet_traits::HasAdd; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + internal::scalar_sum_op sum_op; + *accum = sum_op(*accum, t); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = padd(*accum, p); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(0); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_sum_op sum_op; + return sum_op(saccum, predux(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasAdd + }; +}; + + +template struct MeanReducer +{ + static const bool PacketAccess = packet_traits::HasAdd && !NumTraits::IsInteger; + static const bool IsStateful = true; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + MeanReducer() : scalarCount_(0), packetCount_(0) { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) { + internal::scalar_sum_op sum_op; + *accum = sum_op(*accum, t); + scalarCount_++; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) { + (*accum) = padd(*accum, p); + packetCount_++; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(0); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum / scalarCount_; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return pdiv(vaccum, pset1(packetCount_)); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_sum_op sum_op; + return sum_op(saccum, predux(vaccum)) / (scalarCount_ + packetCount_ * unpacket_traits::size); + } + + protected: + DenseIndex scalarCount_; + DenseIndex packetCount_; +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasAdd + }; +}; + + +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::lowest(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return -Eigen::NumTraits::infinity(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::highest(); + } +}; +template +struct MinMaxBottomValue { + EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() { + return Eigen::NumTraits::infinity(); + } +}; + + +template struct MaxReducer +{ + static const bool PacketAccess = packet_traits::HasMax; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t > *accum) { *accum = t; } + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmax(*accum, p); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return MinMaxBottomValue::IsInteger>::bottom_value(); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + return numext::maxi(saccum, predux_max(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasMax + }; +}; + + +template struct MinReducer +{ + static const bool PacketAccess = packet_traits::HasMin; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t < *accum) { *accum = t; } + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmin(*accum, p); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return MinMaxBottomValue::IsInteger>::bottom_value(); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + return numext::mini(saccum, predux_min(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = PacketType::HasMin + }; +}; + + +template struct ProdReducer +{ + static const bool PacketAccess = packet_traits::HasMul; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + internal::scalar_product_op prod_op; + (*accum) = prod_op(*accum, t); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const { + (*accum) = pmul(*accum, p); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + internal::scalar_cast_op conv; + return conv(1); + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const { + return pset1(initialize()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const { + return accum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const { + return vaccum; + } + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const { + internal::scalar_product_op prod_op; + return prod_op(saccum, predux_mul(vaccum)); + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::MulCost, + PacketAccess = PacketType::HasMul + }; +}; + + +struct AndReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const { + *accum = *accum && t; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const { + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const { + return accum; + } +}; + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + + +struct OrReducer { + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const { + *accum = *accum || t; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const { + return false; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const { + return accum; + } +}; + +template +struct reducer_traits { + enum { + Cost = 1, + PacketAccess = false + }; +}; + + +// Argmin/Argmax reducers +template struct ArgMaxTupleReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const { + if (t.second > accum->second) { *accum = t; } + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return T(0, NumTraits::lowest()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const { + return accum; + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + + +template struct ArgMinTupleReducer +{ + static const bool PacketAccess = false; + static const bool IsStateful = false; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T& t, T* accum) const { + if (t.second < accum->second) { *accum = t; } + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const { + return T(0, NumTraits::highest()); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const { + return accum; + } +}; + +template +struct reducer_traits, Device> { + enum { + Cost = NumTraits::AddCost, + PacketAccess = false + }; +}; + + +template +class GaussianGenerator { + public: + static const bool PacketAccess = false; + + EIGEN_DEVICE_FUNC GaussianGenerator(const array& means, + const array& std_devs) + : m_means(means) + { + for (size_t i = 0; i < NumDims; ++i) { + m_two_sigmas[i] = std_devs[i] * std_devs[i] * 2; + } + } + + EIGEN_DEVICE_FUNC T operator()(const array& coordinates) const { + T tmp = T(0); + for (size_t i = 0; i < NumDims; ++i) { + T offset = coordinates[i] - m_means[i]; + tmp += offset * offset / m_two_sigmas[i]; + } + return numext::exp(-tmp); + } + + private: + array m_means; + array m_two_sigmas; +}; + +template +struct functor_traits > { + enum { + Cost = NumDims * (2 * NumTraits::AddCost + NumTraits::MulCost + + functor_traits >::Cost) + + functor_traits >::Cost, + PacketAccess = GaussianGenerator::PacketAccess + }; +}; + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h new file mode 100644 index 000000000..eb1d4934e --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h @@ -0,0 +1,185 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H +#define EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H + +namespace Eigen { + +/** \class TensorGenerator + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor generator class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorGeneratorOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorGeneratorOp type; +}; + +} // end namespace internal + + + +template +class TensorGeneratorOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorGeneratorOp(const XprType& expr, const Generator& generator) + : m_xpr(expr), m_generator(generator) {} + + EIGEN_DEVICE_FUNC + const Generator& generator() const { return m_generator; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Generator m_generator; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorGeneratorOp XprType; + typedef typename XprType::Index Index; + typedef typename TensorEvaluator::Dimensions Dimensions; + static const int NumDims = internal::array_size::value; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + enum { + IsAligned = false, + PacketAccess = (internal::unpacket_traits::size > 1), + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_generator(op.generator()) + { + TensorEvaluator impl(op.expression(), device); + m_dimensions = impl.dimensions(); + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_strides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_strides[NumDims - 1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + array coords; + extract_coordinates(index, coords); + return m_generator(coords); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+packetSize-1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[packetSize]; + for (int i = 0; i < packetSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool) const { + // TODO(rmlarsen): This is just a placeholder. Define interface to make + // generators return their cost. + return TensorOpCost(0, 0, TensorOpCost::AddCost() + + TensorOpCost::MulCost()); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void extract_coordinates(Index index, array& coords) const { + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_strides[i]; + index -= idx * m_strides[i]; + coords[i] = idx; + } + coords[0] = index; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_strides[i]; + index -= idx * m_strides[i]; + coords[i] = idx; + } + coords[NumDims-1] = index; + } + } + + Dimensions m_dimensions; + array m_strides; + Generator m_generator; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h new file mode 100644 index 000000000..665b861cf --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h @@ -0,0 +1,33 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Eugene Brevdo +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H +#define EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H + +namespace Eigen { + +/** \cpp11 \returns an expression of the coefficient-wise betainc(\a x, \a a, \a b) to the given tensors. + * + * This function computes the regularized incomplete beta function (integral). + * + */ +template +EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const + TensorCwiseTernaryOp, + const ADerived, const BDerived, const XDerived> + betainc(const ADerived& a, const BDerived& b, const XDerived& x) { + return TensorCwiseTernaryOp< + internal::scalar_betainc_op, const ADerived, + const BDerived, const XDerived>( + a, b, x, internal::scalar_betainc_op()); +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h new file mode 100644 index 000000000..a901c5dd4 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h @@ -0,0 +1,79 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_IO_H +#define EIGEN_CXX11_TENSOR_TENSOR_IO_H + +namespace Eigen { + +namespace internal { + +// Print the tensor as a 2d matrix +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + typedef typename internal::remove_const::type Scalar; + typedef typename Tensor::Index Index; + const Index total_size = internal::array_prod(tensor.dimensions()); + if (total_size > 0) { + const Index first_dim = Eigen::internal::array_get<0>(tensor.dimensions()); + static const int layout = Tensor::Layout; + Map > matrix(const_cast(tensor.data()), first_dim, total_size/first_dim); + os << matrix; + } + } +}; + + +// Print the tensor as a vector +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + typedef typename internal::remove_const::type Scalar; + typedef typename Tensor::Index Index; + const Index total_size = internal::array_prod(tensor.dimensions()); + if (total_size > 0) { + Map > array(const_cast(tensor.data()), total_size); + os << array; + } + } +}; + + +// Print the tensor as a scalar +template +struct TensorPrinter { + static void run (std::ostream& os, const Tensor& tensor) { + os << tensor.coeff(0); + } +}; +} + +template +std::ostream& operator << (std::ostream& os, const TensorBase& expr) { + typedef TensorEvaluator, DefaultDevice> Evaluator; + typedef typename Evaluator::Dimensions Dimensions; + + // Evaluate the expression if needed + TensorForcedEvalOp eval = expr.eval(); + Evaluator tensor(eval, DefaultDevice()); + tensor.evalSubExprsIfNeeded(NULL); + + // Print the result + static const int rank = internal::array_size::value; + internal::TensorPrinter::run(os, tensor); + + // Cleanup. + tensor.cleanup(); + return os; +} + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_IO_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h new file mode 100644 index 000000000..566856ed2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h @@ -0,0 +1,509 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H +#define EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H + +namespace Eigen { + +/** \class TensorImagePatch + * \ingroup CXX11_Tensor_Module + * + * \brief Patch extraction specialized for image processing. + * This assumes that the input has a least 3 dimensions ordered as follow: + * 1st dimension: channels (of size d) + * 2nd dimension: rows (of size r) + * 3rd dimension: columns (of size c) + * There can be additional dimensions such as time (for video) or batch (for + * bulk processing after the first 3. + * Calling the image patch code with patch_rows and patch_cols is equivalent + * to calling the regular patch extraction code with parameters d, patch_rows, + * patch_cols, and 1 for all the additional dimensions. + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename internal::remove_const::type Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions + 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorImagePatchOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorImagePatchOp type; +}; + +} // end namespace internal + +template +class TensorImagePatchOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols, + DenseIndex row_strides, DenseIndex col_strides, + DenseIndex in_row_strides, DenseIndex in_col_strides, + DenseIndex row_inflate_strides, DenseIndex col_inflate_strides, + PaddingType padding_type, Scalar padding_value) + : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols), + m_row_strides(row_strides), m_col_strides(col_strides), + m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides), + m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides), + m_padding_explicit(false), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0), + m_padding_type(padding_type), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols, + DenseIndex row_strides, DenseIndex col_strides, + DenseIndex in_row_strides, DenseIndex in_col_strides, + DenseIndex row_inflate_strides, DenseIndex col_inflate_strides, + DenseIndex padding_top, DenseIndex padding_bottom, + DenseIndex padding_left, DenseIndex padding_right, + Scalar padding_value) + : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols), + m_row_strides(row_strides), m_col_strides(col_strides), + m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides), + m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides), + m_padding_explicit(true), m_padding_top(padding_top), m_padding_bottom(padding_bottom), + m_padding_left(padding_left), m_padding_right(padding_right), + m_padding_type(PADDING_VALID), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC + DenseIndex patch_rows() const { return m_patch_rows; } + EIGEN_DEVICE_FUNC + DenseIndex patch_cols() const { return m_patch_cols; } + EIGEN_DEVICE_FUNC + DenseIndex row_strides() const { return m_row_strides; } + EIGEN_DEVICE_FUNC + DenseIndex col_strides() const { return m_col_strides; } + EIGEN_DEVICE_FUNC + DenseIndex in_row_strides() const { return m_in_row_strides; } + EIGEN_DEVICE_FUNC + DenseIndex in_col_strides() const { return m_in_col_strides; } + EIGEN_DEVICE_FUNC + DenseIndex row_inflate_strides() const { return m_row_inflate_strides; } + EIGEN_DEVICE_FUNC + DenseIndex col_inflate_strides() const { return m_col_inflate_strides; } + EIGEN_DEVICE_FUNC + bool padding_explicit() const { return m_padding_explicit; } + EIGEN_DEVICE_FUNC + DenseIndex padding_top() const { return m_padding_top; } + EIGEN_DEVICE_FUNC + DenseIndex padding_bottom() const { return m_padding_bottom; } + EIGEN_DEVICE_FUNC + DenseIndex padding_left() const { return m_padding_left; } + EIGEN_DEVICE_FUNC + DenseIndex padding_right() const { return m_padding_right; } + EIGEN_DEVICE_FUNC + PaddingType padding_type() const { return m_padding_type; } + EIGEN_DEVICE_FUNC + Scalar padding_value() const { return m_padding_value; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const DenseIndex m_patch_rows; + const DenseIndex m_patch_cols; + const DenseIndex m_row_strides; + const DenseIndex m_col_strides; + const DenseIndex m_in_row_strides; + const DenseIndex m_in_col_strides; + const DenseIndex m_row_inflate_strides; + const DenseIndex m_col_inflate_strides; + const bool m_padding_explicit; + const DenseIndex m_padding_top; + const DenseIndex m_padding_bottom; + const DenseIndex m_padding_left; + const DenseIndex m_padding_right; + const PaddingType m_padding_type; + const Scalar m_padding_value; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorImagePatchOp XprType; + typedef typename XprType::Index Index; + static const int NumInputDims = internal::array_size::Dimensions>::value; + static const int NumDims = NumInputDims + 1; + typedef DSizes Dimensions; + typedef typename internal::remove_const::type Scalar; + typedef TensorEvaluator, + Device> Self; + typedef TensorEvaluator Impl; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + EIGEN_STATIC_ASSERT((NumDims >= 4), YOU_MADE_A_PROGRAMMING_MISTAKE); + + m_paddingValue = op.padding_value(); + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + + // Caches a few variables. + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputDepth = input_dims[0]; + m_inputRows = input_dims[1]; + m_inputCols = input_dims[2]; + } else { + m_inputDepth = input_dims[NumInputDims-1]; + m_inputRows = input_dims[NumInputDims-2]; + m_inputCols = input_dims[NumInputDims-3]; + } + + m_row_strides = op.row_strides(); + m_col_strides = op.col_strides(); + + // Input strides and effective input/patch size + m_in_row_strides = op.in_row_strides(); + m_in_col_strides = op.in_col_strides(); + m_row_inflate_strides = op.row_inflate_strides(); + m_col_inflate_strides = op.col_inflate_strides(); + // The "effective" input rows and input cols are the input rows and cols + // after inflating them with zeros. + // For examples, a 2x3 matrix with row_inflate_strides and + // col_inflate_strides of 2 comes from: + // A B C + // D E F + // + // to a matrix is 3 x 5: + // + // A . B . C + // . . . . . + // D . E . F + + m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1; + m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1; + m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1); + m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1); + + if (op.padding_explicit()) { + m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast(m_row_strides)); + m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast(m_col_strides)); + m_rowPaddingTop = op.padding_top(); + m_colPaddingLeft = op.padding_left(); + } else { + // Computing padding from the type + switch (op.padding_type()) { + case PADDING_VALID: + m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast(m_row_strides)); + m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast(m_col_strides)); + // Calculate the padding + m_rowPaddingTop = numext::maxi(0, ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2); + m_colPaddingLeft = numext::maxi(0, ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2); + break; + case PADDING_SAME: + m_outputRows = numext::ceil(m_input_rows_eff / static_cast(m_row_strides)); + m_outputCols = numext::ceil(m_input_cols_eff / static_cast(m_col_strides)); + // Calculate the padding + m_rowPaddingTop = ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2; + m_colPaddingLeft = ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2; + break; + default: + eigen_assert(false && "unexpected padding"); + } + } + eigen_assert(m_outputRows > 0); + eigen_assert(m_outputCols > 0); + + // Dimensions for result of extraction. + if (static_cast(Layout) == static_cast(ColMajor)) { + // ColMajor + // 0: depth + // 1: patch_rows + // 2: patch_cols + // 3: number of patches + // 4 and beyond: anything else (such as batch). + m_dimensions[0] = input_dims[0]; + m_dimensions[1] = op.patch_rows(); + m_dimensions[2] = op.patch_cols(); + m_dimensions[3] = m_outputRows * m_outputCols; + for (int i = 4; i < NumDims; ++i) { + m_dimensions[i] = input_dims[i-1]; + } + } else { + // RowMajor + // NumDims-1: depth + // NumDims-2: patch_rows + // NumDims-3: patch_cols + // NumDims-4: number of patches + // NumDims-5 and beyond: anything else (such as batch). + m_dimensions[NumDims-1] = input_dims[NumInputDims-1]; + m_dimensions[NumDims-2] = op.patch_rows(); + m_dimensions[NumDims-3] = op.patch_cols(); + m_dimensions[NumDims-4] = m_outputRows * m_outputCols; + for (int i = NumDims-5; i >= 0; --i) { + m_dimensions[i] = input_dims[i]; + } + } + + // Strides for moving the patch in various dimensions. + if (static_cast(Layout) == static_cast(ColMajor)) { + m_colStride = m_dimensions[1]; + m_patchStride = m_colStride * m_dimensions[2] * m_dimensions[0]; + m_otherStride = m_patchStride * m_dimensions[3]; + } else { + m_colStride = m_dimensions[NumDims-2]; + m_patchStride = m_colStride * m_dimensions[NumDims-3] * m_dimensions[NumDims-1]; + m_otherStride = m_patchStride * m_dimensions[NumDims-4]; + } + + // Strides for navigating through the input tensor. + m_rowInputStride = m_inputDepth; + m_colInputStride = m_inputDepth * m_inputRows; + m_patchInputStride = m_inputDepth * m_inputRows * m_inputCols; + + // Fast representations of different variables. + m_fastOtherStride = internal::TensorIntDivisor(m_otherStride); + m_fastPatchStride = internal::TensorIntDivisor(m_patchStride); + m_fastColStride = internal::TensorIntDivisor(m_colStride); + m_fastInflateRowStride = internal::TensorIntDivisor(m_row_inflate_strides); + m_fastInflateColStride = internal::TensorIntDivisor(m_col_inflate_strides); + m_fastInputColsEff = internal::TensorIntDivisor(m_input_cols_eff); + + // Number of patches in the width dimension. + m_fastOutputRows = internal::TensorIntDivisor(m_outputRows); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_fastOutputDepth = internal::TensorIntDivisor(m_dimensions[0]); + } else { + m_fastOutputDepth = internal::TensorIntDivisor(m_dimensions[NumDims-1]); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + // Patch index corresponding to the passed in index. + const Index patchIndex = index / m_fastPatchStride; + // Find the offset of the element wrt the location of the first element. + const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth; + + // Other ways to index this element. + const Index otherIndex = (NumDims == 4) ? 0 : index / m_fastOtherStride; + const Index patch2DIndex = (NumDims == 4) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride; + + // Calculate col index in the input original tensor. + const Index colIndex = patch2DIndex / m_fastOutputRows; + const Index colOffset = patchOffset / m_fastColStride; + const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft; + const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInflateColStride) : 0); + if (inputCol < 0 || inputCol >= m_input_cols_eff || + ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) { + return Scalar(m_paddingValue); + } + + // Calculate row index in the original input tensor. + const Index rowIndex = patch2DIndex - colIndex * m_outputRows; + const Index rowOffset = patchOffset - colOffset * m_colStride; + const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop; + const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInflateRowStride) : 0); + if (inputRow < 0 || inputRow >= m_input_rows_eff || + ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) { + return Scalar(m_paddingValue); + } + + const int depth_index = static_cast(Layout) == static_cast(ColMajor) ? 0 : NumDims - 1; + const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index]; + + const Index inputIndex = depth + origInputRow * m_rowInputStride + origInputCol * m_colInputStride + otherIndex * m_patchInputStride; + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1) { + return packetWithPossibleZero(index); + } + + const Index indices[2] = {index, index + PacketSize - 1}; + const Index patchIndex = indices[0] / m_fastPatchStride; + if (patchIndex != indices[1] / m_fastPatchStride) { + return packetWithPossibleZero(index); + } + const Index otherIndex = (NumDims == 4) ? 0 : indices[0] / m_fastOtherStride; + eigen_assert(otherIndex == indices[1] / m_fastOtherStride); + + // Find the offset of the element wrt the location of the first element. + const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth, + (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth}; + + const Index patch2DIndex = (NumDims == 4) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride; + eigen_assert(patch2DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride); + + const Index colIndex = patch2DIndex / m_fastOutputRows; + const Index colOffsets[2] = {patchOffsets[0] / m_fastColStride, patchOffsets[1] / m_fastColStride}; + + // Calculate col indices in the original input tensor. + const Index inputCols[2] = {colIndex * m_col_strides + colOffsets[0] - + m_colPaddingLeft, colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft}; + if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) { + return internal::pset1(Scalar(m_paddingValue)); + } + + if (inputCols[0] == inputCols[1]) { + const Index rowIndex = patch2DIndex - colIndex * m_outputRows; + const Index rowOffsets[2] = {patchOffsets[0] - colOffsets[0]*m_colStride, patchOffsets[1] - colOffsets[1]*m_colStride}; + eigen_assert(rowOffsets[0] <= rowOffsets[1]); + // Calculate col indices in the original input tensor. + const Index inputRows[2] = {rowIndex * m_row_strides + rowOffsets[0] - + m_rowPaddingTop, rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop}; + + if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) { + return internal::pset1(Scalar(m_paddingValue)); + } + + if (inputRows[0] >= 0 && inputRows[1] < m_inputRows) { + // no padding + const int depth_index = static_cast(Layout) == static_cast(ColMajor) ? 0 : NumDims - 1; + const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index]; + const Index inputIndex = depth + inputRows[0] * m_rowInputStride + inputCols[0] * m_colInputStride + otherIndex * m_patchInputStride; + return m_impl.template packet(inputIndex); + } + } + + return packetWithPossibleZero(index); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + const TensorEvaluator& impl() const { return m_impl; } + + Index rowPaddingTop() const { return m_rowPaddingTop; } + Index colPaddingLeft() const { return m_colPaddingLeft; } + Index outputRows() const { return m_outputRows; } + Index outputCols() const { return m_outputCols; } + Index userRowStride() const { return m_row_strides; } + Index userColStride() const { return m_col_strides; } + Index userInRowStride() const { return m_in_row_strides; } + Index userInColStride() const { return m_in_col_strides; } + Index rowInflateStride() const { return m_row_inflate_strides; } + Index colInflateStride() const { return m_col_inflate_strides; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost + costPerCoeff(bool vectorized) const { + // We conservatively estimate the cost for the code path where the computed + // index is inside the original image and + // TensorEvaluator::CoordAccess is false. + const double compute_cost = 3 * TensorOpCost::DivCost() + + 6 * TensorOpCost::MulCost() + + 8 * TensorOpCost::MulCost(); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const + { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + Dimensions m_dimensions; + + Index m_otherStride; + Index m_patchStride; + Index m_colStride; + Index m_row_strides; + Index m_col_strides; + + Index m_in_row_strides; + Index m_in_col_strides; + Index m_row_inflate_strides; + Index m_col_inflate_strides; + + Index m_input_rows_eff; + Index m_input_cols_eff; + Index m_patch_rows_eff; + Index m_patch_cols_eff; + + internal::TensorIntDivisor m_fastOtherStride; + internal::TensorIntDivisor m_fastPatchStride; + internal::TensorIntDivisor m_fastColStride; + internal::TensorIntDivisor m_fastInflateRowStride; + internal::TensorIntDivisor m_fastInflateColStride; + internal::TensorIntDivisor m_fastInputColsEff; + + Index m_rowInputStride; + Index m_colInputStride; + Index m_patchInputStride; + + Index m_inputDepth; + Index m_inputRows; + Index m_inputCols; + + Index m_outputRows; + Index m_outputCols; + + Index m_rowPaddingTop; + Index m_colPaddingLeft; + + internal::TensorIntDivisor m_fastOutputRows; + internal::TensorIntDivisor m_fastOutputDepth; + + Scalar m_paddingValue; + + TensorEvaluator m_impl; +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h new file mode 100644 index 000000000..3209fecd3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h @@ -0,0 +1,725 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H +#define EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H + + +#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES + +#define EIGEN_HAS_INDEX_LIST + +namespace Eigen { + +/** \internal + * + * \class TensorIndexList + * \ingroup CXX11_Tensor_Module + * + * \brief Set of classes used to encode a set of Tensor dimensions/indices. + * + * The indices in the list can be known at compile time or at runtime. A mix + * of static and dynamic indices can also be provided if needed. The tensor + * code will attempt to take advantage of the indices that are known at + * compile time to optimize the code it generates. + * + * This functionality requires a c++11 compliant compiler. If your compiler + * is older you need to use arrays of indices instead. + * + * Several examples are provided in the cxx11_tensor_index_list.cpp file. + * + * \sa Tensor + */ + +template +struct type2index { + static const DenseIndex value = n; + EIGEN_DEVICE_FUNC constexpr operator DenseIndex() const { return n; } + EIGEN_DEVICE_FUNC void set(DenseIndex val) { + eigen_assert(val == n); + } +}; + +// This can be used with IndexPairList to get compile-time constant pairs, +// such as IndexPairList, type2indexpair<3,4>>(). +template +struct type2indexpair { + static const DenseIndex first = f; + static const DenseIndex second = s; + + constexpr EIGEN_DEVICE_FUNC operator IndexPair() const { + return IndexPair(f, s); + } + + EIGEN_DEVICE_FUNC void set(const IndexPair& val) { + eigen_assert(val.first == f); + eigen_assert(val.second == s); + } +}; + + +template struct NumTraits > +{ + typedef DenseIndex Real; + enum { + IsComplex = 0, + RequireInitialization = false, + ReadCost = 1, + AddCost = 1, + MulCost = 1 + }; + + EIGEN_DEVICE_FUNC static inline Real epsilon() { return 0; } + EIGEN_DEVICE_FUNC static inline Real dummy_precision() { return 0; } + EIGEN_DEVICE_FUNC static inline Real highest() { return n; } + EIGEN_DEVICE_FUNC static inline Real lowest() { return n; } +}; + +namespace internal { +template +EIGEN_DEVICE_FUNC void update_value(T& val, DenseIndex new_val) { + val = new_val; +} +template +EIGEN_DEVICE_FUNC void update_value(type2index& val, DenseIndex new_val) { + val.set(new_val); +} + +template +EIGEN_DEVICE_FUNC void update_value(T& val, IndexPair new_val) { + val = new_val; +} +template +EIGEN_DEVICE_FUNC void update_value(type2indexpair& val, IndexPair new_val) { + val.set(new_val); +} + + +template +struct is_compile_time_constant { + static constexpr bool value = false; +}; + +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; + +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; +template +struct is_compile_time_constant& > { + static constexpr bool value = true; +}; + + +template +struct IndexTuple; + +template +struct IndexTuple { + EIGEN_DEVICE_FUNC constexpr IndexTuple() : head(), others() { } + EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v, const O... o) : head(v), others(o...) { } + + constexpr static int count = 1 + sizeof...(O); + T head; + IndexTuple others; + typedef T Head; + typedef IndexTuple Other; +}; + +template + struct IndexTuple { + EIGEN_DEVICE_FUNC constexpr IndexTuple() : head() { } + EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v) : head(v) { } + + constexpr static int count = 1; + T head; + typedef T Head; +}; + + +template +struct IndexTupleExtractor; + +template +struct IndexTupleExtractor { + + typedef typename IndexTupleExtractor::ValType ValType; + + EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple& val) { + return IndexTupleExtractor::get_val(val.others); + } + + EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple& val) { + return IndexTupleExtractor::get_val(val.others); + } + template + EIGEN_DEVICE_FUNC static void set_val(IndexTuple& val, V& new_val) { + IndexTupleExtractor::set_val(val.others, new_val); + } + +}; + +template + struct IndexTupleExtractor<0, T, O...> { + + typedef T ValType; + + EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple& val) { + return val.head; + } + EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple& val) { + return val.head; + } + template + EIGEN_DEVICE_FUNC static void set_val(IndexTuple& val, V& new_val) { + val.head = new_val; + } +}; + + + +template +EIGEN_DEVICE_FUNC constexpr typename IndexTupleExtractor::ValType& array_get(IndexTuple& tuple) { + return IndexTupleExtractor::get_val(tuple); +} +template +EIGEN_DEVICE_FUNC constexpr const typename IndexTupleExtractor::ValType& array_get(const IndexTuple& tuple) { + return IndexTupleExtractor::get_val(tuple); +} +template + struct array_size > { + static const size_t value = IndexTuple::count; +}; +template + struct array_size > { + static const size_t value = IndexTuple::count; +}; + + + + +template +struct tuple_coeff { + template + EIGEN_DEVICE_FUNC static constexpr ValueT get(const DenseIndex i, const IndexTuple& t) { + // return array_get(t) * (i == Idx) + tuple_coeff::get(i, t) * (i != Idx); + return (i == Idx ? array_get(t) : tuple_coeff::get(i, t)); + } + template + EIGEN_DEVICE_FUNC static void set(const DenseIndex i, IndexTuple& t, const ValueT& value) { + if (i == Idx) { + update_value(array_get(t), value); + } else { + tuple_coeff::set(i, t, value); + } + } + + template + EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const DenseIndex i, const IndexTuple& t) { + return ((i == Idx) & is_compile_time_constant::ValType>::value) || + tuple_coeff::value_known_statically(i, t); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple& t) { + return is_compile_time_constant::ValType>::value && + tuple_coeff::values_up_to_known_statically(t); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple& t) { + return is_compile_time_constant::ValType>::value && + is_compile_time_constant::ValType>::value && + array_get(t) > array_get(t) && + tuple_coeff::values_up_to_statically_known_to_increase(t); + } +}; + +template +struct tuple_coeff<0, ValueT> { + template + EIGEN_DEVICE_FUNC static constexpr ValueT get(const DenseIndex /*i*/, const IndexTuple& t) { + // eigen_assert (i == 0); // gcc fails to compile assertions in constexpr + return array_get<0>(t)/* * (i == 0)*/; + } + template + EIGEN_DEVICE_FUNC static void set(const DenseIndex i, IndexTuple& t, const ValueT value) { + eigen_assert (i == 0); + update_value(array_get<0>(t), value); + } + template + EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const DenseIndex i, const IndexTuple&) { + return is_compile_time_constant::ValType>::value & (i == 0); + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple&) { + return is_compile_time_constant::ValType>::value; + } + + template + EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple&) { + return true; + } +}; +} // namespace internal + + + +template +struct IndexList : internal::IndexTuple { + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr DenseIndex operator[] (const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr DenseIndex get(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const DenseIndex i, const DenseIndex value) { + return internal::tuple_coeff >::value-1, DenseIndex>::set(i, *this, value); + } + + EIGEN_DEVICE_FUNC constexpr IndexList(const internal::IndexTuple& other) : internal::IndexTuple(other) { } + EIGEN_DEVICE_FUNC constexpr IndexList(FirstType& first, OtherTypes... other) : internal::IndexTuple(first, other...) { } + EIGEN_DEVICE_FUNC constexpr IndexList() : internal::IndexTuple() { } + + EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::value_known_statically(i, *this); + } + EIGEN_DEVICE_FUNC constexpr bool all_values_known_statically() const { + return internal::tuple_coeff >::value-1, DenseIndex>::values_up_to_known_statically(*this); + } + + EIGEN_DEVICE_FUNC constexpr bool values_statically_known_to_increase() const { + return internal::tuple_coeff >::value-1, DenseIndex>::values_up_to_statically_known_to_increase(*this); + } +}; + + +template +constexpr IndexList make_index_list(FirstType val1, OtherTypes... other_vals) { + return IndexList(val1, other_vals...); +} + + +template +struct IndexPairList : internal::IndexTuple { + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr IndexPair operator[] (const DenseIndex i) const { + return internal::tuple_coeff >::value-1, IndexPair>::get(i, *this); + } + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const DenseIndex i, const IndexPair value) { + return internal::tuple_coeff>::value-1, IndexPair >::set(i, *this, value); + } + + EIGEN_DEVICE_FUNC constexpr IndexPairList(const internal::IndexTuple& other) : internal::IndexTuple(other) { } + EIGEN_DEVICE_FUNC constexpr IndexPairList() : internal::IndexTuple() { } + + EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const DenseIndex i) const { + return internal::tuple_coeff >::value-1, DenseIndex>::value_known_statically(i, *this); + } +}; + +namespace internal { + +template size_t array_prod(const IndexList& sizes) { + size_t result = 1; + for (int i = 0; i < array_size >::value; ++i) { + result *= sizes[i]; + } + return result; +} + +template struct array_size > { + static const size_t value = array_size >::value; +}; +template struct array_size > { + static const size_t value = array_size >::value; +}; + +template struct array_size > { + static const size_t value = std::tuple_size >::value; +}; +template struct array_size > { + static const size_t value = std::tuple_size >::value; +}; + +template EIGEN_DEVICE_FUNC constexpr DenseIndex array_get(IndexList& a) { + return IndexTupleExtractor::get_val(a); +} +template EIGEN_DEVICE_FUNC constexpr DenseIndex array_get(const IndexList& a) { + return IndexTupleExtractor::get_val(a); +} + +template +struct index_known_statically_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) { + return false; + } +}; + +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i) { + return IndexList().value_known_statically(i); + } +}; + +template +struct index_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i) { + return IndexList().value_known_statically(i); + } +}; + + +template +struct all_indices_known_statically_impl { + static constexpr bool run() { + return false; + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return IndexList().all_values_known_statically(); + } +}; + +template +struct all_indices_known_statically_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return IndexList().all_values_known_statically(); + } +}; + + +template +struct indices_statically_known_to_increase_impl { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return false; + } +}; + +template + struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return Eigen::IndexList().values_statically_known_to_increase(); + } +}; + +template + struct indices_statically_known_to_increase_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run() { + return Eigen::IndexList().values_statically_known_to_increase(); + } +}; + + +template +struct index_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) == value); + } +}; + +template +struct index_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) == value); + } +}; + + +template +struct index_statically_ne_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) != value); + } +}; + +template +struct index_statically_ne_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) != value); + } +}; + + +template +struct index_statically_gt_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) > value); + } +}; + +template +struct index_statically_gt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) > value); + } +}; + + + +template +struct index_statically_lt_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) < value); + } +}; + +template +struct index_statically_lt_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexList().value_known_statically(i) & + (IndexList().get(i) < value); + } +}; + + + +template +struct index_pair_first_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_first_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).first == value); + } +}; + +template +struct index_pair_first_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).first == value); + } +}; + + + +template +struct index_pair_second_statically_eq_impl { + EIGEN_DEVICE_FUNC static constexpr bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_second_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).second == value); + } +}; + +template +struct index_pair_second_statically_eq_impl > { + EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) { + return IndexPairList().value_known_statically(i) & + (IndexPairList().operator[](i).second == value); + } +}; + + +} // end namespace internal +} // end namespace Eigen + +#else + +namespace Eigen { +namespace internal { + +template +struct index_known_statically_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex) { + return false; + } +}; + +template +struct all_indices_known_statically_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return false; + } +}; + +template +struct indices_statically_known_to_increase_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() { + return false; + } +}; + +template +struct index_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_ne_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_gt_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_statically_lt_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_first_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + +template +struct index_pair_second_statically_eq_impl { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(DenseIndex, DenseIndex) { + return false; + } +}; + + + +} // end namespace internal +} // end namespace Eigen + +#endif + + +namespace Eigen { +namespace internal { +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_known_statically(DenseIndex i) { + return index_known_statically_impl::run(i); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool all_indices_known_statically() { + return all_indices_known_statically_impl::run(); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool indices_statically_known_to_increase() { + return indices_statically_known_to_increase_impl::run(); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_eq(DenseIndex i, DenseIndex value) { + return index_statically_eq_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_ne(DenseIndex i, DenseIndex value) { + return index_statically_ne_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_gt(DenseIndex i, DenseIndex value) { + return index_statically_gt_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_lt(DenseIndex i, DenseIndex value) { + return index_statically_lt_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_first_statically_eq(DenseIndex i, DenseIndex value) { + return index_pair_first_statically_eq_impl::run(i, value); +} + +template +static EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_second_statically_eq(DenseIndex i, DenseIndex value) { + return index_pair_second_statically_eq_impl::run(i, value); +} + +} // end namespace internal +} // end namespace Eigen + + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h new file mode 100644 index 000000000..f391fb9ee --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h @@ -0,0 +1,229 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Ke Yang +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H +#define EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H + +namespace Eigen { + +/** \class TensorInflation + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor inflation class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorInflationOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorInflationOp type; +}; + +} // end namespace internal + +template +class TensorInflationOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorInflationOp(const XprType& expr, const Strides& strides) + : m_xpr(expr), m_strides(strides) {} + + EIGEN_DEVICE_FUNC + const Strides& strides() const { return m_strides; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const Strides m_strides; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorInflationOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/ false, + PacketAccess = TensorEvaluator::PacketAccess, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_strides(op.strides()) + { + m_dimensions = m_impl.dimensions(); + // Expand each dimension to the inflated dimension. + for (int i = 0; i < NumDims; ++i) { + m_dimensions[i] = (m_dimensions[i] - 1) * op.strides()[i] + 1; + } + + // Remember the strides for fast division. + for (int i = 0; i < NumDims; ++i) { + m_fastStrides[i] = internal::TensorIntDivisor(m_strides[i]); + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_outputStrides[0] = 1; + m_inputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + } + } else { // RowMajor + m_outputStrides[NumDims-1] = 1; + m_inputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + // Computes the input index given the output index. Returns true if the output + // index doesn't fall into a hole. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool getInputIndex(Index index, Index* inputIndex) const + { + eigen_assert(index < dimensions().TotalSize()); + *inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (idx != idx / m_fastStrides[i] * m_strides[i]) { + return false; + } + *inputIndex += idx / m_strides[i] * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (index != index / m_fastStrides[0] * m_strides[0]) { + return false; + } + *inputIndex += index / m_strides[0]; + return true; + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i]; + if (idx != idx / m_fastStrides[i] * m_strides[i]) { + return false; + } + *inputIndex += idx / m_strides[i] * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (index != index / m_fastStrides[NumDims-1] * m_strides[NumDims-1]) { + return false; + } + *inputIndex += index / m_strides[NumDims - 1]; + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + Index inputIndex = 0; + if (getInputIndex(index, &inputIndex)) { + return m_impl.coeff(inputIndex); + } else { + return Scalar(0); + } + } + + // TODO(yangke): optimize this function so that we can detect and produce + // all-zero packets + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (3 * TensorOpCost::DivCost() + + 3 * TensorOpCost::MulCost() + + 2 * TensorOpCost::AddCost()); + const double input_size = m_impl.dimensions().TotalSize(); + const double output_size = m_dimensions.TotalSize(); + if (output_size == 0) + return TensorOpCost(); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(sizeof(CoeffReturnType) * input_size / output_size, 0, + compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Strides m_strides; + array, NumDims> m_fastStrides; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h new file mode 100644 index 000000000..33edc49e3 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h @@ -0,0 +1,82 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H +#define EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H + +#if EIGEN_HAS_VARIADIC_TEMPLATES + +#include + +namespace Eigen { + +/** \class TensorInitializer + * \ingroup CXX11_Tensor_Module + * + * \brief Helper template to initialize Tensors from std::initializer_lists. + */ +namespace internal { + +template +struct Initializer { + typedef std::initializer_list< + typename Initializer::InitList> InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>* indices, + const InitList& vals) { + int i = 0; + for (auto v : vals) { + (*indices)[traits::NumDimensions - N] = i++; + Initializer::run(tensor, indices, v); + } + } +}; + +template +struct Initializer { + typedef std::initializer_list::Scalar> InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>* indices, + const InitList& vals) { + int i = 0; + // There is likely a faster way to do that than iterating. + for (auto v : vals) { + (*indices)[traits::NumDimensions - 1] = i++; + tensor.coeffRef(*indices) = v; + } + } +}; + +template +struct Initializer { + typedef typename traits::Scalar InitList; + + static void run(TensorEvaluator& tensor, + Eigen::array::Index, traits::NumDimensions>*, + const InitList& v) { + tensor.coeffRef(0) = v; + } +}; + + +template +void initialize_tensor(TensorEvaluator& tensor, + const typename Initializer::NumDimensions>::InitList& vals) { + Eigen::array::Index, traits::NumDimensions> indices; + Initializer::NumDimensions>::run(tensor, &indices, vals); +} + +} // namespace internal +} // namespace Eigen + +#endif // EIGEN_HAS_VARIADIC_TEMPLATES + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h new file mode 100644 index 000000000..ede3939c2 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h @@ -0,0 +1,253 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H +#define EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H + + +namespace Eigen { + +/** \internal + * + * \class TensorIntDiv + * \ingroup CXX11_Tensor_Module + * + * \brief Fast integer division by a constant. + * + * See the paper from Granlund and Montgomery for explanation. + * (at http://dx.doi.org/10.1145/773473.178249) + * + * \sa Tensor + */ + +namespace internal { + +namespace { + + // Note: result is undefined if val == 0 + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + typename internal::enable_if::type count_leading_zeros(const T val) + { +#ifdef __CUDA_ARCH__ + return __clz(val); +#elif EIGEN_COMP_MSVC + unsigned long index; + _BitScanReverse(&index, val); + return 31 - index; +#else + EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE); + return __builtin_clz(static_cast(val)); +#endif + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE + typename internal::enable_if::type count_leading_zeros(const T val) + { +#ifdef __CUDA_ARCH__ + return __clzll(val); +#elif EIGEN_COMP_MSVC && EIGEN_ARCH_x86_64 + unsigned long index; + _BitScanReverse64(&index, val); + return 63 - index; +#elif EIGEN_COMP_MSVC + // MSVC's _BitScanReverse64 is not available for 32bits builds. + unsigned int lo = (unsigned int)(val&0xffffffff); + unsigned int hi = (unsigned int)((val>>32)&0xffffffff); + int n; + if(hi==0) + n = 32 + count_leading_zeros(lo); + else + n = count_leading_zeros(hi); + return n; +#else + EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE); + return __builtin_clzll(static_cast(val)); +#endif + } + + template + struct UnsignedTraits { + typedef typename conditional::type type; + }; + + template + struct DividerTraits { + typedef typename UnsignedTraits::type type; + static const int N = sizeof(T) * 8; + }; + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t muluh(const uint32_t a, const T b) { +#if defined(__CUDA_ARCH__) + return __umulhi(a, b); +#else + return (static_cast(a) * b) >> 32; +#endif + } + + template + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t muluh(const uint64_t a, const T b) { +#if defined(__CUDA_ARCH__) + return __umul64hi(a, b); +#elif defined(__SIZEOF_INT128__) + __uint128_t v = static_cast<__uint128_t>(a) * static_cast<__uint128_t>(b); + return static_cast(v >> 64); +#else + return (TensorUInt128, uint64_t>(a) * TensorUInt128, uint64_t>(b)).upper(); +#endif + } + + template + struct DividerHelper { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t computeMultiplier(const int log_div, const T divider) { + EIGEN_STATIC_ASSERT(N == 32, YOU_MADE_A_PROGRAMMING_MISTAKE); + return static_cast((static_cast(1) << (N+log_div)) / divider - (static_cast(1) << N) + 1); + } + }; + + template + struct DividerHelper<64, T> { + static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t computeMultiplier(const int log_div, const T divider) { +#if defined(__SIZEOF_INT128__) && !defined(__CUDA_ARCH__) + return static_cast((static_cast<__uint128_t>(1) << (64+log_div)) / static_cast<__uint128_t>(divider) - (static_cast<__uint128_t>(1) << 64) + 1); +#else + const uint64_t shift = 1ULL << log_div; + TensorUInt128 result = TensorUInt128 >(shift, 0) / TensorUInt128, uint64_t>(divider) + - TensorUInt128, static_val<0> >(1, 0) + + TensorUInt128, static_val<1> >(1); + return static_cast(result); +#endif + } + }; +} + + +template +struct TensorIntDivisor { + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() { + multiplier = 0; + shift1 = 0; + shift2 = 0; + } + + // Must have 0 < divider < 2^31. This is relaxed to + // 0 < divider < 2^63 when using 64-bit indices on platforms that support + // the __uint128_t type. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor(const T divider) { + const int N = DividerTraits::N; + eigen_assert(static_cast::type>(divider) < NumTraits::highest()/2); + eigen_assert(divider > 0); + + // fast ln2 + const int leading_zeros = count_leading_zeros(static_cast(divider)); + int log_div = N - leading_zeros; + // if divider is a power of two then log_div is 1 more than it should be. + if ((static_cast::type>(1) << (log_div-1)) == static_cast::type>(divider)) + log_div--; + + multiplier = DividerHelper::computeMultiplier(log_div, divider); + shift1 = log_div > 1 ? 1 : log_div; + shift2 = log_div > 1 ? log_div-1 : 0; + } + + // Must have 0 <= numerator. On platforms that dont support the __uint128_t + // type numerator should also be less than 2^32-1. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T divide(const T numerator) const { + eigen_assert(static_cast::type>(numerator) < NumTraits::highest()/2); + //eigen_assert(numerator >= 0); // this is implicitly asserted by the line above + + UnsignedType t1 = muluh(multiplier, numerator); + UnsignedType t = (static_cast(numerator) - t1) >> shift1; + return (t1 + t) >> shift2; + } + + private: + typedef typename DividerTraits::type UnsignedType; + UnsignedType multiplier; + int32_t shift1; + int32_t shift2; +}; + + +// Optimized version for signed 32 bit integers. +// Derived from Hacker's Delight. +// Only works for divisors strictly greater than one +template <> +class TensorIntDivisor { + public: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() { + magic = 0; + shift = 0; + } + // Must have 2 <= divider + EIGEN_DEVICE_FUNC TensorIntDivisor(int32_t divider) { + eigen_assert(divider >= 2); + calcMagic(divider); + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE int divide(const int32_t n) const { +#ifdef __CUDA_ARCH__ + return (__umulhi(magic, n) >> shift); +#else + uint64_t v = static_cast(magic) * static_cast(n); + return (static_cast(v >> 32) >> shift); +#endif + } + +private: + // Compute the magic numbers. See Hacker's Delight section 10 for an in + // depth explanation. + EIGEN_DEVICE_FUNC void calcMagic(int32_t d) { + const unsigned two31 = 0x80000000; // 2**31. + unsigned ad = d; + unsigned t = two31 + (ad >> 31); + unsigned anc = t - 1 - t%ad; // Absolute value of nc. + int p = 31; // Init. p. + unsigned q1 = two31/anc; // Init. q1 = 2**p/|nc|. + unsigned r1 = two31 - q1*anc; // Init. r1 = rem(2**p, |nc|). + unsigned q2 = two31/ad; // Init. q2 = 2**p/|d|. + unsigned r2 = two31 - q2*ad; // Init. r2 = rem(2**p, |d|). + unsigned delta = 0; + do { + p = p + 1; + q1 = 2*q1; // Update q1 = 2**p/|nc|. + r1 = 2*r1; // Update r1 = rem(2**p, |nc|). + if (r1 >= anc) { // (Must be an unsigned + q1 = q1 + 1; // comparison here). + r1 = r1 - anc;} + q2 = 2*q2; // Update q2 = 2**p/|d|. + r2 = 2*r2; // Update r2 = rem(2**p, |d|). + if (r2 >= ad) { // (Must be an unsigned + q2 = q2 + 1; // comparison here). + r2 = r2 - ad;} + delta = ad - r2; + } while (q1 < delta || (q1 == delta && r1 == 0)); + + magic = (unsigned)(q2 + 1); + shift = p - 32; + } + + uint32_t magic; + int32_t shift; +}; + + +template +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator / (const T& numerator, const TensorIntDivisor& divisor) { + return divisor.divide(numerator); +} + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h new file mode 100644 index 000000000..cd0109ef4 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h @@ -0,0 +1,209 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H +#define EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H + +namespace Eigen { + +/** \class TensorLayoutSwap + * \ingroup CXX11_Tensor_Module + * + * \brief Swap the layout from col-major to row-major, or row-major + * to col-major, and invert the order of the dimensions. + * + * Beware: the dimensions are reversed by this operation. If you want to + * preserve the ordering of the dimensions, you need to combine this + * operation with a shuffle. + * + * \example: + * Tensor input(2, 4); + * Tensor output = input.swap_layout(); + * eigen_assert(output.dimension(0) == 4); + * eigen_assert(output.dimension(1) == 2); + * + * array shuffle(1, 0); + * output = input.swap_layout().shuffle(shuffle); + * eigen_assert(output.dimension(0) == 2); + * eigen_assert(output.dimension(1) == 4); + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = traits::NumDimensions; + static const int Layout = (traits::Layout == ColMajor) ? RowMajor : ColMajor; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorLayoutSwapOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorLayoutSwapOp type; +}; + +} // end namespace internal + + + +template +class TensorLayoutSwapOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorLayoutSwapOp(const XprType& expr) + : m_xpr(expr) {} + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorLayoutSwapOp& operator = (const TensorLayoutSwapOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorLayoutSwapOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorLayoutSwapOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value; + typedef DSizes Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = (static_cast(TensorEvaluator::Layout) == static_cast(ColMajor)) ? RowMajor : ColMajor, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + for(int i = 0; i < NumDims; ++i) { + m_dimensions[i] = m_impl.dimensions()[NumDims-1-i]; + } + } + + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + return m_impl.evalSubExprsIfNeeded(data); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_impl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return m_impl.data(); } + + const TensorEvaluator& impl() const { return m_impl; } + + protected: + TensorEvaluator m_impl; + Dimensions m_dimensions; +}; + + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorLayoutSwapOp XprType; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = (static_cast(TensorEvaluator::Layout) == static_cast(ColMajor)) ? RowMajor : ColMajor, + CoordAccess = false // to be implemented + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(index); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + this->m_impl.template writePacket(index, x); + } +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h new file mode 100644 index 000000000..ee0078bbc --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h @@ -0,0 +1,54 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H +#define EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H + + +/** use this macro in sfinae selection in templated functions + * + * template::value , int >::type = 0 + * > + * void foo(){} + * + * becomes => + * + * template::value ) + * > + * void foo(){} + */ + +// SFINAE requires variadic templates +#ifndef __CUDACC__ +#if EIGEN_HAS_VARIADIC_TEMPLATES + // SFINAE doesn't work for gcc <= 4.7 + #ifdef EIGEN_COMP_GNUC + #if EIGEN_GNUC_AT_LEAST(4,8) + #define EIGEN_HAS_SFINAE + #endif + #else + #define EIGEN_HAS_SFINAE + #endif +#endif +#endif + +#define EIGEN_SFINAE_ENABLE_IF( __condition__ ) \ + typename internal::enable_if< ( __condition__ ) , int >::type = 0 + + +#if EIGEN_HAS_CONSTEXPR +#define EIGEN_CONSTEXPR constexpr +#else +#define EIGEN_CONSTEXPR +#endif + + +#endif diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h new file mode 100644 index 000000000..a8e55757e --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h @@ -0,0 +1,321 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_MAP_H +#define EIGEN_CXX11_TENSOR_TENSOR_MAP_H + +namespace Eigen { + +/** \class TensorMap + * \ingroup CXX11_Tensor_Module + * + * \brief A tensor expression mapping an existing array of data. + * + */ +/// template class MakePointer_ is added to convert the host pointer to the device pointer. +/// It is added due to the fact that for our device compiler T* is not allowed. +/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer T. +/// This is done through our MakePointer_ class. By default the Type in the MakePointer_ is T* . +/// Therefore, by adding the default value, we managed to convert the type and it does not break any +/// existing code as its default value is T*. +template class MakePointer_> class TensorMap : public TensorBase > +{ + public: + typedef TensorMap Self; + typedef typename PlainObjectType::Base Base; + typedef typename Eigen::internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + typedef typename internal::traits::Scalar Scalar; + typedef typename NumTraits::Real RealScalar; + typedef typename Base::CoeffReturnType CoeffReturnType; + + /* typedef typename internal::conditional< + bool(internal::is_lvalue::value), + Scalar *, + const Scalar *>::type + PointerType;*/ + typedef typename MakePointer_::Type PointerType; + typedef PointerType PointerArgType; + + static const int Options = Options_; + + static const Index NumIndices = PlainObjectType::NumIndices; + typedef typename PlainObjectType::Dimensions Dimensions; + + enum { + IsAligned = ((int(Options_)&Aligned)==Aligned), + Layout = PlainObjectType::Layout, + CoordAccess = true, + RawAccess = true + }; + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr) : m_data(dataPtr), m_dimensions() { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((0 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index firstDimension, IndexTypes... otherDimensions) : m_data(dataPtr), m_dimensions(firstDimension, otherDimensions...) { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((sizeof...(otherDimensions) + 1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index firstDimension) : m_data(dataPtr), m_dimensions(firstDimension) { + // The number of dimensions used to construct a tensor must be equal to the rank of the tensor. + EIGEN_STATIC_ASSERT((1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2) : m_data(dataPtr), m_dimensions(dim1, dim2) { + EIGEN_STATIC_ASSERT(2 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3) { + EIGEN_STATIC_ASSERT(3 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4) { + EIGEN_STATIC_ASSERT(4 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4, dim5) { + EIGEN_STATIC_ASSERT(5 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE) + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, const array& dimensions) + : m_data(dataPtr), m_dimensions(dimensions) + { } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PointerArgType dataPtr, const Dimensions& dimensions) + : m_data(dataPtr), m_dimensions(dimensions) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PlainObjectType& tensor) + : m_data(tensor.data()), m_dimensions(tensor.dimensions()) + { } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index rank() const { return m_dimensions.rank(); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_dimensions[n]; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE PointerType data() { return m_data; } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const PointerType data() const { return m_data; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(const array& indices) const + { + // eigen_assert(checkIndexRange(indices)); + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(indices); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(indices); + return m_data[index]; + } + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()() const + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE) + return m_data[0]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const + { + eigen_internal_assert(index >= 0 && index < size()); + return m_data[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const + { + EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE) + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i1 + i0 * m_dimensions[1]; + return m_data[index]; + } else { + const Index index = i0 + i1 * m_dimensions[0]; + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3)); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0))); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4))); + return m_data[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(const array& indices) + { + // eigen_assert(checkIndexRange(indices)); + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(indices); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(indices); + return m_data[index]; + } + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()() + { + EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE) + return m_data[0]; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index index) + { + eigen_internal_assert(index >= 0 && index < size()); + return m_data[index]; + } + +#if EIGEN_HAS_VARIADIC_TEMPLATES + template EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) + { + static_assert(sizeof...(otherIndices) + 2 == NumIndices || NumIndices == Dynamic, "Number of indices used to access a tensor coefficient must be equal to the rank of the tensor."); + const std::size_t NumDims = sizeof...(otherIndices) + 2; + if (PlainObjectType::Options&RowMajor) { + const Index index = m_dimensions.IndexOfRowMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } else { + const Index index = m_dimensions.IndexOfColMajor(array{{firstIndex, secondIndex, otherIndices...}}); + return m_data[index]; + } + } +#else + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i1 + i0 * m_dimensions[1]; + return m_data[index]; + } else { + const Index index = i0 + i1 * m_dimensions[0]; + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3)); + return m_data[index]; + } + } + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) + { + if (PlainObjectType::Options&RowMajor) { + const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0))); + return m_data[index]; + } else { + const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4))); + return m_data[index]; + } + } +#endif + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Self& operator=(const Self& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Self& operator=(const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + private: + typename MakePointer_::Type m_data; + Dimensions m_dimensions; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_MAP_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h new file mode 100644 index 000000000..615559d44 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h @@ -0,0 +1,218 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2015 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_H +#define EIGEN_CXX11_TENSOR_TENSOR_META_H + +namespace Eigen { + +template struct Cond {}; + +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +const T1& choose(Cond, const T1& first, const T2&) { + return first; +} + +template EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +const T2& choose(Cond, const T1&, const T2& second) { + return second; +} + + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T divup(const X x, const Y y) { + return static_cast((x + y - 1) / y); +} + +template +EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE +T divup(const T x, const T y) { + return static_cast((x + y - 1) / y); +} + +template struct max_n_1 { + static const size_t size = n; +}; +template <> struct max_n_1<0> { + static const size_t size = 1; +}; + + +// Default packet types +template +struct PacketType : internal::packet_traits { + typedef typename internal::packet_traits::type type; +}; + +// For CUDA packet types when using a GpuDevice +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) && defined(EIGEN_HAS_CUDA_FP16) +template <> +struct PacketType { + typedef half2 type; + static const int size = 2; + enum { + HasAdd = 1, + HasSub = 1, + HasMul = 1, + HasNegate = 1, + HasAbs = 1, + HasArg = 0, + HasAbs2 = 0, + HasMin = 1, + HasMax = 1, + HasConj = 0, + HasSetLinear = 0, + HasBlend = 0, + + HasDiv = 1, + HasSqrt = 1, + HasRsqrt = 1, + HasExp = 1, + HasLog = 1, + HasLog1p = 0, + HasLog10 = 0, + HasPow = 1, + }; +}; +#endif + +#if defined(EIGEN_USE_SYCL) +template + struct PacketType { + typedef T type; + static const int size = 1; + enum { + HasAdd = 0, + HasSub = 0, + HasMul = 0, + HasNegate = 0, + HasAbs = 0, + HasArg = 0, + HasAbs2 = 0, + HasMin = 0, + HasMax = 0, + HasConj = 0, + HasSetLinear = 0, + HasBlend = 0 + }; +}; +#endif + + +// Tuple mimics std::pair but works on e.g. nvcc. +template struct Tuple { + public: + U first; + V second; + + typedef U first_type; + typedef V second_type; + + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple() : first(), second() {} + + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple(const U& f, const V& s) : first(f), second(s) {} + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Tuple& operator= (const Tuple& rhs) { + if (&rhs == this) return *this; + first = rhs.first; + second = rhs.second; + return *this; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void swap(Tuple& rhs) { + using numext::swap; + swap(first, rhs.first); + swap(second, rhs.second); + } +}; + +template +EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +bool operator==(const Tuple& x, const Tuple& y) { + return (x.first == y.first && x.second == y.second); +} + +template +EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +bool operator!=(const Tuple& x, const Tuple& y) { + return !(x == y); +} + + +// Can't use std::pairs on cuda devices +template struct IndexPair { + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair() : first(0), second(0) {} + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair(Idx f, Idx s) : first(f), second(s) {} + + EIGEN_DEVICE_FUNC void set(IndexPair val) { + first = val.first; + second = val.second; + } + + Idx first; + Idx second; +}; + + +#ifdef EIGEN_HAS_SFINAE +namespace internal { + + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType& idx, numeric_list) { + return { idx[Is]... }; + } + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType&, numeric_list) { + return array(); + } + + /** Make an array (for index/dimensions) out of a custom index */ + template + EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + array customIndices2Array(IndexType& idx) { + return customIndices2Array(idx, typename gen_numeric_list::type{}); + } + + + template + struct is_base_of + { + + typedef char (&yes)[1]; + typedef char (&no)[2]; + + template + struct Host + { + operator BB*() const; + operator DD*(); + }; + + template + static yes check(D*, T); + static no check(B*, int); + + static const bool value = sizeof(check(Host(), int())) == sizeof(yes); + }; + +} +#endif + + + +} // namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_META_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h new file mode 100644 index 000000000..d34f1e328 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h @@ -0,0 +1,888 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H +#define EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H + +namespace Eigen { + +/** \class TensorReshaping + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reshaping class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorReshapingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorReshapingOp type; +}; + +} // end namespace internal + + + +template +class TensorReshapingOp : public TensorBase, WriteAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReshapingOp(const XprType& expr, const NewDimensions& dims) + : m_xpr(expr), m_dims(dims) {} + + EIGEN_DEVICE_FUNC + const NewDimensions& dimensions() const { return m_dims; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorReshapingOp& operator = (const TensorReshapingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorReshapingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const NewDimensions m_dims; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorReshapingOp XprType; + typedef NewDimensions Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_dimensions(op.dimensions()) + { + // The total size of the reshaped tensor must be equal to the total size + // of the input tensor. + eigen_assert(internal::array_prod(m_impl.dimensions()) == internal::array_prod(op.dimensions())); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + return m_impl.evalSubExprsIfNeeded(data); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(index); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + return m_impl.template packet(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return const_cast(m_impl.data()); } + + EIGEN_DEVICE_FUNC const TensorEvaluator& impl() const { return m_impl; } + + protected: + TensorEvaluator m_impl; + NewDimensions m_dimensions; +}; + + +// Eval as lvalue +template + struct TensorEvaluator, Device> + : public TensorEvaluator, Device> + +{ + typedef TensorEvaluator, Device> Base; + typedef TensorReshapingOp XprType; + typedef NewDimensions Dimensions; + + enum { + IsAligned = TensorEvaluator::IsAligned, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = TensorEvaluator::RawAccess + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(index); + } + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + this->m_impl.template writePacket(index, x); + } +}; + + +/** \class TensorSlicing + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor slicing class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorSlicingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorSlicingOp type; +}; + +} // end namespace internal + + + +template +class TensorSlicingOp : public TensorBase > +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSlicingOp(const XprType& expr, const StartIndices& indices, const Sizes& sizes) + : m_xpr(expr), m_indices(indices), m_sizes(sizes) {} + + EIGEN_DEVICE_FUNC + const StartIndices& startIndices() const { return m_indices; } + EIGEN_DEVICE_FUNC + const Sizes& sizes() const { return m_sizes; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorSlicingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorSlicingOp& operator = (const TensorSlicingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run(assign, DefaultDevice()); + return *this; + } + + + protected: + typename XprType::Nested m_xpr; + const StartIndices m_indices; + const Sizes m_sizes; +}; + + +// Fixme: figure out the exact threshold +namespace { +template struct MemcpyTriggerForSlicing { + EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const Device& device) : threshold_(2 * device.numThreads()) { } + EIGEN_DEVICE_FUNC bool operator ()(Index val) const { return val > threshold_; } + + private: + Index threshold_; +}; + +// It is very expensive to start the memcpy kernel on GPU: we therefore only +// use it for large copies. +#ifdef EIGEN_USE_GPU +template struct MemcpyTriggerForSlicing { + EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const GpuDevice&) { } + EIGEN_DEVICE_FUNC bool operator ()(Index val) const { return val > 4*1024*1024; } +}; +#endif +} + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets and sizes. + IsAligned = /*TensorEvaluator::IsAligned*/false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), m_dimensions(op.sizes()), m_offsets(op.startIndices()) + { + for (std::size_t i = 0; i < internal::array_size::value; ++i) { + eigen_assert(m_impl.dimensions()[i] >= op.sizes()[i] + op.startIndices()[i]); + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + const Sizes& output_dims = op.sizes(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + } + + // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed. + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1]; + m_fastOutputStrides[i] = internal::TensorIntDivisor(m_outputStrides[i]); + } + } else { + m_inputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + } + + // Don't initialize m_fastOutputStrides[NumDims-1] since it won't ever be accessed. + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1]; + m_fastOutputStrides[i] = internal::TensorIntDivisor(m_outputStrides[i]); + } + } + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Sizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType* data) { + m_impl.evalSubExprsIfNeeded(NULL); + if (!NumTraits::type>::RequireInitialization && data && m_impl.data()) { + Index contiguous_values = 1; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + contiguous_values *= dimensions()[i]; + if (dimensions()[i] != m_impl.dimensions()[i]) { + break; + } + } + } else { + for (int i = NumDims-1; i >= 0; --i) { + contiguous_values *= dimensions()[i]; + if (dimensions()[i] != m_impl.dimensions()[i]) { + break; + } + } + } + // Use memcpy if it's going to be faster than using the regular evaluation. + const MemcpyTriggerForSlicing trigger(m_device); + if (trigger(contiguous_values)) { + Scalar* src = (Scalar*)m_impl.data(); + for (int i = 0; i < internal::array_prod(dimensions()); i += contiguous_values) { + Index offset = srcCoeff(i); + m_device.memcpy((void*)(data+i), src+offset, contiguous_values * sizeof(Scalar)); + } + return false; + } + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + const int packetSize = internal::unpacket_traits::size; + EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+packetSize-1 < internal::array_prod(dimensions())); + + Index inputIndices[] = {0, 0}; + Index indices[] = {index, index + packetSize - 1}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / m_fastOutputStrides[i]; + const Index idx1 = indices[1] / m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i]; + inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i]; + indices[0] -= idx0 * m_outputStrides[i]; + indices[1] -= idx1 * m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + m_offsets[0]); + inputIndices[1] += (indices[1] + m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / m_fastOutputStrides[i]; + const Index idx1 = indices[1] / m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i]; + inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i]; + indices[0] -= idx0 * m_outputStrides[i]; + indices[1] -= idx1 * m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + m_offsets[NumDims-1]); + inputIndices[1] += (indices[1] + m_offsets[NumDims-1]); + } + if (inputIndices[1] - inputIndices[0] == packetSize - 1) { + PacketReturnType rslt = m_impl.template packet(inputIndices[0]); + return rslt; + } + else { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[packetSize]; + values[0] = m_impl.coeff(inputIndices[0]); + values[packetSize-1] = m_impl.coeff(inputIndices[1]); + for (int i = 1; i < packetSize-1; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, NumDims); + } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { + Scalar* result = m_impl.data(); + if (result) { + Index offset = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) { + if (m_dimensions[i] != m_impl.dimensions()[i]) { + offset += m_offsets[i] * m_inputStrides[i]; + for (int j = i+1; j < NumDims; ++j) { + if (m_dimensions[j] > 1) { + return NULL; + } + offset += m_offsets[j] * m_inputStrides[j]; + } + break; + } + } + } else { + for (int i = NumDims - 1; i >= 0; --i) { + if (m_dimensions[i] != m_impl.dimensions()[i]) { + offset += m_offsets[i] * m_inputStrides[i]; + for (int j = i-1; j >= 0; --j) { + if (m_dimensions[j] > 1) { + return NULL; + } + offset += m_offsets[j] * m_inputStrides[j]; + } + break; + } + } + } + return result + offset; + } + return NULL; + } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += (idx + m_offsets[i]) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + inputIndex += (index + m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += (idx + m_offsets[i]) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + inputIndex += (index + m_offsets[NumDims-1]); + } + return inputIndex; + } + + array m_outputStrides; + array, NumDims> m_fastOutputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Device& m_device; + Dimensions m_dimensions; + const StartIndices m_offsets; +}; + + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = /*TensorEvaluator::IsAligned*/false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Sizes Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + void writePacket(Index index, const PacketReturnType& x) + { + const int packetSize = internal::unpacket_traits::size; + Index inputIndices[] = {0, 0}; + Index indices[] = {index, index + packetSize - 1}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx0 = indices[0] / this->m_fastOutputStrides[i]; + const Index idx1 = indices[1] / this->m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i]; + inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i]; + indices[0] -= idx0 * this->m_outputStrides[i]; + indices[1] -= idx1 * this->m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + this->m_offsets[0]); + inputIndices[1] += (indices[1] + this->m_offsets[0]); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx0 = indices[0] / this->m_fastOutputStrides[i]; + const Index idx1 = indices[1] / this->m_fastOutputStrides[i]; + inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i]; + inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i]; + indices[0] -= idx0 * this->m_outputStrides[i]; + indices[1] -= idx1 * this->m_outputStrides[i]; + } + inputIndices[0] += (indices[0] + this->m_offsets[NumDims-1]); + inputIndices[1] += (indices[1] + this->m_offsets[NumDims-1]); + } + if (inputIndices[1] - inputIndices[0] == packetSize - 1) { + this->m_impl.template writePacket(inputIndices[0], x); + } + else { + EIGEN_ALIGN_MAX CoeffReturnType values[packetSize]; + internal::pstore(values, x); + this->m_impl.coeffRef(inputIndices[0]) = values[0]; + this->m_impl.coeffRef(inputIndices[1]) = values[packetSize-1]; + for (int i = 1; i < packetSize-1; ++i) { + this->coeffRef(index+i) = values[i]; + } + } + } +}; + + + +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = array_size::value; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorStridingSlicingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorStridingSlicingOp type; +}; + +} // end namespace internal + + +template +class TensorStridingSlicingOp : public TensorBase > +{ + public: + typedef typename internal::traits::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename internal::nested::type Nested; + typedef typename internal::traits::StorageKind StorageKind; + typedef typename internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingSlicingOp( + const XprType& expr, const StartIndices& startIndices, + const StopIndices& stopIndices, const Strides& strides) + : m_xpr(expr), m_startIndices(startIndices), m_stopIndices(stopIndices), + m_strides(strides) {} + + EIGEN_DEVICE_FUNC + const StartIndices& startIndices() const { return m_startIndices; } + EIGEN_DEVICE_FUNC + const StartIndices& stopIndices() const { return m_stopIndices; } + EIGEN_DEVICE_FUNC + const StartIndices& strides() const { return m_strides; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorStridingSlicingOp& operator = (const TensorStridingSlicingOp& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run( + assign, DefaultDevice()); + return *this; + } + + template + EIGEN_DEVICE_FUNC + EIGEN_STRONG_INLINE TensorStridingSlicingOp& operator = (const OtherDerived& other) + { + typedef TensorAssignOp Assign; + Assign assign(*this, other); + internal::TensorExecutor::run( + assign, DefaultDevice()); + return *this; + } + + protected: + typename XprType::Nested m_xpr; + const StartIndices m_startIndices; + const StopIndices m_stopIndices; + const Strides m_strides; +}; + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorStridingSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + // Alignment can't be guaranteed at compile time since it depends on the + // slice offsets and sizes. + IsAligned = false, + PacketAccess = false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_device(device), m_strides(op.strides()) + { + // Handle degenerate intervals by gracefully clamping and allowing m_dimensions to be zero + DSizes startIndicesClamped, stopIndicesClamped; + for (size_t i = 0; i < internal::array_size::value; ++i) { + eigen_assert(m_strides[i] != 0 && "0 stride is invalid"); + if(m_strides[i]>0){ + startIndicesClamped[i] = clamp(op.startIndices()[i], 0, m_impl.dimensions()[i]); + stopIndicesClamped[i] = clamp(op.stopIndices()[i], 0, m_impl.dimensions()[i]); + }else{ + /* implies m_strides[i]<0 by assert */ + startIndicesClamped[i] = clamp(op.startIndices()[i], -1, m_impl.dimensions()[i] - 1); + stopIndicesClamped[i] = clamp(op.stopIndices()[i], -1, m_impl.dimensions()[i] - 1); + } + m_startIndices[i] = startIndicesClamped[i]; + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + + // check for degenerate intervals and compute output tensor shape + bool degenerate = false;; + for(int i = 0; i < NumDims; i++){ + Index interval = stopIndicesClamped[i] - startIndicesClamped[i]; + if(interval == 0 || ((interval<0) != (m_strides[i]<0))){ + m_dimensions[i] = 0; + degenerate = true; + }else{ + m_dimensions[i] = interval / m_strides[i] + + (interval % m_strides[i] != 0 ? 1 : 0); + eigen_assert(m_dimensions[i] >= 0); + } + } + Strides output_dims = m_dimensions; + + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = m_strides[0]; + m_offsets[0] = startIndicesClamped[0]; + Index previousDimProduct = 1; + for (int i = 1; i < NumDims; ++i) { + previousDimProduct *= input_dims[i-1]; + m_inputStrides[i] = previousDimProduct * m_strides[i]; + m_offsets[i] = startIndicesClamped[i] * previousDimProduct; + } + + // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed. + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1]; + // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash + m_fastOutputStrides[i] = internal::TensorIntDivisor(degenerate ? 1 : m_outputStrides[i]); + } + } else { + m_inputStrides[NumDims-1] = m_strides[NumDims-1]; + m_offsets[NumDims-1] = startIndicesClamped[NumDims-1]; + Index previousDimProduct = 1; + for (int i = NumDims - 2; i >= 0; --i) { + previousDimProduct *= input_dims[i+1]; + m_inputStrides[i] = previousDimProduct * m_strides[i]; + m_offsets[i] = startIndicesClamped[i] * previousDimProduct; + } + + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1]; + // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash + m_fastOutputStrides[i] = internal::TensorIntDivisor(degenerate ? 1 : m_outputStrides[i]); + } + } + m_block_total_size_max = numext::maxi(static_cast(1), + device.lastLevelCacheSize() / + sizeof(Scalar)); + } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type ScalarNonConst; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Strides Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(CoeffReturnType*) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + return m_impl.coeff(srcCoeff(index)); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, NumDims); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar* data() const { + return NULL; + } + + protected: + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const + { + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i >= 0; --i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += idx * m_inputStrides[i] + m_offsets[i]; + index -= idx * m_outputStrides[i]; + } + } else { + for (int i = 0; i < NumDims; ++i) { + const Index idx = index / m_fastOutputStrides[i]; + inputIndex += idx * m_inputStrides[i] + m_offsets[i]; + index -= idx * m_outputStrides[i]; + } + } + return inputIndex; + } + + static EIGEN_STRONG_INLINE Index clamp(Index value, Index min, Index max) { + return numext::maxi(min, numext::mini(max,value)); + } + + array m_outputStrides; + array, NumDims> m_fastOutputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + const Device& m_device; + DSizes m_startIndices; // clamped startIndices + DSizes m_dimensions; + DSizes m_offsets; // offset in a flattened shape + const Strides m_strides; + std::size_t m_block_total_size_max; +}; + +// Eval as lvalue +template +struct TensorEvaluator, Device> + : public TensorEvaluator, Device> +{ + typedef TensorEvaluator, Device> Base; + typedef TensorStridingSlicingOp XprType; + static const int NumDims = internal::array_size::value; + + enum { + IsAligned = false, + PacketAccess = false, + BlockAccess = false, + Layout = TensorEvaluator::Layout, + CoordAccess = TensorEvaluator::CoordAccess, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : Base(op, device) + { } + + typedef typename XprType::Index Index; + typedef typename XprType::Scalar Scalar; + typedef typename internal::remove_const::type ScalarNonConst; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + typedef Strides Dimensions; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) + { + return this->m_impl.coeffRef(this->srcCoeff(index)); + } +}; + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h new file mode 100644 index 000000000..647bcf108 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h @@ -0,0 +1,397 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_PADDING_H +#define EIGEN_CXX11_TENSOR_TENSOR_PADDING_H + +namespace Eigen { + +/** \class TensorPadding + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor padding class. + * At the moment only padding with a constant value is supported. + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorPaddingOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorPaddingOp type; +}; + +} // end namespace internal + + + +template +class TensorPaddingOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPaddingOp(const XprType& expr, const PaddingDimensions& padding_dims, const Scalar padding_value) + : m_xpr(expr), m_padding_dims(padding_dims), m_padding_value(padding_value) {} + + EIGEN_DEVICE_FUNC + const PaddingDimensions& padding() const { return m_padding_dims; } + EIGEN_DEVICE_FUNC + Scalar padding_value() const { return m_padding_value; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const PaddingDimensions m_padding_dims; + const Scalar m_padding_value; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorPaddingOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::value; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = true, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = true, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_padding(op.padding()), m_paddingValue(op.padding_value()) + { + // The padding op doesn't change the rank of the tensor. Directly padding a scalar would lead + // to a vector, which doesn't make sense. Instead one should reshape the scalar into a vector + // of 1 element first and then pad. + EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + + // Compute dimensions + m_dimensions = m_impl.dimensions(); + for (int i = 0; i < NumDims; ++i) { + m_dimensions[i] += m_padding[i].first + m_padding[i].second; + } + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + if (static_cast(Layout) == static_cast(ColMajor)) { + m_inputStrides[0] = 1; + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + m_outputStrides[NumDims] = m_outputStrides[NumDims-1] * m_dimensions[NumDims-1]; + } else { + m_inputStrides[NumDims - 1] = 1; + m_outputStrides[NumDims] = 1; + for (int i = NumDims - 2; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_outputStrides[i+1] = m_outputStrides[i+2] * m_dimensions[i+1]; + } + m_outputStrides[0] = m_outputStrides[1] * m_dimensions[0]; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + eigen_assert(index < dimensions().TotalSize()); + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 1; i > 0; --i) { + const Index idx = index / m_outputStrides[i]; + if (isPaddingAtIndexForDim(idx, i)) { + return m_paddingValue; + } + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (isPaddingAtIndexForDim(index, 0)) { + return m_paddingValue; + } + inputIndex += (index - m_padding[0].first); + } else { + for (int i = 0; i < NumDims - 1; ++i) { + const Index idx = index / m_outputStrides[i+1]; + if (isPaddingAtIndexForDim(idx, i)) { + return m_paddingValue; + } + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i+1]; + } + if (isPaddingAtIndexForDim(index, NumDims-1)) { + return m_paddingValue; + } + inputIndex += (index - m_padding[NumDims-1].first); + } + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + if (static_cast(Layout) == static_cast(ColMajor)) { + return packetColMajor(index); + } + return packetRowMajor(index); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + TensorOpCost cost = m_impl.costPerCoeff(vectorized); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims; ++i) + updateCostPerDimension(cost, i, i == 0); + } else { + for (int i = NumDims - 1; i >= 0; --i) + updateCostPerDimension(cost, i, i == NumDims - 1); + } + return cost; + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + private: + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isPaddingAtIndexForDim( + Index index, int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return (!internal::index_pair_first_statically_eq(dim_index, 0) && + index < m_padding[dim_index].first) || + (!internal::index_pair_second_statically_eq(dim_index, 0) && + index >= m_dimensions[dim_index] - m_padding[dim_index].second); +#else + return (index < m_padding[dim_index].first) || + (index >= m_dimensions[dim_index] - m_padding[dim_index].second); +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isLeftPaddingCompileTimeZero( + int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return internal::index_pair_first_statically_eq(dim_index, 0); +#else + EIGEN_UNUSED_VARIABLE(dim_index); + return false; +#endif + } + + EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isRightPaddingCompileTimeZero( + int dim_index) const { +#if defined(EIGEN_HAS_INDEX_LIST) + return internal::index_pair_second_statically_eq(dim_index, 0); +#else + EIGEN_UNUSED_VARIABLE(dim_index); + return false; +#endif + } + + + void updateCostPerDimension(TensorOpCost& cost, int i, bool first) const { + const double in = static_cast(m_impl.dimensions()[i]); + const double out = in + m_padding[i].first + m_padding[i].second; + if (out == 0) + return; + const double reduction = in / out; + cost *= reduction; + if (first) { + cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost() + + reduction * (1 * TensorOpCost::AddCost())); + } else { + cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost() + + 2 * TensorOpCost::MulCost() + + reduction * (2 * TensorOpCost::MulCost() + + 1 * TensorOpCost::DivCost())); + } + } + + protected: + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index initialIndex = index; + Index inputIndex = 0; + for (int i = NumDims - 1; i > 0; --i) { + const Index first = index; + const Index last = index + PacketSize - 1; + const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i]; + const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i]; + const Index lastPaddedRight = m_outputStrides[i+1]; + + if (!isLeftPaddingCompileTimeZero(i) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(i) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + const Index idx = index / m_outputStrides[i]; + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i]; + } + else { + // Every other case + return packetWithPossibleZero(initialIndex); + } + } + + const Index last = index + PacketSize - 1; + const Index first = index; + const Index lastPaddedLeft = m_padding[0].first; + const Index firstPaddedRight = (m_dimensions[0] - m_padding[0].second); + const Index lastPaddedRight = m_outputStrides[1]; + + if (!isLeftPaddingCompileTimeZero(0) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(0) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(0) && isRightPaddingCompileTimeZero(0)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + inputIndex += (index - m_padding[0].first); + return m_impl.template packet(inputIndex); + } + // Every other case + return packetWithPossibleZero(initialIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + const Index initialIndex = index; + Index inputIndex = 0; + + for (int i = 0; i < NumDims - 1; ++i) { + const Index first = index; + const Index last = index + PacketSize - 1; + const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i+1]; + const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i+1]; + const Index lastPaddedRight = m_outputStrides[i]; + + if (!isLeftPaddingCompileTimeZero(i) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(i) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + const Index idx = index / m_outputStrides[i+1]; + inputIndex += (idx - m_padding[i].first) * m_inputStrides[i]; + index -= idx * m_outputStrides[i+1]; + } + else { + // Every other case + return packetWithPossibleZero(initialIndex); + } + } + + const Index last = index + PacketSize - 1; + const Index first = index; + const Index lastPaddedLeft = m_padding[NumDims-1].first; + const Index firstPaddedRight = (m_dimensions[NumDims-1] - m_padding[NumDims-1].second); + const Index lastPaddedRight = m_outputStrides[NumDims-1]; + + if (!isLeftPaddingCompileTimeZero(NumDims-1) && last < lastPaddedLeft) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if (!isRightPaddingCompileTimeZero(NumDims-1) && first >= firstPaddedRight && last < lastPaddedRight) { + // all the coefficient are in the padding zone. + return internal::pset1(m_paddingValue); + } + else if ((isLeftPaddingCompileTimeZero(NumDims-1) && isRightPaddingCompileTimeZero(NumDims-1)) || (first >= lastPaddedLeft && last < firstPaddedRight)) { + // all the coefficient are between the 2 padding zones. + inputIndex += (index - m_padding[NumDims-1].first); + return m_impl.template packet(inputIndex); + } + // Every other case + return packetWithPossibleZero(initialIndex); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const + { + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + TensorEvaluator m_impl; + PaddingDimensions m_padding; + + Scalar m_paddingValue; +}; + + + + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_PADDING_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h new file mode 100644 index 000000000..886a254f6 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h @@ -0,0 +1,269 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_PATCH_H +#define EIGEN_CXX11_TENSOR_TENSOR_PATCH_H + +namespace Eigen { + +/** \class TensorPatch + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor patch class. + * + * + */ +namespace internal { +template +struct traits > : public traits +{ + typedef typename XprType::Scalar Scalar; + typedef traits XprTraits; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + typedef typename remove_reference::type _Nested; + static const int NumDimensions = XprTraits::NumDimensions + 1; + static const int Layout = XprTraits::Layout; +}; + +template +struct eval, Eigen::Dense> +{ + typedef const TensorPatchOp& type; +}; + +template +struct nested, 1, typename eval >::type> +{ + typedef TensorPatchOp type; +}; + +} // end namespace internal + + + +template +class TensorPatchOp : public TensorBase, ReadOnlyAccessors> +{ + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPatchOp(const XprType& expr, const PatchDim& patch_dims) + : m_xpr(expr), m_patch_dims(patch_dims) {} + + EIGEN_DEVICE_FUNC + const PatchDim& patch_dims() const { return m_patch_dims; } + + EIGEN_DEVICE_FUNC + const typename internal::remove_all::type& + expression() const { return m_xpr; } + + protected: + typename XprType::Nested m_xpr; + const PatchDim m_patch_dims; +}; + + +// Eval as rvalue +template +struct TensorEvaluator, Device> +{ + typedef TensorPatchOp XprType; + typedef typename XprType::Index Index; + static const int NumDims = internal::array_size::Dimensions>::value + 1; + typedef DSizes Dimensions; + typedef typename XprType::Scalar Scalar; + typedef typename XprType::CoeffReturnType CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + + enum { + IsAligned = false, + PacketAccess = TensorEvaluator::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, + RawAccess = false + }; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device) + { + Index num_patches = 1; + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + const PatchDim& patch_dims = op.patch_dims(); + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = 0; i < NumDims-1; ++i) { + m_dimensions[i] = patch_dims[i]; + num_patches *= (input_dims[i] - patch_dims[i] + 1); + } + m_dimensions[NumDims-1] = num_patches; + + m_inputStrides[0] = 1; + m_patchStrides[0] = 1; + for (int i = 1; i < NumDims-1; ++i) { + m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1]; + m_patchStrides[i] = m_patchStrides[i-1] * (input_dims[i-1] - patch_dims[i-1] + 1); + } + m_outputStrides[0] = 1; + for (int i = 1; i < NumDims; ++i) { + m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1]; + } + } else { + for (int i = 0; i < NumDims-1; ++i) { + m_dimensions[i+1] = patch_dims[i]; + num_patches *= (input_dims[i] - patch_dims[i] + 1); + } + m_dimensions[0] = num_patches; + + m_inputStrides[NumDims-2] = 1; + m_patchStrides[NumDims-2] = 1; + for (int i = NumDims-3; i >= 0; --i) { + m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1]; + m_patchStrides[i] = m_patchStrides[i+1] * (input_dims[i+1] - patch_dims[i+1] + 1); + } + m_outputStrides[NumDims-1] = 1; + for (int i = NumDims-2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1]; + } + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* /*data*/) { + m_impl.evalSubExprsIfNeeded(NULL); + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + Index output_stride_index = (static_cast(Layout) == static_cast(ColMajor)) ? NumDims - 1 : 0; + // Find the location of the first element of the patch. + Index patchIndex = index / m_outputStrides[output_stride_index]; + // Find the offset of the element wrt the location of the first element. + Index patchOffset = index - patchIndex * m_outputStrides[output_stride_index]; + Index inputIndex = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 2; i > 0; --i) { + const Index patchIdx = patchIndex / m_patchStrides[i]; + patchIndex -= patchIdx * m_patchStrides[i]; + const Index offsetIdx = patchOffset / m_outputStrides[i]; + patchOffset -= offsetIdx * m_outputStrides[i]; + inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i]; + } + } else { + for (int i = 0; i < NumDims - 2; ++i) { + const Index patchIdx = patchIndex / m_patchStrides[i]; + patchIndex -= patchIdx * m_patchStrides[i]; + const Index offsetIdx = patchOffset / m_outputStrides[i+1]; + patchOffset -= offsetIdx * m_outputStrides[i+1]; + inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i]; + } + } + inputIndex += (patchIndex + patchOffset); + return m_impl.coeff(inputIndex); + } + + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index+PacketSize-1 < dimensions().TotalSize()); + + Index output_stride_index = (static_cast(Layout) == static_cast(ColMajor)) ? NumDims - 1 : 0; + Index indices[2] = {index, index + PacketSize - 1}; + Index patchIndices[2] = {indices[0] / m_outputStrides[output_stride_index], + indices[1] / m_outputStrides[output_stride_index]}; + Index patchOffsets[2] = {indices[0] - patchIndices[0] * m_outputStrides[output_stride_index], + indices[1] - patchIndices[1] * m_outputStrides[output_stride_index]}; + + Index inputIndices[2] = {0, 0}; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumDims - 2; i > 0; --i) { + const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i], + patchIndices[1] / m_patchStrides[i]}; + patchIndices[0] -= patchIdx[0] * m_patchStrides[i]; + patchIndices[1] -= patchIdx[1] * m_patchStrides[i]; + + const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i], + patchOffsets[1] / m_outputStrides[i]}; + patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i]; + patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i]; + + inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i]; + inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i]; + } + } else { + for (int i = 0; i < NumDims - 2; ++i) { + const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i], + patchIndices[1] / m_patchStrides[i]}; + patchIndices[0] -= patchIdx[0] * m_patchStrides[i]; + patchIndices[1] -= patchIdx[1] * m_patchStrides[i]; + + const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i+1], + patchOffsets[1] / m_outputStrides[i+1]}; + patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i+1]; + patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i+1]; + + inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i]; + inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i]; + } + } + inputIndices[0] += (patchIndices[0] + patchOffsets[0]); + inputIndices[1] += (patchIndices[1] + patchOffsets[1]); + + if (inputIndices[1] - inputIndices[0] == PacketSize - 1) { + PacketReturnType rslt = m_impl.template packet(inputIndices[0]); + return rslt; + } + else { + EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize]; + values[0] = m_impl.coeff(inputIndices[0]); + values[PacketSize-1] = m_impl.coeff(inputIndices[1]); + for (int i = 1; i < PacketSize-1; ++i) { + values[i] = coeff(index+i); + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + const double compute_cost = NumDims * (TensorOpCost::DivCost() + + TensorOpCost::MulCost() + + 2 * TensorOpCost::AddCost()); + return m_impl.costPerCoeff(vectorized) + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + + EIGEN_DEVICE_FUNC Scalar* data() const { return NULL; } + + protected: + Dimensions m_dimensions; + array m_outputStrides; + array m_inputStrides; + array m_patchStrides; + + TensorEvaluator m_impl; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_PATCH_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h new file mode 100644 index 000000000..1655a813e --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h @@ -0,0 +1,276 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2016 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H +#define EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H + +namespace Eigen { +namespace internal { + +namespace { + +EIGEN_DEVICE_FUNC uint64_t get_random_seed() { +#ifdef __CUDA_ARCH__ + // We don't support 3d kernels since we currently only use 1 and + // 2d kernels. + assert(threadIdx.z == 0); + return clock64() + + blockIdx.x * blockDim.x + threadIdx.x + + gridDim.x * blockDim.x * (blockIdx.y * blockDim.y + threadIdx.y); + +#elif defined _WIN32 + // Use the current time as a baseline. + SYSTEMTIME st; + GetSystemTime(&st); + int time = st.wSecond + 1000 * st.wMilliseconds; + // Mix in a random number to make sure that we get different seeds if + // we try to generate seeds faster than the clock resolution. + // We need 2 random values since the generator only generate 16 bits at + // a time (https://msdn.microsoft.com/en-us/library/398ax69y.aspx) + int rnd1 = ::rand(); + int rnd2 = ::rand(); + uint64_t rnd = (rnd1 | rnd2 << 16) ^ time; + return rnd; + +#elif defined __APPLE__ + // Same approach as for win32, except that the random number generator + // is better (// https://developer.apple.com/legacy/library/documentation/Darwin/Reference/ManPages/man3/random.3.html#//apple_ref/doc/man/3/random). + uint64_t rnd = ::random() ^ mach_absolute_time(); + return rnd; + +#else + // Augment the current time with pseudo random number generation + // to ensure that we get different seeds if we try to generate seeds + // faster than the clock resolution. + timespec ts; + clock_gettime(CLOCK_REALTIME, &ts); + uint64_t rnd = ::random() ^ ts.tv_nsec; + return rnd; +#endif +} + +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE unsigned PCG_XSH_RS_generator(uint64_t* state) { + // TODO: Unify with the implementation in the non blocking thread pool. + uint64_t current = *state; + // Update the internal state + *state = current * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL; + // Generate the random output (using the PCG-XSH-RS scheme) + return static_cast((current ^ (current >> 22)) >> (22 + (current >> 61))); +} + +static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE uint64_t PCG_XSH_RS_state(uint64_t seed) { + seed = seed ? seed : get_random_seed(); + return seed * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL; +} + +} // namespace + + +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +T RandomToTypeUniform(uint64_t* state) { + unsigned rnd = PCG_XSH_RS_generator(state); + return static_cast(rnd); +} + + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +Eigen::half RandomToTypeUniform(uint64_t* state) { + Eigen::half result; + // Generate 10 random bits for the mantissa + unsigned rnd = PCG_XSH_RS_generator(state); + result.x = static_cast(rnd & 0x3ffu); + // Set the exponent + result.x |= (static_cast(15) << 10); + // Return the final result + return result - Eigen::half(1.0f); +} + + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +float RandomToTypeUniform(uint64_t* state) { + typedef union { + uint32_t raw; + float fp; + } internal; + internal result; + // Generate 23 random bits for the mantissa mantissa + const unsigned rnd = PCG_XSH_RS_generator(state); + result.raw = rnd & 0x7fffffu; + // Set the exponent + result.raw |= (static_cast(127) << 23); + // Return the final result + return result.fp - 1.0f; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +double RandomToTypeUniform(uint64_t* state) { + typedef union { + uint64_t raw; + double dp; + } internal; + internal result; + result.raw = 0; + // Generate 52 random bits for the mantissa + // First generate the upper 20 bits + unsigned rnd1 = PCG_XSH_RS_generator(state) & 0xfffffu; + // The generate the lower 32 bits + unsigned rnd2 = PCG_XSH_RS_generator(state); + result.raw = (static_cast(rnd1) << 32) | rnd2; + // Set the exponent + result.raw |= (static_cast(1023) << 52); + // Return the final result + return result.dp - 1.0; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeUniform >(uint64_t* state) { + return std::complex(RandomToTypeUniform(state), + RandomToTypeUniform(state)); +} +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeUniform >(uint64_t* state) { + return std::complex(RandomToTypeUniform(state), + RandomToTypeUniform(state)); +} + +template class UniformRandomGenerator { + public: + static const bool PacketAccess = true; + + // Uses the given "seed" if non-zero, otherwise uses a random seed. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator( + uint64_t seed = 0) { + m_state = PCG_XSH_RS_state(seed); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator( + const UniformRandomGenerator& other) { + m_state = other.m_state; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + T operator()(Index i) const { + uint64_t local_state = m_state + i; + T result = RandomToTypeUniform(&local_state); + m_state = local_state; + return result; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(Index i) const { + const int packetSize = internal::unpacket_traits::size; + EIGEN_ALIGN_MAX T values[packetSize]; + uint64_t local_state = m_state + i; + for (int j = 0; j < packetSize; ++j) { + values[j] = RandomToTypeUniform(&local_state); + } + m_state = local_state; + return internal::pload(values); + } + + private: + mutable uint64_t m_state; +}; + +template +struct functor_traits > { + enum { + // Rough estimate for floating point, multiplied by ceil(sizeof(T) / sizeof(float)). + Cost = 12 * NumTraits::AddCost * + ((sizeof(Scalar) + sizeof(float) - 1) / sizeof(float)), + PacketAccess = UniformRandomGenerator::PacketAccess + }; +}; + + + +template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +T RandomToTypeNormal(uint64_t* state) { + // Use the ratio of uniform method to generate numbers following a normal + // distribution. See for example Numerical Recipes chapter 7.3.9 for the + // details. + T u, v, q; + do { + u = RandomToTypeUniform(state); + v = T(1.7156) * (RandomToTypeUniform(state) - T(0.5)); + const T x = u - T(0.449871); + const T y = numext::abs(v) + T(0.386595); + q = x*x + y * (T(0.196)*y - T(0.25472)*x); + } while (q > T(0.27597) && + (q > T(0.27846) || v*v > T(-4) * numext::log(u) * u*u)); + + return v/u; +} + +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeNormal >(uint64_t* state) { + return std::complex(RandomToTypeNormal(state), + RandomToTypeNormal(state)); +} +template <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE +std::complex RandomToTypeNormal >(uint64_t* state) { + return std::complex(RandomToTypeNormal(state), + RandomToTypeNormal(state)); +} + + +template class NormalRandomGenerator { + public: + static const bool PacketAccess = true; + + // Uses the given "seed" if non-zero, otherwise uses a random seed. + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(uint64_t seed = 0) { + m_state = PCG_XSH_RS_state(seed); + } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator( + const NormalRandomGenerator& other) { + m_state = other.m_state; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + T operator()(Index i) const { + uint64_t local_state = m_state + i; + T result = RandomToTypeNormal(&local_state); + m_state = local_state; + return result; + } + + template EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + Packet packetOp(Index i) const { + const int packetSize = internal::unpacket_traits::size; + EIGEN_ALIGN_MAX T values[packetSize]; + uint64_t local_state = m_state + i; + for (int j = 0; j < packetSize; ++j) { + values[j] = RandomToTypeNormal(&local_state); + } + m_state = local_state; + return internal::pload(values); + } + + private: + mutable uint64_t m_state; +}; + + +template +struct functor_traits > { + enum { + // On average, we need to generate about 3 random numbers + // 15 mul, 8 add, 1.5 logs + Cost = 3 * functor_traits >::Cost + + 15 * NumTraits::AddCost + 8 * NumTraits::AddCost + + 3 * functor_traits >::Cost / 2, + PacketAccess = NormalRandomGenerator::PacketAccess + }; +}; + + +} // end namespace internal +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h new file mode 100644 index 000000000..41d0d0022 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h @@ -0,0 +1,781 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// Copyright (C) 2016 Mehdi Goli, Codeplay Software Ltd +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H +#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H + +namespace Eigen { + +/** \class TensorReduction + * \ingroup CXX11_Tensor_Module + * + * \brief Tensor reduction class. + * + */ + +namespace internal { + template class MakePointer_ > + struct traits > + : traits +{ + typedef traits XprTraits; + typedef typename XprTraits::Scalar Scalar; + typedef typename XprTraits::StorageKind StorageKind; + typedef typename XprTraits::Index Index; + typedef typename XprType::Nested Nested; + static const int NumDimensions = XprTraits::NumDimensions - array_size::value; + static const int Layout = XprTraits::Layout; + + template struct MakePointer { + // Intermediate typedef to workaround MSVC issue. + typedef MakePointer_ MakePointerT; + typedef typename MakePointerT::Type Type; + }; +}; + +template class MakePointer_> +struct eval, Eigen::Dense> +{ + typedef const TensorReductionOp& type; +}; + +template class MakePointer_> +struct nested, 1, typename eval >::type> +{ + typedef TensorReductionOp type; +}; + + +template struct DimInitializer { + template EIGEN_DEVICE_FUNC + static void run(const InputDims& input_dims, + const array::value>& reduced, + OutputDims* output_dims, ReducedDims* reduced_dims) { + const int NumInputDims = internal::array_size::value; + int outputIndex = 0; + int reduceIndex = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (reduced[i]) { + (*reduced_dims)[reduceIndex] = input_dims[i]; + ++reduceIndex; + } else { + (*output_dims)[outputIndex] = input_dims[i]; + ++outputIndex; + } + } + } +}; + +template <> struct DimInitializer > { + template EIGEN_DEVICE_FUNC + static void run(const InputDims& input_dims, const array&, + Sizes<>*, array* reduced_dims) { + const int NumInputDims = internal::array_size::value; + for (int i = 0; i < NumInputDims; ++i) { + (*reduced_dims)[i] = input_dims[i]; + } + } +}; + + +template +struct are_inner_most_dims { + static const bool value = false; +}; +template +struct preserve_inner_most_dims { + static const bool value = false; +}; + +#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES +template +struct are_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_eq(0, 0); + static const bool tmp3 = index_statically_eq(array_size::value-1, array_size::value-1); + static const bool value = tmp1 & tmp2 & tmp3; +}; +template +struct are_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_eq(0, NumTensorDims - array_size::value); + static const bool tmp3 = index_statically_eq(array_size::value - 1, NumTensorDims - 1); + static const bool value = tmp1 & tmp2 & tmp3; + +}; +template +struct preserve_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_gt(0, 0); + static const bool value = tmp1 & tmp2; + +}; +template +struct preserve_inner_most_dims{ + static const bool tmp1 = indices_statically_known_to_increase(); + static const bool tmp2 = index_statically_lt(array_size::value - 1, NumTensorDims - 1); + static const bool value = tmp1 & tmp2; +}; +#endif + + +template +struct GenericDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) { + EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + for (int j = 0; j < self.m_reducedDims[DimIndex]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex]; + GenericDimReducer::reduce(self, input, reducer, accum); + } + } +}; +template +struct GenericDimReducer<0, Self, Op> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) { + for (int j = 0; j < self.m_reducedDims[0]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0]; + reducer.reduce(self.m_impl.coeff(input), accum); + } + } +}; +template +struct GenericDimReducer<-1, Self, Op> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index index, Op& reducer, typename Self::CoeffReturnType* accum) { + reducer.reduce(self.m_impl.coeff(index), accum); + } +}; + +template +struct InnerMostDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) { + typename Self::CoeffReturnType accum = reducer.initialize(); + for (typename Self::Index j = 0; j < numValuesToReduce; ++j) { + reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum); + } + return reducer.finalize(accum); + } +}; + +template +struct InnerMostDimReducer { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) { + const int packetSize = internal::unpacket_traits::size; + const typename Self::Index VectorizedSize = (numValuesToReduce / packetSize) * packetSize; + typename Self::PacketReturnType p = reducer.template initializePacket(); + for (typename Self::Index j = 0; j < VectorizedSize; j += packetSize) { + reducer.reducePacket(self.m_impl.template packet(firstIndex + j), &p); + } + typename Self::CoeffReturnType accum = reducer.initialize(); + for (typename Self::Index j = VectorizedSize; j < numValuesToReduce; ++j) { + reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum); + } + return reducer.finalizeBoth(accum, p); + } +}; + +template +struct InnerMostDimPreserver { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) { + eigen_assert(false && "should never be called"); + } +}; + +template +struct InnerMostDimPreserver { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) { + EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE); + for (typename Self::Index j = 0; j < self.m_reducedDims[DimIndex]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex]; + InnerMostDimPreserver::reduce(self, input, reducer, accum); + } + } +}; + +template +struct InnerMostDimPreserver<0, Self, Op, true> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) { + for (typename Self::Index j = 0; j < self.m_reducedDims[0]; ++j) { + const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0]; + reducer.reducePacket(self.m_impl.template packet(input), accum); + } + } +}; +template +struct InnerMostDimPreserver<-1, Self, Op, true> { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) { + eigen_assert(false && "should never be called"); + } +}; + +// Default full reducer +template +struct FullReducer { + static const bool HasOptimizedImplementation = false; + + static EIGEN_DEVICE_FUNC void run(const Self& self, Op& reducer, const Device&, typename Self::CoeffReturnType* output) { + const typename Self::Index num_coeffs = array_prod(self.m_impl.dimensions()); + *output = InnerMostDimReducer::reduce(self, 0, num_coeffs, reducer); + } +}; + + +#ifdef EIGEN_USE_THREADS +// Multithreaded full reducers +template +struct FullReducerShard { + static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(const Self& self, typename Self::Index firstIndex, + typename Self::Index numValuesToReduce, Op& reducer, + typename Self::CoeffReturnType* output) { + *output = InnerMostDimReducer::reduce( + self, firstIndex, numValuesToReduce, reducer); + } +}; + +// Multithreaded full reducer +template +struct FullReducer { + static const bool HasOptimizedImplementation = !Op::IsStateful; + static const int PacketSize = + unpacket_traits::size; + + // launch one reducer per thread and accumulate the result. + static void run(const Self& self, Op& reducer, const ThreadPoolDevice& device, + typename Self::CoeffReturnType* output) { + typedef typename Self::Index Index; + const Index num_coeffs = array_prod(self.m_impl.dimensions()); + if (num_coeffs == 0) { + *output = reducer.finalize(reducer.initialize()); + return; + } + const TensorOpCost cost = + self.m_impl.costPerCoeff(Vectorizable) + + TensorOpCost(0, 0, internal::functor_traits::Cost, Vectorizable, + PacketSize); + const int num_threads = TensorCostModel::numThreads( + num_coeffs, cost, device.numThreads()); + if (num_threads == 1) { + *output = + InnerMostDimReducer::reduce(self, 0, num_coeffs, reducer); + return; + } + const Index blocksize = + std::floor(static_cast(num_coeffs) / num_threads); + const Index numblocks = blocksize > 0 ? num_coeffs / blocksize : 0; + eigen_assert(num_coeffs >= numblocks * blocksize); + + Barrier barrier(internal::convert_index(numblocks)); + MaxSizeVector shards(numblocks, reducer.initialize()); + for (Index i = 0; i < numblocks; ++i) { + device.enqueue_with_barrier(&barrier, &FullReducerShard::run, + self, i * blocksize, blocksize, reducer, + &shards[i]); + } + typename Self::CoeffReturnType finalShard; + if (numblocks * blocksize < num_coeffs) { + finalShard = InnerMostDimReducer::reduce( + self, numblocks * blocksize, num_coeffs - numblocks * blocksize, + reducer); + } else { + finalShard = reducer.initialize(); + } + barrier.Wait(); + + for (Index i = 0; i < numblocks; ++i) { + reducer.reduce(shards[i], &finalShard); + } + *output = reducer.finalize(finalShard); + } +}; + +#endif + + +// Default inner reducer +template +struct InnerReducer { + static const bool HasOptimizedImplementation = false; + + EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) { + eigen_assert(false && "Not implemented"); + return true; + } +}; + +// Default outer reducer +template +struct OuterReducer { + static const bool HasOptimizedImplementation = false; + + EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) { + eigen_assert(false && "Not implemented"); + return true; + } +}; + + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) +template +__global__ void FullReductionKernel(R, const S, I, typename S::CoeffReturnType*, unsigned int*); + + +#ifdef EIGEN_HAS_CUDA_FP16 +template +__global__ void ReductionInitFullReduxKernelHalfFloat(R, const S, I, half2*); +template +__global__ void FullReductionKernelHalfFloat(R, const S, I, half*, half2*); +template +__global__ void InnerReductionKernelHalfFloat(R, const S, I, I, half*); + +#endif + +template +__global__ void InnerReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); + +template +__global__ void OuterReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); +#endif + +} // end namespace internal + + +template class MakePointer_> +class TensorReductionOp : public TensorBase, ReadOnlyAccessors> { + public: + typedef typename Eigen::internal::traits::Scalar Scalar; + typedef typename Eigen::NumTraits::Real RealScalar; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename Eigen::internal::nested::type Nested; + typedef typename Eigen::internal::traits::StorageKind StorageKind; + typedef typename Eigen::internal::traits::Index Index; + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReductionOp(const XprType& expr, const Dims& dims) : m_expr(expr), m_dims(dims) + { } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + TensorReductionOp(const XprType& expr, const Dims& dims, const Op& reducer) : m_expr(expr), m_dims(dims), m_reducer(reducer) + { } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const XprType& expression() const { return m_expr; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Dims& dims() const { return m_dims; } + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE + const Op& reducer() const { return m_reducer; } + + protected: + typename XprType::Nested m_expr; + const Dims m_dims; + const Op m_reducer; +}; + + +// Eval as rvalue +template class MakePointer_, typename Device> +struct TensorEvaluator, Device> +{ + typedef TensorReductionOp XprType; + typedef typename XprType::Index Index; + typedef ArgType ChildType; + typedef typename TensorEvaluator::Dimensions InputDimensions; + static const int NumInputDims = internal::array_size::value; + static const int NumReducedDims = internal::array_size::value; + static const int NumOutputDims = NumInputDims - NumReducedDims; + typedef typename internal::conditional, DSizes >::type Dimensions; + typedef typename XprType::Scalar Scalar; + typedef TensorEvaluator, Device> Self; + static const bool InputPacketAccess = TensorEvaluator::PacketAccess; + typedef typename internal::remove_const::type CoeffReturnType; + typedef typename PacketType::type PacketReturnType; + static const int PacketSize = internal::unpacket_traits::size; + + enum { + IsAligned = false, + PacketAccess = Self::InputPacketAccess && Op::PacketAccess, + Layout = TensorEvaluator::Layout, + CoordAccess = false, // to be implemented + RawAccess = false + }; + + static const bool ReducingInnerMostDims = internal::are_inner_most_dims::value; + static const bool PreservingInnerMostDims = internal::preserve_inner_most_dims::value; + static const bool RunningFullReduction = (NumOutputDims==0); + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) + : m_impl(op.expression(), device), m_reducer(op.reducer()), m_result(NULL), m_device(device), m_xpr_dims(op.dims()) + { + EIGEN_STATIC_ASSERT((NumInputDims >= NumReducedDims), YOU_MADE_A_PROGRAMMING_MISTAKE); + EIGEN_STATIC_ASSERT((!ReducingInnerMostDims | !PreservingInnerMostDims | (NumReducedDims == NumInputDims)), + YOU_MADE_A_PROGRAMMING_MISTAKE); + + // Build the bitmap indicating if an input dimension is reduced or not. + for (int i = 0; i < NumInputDims; ++i) { + m_reduced[i] = false; + } + for (int i = 0; i < NumReducedDims; ++i) { + eigen_assert(op.dims()[i] >= 0); + eigen_assert(op.dims()[i] < NumInputDims); + m_reduced[op.dims()[i]] = true; + } + + const typename TensorEvaluator::Dimensions& input_dims = m_impl.dimensions(); + internal::DimInitializer::run(input_dims, m_reduced, &m_dimensions, &m_reducedDims); + + // Precompute output strides. + if (NumOutputDims > 0) { + if (static_cast(Layout) == static_cast(ColMajor)) { + m_outputStrides[0] = 1; + for (int i = 1; i < NumOutputDims; ++i) { + m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1]; + } + } else { + m_outputStrides.back() = 1; + for (int i = NumOutputDims - 2; i >= 0; --i) { + m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1]; + } + } + } + + // Precompute input strides. + if (NumInputDims > 0) { + array input_strides; + if (static_cast(Layout) == static_cast(ColMajor)) { + input_strides[0] = 1; + for (int i = 1; i < NumInputDims; ++i) { + input_strides[i] = input_strides[i-1] * input_dims[i-1]; + } + } else { + input_strides.back() = 1; + for (int i = NumInputDims - 2; i >= 0; --i) { + input_strides[i] = input_strides[i + 1] * input_dims[i + 1]; + } + } + + int outputIndex = 0; + int reduceIndex = 0; + for (int i = 0; i < NumInputDims; ++i) { + if (m_reduced[i]) { + m_reducedStrides[reduceIndex] = input_strides[i]; + ++reduceIndex; + } else { + m_preservedStrides[outputIndex] = input_strides[i]; + ++outputIndex; + } + } + } + + // Special case for full reductions + if (NumOutputDims == 0) { + m_preservedStrides[0] = internal::array_prod(input_dims); + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; } + + EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool evalSubExprsIfNeeded(typename MakePointer_::Type data) { + m_impl.evalSubExprsIfNeeded(NULL); + + // Use the FullReducer if possible. + if ((RunningFullReduction && RunningOnSycl) ||(RunningFullReduction && + internal::FullReducer::HasOptimizedImplementation && + ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) || + !RunningOnGPU))) { + bool need_assign = false; + if (!data) { + m_result = static_cast(m_device.allocate(sizeof(CoeffReturnType))); + data = m_result; + need_assign = true; + } + Op reducer(m_reducer); + internal::FullReducer::run(*this, reducer, m_device, data); + return need_assign; + } + else if(RunningOnSycl){ + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + Op reducer(m_reducer); + internal::InnerReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve); + return (m_result != NULL); + } + + // Attempt to use an optimized reduction. + else if (RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) { + bool reducing_inner_dims = true; + for (int i = 0; i < NumReducedDims; ++i) { + if (static_cast(Layout) == static_cast(ColMajor)) { + reducing_inner_dims &= m_reduced[i]; + } else { + reducing_inner_dims &= m_reduced[NumInputDims - 1 - i]; + } + } + if (internal::InnerReducer::HasOptimizedImplementation && + (reducing_inner_dims || ReducingInnerMostDims)) { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + if (num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 128) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + else { + return true; + } + } + Op reducer(m_reducer); + if (internal::InnerReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) { + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + return true; + } else { + return (m_result != NULL); + } + } + + bool preserving_inner_dims = true; + for (int i = 0; i < NumReducedDims; ++i) { + if (static_cast(Layout) == static_cast(ColMajor)) { + preserving_inner_dims &= m_reduced[NumInputDims - 1 - i]; + } else { + preserving_inner_dims &= m_reduced[i]; + } + } + if (internal::OuterReducer::HasOptimizedImplementation && + preserving_inner_dims) { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions); + if (!data) { + if (num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 32) { + data = static_cast(m_device.allocate(sizeof(CoeffReturnType) * num_coeffs_to_preserve)); + m_result = data; + } + else { + return true; + } + } + Op reducer(m_reducer); + if (internal::OuterReducer::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) { + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + return true; + } else { + return (m_result != NULL); + } + } + } + return true; + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { + m_impl.cleanup(); + if (m_result) { + m_device.deallocate(m_result); + m_result = NULL; + } + } + + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const + { + if ((RunningOnSycl || RunningFullReduction || RunningOnGPU) && m_result) { + return *(m_result + index); + } + Op reducer(m_reducer); + if (ReducingInnerMostDims || RunningFullReduction) { + const Index num_values_to_reduce = + (static_cast(Layout) == static_cast(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1]; + return internal::InnerMostDimReducer::reduce(*this, firstInput(index), + num_values_to_reduce, reducer); + } else { + typename Self::CoeffReturnType accum = reducer.initialize(); + internal::GenericDimReducer::reduce(*this, firstInput(index), reducer, &accum); + return reducer.finalize(accum); + } + } + + // TODO(bsteiner): provide a more efficient implementation. + template + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const + { + EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE) + eigen_assert(index + PacketSize - 1 < Index(internal::array_prod(dimensions()))); + + if (RunningOnGPU && m_result) { + return internal::pload(m_result + index); + } + + EIGEN_ALIGN_MAX typename internal::remove_const::type values[PacketSize]; + if (ReducingInnerMostDims) { + const Index num_values_to_reduce = + (static_cast(Layout) == static_cast(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1]; + const Index firstIndex = firstInput(index); + for (Index i = 0; i < PacketSize; ++i) { + Op reducer(m_reducer); + values[i] = internal::InnerMostDimReducer::reduce(*this, firstIndex + i * num_values_to_reduce, + num_values_to_reduce, reducer); + } + } else if (PreservingInnerMostDims) { + const Index firstIndex = firstInput(index); + const int innermost_dim = (static_cast(Layout) == static_cast(ColMajor)) ? 0 : NumOutputDims - 1; + // TBD: extend this the the n innermost dimensions that we preserve. + if (((firstIndex % m_dimensions[innermost_dim]) + PacketSize - 1) < m_dimensions[innermost_dim]) { + Op reducer(m_reducer); + typename Self::PacketReturnType accum = reducer.template initializePacket(); + internal::InnerMostDimPreserver::reduce(*this, firstIndex, reducer, &accum); + return reducer.finalizePacket(accum); + } else { + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index + i); + } + } + } else { + for (int i = 0; i < PacketSize; ++i) { + values[i] = coeff(index + i); + } + } + PacketReturnType rslt = internal::pload(values); + return rslt; + } + + // Must be called after evalSubExprsIfNeeded(). + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const { + if (RunningFullReduction && m_result) { + return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize); + } else { + const Index num_values_to_reduce = internal::array_prod(m_reducedDims); + const double compute_cost = num_values_to_reduce * internal::functor_traits::Cost; + return m_impl.costPerCoeff(vectorized) * num_values_to_reduce + + TensorOpCost(0, 0, compute_cost, vectorized, PacketSize); + } + } + + EIGEN_DEVICE_FUNC typename MakePointer_::Type data() const { return m_result; } + /// required by sycl in order to extract the accessor + const TensorEvaluator& impl() const { return m_impl; } + /// added for sycl in order to construct the buffer from the sycl device + const Device& device() const{return m_device;} + /// added for sycl in order to re-construct the reduction eval on the device for the sub-kernel + const Dims& xprDims() const {return m_xpr_dims;} + + + private: + template friend struct internal::GenericDimReducer; + template friend struct internal::InnerMostDimReducer; + template friend struct internal::InnerMostDimPreserver; + template friend struct internal::FullReducer; +#ifdef EIGEN_USE_THREADS + template friend struct internal::FullReducerShard; +#endif +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + template friend void internal::FullReductionKernel(R, const S, I, typename S::CoeffReturnType*, unsigned int*); +#ifdef EIGEN_HAS_CUDA_FP16 + template friend void internal::ReductionInitFullReduxKernelHalfFloat(R, const S, I, half2*); + template friend void internal::FullReductionKernelHalfFloat(R, const S, I, half*, half2*); + template friend void internal::InnerReductionKernelHalfFloat(R, const S, I, I, half*); +#endif + template friend void internal::InnerReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); + + template friend void internal::OuterReductionKernel(R, const S, I, I, typename S::CoeffReturnType*); +#endif + + template friend struct internal::InnerReducer; + + // Returns the Index in the input tensor of the first value that needs to be + // used to compute the reduction at output index "index". + EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const { + if (ReducingInnerMostDims) { + if (static_cast(Layout) == static_cast(ColMajor)) { + return index * m_preservedStrides[0]; + } else { + return index * m_preservedStrides[NumPreservedStrides - 1]; + } + } + // TBD: optimize the case where we preserve the innermost dimensions. + Index startInput = 0; + if (static_cast(Layout) == static_cast(ColMajor)) { + for (int i = NumOutputDims - 1; i > 0; --i) { + // This is index_i in the output tensor. + const Index idx = index / m_outputStrides[i]; + startInput += idx * m_preservedStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (PreservingInnerMostDims) { + eigen_assert(m_preservedStrides[0] == 1); + startInput += index; + } else { + startInput += index * m_preservedStrides[0]; + } + } else { + for (int i = 0; i < NumOutputDims - 1; ++i) { + // This is index_i in the output tensor. + const Index idx = index / m_outputStrides[i]; + startInput += idx * m_preservedStrides[i]; + index -= idx * m_outputStrides[i]; + } + if (PreservingInnerMostDims) { + eigen_assert(m_preservedStrides[NumPreservedStrides - 1] == 1); + startInput += index; + } else { + startInput += index * m_preservedStrides[NumPreservedStrides - 1]; + } + } + return startInput; + } + + // Bitmap indicating if an input dimension is reduced or not. + array m_reduced; + // Dimensions of the output of the operation. + Dimensions m_dimensions; + // Precomputed strides for the output tensor. + array m_outputStrides; + // Subset of strides of the input tensor for the non-reduced dimensions. + // Indexed by output dimensions. + static const int NumPreservedStrides = max_n_1::size; + array m_preservedStrides; + + // Subset of strides of the input tensor for the reduced dimensions. + // Indexed by reduced dimensions. + array m_reducedStrides; + // Size of the input dimensions that are reduced. + // Indexed by reduced dimensions. + array m_reducedDims; + + // Evaluator for the input expression. + TensorEvaluator m_impl; + + // Operation to apply for computing the reduction. + Op m_reducer; + + // For full reductions +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) + static const bool RunningOnGPU = internal::is_same::value; + static const bool RunningOnSycl = false; +#elif defined(EIGEN_USE_SYCL) +static const bool RunningOnSycl = internal::is_same::type, Eigen::SyclDevice>::value; +static const bool RunningOnGPU = false; +#else + static const bool RunningOnGPU = false; + static const bool RunningOnSycl = false; +#endif + typename MakePointer_::Type m_result; + + const Device& m_device; + const Dims& m_xpr_dims; +}; + +} // end namespace Eigen + +#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H diff --git a/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h new file mode 100644 index 000000000..65638b6a8 --- /dev/null +++ b/gtsam/3rdparty/Eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h @@ -0,0 +1,750 @@ +// This file is part of Eigen, a lightweight C++ template library +// for linear algebra. +// +// Copyright (C) 2014 Benoit Steiner +// +// This Source Code Form is subject to the terms of the Mozilla +// Public License v. 2.0. If a copy of the MPL was not distributed +// with this file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_CUDA_H +#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_CUDA_H + +namespace Eigen { +namespace internal { + + +#if defined(EIGEN_USE_GPU) && defined(__CUDACC__) +// Full reducers for GPU, don't vectorize for now + +// Reducer function that enables multiple cuda thread to safely accumulate at the same +// output address. It basically reads the current value of the output variable, and +// attempts to update it with the new value. If in the meantime another cuda thread +// updated the content of the output address it will try again. +template +__device__ EIGEN_ALWAYS_INLINE void atomicReduce(T* output, T accum, R& reducer) { +#if __CUDA_ARCH__ >= 300 + if (sizeof(T) == 4) + { + unsigned int oldval = *reinterpret_cast(output); + unsigned int newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + unsigned int readback; + while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) { + oldval = readback; + newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + } + } + else if (sizeof(T) == 8) { + unsigned long long oldval = *reinterpret_cast(output); + unsigned long long newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + unsigned long long readback; + while ((readback = atomicCAS((unsigned long long*)output, oldval, newval)) != oldval) { + oldval = readback; + newval = oldval; + reducer.reduce(accum, reinterpret_cast(&newval)); + if (newval == oldval) { + return; + } + } + } + else { + assert(0 && "Wordsize not supported"); + } +#else + assert(0 && "Shouldn't be called on unsupported device"); +#endif +} + +// We extend atomicExch to support extra data types +template +__device__ inline Type atomicExchCustom(Type* address, Type val) { + return atomicExch(address, val); +} + +template <> +__device__ inline double atomicExchCustom(double* address, double val) { + unsigned long long int* address_as_ull = reinterpret_cast(address); + return __longlong_as_double(atomicExch(address_as_ull, __double_as_longlong(val))); +} + +#ifdef EIGEN_HAS_CUDA_FP16 +template

8Cj`VZGi9D!E)z^x?UVuVkU7i1oJW zwY(JX_~436JLYX}WYD9cpDu!cT$|cQtu^eBmuD65Z=8JTNo~>?rAD*PAu2ENC6TQmpb<@DCN9}o^>isf$KS9sxFN>IUtlg1#d6bR)WrAadhcH|gXfv|o zVONm3k}?-U=i#lfEJ*YLeL4_-*K#{2XCvme>!b5s>$T zLI0x3JVf;Hyt7(3K;l6X%`2%kcz4tO<%Gtr%UICIaWSGL9RA}KBuWKiN|=a6m81_J zCeh?Rsn@n5cBIvuJ62OvV5;${u?j za+qb*Nkq?+J}pR)ml@7x4~ZQrC`+mQv@3#?x_=~W=2bY&0!NrsLH@;P^<(I&VV3yd zSSWPGAeF&}q~edR${WR*ntgjc(dUW`=M2sL$!mo0oMYYB1+0Cr_?TZY~IB+BQ&r)Phi zG_t?eY8MWmyPT{w-`vGL@}}3?Xm+};=doN)kiC)6BtjxeEg2BRui?0$_?8Q_g0Is; z%YK{e4HN8(L_s#C^MVmA^ovh)ZI$%@N;R?mKT}Q24F5aE^k1rplaclR2%-OXs)>n# zfr0t|Gu2f69|>xz(?*7~<$Al`YJ;5;d9&SMqh?)ZxYe2ysnVeGpf>mQda-omz2nz8 z7sorQi@Y|>x`yLr4TWUF3WlfzZp17J?u8D9CT6PZUzn29P}Ni!lv4;C#}ibU5kkFR zmkk^nCwlx0Z7Bc!()#Ezz8lbpPv#^0`0FUtP&L( z8~e*o`j-w6&HE?(w6?S{Ify6l@isCuy*jWkJH2~CKm6BHl$n9qKe7m;Z);)&hM=Ul zn(!|fNI{y?5}ql+U8paw?=z^{lZO8S>u9$lI^&Cifq>qi9`XZlYw zlPkUbS81`&+0WqDQYX6lItP%>6p!w2n28NIU6Yf06U*Z_<_CQm(fp;3MLVbFn)a6& z*b`uWdJw|g((3g38~v32f2yE!|4RiGi;Zo~{d;tMPh0t$9+({2m|o3Bj176QlR-}F zYoM*ZK1l!lj|KH|0tbM8>N_c|jr}WdVg~-L5?ub9hMCzTiI%~=w&4XVH9fVLiG-u` z69y{(yHhv)z9atV3po5k3;feM|M4S!>vMeW(?0xL`})=^Al0$4L5;coh3oHggW11J zWNZZg-eCst=;x0bU4?l6dtz*CYJBqHXdk`|<-wa$x-2LPPY5>RV=DX8O}I zKcTTWF)*#PJ~1?eWMFUn*=q8eV7-=|@o!aqHTCQGQPTp1p_!ik6D_l~Fflax`|s%T zr<$>m^}7c3yZBP~oq=L3%DU`w{>u*isuw!x2R0eJfL;h&N8b7aLTG`@#4_k7BMd(}8j?>5V!;wPjt9dp2 zRB9#r%5|lG|9^IMAA(C%V^Y*DMY!Z2x#4JsYV_Mn;x}9{9eLB~!ftY8rSAnd%7F|y zHp1y=2AThK4Ff>X_XOg^97zo!UK4Z)BuGu|`E@qa#qmdkrMb7War+xu;~zpE9XnoX z;2gvj{Yf;*#>f)F`@H!h%ByyeUDz-P9TNhl&9wSB01>fY@?c)9QC!9lK7gXS|v`T4ralWPZ|uWxt#3N2an zLe!;I6=>qC_<5m=8Hb(nmRm;h@0`vB zj=gE@Ulb9^^?(uVx|@%wzW;`asGb0e&mdB@PP@}KZZRcA4!r))_6`$T^5ZiVqeNV1 zWLm%A_E%P~GJnIX>9liBHd7AU*-k+dyJ9kRH0-VDjAaDN5+VP>DtTzvDwe6kG_T_h zkMb>R{t2@x8LspRCG(N{iI4dgRq2dG6-)RpY4+stvv4)1^@4TK&=kyI&t-0_LY@u} z5N^YI9yF?^2!9G-O?SNJf5QoPqI6L$zsgC4!eR{?0hyJD7{SN4RS?1f8K>00k3r^D zJ>H)M!|{4QM857LwsWV}`gaB)BfaRvhaTvC288Q&vf$M21&Y?egWoM}%X$O`^y;t? z@LaX;yl={U%6E8uHxmCTzB|4iyPD~@iH6)U7>kCcdY!%1cCM-PWida(gZk zy4mm*3-bJD;seR67dx0ttf zaKUlGZ52EBxe(L!)9eWLTu3+|l79mW;<99aLL?9%k7SdDlJz-S$_rIc<%^Drt?!2lI{+`czDhzIMGVj<_DL@GvKQE&<{Kl7&m!;XP(XckLH9IP z%Q+y+?x{|G%4#Y1uT&SnU7IwsQwnIEt~@D z2+C6~t2A=U3YE>Z3}qOMybY7hbB29ePLrSyrTR`K?tQ@oOTQ`|Lv?+h?X6>YN@h`; zXrLQ*9imxVaX2ND%a;_#>-V5U*gSzxdp#P9%bjLT@kH>;8Ce4+p825|atP1s@kq`e zTc0t|>J3HAyT=J<>=9>F)4x!9Hd^+2HEJNJix+J)yt)-0#76wU&Q}BnZN1y7*oPD{ zlBdUJcWz~=M6{Ivdd2jN;4NK*7S_LUS^RHFx9CkJmSwu`7Ie-o~EVkOz6Q$n?Idmm3o{7Ua zwjtP*+{hVm-gpA7A&y3Khen8r~;mot)<th>#X(D)Sx+71cJ1seTn**7%_`hImC zLP$vj>-{=sFm*Q3DZQdPEu^xQlg`~~@rMC+8Oen>F^VeZeb32Omn#4)X9$4}B8GrW zK_K<@JmwSQLOfEr;&i9m_6IHXk|QsggjBc~8Gi9pFNW;Qj~kYf8uv*R#j&0jZ$$go z_{{UQ_S%2FcQZ@{AV)c&K99WQR`+lig-ZsuE@L{5&x-@l=I48*@OzAPd1(FBQurhv z^I#0CPPBFlVdCBx6z!;o-A>q$yl-JJIuh+m6|Z_@gY342!&0rC&5Jxe;b(#)k@7vN zO{bkdA@c+ag3(ef4=CvlAUS-%skovB?GtcxY}Yc%TAeGR?oHNQR7rlD1uEn|Cf(tX zP_fP|o3mh=v#sM(2Bq9yas?+FpZeH0-fy^#VY0l7a8h=~6~sZ!TC+)Awm*!{6v=sw zMECI~@(*FfyhR(HYT)QmJA*y~)NWW^9n<*8j{}RP^@fN-b&y7r)}Jh&W97j4-Qudv zEAX4#*vHir|Das&ap9+i=17uu{dyo6*?&_M*a029T|E%q0(GDZRJxAxC7g4bAkdtQ zFribM59NkS;EC6J@g#Jy*88{|z9S$+S8BYFQP{GjDR~-_rdkbVBd)Rvp=TlyGd!$| zBMd6J%oMHP8MR04onA9K&_r|f_qRGR<5$~s-v$#sz|^i(nv_e^l2d6MnEaG?d)BM> z2cg35E?9?VOw`uyi!CNMRbv&tZwWWyL`^AjfPi*f_DZzx$Q6Fk~E?=W`5Q6+)?d+Aq$%$aVrVxi)zz;+R^kdhNp zNAFSYTLtFhb<@xW;-FNdyYT7w8)V0K17H(l10B?F}HLq^V>F2D`uI7s#sM z-Jqc9e36rK&es%gW~&`xeTpBEmHXC1l>PXK{=@=ZbFre54dc*R zl^~(%|2AJ+{){V*)LQ0#11Q(KYz4(eoWj0nEHh;crdg3kkK%x6&jl&?(0aQ3#Rf#k zE#WrH)DtP!_zn(2^m*$yq-;iEJd=8&{OA73*p3femmeG) zWi~Ue2Hr)9hVMtch6`DEiDVnOANYZY8mxHC>JyW|`!zCMe?t_P0uB_PD?LtM%EP0$ zy*I!Z&_QV%wnmbwFMM*oMW7HJ%iS-!bS`J+mp`W3es(j% zP*;#ReGl$BiUaM72SG3VOpy1I$nF+$)(M7iC}RE^ub9lZO7i_*1~c58FMz;G6R1QY zer6eYvAYme`0Lz$297)_9DK|+;`gEF+l^_S&#&tp@V_4(KV~O1^s>>HOO!-+>r#b? z9Xwimqh1aW29-jPZFX*M=2U|aVWnPyvc9An!7QPa?(&Nfg)iCs?D4zrMQj*j7cjRP ze@cAu$`8;>1%Q98^AXl?^Gm&I-BOYrFZE5wi+HKthi*n8cgm^-{kGt~wH;T_yt@*g zI?BEf6xZ;JA0hL}z#41cL0QK>uKh!m)BBB~=9~41c?5Joq&&EElEwj zyE%82Oe*(_Ed}L&ogeqN33sB7N;}gWg z8ZuFx80l$y+N?9T;?ZKd&ycQFX+qlS*F`fh3-24SFCP4Ns`aoj2THT3 zH>q{;H|||qGw7Na5<+2VJf=~Y)7aaanKb2#=%Gix1MjozBdoL;% z(nmAXO~ya$w~zh_BzjI-*L-|1?E2BBgI;P^_Wn_Wpj8c@b3bKkm8z)*k9lHLd&Y3FQ7K+qC3bdiOS53 z>z33mx*MObltEENITR}4>t#&FW_f8E*2}8%K|>T&f_=THL(Pwm-+Wkm_u$)0Z-*$% z8-yoDy{m(fQ^Oj#LiHa9zL~sf@+e*9#?Zv!Iw$x6f`!Z`PPc zvi^eWE)K|3qK%Ky)PCG1YYVQ>d&ZJ?OUhgXYtC%7<@;8>qITB!8=J!%%w?(GZGbN0 zQ&1~C)g)w+ywHDxO?vqye+^j+?#ab~OuwN_#Qp2U#4}s{8WX<9At;2^2xTy_AG?i& zZ&o`z?rUQo7yJ?iJ6?2O%elfGG*d`)zaMhTy1Y>4TZ8}fa+xEJ0~;isc1D}~wE z?vT?{ViI^9LQ3DvQl;Eumqk}h=0TIRhdC8i{b`X(g93qbwJNveTZN=O#JdrV|1h|% z9D%o8WHUFy7u01xNyoJcKF2@wXPbJqPndF#@3P1DpM|I|g4YVr1z`bZ!M83i$3PyT zEVmTI4 z>mi(zobj-We-P+U6Jpk7wl(aoIuF92k5CH0eJ!;yHdeOc{5$^?l-1aB_KK;pai40tQ~F_h~Q$6z$n z{2zg+Jx}9z>V0cfreT;+e&oE?U~s;NZdL^1@40%;u4dcuQ07UjjRlpv@zMmQS5;S| zvQ?W;qw*2j8}pDY^0(^-SUhI#2d_L8zzwb{00?FtssLZef&XD+xibI?2M5BdOfA@d-WcFT+mTmpRLPTOB2%TQ` zRZ~Mwr1O$jBht&0C^^QpG|^WW=<|-H42%Agg3j}x$`2y#88?$|y~~Se+A78K`N}Wc zIS7j3kF(__cjy##aVMYmT8_7{Es@kYrDTpN_veH)32|v*W#V*HVuAwE$vn-6sBp-( z!ovkh>dV!}ehtuLv1s)C8%7zZK-x_n-QfEA4$e=-$V*i3HCIU z6xGGMd}3%)OMkzPWwt%bN*u%H%KBH_Xy3It7-HIfL$MUQlCc%1mru$7tQTA1)rqWg>=0$u>7J&SG8&BIR8KcNGEt${{@-Fikmh zqpnHNG%@IH3|oUpw<#>$D5VaeM$XqeX$O@B6j@z(rLumn5U#kKAZ~etXdYUjb&XR! z=6Fe6N=-xblJ?Qpce-{Ce;;bZ z;|DQy?ktVpwf_~LLS#=9J#CoF!Yj|PQbB$qY69(-@4ZS?_I40i#%7$ZoFZPeCM9iV5X&W9e_0wHOqvT7 z2)3@3@LB1nF_l(VtGS7#8g)$GLGtK1*hAycYzube^@kp9#6=zPLar6IZK!PaBo(?X z(%08X_|{W?*!oL@tTnYHN_ZW+`GjIE@X*S~X1yM^XzHTbp$_>_=zZmlOPm#L&=#D~ z%zTd)FGHDk8xdqHq8*S3a_MWkzVD zFtQ?k!^o~a9I@eDPRtDi~mp-az;Co!<2=S1KSL%3#C*D&*`{b%z_Jh z$u!MgIK-e;>}_@c(m7Jy6c&F1BWh7rdiboRS;X<^_tIi(RC`?lxYpvxp%r^gZDVzp zg3WtXPo`Ig4HWhXX?c=`7upsr9q--PJ`EX)7lJ>rucegYxJEySHx=BL=saXgG3%sV zA_&;r#oQKTvq?Q~$CqsF6$Uy$t+M;3Ja!C^Q5NUFg%|=Pj}XQ2(ksbHfw(&m3-B-| zzjRL{2uX6TBdJI(96p_x5bkf_xa62|c3GZhGs=VjI!!@i;iMu?t}W~?P^K>YM1)z@ zz`~YrneQSOv|sG>I!pGxkg?Z}5IT%S*oCk@70m=lm-ArYd;CnM)gd}nHA?oSr%?A% zU9`=m=kl{degZms+>ulv-`}NY!uV000f=8(Qd2o(!FMIX|F~+`+ss^K4dI`774Ey0_7lFhJXWKJ>1~ zE@QP)=3gaAjJl5b&yr7P^yi}Y<~1+)^h8Wo7wxhnl3d|oiDTWwJk1<&g`WrpSXzSD zDJ2cm=H~i%wbG5iq&D`28H-L-{_rIAB7v%V8WLyPL84{S?5GJ;s{Ic!41H}8otA{n z;s&uh-}nG-TfIYBr5GKe;d34NmR=Joy?VCOu&%Av<#7$If1bkhBP-m{cz9F;kLMd_ zQAH8D@;Zr^cW~1in8HktXAWER4TGGNlopN!+2$wDA`yoR;H1<$Hj6b$(-Ulj5bS!9 zY_LG{r=AK3)Gb6_1gJbyRp?JO{;j^0u6<+!gq&!_h9Y!2Y7d#`!A6E=C7|L1Imoyd!iTvyy9Ygqcc=e`;F$pbz9>#V-UZp z(w++3!y$jtcfU@tI=n7+@`AS`HpEIXeD1EUj|q2!FD%@J7M?i{)OoZ!XGd|e>J3le z08I3kY(*sL#85bX>5q3t zwaqI7yy~H)#G?l3`+N)syj21yFTym-#Ewx^a&SLcSzo@$=&-z~U*)IdN8y$L<*`XyG%$U1(Ki*1{v;QvHFYTs_48g#_*VY=tdd|7xdM* zcUAM}ma%@UhXLwHlSu~k5yb*I?T$JX#0f7l7BnPdlgil67l2uRXs$tBWMj3>>Z`~EnmEE)&)V%A@L z5=?Xy(Gqh|)7D&lGbYZ|iL)Zr3cvz8uDW8Jw&m8kM*CEm8>5J8?B#V9nC{BR*5Te& z-X6i|E6l^zh;1j8Z3XKT7UqmKpQVi|-PQC+yl=dqjXTA~PACdGF6iPyEC@bNMBR~_ z5qlrg*I&!;=nV>UvLYHVDK&UNtVbF}q9$64W#QR`4)|LaK9cozAd_&NAogw5`uFoK zuqQFXnn~mCr>T($+x@G?tc(~29-x1jq028?vVl}VmBV3NrQ>8+NS-$aJ+5I5w*pW} zY)ksO$K5H$i=ZQ=hm{YKolgaI=h^KNJV~*+gpC)2Z>tt7-jr!#X9DSg+fFPPP|OFr z8A82Cz#*8^Jsxdt0xdF@m6r(A?)PPX>#H z>&&m^(}})Ah7#h_%zRuH zEDf`O%vDd#<%tj;S*Xj;q@{EXDka10*1G5)AU7q}TCkN4NZI^rb%n%&Iz6gq&Y;L; zvmn;phCLiYxyh;|Otv=y?#*!03Zg9(9$pstjS~gW>&AOpM=k|_ChzuFrBP=y6GtZw zG7ToIkVNzOH^?=_#kinu4(S0;P23A}`W#}(^7QDh(Ism~uW1*-9vE_sSEF@>YRW*5 z7tf4hn>-$E5>=4RQlK>N3U%~`8{DztEc|YQ zNM)PsUti;E?RiW9550UPKvudUturw^V!S#~riU7QYEXB!edK+7JImllCm14^8J*9$lZu1IIw5=M+bCn~;+tBx<0 z=R}O7DcR%+>8Q+Ua}JSGJK9EK>phq^4h7p(cs`s(f|0rZ)XC5}8sXXLts%s9CvuaO zQD(1?+a&LW&pYIH?AfTwe*`fphIibS#9IfxI6JYr93@+l^a*Yrzq-u&5YeHm;$SeM zn(b8E+39dRQ5!sK!$fB&tJ=A6veR2j%~wQait#VmAZSENaXICxn z`r~ZU50&ehrcEfyBuyASZhnh@b8ulY03tO_DmF$6;!-;`C9h&9yDm35*dXi>?%36? zX1vP{=eki3qMb;iJj9L3+L07)iDU*h)c-4|=DGeb-Q2UvssZU{Ua6rE-s0iz`_TUg zk)u52$&lU6)|h5aBs8r_S}o0ex@N(DGpyq2v}8Em{)GbUf@`L{j5r&!kp>aC{t-$$ zu1fiRJT;j%E`atvrt@Qxtl{3=gh-b z@t}`u%HFJo&_41x=weWz_2H;9=f6v1zEM`i-qXP-vO|1X8GdKSH-0~3d1ykBBYa8x z>=yN_&#&wCeZw&$WIZG&wjF%fx3RoA8m0$u4X_Pl3REo(KqMefQqQ0+EJ_Nwi@EUy z%5>o|X7CwWbfcr8F~XNRN&x{P3`yoe@G~vV;JfbMPX4%eV$hP>euwcg%J_S3iWOWr z*IHb=j7xXtejLrkpPPMOVBmuYrXnW8=D#qfVsG=tm6MNe#Z3ez!-M6!r|R^Bh1i z|FQB=&}Ecbeu);{yD4mx0V0cy?b~y@^9&1fcA;}Jr5jw(`hs2LuLV1ZTo(6Asb@{H zyzIH0uR>P>cdTF`Z~A9P7oD7#OYfW?OH+;E&(6E=8r~6W_+9E?akR36{KcrRW*!>+ z99RrYDYK^n`VI21(VR6^>HK+m>nb2xD5JX)##iE?q-4|bcJ)uF+Ztq^KVKghfYsg+dllZG}^g8qtbV+In`_E8azu< zw?1vkrOLI6rgBdmqSfrCF4>CkSY)gDKSd`ix6AdqF=@|0r9@JJ$=rjN6MtAxF$PL! z^Ar!0vqv7Zc?g6fpzyL9uoLAw5BB@>V~O2!l%De%^>_A4zh6_GdP-{TYwJnu{Z4Dt z8lY4UTvG^*RDCoX&l*kWx9!?6@z8ZCkVRDka=9octzJT3oDN?Z^b8wIeBnS=yqPhAMHs@-ay?3vB;JYLeS_2{=*$!4=s zZyOxp;$JxT0OKg|jj2U9{cd++W~PLJufKA4FKI*r_awA^lm}g;1n*qd@+12{<80D+ z0oi@Myqm2Iq{(Kq34)qKQn1yi{}iel&Hr8#g2JwFQQR1 zaB>#r71!;J-x=11c5Vo(Q@8M>_a!k~i=_qX(IrpRofBv*{eH|s2u%pZ&Zg3IqzH_C zFpl;q{mX{3Ttj4rAS@2`$NJ`Hlrra`-NxpSsl&@jsbgDd;JPrC8?|uPZCGiRB^YqS zr-Pz0uQ}&0=3V`t`{KZGoXRwIWiAW`$ARI9amTis(O#HICmh0n2VQUgaJn9K7;xxC zR%gd8-q2;6S;lJ|S=qHHGbyoGiz&8$z-C}&z|9U=&G(bCx5c2dD7Nfz5>47$a0NVp zBWKIKv0yA-u&|O0J9D`66&gxES1UT^e(brED?c8y@|cd9`K^IfZfWfA2Aj?q*3)cU zL66?BhLB&I^hiarm6-YT7_)?)d%ZeSSzQPhGC!)WSmaxx&>u3=Qri(PL86!uplU01 z&!`U0JFS-Vcg2d2*|Q{(89njQ8kJrHG`T;sR|qph)R6^}1YgFZL1Rj^_V?1KwOX>6@WQe z%?HI<>4Q#c$y@kp%tci@;MeY@QBw8UY)64=UEZ_!y(4F&b6*SXVlAbYJk)Fouj-S~ za2?b9oX>}9g3LDy?yr(~ULZ^!w0boJdDLhUMdLZpXcr#oy? z1oCCaH0652L7kSaigRBoZG=(>z;=YI3Dy(){U(I%clkc%x=&v$kh@G8jGgEc3_DvU zNzW=5Otg`rhZu1VjT^R9m?XNq(wwh)z?}_uqiK2Frv=+4d>i6<-ed=Y?SM=j`VdR0 z4An2?!c?5~wn-dR{<*H=UamyHNc`L%D_bJteH>=9+uRhme*|e-^8qt56kXN23oPy4 z%vPLSYu&+hsb`L-G{e@e_=I-0{{jn!QV|0XMe<|d3X7^s@9 z{{08b&K(jAQAMN&dDX*Noz#3*woVTyB+`&z` zvutOlp=X`xla7{|3^r58IDth~VU`zF1M7}>T4&&0^)bHtI-qJdVdY;SYeq<{(=r)| zey?I`KS}Ip%<6dEcFTVPNz>Y72wmH93lKAv&}_VJNUCkte zr~~taU7{dsofKL`oupSz=E$JdRdJ-L(Y=+wj%g8p0PM{?W`kFjD`wF&!QZwDJ-621kU%&69Rzt?FabfB5baPwR7n z3cDa(XzVNe+q*i=f$bD9ecy>jn~&#lpmxwoE3pasTYvdsp)|L;n#0cIObLb8_24X} zBo9-85&5qNTu$EShF+ULOaM5N8fnW6p)oo!WGAw;2GXnFC^a(cR)vbf=9j1iCG9q6$AwL?j3y!uf$< z8$seks|=6?2IV{=u8ZBm@@UkG+mTF%K*eAgR6z2%dT|9`^NgM&i3k1ujOp;5d6lqB z{-pLVpCKbv`+jgNQOA7iT0dtP{_v>3s%08?+>#KcI`SMlRQizi6t58e|eX zuyQNd=15ItaOd4gPMG$Bh??8bL_CU-wa*Qw0^F0$#ZlY!)lLy!A*_OP`84F{UD8X( zqmVu4hvy!=7Yw8Rc;4t$e@W{VtmCZ z=oACI#6GJEM_B44sN_TD5A+dLl_?g-!* z3j?DiS55_F1e{DL2Qz@F-OEzKrfb@iG{zfr2Gast8A4-{P}VkSkPB0??o$UItWbMB zTOFqH16&zOn|NNkV$Cnu4D;3|@w5YLiKZzbX{tKRHYV;S|7M^i_){chBwoqpk^(8@ zoetUNSIrYF>e?)*0o`Z;q_IW`J9E;>`F&-U7)gika7ls@0pk%(2ox`yyrQRObgcTlp!pNB{+*sDy1C|fOcYE+8|@~QuhGm26b8E`f{~JcFvK3wu#*@W7TSe zwC0ev5_DN=5l?O`tiOgNWA`H!kKldFoAB!hN#+mcXVC;SuIy0}8Sq4Do##UBm>_vh zfBycTRX#DW<&UO0Vqy7qL9(Kd>Fyfxsjt`AasNEn(XFM-g2r#`z5yJvnKG#mTkz1@ zhl>+9Da3r#;UFBeM+#mR6w-33zZ;Wbh3Jcme2&~b!F@*)Ro8;s-Gv+Ze)=1od@57< z+7S<$cl!os;b%EHD^7LU3;Og%IgkRf1z>d8Z(V6}uFdBFxP6?0(3aeP8&}phmyd*C zuZ7!XTPILc;0|uU6h+AXd;J_5zh9Pm@XOBf<(J`MK)Y32<&EC;_ zx>5!c-=CH(#?_q}A6lzv(+&VT<9IQ$1}TyI${lBUDaVnrY4}uXCLBIxY>RZ*{~ARj z#?E>u{Y<=jey`>_D!m-ho z##iB!?E&U%vWaM1(=n{E0r%xi))K!Pmftp+$xew0-iEC}foz;Nu4#-y?#_in$Q1m* zuFzDL&nAC!m`K0uo4oOI^q)_ohkd`3KWti+ArR7XSye#!5tj}={BU>;TEm$JvTHiP z!NrfGrB3+TN>aj#j*&Uq6(QW!+881LK>Mt-t+e`XXUpRZhnm(Te^JIHa*d@eIVCY!+)Ei+1vCkEZ-|h6^sVvj-z7z&~qt|!4EIocoPgdVN zlH1fOVT7ZfG#9BO-@KaSHZ7fiOvBOmKNvfQEm622S(k0wwr$&Xow9A)wr$(CZQHi{ zpWL;2(1SbNPmqy2Bfd~c6{vK`Wqh<;$Eb*d+wQ`=Bj%l~>n$rF(;cMbl+;#0?Z!hN zC}A*y6nK`N{e-bj@mDOGOB>RYqk~0FqbXsod+Vs&13|B;n)HJP&}5nhyUqW#AjC>qxdFcT6iS*+00$J`rg5R_+;YyFMLzdQE*61JG9sr72|A z1^5?9&2QcUB}vH{0I<`%=HB3y$T3$9ooNxxal)M+sPDSB1n{I9#gunQsFOd9_Ut&# zZ2#~Nh5z20eiOfRBFxO=7nub5qGq~!J&1DLSR&MX6#K}siN?{h9eE5L%b8MR*9M4i zpPgW9)JLZSUU^!L?V)?)h8^0G15AG%a72Vj7waA;FD6C}W zTx~7Jlm2B}rmdorI-U?;)si0J70%m*yVa(8kP7=pdpiwL?qy|f@+nS3bd@@_L8>>u zhefTY6@Ak|zA@ccv8LlX#_w!eRD7_7uvQ!`_;*wOKhTaL` zW?C*z;j}4OuGhrj_27368y4+f;VB5Xm=?^n@34~~4Z6o9_T$`?=Cf~=eLSjazF9ur z<_Uxg(1(cr@TLG}&qX_Mf{rYv)Akf=RC;zU%k&$y$Wwr3`08QK&>DZrg(yyaUQd%G zgO0(Lgw{X=MB5720KDHI1Id3LsbezoftG>`U`5GxDLFyQRCXyKXWKj(4c);3^=-W@ zX$!HO5+yXrHM51sc_U{XH|g}}Os!3~XP(HpjMw9!K5Y2LyMePgWRlGrI}{@V^@^Tr zXS~D@)v516qT1y9zuIYS?CZKV$t7noBjYUU7}_>?A-g195A`KZZAz0-UX7GW?2{-m z!`PKMykrb#DsN_nJ3zv75MrU>7Jh(OayIV_)(4v$Ikn@)9uEmiJw(jcquC`X8->}l z-%nM;LpA1sI;)ckVg0Q!@+S$ zEU=^!M=@gTh}(&dCsk?1HRo|2m`>BdU{uG9cy(Lh4WMhIO^=DgQ#tHT(bzev5uOiG zBN0(V%@W$#$j)=MrF+}|4x8Lh(Ew=dMbz5M%rf7gI(u34f!RC76Xf8mjfUx!ZQrhi zZyUW;Kk9@sRa)s5miRxWXi-xAsM2I$C|G6n$z<|d9qP-R$OLdmgYOm%_kr@5geq4%di-i4v_5^TlEbum` z+AWf@yUBbRTVglbX4fbE`Nncl@X#ZJ%3Iw`;KUzMF*BLI4h0^qG{~F zIxGn-w)=bIttWmJFkSR$u0^dlFK9ymRVj8}&5J81+gLZERBzyC8$4?I?;u_C#h)2?tfX9Ltc( zfC3CmL63X9;YL$_nor28Gkf!KvRJns4F|IGtjhX`RXW*1*9sSS8!ZP33e6On#|Cz?Sq*LyVb@tPwW6G#?dpC4|@N7F4!+ZJ$qYE(mf3 z^qonVA{I2)Rp#8`P18vhpIurP501)NLIOzo9rJQCdzAdYA^!s z@tZT}ath`A7j@%WmlGTMOviSmewJlx3{W~tmu=fIyik)Ee1$Bg6ny@4E@tIKd`TZ) zebLvj7Gv*4bKFJtat#w!^-2*0abN|*u(}ZSbkMFMubpv=#Sf8wGy-FB1vCh&${pdX z$Chzz8CIM69Xl;S)iwUE(O^qR*mfYP;|8-o7k?CvE1Mm^3Bt%QnA+>U9Km<}ZBCZq z$f52OI@(rKD9L-i&jifZF9_e>q{bg=t-!)*Y}xpr8%Yr8``;gP8dr=^KmzIMx5Lzw3al)JkC zM-K7CaY!vxVaeFe?AWL8Rx_{CZqr@bV~elzwUz&*IJv?W&!n^vMnFLl9c)cOMC?M> zR@4G?)oSvI^(LniW1`7g*6+g z!w&KxIZob{VGZI)D1JEaz1k~tAyrd|sf@NUO>res)34hED=UfE2C0i64Kwad=7+bL zO40WlaR=xQWz2SoYgvGBr~Jo{HIABmPF+~ZmoO&*OI&#WD%P*o6fShgEjZ!lTK-~L zU0{KSHdbo?bG0>}i41n8dr|We;0AP(hp#8Who3pV(QcWm_pW!4#2}+@I)La?<#&V9$r*j10YG=$QM)kbKihyVSAZ%#?|evlU`i6{e^oNVOj2)tR?<91bYcRc4S@ewXSM*R z11&uXEn$RE6|}4)I-WD8%JM6hg^JFajGQa#Y$0Jk&?8kER+7zS4D@K*_&l7%Z`7M_ zPS<*AFLO#_Mr04RCCXR{lt=&CtcJZhJ_8{hw}>n<)--nJ77ru9x%CQ*isOKi7<-R1g6Jgg&7u_gGIQB-t7ZC(E0HxZd z^xRNLQvbE^TkrQ9c>?sfz&vxn=V8byCgcNhgc829j|Q(TTc=&Gsx% zG=Y20Y)6<(c!+d*A=Q#EmsV50Q$I0y{%E{In}aGVgHK{=#xb zTK||0w*yCT3lsT&kV&NtzL8{r6IPkmf+^F;AqsLOco9`#?8Q(nxfzI@^~`5~|8ZW1 ztVdXLiFDN=(rii?NRH*qcWHok_Da)l`T|*IL>oeh<4hNkt>gpKAIpe&j&Bh)^c${0 za+ZScn{q>wEqLEmVXA7wGZ7t7WVR;6AmS7S`!xqtC&{>oC6b7OVbj#EB<9}=ii-JI zTG}{Xj3|6Z8+IRHRtMOIlK|q!W_O8E+<~w7!ct8D3GI)6amK023h1b~rC!081G2{_ zJc{6bR)-VOjj`x!AcrLh-?$z<_x|@MfTd4uT70~Wa>Tt$Bv;m)KJ%2;-T<&-8Hpo^ zyL!ppPDwL{K-Ck$Q@C)?}i7eA8v$1B8^4+qi9StA?@v>4aLdh;P@bp1P&=v?+U zXaTyRK`77;Leob|S=8kZAo6>SD)$pUWx%kyH9ZGx^+u}???_eH!ZzdKU^Iz}BJ5=H zihx4EKzI@>m!E}6W9xY5dJ+6yRg3}E2`ZL@QpZeD8KZOmA4301RX~Es*hRpk~ zZZLLOj|5kRF0V0dni$B1yIg`bddu|Fsel!b4)SgnfoFx;AHVIG`)r@qzKH@0sq0jr zr%SK$HU{P4l~2|xzB3dCVO4L0SF6S)O$PqvxZtXx>*_&eH}k)Jqs3!j)9J4#4_hIG5%(DMncq=TlOrYb%(>34Zc5-FoVeG zbTi5#Tpck^nuOg`U0(loDBjFcPuOqZEXj`4sm6n!;&<-Ev(lcb^=qRvBuHFb9MLX_ zfZ7XCstNOlq&%z9oR{CF7|mo#YMufSJt*lU>MYNkr{+#$ zyd30@{E@zR1gl#l3X97XS)-4*^IlW#>0cO6R(}cZ#x@q##>=J7JMwHYdG$pwS zO5&-4AW*(tDmEfSKJBVd&2sJD_yLGfzyXGcBwRP?PXB!pcjj6P!omXgHDvnOy8$p^ zOT_}X3Z+S1LkJy4_}k4{Z>Ps9N?;*$c1D6P8egm7{Vw?|RHg=X_W0KOPt=yBCD88e zWt&S2if0d1Yi(kdj?g>n-FE#zq8YpZ`0z%FNz(aM!#w1~!Ocakc}=O1de2p@%D&$M zVR}f;hu5%vpD@I%dl`5Cy>ZluSV;<4;o<^dmHKV78>*{7I7gQ~Oo?q-%eyCXw$1w{rM%XgdI^=#z5XzG_GSf@J3AMwMsS)lz;+{Quf_c^s8L(4@?A^OObZEl%6ueF59isN21dHYY0pwCIDv8p zGPlsV1~76pl(PDood}24FU?WJZE25AN6={B>wRr0gc#=SGUAjwImJ+JT=9YP0iWp1 zuXd?`T8jJ7pMKKyH)q-a-*==0yESo-}?!sa5882{acAWcdZD75pJ1ML8StMkBFcTWy zF@#}a_P3@^#tO<|yV9Z2Kx6L-e%3meh9h8Zda1rB0N@_21#>?pdr@PMUl3#zT5d_T zcG5pHkm92T8TBP`6lmGV#g@XJ2T?V{IynJ$GM+)=Aiyp)ZVcEye}mc@MXM zgVY&&+<^MJ8jGpvj(QQhJSYceRn|-QwZ3!|C4XxSy6dZS#=x{bbM80R>seCC$smh( z$-v$$hy3X3xA+c6x<)clxy64|W)|+nmWpBa$woZh5tXCLeS5|nL;NNZIytswhQ<(O z#lCWy)mhKvvrm^CeV`U&P_;rtg{hujhw;#e8F>&swrSh#CY&RUjU4u&JZgGy{VkVp z&5rceIY>;4$97{^$~G}MxHj1WKt8r%SjDGam;$SrRYMx+ zf3-{6uC$eJx*->maOuxlXxoT})Bqw;k(|;W^r3lQbmDM^pf98&d1Xdx;0gy0>4rsO zSg)XQ9C0(z@S>(m^D!yv3{ssn@<;29LN~ACq*tVIrU(`>zr2FyS%KNm?Kh{h7!!N~ z(9hP^k8+BFvLr-?d~l(*s)aIMEwAgQ!2|4`EwH4^#|<#O`am|dr$OjTlHv?L#&?SF zUUn0PTpuG-%8xGB38lv?))U2Y&r1)hF<+X>McT0pWN;AoM(iYrBxpsC79Br3WH10C z3Jt|=U!6@hOqDD`7mNHnGqEHB;5KeC-i^+BL{}fmz%F>F)sgCzI*Cp9ZBpR4z>(X5 zuB-m)5&P2oE_r!#-RT4P|4n)i*HKQRkzbV@!{r=sj!(jYW5r=!oOQNt&R;FyAZSMF zg({v7I|r=TEr<%zD`fuyVh|`hUf7#_hrl9T;e%$Tl2!4@nB$MJ5F*gK*h$cczO)bNt5>TlrUTVX z_L%hO-}S?QbKH93@3M-n#JplRWE9jwMsYCK=}vxpvdP?RegxKe1_3_p{pru< z+h5(^uAn z8!n2(Qvnwr%taDUnJR!gtEPyW8}GI#Ln668l0To|W?=Cq8grRCLVVhlEl4L;rX%@@ zsj>{>ErC6KOaQB^wF-R^FXW&yFSkV(pny&+T+N<7}JT?{qfq_H3u6Qcd+nwac7hnI&U{7I!9qDb_&U)D?{l z&>w1iV0%V%XhCo!K|ewh*!+g<&e9a#eW*Rb!kmOqfLT4BSYvV;l>%TMR12us9}NHw z4uG4VpPvaYRyz(dRwwgdW|$V~szdO#(fh6+__b^#HEf&Djwk zPsu93b6V=9_1_36xo3-H7)E2%GfFgj#-vFHe zxPKB6sQzyZ(BJ@~7360n6M70etsS}_X8#bR8K5TwkeAk9&QA~@Ku#bWczopK1{=T; zP(ygSzt+xe{}KWqfcAQa=8tNB#`fghO;8SDj2%9V{W?ZwW?^Jy1PI8{5wzPxH7W5! zJg1h;wASy$6|iRjK)i}wURoTwtxxL{+pEY!Sa(Li0NtN@e(9x7=TyL-bbMrDclwI< z4LbuFgna z$r)tJ3y>y2ZM>Q)w$_dk@cEB9Mf3Mf>_J5*)RXnrS)L^P@;Y)r+W-A+0FHAlydFw9|^#_jW!w*-#&z`&yw~*&;|yQBa`8sLfC7oy#xeLRpqV`Y5@7 zioGr`Om1!qDw>;^*ZtLbhq8akJ5gQ*rUx{gy7{JChFh?jtfc%xyi?zM_B45Q7xTXU z;@VoK+$uepXCO(g#YqTZ?iK^6d>b0bzT7Tn{+mYW%E*D60jr?i5*j|v9Qp0e_5w^S zEDWrRe&4e#BE#`tf;q^{{ZAr1Wui`x4B;9q8oj;Ww#SYFkAhGAQr=EE&_J?9Y@*9< z6Fd&!^G%8RfU+1;1s!Y@Ta5LtneZB0;-HHE97%yZW_ND@Q;P~Cnqk@*#+FYY`?)pA zM3oHGCT7m9Cm=g4G-Y`&Q}uH;=GbFynyE*psizJbZ6K5MGuBjb21RBYlI`Wp*RKc% z(($2y$>q}%0?1+Iy=ljnX$a~-dD^HwH2a^7YVU47SoXi&j7R}xJHa~cB z+ZY05jHN8KTEbB02~cYy)Yb@n+OGTyTeqXHG8TvK`p0@xo($MAb%9S9y~dr^dR7&5 z@pN718;LqM2s7RiAnl*vpHwebam&BT!K6Of2 zR5DM)KE70IWV$-b{t>%(9(?W!l&}gFd4sWv9BFh@go5}BGp>bj!WSF3@W&8ZX1O^C zdF49(Tzv>YniZ_(o>}5E;cMD*Q#gPUpaZR7TSy*fX7{9Gczo@Fote2)c8s-(p+@p} z_GR5ca#;nmO`HOReQ_OniU4pm z#raF+Ty7>+sbVhrNz`ZQzPhtvT&g&_PrCeU^O3@e2KB~`F2h*d_~QxP zTsd*DetvWcN<}D)GawMa+9h(>*;Y%1pss2pho0)NEjJdcl>2lyLtg44jm-EQ_SaTp z>InQN5?p=>&hTTx{@8Am)~V+POYbb41(4z;=X~=Y0@*0VL#J-&38sO8Z{IFn@8Y#N z4-JoJ;Ois7?@xn9s%iwUIC#$>|Kvmf9<{6kOuN^fA_?idPrzyJrjhSDw#pmV z`SnK6A(gO2&DoHKJ+Utr<^~en;5Lv^2GESK@+?P97uP9=vC-2%$d&iQZ>P+|?QAi` znc7%=IdAi&ip4wo2^beT3tznqsixB;TD4hrjpRH`RN4aZU|htUef^h>>&a1LTZeS* zl|PhUq7_v$K?X#`qF@F(dvd2~r+ zCR;1i6)ea3U>wa90)9R!QM`g zzTsTzl0$YfRn9(%hmyt(dRid{hM>s%`+OT8n-g289&{~tCOHgvsU{sSy#<9`X9pa(4KdvqV_bSBK~GyQ)^+^4Cdz4=EH)%~a-?9zF4Juocnh2kwNg;!!HyIk(G zPd|`8iE4#~j@`DclP_%gO&9v00Mdl>nvIe6954|&oss_}v22f^m>|CkxkP@x@o|}m z+wuzLs!hHx4Yqh2JngM~`cEFOS)o4Fq?_Roi!ccjPSA7Iytl~lx4^@FfSSXv7maF{ zKt=c+w)}1U&I2eLo8wf+HTe_M(i%UWS9_jozcRIdn4oFbWLqj{Re8c*2p=lyh zV~UgUPm5HT$|;_j=5rZb1?t28+j4AQB&%GsL{Dq#`8P=8YrV{e?oJ^+z%f)4A`S~q z_q|YiC|+jA<;e&Wb2!{3sTF0KHl0?QqQoSmP*!LPl8L00`fof(HK%xT<|NHqv(#Zj z6rj#L-qdj846B{UlNsi(sr^(v%#?%n(0u$EPXsMA#ljI0IeA;TquP)V$l|zvd|Vst z)OJTmW;&xGHHphdIXj2Em~)wa!1V94BnHoZH%#84N`o@cERj?v#1XR$r8yih_V6WG zHlP4ZWGSXIhF6%%eLtBryiwE6cFaoibEGGrM(N;^o~4fN^5ZkE zO@<{EVka0OO}T_9n6Vq!R*QJ%e?rCto$h%kty8FchwgH!n+h6zyVRZzITIDoR8@*~ z`ek8Kg%14{+s_9}BCG8Q+GS`Iz(Wfg8?&l_5%led4@o4s(;y&+Qn3U}s`p}I4tSVRKgZTOHvMbaTx%ydc2OisR8}XebAox3k`b_2+aLeNn2CEE`IkKkW7yBV zEkN$1ZTauN-dMfq^VhD`wi2RbREb&!a~HIq5=7C48agX1`TToX58G;FJ-y%UlC})^ zd<$#4{;F&6q#b|Sa+%Ar5K-e#!TDp!m?zdi3m?%hSC5@l?zJGjLlw^G8m z!Ml$PHPJJa%yH`qGb0ub`Lw&EIHYx)(t9l(>XdDObo1Q> z2ga*F^9LV&wpoW;1dpa2`-rCnFMfB+{Dq+ZLc%iyMxjrXa zMqaDb%G5Fbw2XXK-{choEffvJyqlOgaC(14v{rsL1->GPCI9q{Bm^o9@r1kezM)$F ziw?$!S~qfOLq(~vIAS@mG=^Z5H}CB|B#nsk+moQ0c#=uiIUp0$nqHDq671)0H}}5h zX|rvLH05+jiWx|;$aSgU(nGD$RFvxrP=fH{YKm*_L4{1d9)r_a&8B?onhBOk>L(hB zo%=;ycI+^zp-P_|YYC~@Ge;{aB;q)(>GXH|kHa{V@VKz;7C?B7cR9p%?^SN8W^vNcY!LsKPyOtdjORHH&_ zn3R8lP!(7zYwIjoD#4Rg)iDRVb2yb)<0Ox~^A#a_tT3?6Dbf4AtOQUZ>?&J2sqf}u zOF8&GzdWd7o%qsN4dD9Q9;P?SE>zL?xy{uzVL=Vo-r6%J@fY>Dp~zxBRU~c=XZDQA zT{Z`nuPWOX=3wTFUR~Urpt336ZxwL|Nra%pU0r?xrQq!JA94dRFsxm^`;M`EApl@? zOg~MY{W%jEn&={fG)sV&#LOD~xx_t1FfInhv&okk&Dd#{l}kY7QyhyDCP!9-iQ@il ziKP&bm)9%X6f?rp;l}gf33&J7Sj|5ZX{3#Pt##ya{vsNaF0$O@+#Y_fU2erZ0nj~p z_#3Ht+CpglPXJ|!}yT}bo5#N>2KE~h)aC30*SS)?qoVXHF$!+DGq-ue*oa5dAbPt89h@!IvKZM6NA(WNxt-7J@T=JM zBPtkqFjY9RNFg#(H!@MyaxACHX3TAe4~kPoc|b{7IUsx`dof4oo(Cv_w{hFH_JMqj zHKb;^6XsRgiMc{OqlX@cmm1@zC3@hY$1!jB?R{Z+Iz1{&LG1p?b*{g+6V3$6Tg%hu zHShaB?=W1K!^Zxr9Su}X%E^r)R%g39hlX_!;~XYJpxUnq-mQ97_e%i-a|9Z)5N}QI z;jmT69yNoFykW+yy0tJ-l;fTD!95r((zfgl#_d(?PWAqoNwIYv>s*sGhGzBN3=mW2 z0K0-6%2aKNwLW&m3}!z4sB$^3>0IiPAJl_IWE9gI7pF-?m$351xE-wlR_l zhf$`cyKX(iel0qrwxFyT!M1C2DtHS;!kyuZ4Cxv4Zu%T=ERyZ*1t4pQTxv;4Nao(O zFi@s5;x|ZtnBKe9;&WJ>_Mu^WvwG_~9&`RHgv*UIPHP7ZrOQ*5xF-Y#HEizG+rMHg z5cdR=#mWToNo4F_BB{Mu1FB70-G_3^e+T0KP%FothK2C)08hhG-$UigBzaKlo=G_h zv2;c<`YU$tSNjh%kA=mZIvGt#ODe5NchULtLUwsR&4!+)LYPuYQ9yKVM67R8 zsCu?(pvzUdl0Eyn4>hbUy?n>R7Z*!b>!L99FqToKw_u{=)}+0AacEwgAV{4ABRJ!# z1v*=t)uTjs?C9SI?Vv-aXGBq^D;_fkAupQnubKA7f~Qa(a6RMt$-wXs5yOicKK#GU z9Ki_!KQ=MORtY2lzFejS+Abo_xoWw@KN$zH=gMm;>L0X+fj-1v=lRgexa7V`Qj7G)2 zBx2V6Q#L$lV3IlUw7YcgK}+bd z(|KEfn`W6Ac|6f#@J?UZ`)K^%WSHl+IZp+nKX|Va6#~lz+%963&$N}NKmN7n2in>- zJN4xfl7gvugFs!HOukKppdGiqoB}RheD;~x-ts_tndhjVWK<=9oc%^J?291sH%lFf zevuSklV7%++K5gfFg7)@mB~$-D{%LqkMjPz1LSTikc}amd#0eI zGZ9pC&$c+Fh%AM&GfTSK{MR{0`JHc)fzqr<(!t#~Sk+^*XQn3{W2cDBjv3PWWQ*pl zi!eRH_&koy(ka$gq2QDOmi+7a?q6{aEalg<0R7sFUZo=;rm9b>%eUCCNTzo3%=zM0ygbq0Z9qa!Rc1B$P*@;tDjqgBO~zog9}% zw$Go-Ez*X)i0QeTJ#LS^JhZT)qYMVMVcn1>i~>F4#`$qjH`+ zpP7jz`5%_FBCcGNS2#&)pqA1ts5!JXR}zUX5@H;Um^4NVk)3v~!}3lK!fO>;SP`Bh z%DM5bi}CAvkM*S)4+Zb_5AzF5k|Xi?JGiKCCz|23G(UR$66v#cJ>;yO+L-R>6$uvK z8+VAO#1~n&5a%qemg;aeUp8r-+xMXu3snhPYj$GRMRR{j7*PwR5xY zZx!4|&5m(Ku>3AaJ3R7D2{vFt5dRxeBhyvSBK?Ol_54j!t8f9Hq3S70&1d}68+nS| z-TjT)aQdXWW0r>qj#yS@YfzY>^%lzUY_O3UGx`|}?}BL#iWJ=oP$9>%CX@oFXG^Y# zO_MAkeY#`oPv#y~Y-L=qDFRtO2Sxj@z4*f)T9#=|c9`ndG!8j-RGF_!B8%6!b6Rbg zBF@XNygrwuAs<@JE8devJvco$3TP|1*hpUD-PSGX-XK_qVS}rMA$<~QK$8ocTQt&l z6PC1Jc0vl}`x|aF#bG{+p>P5~2{nGx{tEm$zgQbywxs@QHP1d?B>@rZ{K7>1aVA2W z)BeuYd$+dhAa!3`f`mI6<<(x2YdTw-|Cfo@Y%KO0m;Suvt)-RCs*zMCPXQH@n~?Ml zq#P-dP~roOZKk?+3P%#a{h}qcV|FLD9in+T=PAwnUY|A&Q$@;ZuM%v2C9{LLPpr=7 zhhyA8unISuqQ94HlcYNFmMpBS)U0phJN5--)NQCW3qKRoQ{h47Z8Volepkjyfs5q7 zmbU`#Cn(BfFFkoCE<#(FczpSk9zLs)o&LDN8vV7*d4W^HI>a&DZINqsIS57h@M0{f z4$i_u)3=bd+I^g+D&Qp_J7-A>PR{E;H4 zFXdOCcx*%}S_LKIk!-6&HqEB#&Cjq{CV|U*m*4Xom{60P#%BnL{!)bp_in9%)85xt z>Jx9?(10tiU03i}CHiDCdO@wOeRQTIF=c6%K=qA!#Cz|YMT8Zm)4(*zC=LIe>*8cV))$a-45gV zDP;N@Y>Le)?e5z2X?<)^bLkM$s?LVu!5Q^rSDTz7=9w8|ekv#!w9`e^#HG~|-#8oU zicz&ABuKbHnlgXou@5rWfQ9mhZxh~nN;_;cOq#Ez-(-4)^eF$tcMCy_*55~134wMi zZE$%%0Bm&}qw7B4&vs!pa|-i3Tu(1#V5Uxg$k{|Py1I4{MA4f9gO2p=1v52a?!f|E zSFg=-`Mu7IhXYX(CDjd#!HkGQ;;iYPvG7y)eiWTeu~}ZVgMLWBUNrx5zK}ApfwYj( zVB^l-S$ZY{fehvITL5v+sDo}x9oB1wrpvG@2gqnOpjTnLLq`i)y|?2eILr5v>Tzf3 z=oKqJh91;-{_R5J`9@33Gn zBy~2zPvCxlYA8fPhTES9e9bG?wi(QGt#>+r9tdI>@Pfn5c{^shCF46CnW0+NC}D9DjQ+ zZR|#yyB@>;-Q1E|oP*aY*((@P#v8DP;KW@Ir3mCtutp`Ri!E$)k~sZ!DqpiDh?4)bt-9H-P_gd9V=-ABVi z^ysW6xn|Dc^%?v={MX(}w*|a{=;}kc<&Aj-a$OdVvkt%a-#pigE{e2OU$4d$21|`% z%3;$ImW!<(?VkGrIh!R&W<=3M+#MxoN`$VAm)B_|_gxQmN6* z=wnAsx?4mR9Hg)2yRbRiS%ZHfI5z3Qx@j&MSz_-yRb5{#cFa>5%g&8cry^c$XQYY7 z&!(bU@yT&@+3tpoG2HZ1_Hv(NaK+n#&4qoLI*^{< z<(ryk5#Z?YIKWs$9HMrf4M*t&jTL4A>JSz0hhA+K-1dkSzRv-VGpsrEu{#EWBTa1OK;tq3!z^? zT!jQPJ(d!0S3cO4SR3D>P+fjRV@^ZaJ<;Xo_XpeG=8ZU*Z{84u#=4_-V6lQOEb-k; z3sw3SkCTAdNbXjDL)k1`fup%jO&$koESyz^ghKD^J&2r$;cf8_^Z1|{h2$GnuSD0l zCV_*phEVMXMN8|h_ZrW8rpN|&WkiSvw23KqG6g9_z24TSH}k1pN6EG4Pv5K>XsIx8)m~zajBut zmUP3bO|R@3%^84kRkawBbX2BDRX+Dox4axJm7A@KblS-E3#Oa3ML9fq zWi0@YJex?jkWUtjSCK#5cs~g~X?hF#I^n>RNNIESSg{Qt+;Tti8W6{HO-Y$~8R!EP zEiS^FFSHb!rJt+sr8ew`EFP$L%QD-`;%={maMShKE~;P2l?!KXG@bI0tW`&6t2)x9 z(&*)(k@3=#L^9IB-gXaz>-m$pX)TfC&?M}S;nnVHW)7MatgHu-SP|Lz?O}&C@p8Oe z;Syy~Bm073mxp~Daqn3veIv;AG9BFovi9RDJ%(It^=UN;KgufsI+D5=P@u$!U_!oU8<&Pixx|DFR`C8 zN28nDuUzjI3xOQ4bSypt54wFh@O~kW(Vybo;t6b92=K@f31(7y_mNd&f_(d&u%f|! za>BIrONW^BI&5Aq*Qh<}a5;^vWuuD14u>O^?bgDgJdn+NQwC;fCs?dOnwd<<*n_+t zcbCo1V#f++al8G4i_Lm|@^G}agK48W;ymisyx4UG?{0hn1lahF7^cg)Uh+{HIEmxewf;2%-ioTw@@jx+iZa#n| z{&>nxIpgdZaGZRRa>NMpcqtVEpYg>0BshnB{?{|ei#ze0!hLMtP~oM83*HDr z+R%9dHitEl2l+>{=5xkwE0%>TDh&n2mne=F#-vghA9@X!tu9{U3ntwv@~o1s91_|z z5QIL*2OCjO!r|r$5=HH4;VwMga{t|ra{?P&?M9OA?q{0%havVykgz9u2HW}ibxlS{ z`$D4{)s{=@mFIfnmVXMwQ)-ABFd_K_G=?xA#iaZuVfr_TBB5NI1>^jaeL5jl|I^r6 z2gMPsX@77J4#5YPpo0Vp?!k3%1{fR$26uONClEBa6Ci^-Bsf8WOVA)85Fmu*?%lh! zRrjlJx2pd+*5|G2)2F(A=k4b?z>grF5$dYJu86dP1XSbH zu%J8RaKcYiqY9Aaq&Df$aL}Mgm;n$m@jTW7+1e&hTnl)_FhRwQ=T}g zyFuvPa|6C~gn(Wz90-dGK7KGwJw?2d=Bd390A8+jC^?Q&U@56cZ^jfm*x|^ywMhiu zz`t1ODXqV{#(eQ~Bp8*j)s)ULY7|dW-BWkpM(w7H(n(Eeo5M1v}s+gVGGTy-M?@yfzmj$}|n<6+Ij+iKuDu|kk3=);l z(YecG!-rl8&Vu9h2??;4$7W#y!uk%K1X*(_p)7=Y4vK?=ayoYf$i>({?q(kfbEH#4 zUL<*Imj9w;C6;_gX5w@u!nO}J@EZwCiS=V`}+hi@pMbrYPLV67z)eWx1%BB#-|X zoAaV`&nFYXIV`Xc1nI^*(0@ph;wZfNG_@d~mvFH!U*~U+DwCUI%_H?!X{sDG=Ed_UDKSx`<+^R!JaMl@x z)xM}XDOb0Cc&`}l7ZvyB1CAhWq z&HK-|%Xne~oNh2js^6L(U7_#H+Q=#?Pgsh`RJWB| zT*lOP=cT+mSA5pv)!J{h238ECn3TdK43ei95*IzRbwL7599=z1R1NfdQNU_Cdl4!xnBve8FIuZvJO`5 z#EyMMU!P9JXp=XXNH%^7cwChzOKl;e$d^!M-f3u~;Iao(>9R(GmODx-$*s5(JPaq4 zJO3~>rb=SJm@WZ`chv?9vF!*!Rbu9C`BF7*1P3_lsNhu(xsFD^A5af$8wXoCPI*=7 z$j#6`;(fnrT;8^c_lTHG$VSSN37}dcNG{%D!T;%-g{pqDD`(u#)6@adXqxZuw z)>55A?Kd;qYS*nPyRk-~_93Z^i0&yqNPZ)!{CA9XYU zx7pg}RBwLp0@+0cKtE6@U}~%PloONqu>Jy{5de07I8`Z~Wgvc$$>ciLS(U2tMP}gq zyX_R55@~gJxEHn{&8`dQqCHPAJ+8GRcXRYb$N8XL!&@7~-u40W{rlFd%%!2p5kSIv z4@+VFuG|S?>gf(8UY*R>(pxBe*^$As|9~+rHqyYVM{1&a)BB}^Z=bx2>INte5pk&v z5I7>3iw7OD-Ez+2`56}CulovUphx>9pPprDiO*!;#c-VS5iwm{>U2#|VNrDu0?1gP z;q>E0?@A?802<`LiI@i!s`Q5Gd!`e@ZV7PNaEf??MkgYDolg-yuH}^3pJ}j)7sIko z_?_B#JdxlbkIDLwBXwscPH2BwX6rz^ZXFoC*w8GpXSA7c$@Swmdvs(iDr2;yG_T|v ziGQ3vwzKAWg3*u&jDfFitt|4LE^ z3W9|GX_^lFN2`+u6b|H3aDsS1<(~71t)bWw64>q@a45tX+h_I6#L#{1V^+{@!`2#; zX9F7YP~K6OUeXzp`p$Awp+}Z_CtGa0FJr7roXXlGZ*SliBqi)JC1W!Xzh1fuY8ZI> zsxW*Q@ZtGCWld!iLNr}@BpeZOC_yAq5yuw#I~D@mqC9kM2cM|Wq~g3eq+ML13{0P~ zJ@iFFxnki(@h$4Lg_L1I1?#@ZK7DW>G-e$#RB;&cDv|I|bC60F8(S~KD%7$I?O}p1%t>i=7LNXMT`m@jZ1bk4aFSS znhA|ySjs_LYC3^3!J<+V9HME68ps|CErvSl6icHt+YsXGVp>{>7lHv~D0WZ~J_ST6Ilf?JXFbpHj&i>-CC6bnB zrLKsLk_tj<#^Rh5l`YMXC}}B8d~D4a8Q(sF@>EnvC_0;<5^_d)-^&qzzG{gkQx&%i zN3Jdb3K7Z>Ngp}`p#tu8q~E?4Dl#e<{0%@s5b9AoA{a+AX~#BL9E^Pxxg_nVD@W~z z>Z(nTWTk2xL8XL3q0O#I5~9I@rxZp1Ll?Et0#m%4PmMQ%-HuKGvkz_JWyN8N3s|f% z1=&a~=02(dcNJGw6NJhkiz+L+fZi{QEYB3a*A#*Nx6$aOj6sZ+)X@m6*EvN4V=$Pt zl;QVTN64uf;iHuOOKP;I`>*ICQ!TS@+NkCz@Q*(kezzmVf{)~d+y%`5CJ|gOw0H+W zaWQPA`ZZ8$0)Skna33-owEgS~^H5qAQ|t+Ac&V7zL8oes3u=N3EXL zGBC`Ej)@5zpTF~lix^Igv*oK>!QBFVQ>Pl+1gO&Qn2O9(deg-jS2*d1%_-QqubAj< zEim>tA5&9&{p1hE@vG986>Ql_sG;dj=;QMX!z|+g>S>bXmk|YwLh001Zx1lth{&zu z#aY*^qfgVw_n3XfpLax*W>8KOe4;X>nA9{MM9 z70l^aU=mC@m^x+3Nyt|QIBtDNz5_q~loxH{GOm8%Rm0u;@$~9* zR3oiF0*om%$_w&>rBnz4DFJUw~wo%A@#b_uYfl_9;MNg4#ohM?V z+U$M}YpJbrEoA-9?vrr(6U*z-_SBH*;+4aD(yl2e<&$mzv++LggDy_u?`@f2X=jl=7ZK5R zacd`$I;X|Cl?kmZ<8JG22K%pi8=jfoh>32`x;F+k)0rzjCr%fkUhz0rUp&3H;^;o^ zV3=KoH%pm1cIA*9?eFDL3yVE&RR_81N&4tXE_h0GPo>9mVgxYXk+@10OevdCHcloX zx|&Xe>hojjURt^;Wxgab5OK>SZh&ilRWZ$7$W%sv>`hsa_@+#}b6*v8?&KPXzrtB) z8#ziQAub>wtKS*WGw~rM_e^xmHU!g~7>sWQCDQgPB%7CxHq1WT6F6 zFwZeI_%S(rqHk7aJFe%CGzl~68&Cny6#a6{G~hA6?NHxvdGloJ3Qt9SaC5u#&kBC` z#J`-Mh~BSA-Pdebj4nVKfkN+lF`CY37yshPM-=l#Ur-1#7)E0rKCb=_P0a1DfhZ0e z&4n}=fl$6O1bv`#&z%knjDeXRNLwH~6v>}bkoIqXQ4T5lYnx(gczNp3zFan!gOrZ) zXr4iR*0a7Yy7A_*Y@dAw4y6mo#*@ncy^AIfel;3LOQm(5r=mY&LvSn+CUhY$IeP~& zV2^+ohHVX{uKCrr<``SYHz=o6H)?dPlck?0xRdq0SNHi6GZCZT(>je`H&SYcI%zqF z%g^kF|K_)hlq7x=()%EWj5qdL26KHI^UtSuCz#72H)6>7cbvk8O#Ms9Q&AWKej`)- zvqzXOeHxHHhIK!L@()K_3Vm4c&WGjh^Z%Q}UJUw761BzNb5Ezt5uBeZhx_ zr`WXY#`Aa$G^IxjcBNw85PaHw7h&WxT6d|~C-xU_L}(uH`mgkepczA#O31PK_{NP8 zhb``htSFcxtlY12^g&t}lj1;fC0Vh*-|d3Ecv}k3=Yp0sFc?MH9E@c`s`2_yQ>J2E zwE4h=y1jgg#aCTrS6Uw9KH1#4c1LNkNos2^5bMf3 z8R0feI&Efszak3+w+0fz<8h%4s~6{Pe{3Je%W1vymJ);UGH8SX-}TM_A9tjG$Gj&E zkh^Xg{ULD^X#cCL!{3eBpmQhr^WxJfXM|hVM0zKVMncPIZe)mYnT1(~H;>}+rziZ$ zRIn>_A?4k16P89NW_0CX$qS8V?qSWj0+#c8v{#yZv%MV>{UrY}^ivi}KkfCPMW<+= z>m2~R5u5)&z^Q*0lmAZP;el&C&Q5_!5`^THpV6p#QIn`RtA=^>4-Cn`hX;GThAyLwX z-*S1Uq4@744{?HPrv`;M)%5%+Nv`ywZd9imHb3{8r`^Y<=~;CCO^zxUJZ%eLlf|gU zjZ8w-ygI1g?Z8$N{i2<2)1UEx!4z?*~fpy z9IA%tZu8jg)IA(P@_@Nz9_x)uWFbDceCg8NrwuVWuV9YY)t*(*k^c(4dYH4)Dmk~SCWO* z8uzYJCaxBXwH?E9cSy~89uzhVGeTKinf*=T3&joRy-Hp|454;=&_lu_KOF_eJXA{7 zJhm`&Px>4#Wx^gz)WgwxB#7+MDpHGryPgjR*AN4)TdBnr`qax4ewb9v*rEV#V)~y(+w^7*frKF`#+!=r zx${Yx8%f468`)ABf;t?=5Rs`2)Q*eSY>h=TzZm}f=o1>vrlzPVoauE9GMY{V9I6WQzMS)*~NV??svkB@W8TQ%0>kV<=V*m`d|)1Pi3{ zLO1g-{(LbLekzU?9_p0bHoez%JdogJb9rm$7jp-XNlnQ#FX8q^$2)wgR%TCg?rw43 zdk-D;VSV)efp_1Mu6ij`_@*?J_s^~XG9DQnaGObk zL@3J_t@c>dGqU!Xiu#9(AhW3HI!>}{5dMT(t7aC=`$5N-!mc~K%4Y(~8O)?Ph$hSs z65>^9BizFVw4tYgf%mlakQK-5>HWD*qxN0$;^}{4Qzsj$@qac844*F@L;Uq&ycmGZ_`VY6M_GO6gIeEWx;NqXZe zQ(9Vnxt#BAOSa#7OU@F2ST66xx9W%7yPrOd`!tRxATH5ykf5*`r_Yx|jD1$&PNUfk zr~R7%vqs{n<%m$L@Ke%DCK~7MJF6*i?zAJt908{k4JaP?R0f6IEy;gQBdgLe`sl9H zyQ@8jEBQg#=6!;{6{UkgVOzf@#q)d`3Bf=?2^8z1+% z8hd*&P8%2-Z4%W(<#ACDZZ=&nNx1jXczXIy9l1a(Mht6ZpNR4-dkVb9Ypw#W>F?xv zGB7$WsawQ`6Kr!TOO2LM5-(Jf*nz_Z1a=M(t@An?S!{Ky514> z`Vpg&j384}x~f#CI_*tGzc#gx={8HnifQBH!Qs~a==Z+wm*36k?84Mekl8bRMmw|T zf6XTLv|y~i`*s$#O#5_OPtDmtm7#dD?)&TBPSB@sl2h>=xklbq%nyd-^xfOhZvQ8r zZ1w2)yC5O|?mO}P1pfqjnt9rJYQ0E4EnYB0X?c%h*jXU=QU2gvl=b0$o3z*%Na$D|m{O)5=BqYb4_g=S$ z%}xA_)-F)_eP4Fk_5R1NXsQ!XfwFeXT~;mF%1@$6!C1DsX6W!zlIo##Vh+;+ z+tu&C){EnhyA-fRTfCz+-EP7Z%Mt3?;0>eZzuVLMQ1nREzSOyfDKUQz$=HaSVrbOU6KNCv=12Te@V#7 zb05(?Ip}UETqCi9-3jN{M65f*Xy$~xQ*Ua%ns30)Gv*{FD$YSay@>I3ua{}2B7`ox z@x1i$%r@S22^4nQ<64y*xm)6GavwbwET6Ysch_Q^RX{|GjPy-S?a70=dDcb5s%AFB zAEJl^5b;D3)IBRfj}@|5Y)wVdWJA5N=E8gmVYDABG3xTeYkQRO^K}>UEb!DCgVat# z$uu#d+y3~Mo&VtVE2>Vrt)>?)*|bWT^`>mNHJ5yHz3OB>rW&Cb5_6c}F1&;5tBLFy z&}P9a0>j(Mic-!3?3_P(o1R{ezJuIa%!^fgG;S_(Q*~)gZc`vR`PikHl_Zv4=*^kG zv?RDx`yKOFp$*-+m)V)KCsOGqI(u!Q&>5@i1(lMT>$2wr5%urm&mN^_jB=Wb7h8C+ z!(ul8LCjmdTUGjRTPQ}R6v5ReU9Uf5s1TdX|6W+#ym_{OPY1@W-nN7*{W2ZnW`B_M zr=yzs%ep@LBH?1Vw>1O9bQqnLM|=}d+R)W6(d!wgU-2lNvrkiS^B4T{Enn@u*XOHl z0pX5n$+x9yk9w4Us`RE6o$vi&Fd@(2%8>^)^`H5|PAlDI-sgz6@AH@&~wfIYW7SO2SM4|9=w zrk+4HInif{3n5-1K3)*7fDpe37q0*-FE8tJKQ);3|JFqp4smsbT0bLHh?6@Mn@3Yu z9?Y%a>EvVyadG)aEV_2~?!f2kpD}R)^`UV0=c$4G&yn#7ihzW;K-_}=3iUq&1ghG5 zL4nUP@$<+*E$tyL>_A6Xh=-j!6aw`6uhBx>eB6BO&#V>*b+Lw7I$(o@|9>c0_+KDc z@V~W7fc&8U!odFr4qUFi{&tX;Ab8r`?VQ1x+kUn0^C7d@4Gam>j?Y>Z zR_CI9?}2X}k2?y_ZM)Nq7!0%AxKgV}+mF3zXV@hCJeRww-w2QZWNk$sch2jb9C*@l zsm2lsb-e}aMx-G3?RDbf(b6d(KonQ;GUJ}fzVz8X$(6WuSlIJX;g}(4QERnmiYL?Z z1&!6=SYeZ=z2y@f1(PIhATG^$jG$IC8An3SV|htX0P5!;zI(-+Co1v-y1_qSdDSWI zf!8()f1>R5=g2)0EhaQxdmPYMNDSQlzt--vTnzB}(E-K9v3dTNbM%cifOaFKo{!x+x z8jJIRUJJ>~3JVH@K>Yjy&yEYcBEkZ4GP3f#GQu)40s<1i|GmreJgQI^TMs*+FrUDG zYS{q)4{L>a{;iXq9?8h%uXX>mqKA~LMl{EgjA)X!1>?grlrkeu4V(;QGPzbVlmyJ# z*twjoA=KTeEr6Q9%g+oDDNk!nVrn~AAW9gY0w0q$(NRVfirZ6my7`UhgWC_&?`t+T zx9&E%eb!5M_Iv5Psr+qh zG{bV9BvHWhAiWRLivi&i4$Uahs%Uh>$unV&@b|TCj1xrSm^fQVIVg$E$NOLq`N4SC zQ!HG9Gty?I;_D6u0yTOY%Cc%f&$+YGl91IWn;}NQ6-74ToM5yKnV{iCHui1DU4>ei zk4_r&!B@6_eGt(xCayG#ja9TLKh1eREHc4Sn^x!)&#WPZQ5(hWL$cIoHG`ErXmprW z*hA;~RFjec|=BB6oe)1N<& zs*V~gVFFG{UfT_9_R8&8MWJWBxU*fK2@tCc5AA}5@N%-X5evDS{oC0z%x|DMT zgKVeah~}Etb4b1KRKEqVs{6jUnXK=S8&`aGaF+CzSH1@AxrV{nv@ijGam3*dV>eLjue-UaI=1{!GIDAb+V;>ukwNGpGKK_!QO0#4g-uN)^EOWtlwoyKS$f)VMmn8NigtAVU=@ll* z;lKAhDW)1j5F0mq_`Rlk3hdsf+?k4HQ;r~pvhJ#96tanF-ADs>zeHZp1H09|3YYI~ zNY6b+w2XDDpGI_#19>LSI1+<1Cg#Iqlb@d0x^=sV48D2SI0X;c>F$?^@vW9#)!14J zR9szq^R3ogO-1vqR;tuVDm>`4?5av(28Y+-a|L}g=dWMv>eJ_>Vma%Ev{3U~orojbBDyOLb>8bys@cl|%| z6I!Mnfg_;t3HQ*f*#f7}wcG<)S=-wB-IKnNNFWd&j{q|3zmEUo_+Q5p|988bj_2q7 z_<#S`@qZrw&++v0I{v@ofBffvpO63hzmNa%FaGQ zw;X73zyCZRujBc4`8hr9<8k`A2YCFvp7yb|2(WLFTWIlq{G9KvgMB#SzsKw8^z**k z>+|OVvbEWeeVg888^-;(Ga>uC9eC9H`EwPy*xxPvOq)S=ZF(1NuBY?Q`+0m{e{QE+ zM)N>GhxhB}!u99xy>=x2eYNNB*Za@o#0s3AKR2FAi`$95K+cz+3nSaLDY9=fchTm4 z{W)JBtR(%M&$hWgf8HWU>H_l5VQVwUuFc$KKaA&kJD%_FpGy|{$|BuF9yeCam7X?- zh0xDxGk4MEb^ke?kS6mzcRa86&r9Ttd>zlHO%c}My4uWLv|&~5ckW_-$nEbD(flv~ zfES8qFI$TMTZ_ZoLW{@q2gP8FkJnwvp!GMd?>{%LKY#D_=kIO*508BRJl~JQ>w(HW z9K-qcbALaM?=u?rpoeL(fKQ9Lg=gHD{hK?vGW09%X00G}3f z3lCvXCw;~J=bS#StiVg){qs&ATZ;fL=W5Yg=;O-bA-Ly@2{}&m?#%TI<&7NX@4eps zerS8{KcQ9ctB<_C(g92J0=V3M&H$el1JK2^=q-97Rt?cVk;pkt2#<2(8i8>A`FpRm z`To7_`TOIH-k=Sbe4W_i=fbmJn0W5*-{)EvHh)ih?#GJXuj}!B$Gp>l4)S$9oN;8Q zsPt;G5ISj_b<;mbX8UvEd1vNzi=Cd)ikApe$8wqJ)}{#Z-rCGvv|+&&;ElDsU2O7r zBcAIKdwT$EEe->GTFfo9p#S^%b;NbtT$J;L<>4BGL)kxn@Acoq`g_~+cP96$7Q8zZ zV#q__m0+`LQNTx}g^S=Vw76cY887bCjp_)a8HgR=)8bO#)8d?4l-C{4gaGfTwMKF_ z8aM=ITr0RXm^=PC;#)2^?BERF>H@LgJW~Y#mQN54*>K%wK!?_c(uTV^#!aaK~evFEqGF=7=V7sOr-7 z65p}f6xp|#yIc{;Vd)_wiRz+rr_i#?^ERprl`AdV+7!X7wM{hDyKs&e^dp26GIrG; zeGuIC>5TaI$o*|Vyy(oG&=oxgp-m71#UQJV2t8{`hfkZYXStHL;ptA%37*4%UvOmn zHY^J^kjHL_j_;YFtu{e2d=?5FXIX8NDT=7Z-)%(NGeg5ww9WUkoZ__kl0J0wf$Q~; z?^ygrM71vB(7upJ7UUUOb5~|-n>~WmK;BXf`;oLAicHUC@wjh@d)mC7I((zmMM}iWnm@yF>U zNbVsJrWfcDaYluBcf^?32Qd^~@C=X07{$0=T+bj?BapNqutW=RFO1JN--!Jf-JLn6 z&+4(BzYyABGnZHav=eQjACYK^NS>8&n{LRS(j@Vhi8Ay=&kO%LMbC8v(R`7MVMxSC za6xdds0ALfYyOS6pjW5~WWc*trnyJ#hLkCmd1I+E@o&Hu4DZS4;E5SZt~E=5`YU`U zS0Ia0Tz(<;g5%T;)8=`PFWMs^=SU9eJ6ytNXhRT14$vm|3v4w2&Q{?CfC19vdX7#& zwr@%2V8$S}5otFfjOLC_Mlcry6t5S=HX^YG===TYh|$z%`}s!b2f`ZZ5dp*FcfhTV z4w86{7853tx)C8k`Xmv1!Iom0OfF7f57c^LLOKx#b7D1^RFDo2#BOlhaxgUR^_FxM zunEYk-X57`z~`Zd&|MMaSHx~mHQfS6T;tsXvE8Sh%~kls43IvWAfo1xc2syYNm%|y z8lE7zeULPq@xBB)-sT4{26ZLc^PpRoGKeZtgeSeo3F5Sf@6}+DI4uws&NlG+s0~O+ z+%F_;NGhVBw3%m#bXM1}6>^m^Z;Vh!9YTJJ z!O*kLkKAsL#3O-R;zVr|1q?FdN#g5Wh6%K1=4C%??xi+C zem|?M<4mR;Bc~1dXP$Kq4Yr@>tns-k`U~+{+&|CKc$~XPpC!^Z@Y42NWj0s7=r?H_ zF;g~M6CKAd5~og+I(3R+CiS_gX7i1>q;LH08cy9skQq+WgbNw+wK6@$hW~Ke7vz!> z7iSWaJO4s_7Bpg1<5cbuq$50)d%RoXNisEJ7I8c{q=?y4ABBSeiB-PPU2{h`XBKh%1iMpfEYEAZ(yWpG1tbngt2FhcV!GV#Hra*vZu*>L}?g zS`lPiCrikqAWI3-%iR{p4DQnc+7eR6QpD?A%|^yvMeGHt8S0DQy=N8nh-~zV9G59# zN!F!e(RmVpEr^#R&39Z*ksAFwI%DaUL_asZJL_MF{op3Yq^z&_D3OV9w~MO)Sy_ho zcxam6h{GYFeJfrzpbb@pcpH#qZEHb;6I5`}>Pue5V8u^Qq3|C45|eA@pPZYUsp5;aRRi5M&-C zD`gp5;b7Lcu-X*1HzdXYGkVJZC?Gs^>4$3&XHmpwp~v2JVl}&*Ux=aM3R}9_4~6;W zctr>egV<&?`$S2x5){G014M$)cO4Eze7BLD7KrOm#PyUwX;$v*u+p^oh1dq>gn8n} z$EpIn0uVE7p-^52qQUst0#?3SWQ1p>YDwIA)s+Y^lmYAm%FSMlOian;@|NrHSdTj#~9tTI)r#g@?AOb^# z`Fg~l#%;5j2LA#|3qXOBd9aO>hXB0SbsIQrEEz{M4R*kEfo`#Z^lWUfPuxp@ zHHs7KZk7~@|H*TAP$w(Fpj>=@nbA8JwwVUVx{(gD=HzFM-!%AK+XHEyb3@%^s&jql zb^mTkOAgqr4I6Ag*BwFfNStcxW-jvwh`8MSJ6a9wBP>Kd=bA@I&8hsu!bUl{#-|Tp z18T<9IxXYA;+zY(S@29=qXlU10G3mk#vaHht%k8=X25T=ZVhh%$yZ{U41iMgJH`G0 ztm*)c164z{+{H*9T;P&z4TzX6n7U7yeVXrU{*Emexcz(eA^-yyz}j)G?6|gvdxOj# zsLLk6DQ~@U=8ADx^BTaXpfWgo=GwHOKql{wvMtEdAzQSV$hrqI6GFw!r%+%#uh?<( zDFN&Q?Uy#QOcc+R`8Qw-(|IOG-q*le;1D1lR^^5SpgSvy?SPEb7|T;}eiP=nR)PUk zE;N;@nhHAZ@f)B8ZB1Xn-yLXx=zJ@kZbp+jA9&WOOCNx(%>wp;R^ZDtwED+A5P`vG z?gT1kbW2@AKJx(-7#!$sA9(!XUpt_@34fsVGBmrRW||o0JI=$dGVAGgYb+1#7W~; z5|Y-#-DT|Fkg1PbJpq~>LAnWgP=oHgm_Y3SpTfXka=5I=x8rmL6VU8sFeK{Y9GN&xcMS!>%z&=dHPedeuXUlTmfGu!I zcojn3?Inx&2GR$zX8YXJ2(964*L_4&CI0@H;)B5LFo2JM2RSN~EOuCcQ5B#Cax$I+ zSh2Nk6$=cIvT7us2Jf&T%V8#H+#z5W{0mcNIuydw#TQ@;Ozi!Zp+Yi!hSwY_@jB%g z^pJW3*J187*k9WL^B~;N;OT-KsE_QS)=F_xSSxK_t?0<;7-z5PM5D_?R=JgH5*QmG z92@X_!m~i^r~rCUz!q9-S{TvYH2a3IMk}<_%cH9nAiXqgzu>eCo^%V_MI2w(_TXl5 z2>m6IU;uAmi@=c*!#G9e5_HkL#tH_ofz&!DFL?s)avg_>ZTWXKBOcUaaR?&-etn&jyHJ05 z7*5c-u+##ClK|<1|e_@1sSD&K_WJw!lJBEn1X27D%V(8lq(| zYylVetjqWY>;t1QBZZK5Dk#ex*K|*GZ*5{>3#@c*t}5Y zdckD?JUFL3z5rUlO(fB@C?6`oI0C3zp2abIbDX8tya)0W*vl37Cntz@=K4bs+^A)h zBoUtXViW~zF$cgnKlQ>%1Dt9`0oJvHuy5iyk!&`9KR_1+`h%|ubxC63*7OD>no!p| zVSUcAx{J#KOKqurnu*-@w09^`n?;YOZL|_WjVh2Q65GZ3W zEpAB%Jx(yS2?3viFix)nEkZ!&+B>-R?>!;Hb$4=i*EyW&;W<`{zYhuV8V4;9R>$^G z2r5*uc}akBM**Gzzj9}l7PBk82d=6GwKCiq4eF7+bb)g1pRpqRAlF^;-E{{^)eJ{@ zpuu>o0NzlC1wS)Y;+m9PrP%=uL=@Ge*|tz=4rGVf*Bih=c(5#k8Vd3a*n-8ToWd>5 zj0!laZWY4tsLybDs#E;B=Gc(@u48D)G(aUOap$NX{LV@-tm7S5P=M^9fPGLSY>P6G zUw|!e%`Hy#=*XWyFK7$Byh3o<2*W-Dc;t;UPJ2MTIumU7JIioz{!KsXA42M#l=lkQ!rCj+ zVM1M#FF<(#c<_uCn2TNPul+m5-g%s>7yJrC!5G0SqG4NPhd;#|17JE9qcjW^lExuRDEf%R> ztW_288?X=Dh6PmfKUqqFj3Zm=XY%@IWfX0RF8bA}<18z@KF z1C_Y`eWv=kUVnGf#wU!#Q7r{5kcB6giiZFQ9rNVs0&30xac#7S-`Zbi3~XemI!Iy$ zAyDzwIg*~C5Hxt#iRU^?$hEV;VPHejx>&N;+E4)+kgdr(Rh%%>JwR$;3&Ubs+&T>b z9dg&LEquoV;8_!(1-AvLFiG)X1y;?vcki)Yv!DPOsO4Sd?Ve2x@f+|dFm*<5yoj(q z*KyERp-Bete?7d&g8DRRQ0&HQiRpMDQ^b&FA z8olFixvU+Ui7r$#1B8>`hzj3z@z<;~t3LuH#bxi~|JmN7pq#5>WvMV)O%$lqS9da2C~~SD6~WEXhNZ~)Am}M>L#cfu(>-Pf|d&*-(b?7GWoQkhaOuDCqjUpuk-pq`E@3f>3xVZAAv!P$y!~UZjRY zlEmoUS#Om`E&d?!>{Hpuetcul9^nwZ<1t}#haP9NDZlk35!bG5@|qs!115-Y*B;RV zD9^KxPQKOCfd$;w7wK>y`veJ(BHSBkxM`30C@jchoL0i?x{7eVG# zHaXlgNc*wU;fV`sM_E$-^+7T%5KmJOGnj9?G28~JHPP_{&){*7l>B@W$JiNPfIf&) zuSZ7Q?3uBk`9-Q0I3TibkE>9nnl?Km%V5!~hpv`0HPz-k2n7K$>RE;!_lB{@{$0F1 z;xZtU^n+xxLH!$X$apWuLqS95=4!yp?H4>>ZAh9bw=ZhAVg4SOUW=zL^gmqv1Tuo)_Pzi zTqJEoYy%G>q$yXl*9Yx^KFK<)@??2yQ#pc$j*8^KS+q4XU<~aBMcROLgBj!<05%_6 zuGcU)IKucu;@#YC%N$6v>IQxxjF=6#3KYHR#DlmnGL?`RkL&446Bm*Y|3d6%yf)hF zTcb?<3n3Qaca5U8iats}h15=RlGwMjWqI0?Cm`tN3(1O8IO3(;SZOO*y5_s9huw-W z931-HMcPc;BT6UaId z4R88B2-ifsAWpi7-4H!=b|7zTkHLH+ngWNUUg*LZX6LJ1wh>WOBF>2z53!ORHop7` zLJ?v?G=Vu%jS_H|hF9DIq=f)2=G>|*H0vm!2Mv%G>`kb^0FR47f$~XS`4NbZh2rFe z5a@B}==XKrhfIX$?|m)MT8Qt-4e-~}cwYDe=n=;Ns9*p`VU>c(<{W{3D%VJ(01|^E zO4jr4VVKXKLTyutK|S5Uu}u@1FF+Ony@kc`20X$}Bml@8MFF&V3jp(+eoY`ipVF6K zr1lDoTUcHM_6^vFbzxM(afG#g0X8uCX%~H!T|g?s9Rjq#{#+&i-x}c|dqDLdsrC4G zgq#2xU|l0IH_4)^7=G663sC4}ig}BNm6jy&9;SfHQh*kCVTOf%^}V`W^LMV3bD70C z1_QsI&FiSXfCfVjR=YGQ^$gHAU<;2zXg}th8H7L$Re;wZ(YtgCn@aJy0K)=EBEfil zYeavMT*T|#QGhOVoiv!b@7E=N#l7F&xLOK=yh#3}6cZm(&R|2I5Wq&;B~k=y4aLqhFNZWl{knKmmG?XVC+*3a#>5(G8FWmXQpZ zJqj^t{9Ny9EbkSFI(4OcO4c_WI z;ZuMX$U+MtR^GGeCV*S@I-!^Aw^YHMp9Gg*0A293uu!xk@ms*e$H3V>+zUhEM9Eu> zUDvt+83q|*=&y%7l(-pVf~X1G0X52NW02uZukx zA?hB5NB;xRq5%5u#txQF@RZWVhBlx^2K&;=$TW!J+K>R!3!rLYw-j{%VrBO64bXxL zU7lj4Hsc6D5EqC)fmM*s8(G;xvJZdKr01)twUekrO50r~o+<_LLMFCo{Dmp24R$3Daz{m%vm)AoBK*kZ6 zZvO)yFt_ZC6a?><8NUEkgDSZNk~4cRJ(CpxUpN3QAZAITv5&?Q=8)XCKmw!tsouhI zazsjC+yMxTQ0hS&TXg3^fI`gz8o*U^S`eP?16|cO2{b(8?4CqhfS$(lY>pvpfMFZ1 zZMaJ4uxw+8*oHx-Uo5ZX${;>E2r_XE@&OYBI|Tj<2~~q<lgLF>WL!yuZcNCw2lI##F?c*Ott7HZyN8pLi$f6_6&<&n<=d?Cpy@bebj zmC9uNLF~DR{Xpz>&z2js{G?#!w?Rtvi8&rKi{z$4wns8`0#!JR`34@1X$8UD2jN*n zyS!3~Y-cC!3u!;NdIm^p6BXm8J>ZHGm*dSWNi<^+(c}lQ4dGsnMSPgOoi79-LowWj za^^@dtNt6IAEH~DP(5zi5P%hCr8(GS3zm9b@mWoRAX)5?n{2}>vag5UcLCajVLnx5B_L#Nz-ILQ}hf zzQnAGI8zXuxote2;Vc%dE8^458GV+ABceIfmBI~w0kptP<182->>>Vb5PB(Mn{kvN zt?UJHAp|5v`G$o47VYAA0eT!n>nvg$>J3#CVoiMV7ZNhT9!D}x@4Bj9d=){YJ!2Mj z!<=MjG&v$DaX|(A^#4p4} zz}xxOy>05&i)ao-Y=e|C1E@)o$KMFY!SGXVS9ljk-chb1okZ*I7fE>xVr%mY;aSOp zTu$1=brn%@e7e(uulBPD0G+x>ori!;C>X>*m_t57^9xBEbV^Q=dFEVgHbVz!Hx&Ql z0O>|5eZidoWOM*L2yfEYRc>`28J3+h9|MGar;TpN}CTH<*m_CvbQ^pXMSA3!sO< zymkyQd@2GYn=k~r?ibs}4NpVg z9GM1T+(G8_C!x=i76#S6;N=G~{Dht5xV|7K5pLBN4&|{lJQX&aZa$$Fa;ar z4Nf9_&wzL&F+>!E93wYT{x+Q=FCj%6#B<9cr}_tCe%_LWaWuQ}iyqc-06tA(fAAJg zlW6K3Zp;hXAbIOOh!oeomCBqZi9R5G!&FvAOA1&Zb1)Yqr6dH(Hsgp7*2JR;2-z@Fp!vuY>(cT?M6A;T znE|sdzN;Xo%h3#!1U?LaQZ)7m#Ee1a;JVd$rG;jpGNS?+GDuT@6^Gb^HQ?GB5u|j{ zP)N!+r?Fc!{nN&eys7*1LV;Qw`iKqi6%Qn+rrQL=sk{L4aV3zMIR+B~$103MVpC(_ zCF^d27V(5acXBdhY9(>- z$f;!7v+nsQ72G@@bUKLmqOK*e`7R4c_Bun?t$Eodipq9{JWK>dcP$8dGj$MnPU>|n zBG@Lr)SZXWbdi{eI}dS!6o1Tb_D zt~)^AL$w>bbe`hrJuQ@YivO(=&}Q7jhIk6gQyyuf5>V%4 zelwWthcckkrMkZ`S*Rq%aOL zuit>A%*S$a;voY>=*o{JZ_b{DQFBP<>f%@zcP7*vEp^t{!UNis-La?ut`q&cjf$cR zP5~7iSD+?YiZYheszE#^s`AfA(NN>=73=d8c|iJ=9rUMW1>$jCsVOeY!N57fzE<9t zS2#jT5Nw?wZTOHNcBXHSifU&mXJYo1mev`%JaIND9c1qk$rxjdbSo=?{?lE;pQ{0JdR% zNj>^OV_)shJP~%By&rMzSKE+V>_a5wITq^?S%|Pku4m8q=JhfQ$gKE8SoXU3UQM*3 zMF`tm9p6?i_Z>9&rp}{Bfdq060gWWDQ2#*8A>Heg1&g4+ju_|BBN!ryvDib^4WRoZ zM7g?O5PT2@OeC9b%vQBm%X49#9B%d-0@~{%yDKauIxdn3mWQh{JRHQ2+&LVaek>T$ zQhNZ&ff-8#Wh5Y;qq1l)XYE097zX4n-Qe>%AR4*1!q2IBq;RJaFo3}XCJx$Gdsb3=5xdEAvmVkr-;0mH}Hh~z`SFC&ZoMi#}__uHL zG50W4id>eJNO?qj7RbC?s0_6}3t?jcB4=0=MY9GC@51^3#tRArF=o~zctq$TQ=gmQ zCYlX2YS^nQ8gj@)%j!U)D^S6Cw+SRs1Y|f$bcN+|TSc?!_oH-!Qq!>jbS}@57sbDF zSBm^_-U&4-vjzz-uG5PlIZ^p_gAHx+scJZQ>&1TaDzkvg*X4@z3ocmFJRPIg+I*{} zFWvbTg3_QkJlP0HTm}d{JSsM%*XnlzlJ$RAnc8&ry_hNC--u+jx&#{}{ZQlX`2yR- z?}4~|rtYBMEnvsQpfpmB1JiSQzeS5$K|Ra zJ_;WUHYa+EUuiX?`=j;%;L~BvFc;rR=u~aIzi+bB)y=3>5|AVH}yMZ$yq4@Cmy#Wv9}yIR zG$YL~KH#eKJ!*ij-fNnAl^k*xuynv0!?Y3&5C#uJRr+Z~U(T0xpl~aKAQD8WYIopF z!NWEf(c*5*fU*WVg^iqs57IudK2V6F?9(i^D+YolORsGw3+6R@wlNCsSP{!bQ9)tqCS_epUdL$$@f% zIQpeG+}NqQUl0;Um@gZYMSQJFC;MYoWFt}f$CujqUZ zmSPu41~q~l?LzB1F#WBD3s9e`E#0wgfce-7K)wiv)ec?3B+0&8QhTabuuMZOey2fz+9pDZ(9t}H2gghc#yewSb|!wFKui|E5$mK;03~SxDSD`D z^Bk6yH&k*YF#*!A%Z!4SQVXO$fXa^EfcQB-mAbACAeP0__DgsG?y}QjOp9$ylQVCr zrU^(u=yZE-gbPw1;e%nX8C%OK{-5!nzZh18ElvTq^N8VTb7G$~Z1wA1ys z=w`4B;ZQ};@DidCsQE57hBl7IqG<`AXl(bB)IGLJX=B|X%7@0bjs7^_D+9@~F|1`i z(}U*c#0ZEbVD+4FC?1(|yCE(wE39|Hpz!z%5KC<(0;ETX97Lo8;$9I=TF=%BrI^&1 zeW}|A=_F_(!mEx8SwK7qUtzPHr@+{&lT^YtKvKDp1H_2}qy|Wn*L)2M3rZVweQT3* zd?;EYirwTW3P_KEi-caQR|%kLqjLl4dwM~n!DvX27lmg1_YR1bKcheX-BdQwU&3@P+t3N;EV49uLm%+#L%Qv4!q@0k}r8LAfo z;NwazsRa-h+1gtFu$bs@URhug%osNcT1JjWCy3q^3pX z;*}yZNL37k4|%7}Bj}MEdD=SjcD!@>isuf|<243_3z}dzl)C zKA0!YV6=VbFGg>7NX869@kLk(QdBrz#eC*wnllmw4t)KOe18FB|{QjBvg5o0dp zH2`V~JNezRh+DMC;Azv*+la)&LrvM^bQ~|1*GPk;4Xz^Hf6~fx?3M$l{AJ84+u$Ba z9p|cZM*Bg!I}JHzE1<|IHY%jq(_{bx16H4V>RL@Lo%OZ`Zkxz{L3#@InyRL=WPGI; zAaTgfVf-6aaHA6l33;RkQqlCBjNN3%Q(=ul8gw0>F1FDC2IgL>B5yC~bNXdf#=Ehq zCd{tfhU5&htJ{S`BXSc>OT6$eDeAK9=y7Y;>7gJ%S_2{-*q9+hN6g?um|#PdF~|VP%MUgQux*}f_n>V21*ZTKz61}et^tHP%GD|w5NsUU zh3~Ad1Ib&anq_-Idaj*`OxKqLx!vGDT4(VnvMXicRxKf`&hW5_-UOgOlB3o^Sz^%7 z$z%Iyiwv$VT(@4$B7@uQ5M*CWWlH4xAuEvRabh5e>k#d}*2${?jnL$!Jy$HEg38yM z*>L;-qvU{TG@{r-0BYSr zQg3loEiJasjJqXY0nhl5Da|hn07&?l>O>`gytRdVAjs-1i2G%Tu$#_)TUS-L8c=QX zJ1=@j7Gh|SBFqY7{UZ>>>@gb_bc`x1!A%%_Nvvyym7xPe!CX!)9L?c`$0&h&_og@G zY8f5!N-_fzFZon;qLCVH+@IPtdfX%gAjtyR4P~!%tTVBGk27hOq#DcrKw8nvSF`0j z*ib)cBVyg&>}KjhAgODE^lP6QRk}gvH&g8E4`_d!rnZ@0F!_!KBu7ieEsR0uyYh7u z-IPI~!{%5DA}GJw36dfwq_CDR62}P_4;v8h*G%))Ybch8LY0aq>ZFOxk_CzPO((cQ ziSE{k-{fy5aEq|qdMvxs!Q5zQ15 zb;2e4a5H&@BZp|%VKo6*yGc=yR_c$kf_b(wCdBd!E_3?FInu(_*VHX=Y=Q@NW(2_PO8{n?!t0A9rMTljs= z-XCjlCrJ7;p`3*!wgZd~&_ZIVoi*v>>oLABE%U6?^j%r92!L~9A;NMwfeP>G|IxSEG`T!ukNDCgvC(tpJI$hq3bsIriI>W+mvAkv{ zm&6*(%#yY=beW)1c3Poz$#Oq<-|yUaV`9d^P!4s zLJ)w`v8OV98ZZ+C+%Fb2i(^@_g|0Jg^Qm?gsdOB`TFA%4aCM;T)s>Fin_;PHQ$jgS&8v{>6czXjq&0G`JW)io4UH|U;9nl6;XmC7r<}z&BY=JfjgF;p!>Bl}$#E<9%nU2>Gs`}+!vv730d(&yzmq~G6=0-?rA59F zmW~^1HCJS+{fey?Z;(+sS!V5f^8o19zxk_GC2K9%Z#yge`(S-6Z=I_ z7mMjRjd8G>Y(|4L4G?KLn>unbYmt0hc^U0Z@`YG&)BS}d0qQyjJbAag1hTCORjj9j z)3N@9gMK>BUpmKF-Ak=+B$>e<6Nkdw85g>SHzHK^>ryw%;shj^T#v8aNNtQzkj8p6 z0Zi8PLq|fLo$>P}ReYjr?X}DuR@`;**VhSX@aP6F$EJnzWYh&OixCHYGL3gRn;#s0r}^pSAB$G1J8t4%opUnRClx z2+&h;w$Nt?ge3%knE|XQLkmZNYR6&P!gIL*Jy$I-pV;&FtUC&ip)+t8LWae^kQG3G zI@y66wV7&vQ%As58)aXe%9+^RH3&EO;;J|wz(*SVIWnJuC*l?aKKiM^(P~ztzTOp4 zpk^F#{sKlV)|3y;IWQK{lN)3KesoKKU__^=MajQ_YJw-|Fwh%ABeab%=MEwc)nT`Q z$4rd#v>;Z+q}5ILOVH*X#S)-2jJnq~sohad6eKi9pl`h5N=qU@aG9umiaN`S8r}^QC;>p(l`S+n=+-B; zcqS1>)_mGfhS!3#)xS=-B7vD>a6~*kvL_2$HYK21eI%htbWfRCS_L&MEupsMk$0}= zciXHO8M_J46E%tM1oy2JVsR16HUXOY9{*xu0K-x3jEM=9mhgCY;&uRjh;`^KN{cCZ zb{1edm4)t~%C$9l8jzx+nMm2HNXDJ0Dgh-W%*5IN)g>%A^>8ItBH~sy36TH>5~bJZ z#Nt`HjCfNCc7MnPQU2`%Rl|T>q0XHaz69bLt_J20S>)&i4J@>(1}$*#FM>UAb1yEn zQ5C7o$Xk(>s@4n+fI67E7`1oeelH^0+Gm>YzhJ(L_b^^d18ieVK}3>|C;)O~5aHE3 ze>UHclBc2E=qOd920+^EeqCpd;Qb*2w|EX1eacHFs<(qBVHd_iC1PesWmGI2655gNrG~(WvZ5&Z+p?wdMj>$XvK~SBow>SZT2K#?qDL@^^g|dbVh?bRG%x zVX8fH?t8fG*CN;J0pi=4K+#Yc$z`u)@?Oto6EpLyr@3MW!;MG|wWzyBGM-wtW}TUv zW}*cK^3Dd)=0&j5HtU*1zC`h^n>hxx03_n*smRI>cmNAKJxaUG;Ikp`QsWQl|)j)(x=$}1=+S0;h(WfK?DS}9mhLS)?0Y8PtJ`ZPc{iO_D= zPNtA0RQvmtv#gcoAeFU*K~E(}Y7;Yq{tOLsSkxv)l-ek6o$D-fOg8iGN%(J*Zcc!0 zp@pmB>pJMu+M5YbT?bFK-ehW*7YH1eg;aCEx(Wam*J{PEC)JIVl&P1yTid09nyMB_ zdRUJGj;?zQGB69yILkF~90wMKclBrByoIGPrRPyYt*}7>XkNDW%{koY#f6vOm~%)Z z2+Q$UUi-#}MbOqfQB%+J5GR&A8ITFPrmL+@9wAe?(|3XLV3HxxY+-?^?`cz0UD` ze0Xm4H=lKJHG&PEKl1-#+;6iGxG!lG@UOrtcZ&AJ>L&7Kh5X* zpe?@k5&JWpumb7f`GywO*aKz&d{;@#rxZ*wh zhtx42)_#5umRs(IPu8!r$Ug9408^0XDfuKTPp^OgBmgM%1XxDemv&cm6yP~zvU>yO z7f4+?*+dX|a*kO+*-^MaOj>-=3R#tm3*H4s0PZz!UH ziDe#P$cCb86J~+m&OQP_6A?2-teigXv(n}W3=^Xr#mD#dDeKq{&zDQ!S}S3cG{+8? z`>`^tgQCScZKLi%CL~#z8m7Pqx$f5@sN_UxaUgSG6u|ErF`>@Hz*xd!9SMSuIm*2k zQ_x^#ljA@%48-fWQTB=tV6*uSBEVssfS$p#*A|y3m~~fDz>El>#gqWJe5mrA39Mxw<1RsOV&mWMjTCYke!y z;-DuLF+bWryN(=Uv;Ggcom~eHkTMU8XskX<;5k&D!MsYk`P7pcDnx#C3&3zGvoBBO zdr?-R@ZJ59gexDfk+T3yQsOH(7zF^^Q9cBKD4kzgjx>E8Xd*^u>gTQq^oEcPNaYSo ztefF2Bgajb61;;y;;9b-82Jm}ApoY%4q(J};3dCy(V3Mk^H4vi>D-$w0p!<7UG$_w zj9a3l_-aM~9{e*cnqf`y$Be642qQl@#2Pg`ATHyDtJq8efogd!b6o;Ukl)kPgLWCQ zLC(*i7vqLJi-;boN==nmXt%?yL57ayygaj49V>EF!;Btp@wa}$LUnJ5F0XOwfvtM~@mvUyp9Ey3bIkI!?`2oB~U(2Lk9OcoSl;gPn z3>`sJ=VUT<6(b?QxE>QnmL6ceK7=8lEdqIpuR*2SyR33r~Vw9M-?zWfPOXGH=%WSmPDfT0y@=X&JiE?;_tX->oB8|vUUD{sT(N8aNg{Xu4FQ!+ar$+cdFS%@+w9VkD@G`D$3at_5xwo*!(y{a|kx1b*NQF z;*B(bWk{6sEqSL3(4vD&=-Oa4pEdR6F6l}?dXpXW03W^Zg;s2}r(}Ie-O{wyT=4+N zQ~}mk2}~ohQ(pF=b{h1(C8?Dk!$LHSgaP>zKKKLxKLi6XZ=VBrk^q1+c&;Q%C=URb zuLY^?_QCYR=xkw`0bueOUAsmjK%7- zk}sfhWyO<7@;xr%8cPc>5l29YExMK#3K=QHDF)DaVUsmJJ8cp(U#J4e?l+vd&I`cJ z4OXrqv=7s4)^>gKi)C;ego~OZbJcj%kC`mm=fFr;XL2kEdJHhC&n!o4Bv-)rB^ph36)1mx8A zAPXnLnfq~B>gx4$&>zYZu-eWb*F>=ZO=}K~L*K1<*${VQ7<`stLO9#5DnJ zm^iut_%DARx=Ed#dOQ@3Y#u0(gDX=?R2=$5RCrhufWJ?G(vvL3lIj-#x|QrLvL@_g z$p@Rt@tN-Gx+bb0wzme3SwdYk#?k3!1DfktQu#4JPa1rgye$0-kW%9o;7d8iEHj4J z;TI(0=t16w&PoB~R5wlLH@cxIDQ7^RLtLnVNn9XXAoB?|ki5GCshaN_fvi_?duq?S z@|uQcV)`fxE0kiOYEAEK;tQ#;?)exXKwrexZ$({2tO-d(+6!!l1*2ZUpc0cpqijRG ztNINht7*s=z%(I7J$mMoeFIs-+W;;A;lcaP2d)52HxT$Z5daS^u&OO0W`epy*4_NW z>wJm;hrmc9wrJyKH#E>TQNH=o34mw&0GfKaJbqk5XIEDS;JNdUMg!!#4Ges15iW-j zG)&PVPhq8J^2|wB22g&Oz^bq(Ru80!n~0k)-$=evw(g=(&C0@kZPOS2@?*{FTpq4MiR7%l1Dt2U zYs|2ngT`eOj;78$jnF>a*JUaTvsICNjxh2PU=DspB%cWz0pel_u$6igj)~_7G+2ke z$m(xer^?{!@c{e5lSD6A;f_z{j$iXbX4&-PTk_hkx(x}crm$FfSL&lptY<#q@XohBz$3=2x;3vN=jDeOnsf4KM2rYA z=FqeTqB3Z~%U<#G`na)a?_wD9lL-ATyXKi!CM=7`e~CmZzL30S2{OM*izn!pvEnUa z_#hwmAqgRz#_>~C_4Qml3VEC>W7#zpY$+QX;<^ql4W7Jgp^-%+=m9V8k+sBkyEK_` zvm%CIeE@G~6?VJBdJ#od3pJ>(q?bn^t?;Y$+Xx7GJL}nA0Z-PrcZP8w zG&hrRyV*b6~f}W zJ78>s#K}T@sdi*k_!YzpFg}BSnbUvfft$f@!h~b`bmk}lS}OC!BsW?F>J|a?+W<|$ z^6C+wy=^wrjR(7K5!oZybhXiDOg%q;_PGL;GCn-!m~s)HDg5>-T(5VHaC<@F!YsTWi$WWzbLuv{pa6s8kNsj~+DEirrVc%Bsl{7TC)o<022j$>r zy)Qfp?}o~AG{a$`!0zE<6!UZ00H$r2QGXauBj6olt`UGYAc~v=?YpyDnWyTo!!5({Vy-bg)%+ZbU0016mKznRRr*YIV-@a)PMuZHvb56Q@EBh#M_wxljri1Eo z*wcX#G~5$ZQ>#7zHn1Glhma)D1!~uFxpBw2p>{o4W?=HPziO7$S%5jARIP2vl^lgi zH4V&2DZ(L?`dnJ*wNWCwUzii>MVjX<+I8&I(HI*Ufs6EExa@3IRVZ>wnn zIsS&GBrj1EzMBWFtoCtjQ5rw6e)yI6WuFc|ejZ_3+|Vzj@UQ%hruw1ML;$T9x051_ zOKMRDJ?Vb6fbNk%Py(+OAa@VHR2jKO89gGFx3SeDQ%96@{!Xl6UZ`{TLDkJfRqpE` z5ec?S9^KI@<~v)jvB8)jMr=stRD^QQvq6i%Q_-b zI0}bmqp+-?w;&O44GVupWP}aPgj{NGK_)2|*~0Iz$g(OF0k(ilC^kFsU4$)b^%jrD z!0%dG%u~#+QHD*ya-@QB#8Gnx8y!i%w{e+X!bMvIar)W;bamndKnl&sx9$x99(aH% zcT3S*4AGG3B@Ws$S$1FO$;smo88{{LNp1jghjq^S9rsshp(WIqEaT!N(1^|iZtYIF z^s7!4z;R*H{q`Hq*UD>byhGCSjQ%oENb=+3(+Es+gSF z!$=$kX;q4+CaqUGq*kP}YX$Ihh!X`x7LgWALM4YdbQM_=Tn|b=l!)ux!Em=#Wn!2K zp-n|0>amT49rb8eGh~V=?jA+{w8)@7Aq>ZW*`%t{WkF#o}?Wpv(wGLX6U)dTO~h?aZD2#N{9 zy3kh7n;SF>c zvteC1PKXlMvp|}x;UqAZ^{!?Ww8Wjfitb8U_)^PE0Ak_s24r0stSpCXJ@wz;Pg`VOOoZXrZX5TLtn2=hjKv_5}sop~xb5ffK-={zt-F8O5 zDnJu`ukltj9aB{wg5VpeAdSA>t)qzhA{~*bb3GX=q%p^_^k;Ejutp;hn%koSirAR| zz*Kaqu9BByCpbX$QDEE`Q_n%6?uF!gio_)vv>>j-BdoJO$%@pe%2g1BJtZl|;hByy z%&E5mxJwH#l!cRe26|@7$&Glg*bSnYr+U&fqB?a{TzdveyRYil0PlwU`?4dIF%;#c zDRv`B!1E)l;lyA@;eIHqJo%XUu^MZXXnrzf7+ z#7o^7srCleh8Sh3E?J{R5e+q)SAICg!wrb10UNz!j=IvSsm@+Ap7D|msX>@^7ZX#k z8iCRF-3V(S^ZsFXfCVVUXx2Ron^Kn~fwgJWz(ljpvc*V%Y@z72<4giruf^<{q3HuW z+Z{6m>Lyy!&Y@`ZBs*@F zv56_3qRDKymVCj1`|CJdTkeGd_aK18l@yYsqgxbQ`^hFKacfju=MXHuEsvv^C7H#u zg^5~OPnOeTK3slKOOfU|ys`SieKE7Hy3g_&6Io+P8YA_xFNSKepcB+3a4l;VQl^A zaUzI29K?qv2Ocmtf+i7BQop8uFLpO+S>q!Iy zJtoLRGbSKaBEHS0CFD07k_5Qv#&MyFCR6JN&LI%tfk?XJGX_f)iGt(p8AeBpL)z*Z z2E9<3a0VXghb{%`jQLm6CVS~U1W`v}o4!S5b}DO?|4j0UvP!!^`jOhC<{2>k=L5%P z-X<+hbM_ixY58FuBr(644Z1x;w zrfQ@`nd4y8=HwdyOC3>oWsXJg-zc#q1v!fWGbD!DP(%*WyX`D0h8Lmms`%|D~%*?A=n3R1Z%lntK=zJCy!$keztb=Mmr|6a$tGTw4FZm44)(ljnGX%36PBYS!VGcAu{Fsg)J zC`Qh(lW-Vw;s=b8StR0M2m`Fs7vfymW*i8ozr4-v7GA#!V;e64my3(SZInL%L{G^xG*=u6IYp<20XMuID;^5J-Q6$+XqSf zK)5NYVwc2DbzF|!Q#m4t$Mu^bo0kBv#L2z-!wlYo7L>2>Y#0Iyil#KnX2fzZseZ!% zK)z#!3Qda4G;^d$rR**PqDa_QapP+Z8Y$wb+%p>dprW8&rN$r%79ziJ?XGi0!D3lO z@<2qY-Yfvxr1FsbPYnXskkUFxU+UI3q&yF@$|nQ|2?6QOoKVpfK(0hqeFWEs7642) zNIU#)hamN7)3;b7+zil;vz|zIeT%rBRO!Y59N<`}Y>O3k5+$~XH)P$3YFe>Scjy$) z)H@KkpK6J~%HFi}oyQ3KV0n_bkof8S{-PNym>LgKDkg?(RYRbvUL9$pvK3K?7?l#~@3sY50_rlifR zT09e1R;)dqUi*ao=3FAy*xw6E0e@mgKYb{r=nJoUt=KuSyk5qwvM@Eny_ym~W`Ztf zDF4Ni)aAnAS+az(uwPidIlsWlFp$65BS_Ern;XalgG@?9WgtF=yXtk!OLWTIH5%yg zNC~?>FDKeD!L9@2n~fZh_G8JWBc8Lv7>{e_9JtGeWBFYO9+h8aL0of&4aCp5D$)tH zApKF~Ix)L}GQ@e|3>!79bh^UoQgQ=;u*Q_4lc^xBj1Mi~+uS43dPNCTvl)hwIEOW; zI^;kMLz&`;`kq!&TRjS7Z;~RbMJlqvqiGToS6ry}7(O`=iGBS?jRpG#&;S2T7k-UIdnb=PXG<@ zvQCH0J92KPOES7S2k^KdELN)LlYRYCW3WmYmq`7u>lF0Xxomlgx;IHKDPrFV^b`>*OOj6Rh^|sIR})DPTZ`e^ElTsl44E3cw;OO>Zc6fr zrDTH*GFJTcf0P!;Oze;;>BoG3CVZW0Jbo7dZb0Rc!_Wd$!8fHP5TpaUUa&Q#Ur88Ja6;WJGC z!<-crJz_qga|%)~XI(OfyVyZ!$(D(Qj=K`+0qc(Eccr|;h-H{`A_e9- z1Hxc#Q~KzJEjE^)^uoDBSX{f2kP1y!6|3~CJeEUSLIkh}kz4ZD1XsR*(FTPHVsr11f4oi<* zix>5HOq7{h$ZwgW8y(^X39Fo)V*_E0C%ID;jpfioui65 ztA=&E_hY%MceC2s9)=wD8oOSG?ON~cJV^$Nj(~6qR(>c{xDCN70Q84+k$wuWx{a(X zKx$k(dT0&&M&HQT5F`&l{rR$A2un-9dOjY)R5{Y!22Yj4C{{*;5LA4`jRB)zbWy&= zL&`?!L#l^#nn)wwa2b?i0T;Cc_d2<(uG({1#O^+oLJ3{qvZs1!p_EbJGg&U;E4Ky#>!1M)Vh&5F|4an-wF=K<1Oj;O7$~|)GDvu1AFR?r zlVbGNwadgOsG{dhCQz-|65PLYWeTAKOD!0V55d@a^qD0JJ3w0^J(Mr)4NgA786zwF z&{!4*#KgIV`)l7!k7?0g(;3a7eyT_4k+BPmwO6z(TiTnZ$cnJTkfIcL=ub1We-l~l zj%yc>5I-Lv=J|>h#~u&F{R|JOuI`faq;~J{Fw#_u;Q#4P+hI6X7Bf9oiQ7qtn$+PN zlOUlo2?naXiXiv4yQycOIi3_HzDyZTU#mW&w)BqbRo@}q3X>$`URnBA7+-zZ50nAZ>S&W=qC9>jEk;AWPiKxUJ z?srbA5Pdb(12E1>8*3ykhuoAHTFXN&K9-=>&!-VL{83n~X5CTh4ns}`hs(1E#5U`Q zw{;Ze!Ev`5v)8!Wny#me=@K!nbBC-vML0{zt*YYBH5GPXc(BsJxJ^Q~2m?^=f_~)| zJfEuw{mCa|acgiw!iz#ySVv51QtVO8gV5kN3yXHLt)dxs~a#E(fg0I~kb~ zT%{qfNbOuiRs?;d+r&-64YMM|&1dD{J**BR%5w3g>-?6kwR!D@IH2`2qY)d+jb1Y4 zIn~F+&<|uXm1ep{X3;dwr{;-lXV;SMXinIl>JK8dJsMeK(xI}9Cf7;v(MOk=kRASs zlZo@g8Y2bktlWTVKlfJ+^86v?$zu@Fe28Qd(2CY5vx7lm_)EiA{kqN=PX$pycM z#pH1!x?-x;{ZUs)jJAL*N@^l>eG~PF_#Ot%-&wa955CC7#=2U|!~nEbp~6@)S~EI3Tg-;}AIz zV(73$gRka4&5TGzyqn-v&&{e}Gh`br93~IpyYH52LKIs&Bd6r{72S}EAq`KzaZCzz$tq6!GP*Nin9J zjJF7_!TBErX@N(k)`Rq{xL*=+D=ssamB1gl?%oC(gT*8ztAR2q)**ja>rptZ%KPIr zaIXG7GuLP@f7UJX<_QmvmRq1l%^h4kF6wM}aq#IL&&#?vw>Ua-Yco-&9$#w7gd(z{ zX>sYXPaES4cJHkHLOzo0+khvLzkd3P-)$t9|AMN_!! zDZ^MSXR5SVZ~wO7(018J0-|M_%a<`t}M4MIFc4IA4xYz#L$RarOcyOrwNn`1Om~brAXR% zY--(Q$wuGY&ol6(kS)ut4dNLM#E5)$0zXI{KEbYh8H8mt&@Ud(yz#<>gbxr-VtP8m zLwq*D{g(_x!uDdk2rmaoWz&qcoC5_4gQ)sANgWfTBY#=r#YI`qwI)yofR<%L)Bsk( z1mZUz4QV4!G%s6EAZ$`9K6O!!1TqIJbXSO6Ahgw*Z1OIUNyPMEQXaeMVuDZ*XMhBj z&J!fXWRTfn!_Q@J+&pduNSc!bp`}ZQgEAx~z+rcvSNa?wV^lFBEB@K5HqDrRP@I%6 zFvRL8Z4&TUnilJ_PmnhB_p2YAN;%W^EDW-`w2cR8jF>ZK6b1SoC*qhhFH^6$k!*u2 zA9V7AWWxZxT_YSBTA1&fZA;E_&$u5Y?^0k7pKbcA7B(~6#cM_Nj5Fk{I*b+GUUgcU zfx#xcnR7&W07j-&Fdl`KC)XYoHK!JitR*G5)A7&0 zI5lszEyZC6$G4wMf|KMiCXF>fj1?e@86?yTdx#$lBG&@wSGep2NdeTeriJtlq*1v@ zfvnrElU8*Ccu<6Us^~#xER7IB2r=5-d`&Jh;z=S=$ILMVUw30B7(}v2n{L&LBv}Dz zy*kLWY0XU}B@x@Wl6;WfvW?aX$qe-fVvZ|P8cLgdy@b^i2?TKqTJd z;_k}$yF~5)@nuLb>KA0h{%JD3G!aV^Nj3}0DUA$|ejTt#Li)aqyQEHvHlvaKPWO70 zx-|Mn6TcV((obZh$vCc_s_&%W)U>I)3!-d9!UThimU8-h$&X>!M&4B!_h=So6gTBv zJ(LTwWbBWScvD{kwFyTaGQj!96iDi%)&XU1Hp#IdZfdneB=0MUjEqey+cC(DuZ3XS zEIsLFjs2M8*-t90_A{o2wrde0n=Tf8aTWI;u=5s}c7v{A|;wIka&LJ)$mGY!%F>OzP4@LcvgkHRjz@H;ctB=SEo6I7UPz;t z5wghKMCpB|*-DHgCd)^goO$3bG`f<=*%*N&qjn7O%J5oV4&uRP+Kh*zO%E@CY#sMN zl!!GR@9Jm2L8?uJydH}Pk^zEne|ny~nmz=n$xfim!z&!3RPtrIX%Ml=$gig~Fl9JG zWjtO-WJ#w+A~I_=UsDZYs;o?Bd^vU?Q2)QXsinL;YC3K)VgGQ?H{#p9OYcBG{isfm znM6Nc5u{DJwI>i?#Z7&WB8cw|i_|aLW^@TF_?CJJRMuf+JT5P*m%$JmM^9jPMMmhB zcm{C_SD@%@{^_ zGwF{3sf8WfGP2e@>^2@S!*%}&e?p~7hfLaQsKlKJ$mK-3ydt`Kkvv>rZpsNbUiKvs zGw{%4JgEqZDAHGn(kD_rbbrW$UgXwNM-9Q1dsa_}|z0CJt z>38!9AryN+0h{LJo7uzq9~{Kcb&#d$zoou2W)Pn*(s*Z^B&mE3=;fzR2#>0rdJbneUK_*^s}ag;%8bQ<(Ax)b0xOf`soWEwm~nMC^24@vduQ0Y(9#N@28D+4bsi3 z+?AyO8GWJ+rRL0QG~T-^pKf#HE`^FPMtNwGBocvbkIJq$ZF=V1nilL|*1CfziYQ!9=U_+mlolfi)7&&4q*b>gbdd4w2D^5= z7y*b!-ngq@BZ-YHL*FbSC)RAU^^-bkkfdZhYeS-N{M-&_MpPbl*TP3~jgY-gU-{xGAu9&IIrtT=%$2uF)rezA++@!&j8~`pY;14vP(^kQZC{ z$q0a{y#p8m0jAgvApK{O?^es*$@3dNg!F8)_(M0@eDE}hgi^p0LbPCpy>??pIcfX; zops|f_5Xv{{@K=ds*bfw0}MMFK3UDW(jZ^hMwMe? z0y!L`vM>*M7Kr%=!0CUr@Wrz9VJNc&5!-Ri zPg@C)QwW5HrbU6)eR_)xX2;Px`cx?1jLXx7v?v43FkD1g!8|m(J$mXTjQsk7MxnuY zhm4XtdL~@JuL%H@?g?P=TsH;v+R`k*{JcAWAKwBX)@NAe2CR`=Q+)`Fh83w>30zrc zR}t;oRLMvNkg#flJJ}xBHBkY0F4wKpdyNa_dVVI6Yok8E{C1$)>c$vmWmG}85W)cS zOoZSqdrOQsHC3Zvtj0wI7=1S2qFiiHjer4EoqdbV+^bxB`*_^9NilkfyQZ*KtyXI%5L=p!)HpsIM=|}(V;p41-n&_^n-z1WzNurXwzp+u< zNNhcxvLWo_;0~!%B?4y184jhtE-82ABo@aKN-k}a$gs-30u8^G-Lgdv($D!@e2qf@ zNi5^!-IyzgDx0@ltD+$JXbEkS+-9CR7~)ZZdPLe}4+f;v`$|)f< zI3+T(M1_n~3t^TZc%2|4En`H0*>0stUWD}FsnmH>YBV6F_=7M_CJ}4QO;8Mge&ixe zB)Uj~MOX7}lbK5n7Lw$KHWNZUrb-IOnT=%uzHgh>MfnBn?~pyK1IY86scLWqvvmqh?H7h-QzP= z0U-rbcSTHsKt?x2WI_mY_z6gK7o_JWyi4w2n;dUE1R*Af^!=?M(m9ZEPTmy+iPztX zpzE9zNn;A=(Sj+`uLrj3vpYW{$BcLJuvZNx!%u5I@KsS5FFxXzBnhDF={}f}qVA z9)ZPP`tDr2rCE@PyY$k^ucvw~K-o>-0^@W@{S^q?ISfx^wQ;9Spt?(wyjcX&EpF=G zxaWCz6kb5Pp$U94!)v$|>48>nie7@WloUjL16i6wo77O;PGB|B6A_wVel>v)u+ z8K+{C^vgy=t+>x-mbiym?=?PLNJAKHG6(c#=#)q_+tX}`)k_q#VKa7?L1}5Kjh_{0 zkRIjRgif1b^t8#spz2Ga&?`T>0@5mhce%a*^75`-A`3{1b2d>+04C-FM3FStGA$5w zO^Y5Ik2(e!x<(TR1kEFLgu1vm1bwF4OEGJ`D=aR!2dj=U+ z1Y#~3)g24OevLG!NH^)lBGdnHwL1%u=}D zUXx7aOl{7wEpF;*5)mFwH-z2HQ=>4{2$Y>719I%VyZJ#<@cP_DbW^`}{gPv-1t9Zi zj9A_Tz^Ss>?6(U^?!$*pda8)HL5hM~5lJZxq{%f%UJR8f^=Pe#N+_91;mo_T5+FS< z9YiIBrOhnT28I9sU7g95B{{Ms_fAEUkV8~O*19R^Q%w9tC;!_Pk*j9U7uI7o zr~`LM=27FNT#t<^7z6I|`6SfI+XLCLE}v?{2*_D2knWDqoxcvkO)wn5eOaC=C|OSj2uI;7M5^6h+%?5;I~Y|SVn*3s%PpD^-;UKpmAE4on(4&3s+ zRWche>Ao5vqSIQ)^s)tEON@NZAax=JGGi1pPF`9ad;7l26YW&l&Lh)a<7u%*=aj9BNAhR;1M#XA}z3ZZYXzDWa`}= z;~G2CJg_lc#-Po47b%?9SSdJs5CvaClZ4sXEjl97!`LNm<~A(ozzl-yyTrtV&;o#I zOH2gt(op6q75%Lr9M5PE5awf7Ewbu5D?v1fGYZv6{aXYw3KBcbo9wyi}|@(?C^~KRzVt*UK>=u%t=!|<`13PYK=41+=fyDyi8(Ef7XI5gZ zOg^JNe#F-1$0#pqU^%qSTgp^QFeXk~l{>o^qpOF$$tJ=eX_Vg-oZ^vgPsaBYLM3fL z9#&_(QbOcd9pOw5e6PdY5gDp0CJw)9kGv92(~(Nxbcq{x@JT$fiuMy&ib0@r1jI1v zamp%HDsY<5nR@_}E=4&#(I>69IiNQ2Pw=DX5mP}YLT`K%z$pe-zyP+tnXUiIwoY|U zBgMX-g^NDc1yEP(Kr_i-)|U@p|C3Ju6bj`{IYrcof_PnYe?7k&)F<;CJJi{b^XGSY z4v~3*&BsQRx&6}ePJ{i$(cSt?=v5yn>-SS(yArJ6wXcZ9&lr)icMd8hqbz{&1pv#0 zQqsd4t1;=Ltm}!?7#n{1yEb0kHE##NP6F%`pw`ek7q~+x+E$KT0JJP^4J^%1R z@S7<=lwn-tR{_qVQ^6pQ={cqYc)q+IZ`-84JvILBDr?E_=3Q9ej_*i+Bo^R2F92PA zfXDZTD5zcowUh}Jyf2pWPRafS6WA>@^w^Ri+agZl@i9Y2WdTg7QQy2Q<#bwns&@;p zvu`r4=|iRI;dGbVC@(+3?`DT6U!DelK7Ik*iUokXKm-~<;uoamBeC`*!U8E2|zc_6*FFOEX z^Eg&A7XbMHcH5JHQp}00eJetM)m6$%v|09GBfx@>0A`&tTl2343_$^wN&12Rgx~HF zw57fT%yD$AOZ_F_CSaVhEp!N&8vtkyEccmuEK_Tu0xlrq>Fo;(0z`uNvkL?)D**sA zANY$}W6F23O$U;=*lVumB>||=0G4Lqhy?R#dEbz+jD_=bSuv+&Q&Iq&vciR;tk*~R zeWkNbS^vUeB7KfZ-{A$|MS&tYYiKZhL|&|XP0lP@0d+%#X9fj&=`!6tf~KcN8mlr& zkzqV+q7LBFa7=;P#0tjJly~=o<8VI@q}th_2FAK0z^>?Pw;9m-2U#}o|O zxjJ$%XBjuIZ!8*gtPN=8&|ZI#8i>jlz%BdZ2-b0xTi$`^R+$H~ z`M1Ijz*bDkkOad`(PWnS{{k9<7)IKsBDWh%z{OsY{kxS=zy(8qYhvO_`7$lIk)E9e zcvgst%qVmIu9uP_#xwvtivxzc^hy!C3aWtCbjktYW4a$$V2LXL51;)4L_OuY7=ao_ z_O>~vMF7nuFmodyW6-Zf2sY}J*m1jIx#A6sGEeezhklqsbTv`{@Q{Xa*iDq`afPl0 zGj`;K-spQr`qH2N63kP6<_DtK#AgQSjcoCmV+^ZP`r!iJKTd*Abab6m$@k$T-Y>U) zc#Zcv?Z=HhqFec4SHzWU$~Sh_pwSH(zU&mdXKDxF5eYhEzZ9Bg0G4kkiq%%{P}p`u zm!N5;gLWLr%pX^V(7}{%OAi1cpyfw~aHjo!z*~Mq{TK_mePy3Fuq2|g;GJp3Rzv`{ zPOYkvS^{t*HFhj70Nw()f!GH0MC0Fr4ZyB-c=q1_bZri7nH&eB!`3vL7ph79E>?0s3YfZd)o*swKU_7&d2^7lSJ%C#AB{DG&kO(?W zabP~UZt;tW7@aUUP8Cx}qjZO|6N62k{9&?ePiL@+$^85KEdyZmm{GEGi<&i>xPn;x zx9si;%A*D+$$b&E76VcC+fv3%QG+rUC(z#S%h+@EmPsnwzwSUiTq8V;>n=JBX8q(m zl{epi)5G&_S%eXL*zpn3M zbCLe|*pu@5BUpf_3A^<3f2OPW*?V(w;*a`R1_Bwh&s#2mfHt}I^`&4yl*bW3AtPu; zS==j_S||dGavnh@)~6V7J0bu|b)wFXs0LWH!B}rp#2w5M!0qqKhwyf>Cme$7b_y6f z6dwST?LvDTKnEBakK9;b+?`#+Gffx4>8;pHvg7>nnKZGuuKw?el@={QprHwk$8Dnad*6b0lr z0_jDI0^JM3So_?zfZw@t-6+E*HM%sxWTMJG@+kA@pod)2k@8Z~R=|$=J>(C;U8yj0 zdQLiWf<-~;Pc1cxz7;F5!O#Dpti6C-xj+8Cl~BFVYhedO^JLdT7RR!yaXgV6SuUsG z+{%2p(SuUmx?AWvunKeHv^G6O7rS8o86%g}JGqY&8S)9J=0K;CN) zVBJFQac>a2DQ9aKnJI@SM+{-2yuIp9d+8`-`(+&3_~MbJL;jcas}R_21@-z^9=0=; z(7G#DkfX0>x2VyPOLRnMj;vwo%)R2%P1Qi}(%b1KfE1ux;gxSuZW*06##$zgXA~%IDp{oSq&6=x7d663hvg06ameiGIGs2yjip->4CQxwi@cTHErC zlnz-$3GYr_G3jL-8AQVTJ{mRe(BDS%@Ym<$NO83IcT0GNLi zIBEcJUlnhijNJJ0vm&9A&V+z%6tDqXuO|1g@02vsM6{Q~UzB^+W)M zO8FEUWw(9-I5qGZTR|i_z-<(AcM>xWaGP5J41>{h`^bQg_$f|+)B5f~!EymSN2PQR zrY*-j>|`MzR-c~I2GBhKn9xx6&=TcKJ-Sb6u2K^~(LjaYfA;~->1g_9CN_!g_rTrE zZZstT-G0ab-x}_IdD>v?up8P`V1fwX;;Fs3e#5b_G{8fhbPnayK|G;)1;C2RTmbF^ z12|g)fYPM=bIR26k#pKWz@bC%4VALJG9#1vwMqGcIh%R~aCr`Z&hDM+B+7TVO-F=2 z7?Ht@9hmFe>{^92iSOa8!&x_SG`1!Z-n*k!sQ3Xt_YOpY6bBW~Rxts_aNhDeSq1Q_ zOn|vHOsQdr7o<*M0GOo#Kp#Xamx=m@@{gG}w>Q~wbkmI#ow+t|A(9&Axu|hE1ZL!l z+Ao2Zp>_4D@o>1`Ww6mDmyiLoCj#p^K;~c7o?ipt0d8u{xKr-i?F?ld1<)a*0(%CW z0stK{fOC8VuszaiIwgP_0_lVQc6!^dZgIt~VzIO2+7cD1efNN=6awJ7XGk`nTliCM zmDS@Y=MSJQL48McYv|4bJjeTy3v?>L5+c^{a5})w917Sg=gGlY*0wPEoFU8dIKWPn zd34uPRIHXR)7@EKn~+;-0giNF=(^}-1v7F0+o&Ue!T180T@`Ts24I0O+jkkG<*5+M zE(rnbTd@M3Nd&;jh*(Uh)*K+wvWDIfz;gouL)c4FD-6{MT#fYjpJa>v{*PCN?l_8N zxhY^%#1I5%Q^juuZuPU6yjRvM0niF^8krGAiml029<6p#B|v&Ju$xn!h`L+Yt^(GF z3QLy;jQ)Hw`{@K`k{a!4tyd<`0k*TuM{=*2vd(GR%)M24k+Gg5)coayzPc?1HFP@NFrTB1;?u{}%jufDp#&5`-9${Pp#FB9LL zdXroN`Z_o?dksKq-MT!=J4;c|?7OCLJVkqCe zR%Ue8!hBDgFcn7)%wgSPl#l~pCe0d}dw{!$2*7-Xz;ujTO_)}J8wtE(kU@8|o8&n4 zSgo-vzJSJBAfqOr!TAM%X$N#s95wXoY%^h|tjz-03LSp?yk7gY8i)z%)Ef5)g2Xkz z4lQ2b2@kUaEX!yUp2rc$5(KQq-55s=7lf#>v!T|23YMn;-tw~G{k{j2`Rwhudu;OJ90vIUeo8=oaN&>|%P5Tg z)i};^f}jkJ}*`%?vGHvl}l4zP6z<&2&Dmh*Kg;|~C+2_csJQVR=!16E;| z=?bXWc;ZaGz$^X63xATkVe=(>JKYbJAJ$QP?PdPxEkOfqnk-5g*>4f2ymB90w`kuOS}7snJ9oU zGi9AT%B+4}rxZGO4(Fh8wKPA`3%tRZGXQ;ifNjXJhHLErXA;eokwyZTDWcqt68y*6 z4FGik748~608Z`)94QoOI!+Y6`);U#vtW7Vj(nafNgzq5jCWIU#Db5W-_sQ)1X)L_ zg;c2k#!Db)mBm?n(Av0*J^`8lx;eEcfU@8bvNKT&U5Zl!u(dkdFxV1EKU;?3DQ}-k z71qR7V+U|Qfr~4Kvuna9X6S7J?sdj)k^yc`Z$jwR_#%x&umS*o^T^!*1K?f~fKze+ z1|mAw_l_87UR(Bause zkoW^60swjc)^I_9N6vWya3xb<^9=V9`dB_jP_3@QHBoTX6Xgfwd9AFE%qj?A0R_77 zIH{PZmV&fwzJLl-N|uxLZ47lmf!Hk)dR3<4%eCDixHci#JdtiZqRyP&5XNVnl$C(_ z4}rT`Sp+p9!nq5$%sO2h2eLeQ$USx6MYRqV!KbEct8?x62EMXr9mehV6*h+*SO41q~+z3GHi0po-5O}2vw_{q7-94%w?Jk9oI*j9-Foi&M zpK|}f>TGowdzds>rw_7IXL(zZPCXdyx#hWGZWS66`1Y`yl#C(MKt9zHI>I~-_(j56*W&(hoc>z_~M8P%njT)#5tK9dS zZRL>NbGC=11F>9=Sjcf!C+L|3x{J`oCdIxX$4JEn0TG5=N*W}j4x0ee21Xdqb-`QP zf*NA~%z&xKqo(be)KNtQz+)o!Ss$kftt@h%>=r?ZiY%SyQ`%0EMb;u}dy#F*4Vh$4 zR}1`04l!xo}+BQ=ElL4z7@C%<_qAy^5RZ>JUW0G4!@C*gJ1UaZN6;6_&wMKy5r77U*fopL`A04zl&9G%UYnaNT#`Z3IV49_QzvVE0 zN#xCIpUfV2pJ7nSOf{kk zz_C#U$PEW$^kwq|^bz3NMJfUqLplGHJ1pm+VSojO@}QfD08VfLWEbRX*$->9CzAj6 zO>8-THMVB1D41?mXm6U3o|UJ=6R+BwcXI;x1n0hY2{^58;%Q%jpEPkj zRA7t`ppXk(zi`r-R@=C-Eyw{_x~4d@{_(o(^7 zVl~num^Qj8fuYtl!N63b&~q*$HFW9$&bI<7b%DP%`O3nK{`BdyAF_XME~Ef5UcEKh5|ue%`MC%CtV z^64tdjF9p}JAAT)W-F?4uf85avr`TN#$8I8@=mAV%9F!aB#f%4K_awXB323w!1Okc zcyvyH@t>%2eX>B&ORS`L$=qt`$moqD`j$uqBu!T(RXM ztx$SL2QM1~AeU2vg+Z;OE0=Z~#W`ILU`8HbyP&O6#uFFnt%2N9;miXS$p3hP>l{^p zvNOD^Zc+A{Q}@}9r4# z<@-J^SIq!EBQFgbZJZ!`WsRtJy)vHu(ASai(ue*O{~}}bnIHg?`JWl2>?#-lG~XLE z=pPoKLb=F?M<_cgG|#avBpV;bWqIV~v_E_Z4>-dgPK8O3&2PL68__0C*V`sbS~B}1 z4)Ecg_y|m!b-s%fe!~gf@v?+SDy5XtASJ%bt$ql=w#X$>A5qT%;G9PHF<}em00^{s z>|z7Um^gNRU5EkTgaB+2pzH0CDffoOCLA9z_XQbof9x0lE4KozvXIBYsc8X!E0+SU zHz6p?q<5bhBnMbVu1|h4iHh^wA+F?V85XrN=Jbv(R^MqU)#epldWQhJ$Ju+cJSPdT zErl#>qRw5&z1)Z!OyGZj-5`xgg($5jZ;hqTmccq0y5-mUY#G~D0d|h8ua-e_P2+^0 zPeyrl6~H$1`9WXp5?1QI?}Y! zwZftImCKJ{&pZVHutft6oQt#oTayi7k^#0cF@Tpa)vfDTHqQfXmVnMA!UX_3!6d*{ zr~>EoYVsr}lYPcrj`^1h<=ZCUK-Ggx>V5DNQfO!Z&S!&Iw%_!iR%VsBm@^&grUWJjxkX zc+0b{?5J!djf@B)(FRNXh3=i}a}jXdtPCf^yduSXXC{GjUAHm!;zuN)uij~QN<08y z!N?8XE0G~Q4$JGLLI$JJs?3fHNp&#^Q+cGETEjVPx2h_-lm$Rn=ELJx13hQI(YakC;ph^Mco)G_C41HcFbU>hCqsUQy8fwsp4cxLWehLQHUTYP}R&5!=T z2QpR!*q#D!zObhP(^|%=I9viSI-@7hRH+NBOo!0=mKQr3BVr!`ZYU;H+)6{gW`y}# zrq(xPu_Cevj~G4?u2GMn*vVn zwL$p9!6et6d34W05Qf?vXUx_09OiZ7`0JcOopuQ0(NFLUZXvmO`*9>B?-N&w@G~hc zjG6my8>h2oq5)ugT>G9kS_fcTe4P1us)k(~$j%;_#)WxUYH&mQ1^BR6_YKqLjE|v% z1IHmZAbS8 z8nm(mYde_o+EzJ~!ZbfXBt{FofZ1iH>EaAU9JXhsk$J6;z^emv5&oNth`Li!;f8-I zca_B)T>L{-4L@&}m1Uv~$~*Jd?;SCTHWc*+==;|EEW>=1cfO3WD$TK_WpEbJ7@j)X znP18VkuGyPTNGsp*Qhfyl>OX;E6z`uoHi+}tSP^eaG|uEBwnTRNNQ;@u0FbrIVoy9 z%Fj&`YfKZyP+;m zw%w;fS)r9q&qzCBr?yl!_}!D^lKCn7pwqCi$?&iU&1~AxLa+d{xZe6)v$}6;IW0J- zrZp2^XN{rDBWXKl6+HwCP0LW$Qc|9+kSiP>Ecn!SIhgVdk8wdnI5>uv=gOPxf(VL6 zYW%vL&N8h0uVIYmpqi~Q5f6iVS*7B&d4(VTQo5E}P+S-rvgx!bOmdi_s&rWXi0)E; z=uq8t{4<&UpHd53-=Qym;LfL#h7pi1@2@NdJ&v%qdIY&6me(BDtj-`9D{6kpRX|8ZJj3v41%T+*@iXi#7`pg6-DGZkS7ZV zBAG>6?fIYIxGN6sGYoRw4hI2?mPi0JHv;H9Yb=8*;8bb)U`dJ)hDmsQQ~~t>k=9OP z3Yc{O*a;p0xkX@_k8-nbqC)yxp(fP!YBd3eOE|YXCk1K~JCfQEz)+YOn4t+!3^0GG zQ!CgD+&EsoHhY5TJ6rI!X$IhZ>tqY-a{bb`RwVKYeB{KMd+x4L-EnGcX`LE5e(?G} z87tsr$pCYT1njuc@HLSO3lQt^dtW`GJXb`ZcVLFv2m)XXONE6@mZPV3NhJYb)TK&Y z+D0G(13a_Lssp`xYs?S|?2~?MJldt}zNLwGewAyxp;o2_$q&n0xv(5@7zpCE3e7u1 zeVWL#mKF&)k0?MAtEj=U?z`kHLn81HeDe-~+t!ruLodM*N&DrQ`NYaQvsT#$nDz`s zfW(0@o^iNf9_PF@v}3T+LINK#mCcu3WE;njAl7S8Yo`z z0!$Dy31%hE^8o2HZy@_5pzXK^)H(zmj0^1-Zp95D&$R+zK~HpK}0d z#>oT`PDcz@S{A;7bYVM@@RXKyj5UmnZ}AQ!C(%4ftYn>TG$nlg0CfjP`G(GLG{8Kx z%Ts;G2rA@e-6;ByOC=O&QYXLS$Ib}N-Bik}0>Zy|K4K&WB&LtSFqn3jh zXSTl~PwtsI@;i0Tv8ZLI)C6iClt`nnZtGhh<=dRVn`Dr<8B!+Bjr|yb4LnV$)R4?f z_8d;y@jDOzyVW!*_Ygey5=^x#TfTHBpHBba+_y^F2jmoGTyJxwNkwS8ou=IT|99*^ z)fC2c=c7RY+^ql)YAuMJezLskS|x}ILS$0|l8k~}o(W{%iol28&_$SGsvI`~u)B~% z%A3m*(fkofeHNO{G>bg08g-mKkS7Ta;@p6+sNoFTPQpgkVzbq|MxWhoY@I?ADYp3& zNsP5Sa{?7e-tKgryUWl|Jw1!AAWfGc+5CD$w07{-#+9`EgYX6ZdKSZB!Pxz=OLiyM zfI7?2h>Q>H=$3O`TyWZX!L*aB3#n?_yP3cRQjU1|MunP+b9s0&%R~Db0aX_wl9q*V zirTj5yJ^7uaN_t>DNm++Ua*I1)7Jii@XCN&Q$g3A?tGR!KvGTSf)*B`CK|!3Us=p3 zK4l0y(&cVP4@*0!T`CfiL_mp~7#B%YL{Mvj&r`eA0g4_6+Ky%n(Kw3wuBn10XlgkN zKw2onD$+IBi1qEv6?vGTuPjKfZt0g%USCxxwR2FCcvgopHU?~ zA)0w-+%1n zQT}Va1>}htVPjoQkY~pQ^rsggv)?@ROWu4#u z=kGXZ0P?$vN`SsmUTjD?VF8$-6wuoQSej0tcQRF(TL5Rq6`O4a7C;kI-bcYLJ7KPq zwmnQh26vSx@A3s8NG@%U*l`@|oZtY;W{u=-%NJq211Y1gTNh7K!!KzUaT!8b)_xUW zDR}}?nD`0ZfpP=L1{+W%z5)zHk2d+H+$~=KJHjAPoPr?4L`?`ju-c7RSS($@^yW?h zv_F^%%a#d9Jb+#85733}0y0X=jY@7n0xoz5;@N}PqIkg?u^QQr41|DM+p8!u@BnR8miLk? zfn&x`4YIE-^QQ->@h`_NgC|7-YAJx_%>hy!3W+jLxmZ9c>U(DbY7&5%O#uH;GUo;f zu)>?DKIC(!>ty)|%yyOBz%9e_$am@A;>OR@EqASd%gzcnYrPeE0L|5Ru&D5_05W+6;{ZyMm*`C|QFfpJi%_Xh4v`~4OIHGP zM<2km77|n#@qgUOD147dFwM1K<-lg8=FwfwzWMTwra`AG<{pwLtNC zN7Cy_X4Sl%7LK4d{ReO7T~4$pADX+oH2$Tm9JGh$82=jM&XRPFtpLf%K^|E>sWpo z%=ON}zP>{y;+fa9E)2S)H*L5m5(ke!FcWKKGX0YD)aV8;@0WPGt|LHsUki{y9UF3W z?8fXQ6$siRiCG{eaTW)$kb(fqmC{D3WPw-q8Z3=}L=9Jr8UqY8=ql`i2e*W#KyDVm zxpe0}^5S!tHn}`P<_VHHhrY+4F}H@YO~Shqx+qu@0YE-x-Tc|$IExGLLDOHgP_7-{AW22 z|LbJsnOWCNlcuHJl!=MgZHT3HDX2W&!V~0xU;wXdXv>uGr(aL7_k?7>XaU^?gKwf! zcVOTP{o}35l9=)mFUkzPpgf}h9aGM@cuj$}S(BhuXP&u*xlU4^qeQr$b~h<0M^m2%7Pe0KK0SP-AGgk-bO79%V(#I_q51U$dHn0aMc*&TV!H@{0W%B;Ju zJ*C6&wV9&3wGR^}ft2+G4cM-|5}lNn9AfxRo7)Xrl3^UZ&&-up)p0RCR+4V%8&UUt zJa^;W0Z4PyiiHcu{LFCUHHtdnlqcTqVPS?@ZJ57jv%H@2QiR4WypHlVzo5|aw^^>3 z3kAC|e11Rs41=yXyNOWj=cVSDv|<3l-_(!mYEZ-1FP6lrN*x^4IRr4zx;y@Y3NjC) z-7W{$)1($u$7lXiH@R!0ExU=|7(*WX}oYNw&; zOpP=3v({7_E1VsrQv9VzaPX3N~w zO;EBO%ao0`DeqVcWpm61Eg5&p`htYe`yh}e9GY-H(S6W^kcp_3@*F{a|2I?Y3@rT2i-@KdJtbr2C@p*UZMvc%zH#QXRN6YcNtN8S>yg;$nR-qC%^nl3L= zY@Z8d14_zM|CG(GP@W>C+$D+M%gk-{)r9=+H&1OZ*`n-e3CiOa%S;aC<=iVXJo=l- zvMh1sdlk23Vq%BekuA!uze0|?X;`1v;`W{K^A9wi)QmkT>n};|(j=7O>t>_PT9gfb zovnx3I+IRjiW74Fxw+q!*{G&tg*9h4$13YR;%Dz*r8UQ}96g$?$zpDiE;;d;`*tkJ zP>vO%v0LgordM>)wHiCX$mt-iTax-4Kmw>^BqZj%5x-I z!&`R&@yk{sm--c99z;I7Iy>ut-rc7!Z70tS(55m0v$4$ZlF06dfT)mQ{o`FXz9 zP(Pyk??jpizOVcA=L-Y$F=x!hr$cL90d_aOwD+!dio*3>$gPxMvhF(3p_F(qz(x*WYr`*Zn0y897? zK-B($Jj?&Lb}6D^rOtM7TBn5vkP8GrT5b~2`@`9k4dD`zbs1#aLuh9Xw8+)DK7(*g zZ%^F`5RqqVM&e=1tzaj()wG zxx*kxZjiVrMArpmcVSuO9=c1wM07-{vTcw))HgRkwn8~%9@gC}Rh=Py&6EQ_KIN?G zxX2E@{D}x;^C5fau3+-zsgft8>!H2^4Bcag#t9Md=I)vx2Y&wDM64B%&b?~({ZBs?h4Apu z(%S(T*N}8*NIo;u&9mLfIq>9Ae}oaujvJ zZVzp_xjJK#mA3m9+ z5^m%~SZ9)I0P^sFEJ-t4<*|z2ln7}#B*ZYoI%yJ-GF87KN7A`!)+ujN%dRkqv=|}s zO33c90m+53j+@GT*TTgRw+o1p1$a z5S%QLEv$toNg|UZ+bQh?GMaru)@cD3CU|Je+us{rZf`F~TUjUbA0qpJY$-8BP8G>G zh#)Tl%lik&2qK#utH|&m+qh?)CRro}9byt0W9yF^0%OPV4Mr5F&dD&uX1p){d+SVl+B@LvAv6Ak;eT;qz5v zN|BLs9~7#})4dxbRc=TVVV_YNZDqPu!Cd`$I?d4RqU! zLX<1&kP3fi4-G6*@}v2DBxV-EDL)dn!ef>4l039TWr%u6WEz+{Ib|ZbsMcxaPUPq= z({66=GCS(D##J3Un7Fo}9P%(+OD?tiAm0^1%E9fOIzHru&7}Rq1+^gZ3c!R>AUYG2 zOsL(b8!v;@vOt2yO2em$CZA@WYlN+{hM()DKTkb3P(KYr=J^}%%bl)l!qY$I_+I`D zA=Th)Sw&6B&`<6`I`;>%1yt+6Va@0=sUfj9OA6yB>f~Iq$ne~+43bdbfX+Npr{iwa zIin>KG2AT@_khq<*DAK_)>oBn1~~-+(pGYi1r*jHA3_INyn34<^baVkvr6l3RKY>N zk(crldF#MZJ+-xFpBh`@XV3ou>69N&eM6Eqvks;oe5yS^wfq3Cjri{Dr8S~D9e(M@ zs$m1)7Li(sa~$SFn{uv_q8w~>j>gNXhQvCo(oLb&8zmH~f8Ld7U1$&^r;|xnzC+l~ z8YcK4`B@G zAJ%J}0Do%602W1hQ+YNXAZ?@iCFfZUL{`2C)_{-1%jmFrAd z!-8Yry)GI1)Iryf-WKb|n03WSN(tyE$0^kHI`i9jCx3+KnPAn#L8@cZ)=2r_k{ zWS>1wTFY(G&WIk$@|c0`E&OtM-Z>*Dca&NPB=P&PQBu6UfX4aJv-c0)Way zJ^-W(A{I{^kQuJVh8B~qNgvpShn8h^fSJ<(*53e@g%VIbNzGK7fXWD~5MaQR?~BNk-8ls?Nwk8S{{g061YCGgKr&_WZuh7^8#!WTX^D_!D&lss&;sif zBtU;trnQCv2_OXJS1R3*BXHxCtLc^itO%{XOS;|!_i5x7y8F*<4M@L;@h-@H#z#ce z2$05S!p>T?srf3{S z4ODMCeT@6)S|r z$p|*_vxl_aW&8B7aNmve5Q@*l`@Jt56a2E7@juMU(cK2D*l^1f`K#4zd5J1+oM znSui8G&St?usX9;ve@Oi6byCp|7FUTVDl&4q^-vms~9HA+b{Dp2oM$?j^)}f0#=id*=wqQb?CHzAqKFFEQ&NIP@ zAlo2go##YDTR-`tD2S^yOu|i&NbgdJq!=`S=0WnZLHJ*`6ES)ODeWjwTmWzy3Z$J-#Hzcz%sS5* znWZN}Jm5o}rA9V9u%M#Ik7Py0bbce*E9R?`j z4r9)6fRulAUunihK#j#SyCKGh{6>+;Hh_eb^L`^-8Ni{f62XR$pC4Rj5{T=-du&iXXGLecHZbMJ>Oh8bCb1R$$ zMU*-_TVtKh1fis6#{gRUhxt$Kfw&P!ao7=GA1ZN)oGm&J(EurVx*y1yoHPmE4+JLSam--1td8)eG38`czcft zJdl$J5jqX9@TV#Q2<&FKXW%!GqekrpEIsBk@~ErPvo@Sq>&63+bCEpNCUrpWRQdM4BbQP=>4yC#xX)sO8E zN6d9+z_OM1z&~6{3~i_ivS1&FikXDtKuT>fqi9SuKFD?nsj5uVd2#zk!Lx ziKl}doo6;5TG0(PG`z6%rxLP3xc==Dwn(REsI$WiNs&Gp+_6kuCZwV3(rysQoHFcA zi<3|0&e;TczTS<*%S#~3uEzt)umW=9LYnL$$VI2}l56$+zf~Wf@^A&Y45;kl z&*Fc&nj0sRjf5cC5Rh_Xalg7j;N;hpd1X;#5&~5oWT7xrX#=wjOXV-+sx>H(ZK+mZ z^Caxws~Ns)k2DHbfVF6iH={=T=L=tQ&N0Zvt0E9pho_8oRp>Loc}dnNh{4j#DHxKs zwKVwq5FOnho@NeSi=jxHYV==cU%eNt zxB;``yBQ>iOps%o+63vOI><>dNHPL)ZYD^|9=CjU8i1W>g&$j+wqY|%o(-BZ190`k zvq96f08E*ubhatQM;1VtaWZioB4bl$cR7eGus~3*85mouM@+phWU#=TwFfu{TtHn5 zvg_omqDwDwrV`}e_6D(?<1BDh-WPTH*eWd{*vi5%lO*{oB2J5MnspEIJy2JTZOM`1ZD%Jew2z~yAr=#iIBYYOb?{@6DLk{00-i0+k8PgkLzR3iL~{$zKD5Jni00Z= zJQOpnYo6{aLa)w##SG-;^AW}Ai7mpAd0mLdR$1Hn=eHkFe9Nuq(y}5Vc$c_+=*w(G z2$KUa+Y^A$xFNPVt`%pLJ+X_Leba6Xa0ikCE7GDA2Xy8oh)hpnX`-P>nFvf7V#A!m zRi`;IZgG!Do29T*+ZXVIRN1cY(a7#yr0^6-!x$-#0YTNhO&u8zoa3`wL+xt5}3NH$>-%4!@jb0fX0W*I*8;uJYZOa3VR`@lKbt|05Q9-&2OD|y7$i$}BQe;LA zM7|Cg?}BiTWyro^$E{!IL;0?_4kVGZKld(>TBgtQCaeQvII8QQFO@oseDSES;`D*Y z=}M567Np=?r%(>MZ=)~w^ezx`Cf=cs4VbN1MPfWgb_e97Y2KH!enVH$j4u{znr6&% zfOlrZK)Cf8R)N1J{Y>9(O=5KORK1EymrXuBD!W!8f*?0rvPv5(t)?8dr|xx`j`CPmROK^3d)3MJQ3?LkHGeD=n%;&BHeI6ohd$r z&18EAE>CQrU=iu}ItxHQ?fjxbXqkMhM?DB(xCYf#5uzLc_zB?H5goFM(Ne0Npo$eQ(zq8Y6+pkEbaZtiWU!0EK1~-9v=K z(V`{5kw*Y>0NgwV^vI4O^oY#z30<|4yLxua!Xuu_p~mBc(=P$HhNcwl5Q3m_P_li=dnJ>d>c z_-kw6&QkY28#opL!3%B$fM;j$;uhXvIQ3L8_yX8xz^p(*nDVyq$)WDJK~Bh@9NUvB zQ5w&Cp@y0a;IexFKe12%+xKJ}hM)lFv>{3=Hi5-G$`;Hca2;3XS7Y>39Ir;&JfT1*>i=p1izLX%~h6O9Z@qSJwht&r>G5|oR&=W8p z>07@q6C3<+u>egaFgqiFVhXq?JSJmVe)a)3%h6;T$DtJf8pL;`g}wp1o_~+ji=EpJ zK)`t9&V~6>)D0uuhXSo(vJ2o&5ehJ}CkAO`&fbPH}E7GXw~i;Z}Q zgwbkhT)^-8EgREHuC@5wCWRPa{zAj9mmimUjTNOX@CIqDqWq(ThVi5swwXdJ@!!{ zG6B;%0u4mnoIwKMVr7#0=kHSXiw3T(%zoondTI?|a`6{{n=}BnhfDxR5cd%8(Az@< z^r`?((F5RHQohIluM_^VT(>ED4Ho5nBn8GH-hfyFu&`y8tu4-IT6S18kd3tL6!XH* z1I`zHSI2zSqVq$iXA^w|O2=VsB_F`7Fu*130nD}lTu{a+m{MtV8AEkB6(IVWph8Rm z`7aMjhc-X^WQvqw1WaIyKICM5J-t9SX8i#)Gyu;^8#CieP;K`TrVcv*uz@h=u#JrM zq`>hal?d2=kp?vyi2gv<9maB7uH1Y~!240K0POi|1~sO<_0e_mqO17;mt%n8`*5hv z_Zp=`(ogqX3#gd6tOl@S(gINfQN4a39Jn^rc=!ZClo15hs6Gun1;|5HmY=dOA#hOT zkXg{v|67GXdDs8%c*y|cM+mtTiZxocejHGM&bi9b@sn*L1e%p86@U`?&Uj)2pi+Tn zF0wU`f-+0hGI({VD)m{yLi-wbqvtm#l+}iKm=~!lJRFjSDH}N2ob?;iN=qK;>Ef}$ z&UFxTU{ngN6Cmw}Uga_s<$v(rn9WTM2FSzy1UXk7aw4Db!$zk`gU6ulsE)~tkLhya zr;$`iJl;0t1b)5`2L_CGe?vuX;wc*wSk8~8oB}>Kgp<&WlGaW!Qd9(R3N|#n7Ndb@ zED+AFlf09u{>B_KnQ-n{$TC|K@nk<`-BQ?e@8)-grk5IBd6@?!Os$TvYD^BF6FaXy zvP)8iVBtuG%B4O|*G+_3A)EkayY9d_vBBjsk?y>@wfKV3u~Jn!kFOi!BHo zE+Z=OoiJO+6wwoljo{9ftF`xW06=$Q0OXj<-(^Le+7@pB+SW=NCn28 zl5&X@_yoS821BbKh+U`DpQuAQd}Ui{*C{ZAWcZ7wHypqTgdqTaKi3aSjMX$sYLlro zbYTI`Rfmsxg7Om&sCD2OcYDo4WtNz9fX6FSR65o_CjG(HY9`HyA@`{g0WFfT&3SgP zs5Ris^KzMK`-OkGv?PzX1Czk+@|^-$Zz8{`WgB&~3en@`Edk0kAQR1`HORJ@2H2j= z`r%tpRCCYiIhw)PS`z!a5f=H$nPLIy=Nc04);mNnF&_ZC0#v}{9|^E!#0AVM0*tE# z`Fr<57X6-aMXyI2V-9)Y5bx84>Wz0>F|J0!oTC zmU;p(u?nz#g89yvN`QTHD({+|g#g>zE}&@8QBG_1THPGWpOC3GRVX817M!uqu`o)I z%^??5wBI^C(sv)|s%*DStvn6r;RD>|B0NC@%ox&{AIx7SZs^((k0zNt*kHNf-btG# z5pLvJk8%d*JL~6=Re;_p2?yGzoSC9zO@K^{410NV0M~P1=}&B8<{E&-p*jZJX>^Q0 z)qc)Ei3hadh2rQO2##n?7g-~g#y>lTMPZ;f3O7MlB#S@SuX&U24HXuaC;2}Fe~g3znq5v!nMul_lP+UfZHEL4V^Q9 z0;zT+Fmr63U!uX~;BM9<4YV9MfUXxcaJ}-QR5CnbjGiKu4+czekgvo5padcN)u1&* zgWG}iUc5oXn3S0-G5FOb$R)RNsm^IZ)X z!$)A43>y-FC{eupH6qhZ70A{c6adIa<`;R1;sD;eBJetuyRz*uO!$!P*h65?L)4hk zEnUflSz3?ER{`UJqe6vS3&53)!1U{euJK^#=&0)kfD53A_!|>-69xmi!0RlPKE=ig zFmgS+i*!(+4n#U~(GQsiEigBPp|qgJBwasb<7SNq;Xf*LBL@Z|6H6IC;>*J$`yC=U z?ab|dXGDlJ&O}O*|0bB`W zOQE;;5&fXnSfM^=wiqB{B zq(-IMRTMTL$(BTqY6REj>AMeW`5!2XvxKuFUD-p8P|DO%p4#9*{lV!mz;@|FRCs0_ z#tN@!M_Dz}%A41qg&tmD19N4zB8pC)>bLH-z?cc`cSGRA2586#34eH!XPxRfYO)m5 z>EaCFyhs6Mj&;cU(0V10Gm(`Z^)Tpyyo#*ZHY5mtQ34pzqjtEAfjCsQ9<$kjG6?!) z7QCP)aQHO4-da&7@%+ePbn@Wue66Ggz}YWIa3LD?$nlD#Xl$eTRYZ!tJvAN{q#QSp z!$GnXLfZ$gwn$J&OoX4?%((iKs;Ev07rL_bx_Q35l^{R32hHMf;@( z9}z3L-biGWD9S#M$((yGJ!?d}@m^nZU6sG1abtp84w-1#o3r7)>=#w>amdT-MwgjD zOyUlm4**#y*p~pM)J&mUO_R;+NCg%I)!`BcI6T%b-KG%f zMSIHP*AKIGy!yR>2QYUisDTI@a27>rD8&cn*;r|V7Hg5QkfUbcH^KW`sqYl0S{fyn}BUkV8yyqOh{v5@Z%n;ulPXfq% z5&PuxqF0QGF#Z>My`|Z)`L^ASprus~r$4IZhiYhw`12TJyUOn{GGnVA4(-6eY4-f2 zdb7d9;cQ+)FV;Avyt^$6#ptJH(ip+&a(>_-%EG+jRZdj++7x`QWgi(#$+GD$ZIzoU zceSyUvv7XCKA$Kfv=FQkW&HS%hxt?(un`CJLV`8UXm&`oHxGS>sJ4G{57e_^7OR?r z(@T+(_dv->;PY6Nc4%9LlCWt{*pbhmp6YunJh7nBg~!Q0)Koy?!G@ZU#272F7ALam z&kOxQtTE7yGJm*T>lrpiX@o`U8?48Oyh!8vfLn71lVWCr`cQ1hEOSWGO@6xNFnfU- zq7wD6dh+O+v?(x1b(K488pijo~E zn@)8Xd7BzRfGFz>wfJr}y}$^Hwg)*rj)lLIgG}L%o&YPfvZbspQ*Sd3(YAT+3)0Q6 zw;#=LvKO&9Rd4e^*|8x=hR-kOikpw6YI>-VS`Lr; za@YDu&-;3+;-P>9w*dZ%1CdX}$z7O<|Ag2tJGRGD-b#91PDEn7`w)mEP^n8^b)~dv zmB`2caeS~C#54q+Q-srEe1Mw}cDN6KsXrurNqj@dy@6b*`x!ti!6BhAg(YDne-x}4 zL#S4z&waWa(`CV~<4E7?Ah3owW(LhNDJAPFnM^SKSX9hidO&!_HX;`CHeq1#w z?eVyYc#y}aoePqRp)E!?nx;phjzE>dA~~FyAH;_teY~ZN+$cy{38;EK(W0>gxJ@W1OpgHr zE;vpC?@J%ngY9&@Xxu4y+2f^v?>V#!dWk0SR#IKT z{uZn=1w~AU88cKD5n2xv$sR+*;1&VRuEc14^EgVD)R(iN$o0RN+rr0?f1u#8o8W{B zo8+g*W|OnOel0Wfdk5SCSq2fKvS{tSB5jZmxo(gA(T^8{?WvqnI*pfsA1QF%hX&Ne zFrj5(Dei8I)r{)|yy3(*i;(OPj6iRIpt_RPV~k>UEPkfzc!fTcjIlCRNfhr{qH{HI zgkBM6Li9WE=3VtX>Y{2BD~TSKWC05(ltrBE^$Q}58LXNJH4t2g8{{Y%%@y=9{()~z zeirz+Sd`rE&zSTh#BkA*;DKQ$pAWmTL#m@y0Pvtku^l?OMRwaK>-cKN-WLHxyh2H) z2yz3%WIP9V>rPE7=6J%^q9|qiiYhs(;9<}pR%$?Po(nqt;??UA^-g*(9{y(+_Xz;&!8rm?wmCmX` z-xV^7+mmsC9ZLh$<~SmL0+6_ly6UoUbS=#$KXe;1Xrho|bDKYvdO3|eP9;Sd<|(7Q zkj6ZP-r!&_#jRJxp?dJ1G*c$q3tV0uVzABCgtTkyqH@Xf;6mWrtT)XkSB!2pxZx+n zxVxT*0(}AbIt(|f#9Q(D??d51KeMg)q*pX!c?!^P`=pt4=?~Vch6BhH)(r|8Td8A< z7nvtA{5!gHq(o9*A>*?Vh zu)&|n_TA~0is%BNe`*@hPzg`&=(|f9F8>kZ5;xs9$=|@seFC*&&|B(J^V?i)2v`b? zn{L3*8Quu3HGE%qU^q;lEIdE^$#mD#72V2NKQuUBb89ZFp-8gvMQ-Tc3RF_|(>;QweK8#ZN>cdol7JRttF1Ho%xy}Gb zR@#AW`}(SHE9E#{Ee96tJKxJ#VM!p;U`#0I)Nuib)m~t(ds92Vo&7oI8Ei+tJqXM( zmRXYZZZ7RvK#Hj)qnRpRWlI#mgR(*6c9LG3^a-?JQwgNY!>RGv%~0D|EHxYn)~uP) zBR_D@$gE47{fOqt)v2M(5ai9J`(gFdLD72@WAFZ z$*=K+;brrRrg_^~Kv1ZOe*w>rDaO)Ok+N5D%v|`bF=JGiOXzp1QDSski!g%}zSq(# zSJ$;9EgSTt0v~t^YFQt6Fr*sRee^Ci(M{fJ5obR}{fblr+N;Kv%TtRK6ApVpkIy!+ zZ}lbES-j)IhDq1Kqn{R}YeFKAng5xzJV~joHFbOq?Pi-t2KHmGh!$K(H9$9;+|ma0 z+vI)H)w2ZDQL*QURKqx(D!zOlFdV4~HbEo#a0?7EH;%(FLo@_pi@c(TQ|th;*PsG7 zmYVDEGNiu5iV#%w=TwLcX zqm*@hBtj&Ps>#Pl>a>QrOr-qf-|JpGeRyTFmTK}@Cqcs^XlRJrBX2sl^81eq?y&g;4oQC{;@&4q_?L^d?vJ6!6v zh}~P^qOAJ`m+v?Z^dkrRPAJ-!22HzuOg6GZH&Kc==R?N$kdw01t|v8n*Y{dV;S(X> zU}`bHE^`NoF8JwNj1?L_VDQ19s}01xfmwu^hQ#so6=Ud&pbVr64O^TuY=;6vq&>z_ z;*}IfzbZ<}K|DPqCTrSV6vFuL+6_oo4CDX?s@}~YGv|{gED_|VjgAtI`WiuruZ`8y zKS6Pm@`Niug?qeKr@Son9i`T8PEwNU4nfULT;+TM5 zVwjBFjb_c!)Hm!MY-P~Jf?$PQ78g-Er4B0`vt49Rt&(KF^dRbF(XuyD?*tRa^0YMz z)h?1FStf~@u%bsMZgtWLke7DgLCyK4-GHjY<0UHAhBHm$3685jW=Fb&eq9_UfU=}& zVp#I38yU9)@$U_$GOIX!2SE7ykaru4&YlT_@cueYNemv)kljymu`sk@HHLChb?UZz z@udH#@G-i86@zRJUj|QMOXz62_PYRP>#c(Rm40)wiz|RD_xHt|z91N7<`HQSVK>n} z#xI2l1lJ!5Vl?wfP7glA!cSghAJKiqM*RS;rNWL9qyW24B@e+2TNFyuVv?uDyavR^ zE_!e>JlF%)$(vkAK`j;loAYcl)>N_$JkAJjCToD4U|!A24-jXAzvWq&-H@OF57eph z;;6=cgIP7D4!?jdGGqokT7PO>w1_sQx6wl{~pZf@gT``H8) z?DlAB;&LunLY2c|76X-DR0F(S!1Y$q<`X&kD=_rOC^LC6$j;4+VEUc7v`Q6D~mrBBEu{)!ldcXI{CZUj2FTO_JYG|U99(j!N z_~C{57SX7R97L>h>0JX2!AS;?2C*6_n*#>xFTdav?WoANtWTIYJtzk|eRBQi%oRv* z&xrMkYu&tb9F>z?O2cXXtBz`03Z~WlS7K|TgZQi(HL>g$;Qma7+O_YUFf~`++mF-i z_f3O&^(o(I@{W24&yhN=JDT7+Xi4D{YdSZXQRyrwrLIHW!&a=DJ(lr|Egl~PmQqB! zL7dNfNP`Gwxjibxr$duRIo`TRW#v^HJ*te0 z0|)L#Qf|R7CY9b-s}Wme44Gi1C+)62-2n40u77@FaZ9t}$u?h&we}qZxF#q{`GUx# zfx0-!z}O)EPF9RZJC;=;MO3YTs-3)pJ@q#YMZhCnNa<}GS5#RtH)uudo5dx%KdyaW zybdO|Tt3hthZ>7W(jkq|b1yR$Y|a4G8^TfYVVW_Umr*uVr3GgiEt*ugQP&wRU3q8w zm___i{k5?LtJ=hrk-34su6&Ra2|)B z?}Dk}2cWfnFXDpz3rUeCrJyo%uGASnbC=Z}UgnyyoW2P6iZxa z9Yaef6R_kBb{iDy%;7v{-(#EyIO-Y6>MTM5GeBY*{TXgj@ z4I-84hpS=(j1T#db@31TAT{bCdbt64wD=^a!aW5CI;XtcqKRs*9UqDi3#t!V5#Nbn z;>3X_$zNKLrk-nZWD_`*`W3hMe8C&%J+(5eu1H)J9mvg%9ON%aTo*7s;P1L{S+@P; zE;M%Rf%aw;x}!e86bf0O_8K6!=xcexPAtwTFC4AWlyVNIHl}7aE>lmk&C};`%@r%_ zIK%{tRYuckdY7Ik>a*A+C~83(!*=KoVx+_4TQkI&2?VTg#-oZ`v~*P*rC<_9_g@ zL0^_Cg*_gre<6xGXY1{e7a7^agbh6BoZnA>z(T`>ML!lfeK5Y9;d#K(o5GT~TR%#X4QQQxKa z%YlFV0#{Lnd{j?#08^z~kXF9nJXsLEbtUVlLo(>Zpr@-$Qw8OuD9EICk#%Sdjs?(m z22Ge2r7P~OS~UKu0&Mep=j;R4ZBvvAY%ZN~LjqF3%V+V;<5h{K=r#Z00ni{uASOXyin%V6QxrH$BAguACf2!nRJ`v&p$jVtB3 z?wRD%=o`w{$`2X7{(9WQ_kEzmAc)cu8D7|=fR@m=}?RjB&-8*;&jbO}?<79eNP%U)_d2!j$ zcJEWotrbs_i zEPw9JH$B#Drl)G`Onh}b=l(0+3_onkF_7np+ZUm+KLaan%OY`;1+mS+`Xfk4&72Htvk=2HN>sgQ?_XWO3-G6x3@e5 z*))U}4l7j(yS&V;OI}!h4v(>mcw2v908hLaJ$eWxY0zaOQs2)-n(Bml@*JufhH?^n zeM%7NQJ>&)zy0W2GH)mKNq`ui5es?T*cS-M6CInF_}qVlHoK)5kYuBwywb9JGpc?g z=Fp=%_5?*(DCSYGsC@&&SDx)uVIr=NE4w&}@VszQzjTj~rh}mE>o*G}F}vjU>YkIQ zs?#EUMrzDazDJ6!{0g1FJ>pY_`*V*m6rVxPgzHL|dzmVKHEtE+H8C?jk6ozZFeG#vy3|dk*^3G>f+@EirCVjMW$x)6horzYG=%Ws*b6~O^x}B%` z9r~-0<@s#cpz6>Q{$TQTUY}Oid@a^4BCV5&aBC?Wt^Fbv|Rog4@Qw&R=>N52d|IaUfdAg(M?R)y!8eF0*m}D?~aU;*Y?C`Ik=G;O-osLf)Xn0*I2uzh((2k%Wrsf*Kt?hf3{ zzY>ZIsg~$?Zi?)W#XqbKs*ND`X(1|)UlU*S$e*u1%Z>C4G6I~f2=veyD={r)2LcRo zFsDOQxE!SYwcq3~$^r7xi5sv_GtV#)Z=CPIybU^p-Kp)wf`0PL&+%44k=~H1iNO_k z7>05AF}TBGJZRZ#sLvzMV7nkJ%p4aujm?kL+|)?3@FiJ^+to;N|n$3oma|@hBESc+BaxW7{xJ0 z$;ycH(|tiYPMGt2b?rpNc|5(rl((c5C#ktljuiRxJ`7gjG(H=+12TvxY0S<}bdC!= zs8gnYWm5p@6hV>L&^lr>^QI2At4{v8FWBE(UT5)t7c!$_LRsgr@1{-6Pw}CaeFpEt zt=tVjNhjBsWuAzKL53&V)!f&gz>$-}!CnS9gwh&Z?#9CWl1Lgj(`9$geY%zK9jXs4 z8Xj4_ud`TKGVRU#+Cq>H<{f*BU*M%e-5J}ka zY?eRQO=*oM2$mpaPJ}HYQlw{*@=z5dz~iTH-eG88?KK%#;HJA5co>t_USmPs zA!K5(EC{8DilV!b$ASdKm)Dj>9;o{F%lScquI8q9w}HGslGPt#;Og{_@ogVO=~Q%V zhXpJCm0)HLaUtxL7Pars)K~Yj>1?0ONoD7`CwDJAnp=@Tv1N*x-fqZGf#-IPw;0z0 zb^Yl}iMa{0e04D;XxpSUnXWBrytk*U#o0G*xnIAE!sqTdoE5$7&CrH@V7A+jy*b64 z`QDHrYDy*d?AA_}cXLH|esuel&?rtjQi*&Xj%%o)e>w_+wt8pb-gtdN$#3%{gf3A7 z66M_h_t4i{x(b%YQTlVNA6)9tgEHthy$_hMJfLnP!kvv~cp00Vi*VAc{UQa|DyPa} zwHgf8MqBY8dzS;BuR_tRFVd3MXtdv}<)I~q{5nb;A`-wJ{E`|$%QDDzc6!1HG_?as z1!$w9HhcBT=OE{R9EBoKW1SdCGuOWJ;{(t}^7b6tY0+zd#^B7RN_N z;23M_(aAOiu>dv5{FBdAj|=U?>o@@E;N_PQjxQTI;(AB+=BTGP+|l%^-quM`y%^i1 z-2k2V6gP{sYNB>*N@-Sq6Xq<1oRiMV$25y0J)gO|Vp?zq&yw4;1sC$o4hsFb;;X&- z^`E+MgCG{8kIghl_IEPZ?=dqi#3~v_*$3w7HLgpdZ}qA*8Lk3MJ`MUOa!uW`>3wcF zrHt2Eexe!sGNi;rpYOvV0`?E<;|-)_?TH& z!G4!UEHeq0hyIZ;|98ae)(J?HC)(eZ4yJJZcfoQV`}Q9v`!T+&^kd~UsHU?v1?Icm z$h#RYeJ{l#-7bs3qNd#{Cwe# z!*ckhD<(C}eK6}Zw99PQ^`7*>3-W62PF`YkuS9z+FyYikH8%3I>I1z@J(opbIq!?* z70QCJpFfzDIb^;VO$R2dJkie@G$XHzA|Jh9tK#loE9PmoBq(-^Q}R#Z-HkGh--^+H zHy1yq_^kb>t-jZVlUQ~QEF}Kqoy@Fjx-V>rb3@WC2-`0lg@x}JbqDK;=ZCTTnz_=vcC7*yGuFo+2qUlQtP0b z#R44IiIf|o7~asKAs07~<4bL2Wu1!?&_IM7>vI14=|>zv!AF;0Djc+VzG~AX-sLwg zPq$urIoofYyZDsf36fnet+rxq5^nS+(hIbl9ZBJ4zuFl(lZc+<$U;7zQD<$Um2!T zpf)L?@0p#t>89B7}4a2UavDX}UfQ(fM7C zr3CCt!AlbfgWumeToWw6@^O!yQ8_33bx2zs8McSWI89GM%R>4^#n#%{1TRvgSYTrP zBlpy?Hx0?wlcTT&ospnt_(U-*^QXq8xk4E?-yaCH+6hsKRVFJtc3aO>J78HTXTGDy z^-(emxhJFf&sze?McoYTigj*C*S+^6@|wS6t$V#`SVc4RERTo#0WtF(C_h_WDVq&D zz_aQ|scD5za%#$@;_dcucF6(C2{gJj=&&-HNJW$g-2VljpNALH})KJ@f(kpOJwQ-%NiT(l@&(9z6cd<&`SNV1-P~ zGiO$TXa7L5nq@52W)b5xotOqjEkho?Kt z-09Dii-kR=0E8Rz*ZHX+pWxph?>|8?F$kBgpDPT)rD<;S*S9;&*%QKtXx4^sX~R5R zyxc8e9uUEQ05UGlo``l22>(Cs)nHb3=F%>{5JPSRz|YGK;Smxr#*~owyPrSL{ptKq zKbr0?mO3y`h#}%qRvuyu;gWH2baB^lHMfL8{us!3@IZwAax5VM;ga+9RM7D>_xwkj zf(I|;>7O=CE(L^{@ZVgrGH-(CGXO#XJkRPIoB*#8_{FEv7L}@HKlnwPfWs79$-n4$A~ims0P0^_OS2>ZfOI4g;o} z0L{B#t6e;%9TpV!1 zt(xaK+BKOxrXF6$(hJEjpaPh3lY(M_Ok^A2c%7PW6ub|}17``Wyzh8;NwYC>O6k|S zD;zHhH`$x}larX%vnln5DO&hHMK)_Lr82JOMj~e$B{QzrQcd4z0`l^nc)nb3(CWBYFB+7vp^_@~|WB1Fb_xJUuHf^ulXO|xZ>fDR> z`QJV}X4)J1Bo+Bdf7x-bl&h5#xL`0yqp4|2cm~uup+YxSOEnH5zzGUayOe(V=$)g< z$L^ol%vce7dyXEUOb1T(ZK2!DV3&dRcfyw`g9o?IMGMFzgB~l9@WJFZ3JMEUWQT^Z zag#=@?l18l);fgkzV~-=q-S=J9lzavrnMc95fWzG{8lVTFNV_!GvxK;>T7aAW;BYx z3xLG~DBO8f zRf=9`^8!2C%AGNXgCci1#IX}h7=z}Sg~=bp$qnW(!=Z-rxgsq=fDpJMK2jnQry|%6 zid-!vF#}*q@yvj{-`KkX6G8r?$m+p@uBb-HFFJ5sv9RF^P|SCoD%_x@AUpKnBYct^ zsgfAdJiHX?DSRpebUzs>&8Ngj-((9J@%w*LN|VMlZ7@4 z;YYm(1%wbJgU8KrW`H{QY^5kQy297N6kE$_BG1hGz3H5!pc``X^55?Mh{m4~| z=jKxu%G{I5mdVdm$unu=?T#q*$*$m(9!dYcH_HAKXB0dbp>-0FXctzKS`I`FmqvdGY zo_6LK38*pdt-V`giz#-9{FyRUc-gT9l}n)Z>Vi z-Z7AAGq9%A2I(r<(;G91Gquvi^@~_3xRdKcO*G0GG9jjncpoJ-<5`%9HI%94q-WKI zl^dacP(PV`ZJZ+K3B8i!rVIm(R@ngM04{|%zNFKnwf?fW&#?{(yGbt@HR7j}e3DE# zGnq~4UMv4DxN87wbwWFJf^sXLXUnhFeieVKB$t|#U=eDOY7u7f=BL0nEyk9QK_BZ0 zHHx7-l|LBs=_sYg^ZkA_)T-5r%)#ckX%vL=ZpY(xzMau-x1M3Z7-5DREF07tlp8ez z+NfW-&93;gDe@!ZBAX+lPx&_+N7hE>1uN`K9$HuvuGyT~UM0{cSSNrIqDxetxl9sI zW|TOUXiRY1GufNl&)VNka(<2)DID?nG?HP;|FC}d{#RvFn192K{dw0f@n3P2sg!M$ z6qL^>llXfCC{mqM`%^bkxA=Q&Z4I!#ARBBLY<)4|PDnWz(zRx+i4e{%E8j1CGA5C? z_*uNnvZzMSCRe>?n8^4er=gHky-~f6kF* zS%g$tXHj-|cDwl}^W0U-$0f0!$JlZWaz%TdTGqLRA4{wmGF66UD1B6l>Q~d5nOM>_ zYZ|E?!FJfRW#a!V(A=9-xuCCKDnFGa+$GlcD%UUVnjK3#LN6kNbdl7QW1mCk$u0-2 zKC3>8o>T3w%A2ma?o%V?1*gQ z3Ay{2+iC-~dn~6FXQZjGYxcym`Ghrt-J2n`>8LI5Zl~_W8S&ZshFf+#6}(u5h~D_Z zxGl;NER)criWjjjD(XL8S{&LR7D|Xngh@n65Vd)?eGcHdGQS7kd*3XcP9JUEOy6oC zKSeIZ*v8C5mPdY$CV|C^L5Sjo+|>!{Y!0U7`eDjoG(ifMzLW8OD~2I}ZA^0GLC(p+ zU&^%S*YM0Y(ANj~iG`f3On0+lbl;CYg@`Cp6;dDheuZyxlL~5bFXfWtRFd>K^lR4T zBMl-U1>&T%R3tAMyxog0e=MrJU)%eMxpu(GXOvj8H|PFkqj+$nJjS$B-;M1N6)nv& z{zDki*WwM;@-x#$pAF>cxaRk_AGdngx1x@XuV8nv$Vnm9A!D*h-Ns>-O65u&5Xg@wu#g#bd?a?Lum=YR9D+&BH6%jrqixTe-UUbGc=j2J9veo)P6h z$6{4kJoK%blRx}cJy(omNMn4Xk5yw|y=0>R%N)=eBG^1zPer7%r0GBHzYP?y7Vz=1 zY4iU5?yghdzyY`H?NqtZe51OLac9%&dE0KZ6U0ez_GnOkFbYPs>>R!{p_Qdo*=A;2 zbGX?f-6*ZK+WKVJ5ZCdWBZ=ewqIFG~{d^L=$=JEY;Lq@%8jK4ccbD}8UR*B@U4-nn z=3nIB`mA`P`z$Q(G@a_DSm>L~j+U<&mu(E4plg{MSQ?fQ?5^2+k1!JwoH zljBDB;`!FwyJtzCZOVm>MFTPdTKC`GM@>Cy{*-9C7ihQh<*GFlhXsYLfT1n_`x{U@nMc!dZF^Zv!wy%5rX2g0Rd zXXSxl@qaV~!r#Bs9&oJCfImz#%|Taa6To1agJpWA?&n;CKZ%ktl* zh)^F^UX}aU+8eNuG8t&a!`4`(Hj0pqh)-zu*6BpuX-fYfOZ^5y0gBzaNO8 zfB>HW#2WGsOpupb03o*id?3#M!~~uS2_UBUADAG|Q(lBv`40?n!;4tF|G*H>^8GLN zQ~+{!UUcQ3nG^3KkNjAxw#R#=f5!lghu-h4B<}*p>6&P6aEuu|BVU$ z4~E!~f19tTySbes%>6Ix}}29V?}*?1|50ufw@AOQtY;U#&2NVa)-K)|BN$Wm-o zDqyWvEoxQVu~J18Em#rtL&qv^bpZwRQ&RPEdch)eCveDnGK$-U>?v)yy<`JFFr zA&LMV#uswjj@?~a$Pob)nALMRK0ZhgWr}6ufEZFjkpR7cp=f{v7)XXvP#UwAlFK<( zhNeg($F}-l#BtMTN#BFDGk(E{$}@h`^LN;#6Y~tfB}VJq_ln&Z;^tFV{-`Y`uI0yX zV+sltxxrf5v~4d-zCTblrfq%Arn4>ejj5?Gt-qCQ5Y^|N=dJkRrzQFq^|h@lTA$k2 zmKT)GzxRinw`=3xn|bFQ7hfnnaw45qgCofg&mkxLlg6z)meBwHT_G{=S+B!cF)xvi zRt(u$I@xr%uHlg;*sEY*m9=JigK$TiO}c%Y>`B-N;lpQC?%jsHC88foLt(^nRjgnY`asA-7AfDjeC* ze&ja|Io+f9IiFMv#0D=>WU1^c98Rse(RR(0H0O5jW&4pduVL3i2CUQX$nGC19c%5| z`0&VJmqpL6XFeNWe7RW1Cjxb#K; z)Z?kww3cK2LYEh8Iaz$^c}eAy#cf8& zaV`5DvUZ4@A}iJ%_f@&Yue!&J1973J%T|=qZSn=2D?Sc*-sR-Uy-F8s^l|*7O`o{t zj=M`z)NOlk>p;qBTl3lKsDiZx=i`(k9Jk*)LVr;@W9F6~i4BPx_o)ijeiZ0jJt(MN zx3&P0aBJ7ss2(RTk=LAQ9FjWKIdhYab1k!Mnu~sLMVR`es(Z`oG#@Ug>GObIp5eB; z+TqylrnJwt4sh|jyWw~SH79@U@dU?}lc(j1#s>zMZuN5LlN0pq)E>DW^?^=NDUJuK zZWbDf<$F#BqFmF)3k&=m`|onn?#z5#-d3SQo0_sqJX+Sz`!y$HmuRtJoY(dB$s@eR zHOp0P_qQ!sQC0NNGv7NUFF*Xy#Qfy7LDrc3rJ3bbMbk#*wDEGoUwW@fy|%kFMsw=w z`tx^1CmJixCGIYYCa%wjGcUP)^w9y&EBBhqiVRn>9u?SfK2BVDz><6_BQbKWqhU@( z->n(7sBx~FX|gJe(0(`K>3-_tsJa4t2dCz%?PToSD5u4rO+T3#e&%V2WY@v)BXzRc z?Gav1XVlw@gRiQc`q7(3E~A=9TAS<4_{SRxZNNNj87qT7F}vVO0FE@wZOT%rMb$-BzFK7IVe!<-(vAhgp@2Tz9Ez z$6m49F+Z~U>lY`_QQvr`r{y=g^#rE#UQWxjTcY>n)+ni#i^a!9|J;5ir>ewB@+fle z`9afVr=NsG?LHVz^eSr{k#jV3sTT9xNhHdLAYVDk#;)1Av~FAL57HvX*x%23Z!NZ- z&!g4`CG=jnCsp{5lBJ7(&se!V|s*_Hf3vBIs^?KmTOutzBU!D!;Seu4k5%zl77I$Z8USYkX=Kj!Gkz>xb zjC?K&?pA(i`O=1-k9WI`r-IWwhycksGHASuvQJZe-TazC*Q@cBZS$jzM-lmjbze5$ z`XpQYrHJ`7Eia;=^+ay%y1e8ag%Nu{`OdZ5r8%dckGW@`Q05-y_4q`Ox$_jq9G-d^ zd#0{5{maj8*tscgULG|WOVeg~Y)m_IC}g;U@yAv`t$C4Ff(-v7vtb{42`SEBA0{{v z_j^{##94VGjYs$01v5v)#Mfv4iY(}ns-JS1GHE-}2Ci6yVsVN6#l!+Jr;{dpjb35N z777U=V<|*QY4xO^*#@Fe$QENbkP!H64iai+AeI3Xo}wue0|YG4K{91EC(s(o3L!9r zHfvNA6NNyK1V|WVW1!pw8xyE%7bQ9*0?bevW0i+;ASfdKa1Rw)0Sl(>q)zu(3mxDJ zl|lbNyMtDMOwnttAd17fAIg~xpoRoiC9ADd6zdZ0l=LSV(qN8#rJ~b$CB=|h$N@0Q zw{1(_R`5Cs4iX%q1ejdjX^9Q0a{>sJa9FX>H{4*Oe8u(Vc)!hMx1CHs(n_)Sf=r|g zi4>#PknMgWEDc_v2@Vi?Q!K#PxIz(Cf|_CT#a;^Zq$}umqVAGI6ndSGf?0!Ug4ZTO zjCxaob@m&QZ1|n7bj~rD02j*Toi*e$&SoJs@e~8pRIJ`4<2D~C=K{S}#+@NjqDqTD z6{nw=LQ|@gsbQLwcnzWDj+1kI#*wh}D4vb9@O141krhx@jck;EXi&f?_JB=lGg^!= z3BYDFn5in#{-Nn z=0cUURwoUG<=3GQ?qu9JhOtNyBq=G0pCsU$=~x6K2m(QI1jl*s1kajmVn`d$WOar1 z+8xnHbcva){C1!C8nY46M<5s2wk;E_h|h@`i_RnSu;xO8~C`uB7m3X%jRQE#vyqj9y3CKwzBN z%5<0q-h7dei*!c+0i1#vdw=|p(QyF)uB1v>mAYgFYzs0jj$$|u74uLbj12Pp;iwBo z-*c7crek5yv+qD^AWg9{u8pUqbYy~o;mQ#Utxtq0MHr(6VJrlp zrf@KVKLRn>byJY-)EOcDEb+!a#xVWDDF zhzoE`h(bPmb$`Wb7d6xFO5d;`Uq3Gp7DoXk$;8co4btibCYdyRFrA{UY`>E5F##Xt zi^M`O%RLlY!PK)n_#oIq(a<~u8&$HEp^Q?XAn7E%31Sal$VXr8rcktrGIS~HU`l}! zD)zO|01yBpqyk)uiQqd918fkV0@`e5q&8Cm4-*pv9~bkz=VM6dgrEt&stM5%-r{KJ zi>>{K5917D3)B7oD>;uYe74b)j)MYBz+qc(#|OkBkw64=pp%9XA_(K`2TZSM0yrnV zOT!3w;+=DtL11s;V2Ggn73td>^(G8{3m@lO8i+CN8dve!}@z= zgP}>ifuiC66#!A`Qz&>Z08VyhI6bkG1wba5bY{>o3?Y*gAj(H5_Qiz(VnX1J5(@tS r6jz9a_=Es&fuC4{3H(Iz|9)aNJD6D+l4jbIAw)3=$IWd*Z~*7u?7T|V literal 0 HcmV?d00001 diff --git a/doc/images/example2.pdf b/doc/images/example2.pdf new file mode 100644 index 0000000000000000000000000000000000000000..8fa600edabce651658187215c6bbe9ec80549bff GIT binary patch literal 4025 zcmb_fdsq`!7Vjc!HGtT!wWzgvm1021OeP_dN0TTaP*GD6u+SpKNiqp3NhY04B%ngI zU5W*zZo5@hFk)-f6(3arL42W>cEO5R@re(tx}pNwMYPm)?}UJ2?e2d2Ie%pCoO93X zo^yWpBq&xL&BKszPEg&=!nGU`-~&qg9!D-mXOLDSlLl}|i9@4JW`?8z8f_*RQcdb8 zJ*iZ3>3#R^->&}km+aKZ56Ty$=%;ULE^gj*usH6W z)PR%ba&OSy>Y>3v+L}`44)S&i`GV8OcJ{`?rhPzewH1{Nl}JfUq-CH ze<`)b==d3DZ@;VplT5$oX zuUADqFSgkp8qY5rS3~U-UJEOccE(&S-Y7hNv3%#4n*GL1hko(bd8c0+-mvJX;NScfe=C z7nPkCOC~IDI?|jwen{@qH$docco}bGvX;p!>r1kLLj+VBpg#0xxwpU7IXBMW4{?*;lct%xj z-Ir2+Ib_C{g*6L|@s&#tw+g03UppLF*0dYFc7DZ))v@~xoZ|ZGw_0I>kHd| z7@zK+S>vkBSxE*ATlL1}TCBEXX5A3u9OFCLqk_~$z8(83a(_8_s3Ny@&#u(DdkynD znq%&^t=#dK+qaMp?UgSHt_CFM50!KWuF=Y0TSS=gQ6S8?`W!gD(szI^WQ38PC7%$c4zdcFKrt^EGf zhOE7V72_2@HARl?=(v%w`b2F;kpB7#>BLlo%Kq#A-6?lItuk|0=X)g{%ziKXROZ&C zvlr$!7meweCl7ePwV`Q5Yog%c2I96eZEmpZ^xZ(;;@#SXfi=Y5#JY;W!3XCb!Y{Sj zId?^}G@m09@y(V^U|Z<8o?BH}e``}4?JZv)9J-13*{!R(kE$!w#+>~1BTL79DLei3 zr;5lSy=QeIdd-{O*H_AuRX^@g$zKbeww(-E-)tR}i(OE7D<>K(&sQ98IJJ0}_WfVH z4ri&pst#Cm{G*ZCUcM)myyCTGmGg?IOncQVQwJ+rP^-Ejo-aRzWKj+0A zv!bK&=HFZ9Ja=51`j&6O<&jlc%i3-Z_urcD^ZERgeN(F5o?6=O*n6~!V# zH?-b6mMu4KXdjZq@rNj zy=5D7u{!Tj`(~$Y_g>>O>B`i(zYd+=SoEVgrg7;UbE#L?+I3BPVrnCg2!i}3%eHMQ zto_iOJ?yB1Jn&)Gmd-k!iZd=7+tu|+&X_7Jr{uxmY~%gG7VM{`q*d<$Hn?KJkcB|@ zjR}Mp$3qK$1e6JxHWG~`j3lZd^(I0^IYBZXvT;lR#8N>D2aTf`2%CTpchRJk0YVm2 zA(^yO4q8XrA=<{$lrElRl2M4q08JpB43vvV$$>Sbtp%=%YGUy+0J7@>!bd%l=k~ysVahwzYH8@z6tTvA*)-URjj3gMsOd0!B zc%0Xe455b{0HYjeTRc#~qbNA&%vcS;luC~!HYm?!6DQ`dVsVeT!A9A~m2e~jx$LKh zsUqwodoJiy(mao3Ogh5tH_FoB5nAD0WwIIp#>N$g#yhkOn=kfIpeOx7KM{4m9I7@M z3?$4NOcOjd5o$469rl#RB-!viu6V9YOehFfDm^tMpX{^|x^$8OTGD8;D!3iH_i=$q zuiz$%G<=OMl1wvA&7#TptTz*MS?M~do;z8|kxwRI>5)7qVdELxcds3gcAa8EWZaDC z3G4=^%xSS%U=o1SVz%04P6gL3B7a_#vbB003OcG_WcSnQ90N3a)^U33z;*#}~oK zATJV5RdC9BlBbmSGbuU&rc?QQ@c>AJhH}v!vJcyJ>UKW_M-lbtq{jS&!^6Q5f`7uag-l+Csp(By2V_ zgci13QCL)5r5rLD6JsWo?!JjIGrbG5iR}ZKnXnoaTqjRY8VHA(;VMxZZJGyDiZT`( z%GiXsgfGPS;#9FnZ%7T-2@I*)a9o=zzz8j25bzB`gA}pZdy{20DSH=gE9fK3Pf4Yl z1iKh!7463eB?mmC=h-QG1dQ-HP;fI?*n_KqSMOus+SkUxzgP7k@IGWa2d0SaonW<$ zZ7e>{7x6KnNQ6N??7H7$xkV{DSQC*jBSIAh64FSZA(*s82$1$L5M$LL;4PB2vv?&& zFd@Q6M0hxu6C4MvVA?q$2$*RjX=ol^Hu0HuhP23lnxHdGR(SUy;RwI)YdT3=Nprul zUZxCapyCJ{4S*D2QkhU7!$h!;695~;>wu;xM&`6Sco;5~A_5$dWMgPt)QqTz_^8w* z37!glak^g!j5C2P%;5j8IDCK!IV=SCJ^&Yqgd$)79vUVR!C8WRfVGb% zgmco9GzjT%Mj5yd6AIyIHIT;V!?2&AVM6RT`!F1XAFXiG8@_DYDYv z(j+1{l=R6mG+{E6H2iA}(0Ef83C{(<$&P~46FXS|G{$P6K<_Yw#;8HEJQ^2@gwZOD x&zD3*MN1>q5x7{zkHn=COd`a?CCdN4BZVEz> Date: Mon, 13 Jun 2016 21:22:40 -0400 Subject: [PATCH 003/197] Added one bib file. Updated gtsam.lyx and gtsam.pdf. --- doc/gtsam.bib | 133 ++++++++++++++++++++++++++++++++++++++++++++++++++ doc/gtsam.lyx | 2 +- doc/gtsam.pdf | Bin 819397 -> 823965 bytes 3 files changed, 134 insertions(+), 1 deletion(-) create mode 100644 doc/gtsam.bib diff --git a/doc/gtsam.bib b/doc/gtsam.bib new file mode 100644 index 000000000..8cb4f1a55 --- /dev/null +++ b/doc/gtsam.bib @@ -0,0 +1,133 @@ +@String { ICCV = {Intl. Conf. on Computer Vision (ICCV)} } +@String { IROS = {IEEE/RSJ Intl. Conf. on Intelligent Robots and Systems (IROS)} } +@String { CVPR = {IEEE Conf. on Computer Vision and Pattern Recognition (CVPR)} } +@String { IJRR = {Intl. J. of Robotics Research} } +@String { RAS = {Robotics and Autonomous Systems} } +@String { TRO = {{IEEE} Trans. Robotics} } +@String { IT = {{IEEE} Trans. Inform. Theory} } +@String { ISRR = {Proc. of the Intl. Symp. of Robotics Research (ISRR)} } + +@inproceedings{Davison03iccv, + title = {Real-Time Simultaneous Localisation and Mapping with a Single Camera}, + author = {A.J. Davison}, + booktitle = ICCV, + year = {2003}, + month = {Oct}, + pages = {1403-1410} +} + +@inproceedings{Dellaert10iros, + title = {Subgraph-preconditioned Conjugate Gradient for Large Scale SLAM}, + author = {F. Dellaert and J. Carlson and V. Ila and K. Ni and C.E. Thorpe}, + booktitle = IROS, + year = {2010}, +} + +@inproceedings{Dellaert99b, + title = {Using the Condensation Algorithm for Robust, Vision-based Mobile Robot Localization}, + author = {F. Dellaert and D. Fox and W. Burgard and S. Thrun}, + booktitle = CVPR, + year = {1999} +} + +@article{Dellaert06ijrr, + title = {Square {Root} {SAM}: Simultaneous Localization and Mapping via Square Root Information Smoothing}, + author = {F. Dellaert and M. Kaess}, + journal = IJRR, + year = {2006}, + month = {Dec}, + number = {12}, + pages = {1181--1203}, + volume = {25}, +} + +@article{DurrantWhyte06ram, + title = {Simultaneous Localisation and Mapping ({SLAM}): Part {I} The Essential Algorithms}, + author = {H.F. Durrant-Whyte and T. Bailey}, + journal = {Robotics \& Automation Magazine}, + year = {2006}, + month = {Jun}, +} + +@inproceedings{Jian11iccv, + title = {Generalized Subgraph Preconditioners for Large-Scale Bundle Adjustment}, + author = {Y.-D. Jian and D. Balcan and F. Dellaert}, + booktitle = ICCV, + year = {2011}, +} + +@article{Kaess09ras, + title = {Covariance Recovery from a Square Root Information Matrix for Data Association}, + author = {M. Kaess and F. Dellaert}, + journal = RAS, + year = {2009}, +} + +@article{Kaess12ijrr, + title = {{iSAM2}: Incremental Smoothing and Mapping Using the {B}ayes Tree}, + author = {M. Kaess and H. Johannsson and R. Roberts and V. Ila and J. Leonard and F. Dellaert}, + journal = IJRR, + year = {2012}, + month = {Feb}, + pages = {217--236}, + volume = {31}, + issue = {2}, +} + +@article{Kaess08tro, + title = {{iSAM}: Incremental Smoothing and Mapping}, + author = {M. Kaess and A. Ranganathan and F. Dellaert}, + journal = TRO, + year = {2008}, + month = {Dec}, + number = {6}, + pages = {1365-1378}, + volume = {24}, +} + +@book{Koller09book, + title = {Probabilistic Graphical Models: Principles and Techniques}, + author = {D. Koller and N. Friedman}, + publisher = {The MIT Press}, + year = {2009} +} + +@Article{Kschischang01it, + title = {Factor Graphs and the Sum-Product Algorithm}, + Author = {F.R. Kschischang and B.J. Frey and H-A. Loeliger}, + Journal = IT, + Year = {2001}, + + Month = {February}, + Number = {2}, + Volume = {47} +} + +@article{Loeliger04spm, + Title = {An Introduction to Factor Graphs}, + Author = {H.-A. Loeliger}, + Journal = {IEEE Signal Processing Magazine}, + Year = {2004}, + + Month = {January}, + Pages = {28--41} +} + +@inproceedings{Nister04cvpr2, + title = {Visual Odometry}, + author = {D. Nist\'er and O. Naroditsky and J. Bergen}, + booktitle = CVPR, + year = {2004}, + month = {Jun}, + pages = {652-659}, + volume = {1} +} + +@InProceedings{Smith87b, + title = {A stochastic map for uncertain spatial relationships}, + Author = {R. Smith and M. Self and P. Cheeseman}, + Booktitle = ISRR, + Year = {1988}, + Pages = {467-474} +} + diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 9d1e6831a..38c6d2b4d 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -3748,7 +3748,7 @@ GTSAM was made possible by the efforts of many collaborators at Georgia \begin_inset CommandInset bibtex LatexCommand bibtex -bibfiles "../refs" +bibfiles "gtsam" options "apalike" \end_inset diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index a5b92ec27362e7b2a3153fc98ed45406a4a5e2ac..ef4ec2df15acd3df8d65e97571ce0fc4e7865f65 100644 GIT binary patch delta 78618 zcmV)1K+V6!fij(?GLR$!I53kDt0;eUSW9!;I1;|+SLifF)tC&ym&my}$vErTxOOVm zAyYehfJ8__g(SEHXh-|&w;K&mqC#JUCeQ%-@%00WSI1Sn`ur|_WBjmv_x>SGS8Nj{ zEYDWk!-^GEv|;HgFE&xJfvI}+@8Dt0@__G+8rETw$HC`;_a{v>?`k)>eZGHx`fdH6 z?H?<~qP#3tVX}$RYC~t-6W2e0Ux%urugA^|svh@7!VK&rX;@U{d4kg9EGn~d6{bm) zZYn3tz`O6X{gY@KE(T*S4XZ4wD!3K2$xvWj3PLGJ* zPLlbNTc@HXV2>(uJ{kL(8{ts%g3^jXOAm>|pjx8LNlcbah}wSjOWb)-Iv5%*8#VY- ztu`>Kakv5}k!chY(a7Dvhw}}LcLF6ktFDeFZ(f|@^qA@Muud+~v0>g&KYO%DAhf_5 zb{8MS6}yAyCJ9%|jqHxVSXIGZwS8l4^kW^SF@RVb*>Z;@U;qT} z8qsQyD`g2>wm;DV*EBxMc5Dpqgc>y+@kN39@_$!{kd{C^@xFhzcOxI##aPV3@z;ZK{g~>*+@Rn z%B#e1!8P7NdMi`V;z0BB>o3}7HF$t6LiA7;-zZ%uJ6cWuW-hR zR>`+O)N&Ae@+p5#?=6J)joi}&AriGLVo1b4!#ZJQlqHGB=E0-c@4Z_TLSsXZ#rPGGHW6JAevZ#b??atZBo(~4#xo}}xL=_YP$7$sv#HK|FnLnQ! zaj!Zp0h$&&AeB1Mcu8xTCV;VX#!HjJ21IJLz^EQ12QYu5>2e6e?MW;dFNW%rOe)yS z?l&%|kwHx>C+J2(=FP1qZ1X z^n|2=HC59L1_6%!Ac<_ydbWP$RgY-oc+BBWno>#n=vk%m`^ z*%>JyMjbBY1u%sXz5x2dM;QnyO3ED5v%amRuB?9p1y+V6xWDb*UL=;_h}yS>BDb~0 zILW3;nxqgas@bU@G>_?YTFU}$u;C!SgUuz#17Dv7e6cb(N=}o$MI+wlR)MHgZD5h) z1H#n-I3aV{|5gC02@Olq<5hs=56_=MNQ$DfIT>d@{`xBsmu3Jyc6?&61qsGkHw535 zQtyB0qrS>}jq3egTY_PvMh1wv?lAEP_?BigZXI(Jj#JmFnnfU}qwQL%VCTm6tVMG` zX$mOi&~{<|rzLx)WuZ}aKxFHKRkiWl$H!rK0`CVyE(;1Ok7`Gd7a*o&x%S-5TO#G{m&$o!i!EMeJCw zafWIyQub~bZP6vB=@t-^Tt}ZSRB%CJEDhH}!M;`vjuTp;MfY6#qhyoM`=d=U>4G*c z3$ih=Iq8Yv+S<5A3s3jZps-;3<^BWBLt+$zL#Ci9-yHxuZ(Qbar%)Ke0zg;RGzWio z8D-A>+#@OJaRY12i+5AD7^jZy?k1Ih)m_(Z<>NNny`5QH(qL8QGFaazi3u2IG_(U+ znlpW&7g?2B|Kd0HqNA}wfU=HB98l`N<2cz%kQg5)6&P(@#=*JA_RBNQ(>>0p&aYiR zqu$IavICP&u4OJ+u#F1^m>5K3m-T;1_O!HvhE52_&uPH7*6HpCsG zvksr%rJ=2+%*k$^Z>+rPmu}EXl?UFL6gDtgql@NDUsHb+Q6u7>d9dQgE4R@DEO&`1 z^GN~WeN+RKs@Ctt&_dJu9kQcwda30uVLWiy{kt zCm?sk25pU_{JR!u+fX9`m4%2Ji-n(~ap%6#ZH?_B;Nu2$Xgtg7MrzQPRA_}csaoIt z^iI7^x)4qnP3EeDp=o!*?aP=R2SEH6pL?!Fm`mw80&A_~8sP>CY5jJrUS3GJkuon3 zwd+(H#p|25JK!G@;2Up!Dji8Pt+{c1V>Rorvna08>9Ju<|J(cbfc5h@G!c0G{n2RN zE_9qMOC$Ur#_hD4O@DuZZbcQb9A6Mo6}$hJ*o^1*?YsX2LS{6+lTn)!v;PNA1OhQN zlM$;ae;QqL+qm)Fzk-j{jD_Hf1eu#Yp3Qkg!w+?~Sv9l&f86{9W)MM2(wN6)0vbR&;ZcO+Kk9Zi z7gU7X2Fs?+Y6p7A+ZEO_EUHq^H`%?$uT7n=b=|dKc{gLUL&JRETQsiWgQ@Ugl`q_c zx$9q6ZYewN5kG3ZDYAuj2(>G>o}RHN{IbwRp-YEhRxZsJ&87@dq{K}vb(`gdULq-K ze{E>z&h;m99l*~1iZsw1bF7kU_k2*@z zkr=f4bNtiI6@v;5Siqu`Bq9xD%1M$$!D4;&>lKM@t1B$1>+b+>-mh8k$Li{D@Yl`S zb(wc_&Igks>kJQ`(UkBc4y2MKiX5fhf9LmGppV6$y*0-~!*?Zq|M}CWYpiX{x+;2l zR^}XjGyl4sx2syaNm}5EdDH4mbKOyYQ|ks!tQ+1@KEvY2>`}WjDRn!hTUQ2ip)Brm zo)E#)3GRt9Vql79RrQAqpN4f%0-^yS6wo0SFtMEl);GMT-4MXR@?us0;t`%Wera!z(~v$5Q~95Y-}&L^V|)s@tHUEHI|z zEc~goybqio5k{l22pEZtL`Pjyg`F8WRB5O)D~1LJ7-21Uy|SjM7I|h*%X~W>5TOo; zWVooxWjT&^iG(JhTb8!(F zWdqc+=unpn{mBN+hN|0d*+>FCtUf zY2CebB#|l@bg@V4;UGY_XCPE0u)DU-3c4{SPTj5p!;^1%;#*Qd-e?1HYRfV!1Osl;@Lt!d0A>;_PeM+`o5=Ar_lG2b#C8*!E zL-5w2XZ2;LEKLI{%L8&PDWT~Fwb=psQ|8;`h%@&#c`9d~M$qJ`rJi8TerLqkG8KNv zt#fA$XNeU5r9>yd@rC2pIT}k2E>f)6*vcH@WpI?!e!;K%f+tBVe}qqQjnLkcylc-= zk|@fawG{U%znG4eI;a369zSa}ams2BMgrj^vf5R0aQndfGwyO*93JG zU8u^i(Z6oNG0^+$!V*|grr*k_PmX15-hP1VR;+yUG2p9&dF>^8iW!c~$bF}9o?WD@ zr$@WWTBP_o`;xEof3Md4b*EzG1nz5uv58Z;slflVju>=K242deXQv4$?o0S67dgZi z(EOX7;(3n1)U>K6EGzR7or@7i|G{f12{`iSD85sK$AdUyg!AN>3-hgT=a8cn({Oa|DGF-YlYkC=j52b$EYAY6;E^J#NT*{mE75_f0LHtCog4uPVilmbaIhC zWI>bkIil#dpDAdDp|!5Nc*V%x!Ktf$*Wleel%C1BQSf}|xJNE_#v?w`-0+z<4qR88 zs_wm0fV7n>`;m3E+%8)DsP3?A@-Lpi3a5+!4g2tjjRX2(kUS+~A5|Aa+O6W^g{Ha$ z`v<=QkC zH%ArTYu|Uq#OFZSbM*6Q$0Mp7HQ_J1F{$TX=HGhIf0>I&5fOoZ!lCSv3jcT3zMr%9 z5-%h@n--_d_`K`KcUA@8AkcVN7r$B%k-uIL@mWFc!{_i?M|l}ReNG_!rIfjx5Abp( zKh*^|=@$56aXOze^5Svw%TVUKv&>n-lssvR{B%)A=pxTHDc*d#k~a6vB_#=*$?5rY zemI}*f99MICf(1cD;{vp0ZTPWN7FRqZ%w*3#Z)>?Oe!54Fr8{Z)or6|yv{7KZFtc( zHxj0XiFY$(oFj%ICNb=~j`Qr$+vaPaPliQzX_>LGa-;3zi~|{WYVKD=CNXaAW@Qt^ zl85W6bvH5d;H1?KoMExd?+pA-*Z4*QKz5aUe_?aQcKlKoCJ`OOaL*-@C5lMO$Ct># zOdc;cl0>j!&dSVflgqNdMB1vx5_3nU))NgsF>?)-ZP}#@BqNGV?wErFgAmeDqRzA1 z!kg5IQ^I9(j>euwE!462NKEMNV*MNqcw{BGCPW7!AzYC2@}S2;GO%WBvS+1U;A;dR zf3=BDm~wOj7bbyj1KOqu9}^(74^TI4zQE?ZysPSUhN*S~sJd4a=7|Yqd(RKnHV4X3 zoVddL1(dzG^El)t8AW+`GfPZ#!L~15X#?!rHFnJAeIO>sW}~q`z5DDQfzy}4Z=KCC?GcIUbOgXys`t=-zW@BS~?)OVoXB<}ukjaCE9=~=7!G!$sd zln6Otw47*Scv(uvtDs*|WfoieDKOyI>0bjt`36(v9yChP87q)875>yBtXWmte`1Ma zZ{5&Ep|cu6E*3bP*u?3a+*)wvX6i9>3I|P`No-jtB52=0*@<_r96fKA&`g0HNxGL! z_T3f7_hLe-?g18b7|%527$9S^i+3O578gc{M&~yP19b-&?X;^J*v2Gmw&0Jnh@RQ4 zf%y#Ekh>TYWY65}u~&Q)J>$W$e<6B#iwNL@kH%qD!s*9Un0Ifs)mdxh9)@P?jYAXo zFBUE-GdP!9U7+2bfqURWz7HE%dnQ@kf@8I4#_m|aQXsKRO`LA`@KH>i;okwb9C>yMlTw=!v+Wg0 zTLCeX5vwSF)mrP5+qMz^et(5NQZpw64}t{K$4pz-o@C-oQeQtM`M{H)6MGaXlT^-^ zzrMRzfG^RxOMG?P@yrR2&s)CP{ zj=Dq9QmeIFw^Z`>=e#T*{qD_Z_ex5Zf>Jr{z9b#m1v!;s3KZ%I`^`1(0Dye8Q95Bl$<+oA zDvpV;UJD)ljDKuH>g7-(7_&(5AwQlyd20zxe(Tq#8ignCHrb(5ri#xCs z+I9RTX>er!<=FlgMGb}n&4;4%t@B|0BU_v^2uk-8Hs2nG)AR?`+0#^y;TL39PMnQ@ zG)&2{r)V9W@}?`c=Q3~BF^{fsFeN{M$#ZLaUmj^kv7|S}UI6U{n7D5e?LX?eLS!sW zO>fgRaXIAGj_fe;hS}MsA`{aSheb1%NibtQF=OWvk}DRY;A5BAH}#REeAkBt=t%rA zkqaBpt>|3S;5?7i1BL9*CAH~GL#~j2Mqu-P!a1eWWES1pZH`)W6Ga!kEFbCHZC!PF zQTat@2cE)o)7bV@S3B=bDXIx&<1;_s)koX8T}pYOB<_6O?E+@=#y5)N$u@gX0(M0N zdZ%$8%%D};d`FY+bYSHDx!B&9ew}=~Js-hzysrbePFp$}2p#M;e@&5sb{^zKVY2nzz<- z87u=j5GP<#I7P-o7=W30Nw)S-yLbnDMJCZYM5cxyh-2f(fPEhsknZ7Nkvoo)z;qga zt{I?+nMu+7S)BRZaUvRDLNSZs`W(@qDi)Sgz^r%s50{H+mH>zGV&Zv=iG|>x;a(JB zvBK-JJ{DbPccdw2t~d(r(>XiE&V%){yPe$yJvP>B(g!Of82j3#tUv;&LdCPt@f;0{ zPt$Px0vb-oYyDwiA)t{x>iA_zDw6$wMUHYJ)%D_T5-y&w;&ieb`Lx(CregUF$v>uJ z^MsDo?~v*lDh5a_oqt^J3cxb|jmlP^QQ7LVDO;;7(6;1ecu5;Ql**!{#Zg zfcTfhVj2en<}-2zSxi6|*f^caVw>NVzE7GlYI^rB$Zia~ILqH5dcu^L*p1KDU@JR& zvcWqh`Bg?&#FO9%G`45JY?WUrpc-ffRFlD>vpaU}A!>prolN!n z=DT-Ds1Z{l@@uaVdw4il219~>d53o3H>V#!Q!dTRlBmh6JG=Rjb6M?ZOcQb%s85aE z5Hc!SkKo|LV}5e0B~jgfwzGJb;w(u?9|zP$`&d9i12DtfaPMNuTd@AuVMCt;n*>c_`&deL{H%SyFyHxBW_^+k{yrL18K3hNNm%?%Hb~rq7 zJDj`q6L8q%)NZpllhZ^GK-~&pDXr(!1orN1ap-m}Au%n=Zc|iadM6&JY9ikFz`w1F z*1oNGwtT(LyjH{?Z~nZ0pqR|CSd4=xB%cq5!o^HwFf}O$be=ksh2ao*pgAqeT&7Au zLZuuNKK5}3g09a_VXQ3fk&i8l4f!MOYa-R5u6Oga-IqV!KyKF-xli~j6yN9asDve~ zBe-S;t28om1s%7-H0AxLrn;BX2(Tj znq}Nzz2}FY_-Y4}5U`la%<93B9zh+M(|NgiclAA0g~p5ZoJ_*BnPRrd_7f)31pXT3 ziS8G5pPBxGKU|7`rrB_|FLC|@n3?UB8#B=GrFF2SW@a*BGO?5UCG>@|#!Lt`(i%n& z&}5qQizk;x1G+R|Ge9SLlTnu|2+j=pEqHIwZ6RgZa7Z=4vH*An!&)?E4$CDokUTw{ zO#f#NXA&d5V7TjSUCxW%L1}%i`(*% zCMtl9MP>7b0wxZPE4zgHV#%aTXVrys<*H8C{@EZP)QQ9~OU2kAFs~l(S1J+8 zWum{O6ksub|2*K20kE1ca(!EOHhh*ZCMZg=Y*5Ogu?ZI~XWQ7;Ra*c^u}kn9q>G2- z6s+Z;T40P-Y|&HYx1%?Xk?Nd)z0kuw?{4#jf)C(wW->KBl8;=>|9kiHk}rzEP(npl zhtjjeYPlRg4I%EclNq#%@|?SZ8xFgt9|Dy46U^0r^W86k0!Y7xt79o-pe`oKv>I@r z3?=1*V$$%n(5>bfxN>go79-C011a`Je$lx1fC&C~yWoS*PuKJhjgTz%Qp9>4Ob zO%Wc1N|f)x3HjKD1jvS`rBS@afpNTD^l1>+{Az$tnaoCykojyo7VvR+XY4)Bzix&6 z>|Bk1W)e*=PCU9Bl_IK{Afxcf7M`Ov0wY2^PenTW0&t=$VK zw(l_K#0I@2W9v5G-jk}E9cJWM+o|`Rt!VmKv?Z0Cxy#1rW6y4jc?o(8K0x5W&O#jQ zJXuwDqj&SEc?pm$>s{!(O9M-PV?g>Cfa{rm{A&qYuyk;gm$Y(-x{}W>!mnlzsMj-l zcrut9!+6pg^8a-ZSIPJ$zq~RbNT?pE?x;@D->nnv3#Qd@YlZ;QKa-)phloxEn@gcm zNXfW-Dn#@fIyLpFZi3yrL#!9LCV+BH`Wb9Ieagnoi`)4489vsKS3pRQ0jU#-ng7oR zhkpZ|UC4g3Q+vS%12{Q1lM$;Zf6W_dZ`;WAyMG1I0)e!!#&dHf$9^c9>?YYQ(#9=X zY!(GA(KdHwQA<*B+@k-zZw?+Kj}Asj(GS9q!{M8EAHye{+$1>p?hO0!50_^buNX@- z(vr&L@;XrxY0eW#IMO;zE*Hs9lOKw@DONYr8C873%^)WAZ8@c4a$mdIe{AKZ^C=ON zPubminY#z&%8h=xTh)|qa*=<)n67d^d+XnsZ|bJJbJy2Xf+yL$DJ!>VzRc=+`t#+R zi&ugU@TLkQ!U<4iQU2>Hs~%oWweauS7Xm_sKq3|G`up2re(QED?q+6rGGhWGDU+FD z1+c`f1G?_=Rb!|YfR`ISe^AQ4d-r~}EPgfE=5Wv5le;{tHls>(9;^ktNvhkmPKS@dlprm5``Q|iVr;T;!<8Eh-V7|z-OcwRED@I- z!hb4@I{&d;zqcQP|$w~-4XxobS5#L{Cl?@ z3xycgr|I8l7~}L$QpAaN1kthjM>!&tw)|Lt{g1B&co2I-*B7-@&LL`&)9iFKjB$3#6@tiYRgN7d2t2xm z@g#yq!x%>p69`jJ5&w+9C;Pzn8Q~;w2#g@y$G<&!8A%ZZ*KrbCN5dG$R!R_~%uyot zd0WZ=4>ls`chT_!7WhB_eVaeH;P^{Cit50JADKW%slR_psQDD5ctFhm1C9@I9MjKY zq^4|`Gcs(Eqom zNPeNXkd7;)pB(Z9za15!qiW&n+mqB{G>ma-0o#8F>Pv9FkGBL;0@88qsx0f~fWv9(K<|!FPv|IJ$+k<}c`>0+I)ZxV;ec8jBf!gh4 zP6uaIuJRZd0y#mDgnaGfE2`SIBs{HZ9S`G3)lLx>GU0+E<%=u{m;#qD?e)%KHIHzzN$V+ z>qf&Er*&XKoVB(#`XrY@+CVzNK(YaO5R`wXFr?s$?A^xQ`Dd%W2PzUtEJkRgPjQZt zYOgiVV<8DBk$rSKlsTZ&Gk@G8G>a?mAm*HKtbHgO>e+-&FCh*SbwpXif*85SynGdW zl6j4WG0waoa;MCH2PW+JP`0}UW4^#Sh3fGzMo|rLAOrL@7~uzkkoivDQvGZX*%*Hb zrcd~|Z6KsfedfpQW8OaSar*=Wdclq4!tSOG!cE2ie$Rar-D=tpc*37fXN=&<%TM#X zTKisv>&iA+z}28@qrUi|oM+48Uzw>1Ub;y%U#|nnCo|XzcAQbDi?r8{*O0z4LE5ek zyScfyeI4#WRhTZ2k7m1k;U--}2V8$r+bd$Gmc`1yK_E;6Rg-&vzphI2?#E)02e9d+ z$pKNQirsWpO(8(tY;5Dj<7N?t1=4-`{%$J7WKgCKSxZwyd*5vuR}B1OwJ7G@ZUzb0 zF~UsMuELg)=3(9T!d!1Px_mU;$f_c{TKXb`kYO(lMrzyR4{_s2^&u8GMKyn$+~4L^ zp82jEzmeGLLorP*enky2*GR(l@YGxA6|1_*R`Uq5(GDC?LgNV@g}H#8p!2*7WB#+^ z79jh1BobR#xP}NB#7khm(xx~LxZk!I85$vrw(UqTIu)ZjolrELK@Bvyv{b{Rc?o1! z8{cvSD~9jX?o!O8yQm9Ly9a-Fy#_^g3;K7O7HS}BJL4LGj5;^@ zwBtiohC8mz0dcFB3K8%l0cYGH?Tj+w`mva|Cd%lf-mLS=TBcDeCOmjpVil$imXj^@ zf(b|Ma^qIgq1`Tk-wZR)Z+LcR3U&Jy@UpBxJ~Nk>m^7V@XQP`?#MWh*R3spcag$s z4@9)9e4cIU+`V=0-?_JHY^{cPTZRe041<-n8wdIhm)Gusm_vUqgF@!#&3WLR&j4b^ zXCzVQCir1J$#W3s~#F4kpTc=LceOTh4PRbG|N zc}$bRL1TYSjL{;@$^TZNAu6aY2ySPx$_!nZ{kwRmOtldKMp)8dUxEh#nuGD1L=Va` z5u9IzSp|4SW}q=xuE#)ocuavt3ZfnbKZrd~e;*Hz1Tk)s0*pBEEANZuwiR`~&gadR zELot8t@LBX65#?VO7_SE(y_jM;)N5)4)L1v^zDBG#7B%#2iYtTCL$RudgfZOV-OW+ zl#H^P1bUS!Jp!T#Ab!A<#&lKSGzpeP9dM9od8>UW^5tUNKCjE=(*50|JAkltQvP^v zLZA{?om6NfIRpF915?5g3d~gpgGEavp7zO`jm}SFWl>#RSpmD0`r7C25X3d!l=HC zeTsg0dG=r3ecYI{l#P5H0X35mt2BR%#tiS0x@Hp%g1y14sRw776A@k9$}Y0y*N5KV`z6 zm6~0(<3sOH213niJL*UMxmJJqTont~%1NC~p!)MFS2NY5<16E$=VA-r( z*ZGaD%gb4stAE{Ksci@bEgM%-%xzgGp_WW5g8LeLAt$trNVrfFD!_kOV1ul%MXH#U zOKYZxhILldWo2uYSqfarbnn`h{DlR6zOE`D!}QOqi3o3+%+^@3AoDa;xv}xhu`Qq& zOXx?mp&}kW&1yBz>LH1*ud+^7ld)bz~b#q`}%QgjxNNfhvtAJ!~uqV)$@$hm2gS7ZebofwZ z4W8;5-L#I^b?Ygj^%B7uF&{RS+vv%6Eka=!3Wmxm?d0eQPU+rKNgo z3=K5eFhj;DCNyA}A`&Os>F?g-U=DR4C}K$*T$`3l_}7bA6y(7<(5HtW2?GRyfI4>} z*#7tyLPQVhoxsW+4|L~}>535oa4Au2AjVih+mXgG;t9DMfq=Y8vQr9w4B|rk@1V{7 z+Qlv~Ee3!0KD2sFmiZg`Sekjp3sjq)hSdKodn#wwHRjIOiqop14B+SE1 zblcY-cY9J2gcCN-linD9o|FQ?cHC;h?(!sMh>~yW$&LBPyRu`&xmqmKdH{$~M57K! zZ)NrWKDa+Jvx*!7$MiP$^wbgvJal|JM|2bYe@FDgafc;h9A~^S{5S(UBY}B)cs)4! zcg=r{6r|qJ1r4|aRf@@tW5*GkD|kh zb!~pqLXqPEsJ{A#U}-3P41bzRLy#O+Owu*Kb22lr8gC)*<0sR+k>mL3jp4^n7NHos zHC=ppWVo#nf&DxTJxU{Q3_p!1M+Cd;BH4dG9w6w8fclVDi(vcncO8#B*%^-~Cmu+L zwF=&uneK^=(ffez4#f9_e`)4~dOvHhL^MgpvBn$2k2SE8aqRB)qW|G8ZMj26I2rLn z_GiRw{l|FF7s1PaB#|g0R*CpwYxeE7X7u=W?trZsai^Y9gz?7kqf87wA&xW2_ql&H zdus1AcW%xkEVY}~r~5W~9(yxG1vQVg;%q?qa(2ieis_)Gp-L-LxCBjiB`>y%z z);Rl!>kfINi0h4UAaNsvg#`EnG2+gl1mDSAds+Cv+?Kg5$=E$H_ckbOu;pfnc>Uq+ z&mZU^6Y(JDdshBtls9M8amQ$X3_pL$3xQ<&n*kvYl=q-~d!@o3D8He+JNAyEyf=m) zZ%<1LZv^&mB9(1LZfAclRQrDDREoM|m2<;mlp#5VrSTfw)8aD3!c1{8WP2 z6eM;k@e$Wiy%_&4ucP$aiu=OeJi*w@8hcYPhBLkhevH8w#qQ@qA|9rFk7<8j-1D*Y zdz|(Yh8Sfd9%lf6p!6%>W*pFY&(n;rAHIuLPYd*4qxN1f>E8-t7DNdmR9FwZQgvhB z@oc?ddhvOdRV(*U>#{1Bx8CH`Cx(IgMbQgef@Z5#FWO=45Qs-oKdVBxJMYskC%FFr z9;ntg3T19&b98cLVQmU!Ze)|6vj&5|vbVpo0SbQtI5m?It0;esR^4ygHV}XJU!k{2 zz@(D;u%x|ZXcC}Xfp+oQhjkceiMF{=k}Fb8v%h|KJkqg~3>XZUz%b9Lv!mIeZ7>-&JgFOgKSIQ7&mZB%hZk~pVx3m2$ zj$Yjt#&UcF>07VugBGKh?|!{{fBij8{@lEaQuF{k39IwOssGEpl?^{8X_2?FIZR1j z#SbGKc@ZnO=JAc%FS8^X&$A>gLCq#?fPNji?KqVwdi?xALNiwHjSoU_0$-HJA)AyI|{hb5Q>FEDP{-UUHvC zyyLv3%@<)PmsV! zJL9D>uX}$dkfUNTXS5C`Lq>pX6>*-mRh1)VL9WO%#wwDlvJybS03BB(_L~$s{hZWQ zJk7c%+O>xwJa?*w>&=S8hDAJTc~&)5RIID4t*fXTR$o_HQ?y0y7|yotDu{W)o11}` z(c5YD5q{zIz?1s7)3e84)?uATMOkO-5R4NXD}aAv@l%pkkjT41XiYRDJF6zdZk0O> zATb2Ir=y+4-xBljNNg@;cmc)J103%S9WnoQmeLSgFD*!gM_hftD(F%R_mijlkt?>|~ z3QZ?(GFG+ZKBBP9vAgN?0c*me5Q^`jDI$}rQ&`WM67sniluu0w_q=cwT*Qk}1L%qoEqJ&e&z>hS3J^$klh%Je-_D}(zuW06DXH1>l+^r`5;Pd9Fc=KH zp25ybcTW`gby3Ho(_V)mgDipw9&fmHcuP;<0t2w!0qe%K#Ts2f#iwR9c9J9qVQ1CJ zSG$f2b&cc6<)UuSIys&mWZ1zhJT4R`IDJD^5=#qDa)(M$vQu)zp}4MMbiY~0!oPn@ z$v?zEQSVkSZeDO68|*nW)ZrNb6mTDnG`^&PIBjik2~Ien9d+>^0yGwkC9=?a zz==H!bnGTIcB=PQ`s{;{eQEeB?!AA^w;wfIK#dzuZ9Ms@vs+v-&>SjR$e&TfK=Ga& z#$25NY9`~pZcyf+`d)g*t*2p-DDr;j`r$k*-GMkSzKP(bn?^u0*&C)UTJisUqd_JO z^mrJ~hK^|U9(p%^IpF!E(sOHlo-LqwJi{&o3AU3Typ%MQ6SG#*AAA$Lr;{iepEL)2 zqJ*VY=**h}d2C*`&WN`xYoJ%AxT)KQ+|Bv((fltxwayNgk@f@=hpsjPhpsjQx2`q> zyS4!~lM$;ZKb2TpkKDEue)q4Kw`dTLqWi@t3fO7w+OdlQyFh_9MZuA{Gt5e&B1+k8 zivIVWn>3oSwrF35)H#QT^0W*{{9dLq4(E)5qKhkWEQadF!g@H zA3ZS7wCbcCbDzw37HU^(l=^l5kNZ#Gy${3HNy0Mo<06N1(m@Q1Tpc#{lQ^0MUZcv= zQ(euwn2z@t&qns;tyJ4LdS=a+Q=^hqjwvUzkLD|M%u>P{pY~w@S0rMkn+8v|JAZ^_ z=@(%M6EI(r@S)T&sAu7z~UDHv!UVYG^b4il<6XHD{9)WGuT>Y@G)TD^-nlVE*{r zi{z7LiOC58qm&HFH-VF{^QQFkG@S49L3esE)n5ktldeW%yZ8Gt@xf0C>i;W-G+70vBId;mg~77>3^c=eO^`d@*F;&y(a8{HR8w zjgU^^4kOzcCf|R%54~@BUYE)51VTH*yfMc?;Wdy@NH8GlNi(H7TkC{2S{^4S%pZd^ zU}FN+jgWY1sPS%L=5_WksM@H8xwUa%BHT&%DXW)8@B}e`cK7-17nZ~`-?8hMm7+Q- z9fe2!Ah9P=CdrU^?zuhMhMA9;LzHgMj=7wBmF~yu<(DTTQLnJ9AQ$O!59_W z0zSX#zYzh;W34+oiY%qRd(9tUu=BiXJgZLD<0%`_@nD5NTgRs}$$_p8_Ob23Q;I4} zjE)>Nww5A)#{Pj6X}Qn*1sj1Z{iH&TF* zBMQ9__jedFC|+Bt&@k(?nJq2lB&Gh&t|S!DogA}&#o~$gY^OIEUb$yRrZ@xW;F;(B zz%a(tS{6z?z%ilqANLVdV=HfHY2l)+q#DCDqCwpROt#)X(oK) z0Z@y7gK{m|8pXj3!Z_O)=!qj`ooGha0)I~ef%cy5^@bseXCdq%eK*-{fALe1SD z)QIS5P(474d6yO@2ncjL$|-EG5iL;vAgx;t1?9~F@&(reKB8I_ zOS!^v-R~lD8m$e#DY_4gQ;%-0`J+|6a7Ef#s*!QDP&zI7PHf#d zx+$)`d5hg%rn0Tn07I=RB8^QG1~CSPh?CSVeX41<6mw*V3y3Mh&{sitb4|6<&vpcXXz z$*>M*tBQ7B8@Vhr9 z2RA}EAPxZDJ!?qtfr&?=b0&&bq6GN8ui= zT#g@|?G6oAa$us-L%0NUpbg4Q+8Ar$oup(T;YwZA(8~nr)JBm;xRFzTIieWb$e^P@ zd`e*$PqwKK^Xmmk8RTm-&A0{(A)x-o$Vfu#(o-Z8kd;at<1F$6LRaN%G@z}GhQf|F z1dz>yPHR9yvP`*)%4ie+O{0Z35q34kllVvg z=Acc3>(G0-8gQTiFuw+WN(kk`nj~t%EyJloTHHa=~ zOC8T12HVPpvlj5pMD=?07aNN#FJRii;XTO8ezvJh0(?jz=!z5%c!UKL z*Zx)rQJIWq^)NvwK9l$_1-S=|we5sQPzFZWX`F^5m;SYy)gu5u7u=093+^sGe&39; zjR-3qux|^Y?;8km30zXAl`N_x9`Y9+7wg!bf%VEn)C5=026|h&IeV65SiB-nZcYEI zUD9r8q|!2NXW`K%tA-iK|2$!Ikq4Il#dl#D_yzr`m%=0ycpk-9Qh&UE^&bQ}G2XY4 z_5{-j0yr^~5vwSFeO6nq+cpe-Kfl6{Hqf||Z?U(hUe<#ZE4rZv*u%O9#a0rvj^)aB z+w|9u6sg4LG#COz6h+az=_5sSh(vUMCwP7NaQFO8UPiJ=^PGnimm!5+_*O9~M`LrxX%bZ;>N-$=lC|IuTN zTv3q6ib6Gioyc$`7xy)hC43A1&cyTH!TRl}W}?UwAjp$ako@;iw=6MRT08rU2sLy; zi)oKca;iGRXUhc9BGLyU<)lISW!jWw##zg=R0z&mol4ICD?5Bz4r*qt_fB<24{Xr; zaW*IO!`A|8y%gAQ4|fs>5y?pABHfmGl#3>nbrrRLr@JqAX;qg+<0V$4KMMDl@%+t6 zR?%yF_ZR$v`XI9j$~P@EcpB9(P=J9sJI#8hBUQ>kTQiXOu2=16uPbB^m{iyx<@8Az zuZ>cFRIi-K3z^nc4SstcdTYl`+uP|Xy>@vM#5X?46R>x|M+) z@ml{l62K_`K7e!J_raPzicK+zJjFX;^w&T-1V5=u4+kfReUa;g5ru53A@Ih~; zR(U*?P5j{x?+EZmXLr3mO_(%zvjKDAq%)4-1LXPJSbbR$k9J&8tv~XKm!T5jUTmjea|;a#_}KcPMfKa9OCJa-plwD41dK0>nVI}K z4Zx(B!38KuH?d^!A8p-|7mTzZIG;yoSABmbS*PI>F4#d!Z&|y4^r(EcP90Xp-tg>a z^YS9rJpkfBfan?4b=q;e%1eT9V0(9eVcpwh@NZ3&@$Y;ELJ5y_n$a707nBKuALA}U zir3idbzf@>j|cBCP{H9_t*UMHG~w5!w=5SKl>jmh7pTXb&lsK`Rg#H|CH{yOZg?nj z(kJWA#NJywj}QTLCzs$kUSDPs^y&AP7az?%R0`d4_CzA1wakOKU@v}JQRyvz&)zS1 zX&WBgvl}2(me6`+0F-Ij9UN*_o=@_*w@Vfz+GO(LT&RKweA-dTmXHxFxXI(x?I3RTIWTXu{|~ZC!+O zD7V1_I?7@>Ln*U_Wj4ev03%E|;Mr9i27{%YX)Z$bG?$`PYPe;7==e`yu;<2n%|w_a z9u2kXH1_)OBs?u)gbfok`@plw|Boz}nGR@KKAs37>8HOY+H8w7gXilV$jYZ9>wkXJ zd$*U7_5>7%0R{z!0R{$#0R{($0R{-S0R{<^*a0<@5vwSFjTp<4+cxs|SF6yu@k^-4Ti&YYbMNt!vdpHmm!Cv-5CvgpY`oZXSYzC!!!Va4L z|4a z1QCN5;lnZmh3`lND{bL1Vwpr3RL+}m?XxBI*+M6jC9IfT=>UIVlnJ9mKM?BWAdMtk`aqz6 zljiI}28LzOTPqEPXGY%GeC_Hc7T}va$cY(@`~d= zhk_x@pqjB0#$_6y6lG6d&)f*$t?V>^n*YUDwF*0rt@=~8 zt4{1WL5>;<1~n;U?F^kGSvN?7@NYIrE=5UMk*#pyZH4QTG&^mMv@x<7&2=Szb@Uc= z7T8l=2<1NL5vP042^BAEumnW-f5<8rm14^GHfH(38y^Jgf@ag`<-=73WVV01Fd)12$9NQA59tZ5FWgh(8^8u{1 zh?>=9&ucqN3?h1A?nHd*RHKG}?)zk>SD>Hb<*E zq@~kGa5nVJBMeCv?UWRL62L=>88*O1wl`{VQkP+oRlclV0`l{~%c?L=rvki{jTkK} z<(;`ov)m0vR|bIb;C~Wbih&d*BozFAOp?^P3uO!IjG*8cH!vlf4gdmwiR|@JAE2=G z2>{Ezt7lOfsDbHvsG)orRGP;Pt5wY{P*q`7WPi&7Sy-eKuU_Q7h34lk9*1;8&GuiXnkEO6w{O@hU7dZV9?)7(f-O@h+fus7O z{+Ek!T82>-drH2DIv)zsw^FtjRmd7i5ys^wL%zmIwD)rp7HsH$m;A`V5p6dcsAe;o zr45dOC?i&g=>?S2OX2CL2JT$0YUl1HaYw7TuBs_)zuClcZekD0Hm;<~fhWcf%Q~5t zuz4^0X}z}JZe!Q+fRTOG37{vrP5#3NQ6(a zxzHqc)M3a14OKdT4+p_~6;p!qZYTj70~(T&M9T6h2$pf+!!^q}qJYl3$vw8KDLeo} z;Q_R>hVHW+7ney3Hmcu2hw2-?l)CMZp-?Cf{9TuCo&`fvbsWsB8r z#9OkO>HtEgI)G4m5Oo=HA@&#LBuDfb20Vc|i11&9w3ZRS3Pr&8iXm^{*`=)q%0V;yVLY$i@5i%b?wch( z_HG(~el2>?3BT%qrvGy4cB66nrZHJ@a8f$F9w0aEz}VkVQqvL+s)00aOhweA;YW5J zJT)*+v>kM?ED9LS-%S8H$P>*5aTffJ6sqf#aFsHT-28s447aWFFB`_9*0+BhxFdgK+^Vrt;pJpTiQ zpT4Xv;yMbe9EPQ&4y&pnU6SI8=*P{g{{!;vy+W6f_5>4`aOVjW12Qo;m%*V5DSy3K zO>^Tm61~r_&}oaR8Z!h)f~0S@=gZD`;*yj}r8awjCD>w?A{COFjq~gGH5#Nyh1!|9 z?7|Fyd7S9ibIBAjJ@rhlZO9fH|~jC~o$yulkimx1>sZ>sY3{347J@5;xo zOuXNMIFLaQ;#WYVf&{1O;-bxWhG#VS?ohP4G}WPDNl~qJkvF={tCA$Cr^^iw?eu=1 zm(Se!Pu_01rFmL|p~7vu);m*ccjRqJm%<&=!5yd-&Mrt1QN;JSE!zT1WPcoZH&yvG z7qREM^d&6b?GG)qWqY6JN#x~C-i^|2Z*Ois({0^}L#>Gz7^n=|v!}i0MSJ}WrQ4>6 zpeZQ}#{G%1us48n+1q zzaO6G*tRuv#VH)HdXt;7>+$BR4E(Y%=p3$^fi@Nuq%mnTBc`SV-^UjKEA>al7Yp4e+@`G3;1X4f1wbi0^G zf%nt$jAa0Pe4psP?;Q4Fifd$Np$}DXgg#UP9bBUN(+$1p#McMbBY{wF+~_a!O!f=e z;ldP<*N4&xmp;qrJ|fGq&ZlwlpBwf{jJ8|D4MN_Oy&H#_r;F#RhSTnN0^xeb0P5m*;DaxQIbwugbbvwGC8ye-eBnX z=vwTpxOaT?Mvjj@1CPc7sb9C4Xb%Nc?wrx}7H|tPqUSPiN91wy`C)O!L{jMo=~pcz z!z`R~mK;>%EQHz)XQ`z3qc%Ku!gSNE4JTaL(_ zBttw-&g{vYq+fD<&KR2RP$;S9L($4h*w0QM_1Ek$w#A126ahq$p9~1#Nc4Aed1Uz~ z{R}a@KT6WSZ<)xVdE{y#+{hC)H-uX$O#%^_&Yk$j(P~)#0K`)qLA-LAX+Knb& zFJ)F0V#L{ycOFSYE}RMnQXI$Lds8BnffE_Gym9fBd!ry*H!QR+8+$px_-)@;OLM2Ui$>1gj1He@RsGRm2kICnr4Ea~y1yIj$paG=?OZhyh9V zIcyj2B7YI$26U}2L>;<@9jpyctu3+B2>zM+g{4n*wR6YuPtRzy#L=iaVKhbAZd>Pn zx;@SZ%Z+Ze!>ehkb?#!{-+@w@ABE|(3$Y>wPE=MqCI!g4bY{wbQXk*(H8e!xr;(V3 zBMLIWK@B+SUA5I^*>Ju}BOkgEd@kVW7A!h3r+={|I;OEC|7fa`lN-CO?F`ce>g5P=^70%2x8=GvcDSg@G4}OJGRhi?f;#;S}L+ zq<;k&suea+dS{FUqc3CWEp%y<(o(luOP@4))r~q69nmLsdtZ(FoF(mY7Nj$| zOHVL51`2{9P_a0k;DGYKv25hz5stE&gRg5F2g}AkNhT(8I^{=6e3~^xbP2^tL#Se# zG{7#;Dpy&r9{bijMB-l*;8>I$v~j8shkuCM(k`H<-n%+Cn;k0}3WL_9FdB=e{Z*%;?I_>jDG=HeF zQ2e~BM`;(0U;D0s?8D>7i`e^E85EB_BsBcNzu=dWxYN4mUrGWl-}Jh*u^dwn^sybq zeONAuqV8qHQ3y4f!wz+KwK=R?7EoSwHu&3wYm#OXUnzA`9-Xo9TN}7s2kNd6_@K(X4Ma|vGE2Oxl85rLW$kd7g`}sIF_@7CJ(HKh#Q+`S>xDp{f*0?8hnT#gA zUA_7*glh2^myz}a6NfJ73AZlj3W19RG&nXimk~n?6$CXmF)@=-3@3lBx?^-@ZMP;I zt71Dltk||~+uEt9V%xSWwr$(CU9p`?()GM=pFTa#*WaJ+^J9&%?#XM;Yu?FmZ8l!I1+*?CjkgfEJcc07^Aw4JsNM+W(aNV*)UC{}0Vy zPe-7IEr8l#o{gNSN80 zIT%?36rGK&fhGW1poy8SqZt*z+|B`D{qF<7#Lm_f_)lq$^nZV22{{6c0FL%%CcwXL zW^N{C_W!780rqANHb6(mzwZE`Bf!GJ$kyp^51i}(KwA@QXVZTG{FR&A{R@!2gWX>X zo4>lh!4&Nrog7UZfc8#+zgZPU#s7`d$B;pH+8oE51osd!@n9t`OnNy{RLrUYG-Th4lsW;Glyf4w{!ZN56#usn{NFd7+}YY%-pJ$lMm9ie_y0eq|7xva_HVSpcGjltAv;TT?R!YoM*!Uta&!QUDzjBjbP3sagU}e%Ss)0NcM+X11pP z75-nU{so>vN>*A_M2hDBuw4ITsQ7mXoK)TI|6==}rO4Tt{;$J7VT6V4+yI_*OzfNh zIu=%@zjyC1ATD-B@Bc%}e+6Rt&$FD7lLOEVp!0vXZbqhmRsTPq|2*mamoQ?sCU&O( zjE#zuk*(?9N&8=df7B+<4i0|_{@3OITlIgO|26YwW^QICaBItUCOkn_X_@IxwOBdB zlcGBPy-eW4!S*E$s)hM})pk9;X<@ru6^4Img6SKlxj)<7m(J`z4yCD&Mtd=>zxSk= zUFCn_dy`W2<)ds-ba2od1u*EBAf%sbM0s8>%I-jDvooq6?M*5v>lgolBAD)Aae%pg zrt%|o$@fDid$LFLF-fhD#ppzC1VODWI6J3EJb8ZlJ~%cqJk)aw*>{LXlN}37&SQk- zlYB;;!o*`#mwMFfl$uK}urAfcHR8#$Q zZzGqi9-tQ`Z1Yqss^naAGG8b06QX5saESnW%*>k}=eJk!CqB%q>y0SYyYEGxpSX-_W#dZrNO}bq~s$?NQ^AH1J$h zD8UDw_ynpk&6uiPV{WX`q9>AqKifInbk(yb>sGMta9Gp8^=0(*qwN&U2a8I&tuH>j zua!U?`iWOi{KcXvkHIa0E0)ycQHPKaytYi`w40;iw!n_4krw1qW({r z7N}XSrar8JEzE4tJs?HFNNQT{Wop_f;Uaw>hD1HJ)4Lq20&p2MIrsO5YJj`HGhb#G z{*Xe16JE*B+4=281qT>{tcZ)_AM~9(f~{WczJlZrjg^*u&S+i!Fg;n}s+WKC_?mOm zVwmwXg7eCPozWGh; zRxpSb4hhs}p58`UQU@D+n)iQA;o8}4g?#;Q5h1XT$Zx9CRpL|2~gKMJg?)D3AXkK ztE@AeI%eCK_;wRNig39busngN!1(RLrh?kpZe;~%NtOreuzcve)q{U8Cw_b#^ketv zW9}51ddJfl-cR%Dsi!i6f2CSFNl%v?*?lYH?}c9VyK#f;jyy$u3@tTY!&f}4YwD!@ z`Qa#|-0-56aERjkxw?PCP7?9Q2O%r6OxU!&E~-{;9Hv8Y5Qb1EuLS)XG`bUK9TVdz zWWs%)PsiOVot5iXmL7%D&s;vLMs&XgP2g?s6JB28Z2_zkrS-WauM)}^Nl1C$Oq;E& zfE}NGm*%INaeurp&D>O!o|$$OsWc;|$q$a=&iBtQJr))dGl+i=??1j{M4scu?pw^c zHR5(f&2WQbn{@>k(S{8k=ut;YU3)8&b7hV_RKCZ1RahzjsluQW1zHAsnG?wWG9;x3BtcsfAt1~ws^*$f1%jlNF z`I~!bYoHq}C+~l+9w3@{E5Gt?#7{KJuh`A?uH~0a3Sh`#843>}KW{aX>TI~736ci$ zD~i?o*Lm54vwNA<81P;YE&ZN6_VMOEBK&DQG>Nc(L;K>ynF(&!$RKq7(kjxb?`j{6 zDTlwY{)VUE?|ei`XD*sg0mE_Y;A{s~MH*y$KDKh=;Szt0X^6P+=PTH3xXARXv{p`> z%-U%9C|TS)W+7@=3Y@HEGOWCI3JsQ69foA}<=40lHdqT~>_-U-GQqTf4%V{RW#=~z zo>#AR4<#56bE`dfdZ_U%@0zA@TI{OgOxV(++md|p9*X_y+;ec;SD>>%&AF1Q4VKE)0JaMWg!3bUC4Gt6ooa?-B&^sqfHKicg7!#O&yFu6a&` zl*tpcPfrq8A5}^S4mj%10L1Fp#LMJr;a^^(lNACe0+Zv(VI%Jjru-GLHW6oYo2+3$ zIC+vorI=n zw2GyBF@?E=y8{CA2oj|Zx>LTIyPO27&@~U}2%)>O!`#!=TZ{*27&JN%dneVH=W;UL zNjO1^LeFU@ z!{}#(khDu{$LVqI)kGg-*F-gk1J^4_+rEGEO;km*c}hyuDmvGg4HoMq{WLyT)Q%Tw zM`*U2qr2fLemT2jQfmjAqToR>af`VklYXB;S+o+p{;O^KcWtTaWvdva)5l5LerA8z zfv(fnyKFhg1vq)OvfcC=*j(eN;Oul>4;$ys+b=Wh9cc0@$zeFnmOc%=w}rEyl@;{e z_BC?O^LppPtL-4PELxkOA;x)wmMlRT%@ok;5K&{I6WoFES&JCy`m1V#gy~1XACnTS zbf_T@+OSbQ)bl7LYyahCsd;mGIp2RS=7Qkdp?9|{#6MgpiS5BxiE?-01n|i+H+gqw zc5~D+ci<=k%Uz2ETZE%O-xO0>HDGAs=nLmBLdo|A^h719PRr;71*y!8)b(n%`c9~a z5Lf1G8C@|qa(^&Zfy_z@%7U9nY9n@UiZ=Pa)3C8=cjni_+7LXO4vC{&tJ;4JOqPoT zse6Tvf^YXIShkVVUlfgV$e0e(%RIMO`eORefv@ZgVt{(lYbxdbXb&QtK*3OE#KFA4 z5+;$NSEhVZS1#(W_rfM=iREIp;b$^C$^pKM>zLKzL(BvLU z$+qwkO&~fMT9Wf(*c23j%Lviod{%?;@NJglKGC?sGmL_INUu#qZjXgwuRlWWeF zl$?P4l~ScoYb&va083UnIx6SH{4u#d8AqsjF`oNyxI#A`?Yn=$SwGf? zj)^#!yKrDlK0vS9q|p{X3Ug}!Yo|=;JiVg?+K#&<0HEpZCq#_|WGK-!n|&ASH4 zCKjxs8|M~l9>#wl`ZAr=OQp&yh!};DsOQ;p>F!6lRa8(uZ5sJpIsyvgm>_q+Dfs(` zYz*W(jW}#W#4cwWAxITZb-S(j`=)!CdR^#(C@t!p-3Z?CJXjL zv_~iAR_*dB^i96irSwY?F5eedFvlK+&+3007wafDOzmyaP2DI9`a;H_Z>Xw3Y3pg8e1Y-#QXk?x+Ms5=@oEnkIe?S4>ytfIL%VFkI z5QtOJm6Egj%0~-(FS-I^`(17QNT*EK0@+o8+BLN_8NW7CafTcc)U{$hE&aIlv4Gbh zg-~AT&5|sfq#Z%kc8b&PPG+Q>EU`umi-xY@zNLS23lJ_lpW4AhuHUMe(HfZ6774uf z8?mplb`fqTDaorc8RygQSNNd)7(;A4r=2hL3d%jK7Jw)VLg2 zfp^K%>p-{h?hmwybEx}KMW{AfqNNX?7I#9zq)^2D5~R4TO+Qa8f>7fFpj!OXtql%aLaR| zY#+bs7~du1tE=N#vrIkiY%y0I)GmkE?d*K(pq$teKB# z%V&nBP$jS+U9vhA8xAJ|sp5WJlYDmK9F<)pHn2hNNJPb40cXloGh6Zf!zf+q96wWl z_u4hJ(&;5-th6w?2J<5ip&VwAaQGplUOnaoJshlI?TC})Uj@w|mvXE{hxrdfl&rGZ z4%^prHwhxQ8b!36A+g=-jp*BOdeVP9Zq9^VwQh=3!eYY*6ODy&V*q59K3ychu>EG6 zLkv^fPn@SH+dWYYT_IasTFBBMReHh57^09hk!^qS7Q5Z0ysod@$VZ{cs0~z=WC-s+ zgZVVKN$j*Cw8#T9{7fbIFn(^sRI+5%&V&P+)amL@k>}zjHpeOT?GcG7Z`DsY3uH3(eqh{XheTFY8mwVsi`X{p_`@8y9+vCBEyeKvRXU`ONp02qh=@5UGxlp z(D)oLC*TRIV6t%id71RAdHt!ZD-YEosp;(8{gd8p2nRh^Z`wg~XoJqhrgL|zsSH*R z?Zbz%1Sf86Z4LPj7Fb&d3^BI|LnVZ0wrgsLegfYRwY$Urd@+AoHF5dmq5^rd6T3yz zp1bhhx(6ZOMr`WV!770mG>^6OFD>cfk)FU($*Qqw!}H3I6Xpz__NhaIbS_dmF0?v_ z{ngX`*=+L|F^%mL7t0|Emx5-GT+2Sk3`Xp9&ji1;=2%?t4OcAla&3y*32FRUi{ZOC$~g zy)GV=Rog9n#rULkAC3u%`u92C2HmjW8m`E}O+U5A^q7Cl*!Ie?Gtt_)J_GeTc*?)M z260vdzUv93+D=gvHm#(Aq+eFC`(Z?y0K;O!UM_J4R}$WSr+dsKh0?{%m>%>9f%3XN zlz{aZY^$66s>-AfDEX?22pBYyD)5(*9V@#n)7oV)WJrHFDNu$*hNvEACC5+S47&d0 zlu0TrxkrDW>OFKF0x8+9N?|`n5@BtODRN7rGdNcf^z4sM2=TyKMO#xP-~N>!-eHKQ zYY)>i&g=%x+tL2`=ey}6-LU(!9qats%-9`@P`EQ}=7*U}<=xah)Ya*46U2(K*)}sEoVp@sFXuR1e{%T&B^^7wKIR$jHDN+<2${V-;y@`It9xad5&$| zqeK~D_G|FY&hqlPyWlCgaAQL6hK~?#cEW%jsLAj~PyRi$oB8`N+u>U0SGO;xTbyc; zw?*N(U^tq}G4K5ps&r>g1lq=JupHCFCK9aY#NXTQOSP&3$rm~sRNN^LU>0r53}lvB zDR+OFi^H$Cp~3>VZKN?rG^aoLFO7gvtK+g(AXPVYPHfF@PYm1p1xoTqpfp7)Nui+Z+Npnw2U--ym5E#)1jCPs zWBt9<>(pp>YwMKMehF5{bOz#wgyH&+N zzJ0zsM#yZ%vv~Vo_Wt|X2aKk^<=KCV>609`5%iQ*xcNF585NsJ&s=4Z8jeWmvmp`X z5^<(Fn&jIwmsL(2@*_mClp0hDYt~Rw7lu&3B;r~4S6BNLWd$ZnGpyPX@_nNpYC?-7 z+E-w8K8?uxJNZs#MY*m!rP&7&G8$rX(FGf(9auAEjX#qd7;~&maw)uLZdiXk3%@g} zN~$(n(h8o4MXkt>BOD*tZJD?7F!|tU<_Aftjmhtv5Z#%?Exs;PB-8yY+?XwmzuI9q zU%XPviKkUCMiauDHz=rdC!YpW;*kw%Hhpfv|CmxjlOTe+5cBmYqMl|)@;CLDQ!rA3 z;1WnalK?Tlx2$AegYf$#DDr=sY+~4sf*6;|wrh!DhYy00vO?AAH*ewihH*53x9VXI zOLuR%QB`-G{8DDhgOnDDoXeRcPl&OOg2qpBfyHJ7XnHio-^SD8A;J#B&;P;2ou;0x z#o_96x;uhDEyntCvV$(!qhzVLfRH*_$U4l3>hY(*IMI=jd-`Ph(C>dGjAuVz^j7SY zsg;_trviUd7{G)iBiyUCP|-}UO%EAY6S`2W>)Gbg0hws?(S4{EqsqR7Wd}Gs%d7Rx zlNLHncZ(k;2h#shb!=#aF9W!Q(&xv1xUYy^-e=A+vnO{)8X6{1&mgi0%ny_c zh#$bwADi?~n(nW&GgbIy{MHri#xQ%|rco=c1t&1Agh7*G+hTuXs~xk>lNwsnpa#@) z7KOEjcXUQ`T(4|Rd~sflm_sU0=LMj8aY(kYU+8CK39IIC7<off7+bW^kjNPumh&1kq1KS!3@`h+jk>R0(0=u&CW?@=)HLA;9@+uLTupylD z+e$pv&_D$J!`+_|Vm+f^sk9;I@ahG@m*jTFel)x=-fYFEM6jV~SH2*hdho zETO3dd3%$#sC=U|<)w7aKP@Uy)-bouK~7a&s5m!Pis8@A7#$Uetb#EF;1Cw!EG{<7 z{qO#km2-b@PQQJh?lu~daR{x&wZ%;p!eZ*1_FtxAi5rWL|5OyHKSou}`intquX%Bx z&Cfd%@~Ug8L|HuKZ?G;(ta9|Gv62`L2WKIs@0Lv1^_U^cB%;|-T_-S!=n>}0`9CBS z0hJu#8(amUp(xRk4F=!++LIyk7;L>y4EA&ooHmR^d zWXUO75Q2DLO2xHOZ{l!hxid7-9JukqHevl}1iZ0@<5QS3T+T2)`{$Uym zh`N8P^pgpyCNM5}9IwLr)@o@(>`A5Vzqt(r%|!8HWs%KDDPZiL(d7|KfgOMiHYWv~ zB&98p>joAW`O1MAPz)`$wweL-m5&QsvI3LMOi)+7AcxG+)!rW`mFAG26Y42p2!6d( znBVIF_VR&f|Oy;uc&LmNcFFsZ2bX#Ooe-IH~K z*&sFTLmU1ggM%KAjwbVtJU1m>IR>K&pJUC%!C)Dvzp+lwN+TSs8TlKU1a+y34X>X> zJn<1!iOR6xO|XG|TRbL@K@`7LI=irCkQ|{&b7@@?vm<&+Z#qQ8$h9;2HzuHqy-0td z1e)R;6CLa9*J_EgXF;C&WLl_Jf({RS-*f|4b1ROxL<@pF4rKT+EN+`Dntyz=VXOHnM@5uDXD*vvR%!P?XiGA9MDHTbg~f z#|yPO^Az-a5N(*OFBc7N!K4Iy3F#@PYCn%1JW8cjN`1@I%=rVDj2j%|rC5J8^vvZb zzG|Cb!e(4&PlqZE-tvA$aS$eMdX0qo3DPV&=GFhknCmHfZ3n zqp)Tiot08uyV&j3m~Ezvu-AW@F%m|q{R@09HiUw^06VZcMoO>hoEjT+`nGX?t}t4x zkb2!T8JSAA(!Q>=!c|ay##YOr{qgB=zZ=r7s8>D61zI3?Gns?jMcRC1x%wpaJ4sbD!6t+K#P=5gTb>6dl0(#xkjjc`^oX0^93g>@s4aeq~yH@S5 zr+Q{isiRUC9Ee&owY?EUHG#dUZE}c7cU?UA`W^F5_=lRKuChcUbHlk#s~FclzYYzR zRx9GZt~xIiac(aDJ9jP|8}Db7m7nVLem2il&1T-y@1&PvP2oNi>7G@aF*SvBpTSs7picaNxdMOn=$DM%XJ7#3IM#A( z5>JH)*)X%LVytoGW*LQMI)WMGq97E}u*LrDF9MbtL@tx-t;;Sy2Ji1+8*FqiPNFmb zr{L_yM6^!gomH{`;-)1p6h?zbZc+X+7ICe2Jiiv-S0^S55bAM!;g94HfI$_$Z~f{h zI-B~?OflL!XR3dVH;7@5w$PAyD}y8^BDv?4;R=x^#_JgNGxN02tEWHe3k1Yg-I){L zS>s!>xg8=V=t>N+-uY)9PO*W}uAJ-}t<4dnAW^m z{S-?2Y##k~(*vG~o>wYS>)j8YWWo2Vj7(%-zLmSmPca7pVh_Op zNA77nlem9+%pW9OIKrH*AX=D;P3)d|5AuAOI&X8+Kw~L=erm}zi;!%%P1NdhLEuiA3vqpRU*O1D^ zTZelY3F<6F3~AjKsCaE4SS(6 z%esG^LYxodf-U`-{4FR_J5+UKgEz`$Uwt_~t@*+$ua=v7J$X!*R)~T|R@2D0Witc; z`<2C!XIF_XzC|0Sdf_sUpFBdGkhzor?*YJSDx9UyacE9yK@8~z`;nd#tPQSDT4p;c zSZIh@t0Ep}t;u<7Zd8Zq`&N%1*J>6^0tSB<`(3zGxzspFf~2@53m(xmXxUu7<*DP8 z9(mj0FI>?BW<^$1MQbu4+I5dryC$-)Z|JmEn}QD>)Rl-`x9t}Bj*FB+w+R84s@gX0daqA zXx}yuaeRmHyhHIoW7}w3?lp3S8#hHB}BD&!7h5O54+l^(s z9CVQM?p?Ger~6?@iB0fCB=*KocP7dKpEB+7UTsQX{J~)86hMP0kh!^{R0YEQDR>I} zJ*w`F;-_hlWtx5T+K6$%$AC{N%L0D^-nZEej&cQCREi>ww7fS;0?xIBTi2{3myJQb z+=eAOmo>1Z0(1830Rs}bjG(G~e*J;ow*zODtNOUQ|5$YtksNAn6g-r0?MJf`8cfqJ(+LUltBlGOb2%xzJMa z$$7LPbyDE^WOG1H&_NPd_X})2m02R$QuT8{Y4os;m+j4dI1Ose-I|k$-4lycj!`{TRbT6S zR@pcSe@F9HJD!;QcKImUGw_N5_7U}bf-K*0asJH&!R|a@cf?XQbLv~YKDz7-pIy5_ z(TIs7=upXo_{D`xe4lj%nCRk}QXQ2vmOQms`uwd{``gah>bChaE&_k`)TxlLX|I)N zmXZz|);b8e3E>wMW`7l%?8fi%wHH_kfSGz@Pb(iPkM?gQ{tAX{IxNs=bXm^W1>i|lYS@j=m z|1bVQ?xxT?qVwdLSB8HUQ;s<@NrIQ7aTr9);2Ow_Wq(|O6BOM&bP~ zaMVcMjh)T9>k+%(RlIblEwwQIr6iu%+ODjaj>UHhHM)odMVEhP97^KDQY9+pg5*Rn zK=w*{>fU8ESKzl3a*1W4O$UnctyM=65(VDtDxNB;$Fj~ei;(!_uAHBfDfix*Fdmg_ zjV#P+R@^wEftWOR?n)iMJKQ(xCmy{}meinHCEOPcn+8s7_ilDtviWp(30DO=>O>2B z&CY2-WU$t^37UU`_MpopUcOA1PB`N~ML6dzP32FP=H+aq&|Q_y6Kc?+ww32ci<}nY zY8{bx8J-Cx~IM20Ee&R;g56m4nj&a9gDWwkYJXm4YsNT?q$v5z4?xL~r~;-x?+wG zm9}+p1x@odWxg)+;${Avc7qDJ(s?z*`Ih`J7Rx*v( zx{vT(B+`F|K7}rlfDzqY>)Jr{IqFLm%Xg3Otp^U|3pITFJ7Z!{)oi)%v6OJ9FH20R z5|II83xDL?9+ZAXys6CZC}_v^9Cn1KFUpGV^S8_lK}Stb?Zx9uKXC{4HaEZ>jHjM# zfGF*ta4TR$8ow7EK(UO|lHi2ssiTF2)!f$^K_Mh>gp;`nYB)gMhI*giHCSdaJ zyw^>UD^nwN^!q+Z2;p+f-AuSwMM^iszxHN?CuSHcUd}94eNzcOxrBchk0=qo^S51) z_uw))D=g-H>xZv3yigOSOch}z{Mnj5otTIHY-1L5gYX(g zC^xoPXMP~U!E5#TQ^dH(<1v#aNEo_tLvwBpWiq2mK8cDDbC$L&Kv!HA4T1}Cs+mR#n%HgnJO z`BO;vXfV>N>98=LQH-oytPo!(_J_46gnvYA9VfR&-}M%0(?~V%)(T>ggePMcfm7udP+u(9**@qlxR*LE|yjbPh1#hur>KRopL20cN zI|fdoyQ|VxO&9t?tSm7!HV{lb+aiBYpgNEw+JEkA-1!v;_9ih32Ap;f#oo#NsCuplE9&_D`}Omz-soFSto5M>BuN)Orzb_YUP{E zY5H+*l_BwtAgZUBVWe+WToLo|k=*w>reH6W6mo~rE<|0C`Ht9!?QLS?SV@1@2>7-% zX}bQ$S2n978ME*ibvw3qmc+je-E`(LxjtylX}*R2Y-vyDnk|1O$+c37#T(BE6jr@T z4e6Skr;$d-Lkq_0)EsTQox8Xclz;q471WP^pLa$% z_3gr%b+ill9x4tu)Z*_(N8>8P1^O+1iC2a|!Bgr)2@ws{UyYfkBOZ{+yH>!XhOzi(EV6>`OF94b|daa0*4ua_N6Le^4n>m5>N? z+V0C)nHB6#HLAoNHks=Pv>SFR(2eNuJG&3@SU7OQin(r{1FmLIBmjRvfWKpDy13zz z*=WW^xsC=iR#)|B7N1@`4+wml4i|zi4a(zBZWo7Nn_v|XToVt43ZdDfV560|<;zd( zm@m0I$?cH!MY!{GIbD@@(ZQa7%LYm)02bUCWzQuqmGx&GQ*~?+tM`6(i#dP}{N6CH zG4-)8iCIa!70O|iu1kCi^`dZ>LITQL^~I8x6;E4d;6d2=yreXbNLHLfd+PiW$Ln1n z2=Y*45!_go&X1^`Ct+8dmT*g?#jp4CrFlu`Ss2GpT80D%0<7oSa0cd+9W)`|Degh zh0KEV?hO4#PE5#U;`1?o3R!;(A{El{_MwTmYaP3yZK1b0)fgNM-@HRPCyg)bRj8?4?+Z5nT z>549zm60L*+ZM1O9=|HmP>)xqgNiXeq~%t8)&r*c{NMeP`WTR&tk{4{Y~CCL>uqF^B|suJqY&$n>v9bC&}WlM%OF47tr*k$Zyn|UbX3Mi7@x!W}#?;UzXMa-a1er&gswH0i6vb( zb>uAD=XHycU;aeLrW=~EoDaWyy&Ld1 z!JfwUe)=;yeN@*3S-fPm;QnmPz+Phx-fkngo(UgYiW^Dkx1=Wn=9=TP(Jt+0aQa(^ z=910T{T{|jnoBb%WEH!{@Ps_CvybSk&4El2lpg_Xhc~%O+ z;d;G)@LI6|KQXSgJ);(XbRbdl;Yf`l+V0zob_1`~2ER=5i+sPvEc_VqCL#a(Zi*8@ z^4Y`o6z<{26SXd`^(&eiMyuG3V}#v>iE@`Vq%RI?-TqR}+BMWg=Yj#UD&kk1yXeQw z4Fa)?!Np1oiFvR7-fK`0gfzS{$*V>RPATet92kS0r9mSy&Xiyb_-~?#7F&dp?7*|N zeSRQ5XdK9(5q}EWuL{(%XBKm_EZP`QhIMTiwE~)_3v73i7g-?}ZNS&oVG!!0!^`NBb0_5fgQx(bpVT9q_$;pNZMFw{$cRPx(9VF>~shlL=lRXrz6sT zy@rEE02D-TvUXNT12oFsp*yGq;M0)S{*S})T8MVnuMgb)e6Of%grQ3*aI~Hgt(?s{ zD2y&ayX7P^*_l@784iO;FBsxp3o#CTU;W=K_x;Nsw48U!klAh3rWm)B-rA&bkTzYA zT|5>?#FT8TulS$RNm6@-1RMUjm}gvn(>k`)I^nnbiwC(vhIxqKZzjTea)cBxh4EGm zA7pgR%Rc1hel*`=ecrifMVqYKZg_5p<-qTbCedk^i+KxH!$`|Nl*iV1%e2MK2}k(M ztOKNj9UX<`<9g24ck&{ly$_Gg^%;hrmQGQAb%1}KvsEZd3S@_xa^=T)gPRF|>l;-m z{iY!82I^0+tXGsiCCnD#vayRw8k|zhYpMYn;+Q;Q@nBbu$)<$`2oXa%=X;-^qlGt| zvqxVaxSWZNsDuj~db7xXzXcG3uYwG1s$^shNhr*tJQ+fuLq|O#Q5KDO5%<*o>U1v@ zmCN37*qOV-v6u1Gok;rG)#jOe_f*-seOmnv z=~r`T{59bN3jjv2!py`f1~5cO5rmWdli6wb&t#umdpj%_n9q8(h~{>GmJ8PO6Slt4 z%P>26xt`_hwDB7_w#?w!75MBm`+JALU=pTM=Q}n*=S$sVITxk{72M1y^@~o?`{_ie zOH5rk!Q&D;-l`AUDE>CgfHVTG~fV}$Y zmh;DgqIycSSn2jtBFLeCGB($<{!;BULdMkzy#y1N1Zv24jlq+17tY6@?i^ab0Mtoi z2lr&%c$e>re9y#!{_2Z^Z?1eWEcx%WrKF(D;ONwYI|zm&zbNx3fA$xk)w%d^-Yx#5 zn?}J&+@D9XJ4S-$y5nMeM(>^GQfFMTK3n(`vY{89VxL6NNT+*}g%M42vKPnOVB|#uk9;lPRe_*>uUYE++kn2LY_>xv z(hi-_JVKj~22(5=G1eGo47v-S1%aGu(QFTMG>J^wPY}I-Q7R)i#4yHBcM5F7-~De< z>+8G7@p=U5Zf%`r2qTUL_8j4RF{{R;9z~~nXzm4(2%CI3#_ep5ygDr+%By4qIF@3O zzPhtx^Q2@i$m~vZg_q%J7igP@W zqSEp$W%ed}q?%G1Tt64|uasG&YfA1aC7M!K?9T9iC8og%H}obOURbM$L`Ahwp#i#m3mL+*kKdTae*|(>Nd%_)6NQ0L7R-i!O_j*YA#{|}es2VrNC9WOcpI@5w67df zY2f)C86}w4Y~IRKX4K)#ezXY{y5yBI0Uyt$--(AWxuUz~OQW{`a_hQ3BiD4DSpiX5 zh|t2;%V^D7U!h1v85A4WoV&?HIfnJnU2ToaSc<|hl+O;BD4NRbIIeNXr8L>-$Pglb z=AOo5CLZAHeCZH*HMSP(;HJDHS!%icl$k>UP%*I%hE*w@ar;~u9Y36IMB;{=uS zIwh-ns%j>U@H_B<1%}*c+1h=8fL|6Nq+|kwVqNg}=dz_v4Q!~*W0Mb!85}n$k7nLx7H zgda)|O>7ivgKV?-4=!Q&%LG_d`}(i}huL8S+T28zlkzMLEbT=4m(hh~53!S@7B*!> zqp37TSkc8a=3qyAJOj+Wm2u;L_1nP0*nrluNhEQHfrizuzJ z4{8@mB_w}KMtsi@%v$|%VAFWApr?b6=&#VIfpiAlbe@juPAj??ga)&JKe?)y*#eFnwf{^_s>8%`EI#|6|1j*%)qR$W4)}%$(03T{vsXwnDkXiXwq2gHsZ8Gad`?<32lU2 z)B~GKqJU5#zM{*ZtTcqH=XBG)k)=h5smZ1HzAorHuY|5L5{D~(X5%Y6_-zmlRrJ#F z@>6{D`*wOIE?K?f8if)TuFCS~_^Q_Bquj0QPhJlYZABM<9Fh?ErwRy-!rgPD zgAy>Rd}{MUnjOQn-r=&^`t<4NQrS&q**en?%mDCxZIgkswD&A^1jssZ} z9I!T8B|D3v)sJ{~Og>RHUv9i1o~!ku@qxqC@O+-h8CAL(pNaa(cU!1ZL$eB{feQzG z7m8C4;E?D`a}T|L7lGFEj`x&!mXDf1i$theoV%jTZtr@(`~(}+1oc{`@+@4@0drQz*X8=w{3EtAlQ;y@UfzJ}j z*FM}>bZN#YK8mCpEV%{Q^5`qk-+zCY1#b&8Q4kP=v0ng zE1@L9l^tHbR;(R|h~57ICqfG6tl zM$VS@cA`ekKpubw&=epFGy$-%0GNNdxw#Q203!Ad9w19|3uge8nz9BpEiK)DYW{Hn z7<>GOff0E#ZgHkKv;SxXb3ofD86U}g^j*!)`nnAqEyTK?0T6T@FDAt!%;5x~g- zXkz&{4CrnGboj?a2XFv_Y%QIf{{90jodD(_BRl86GjO&CSlXG`xS0M^z+b(Y{l5xw z0NMZbu>EWM3#MrA}oh^)<|H6#usn{NFV?qXvjZ)E#-0sehs0Dq5+ksaXg zodL)K{y8)@Mxg&+jFGLSjmQ5f>c4tx0RLU?{{c+O+34?BgzU`!Qp3c+^lzo5lencj z&{WaV*~9{1W@PhsX8(WEtJ#?XK{l3lz`xx7YpeizW+tZpVpFxSG_kh(hXnS2n}Bwv z|Fwg^bp5M-Mn!RPc?oUW|ILB@m!sm}MQ~R2aQIu>|L8`}-t>P8|G)?f+q(li>6tmW z0Q4+e%zxkC--5VV*u4KYDgOn;{GYO%ku%8B9ia2KZzkq{b^m`qzWCcHsbX_@KHb=bKh zlcG8Ueaw&}!49R3szn8UHTJ!}X<<9um4@%N!3<5mcs|-a7Ec}i97xj~j`d;LeCtgC zUgi^clTr51l1~BTEBB!5eM0s8<$ZkVvb1zBO45dP|91;JfC zQTvg(7WiS1KRSHzF-dKR#q2_D0{dE5czQ;ec>MJEZRqFd$Z+osbpHW9ZB8sa1+Njd zPx2{AlCy^)=)Te91NzmK)2V7Pt5u^0Em6(w2mafV3o(EBL(C33bNU4$J%)VKTn!<<_dR=CF1X<$R&w1vLg1a z4>WZuLCK+oOzn_(Q%Q9uF4S}-E%ivgX->9!JOK(Z{x6Y&b$&l9l6D1)qxCzTy@}xX zdcdkx(*}R*v(FUiNBAru>7$u{yG7hPerFOC)UpbpIg5IPeN`@JixJrSjt7yl*@Pur zF=bUXH?j&1E0ES4(~VZ^CUdz@!TO3DiYB>f+eFM0C6!BY=XIB?-`cCw-IFH99)LVA zU^sm=&?Hl`3+K@|q9xgL0ahjh&mSY7=fjq)efEFn%Yt$3a8nbVPUNxfP9=U;hj2<} zZv@9)5-(vU;PHwLYmd@ZKrKII967{2!urd6%y8XT>7U>a28`xRHYd_Gn(z$(-cIdE z938WU=llpUTZmZWm0e%i_o)q7kv9l+Ux=hiw~f4Zhe%2ahkbZ2SJ%wNxV+qIOtSrM zqQ!qdK`wpGp2^_YTC>Hv4vpy!8`G{ZS?eir7DdL^V=7$1BRv|D&KnwT1CaNgPozO**#&dr)DLQlnt0lOpGLAt|&YqGW41{T({F)C` zTkXYTf&zVB^^54iC7T_qlYyPPB^KLml#s`5?7BIBzZES!|G83;5h~N??m~aQm>qvL zG(PxGdA*zy*%+6(gS)FNNzGy2l>rFFR&uqx>726?&dPfUNA z$u~58x8Ubj%ulYiqy_>vMgOqY$rPPVUHCU1%|G>Jt81HntzvqQ@$U&EDTl;S)X0SR z^f`jl#h_V(1twCw^ik4vKf#NKf|pE=w@*7 zRw7wv>ey-7Z4%RbR*g6T)3p2brXxj#9EkS>x!7UM#&1qFN^)5m=4znh{ufsCx7j)s zhzHM}j)Eim%a6RatiVMyEE$z1|E>fS!NqJ$+WH4`5m7&4+(AV)Y%Cj4Z?sdWu*s!e;$Nu!$ z=qb9Q2yvB^?`8VoqOh`x1pXoxDliK-tdPE^qM679O_jXA!l4S$UWDL-mQ@QCbCp&y z#OF$aDc_i-YUzTTEJk|BX?`tI~ubJQZO-hH>e!}iIPyFCS zSJc&B{2smHh%nXYZWVu@+o(QCnLI)2B3OLOUV~paa;NHhD-HuB(hU6w%UX%&+sfsI z0?*o6Chvb##--?1Siw}Vmor6qkw!#>@R1bA=tc`mqT9X?xhY`#^IUzVM(g8)TA|@H zzo-R{a4HE4|4MACaM(J|=Ao70;}AW?TgYQgZ;BGbEkyxL(dU2la_)+fygSV>lsq;{ z#jxrUH4iHs;|zF8o%$BD+bU@6M#+y2Np3xC^qOb5l{iO!!C&928kW#y>SrS#A5zfZ zI`gr>!$i_tEXK42SogPBkjIsnJbEP@drJ7BMQENjT+oabJa{D2QsqwbcpY8@kTLO~ z4#6IK^x=v_7+`-kLTL98M1H+>_=)8)j5P;Co0Jh9->n;khj4Qwh!I|G=MUbF`n~x9 zd6;kGwvpzQBq03crg<+%SDOaKoGe(Ajh)8Nc?{$6q1EVPoFWWcyGoNSHt5m zZ>f|S%^r`kDCiA2oq4P5^ZG)&6G<*T zAudN+_$GhoK>R#;mlNE#H~1b#!T;84T_GO3hdd%$8%V0ZQNR$$_Yz&Co>oM4QClV$ zJV?f!Y#gFp5fE~wH^NtK!QGt7We2S}ht?&wWcS6e%qArmx2+L+vBRf}vD&K{OiW8v zgvl%l&(m!q)wrX!2^V=1uf`mXJU|}onrzs4w-0}NpF?p^p?RU&0k3UU0A&@&yqknN z&HTme-me1~t2q`o=))sk^b}ljF`hY%gdTfChR!5hY2Wr<$3oYyBSeZf zyEIZgeh|-sixi#wSk9d3_7(UFjSgm1qKSVe$ArW0_~EzcAPmPvwtv2EYogrJtt!Nm zY28toRBHRRI`K38MTDP!q@&Sh+TUWjMOFqg&B^y2Jd}TK z6UHQP>LfB@)E-dYBQ4zO1M8Uuc3K!O0YCVThvn{Ll0oOYT8Nwz`%0)Chx~JTaS->M zO#`V_vtz$dc$K3N9&>#W3!b#%R>-*zBhaoML|)?GzdU~QfeiDlTl+d7WH^UXaC|$5 zb=`~u*E?AomIWg`~N-a{M!t8P4q)wG475Z=>LG2NzsOciCm5cYZz z-TRr)lR@6IAab%UKzQ21b0U9!B~n9ZA*M+=!6P}OzI;+9RUSa+rpT|83z2&SZV^aS z%+NP5B!Ttq&43=V`x#_CxhsDifknI8Nr?_p>4?%VW@2%fG5yQEEEC>9YDl!VJobbV;fIlUQ+scI)N`v!-g3zaF-@o+f<)j3Q*N zemtMYLBjPQ2+rG_RrOu>gYqcZK2`rDLd*P4I2hJ<2P%^Ink?c}X*Pc;j7T?zkTCEH zP8dHV)Y0%D*Lf<=fMW-P-Efycj917vMMt1N*)`}rj5v^u@&7o6D4z)|3E!8EDo6&IxZ4oBPhYcn z7JXwN?97jsbr=Fg5OA(f!4=&OzF z+RbN#Y!$jM-4lTITtI&^=Hij!{tk@t&q;PYxFWHD7%E5K0)u~HaM+FxbP+NuaD!v@ z8EMO7hAN`WA4GRNeTE%d;+nMsVqU={0`Uj7#~kuY_XQWBdQeV#$(y@Eb6orgal+Jl zNGZw~YT`;0-sF+Z#*w5=i(%vmvKV`UnwK=9XddjZ*bt=R@etT7(EsR_|4stgHieK>~Y9$AVtqLgRJMtRN;Ax%~&;P&n83{8d^;ZS#vv&t?dnUF>? z2JVVGQna3Z&+(@-{!<%><9Lejr2ir7Pb&Y3Y2Sc57-0txzpb$%i>WkY}0H79V9yiX6fTb3DI)DTS> zHsTY+grSC}!Jorq6~c*$qi>^_^QvKK#WuH*1`6!&^!>r-2zn~9zkWfdKZ?eUZP^sd z5(Y$XqMzThF8qwcN2ryJDz(r++iJ?rpnDaD&zsS#2#QN#HU-jle}C3InTfBAqqc?KovEa=hQoXC&1%@TQSsi06Nr8mxmtm5jZp*t5;hQzO_AX=%$_ z@|YAtOP#{=GB`>MC)1cfFdTsiV9*UBQcC4xpPagF*uQMtThj5Gi?5b9$}Z)~zER(e^J>UTzT|jg15dkMrrt9!hM)xI zJ;m zg3o5V0V)AW!)d@qWiZTVzs!08+u}J&CXs)V<&nfsZn?omf5q20E(>#>qEVUrF#rB| ziWCrXmF`C{vY^xIw@0AuY&vW2)}+kQnTC786D8||k16=2Dk5Ep$nEOSuiA*mU)OA{ zX~w4&6=2;E4`x65^S*I>}R6 z`WRo)>ddT0ya_46wGMx86ZJ@^YFdAD^ZyYwJ81Kwq!>5xD8R{6i;1RMYB{0lAWH{f z0ug0Ogttddrn`>4lJUSD%STu%N+B5jyJ=lQLYsJiY6p{;Tn0j47ek03j7`!`l3%t- z&|KL)wmgwz)vvVV_f742cj)a1W*7>O^#CS$$`|kjkJV~M>^wH{4}lWK{7AeIX81yPCrP{gu`glvO_Iu9^+Drx0Xl=V zk*6T_qvy(__lF-``_Ydr$nJl9>T%k7Zb@;nNbUMGW$YM=#yh0-TCX69S|QCiv>$XC z>E@F0^=z)lSD1b>)olwkLedzhVRoO<%0YF)$sy}zsP9Bxj1L01Fkh@iw(C}UqgUns zC_!HWY7jS9HL-2XZ0V*t@(b(Art+GU1+$_a@pItxGU82JPy1}EpWT12VjuRcyG=1F zLUxz=NYGp=p%@lFL6C@|m4&pai1DC+{H0tb=(>E=7kJ@Q`>cl5GmRo9u%XCzn%id3 z;4{~c27~I6cel^C4EBY56 zm;E{@8xJ`EX|_)dxG#Shn99(=y$J*|3}UeI^pZFePE#L?%T`{MaH=O?Pb#0!JL%8O zUa4FfGR;S-A5rPzf3SX^q;0tJYIl@`1qBU=pfI-I*3|^1N#D^H%htz#Q}7J7G%%?6 zzIcWygM$A`gP3u`r-das&uc@r=bM4E)214EbFZY?;f0Mqi*A22BX+X+?ckQL_pl+u z%u=1I%tLAlSq^gw#uDptb7W%Vx_A@>zA(j35me(a+jdY*uk2m~nqx}$@`9YTX+A}s zk-P4i9xZUoJ5R>i1!pV&Ol7~CVuM-rx)oLB8Or9eaX-J2yd+g{Fz6SlPO>s^o zitWoI1|y>GL!5to`ha80Vf$~4C221ZCl&j-bb2RuY0bnCAp{!ErurN@D2Mz0|8=`BahwvK}P z8#=2|xT0XY%G|knsLd$jw&kg7!Wwun+`y+p%C5Kj-Xnh=RI?y*7L^e~*+Qhpmvx!N zX*g3$vbx2hZ#6W}`yR38kQ^qx%}A%1n$ia{>fgdI)`B};w>aFCjKh^P!fRJfQ+1pu9Ap&;^~tZki0pEUY>y*3F{K0PiUHW9Cwt`?M z)wr(~MT2F0COZ;V;}nqAiN*f)!H9G;qUctS?yJw@;}Y5PN}<95bhS;=yfnR?qnP`|wlZSbl53zUeZSY67K%}2DsF7tw8)(FAt44p(5kkLwkF0;nv;a9s`P1P@@x1tvLIMf4XoVe!v>Ce# z>A%*0nFBAsNpOiwx8@C1d@qMnaVnZmMb&AFuaeq{SlxyIxlpJUU8?c5Tf0X;AUvb0BAs(h}Dp*PvbCsb48F|pj^MqVy`FY#sk%$L$rXNAEf0ZUH!eHG1$xs zm!U!2GFgzQc9@NLR+XWzoay%q6+)yLTy5$CT49=&`xLF~+>C&ZyRZ-|p^i)-O@;U3ty7bttXwguV&6;^+P&nY^5S= z?-XniUy=IZj7A%@C#-eiYIB?RLVZfh<#u!DyJ8K*E<(PHho6t}VFGGk6ElJ;_BTlP zzRI+FXKt1b65f%9EXyXX)ft<{kY9k*iLJUEG-`jR0aQa0U&4VZt`m|0+P zIH(Kaqy(Jf-kAAkIPz@#@wsv|o716uI(Myd;cO_U;$Uz6dDsbidECx=@dhC;Mlz~4 zFCzt%Ev*7ShgO7B5c!4ZL6=CmU4HTPIx=43rQK+}6TnMumv2te`8Eb^C(~by+QRxM~Q*7%oT@Nau=* zKu4Nxq#h4B&Je1oQz&FIfXFVBd!5{@_QJpWJ9oSo%N8+1$_-+PB<9C%C^qw@P8UxZ z@n{*R?@Pqc=YU=0?)7bBCbu8mt>fI1Xe)0hGt(PUz_^z`EQAq@nT~%q7JP~h`k7N5 zV#Ts?SQVg(psvyBM`gKDq`t0gijomLnc>S}+9T$tko{#|0gT)SW+u@z&h%K5vuSP2 zu$KKTEEco5+dP?ntyu9M=GPxYP`BtRr0C&rgUTQ*xAHW&OP7Qw+q!jl(Q;#qm+uy% ztq^7x1vn#fhE_5z`m%ow>rzP6pI@=G_v%wy_Y0Xgud6bjCz0BP1P`OczvX{hFhp*W zoTt4#k<#$_IlVaK*fBcr-HtuZR@-?d+g3ii0&Yy_qQPWWDA?&Tl5&ci=h$)eROJ1R;eeEbLEqE`SaRLg`1UCUQ^=o zqWFt^ufm%bPJm8v(Vlf+kasUqrE9}5vq{OpBN()>q2YBVpN6T;5lR=7pY)6NyP{_v zDWwg}zEYuX2%&#?HZD#<72*7fi~XI;+U)SmT)0wOHilVdp-10?6vIlaL5k!z-S1Zt z@U$i2pg)KBQ@cylO0*Yhr^tn0S(lmRaZC)@eN`!}&b8t(Xo+5Z-l>2>2*wkZp=nf}ww4KV92yUY7|U_cB&lmvIL> zFASG_*YLRVqK1nwca*0g@+t#icw=mQ1gHyRQtIP8ceW;J5}N|5UwX?sfZt0AGFRxK zz1-pNQQd1skchpBM5CO=eWM*Gm=W9Ocpkvza@be|@&g%vZHE+ql`f=rY88cX1_HP$ z@KOr%Te*LL@A+?KGWQ>Nq0t}lFXhajX!nc<{N18r_jMF? z%r=+jGN@hGTw*sfN6g8K^qnuo{=S#8n=2gp7ePh7F1{!Rx2ES)PWn+{Gj&et2j+R@ z;?)Zf{KksT2_Yl~9ab8-9!h$Z`=j#q?!ww6=$n642_UP{#}x~4(Zp@RH`CFhCs&o0 zrdWm&9P1qn&XKCIaG2V}-;8^s<;=<7>n`pHxL1BW#8p$(Pi8cr^SuQAaK(i8I(zV= z_MGoYwUsjI#j7j)mckL^t=2Kc5`rG=naKVfCEc3%sPrfD(Xtixco7ROOrQ`R%XFkVL{qMh%z`Qo~A^GmKcgN*)yJ$N=_7VM9$2MjrZm@}*;cnIEn0-$PH zzehIgLO<^)-3twv>lUUc<{P!&GN=|X;yQmF_JM>@ax<9!EA4S|Q@}b=gj#}Nd1SOI z?~Wn;SlVR3B;wCZ3Bo-&nm;-xOH`64IIH+XfwLA}GVfyf#LtwUHLg02j$VdCPsJ=Z zNyFq~exmbZNKMGV-uO)4O6M(*JJh;UN}@bS!N}U2b|ztC*orjtIs2i$ivb;4w`PBd z_*n_Y3HG(Fy8fX2R(X3UCVL^7hg@F!h&SySz)N!k<0|#GPiQmJA}}cNa9njE2H#h7 z?NyIp(mAa)r@R_oAoY79XW^-6#m_6#pbW2tL`A>~m+Saz2ltMP9hPr%tvXdn8es$F z3WWh43jPeJjsK690bo7%o)w*iuBCrr?F(j7N$LYBm{iIWH9f~d3#Yq1J)?wwf>Iqg z)I;uxd0eH~V}h3#f1;(YqUvp16wFU5_c{>rO#c_wc`YJoCaFX=R^#n%M7_Auq*;!2 zF~qTLL$Kvy#~miE&=8Fdufk!Cz9z-!&G$M$m5Mr6YGQ7yIWgY^2JzM*h68`n-4Sdh z+z+|tSQ1V@gJRl{skgY7J50MRchFWl`|xUy=_HRY?bi-zL(9zF9c=Pr3=rdwZpY-( z$)Q9I^Cjo%xQ5!5CtupzR4Ks~S{dcaA zAl>mi?!^R#8JraukF(#crT5QJO&P(hi#qp=Mor%Hck!V)5`=41cDIfp1m298)^1rA zRyO^~nJ!q2NrVIoP07KEhiOkg2Wc&%^_>O7G7UwTFi3YN(!jZFbufQ4-z*i8ySxd= zGgpr08KOm|l6{66@mY6OU@SV)j^tY&H~Iz0QASVRx^eaif>2C~@}@ z2k)NfyL3|(M?_iUE?IfcE#S{uCPA{U(iIpP-|A8iqvHYn7S7@l_ZYUtiOr2M0npG< znChew*JB059w>{nKHz2Tmr!ft!R$r|?W2fuw06%Bc=aU{oBhOhU+c|?0Af-Amx#=W zs)t2^NN@&iMO%LwhIm9WF`74|u5b*J%%SvyAr>&uJ)x#GCu(vwT@VQ2hgY@KJY5qg znRjjW{>2TXs{pO-|D%n$yCb@fdvtUT%O7FD%yu@}e& zDFl!ibbH{)vX78;>>Aqxhh|+doZkEEfV*5Ay*0U=B{)3dw~)i2Xz!?Lxu$LF-C2=1 zu;A}f8_JX%i>+^VPp0rcu-8DkJU8zxd^=r8T%v!H2ocxvuiJVGasI&iU>i;CBKI`) zFDodq-rHR%ia1HRtG!0~3Gu{L&G>5zTEGc@*#)KM{3VPG6O2Z+`z6oBGgE9$T5r!7 z(espXs<8UwW@S;dEeAI1d@7EZVL}u%tKD3R4oRQj-5^VAbywQNSgKU!-DWcr-D+)u3KOmI}apynlT^u z-YxaIqU6No9YJZIt91E#$0AuSsu#8j%=FKH`S{sZxkmwc_|ZN4;j(>fqk4YlN2E(3 zv!aB39y6@7CgF1S@Le9>QhG_!aO2}G0xW-lcf+jgYduJm`D~5Bz1Egh0)QrPO-px2 zIAlWTmrS}h1l3jj(nA@*GaKr448X$);O5AR-fDKSABf^Lc4G7 zPeQm^9}ni7huoloN0x9Zr8ply)+d#f%}q(BH%(I>Hd%1&k2J0QF7`Qg9#g)1su_O> zjf~P95haA5$C-jw1cvaZ+V#wJj}*g1q`F)d@&e*4TgjLfyr7Mv)p(M|_?zCSm}Ev3 z2`6I(Z1h+~9k{sKmm|o085KfhDpr5f-V12=utX^0pxco(5&06dv&nVC3(Pg9W3%AQ z>syXky+0|u&!5GnjPcp=*=pg#wBRw~XTLdGNQ7LL27{4P$nUOpznxg2x7<(D%Fd+L zb>nZwEs z>l%n01QuIyiDtCwj1~}+8UzlRS>{6tF1Jgyrjo}q#IKs845gU1nEkA=r7783fZZsf zqwW|$kg)Q@&ADi1!GHUty$#98Nac<}0z6z}k7u`bGl1i)z+RjJ4xEZ1w|!M7A5il4=w;jO%qU(n+V;C%|yjOxyLS&FT65 zVh9oP+H5=Fy}VXw8f893B34P9`mjJ(VM}QO7bX^mPt_~j#zlIIVD4lB+ei)}5uR$S zHH+uFM#rPxxC{hyBTs(;Hs-*(tjNSZ9E$k_S}~;YP3*JPOG9zvUfEG~IMYwJA2U^N zHIh=lJ^h1w{MHM3OC1&F^tRtr&AunrBj-x2CxqrRy47HQQP`{r6rZwvlCZ#H;_y7) zjhx_4CmXLOE`y{p`cC|8tL@M5Cd5+x%H8zr)FxJWYlh?mCSQL|MIO>f{<>u(#HqU& z!kO~(8?7KuOGt+ue-4+)<-WnID-*}40b!px@e!7&`0BPuOS_yFn-2Sm!>K>|d0q$x zQ;&w-E7M3!*i@DJCBzYd%INU?a-B*XO51x&IjHks2Hp>L)*g+ez zNpIHcEhZD2x(a`T^i4hq>IRGkq69)Vs(8E`rKk9Mxxkz4WQ~+=%oVm_c4JqqA2asj zj+P9YV8ZddYZuX_%VXfSDBYhbB;E`IXvab;zRxkq0V$M>c`4iUiQW0Ld z@mnjCBiQ=aCHEG(~ z%ObgEV zlZU>3rqJzDwC*bJcC7RlkgabF^b>`MY9Wv}F2;Qh&^$9clCoBib)+lQ4YXCKtE8oJ z4oG&J_jG^#-ldYAH*VGk^;%-{E|d&;dYgKn*&ak2T_L8-%PjFFK}9x%yIk%Kvh&$Q z$_Kr-y)w~R{IXC^oNlTkyF*+fsf>zPzIl2S)0gd*yVz zs?I~kXjx@_C{hF64&?bgWVlDD5kd|TRwxI8> z=>dPD?04wK)iotF6~qzZ1f5A&sutTHD4zAG@gWXOja9C9>C@AkunLq%qGcNN#(ek; z@#^>7nJm^j6sfF-^+Ql|Os`WvI30(NX5ly%J9^zACYUmAlTf z8nRe^<71^Xg8~n013H_S(}S%12rig(?5ck!Hqom%rihr?uRSQ6whr>WU+=|i969)_ z75F^K_fjIR=p1j!tG>y`fhh>(zx+IAX&wb;6sBiK<2%v<6BjII*YH1NBuZ zh0hKeWCdvE9d8ixUgt=MK7%%+LzaCh&qF5l1tiI#9hEU9n#iQT4cvq%&P1Q}e6bi=|C7zlqeA2MXCBz|QdoRLEa=5jh_&%Ika= z=k05p(V5O-j46>G9De#mKNDMU;MS#Bpm}mNbh0LFpW_=%g$D8fj_SY$k&xRXkx10@ zImm*UZ^bq9#hYw}Qn0JlzBo+%+P8mutrl@fuK75=4U?Y%c5N+da2I5+E#f-p_YD?N zJPW#?__|gy=T_+kLWaTiPp4T{R+(hN+9#9gwVG?xY^ZD1sS)0iqha67qWsDfe{q7dAU-jrtHL1gZ?4YDU81_0yG7>EwbwjQsVro3FlL*4nS z9rb=msj5Ovpkh73Mskd{%pEGsej0JVVRRvl5j(=RVg;TRgQ`**Qs9A|vo&5c=ckN0 z$;}L^@K}lGX1A7SML`M0bgzGCrrUXM;I!Q$lq4cDtRDU_g(Kg(;g!D{@GAO2yZIfa zwh$DR!w;7@bi&Gg*ae_l*nsps7@BMUS}~k-57BtNw7ErZ^2M;LatDh^@+D@*h6Vpq zLQkWkC_#Y@Q@@P!*UcJ1XccC3hw6u55U6Htr)DfPr{q{H1DqN;4bFce;V^2`Bhv3t zUbx|GUp#&V$|c8IgP3A4bsBFBPuI9T?2Ef#4{}FkYscX$KR6UxJ!B;UZQxJ5K%Vu^ ztBS!m1*?%j38Zm6-B}XFZ-LDXb6%}#c*@yi#v>ZzWx+^y;uxyn)@=M}Hh*xYkydh} z5(_M~0@S(+A_~}SIM{#i2x}cumfT@yR7`CHrzXz=Y?FsRMtMS!r?mP$L&UCoh$sY) zoV6xW9MilOKPs2!z#@OSmj@5Y)i2*tU9wT+1GVnrE2G8jDo;-KT+6H4W^SY7P?xlbtIYAhW>Eo`Al~r z#Mwcw2oBMM~1Zj>M@zos!u~Pk|7s&+SA@IN53Y94w_Llmz!GE;KybEWekaPJWf%0HlgTa=)heI^H%;w3Zb z!z`8Ev!uDW@^vIhEP2$CAr|*LVALJYu$Oa$ei?rePe>zn4hJZd@+I{|^PZnMMoQiG zhW@G|f|^kp9RJ1|zXNyI#XW6Re>2rFJkeAuKcra#q2&TjH4~lfSl}X|V6mSoeJN2q zm$s_dq;B9HU%CB%4x2mfwF~KtVxDeh%j1solf9sIxm?9ThgS%nD*8|>PKty>D7}~E zLcn%R4o%U3it|PKJP)UCDng%Bk9t8R`V?(}6y3AAH2EEYm&T~W7JjOOJTim5I81b7 z{YelUEHoFM`ZsV$RNoU62}J2hujB}qRpYb_;N6XBMmJS|UVR1ABh{bruKeT=32kBmn@2A2+~U;P*W?`?5)B40 z2{)SG`q6FHLJKvQo&yYw=T90R-uKhoW)c=;t8%Q_SMAKdIU;nlE^T7#<0-cEPc&U( z*IKm|(HtR#f}+DNl4bgB58jq|3}Y4Dj;PZb3rLcG*aG3T75bLyisw3oFb$MviB5H3 zSsjwCE(jY>nRosuj9ch2s23zLUSzp%`(x4*YLi;gd6S%NxX+Cab%;tR>;@y*YmJ_D zGWp(dIE_x4+9m?$cb%Z1vxsB$-H2rjGXu4a*=5&vo%Fi2e4=boo?^#X$2uRlIj{1{ zA)pC=VvhE~Q!=-7#dDHx(}6pYC&D`WG-L;}aSXxV?+W`oG??+X$i}5fxOe(7#qlT2 zwK9?=S4dd<3<53|zM@8e@!LCIZy0`|L{Kn>i#JlnT3uOt2E@V=v65 znCVF_@tlpIpW5cm2_xh#n?e$9i9+m`W}a<-0AvE57_k(8()nqlGjHV1ddDH}D`pF~ z^UPW}$voBE{zIP|Tj5^uPc7@iu3q|mJA)GlgE8Noo3-O4=VFGU3pXFW!TL~9zim*fCjKU6!wl3Q}DhwjTapW zGgG<>BSq=~I#_bCvxRDbu8xhngXB4XFz|*JXx!qZdeDwcvwsa^aIkP!5c9;U-1ynr>-4nt z3(=Kww*@VQowcgx`FRLC(*5XW8U1-$V=9Q57ON(fEJy;=N)DK27k>4zctqQ&pFt$1 z>uIg9D=bducJQUeW5O4tfk6v@TcsWN3al`#8Trphar;;uXpzQ%ft;DG8~Ijj#OkKyiVv@IfShOv!je4iO}8 zO_OCWM*6Jed@b^r<>qk3j<5==TJ4`}UOTd$iDmv}DxCZMGq>*L9`4Lg#b#BtccARI z!w;`DoRWUOq`86*$JzjdDfB_s`(>5KNfgM013k6Aw_~=JN`;M}ul)(G3%xs0jKOO= zQ%tQ(Nt5(Z5*ygU!BQ!I(v2N|8Y4nBm9Yws)T@WDAUQJBO}d)=npaLT0t6meCP`FDYox7h6rZbq5M118i~R32gP8c>(A)rwyZ1qKuz-nisVTp#k&l9wltn$QlvWnA=yw6$qMfXagp?#=P<#Ln*ysY~vWHeU#^jT04V&4=7L(eu3Tv6JkT+s-&G@VJL^8$5C1r(QZthC1OUoBf+f-pf z(iJ9G^1Hh~IO5t0r*;tki23{yjbgCff#uh!7I*ntmc}=ThhOx_qZG=Wf~HUp7r5*c z8dv_KtT3K_@d|){tA2yN_g|s(MTGWzPjBA+ruZz#lVCT(%W%IHDG`#aBQ?5%2y_Ag;;Sz`5sIxHe}a~MdwHZDkEKXdPUc{Wrvr& zLr;`Tfrc=Dx29l~7>v$k!J2EA{O}bCVJEta#D})&@~T9C5`*P871+Ka2rq!xvHgQf zHqAz?1QmL{#XKcY1)YBJ(Xo0IX@!Q8WVrho7rBX~nTL_{2{sCDU&RmjQ$A*~OY51a z6e~}!G8|}CFY7<{plTMz!K`6zU0tgjW0-`1=ZX4hQ4Bq`01FN+vnw{LjFQMPrETOG zw|$*hcQvwq>p|9!AU?S5==junKuKq)r7ui{a%@@pH0seA#T;OFaek-!$JlQmLA`;% zoS6wO*Ku*t%}FHH7tI($A+nG$5T5nR3Nv+A>#4Ak6*M|?w4&QvdUHkB)go-_S~9SI zX3tEZ_{YdaeS40pjMM}k1d8jE{uS2aNGrKy$~L+Br>ifMJL~ z0VZ(mmr{sCNP#sv8Wb-Rh(ll7V9cA;@>FBKRBb0+M72Yi|+G{L-)tKRaUh2ePOYtvaq8)2+BX=Mp1m9#+ zyh-u#3Qa4nneOl9W)32bZK7gAZ_O+D+5kd|^;C~c>nh52%z`Lj1;8P&wp5m^bl<}( zm!P}*Bl-M)=sIw!gkSOYtL%*RZzwI?c~c@InZ9hEa&fEqaZs4H-zFpgjZv*j!Fefv zfa?|bB6);9oO`zEktmkL2U~7$ENtx6=J{clN+UTK7#)J`nvzSN6$+8WEIO z5!Q=Hd`rmCwn>4ZPbt6l-Stbk?e^m~6Rlt*-n_m@CYq9+QZRVP%T<}s%NlpKYk&G6 zI1STCGgx*DkXO|t#3J#`>h~-sk!BXrsP8{KW(GiA56_+0i!L?44w!3~$(;y)F=FTX zeA<5qI)2H+6^)sgwc3BnvF=E9;(}ws(r)&>E;!!0mVx`iTsZu4Gk}{ceMnfqw8b8OB)(7$xKt9>+%T(n3&tCUV$q4*-BwYnzqB5;+C|3lewT^-Qc_6 zNW^xLqC+hi>NP^|Xahy#jJA5Ofhu354eP+8q&(&8a`YU@ko*SAB>{ev7TV?h)M(ga z*sSUTih560+GYTB_*DU>#Z6r()Sup>6xirM28=Jahs}qXSqmk>qMR#?pXa@(WQY1R z`{0gQ2P89gp6-#=tJtxQ0w=gJ2WZ?DcZTfVF*!vWE}gtvj_AF-@`>=Gw)F**Me%=GtSi2Q zjG4YA&^HT2JUKoW&62}s0uesB`lT}s`*Mn=pxY^$TN%$0-13Ki_xV`WjnM}5d!Tjl z_!J3jJ!nK$LEnyw20RicdI~1lm|gD(^wB{jEpqbDj_%7`o)*U=s}I55%-|)?Bhvh- zNhvqa*$k%a1gTib*H>nf=B2%xhmU$<`kKg4pIKUh`s0v6`aMY@y5BL{6TFAM_4IQ9 z*AGfc84faY-PEstKhfX2a1B!z)9)RHS99dLB|giB>1VN%g6ZM1@7f1&te|eYTu{MP zp@scIJC%lNY*p`%>Fa89IX^G2rV%jkXlPZpO*qO?-#1{YF@En(RqYi*h*`g})3nYs z2;Ffj>^Hn!k>#(W8*$ujD5wl@4U(Ey^7hEOePJgEVlR<@%@DH{RbFoP*J8s3PD9}l zv_2^Ts4&P=s67V{WY5JLp_hDa!m*gxp>x3x1iv?tjGKv?^BFN>@SK}E zzM~or^CfP71w+z>$kfE0GJj2O=12xgQ>!oY@lvkO;eb7MLgpd_V51TG3!6p%3?^ME z)z>}#;uGys7&rGweiKW>$C^71sN{99=`kdk-;dvtjV^H9QMTbdBtL?oPt^?q=c(q5 z^@lP$Wn-=Nct22d^q$vclrj(X_A&hUk3y-7z}|j;3{^I#swO0*AE>Q3f8DZ?7`wPq zw-=-~(#1w_Vtfq@3c6IR$}cRf05jx8-_(m7@I@WPtdlfHRdUHS^cD<~BEJgp9m1z!=zp*S$O7ur6oWUIc%GQYKA-OOH} z72Ck|(|5co%T(a++l~~W!U|rr^vQBrF(z4k7FRJ+QZ_N%-*MvLFi>aIg$zViJL__P zS~?fy{|&VrX?1MRPn;0>St-dG^GlI;-wBB zsRc$RSULfQWuFcRZCj&ZKnZsrwnuATtOdJCi~lWQZX6^*YFAwR5>$C8+M&_yr>7)t zwR%BIO)Cr)^s*CaZ!VXYn9w#ui{&3e5-e$|Fr#Dd3j6WE?f_?{j&qq_$xkrzh4N~v zZh}5XlodFy8a}iplsMV1|8o&{POrYQhH%(3xVCu|)BNJiNeda^W+B$(DNTcjTWy{VK>#N{tpzY!1i?xmL@j}J_M{hrbXJ%`@Yh8Dwr2^aHFsqN;N zUr6HIk;=sQGN>+|xL2vGjE3{mZxVc8i!%;4BSGuGZb=!qdK3x0IvXsFGF#c!*>7(j z0EZij;?r$1e*rPJgNs#ALH>7384dTgPwqBND-I-^O77w-1>Xu4#8$!IZ-BlbR3X%` zsjKA@o6xVW{pbP#OG4Lw7+(M0x@9j3;t4a+0xiQ@WCvPWXb>cSrMe;t>#(kf+hOHc zEQv%J2m$vd63MS*VTf^O#wKC##pWEVCIKUv_e3K}nzgiW zlJ7fZzf0)D_5cTewx}`q6bthPw%hJrv(+Qf+L80WeL41i;<2UJMNlDZlAsQ2_sznVNYpY+jhIJCUY0964m^0fuET zj`9534F^%qxT@GO+Mxp7`bG6e7X6d1rj%Fz;%Hrm zA^dlV_7@j+?YqgltFUu%5X#B?IZN0eC)-{f1WAlZ$10&QGvmKhRsJ&&*V56-gP)@{ zmyxMBM|T2$hJ_(+?TL%ecaC>)*R*{9eWME5Hy5q(E;?(a;qGn=JC^3;P`pm#iL;Pi z^?)Uun10mUFI!<5>*>8V4o?P>ZS5j|ymPP`+6uOAY^_1IDgyq3GXbC<{{D-wS)`Is z!+zdxyZG|HY}1FG@ODHowwOMo1XgyHyzjt>uUXT7%_R0V^3Y{R1_Xe10F^c8&lxmR z!7TO=2$_r=^$4)3s1c^p)`n}}hs)wNo4o~%>~Z0#@D3|TBYvb z10NI5a*(Y>3Xa}{XgB787m_nHqYU%L&hIKXgzg65iY^sOa4x^) z-6@gAV$=$|gr4hLd<>pwcS`}rs3i9lvO}tWl*=w)Log z?~Q5xThJ%R%LpRQ{`%1S_c-TDe1Hl6ST3EcOT4H+yNOt~doe|#=oMdY8nESE>I6uL z{;a>U;#jMDHOwfF%wK6}Soe#}2K9{hQ{y8zwqvThA_c6aJ z;`;El6l;z%MS(Vqd$_IW{b`L{mCF6c4G^^6OEM9I`#)c&B(I!iu7b;kwjScg#k!hS z%lYA3ckhf<^PLV*T(PKt}BT5`b(!+ULyFLqa*qt?A(Vn@Cob@=8 zHK4f3F3TQ*O>6Rm)0gvbs`77M9w&UIXx=^QvqixbEKy#Lk}Wxb(jC|KM6~I-5q(sb zGjI$3Ww5UlLdq4@F8-gx+r>UjA)>}mrr(F#C(B40$lQyGwB}63u?&~#E z?2kNCr!i{dyJK-1<_7(C_Za*%nehm^7%G1jKRKv7!4=*;N3ffJ-^9RSV=#pXV9NJu zAlY@$`JxMDg@`SQiBCTbvVs6O2}YTu??-SV;hA}la{(*g;&$H9F+RVoSj^2wd`Gpe z>SS)O;(OkE2xlmTQO~%}9y^5l-54gFv9GldZM&^Is!=7~2;7VZ;Vvj6oD~WIVqw!h z?z+w%TxR{-U9p{iuf>DZ`7*s7yT^ceFVrmCo=)fo$*$EO2vv~U zLt1~-ddU6YZJoyukTu3@8v5^fCSVnZml#P1mGC43sWuaWqhr#ue@txXRePyHC}S93TEy4!XS!kuPkE2b5kw2S2mi9YF7Uv~_@qMsG@2?LDoMPnc{X^p?cX}$Li&SR_+SJv)B378q?4@mpfc20Gv9u=4T4r;??L zXuK$x=?l-Bm@Ru(f#=Of1`>RYsd=2s;xW+}ZTjR~q^5sCF~&7H;u{#5wkhi$l;4K$ zdk(mNO$n+<9%XZ73AON%Ve zGe#S^QRBHR(PF`<3Pbyt8fec5<9Gfv&e%5J8{Tou2WS$rMC@FA3@Lw|@;))un(#;j}d`v+#U?`9gWcd>(i zsk2-P_q|vX5>4R(NLZ+X4Ukb`M?!%6+|!ekZ?SmLYYHuo>Uf1iPY{?ol-Hh0;Nn4T zpCyy*9S%xP=b*$H2xVtFk?4Y4P+{)zQ|3jFw7vkF7xg@>Z!&*vFjWEc>>N z_f0vDm->+RmirQbROHv~=-S9I|DIl9p9I|2IQ~k11lwpwybjg&2S{1m167;gMqD^~ z4OC%#<-+SMe@|ohzOUR4)Q~~=ww?momyz}a6PG$R3?u_HG%%N8HVhU7G%_?ZlTi#O zf30{`R9x+rE$;3FE8N}P-QBe)ELd=N4Z+>r-3jgx2n2Ts?!jFz|9|f3bH};eFWvpH z_t@W(xn!~+c%Ll}N+ff|^0=QU#02bD^Ab_~C zimt4ZG=N50NfRIqvIjYR6rtj3W@`-uC|CnQ_Rb($fQ5q-!1f;p0MNnS-1@K5f1H^< zutc2!rT}M05YYO=4dej?IsT<$062o2?5v%gKfVFh&Hzg%Q+t<>9=JFFtnGoeuI7Iw z@FBNw_&Xs-Cx;IUyARz5n2Lk5i!;#4+R+8@5miM(>K}Q!Sed%~72DbRLk)1S_^>p0 z0J{EF(%-rdm=CRsskOZ`zy;*tfAUu>GZ4Vs+S$?8)bk_u2biOi_1|f@I$PUY{wo6p zfD_2l)XCfy=g54pLk<3Dw7Ag8|@MDy3o(0(LgYVKff>j^Lie_0?fD>=A) zgapw1_gH57-y`{df#Uxag8x_O{hyKh?;QOzm|=ysT1I@g<}o;|6EP&tZhC2E9ZZ=)&~6}>;H@S@9KYq5Vg1bV2F{G zlZo>mVryq9YY&jQinR;Se+pn>YWvZ=zvY_t<{&3qYkSZK$$$6v!-<9E-*g&Q*1*s9 zf3d;&4;9GX{NHQ%;O*}UnB}AuRdhA!|BG$=x3S8{RJdq(I)VWIHK74Y%?=ku?V z;lII1+5;WT|C%Fp7gKxlkJ0-N!Cz{itCQ0Q<9~01kIMgf{`(SuKpr3Jv4mWrBr-XigFDvA5sAFlPMo~dPjYE%rTEr%ArO8WeC{xoU-`jW3`D4e|T{*hF z(Ow)|>YfzPSw5jJe>rVm0s1;s2RHp*5VKJ!a{7t(H}CT~h2KzmTr669TR&CRj7nZ$ zh$cJOo#4*zX#>dJ3Iebw?i^A4fT<0!*qvxiU>J3U$0t;Yhxd2XgFi-whk7od`*sQF zb7J8s`Au>Cl8;G~Ts%#jZW@7a&`)mMu88i)-k9mHuH=FCe`IM6;`LrLk8A-n9i`X7 zlLlg`&W+1fO)OsL!#7sqg5-d3!qArtZl6G@I`SA`*wqEvZa@DmDhpxq2ECkSMwgpT zz-{AF3bKzBGYxyjsjSD9X`Z&J4u@4Mztjqi+A2{dqWYbft7^-k|0k@3{Om=SpTqf6 zJ<%k!4f1`Bf5rBa)bWSU2`~jee&e_w%9Qvhj%ZB4v7_6DP-1w+=RO^g-JLp#snw`k zFbf^muNJVBRN5?myYhNzu;P~Sn^eQ<#>~f@@iiKhtpfKMxn#a?Wo@Y`kTARMIS}9I z!Yj{N;hGAq=7Km&%n_gyc}`Zn**k*Lj)}ggDcOQYf13vw#CuEDP2DI|qzje2FyS7H zw+We5Hsazo{#p#4(FlW6s30__Q%uE=vx-zj_A?o6N0j+K2SGM#1OBOK6f3IOA4k6x z51ZpRg0A-j(PQj_#H$b=d;vinUJuaE3`JJyBt$@4f9(sn8P--dvLGbl*PNQN2(q)( zrS|tOe`YmCzW!@j>J(zUOe7ouE~5@nu!ti){TZ-*`uXNVsjizoYVfZbrBRc1BNBss zHN9}YH;#);QiK7Xmxsj|o{H|syq_TEXkNxDlm{n;&VOMvt1rFi>O>__f+`F8JR7nn zCyOZ+7lnDEzRUR)UD~4LQAZ!=lhE(kRX5d%fA@HhG-H2Kq=@e+nB#?G`gWgZ&>6zZ zSI$fXUrTI#X$=7VZb%$i?9imJ?yi={@~kFs-BYVoz+vQu@Lfp*8j)Ny4YX&iiXQbR z9Dz&NiR8n>j3Eh|=XzQ-z0VA*gAg0oP&A+L6Jr#(U9ZCO^w7|M-RzEBt9Q0Xl?F8g zf3a)hahP2obe>IQ9z}gs!F)_xY9Y9|ZMT{mU9+$hJiK;?2&6>LZhhBwA9{Q_f?I3t zetV)kS07@p;H|6x)qkJKK- z33}m3mx=>x5Qx#whWPwtvscf!KGOx(e}yKu^)tXF_4Ga=w8R4Am+AA*7e>t?@nS+B#f0eO;gg-6|>QAmD+?A^E&e_^_*NwI3`D0oqfA&1g z#f??_V-s|#INtzmAbw5kA`{Kmwp_U`7>6e$Viz;~w7jny4b3FWK1u!pwQ{&)s8PpO z&Q!{7#VNwbshfilzUQ@{j8t$&j1EvKUElbS&t>+0fW;gur^CffjPNs29es9y)|yKv zUto0}1T9jM@x?K*dEm~rqtJhkf9^yR_0q8U%7?gc46frAEpy!!d7MvR6iIy#J8V%y zwx><``J%M5vP!m7X+~5?N5;~v4%wY8`Q?vaCHHj#mN??;7G$uvR*6$oTKj0t)m*TX zYDW)@0S&*8H~&<$Yv;+_!)*GY4)O6*k8#{NQ;TueZyqLvGEBcX6(JxNf5Mlm_oftxyKYNJ)8#g-tXq0+6>2hHeN}65ziUxBqCZjh5;z)Bw}H1&e}SR2 zB053HOU6qq3+5}Te*9uC>R}9q*_1Hbb88&t5rDJj_chz;bu+)JK{$JJ@3A{KLm65< zG0C}HMo4XiqA6jhTZj`fef@Jq`cVL7It6)3RyYIJhW3&y2cW*m_*;iFb|W9*s8ZYn=R{v zM~Yl;YYfOus5T8cT9U>tg~w%+@Ydo}ADH=Pt*m}dMQXPs^>wvP1?XM6juR4}w{A3XaxcgD{$o;S|(T6N_Zy zN~7zXGOcpV_HPK5Qdp>Ja$*SMsj&rCNUK{DQ5Df0FDkadkY4MLn?foqHz;+s}! zUne8PcscT#glV;*e}p5*%|{ex1f`N?3~|lLpzv#f3EM9vtMS7vSx;4Dx?=CR|Adw1%PZbjmAI3EU2!=40mMq9ExY6kOcqHO)H9e~Uoh&Ou-sre$JEt1OR=WFzgE z3k&iZ3kz(RVpJP+JXW4JJI1I$fobcYrisZCz&aiqvi|v3Gey zIa-C`iVq`7hh)my*GJgHk#%7V&ia1h-Yj@DVa9{ne}Y)ZW}S>V>0UwQ8L%`bjiAwn z2R~sHf1XJYIC8s%Sb_~y!=uu?ey9|XQOolyEL{cp1(cRMCrz44z;*8#*byBA@humC zT81<5@*D;NY(EuR9E6MSPo_#YRuVr6^EDLHt=}C|rkV77#j3Q|tZP%9c`eYEh|=^! zeU1e#MHdFPep4rIEHm|IKVcPeTrE&0QOetde^~miu!1F`-8BFBDr&Q4$kWfaxkEGe zI@Es%V$dZugr<$T&YRkXRmt{l#V6}bf}x7fmeB<2^6u8YmL&6^MF%zHu{( zKHm(swYlGYKkBx@mHZZ|pI^-$Y-EY4Ty@#NQu8OdS$?L>EBIbb%-Z_r^KFg%EI6o2 zf7eg&=`4!*48aX#6D$@>M3=kRqobbAfmV8vlfwhNPt z{1x-Hk!P&_d5RYVVm0+Fxg)*_Q>U7DNt#j?#C=cG-60qU-K4rzQ28?o!!HI!j#Lxy zhMmhl#P}?m1oP5PL#ELt#tc1vj0)&8TmC8_ydTo=W826qiL;21@}vcXvu#nozzKKdXRy7)Rk zoLuDfm*ONHqXD!QA@EN_I19G40;a2`6cXC6&cQdlc?hokU(GW$&qdm;*&{gDJ`siXqpWsvC^e{(L|8RKdU z7n`fkQ^pB$AfQ6j+T+jMxbp6we)!{07ed)KX1PmL6eE<;5O9<87KJD!A|Q@&OrED~ zM@cBib@@`RuEt?u5N#ej6w6HA3RCEwC(|veGM+p%<{Rr`uL^@BO79IcHy=ktkDr}n zf-2hU>eUe^>1N}>c6lM2e_Z{|Rz?U`c#wwp8FSJh+1C#JVN8u&a=4!$O)!IM;FCgC zrn2QUEW>PPLzF?_uYAsfo%?nORQs4fi0UDjxCBaA?5KsGH~feJ@rDDBY;^by2j8Ug zZ>V*;W=4N9^&LdLP$1UyBg|DSamR|gz4S^-VdiVn?MQCeDYwbfe+;+cQC`N?xP0Fm zgRdskgV5J@bZ@2AU6QIJlXiMQ6MPmu2AK_I8PGiF&f_$jb=yYob3~xh!mrss2P5ApmKk1W;=q7564Zp#%=EOQ{fDJZ8ey37^+(*oD$@%@*Tzm;QSY095U zr-f$Wx*m_%;h(dke=1zSJ?>Uo7d8J0_22+nrqph#=D;-145Ij3`W{DqBPDBNIEADa zyNY+ZY+>}AtQ_^T!^&$J5fY`EV(&=JcHf~OvpqVNpGl5SkKMXVBm*#!88@Jb>c^R$ z98)brmc@c29S&nZ`(|Hgl$(i?wlz2x+QNl+9QNKzfiuY8e@m=b(o-%KqP7I*s<;>5f4;0a4yOirJCR$a*PeufzNDz~(nkB-Q=zfEdt4zm-<%VRm+iDU*9LE@ z)NQtWx=~Zw8y~{w*GLCRel>bE<>wzqmTl%JLQkkD;l9ByvrawwBRK6ento^EjI?SS zUNUn$BlUt*<)H#D+;~~%I_D}ER2;I3*8Fl;hg&J^e-nTZxNkP+RW(=be$lg*-cU_c zSZD-EA43E%Z%1T011t1q^GJQl0LY3(V2~@rIYXn0AqSpc)CNJ_l;7GsB&JpCA0IJu z%4O53Crwwaw()*(e&hJGx9t22cw~bk6SdvU5}~IOO>c@++GWeyW(foIqjU}0>l z?ZUe>lOSrvRf%EXuNFe&H~7Gpjd-&2Ngj zjksP4xC1Lx)e}@6i%nP%k(wR%g=)B@^SAE;`MlIYp|ZDBTznHAJ$nyP$x9oy8G~Ci z#x*;TX+t4pWER)rAxJCV&n6&>XZxi8P5IMaWeL=3)W#nY#uic)e1nR&$N4DL=G_;y zf0;e!dB+n+J@ZUMBtA!DaT(kp6kc*!vcd*V>mw}>_g6NNwsiZ@OQfP1E1?>zs!Y>9 z57ct95)A^lB}Q#X_Kel7>*=6FF-zp>g)+?Syy&3{<`L@McnTaonruR&?&VT}soLzoJyRS$d?hR?Q=Cao zMY+j1EeqvZi^RI8a)!IupMj@ZJ3erH=0(phS~)?VitJA~Dy22s?E=SIZNe$%L1c!m zFoI|MTh}k&Q#qtM)~btf2`8N$e}>BiScd9f58TUFUex}C?{50w(*fn(E@7^_anU=; zPEO>RzGdGrvwmfCswLHu*6N%~{^Igvz3yj0`eh(4?{L{usNbq5Nc&PL>-ftyb~Obt zOA%4}iH+1@z(}Qa_Ay!@1%DCuWI{r@CFivvf1S$4$XON(mx+T=0da0je}vJ>w%M=P zzChPrzU#Xy1><}(`Hjri0Ls!_I>FK6hP2D%#ac{c5mfUd@ET8Ny}IAZ1n%F%2mrMq zPSU99{qUginiuou*{mM^XKiJQ3&%zlb8!1mjqly6Qjm%D;!ChQ`rp zr24t3s9jl*fBQ=bX))oAe+gC8&+U&UElhKFk3ZAzmTlU4#1H~)aCw}#Uy`G;5P&m7 zKF|HJ??1H6AN0&a+j{UztisP~bNLsSQ8)d);gt^X^`%s-EJ-&hzIHd>h1Lf-I#ee; z*?6N&$B7YzxGuG10XL+FNLvO)b2h<&!2)~FV{mW`>p>~6-_lHF3p2M6B3NVtW@ zsbcf8Cdp0;N{dCiKG?q=p6@Vf+2MQ(DTPt3$~9)7gjmwAXeg}z1lzO@Lo|J(^a#Z) z|D5_~m%+IjD^lA9f6Vu8@wINUt?ZFpK+Y)3(b?#r;!9LVJT6>!x{>f|2G$rGWsC7c zcCDHt21UXiqFf!G(5Z`os~RtZ!q(bX8k(nmO`R%@2gQ<`YHTlpEopcuH}rL+c)t>- zCA*oVy`{Hy)W)RSpY)AWzs+bQ94YVA4ndh)U&(B;DonE*1!3$`{(Liv+)!b$3Cr^Kp+@d27RX09qnm(ZT|QMjT?~k~k}j z7naWrsAPa)@rIr&%mKzo+A;F=2^zh%iD7F;MaTys zO~Bpfg$cKW5Mkyir0xgYwXJs1)3@0s*wWLTM8{eL% z#xVgz8Pm}2h8f?O#b;JE;3~QnLuxk?ON|!?Zl3t6lZQc;u$uYn(i8@rAuh?!12bIf??A|Tt z7p(`NJ%mjDB>Q+5x=+r}vKb#dc2MGj*Y`RDYcIY*>L{nPqxpdKR zGE2Pm80`h#sLb_>R4U39zvZ`|;*H5+`yO7WfAK>SLQZKUKm>ouOD`jn{5|tH7OtM1 zwsIdr9&WcqJP7YH+K#;{0&K?XDmI<{-@;6V7SR?*nWVuxgQ65p99r8H#bmV{$p?hKO`b8Y(8uE|=!m-p$(1EMp~rXO zf4L@fo3t<`72dWIe;67Sqb{&kx~q|t+LvSTDA*a3ReWff_{1HN&h`rQy(rf=K5)OWTYV73=8sPrl@BTS0rF}rg;^_$pPez51_ z`c@q!&;`S`REmJ7fXShE*kQ@W@5lZSe`HdEva+lzVG48kB468b%1Ao~NWsdDD|qm0wy8t_WDR#EkYle!+@GSnfb#!qg1t?`G#t zc^sUgOwEPpn4S_0R_C9~JCUiYU$Ga)VsDZ4$BtQ5ODol#1)0ogz6mz&vux;xf8{-* zYBNfz@0dKFq_d}q?W;*AqJNn!vioc@>T+Ht2F5mP6+#h9X#N{>==x!YWTmyHredq0Y$I{+XtYp(OkkXB_Vl;vGv z@^1M|td3L~>TK<2JTecOvanUHq!_Srn-7iuFwi-m6ZLNW*&r8$xvOOAfAg2VqHiii zp179tfWsq&EHpho%)aoUL+{;kmdBVdDgqmDM69#NeHKcV$_Pucvk8V1KNZovYsKOB7wv=;(Z4X7LfgQDPH9<8M| z9s7$LR_?}BT}+1Q2Z}{ry`Vp3L5VB8iJ+$cLHJgN|46BdQa8O! z#>^%w>XsUWyboYhf9-8@EmUx=MM}c$&5tu4w}LHxe^~xbXyD3y!U(6mNi`EW=Uq33 zw7T6n{U-Z0SpsiQJ&~b-2aRNJUw%Kx#9;UIyOXNt5le0F)aQBC@JhGIn~gqHP&3}9 zo8l&vF?FD=i;qp2c^2CgYI-x2(w8QFo4p5GljZ}oZA{bYe+-3zVA=U~Rff^LDxxTg z1&FU0b_+3wchEj--zHoO$mQD%7+(dgzb@aj>mc>fYl^P$(>=*J zu?V!54u^hT$s|V%F*I3xX9*70kIH!Tcm0`lIKFHM&{~-GBuJ4Qaoa*}wG@ZwPDiRq zZKusdc!(ywe*wSQ%0x&~=#yW7U}6WaHu9!97EkJ%l=S|(vf95)xY;6g1ZC4xZ_b>j z;NYMblCeNn7R?&qj63-vkU;&cy`Sh%S35}Dq~t?+GLxwyz)Omu@ibu2w>i8+vv~DT zM6iZ)pn#PE)&xbnfGh#SY=NXw8(5?I)i;^1NOXU|f8kiJZr5ra9~v3K=!i{p7-*2v z+jUY0dGIZ8kR7!ge<8-l#1_eyOHKjtqqmPAkGd|%e72^A4Pz$9K!WLA!htw*{C-?rl(ZXOKLEXzrT zgFuX=`R3nhCUb;8hn74g*a8ePTf2oGgWPLy5}Xn|rG1gr`=9Iug{uU9xx+#RbEi09 zOu6viM<$-=>S)9aGcb3rwyIkG?(loGuLX?QOo=I)xX%w_*SsA?lxh{HmDh8+-2vAz zD9(_aLVq>)(Tl7T@YqFGhv76~3qYb$n&Q=k`4&_?@jl+269o>#uJ?;Mha(1;&>=JO zdDnq5b#`_yNbh)#4_>}(5+{Mbrx3~kMla$_>&1}(ib}p!IF*N3bXwfDBg(owQf~;pWal2Q z7k|^z(Io;`;bKi0cz@7nGrQ@SWbxNTerQbN2d7a(DUtrGI>((sCbUAj^(~Z{SG+pX z)dq*#Dl!J5%G@7U`ZkCwQ7O#M*xQqh*Hqh2lvj#gc)sQwG|+X73Ko#f3-cw!(0G0` zIBroh!)Q5zYHIfF+Ht#jk@+OWMqFv`aoS zaCjdK$7j*&a5MwjJN`^wI#?ka14qJREu4mkEE#P=hBz{~J!x|j5 z#eQBIqOy}Nx{LF98V_`LFS>(wXgwd;6* zEPo>#(#mA4r*lM77b(__6g^mt_J5w+N_*Aw*#cH#{517vM~zi8__wk8~;mrn~-@N)f@`hF?330%dUO1ejf^nKZJ7!G7B^_1DQ1#Aj9| zf(cyRa1x@BlQ(9G3cHBjFUMYzF)e1O<8{U14AhIQiY;`Ly3vApC=-uw-G5>V(I$R( z?d^70K}RF}YA&N(dBw<49ZV<>Vh0inS31#`Gzv65%)ZnRtDKB*E)w(rm(ZN1M9faI zX!R;^H8otqFZ>uf%yzWZs{sX+t$lBXrtz$TSYxnu1?!&lsf~2M6A`kkw>`kGO0oSb zLVSz2nZYm}NU6E77h~|^Lw}#EFspQ)-0Hptg6wAWJUG|wkeJ<=b~vF4cw2Nj5T_Ym z*yu{HKxZ5G|H=RG%fA|Rw19;a*sqmbtevB)DpiENsJ0zs9du6qUtpCz_A<;DGhJJP zC}*hF0e%+dQ~Vg*!f6;w-leD^ndO$4@38)9g0*t zmKPahTUv{0SMaPtb_a9Zb&8&=;H2S7N+aU5%IejEJ3LftNYAe8R8#9(Fa%v!Neqdv ztyG#){iG-<@h)_6O&MM9q~nD1p~4KYQWWxwO6lpWJcn-$F#1Ve2wse0Bwg+j4I$umJA^)MnlMs)qg>Rzn8 zDS_)NPetP*xPRX(l*Q^)Tk(gtj|q=RiHtR7mP*w6$~T1kt1t)Nh<>lG0r^sW>ndXc z3`}QT?SB?5wINdGexhAnDUE)%Ew2$dY&5!-a>}^GgLP%+Ft5>1=2KCA-QgmbBWu<@ ziS2!$sN#N9P|T!ukJ~hMDyj0e*D+v(k|IX-L*shNmVan29Nr;IAaX_QH2Q;8ra{}| zwpCiNVZS}GqVAF1_>Efe4|zM71ZQf4hC-BYjaXS8txI6WPxLOPmxFk1U^;U3q%=wDq^Esy@ylo0Di1>66(RGOq zNn07n^kfP=t5tP$=fu6*%rZXDQTS7}7T1ZPN9m{-+9Gyg%)m^ z-sVkL=Glu!spJs+6xb;%=pBaLW+G)oe!l6GgMX{p7TV7FHj9#@WB?KSo*It$T!jte zn;SKCuEYP6qp>P(1cBmN*U4)z`fw^(xyX~{_`qHK>=k-D>72})aT}YGg@RZ+%?>%i zWEX~v7I`|L^4q7h&RGuX346}4CwZ+DHW{$up-*RC?y)GUcI>pYH%JuYYFiQcJ&B~j zjek2AY|y`YHEo|NEg@hSVv+~ZB2zy-iCFKM zd7lm4thVjDdMk`%qnUv4sfJOzWCK~o?SHa2Fs36emsH3q5z3}x-mMRZFn&tn2o9@d z@E3-`>w<%lhV^AOFX+)k>Xx|l7i%PayoM^1O4LD*IZLcf&jjez0Erlu(8ww;hc{|bJ2&>5r z9#Jc26?pDaoVL$plb}6b%Fh$jD_q>q5MP5SO+4FDlz3lSwZTo4XR$cY^nWB##mlwy z1@#-z@@V1%72QL4F%A=*Yu!-!Cd*SAPC|PjOdYWKe9zbleb$*~S!xlo1(jeQ>UXDF z{Ojd9SuNp#>u!Bvs8&~I3mHJk8G13&!-N?2vnK)g#rQi&Vlp|FUvvV;Fyb4-9DYVT zIBQ9{XBr%9BE5Rzi^c^OT7OzxeCA^P7#yIkp0D0h)@!uTJO`b9F+{o%V7$CdSSQ^n zeh3;S)3*xWnh-a}R(qHX0*lx!zHpaXnvNIPn`+Tpd3%^xUWXy1ugV$tc&dDsbw5iv z_Ur3Ahk@}RnJRRTk|Kg5un(9M^F;lA?`M5~9JQriB_KW#>!0-b+kcs-4fKyVJd2)6 ziltwKOSTjvDx&u-Q|L8y?FMqW`=Sin-)NXD*Z}XxXx)*;#2q6wEaP! zAkcK>S4dWj6Q@PGP&T$8;F0GI9)^{22k8g1^v-K`8~f0uZjbL#OmjN9R7+>{Qo}hU zYl>8@_b-Od`Gn-ipMQt5XhMHBCsw;x%abai-W#L-o-p~s8uL_h|B7w{uEh1=x~R`s z-IT(r7ujWeqeqhwA|GKK!pLo=n8e6~v_p}}bp|!vd2zPY1kT4ANrF;fBksNY_~vXX z98JG~TD9U z`V-?3eQh^5V-10rs+!E~&N@E(zRvnUfM4~e8@ak`?p=QbWbSsRvXLJ2DOmJWY^Bdt zA!_ykB`e5QKIntix{k>zmS9kxUwOB=NBO&%|>nP|`OWY3RckVFA^72irNFLnOl)cREW=4`_ zg)sx6*gABM2c!k}vM2V#{pn#7LK0J*4w}svk`pC;6021t1KC&%X||y{PtwfR7Na}K zVlFl5wSOH5xecND(c%-0g~4xlp!fc4@cA-Blb*{nN_H(jcrcBwBBSXr@hZHV$GU*D z$~yHmay$nlc>1@J(|5V6D<`SETY^3h30dF?Da6LJkWf=F+b{0su zaKq`n=*Kys>z}8E{wOVLigk9`t;>P|{0Dc)^L2^Y;kv}oU`CQja+`X%cccA-e*L6( zu}6+jIt4cIdGuDV2oh>66=S-iqyBZgkd`>zTp$wVTSXTA^-Y!sSK&|k9u!Q2W@Nvqmz(Z2rtT2ebozF_pyXtZY=MtB&rAg7q?|;LJ z?VpyCC<;Tx43%RoZcpqSsL98oV0kW;)QD?;I{f2ve-zD567((>mr5aD1wixl; zn39c}U3Xn&M_6pf}IfPupyRe#}-@_Uuf5NOD z#U8mL_N2<(kXo+jb3V1aLMgXY=4&&8|9IZ@hIooc>Q$5SE9M>V7Q>o!^)16R3dVf| zt%Gij)b`>H%cv)5fSf4C%ac2k8&CX=Y*pWc<9)pAowgmAOr#)UciX(I;(tay0Mj|<8>zEfH3b3{N3YssTvZ4=&jDcCcyjMvP_9y*lBm;j=U!WiQ8{EEGg7dkJ`X1 z22m!4>Ahd}=kWl#(OC3bV1H)w#R>F+6J~sNAG-0So@r>%<)5* z>x!nRcGd=-5wTR*wM1`*fU1jhoNU2NF+-${8=e`iw^(U42PKol#DA7vgD+^)NGacB zucs9dEsGbH_w984IQ{Oi_qmEe1AT3z>tL=dsZVi$@Ay{b9BqVO52yJ^u+j@pPs$L- z>?Kvm`$o3*ow~xz;{vQyl(iUM3CXEJCFM|#=?T4_wH0-qh8o2Lz4r|3c-0@A!^Lsh zEl=3Lq^ANLO#cm;j(^u7yPR=Q^=ZqVG>Cz@DQ0K#s_&PLrk-M}^e=FGe!l7AUX!i? zwbl68IZET^nw4ggFQP}~_n1zgjmCF-g)1X%7~u*SOE?&LUMhkU3LvjSQ~2QA6uw*zg<@RtYJVv$IL>?Y9+Xt9C(sQJ zjAQ3%5ZbD+rG05(n}7lO7bP2k=kHH09lLqS^EM|4c{@-$S(59fyf54|`jf4T5khTQ zN0x58b)+)Jp{HS`Jf{-j``fc6e3i(XdOK7BU&nJ5Q4-&JdO!oB#iC2Ij7yxv%-{e{ zDIW0hwParzd2gSBw{Hnzsxu6?V5Yks)uHqy6d|M* zr%Yq<)F2Z-^Tk^>Vb(J?(q$1MzI=OSqslnIsm$(~Od1U1ctEn0q9Uog^@txUyo zr{7}1549mWcptfYN!EwpIcVe&vk}P_i+;n&TD*m`_J6zlF`lkn^e#mCrmY$Bf(RnT zWEv$u51kP@G-otKxG5p!v*}|E7yPnOD{TbY4Eio!t^=NWRjlPq!^aQhI?NCne!h>R za8aILr)#NqfTGh+SE)N3B(sdHG|ELJczd@JIOyx7Ln-MvtwIchh3;6RD??r(A{}NY z1MY)2w|_NH9ShnzdU`KI;FJ9G*Dsqb3>og)Y9sKXhFYV;U5<{cjml1BG*951vE_6o ztAqW@JrKTP?y7+S*IGjNZuSWZ<;ZKEx<*FNz0l6>@Z4gqx1`rB&eMcR#7LvARHHHQ z^}o01GWOM_Tbk;Kz~Gg`6}8&T0fbZ|fho@ql|V>IK6#c@c4%XY%Ey zrY*H*Le^Yre^l!Y268^41aM-6Q3QZMK_9WABVlD#(hgJD+{Mk+DzdW+(FEjo zc7M+Gj^`NIDl`wrn`e=iZeOqbEF#V7US15MK6lNYxZk%Mv%6i73@?;JW&R0gC?2NQ zDZ`49>P^=G$XYg*vX=|A--wi`J!Af{=%#_F9F(m2W_P{C57iWUpU4UTPLRsQyQYww z220}H_XE0DusWZN!pYm0hSxB-7nFBXR`xkVaX1(e!g|vIdhk;vz&)mVsFfSKXnc$Nv87td~ z)yy6Mh(k8?vaT7>CQ5FgTySXUG?`{j*q zM$IOoejJN|R}pnk4ulB;s&v(w6b^GDI*uJ%`WZ+If((#PmKTz2akVru<@;o>_{eXT zH4W=&>1%-$umXuyN+s!D4qj*62@{=u1+f%`s$Yp7ZsLc6=n{Aa^ehyKAb)D>`cxwY zMh5eui9t7Ex9ZDUT094M8BD=?`s<*RSB)O=`vh0b}edku)lr0j(dY11TECfg;55j;-8i**M zDhgQ0;Vy$HlyFx8H+VOJU~tzokW#}v40Hs=lnxkY5TQiCLneDvM-YJQRP%syf2>nO z64w}z0T%*mVF8yRHirQlqXVuq2B1L=Pt@>0gcO=EDiD;i9yK};94ey*h!GS65&{bI zM1hbDX@`K43<8j(fi)IFal;e@pt#`}fZ_%iV^F&cL(^jvxC*&|m}*J z$_yl_Kr#k3Gbj}?sF^{j2S%6Sk1Z^pad7x%(W1vC9+^5m=!B z#e`I0G09LSJL12AD4Va~8Df8tI_kP$=RX@m?D4Dkvu01Z+T8ekq`48Wj=c3>iqHUJJ_ zDnSNNl>wANF~lnc=wfD#%0jpzmJw8x0|pVKh)!#1AR@#lV7K?vPd)Pac<`@emIc{V&t^5APgPImW$-+B;?jneMNUrl0Ss!j@2_(dqNssIRiODoy1c)6d z-Xo{UB3sUf$-+7T8+DY7()eX|9efQTLPVkusE|hXLA1X?Yw;Ya0OVK(%2t4e(Q=r~ zgJ-W!4ue-$*&<&If9L5e4|HFs=g{;#iSsm@?#6i%JllN%S^#;6A`~K`>I>vJ%0}IZ zws;2BkG`j~#jnr4{rWr*eQ-QG+3aSXUS8#(K7h$-JW7Z0IM};Mg0t)*{{yIn;vdp{ z3^nh^L#X7{Jf2O@dJ6CEeE-+0IQ)6CcB9f4lpD`C-s-{BC!aP%0=u=huJ8dURvkw zNxGdHuzZgkke){mGgv{}pHOTA3Zo{4x=Eo9*C{Mhdt^7gxJUprh_bH{Ba2x)Oh|G) z9LE##`!dUuf6-t}rpw77nJ?1IDH&zsaXcrp1b{isNj!njBA$+1<^@zbPRI;#I8H8d z7qS>2Ab@0^F20f3c)1|MY%+<-)y?cGnPP2eHX@60ytpENCi9GB(}d)IWF)_uCkeR# zJ0KV7_k=9cYqChbLz%=@I!z(tFdJu6h@PY_G)@)^f0F#ZjK|~>v6;+)x@3V6Cvi@; z$xE_BcF7*uC$GqBazNgYx8#rnoRIhAl$?b zAm~UfVoUypX*x{j!{vl5ry~%{FqwM1U7^Nv=pr{zbl#F`1Al$;gcS zPUd7me{!-U-^m~3n%s~-ZS6_X;@mxXE#>KWl#s!4JWg`5w*;9L;guo=fC_Rk&gSW~ z(xr_{#$&M5bU{Y(*w$>RI^HXr{Nj>} zC!Y?R(S{u9B^j%DcyLKYv1B?z(Iyjnb6n>0e|VHk;`ukSXb|FxW|biRbm_m0Qb09w z=mUC`{V^pLwg|;BlqbXG9MOM6ZU9n)dG;-tqOcd>&=DJx?xEY$_R%NjyZtM#&`t8chJ|06PGXFP0Yna|ib7DIPBKgiMxb ze?##l`o+RdkON!i5PAc!Ml_bH6p%Lod@RQ``U=vgXcTj_2MAup;|teh5xJG(6q+Xu1%9DT?rmnfnWzSsp z%*&n?8LCpF^m~dCP6$g^aOnyzy@JcC#EnbLtq^X?=-+B7lI!LKmftpkg_*FR9rM>Rt(v|bZGSl2e);#{!&MR- z#rf6G+5Fq$@4>-z*bhEo2bN6()u&NE>qU3Bp4^L}s)_5&2aeCzB6Om^}j z*p26Zq|<=XKJSO+)7xY|O~zGae=hMwa0KD)**pkLK+TJYy`UmE+5Ld4A?zQ)Jj?PI z*VE+|mB#d$?CXD1a=Lf8w|%yE{#na&pyk@$`m5PAna$JhF)Cv+Bl#?nI*e$j&XpKl zobw^OI3I91IA=5-#1|~Qh%QWjw%BmeUClPh>ty^r$-!^c=f2+TQ@Z(Re`6lI$#^2* zf>e76y4Na?sm<&?K3B}$ zxqwxZ3M7ki87zVpAH|;$Yy6q$5&S*e5okcZ5klw|N8qRZwT^)GX}2S=i7$c=%Ou!d zg4ytZMlYCoAzB>)1Mk%be^+pSKX9S=Kn#cGTqPImoSRsm5A=wgD~YSkD!vFu@e}%i zcB^lgF|H8P`QN5;1DxXA`jJN5MiH0tj zXj!yv(c8WBLOEzgGF9mXTwlmp4KB<$xX4g;stw=A@xSVoOV#hxtsCD4$`+e`$Qv4@ zUpxvQQM87Sh(2}Sf8E8tFRf1Z_8_k0I#>Lux%%H7g)mOnc{2CmiE;KcqY!Y56wHhA z_UTBK_Wxlz5(}=38t`*HGT}KF;oy8Q(Bb(=Ymtm38;MA7J`8ENC)^zH_&35eV1%SXWSUfeu{V6kpT-2C?m{)$^9A}D9KN+=x&e;80~^20Lt!>uvZFT@=? zERa%FKgC!rte}kurf!(m#)FsE@NCmCFFcoJa37EVjQPqk__K6leI*?QT_ug2^Xgv3 z3u()gyy6{c!uT40&=&q!k%o0xn#%e#=;o^o?e?A@zuSL5B=r|cR)OXEKN@ll1KHxH z4DGApDso7G7HWG~V!;et1*pOWGF)L z*!=L8HA!h0ZyU$Si&o?&w4* zNs2Xx6d6 uxy{pqQ``!6IZk3bA^tQXWx+jS?86P`w%;f_pyE+=K#2ps8Eqb0+A* z*c~-Pn_Ow=^>v#U+n`c=X^$=2Tg7;pSI@qYf4633;0avL4%cGGQP#BG)#b3PGBony z>JjN$Q${121R5urD1rucA(+ic5xxinXvg{iVXxBF17?lps&Io^h*=ooM!`4^m@(Fq zQcEbP6nFkw@;HK3GGR$TZ(+1+Dk{(wS$nz5ulge6*6*)hS0fwiA?%fv&;f9n2$|Ok zfA{lJ>x%${-1Opd*P?}09U4{Y*R;VE&C!R^TDa(KJsA2uiIaTfP|z~I z#-4noH@|j#HX*YnV`budg-W4CGpmrFf6Iq}@XX4ldE{+68E^yXCKamaB)K#e2G;*6 zS&2ph6ELtgpq2d?amm zY+={%ANJCe)I+&!^T6oSO)(Th04j>cs~G}YMYd}JsDr1`(n0~d3GCDnBDP!Pf7rcB zjeQ#$5yh?aSdZfgx*uh1zb9-y8d+%~Or*Ah4J%n=frAnOsoJ_QRo3+Gt}Cf<>zo9X z0i7_{C)paU8{-mz$~98T(I~ARBR6oOw8$rMJ1({ilO`CPVjbFcn_*-flQlumAD+m- zjuX2{YKKXp$f>~WjYR;&n9z38f1*!+Od$RX6N{?5hH0;zJ{MExa_a9U+c0Jc+_c(G znTsiT*zsr6?Ea`FpO!& zo@{cfQB^(^FRnOw^|(Q&S7~j@Nz=M6i)Etn-du9>ZAcg4GQBEO*if0~>m1VCbcwGy z)^%x5++o_Ly2Nu1l~soNe@?5!79Og~Y5`92>W6e1M%NY$OH1;tGAb4fn~R5)6*d+R z@mHz5DCcVu&sUY2^sRAi@zAH;Up#Dss%MognuPu?v~O?mF6>*DQWIs4+MLO%C@j!| z4_cd=4l9cno(*C~Jlj{oO4%1;VR84_s@U_|QxaK}mAcC~2azHUfAe}qV2>siu(0uT zHJ&Yh+*3vK*IeWE*LwY5S9vRD*ay`&(@9@&X!ukDuV03NUr zOxS{cxJM51c$^Nme{p9wCZ6TVpVN#Z_BgmWMk2_xuf&HTcV1E;V z)l0MrEMg!qx15P{(QqX%c<=>gA1jeD(Gb}d<)zRR^X0The_j_m&rir_@}<}kk2}QO z{&3tKK3Nvq!}F^okKM-bx)eH&ueGy%e75uc%Z_DRwR24irg3vzjcIAP&$QH$$27&n z4yHBjM2g!5pRbs!vt}vvEYJPY&_~Ph6wbDLs5;dQ>bV4Eb`?d1oP#>WCsFhSTp(>9_~7RvpRh9<&I-B7DLt1 znH7+h{`s5gJWXAc;$Cj^&Hl%;kG?2Rlgnj?1I2D5!eycm-%t6X6m?N5UzFINws*9? zBvIfie@XgsJZMPp6Uc6LIIB8)HE5h(T8E^6(8)jEG%Su;xn2rY;!a={F3vOU%j(qC zRe2C51)bSbS*SRBbf(l^t4l1-gIWLZ`|22)ca8{EzH*%IM3_ArW;v^aVRfQv-NUH+ zz~J=L$@|xznlLyXjMH`~Na~=V6n_j908$kgf1*w>Yy%kfDj=-RvElhOXGSZ{Ib*7H z^Uc@JU5c^ir<~1|!fv;>7HOONNc-UM&F)U=zfQBsyUZMJ;Z~InyMvL?R>X@pHsIy` zp-bJln_4#(nl2|+^X-y8%!&P6Nx#i{&~9p` z6zVysQq1f4cd~v!-=go;O`q)VzkBtiA?jPY7lb)#)4`nia#nRY<7YEga;9Brsjmf1vIVvS%UVTa9F+ZpC`9_U@(SNNVd5*86ll zoB2h3uffQhS4Stmd~5+sw{23GN^RM14dKV8>Y%aHmKA95(Hr?@I<$#K?a4fj_zi>FewSD%d`N5vm z8L8$fTm4Huto*jn>bpTWLaRO-q)qkJApGc9$47^{TW>B|wSPy*`)E=9n?-EZx}^7S zy|HrCU|ofGv`#(V)%{yhv0RBGoB3@f6hEHlb<~$JSg~r!#pHo!&L!XwtWaea<_D85cbTfwv9Q zo5ac6ga^HkC%jt}`yVAa!?Bl<_5>4`+<6R62QxA;GB7hSmoa(_90xNpF)}bSF_%<& z48{R8m%%v!DSxF>$xg#C5WV{==8ll#vE#&2)dOV_P^zj0A%r-jZIni$O%*2x{+@}) zAPy{2IX%zV^A_6{5^$hw0(kfNgMi)J@#+<)|RQC9tRSGjACiqZj*iv#IwL1;Ef5kH7ev7ggznoHRYT zv4ZNhq}328OyAZU56@u`lnQ`h3n=yg8CO|QdpU+Y3z;Bi5oZ`OmP|~Pc1QCot(n8b z7$$P3Y(!nz*#Acc#ScRt!^AscO;oIf8Y8BEY3Lsx!LVP9{*nFv#)a9(Fh5ov6SIr( zjhPX@VVV^51)EAR<)<4u^A5AS!x)#5_5>4`n0yRgQA9L0HZ(y-I5R~xH%3G;I5I*p zGDJl+Mm0e}H#RmyI6fdeL^L)wG(kok91*E)e6=(~z zML+2Rgx##zdolBQ*gA1SSiZC=(%=7?_w21QLQVQ85|=12M)#rn>*@PJY?z z?6dc|XWeffGqeA4W|_cb)@W(u<8Ux%YK!t!>6?mC#(jCn$+G5uw4&)Bn4VbrdZP1W zV(81n;Pz{{`?UV*)^oBJwIhB~N+23gCb*eZjfZ1!-JC71!zVG>M+ zMp^auxMd1Vm37B^WYb_SG|4udjvsUY_QN42=D-s$i)-5$wZfB>LyVq+X37^C&4w1r ztuP2LaBUv6$wvNvh=(tL`Lg|oQghyYGjaSxOgs$>Wk))q#W~6~$n`*aMdx1)>=NKSSTB01x#yfc(m{Lq)US4(>%M9h+6C&k{W!lT1+jkNnR6&_zR z)iu;7>LX1~l)b7ttMwpSw;Z~F+&i)L9u-{SJJsw*Ps5ChRuGCk1k1Z-4xR=V0-cI<}acx+oiP}eIyUN9u z80}Cqd24HocB*{5)}axVuYM7uQI-EX7Nap$)^){bmnxrJkN2&I230;zpV!LCWA;Cm Y48n7loPZ1+3^Fn}IW!6-B}Gq03fO7@r~m)} delta 74107 zcmV)GK)%17r832VGLR$zHIp$2DSvfXOOx9+62ALa=#-)=BbwlwxunKP?97&@Hs#U5 zsm&fJ5t2|Q35AcD%>MfQ8VyjC%()1SMx)X1ZYo$ESHbGjyWoxW!}i_#k5RM|nIDQI zUTqI6krsX?qE(V+ewqPQt^VVET#Ljj_k-@%n=lEyPhELF^$eG7Ws%#b`+vuu*8ko9 zYbAuAVb2sa5;3=1X7XS>uX<+p*b6r_^>` zgx==M!{g?cKYsYK2?G&tzJGrGYM2*+vBoBh{jf-w_meyi@^YW(tq#db#C{Z~Mu&|^ zQa=xq)h5pUz*^(q&uam}I{JN9@?}!K@QXA|>0W@>5KUr^er#kr z@a}<^bEnB!&#IDy$i0&Br;FXOQ**mBTg~fE4=08WB%5bCMHZ(f{Y^|;dK<2szOBMO8w)b}1uBR>)$ z%wevTot)8gd`3a&HGjI2b8C6vCltzEc-zq*?3xHQZ@8eWL#D9XG)*FsPb@vc$F6Im}xDM$>8bEHwVDm%u!D9Rs# z$`+|4Em|K2*)llx#>n6@cRcYYTf<0EQg|QASJ^YVmBR}?qq}dtInBKn+&V3(z+R05 zuTq`dvp1sx!GCFDdS9zOA9IL8%OuNDnHS<5r8`ej7eNOX-tO+*Qg|aO^W0rIX-bP1 zNxwG9*SJj@q@hV$Bbnus&-f&nFY+n6cj{br10r+b#VGT$AaayOFqUzz+g>3yO`PBv zePH~hru7`KVIKJ+x(Qg^Zk_dl#O6W_Ehx`BRU(?nc7Jgeqvpva>xslqlgtTbYQ4L- zl&k{HWinhR&zl#_&@)fp@Ao^0i zlBei3#IQ7(Dum(ny}CI-G~BCLS<(|-JigSwxt_2Oy;|;&Nsw~SuaOsru0*rynZ^_Y zLFHffl7DHg6t^N*vQw9^tC-MK09HB-sX1RO-9SfF3+kuzSR8UC!FukL1DykESsf*1 zPoA2-OlNFn00&*yOvd2{R4+}ZwTvHVLE%-V@B#r~Bt-}5SSd?ts|g^kx+T@$ekt=W zZPRveK(Hu^-Trn^dsftKeV)`7`q|d>-7ub-W`7tV2XwvD|1h2k<#ZN%{Xnw?(;dvT zKs4BWlGusdJF1eAZW?3Sr$$3mVElF`|$MZ2IWq+ zrrHwbmmhy*;L`W8*_9K4nLw~!4L;a&vAp9=H7jVfKD)bS9Kp&n3xI3gfp|bHt6?1M zIe%3oTBiY3*PA83>Z2J@3U6oE=CzmgfuunhZ7^X`W#=Qq(~$7m4`W5~Y>0&mfC71i zv3aKvaL7~J>K;geG?>qiz2jm6bN+yx%uv30kOq;iM;qdXKwk(Kl%kdmg2DwQ05o2j z8H@R}5Cw?lbr^W#z(o79wb$xiGdXo)!hdjACCI#u)wEM4nqGmJ>^k1sRG|Y!nbpmO z!o5a!mJ*ZCqI)jmP?#n2aR~c#(uHhHrD9+*D?Jm;txacq@OY2WLwMWI_a7LKA}Bi> znUYaF1sL+ul^n~3(+~#;T~#p-Zw-2QJzskyVm)rcn#$naR4vA77Q4GCC9t|3uz!tw zr73f7R~B0|L=oG1cCNLedP|rdeZE)2EAPmQqKJ%tX-}i)I2a+ItR<2MlKQV82=@vS z({~6)!0kE@yw@`gR*vwxx)VmX?ri?W^k!92ElfJOR@h=8GMfrObh0+b{YjnqXotZ~ zN=skzLZ4xWv1S63PC(xFuuC6wO@2NaqG-&{H>MP!W6rrK;eDV9U52T?ow)z>D>+0@;ZH#CAMH-rjht6 zU91^b0YF1!KK~q{xJeTaa;Nyr`Hcg)Wim`K7IL4k1oNm20G)+_ikgMP@qfCrdvaTC zCJAhAqK=GbXzj|Q_mT>Y#Nbl(ci(-I-WFY?6J^sdn_?JkIoy5(8(j$an?B(fyphsQ z1jbs&HH8}#>if5I_44gQ7rF8RsO$(@>$1A}Oh^2q0KV~A&#mK1>vFI&VlkT$!yxv9 zVw&ks!*KrT{d>gv>)6#kJT3nIIP_(+FkOl`^64)Zd(&t({nG{A(!v**bfeTS0{d5z zxT5)O`|kfN9WRQL0TvUp8wgJX0x&d_A*3jO?HXN=+qm(4e}x`pAZGX_k;e-S{l5dmz`Wtd6S(53s*XtxGP#7>Neh%lGGo;anh(>R3s4u_2 zy?OaYBoUKD$dpI7_mSdJ3ZGe~qT6Nk@0iWzj8YoEneimf7j0F~<~*VC+dAK_n%RGU zZvPG|h$tgj%2T@lji8_KB*FPVnszo9RK&Xm%cjk1-}F$lE3D;MRHd13^A85Uwso;F zb=QOC{fyBL4Ez1Tf$;)9n2H}(#lkOG`0-`sw{r77;YV$@>wIB6K<&!!XJ#ykKQ7FA zZAuSeUM}qs?V&7Eq{KrlO`8{MvqV&X)W+iG_retq4L06=^0-L`xKSCADTCGADt``O zPZO%Te!ux-4VDtE(#O^SKsE0M5IdkJ_+M{t?DjNb5lb?nMHb176RneIvAOx}hNQ07 z7p|!r?;Bpe*|6v@)y+TP*R9$OnRjc>2a6()4dG)nBV4DERFWi#N9mj5!wwLC>2Swh zS$fj=b&219d-v`I)^=rGt$V~*mSDfzKjXQwUDd`f(gO3$o7QZb7af_lwP}E~-E<(4 zD|0Nq&p#PYywbE|yme(X7s|mt=b8wfO<>o`%8MC?d|Dn0vI9>=M=99fGO6)X z00zgjRsCy##%V&d?1_Buq!K27+f+-l#_BILp@3f~JmeFk zI^YqhwhBn~2egIhh1BRlUadPS!{AAueJ>!!dl@+ zEVm-75h_>v;{DcEk zl#)ydjoN{Oyv!Mqne5c_!9J2m6%B?s(grvPz~w_#<4)Jsxy4{%^(_|?PFvmOcf}f- zOcQ{ZQB6S3pMC1&#Hq!9=+xY=A|E;Se*-&lqEdAQ{HEEN2o?vre2l%6C@vqzp31I( zzVV?%7=7bYT?c>sa{P_XWp%jFVBt+|@&~ zz_tM>=0a=2z$=VMQwHj|CEIeIpWNNL!Qf-=OI)- zw$&r7Dfb>0*fJHrEu0tV3}=ZL|FuLX!1IOY*Et$X4lYuv*x1S(<7M!uvwp+Rhk_?b zDnv+eO&r6C`7bkpz=%UXse?NFyZNwb`$69_FyFtD3RB`Qh?hB-k)_B zoLsmjEKyvc(tAx%N703$SzF7mNNTNMtwq-v3dIr?q#V8t;c|`Gz;2G z_82pqSdoXQaG71Ctj9;Y%3H+vCjVG$iqFpd^;B_k0v9`f!q~*A+*aU!I!6o!>w%Z@ zDR5E^iu)Qq%2kN?44i*4DqiLYOiinL#Imvw(zzIM^q+#3l7J(BiQ+p)cmjYkMmX1} zT$nEfJHIyU;_JaKF20FOttrp4_@9N>0LyZ6yhAGlhYUnu2e7vai-zGRvJ^Y$*@kB4%bUUp|c@VCX2{q66<3XtoGDjF`5 z0PfiUToy2D;2`d!WiL-Eysv%V86%$qW-rmtqZ5y?a?*r9>&B#>dYOL}0B0@|MMMJr z35T+O%Rc|$J;x8l>TAKzFNe1SmYab5h?f{6U<1reVV zcWUofMCud|ce`>4V#(u8)%u&5eVNi4-<)HyEbeXly{Yjr2Q;}|iiOJ+yZKAAwu$I} z6sCtBT4+Ti<>O1_V5NYUn@A$qFlS}gcFASgUm{)AV2QaSTkDaApP0FZ%C79v1(FfP zCU?w1feBqZaB^d?Y1wf3bdw20XD7ToaNbkq|D(WqHt3 zAsN^+wb`@MEbuh~pxQ8F7Z~DK5ti8LGWD72pM$wwKtAj|7 zxkkGIH%n-yz>etdWs`e%#qqtEkg9ut1p~$_O*sb8sQ2;iW8C7y2+4?klQ2+6z+|so z)xb9DxY>a}(js{Fw6-l|*oNH2m>>t{=77D@li*nomJPuxS_A+ed^8?^suHN5Qeoe{ zxn6Irm488+Z?+yx;J;M(q|AUWcV>-tdj{@-5BWa$Fz>E0)7UP4<4ac`7Ot@D-toC= z_j++j-S>jt<9$CI{h=r>JA*MMKgBCB9;M)WoF}a`-hKW>J0w@ zfLnle3T19&b98cLVQmVt3>HyalTp+uf7M#ubL6%SfA?RpkJ=e8!w*rS(ywWo-pzG# znWX1FC3%o{xn9*;X;0F|=lt~r2vT3Gi=CW%ZO1b!iiAJ{1i&9a^VQvouU=nq|NP6% z)fcanUWu5gIFYNH{VJ8K1YWZ&UESv>Hc#KxfrF>ruLY<1 z>HV(BPlrI0cb;)kmee}f@Pyn0U64~Lra+;d zuwPu`HUP+18>JH_lw56aqvDtd>$T9)PxxaSQfF5jEn9CC2zBGQK%Yf|5Bc#_`i{J8 zYihN&q0d`C5}uyh8T3-*CA~Q{!*knMu!HK3-YSbb_&_fcZ6brmlWiGFf6&|C-)^o1 zH26xaM5>vIS8*zt20d(#SMRTwafANhx&pcH_~O+uUVT+xeFuMmX&~8nmYWezGWfB! zjb>b$RjgwsGEJ&{RosE4(5mAvNrNN%FUR)3C~7bqXg(C3Z=DD0AKBuZK~TCMu=(~d z?55wS&Yq@v3{Q|*IdL}9e=sG-o}zVh%A2m(p3A&h$2_{m&XoKF2G6bSeR-rE#gg6> zdjYf;VB)?>wEw8<3X!oiHN8#O#O07zJF>&X8)j#licCyT92U)3Cc%vL#EhLwNUm6n zf{$Hd-_%Ev@?9Sq;6>uYL@sQ=YeoB-2IqOCH&Dp_TvD69G~^0te*`w~2b@znO=i)p z-R7u8H&Arp%kq)F-PTo?7nPrMw&5uZH;rvib+z-}l%kqYHa_$7U468jTcwm2O5)Df z-6~)-Z+xRTo@}!RCE%-wK=0J=gBi3+o9}4Q?GE(3KNs8k($AA`x9206j`wvSJ6BuV zphTS~p~GOlTpz#Uf2hn`7eSSeWUlj6w-(i>QnGlYvpr!^QCH6+zill{OE2}FsPYQ; z?U6cXW&}O+xUZrgxaO_(Tn5X47l;!uD4ZhWAq>Dsyd+zDs9n4Rz9N%o9U@ah5X8Q5 zWWaYH8IbPbV39laIsvh9Y6_rq4kX0bffC7L-8;~pNYYipf3g&g8K8)nNzwdSocYyp zA{rk;F^l2&9MPaE7N%3ctatklmy>Ch0Eh8p;(3#ah2Ws!Tohrl!t1g=7F}m|q$y{v z*bDB{IXlId2kS?7JG%>dY^>L$4^~Jp_O(k{fdo*6if5tYIT{w9rs4PnG@Op-`rX1r zKqGt9@$-^Ye&4Y1Ts&dL>0~wXX|Z2S#qt@Fe@w^b2_387Ak{Ne43Jnl z|F~QgfMxzGm90Lbvejo(wt7)z*A*TK974N8d(iM04O%l~$W?#(tVM)4X(6&}!!%&| zsX&7NqD0-|S~Z`@Djv=yD{uyFMosR2~%QXH$Gc~rR?m<2Je{UV{ryqRv#E0 zOk2RM*c=fNPl6-R*q#BiReq*`YM>cVO$M9J?%1`5s0r?LGS% z;o)Eze+&u69om6sP7gp+F3ro5sL884yZM20S?#D#6LK1;PmSFWGAde+;NZh!esZ%V zQQd#Gvv`)`C`m~l2h>IDSU^GpFvHw%?{h<2lznPg7I%lvCpQ6rUFI7?q)eOMB>uFp zCx&qd5+SPf$>kwrO!@KL_Op)i1Oj#o<%*4ve-NECL_#GYV(L(}kiKg1m36x9dH(g> zc9d5fGiP^|*}M`c6L;_Ippn?ujSj*sULc{U<+n zi^Y+g26{~DW&q=9J*OtHciW9!w`&QxYEgEZq8igX@jzn}@y0grOUuZN~ClAu&edUy356^h1_^_)xs5o!wKCd*HlNE7%q$`jo$>OM35f0=){ z6iu^XZ(m~n2YfSID<6XGpybIs*ithynJ}5y$^8-_Ls?@cgc@lLqX%d*P5Q}`OQQi@ z8n79l6TQi(%NYb`2K^Six97Hy#cViaA7EJ!?So-08Z(FKk{NEEZce8EGn+FBk^m(H ziU{WtSgP@gqN>3H+D`yV>DfL_f58lQ7<`gw>ri@_)W?@Xmw`2;*-WGv3QM*4DEo7D zUs1KBqLH86(b*IT8#=^Gf zsq)*=wZ}+xPQYI1;hcA;`9ci{pgJ>|nr_KQ4(9*8b9u=Z#b79*$g4v&T4DiRj&F+) z_u0t^T19!zT@4Pq-E9y7e@c7=bM<`pi=Y59vf=1h3K^)2Nq(&c94JGT|5W<2IV|$w zu%=QkjJgs#KBp@SC{a%C^Oh3t44`@X-;eVX9?a+BCWE6do7&?WpWzhYj;KWW9-NSm zZODUcxNRE6TkIIe+eM!Sam_CV_>{?PbT66DmSX`QhpWflLOf4JI{W2P@BqLgd)#&GZw^Gpqm!-Or6{)VY)1{cT*lUI zzP%?^H#p&#e=z{pGx^sNwqWVtC@*Q{5OpP=9fWUYcdFMjdw4RKn@NS>|2l}P zWPFle9+?m%RF715RHx|A)`|87(`q<1LjdV-&QRY&M5h|grBErPWL!QKBKifLn)*~X z!S3BA)(cz{K)ELU3^txVW#i_>ZG3z)A8W`fAf(5D)QQB*2>%)4-}`IJu(Nx6!3G04 zFf)@Oq$q#Q8)6yNDUyBInow1v0xcyIV{S>qX?9|B4g`S|XGe!Wu|y*+sZ4I}5+#x5JduPW zt<&UYmi#pOp{O>+@_sy_ijTM%#HgB=V=6|Em79OfmTo#96EXUfJ**bF`%o_3=$E@y zo6=3r@(&o(W$tI^e$RAUZORAtd^aX|lub9~+AW$cvZ@;YeDn6|wV)lmslteG0#sR) z|F+E5yVqka{9d~uAXEq>QcL$v_B z-0**aQugh;_mf5OtHCyhckaGC{+bwRQUa~0WWjT9p4!XF$x%lnEV2%@#NQD%k ziBJNiI8CMx7eD=slNo$_n_$GWN*?XX2l!)%sWe$6?=SumLXd<31c0Q)F$iuyegYw- zC+*e*Nfp`7B{Lt+K!8h$lm&4P7c3uBiZFjx#~~2FSL?%A42D4x2jkbIe)_&KHBcr6 z;xQVik>DwSmxvJM^ov-HsLeA52Y`q~ff`G0fWWz$r?nbS#}gvc(ZUSUsHb_W>Y)o7 z%m;VCFpN?qLhI>Tj_#}lyh*C-wN8gm!IU5^c)e`}NHI3ry5ZIh25$xy=-#GB5te_5 z%Ld^;mqnHTSkCf=!K$Gh4@5(Bt5hxUNLN~;JGoDC{NB=o& z$3h{7^?CX?7{)ODlN52H9YJ)c{!xwyr8PfhAURA%r5UIdF1+2kw}pGld!*X>M9`VI3TnB z<$(34LbZDMkFNzdTh6`~=zo4Kz@69|y1uBLat=|GoM)$lVGOfVt`J0Kt8%QLAn@oK z#Mf@`YpKJr)XM~f$Auxh)8~={vWh6xuT*p~#9Sma_TPc4*j50@w zIOc6B13cJ(px;Et4_M%y0Q!BtbHVYKcofxv4?i)1kWzn@Q1dB9afg`y2OM{C9MjKY zq^7K!Gcs(EqDAm{XARevo;ZnU<1q#XA~|BN zm?1&LdFDD8#xQfmDUwt;YUF=WenYCCvM-+Uwh}p#^R^l90n-mMq9cOqB+r+9V1DVb zN+bIy5XkPB9*{0+-zhxcI{4zXwf&D-EMO%QS|=7-Sk;gT|ZN8begt zoAPj9NS{T~U>L(FQW#O{uhrD)vH9=0y8$yY%|B*~ZMMm;*XwAcCg6WigiiPM>6E}A z0m&~E7t&#c^s_!+@Y_idI;s}FzCBAV2E!Pp7I2K9z696DcuOE9APv`U%d*<^IPB-o zd*f`m+7#t7i+OC$5N_R9-=)cq*=AkDJSC%uHmja})9WX{i|Tbp9bWb6%MsRe)b1d2 z8aT^xna98o$O(cZu?w+s&zQDPN2be5?ec=B~F1gNLuw zxGx*eB6={4VMH^imYA<>$>2L(rXWZ(oG|69mZQ64yd%7u$DNQue0OpRQ3LZ?$^;bO z$FDye%qQD5r=RmGJZ?W6c0AfqFB5WsUNUpS%a;x~6#19f|G9q|^W|805nLPa8p#Q=@;Db7h! zZMEiQEF=LXvW;$inFBgM^T#bhleqGBV$K=Y+I`tj%O-Sw3DHl~31tlnV&oC?@>TFz z<~10`F!O@Qoicy_J1}9VhqA*p81n_rIaCjaF^Fn_0~w&N!3ggOLgsh!n(7xv$i_%8 zea4U5213fzXa2Z-%I=;Yx6eSJ72H5B9B$em+++;k_uP-7drcbxkNETPgb_Tt{xr?k zE8mN7x3*0d@YLzrsIGn}r`e+TcV=pWYd49et5qQRWCDLj!HE+Jb&>Yk@dnaYCP>}Y zVGlR&wy(o|SQn-XWCl)G1TDtfeWUt?xFCD+YeCoE6jNG=qfe z7-6PrS7Cq4$Y!^ydtvVO8eKjbZe;5syIuGqgOF}74n}I<<9Bi6NVOprI7KxZJ_YN&yz?Tl*#GU~jG$euCalw|u?pP!*;D}h=kaz7Csz84kG>!Z`7wQyJDc^G_>X1LF?=-Gnr-?K_ zJScYz1rZ1&xvH08@)XhpL-r5hp|kK+1R=<2Mf(fV{3#sZH$QLjW-c8+~&oKi&G5DOU+iie`A>- z&q$)mP4J^oA)lG*`J95!TvgQ`}k1-z($xh35i;Mv{%QsoEsN4@K6UI{$)0SQH zHS1Cz`e8$JeQBqkhW=3Hz@8L&a?yVn;6)K@8`TW+%qd+L=JCoRK0=rjmqf2Bx@Rx~ zc~e_#=XVgbA<}xlorFRnf%g)M#xDY1vhgD38QfQK@8>;?J*g0^k>ZUWzcnOf)AF{+ zmaznbK=RXYqP&aolR!WhJtj=Pj$_)3hJ=zJPXi_t8_Q8qdw&;|G8-H$!#00r6tynN zK+0~W31#l}u6Fey7bG}FOioVLz{mwNIfv6O>En&*IW~Fqp1{4s;M!X(WGmjNVJhsn zhELY1zz6SCUG2T{MTUZ)=6H(>7_fdpr(wGAqEiDsOWZEvu1Z zGAd&s%+Ms;9>IAmRCfHlN5_9TPRA4p775NbV9GDsYSWFKK5#oU;bB!)g|ia#W~u0Y zUYED!<}xZujs#7O?I8@BduC`Frq&QTR1+!p(_LkTrWXHQJf5bS0iQ6!k_P7z+==2G zac;6f@IfNDJV8n@E`B-e` zwWzCAKHcoelI>}vlYXqCB3vLv$q|`A&erx=ymA6LAYOCnzJJU3gfXg@%>rQ}lFp(R zu3tL_5rRu9qpT)@UZqM8fG7fpA26jcT@^S@f@M)R9He7D=iL?gVzzIecjaQ?{wJil zrLe_R{`71@pj=mtRA_%Bg9H1}9aF*)3d~ajgGD0O z41bNr4DS-VZbQ2^#kRJ{)?hDfQK+`!2$MxmQkr(Zeuo#yRwKt|)jV_vf`Alx_>t$F z@9<{gXc^(?`4RT%lk=mKQzjz95#y3Z=NC~-BMF~M#nJg9dNbkE8NnD&&ZZPkbe+9^ z@%ZKR-T7~>9YIP6+YU!F8l#v?-wYAo@PCEY>**l^xhsMkHG@1?6K?P`ZAwiw*5ovj}{_d)UMYL=6~}l zFBW;Z^iqD**%Ycjt&4n~H>NKzfFOvmB$^qQaPGQUrC?CT6Q?Ctlg63`3bJy_p})M+ z8rZOWOcsCJpA=#mK83m7kZU7)#s@c*5zPg zU1q-S!ll+FcA&a$eF+wb8Sh(St=CsYYLp_af~G^T!G-pv*1*1SrHy$$I)9Tuo#DGF zPhGMuOc>a)IC@(lUrC?3&myg}%5ZR2rRCDgzQvf93n&M_fKHUsmd2(DM2+j$nZuA+ zH@?nTV>akyV{3BBjL%Z(K?+smVb*-zO2&qrORHl zWoLeN>}%PkFd~xJ&dmBCneXf|v}Js9F@;WAd?q@4sB#8R&0Ozgoe=LjbWJSFp|rl# z#%b53`^PGA~TV|5;F}IR}1TRhdjWU=jX5O zh`=Ce?bC9bI#!coSAR0Evb4$SmNmK0^{mmicJ8svs2*BF1C2J!kO@i%jTokgB+5Ab z%{v?|pbiF#m`b8+E4hMyv%JMo5xoZb^bjOrfFKZ1=Qae_9^XKS=|Qa(tm(->b1s>w z7%>1YB}y#B7%Lb%(j-A#k=qdnj900hqX@?!KE(fy+T8D5?0=dy3fu#+3n43b98pD) z-)oUx;GLWb93>FylG{+Hhzr)PZm)D%XjMokSAdtW}@5J{0hho^)`eTT zSPaFaM6mtZ^2Q#NGZWx$?j9mA?B+JkeKd@<5it8GI;>bH^OG4AIUa!OtA7ZVfx^e| zXQ(s;$zjDLo%pSjnT^$C`_Q(BpUm(^j^k%AMi@U?j1uhEbn)ep;ig6e_Vdv7D2;+K z!Ze~B5r6D2l4SpQfS@e`>O)#BqwUW>O+0e7GagS)0+0@qir(0n?y-x}yMXTQ4DJa3 z!p;fxe%4@#s8Zut6O0kY8d%9V_P2iV|8SSK+A&5r8Sz8*XT)y($9OOlA;^D3NfZ;O zL~_41`*vG1dVDi?z}AfTQ_m>E1Y?9zCIO!i&wm;9eQwR3xI4|An==VZ?MC|1zKveM z-po>g4sNJ=RKEpt%UTAs<5!!SdoxIPZQK%xaNLc3*Zg*)pMAvjhrCh54aPW-xG};) z0=zNnK7jJvvs2tt zenWYGFEWbq!5CqbrwJU+{M8L%d+!y9KeUfhDHtP6C5TNy60Z^;aUIo*@$d3F%Dk<( zE9}jKjJ>RJHw9xj6N(VV7>rTke=a2Aet+5znD)gTA4|W-X!xO0{{f2U->rU zfW~{CW_*43U9<*Tp#M&__kzj%R+z9TR)|pHJn$l~8~2W9>jl%ZPxGu=`-fT=m0sO= zlT)8q2AUT|&s+(buh+e3hqXf>9!vAA3gPa&Prsbt{sWqD*suy^Ze(+Ga%Ev{3X=>L z2!q|Sx81S<3x5JRG?O8uD1Vh!QE%He5PtWs(Ay*+QbkI%ti22wmINqPpj+JTVI2lW zqHQjeu9@+ zHtVb|%V^EYtgfqQ+eUxJcia2xcS*|XI&Owe*(Bw89zSV!AW#xujep)BoOveD$T4A? zc&|n}RS6UESJ@qnA^~@hj*he?WK^;xWH%1o+1=TGl*eH1Q=W6Y1o4Mp?Y)t`9PfX< zes}XVP5#=xjZ%yNBALHF5^w%*e^=IBC27Iy*dB(2i}S!yM*PjY}_!;t{t83^uMzPzO;8?#B=zl1Hj>V5jDj<>foiv6ps~V>Vvc(YY5 zn3)vGxq*PUgAK^tbi(-FVS&KvLq>8h_R;(7j5+f+nwt*aWVxs*d}LwCvAdb{32P#- z5Q^`tDWZ_CQ}~`VC6x1TP`)%JT(iPga1l>d_j|&^8-hl7SHL8Fp1@X&Y{AWAe{wyk z(F1{IGk+Kp^6fq9zu!(Tq@>DUr=(&_O3-1b!r5Vv4FYbQnnyy^=Sd%r-g-3;85EHO z1isj5H;Obn=|Wqe>4)Bceq4Dj)HxtI;l;7``Htb zFAeaeSMW`h73%^b@e%wKL{8fY1h`?d0P#01MID|B9VR9=jx2ura`adr%d_G&574g% zGx?EH0C}-3`7CjmIL7FsRW_77Aj5+TA#+~&3GUG;DA3rjj&{=Qfk*Dpk#sZYzR|6s z!+*dISkWZpo6|UOdnpbw3p{Fr<^B>6c9Sm_QR3^DOMb0yvOILj!E+G92KIG>^}l{l z=b+nG1;K}a;R}VQFZj$-z`LnAkmT8KCOBz^9@tLa&(j#aAnA+j1}$Zw>%+LdNN@Cd z552v=qB*#jr0uJ0iG}a5nx71oLm14IG%?hZqtPmCLX&%>oer|!BQLLDQv6@?o;Keo zEn)h@AcbFoc~;dM66EalaQ_dpwb~kou{HvSu{Hy@u{H$Gwv#feDL$20S&!Vt5q{UN zm^X7^4bA%yf*6t$DH5b0z%CFVaS-&7y)*44*)*H zQ=^hujyWf@kLD|MEK(vGpY~w@S0rYon+8v|JAZ^_=@(%M1eh;L_)uyX)U$iDKO{ls z{q0}o-!Q8zJlE^W{1^lgnWThM3tx{+*ase4t=u%|R(GS@vQZKFNtw+i_)S!TUFMg0 zT%bzgXJE5K2zn`NJ#JVs_Y3g+N{Oro2Oz&~>>L++FfMY`IKkg%_$X(s& ztr$}EPm>$5Z-Z`vAs2bJA5D9?OOh4d$BsoKH-#&VLXn?Iz(&i_Pz$U&wfbhN7#&zE zqqB(1b>uxt)C(J}ZAKOuw{;EORkqfIsL~ap(#-h81E3av2jyC_HHw27gmJbp&=W_> z%ozfv7Yue9>@-gshiN>|Yq^_UA-%Y908O4=3%|m64CvC?d>eP1lh~c5B+wVc1`}7@ zMVEjY5L16sD%MVxf-qP>&aE$PBE{5>lPtnM0Y?EO6$XN~^Zg+V0%)%g;cs~M$F3Uo zPyh)7Qq2Z`=3Q$oMKpg(`UKt=)%OBSZW21kXB`NSgtuhn#c?)z8Rxh8ZT{*cDHN`*t)#MOlO5vnA@I|i>lJj@mrAmOy!8b zryf0CGqY8_yciuboTZpWeTZpcc6!c!)X<%yE5od-ml;VbOBagpp1#yw&N2{kAnIOp zrCybEiY*AzA4YqS_)G(~Tq-w#QC}Lk;bNG7;*C0h!22}yUWO2#0qu!D3NMUs%$LgN zn0={unLtZmGAIIu+zD9h&YV-c;0mjm{>8Wnt=RA!hD4#R@CI^lJ_%Q-;JlUo`%x@WFWstJXG@~3a zgh2coBO?o~OAnJwAXh4Jj8xhS@6<=ImLLVeyJQz%~8Lc1gRXkxI+7orNbRuo`Aq|MP^= zMIKoGCEtZ*;1~24UkXGfU_FYjwElSi>OY(>G_semHUbm3yY>XY2?94alOd!ie|=U< zkJ~m7zVENlQ34``4@s7K36iwCXwe`oVxWhn2U?3tJLC*)@5TrWn4{rv zIFFAX$)ZEVqK7+1%X?WwJkMlaifFr!HXx5?;kR zNkzfp*NG_NaqLW^7GsAw`EUCNe|VBnozw-yy&&2mKPVf*3ryP!OK zQ=b#gVsg2Xy9Gk9)cc9qL>%vfQmf94(ocj7vI zNq7N!!QTmWK06q{9@T;pWcQZTgtHtL2f7K>wRU!b6dHh3}3kwj`$YiMqrp;{>V zLS)o5Xg|;Dq7c+IDKf^WYgNXn|8MQ^X+5Zgygp2-HF}_c-j9pv&3BIl=k*M*-?n!g z1Qzj#OO|a48A(=Wyegxnf4_UY%gU)A)Ju0 zqQaGDGAMyrW{Z*;f0}M>^^9M7?~3w~G0_m#K{-xW0k)`X{NYG|qx|^*&4JDbdHTo- z_Sf477&t0=y&P>zvwPrHFU+?4LVY}Q$rDcLlxN|CPUl8>KIL`%;ZL6k=*P+KI^EB% zX>eu(=fX^DCZrFrr@bBeL>`ZJT%B7#=!3OluWqU%Z) zNa3LN>B6|Tf9v4S8Y|-8X$h1P4(YtOY~WmACyd*SZV_~R&As0D1zT=<@Ckzy625g+ zHI1HUw>$TdNhS~iPH{L>z5DVVbMr@)2zHLdPvJlpp0nw7Z>JNg_tq{WRKTSpIb`mZ zuL~Ob_WQ-FujU?*f~zLmqseG3>7Xv|E`E-v>{e#)e^&<+CaEYdZjcaMd_*Smx;sqH zs~V5E>IoyklK^Ubn`b!_*`}(4C)YAA!o}SI(|W1^kN$)~I{5lI>%vuh@mN(^1&=Ut z`0CY-O}+GN%f|LQ*lkA7c#dH^)qZhx05?F$zg5EmaHdHQau*76gC`wP$gIq(XYjxa zO5TQ`ye1S`B7Y@2;}$?;_9wa&@sLU3s+`h6Mg4+L9~oExgdKU-YBnADbL8kZZP8D7 z&%o4~-L8YVg>w&HAi+e5V3-9bXiujEI?qtrhGh`#iTq!3oN=zP z)1>Foh6wyI6TT>ZLAY3NMD4Cw&%VN!5Y7%DYCy^^5NWgkShBFBhDs9kfxU&yF6MCc zug!ulA6|s=^YC=$#7eHzPpQp!!udFN0xBTtDtyscaq~5|WUi z2o*r?c>MM0MmH#G%~?Ay0@NqE(H9u44y$PO@FwE*?e@)I@6&u0$6=l4$!fb_mC34z zv#_qq)wW&zJE+2By@{hJ3O=sWGEjCD-FlPcQSgsepX6X(*8hLm{s2C5($e?NctSrDbJ7Hx@5G#AD`U5js)|b!p z#dQ&uNep_OzWGU!=PM^IfiX@z@!xX!@f8-E@)LWYNM=`>Lp zW_jg>{(V6$IJkd`XIkSMBwB6KDi15Tf(>3lmJ$B>sG1}AypDsj(d!tG)=Gh^~*nmtq(VNzQ=**W#7)0RAKnL|X)dcv^qQQ9vf-e5fK2v^3%*jUd!X zkG;DrL>P5YZTCVL&H9ETD{uyf>rIxG!Nc~$?V~?e(~aoW1q*=TNHPEJn{Q|%`j$42 zx9d2LgYEm%?t3b2hm%SL^QqNE}49_<&+pbgVu zmf(7n-I;%OFM6bnvlK~=toYe6zpRTqxP<8})xpX%38N_YnV!Cq=^x&Mmwq4TKFh0x ztc$Wa*F5x#ILzyOo^g~YFJ0a{#4mjxvn zz>W~*kSS10&SV_`T?P~pA>se%`h+91OmSqs9TcyP?3q!Y2X#`vIhO&_6(RsbAv!LZ zBPjN5BYOxG{pT_$;|#i2zsh#gi32ClNka*tS~)Ks_o^GDLHHl`P+zLbihTu}$ycyH zOS9MJM1PEIM)O5&MS2S!5ZH2E2<1NN5vPB9FUf@s`UOILVC0@w@+@lOR)OSR0@dm> zv#9>UveXo&!iHo?a4_P0bn#VUzjL*-jJ?7HEIL7FBM$<6(w}(!NpKQo9aq6Y^`e7o zZi!NlSnN{>+wXg3aJ3guvr6q{?PiHVM9(aph|isB)X=>wndIXO=o6^i&NA4Ly10M7 z)SMmZ1Kdb+&4mm%Yxp5r)gdi$pWw2gi=JSHvgoIznC1eYS1hmrF|u7Kp-EkaMK;YO zmw;TTrBxWGrKjAWk~ABuTAPC|lTP1ci%1 zJK}`X0YGpfd(G+t6t+GAV0&=&3<`g&8knw!8p_I`(mZV0tZMFostT(j`%@ms!Xlk0 zr{g_}^BEYhYK82EG!3)5x^}}aN69mXf`Lp5o=P~u>fDbaMbHU5&~EQ0&S&~F&0z%x zH}K4o%L%?3YKkd+(x?PQ41{4qJh33i;Dx>#MPZgry?9=2y~f$J_j45%Z0MKt z267|Zel~E;W;h=Ha4^I(VugS34ZEh1o^+;gO`=Zh#Apm+=Mg)@H{V{SW&H$uJ}dmKfN;^fd7pp}uo3BtNW70@{u`K>-KhvMW3%;5}5 z&&M^sOSF+4h|1C;_`Va2`qw(fOzsbxJB49~*dLTTIieq75)_z&2>($?YZ>vQPz3x* zG2|V*&$RVGIcSF8jW3&@4&#et>Dx7w1aY%;@JG>uO$L8Ig5|+Kow?m;oV{sGUL4#h z9bONRn|5IA&v;VP5)P_?G;W?n)PtetI3PYWFnF{bw7M(`7)_CZ$U&ZIh={Y`7o<>K zr-ZANdE^HDr83;M%0GSJmgv|<4chXzokw?1)7KT>Tu=UMit-hB zP65UtrV558dd4PZMhYQm z3g$)%WZL}sDn-zPMnFkBTPH?VCKf(`qJ@o-Gf2hGM$wK}o>2j4VgdM+ zb0Sbuia7!eohB{*ME|*v{6(;-At$OrNoT zL_h#T0LUI_Z1L#^bTbCp|D$36*aIDHEI^>oXMhC=VCHCO>-5LPK^C8CfSu{5rHP%f z^FJm1tNRS|sdX~6umu5}fNoCzpB(%ITt(a`2|0RCgg06v$D zp)KHZ&j92B|1273oBx-Kp^b&L`~R2If49~I{s&r7J8P5wu9I;x{A`Jct=T6nEKDr_ zA+!KVTDSpClr5Z$%>kx{)}Q@<`d6-QYXWq%wy*_$^7?N}0gS9HEdNcXW^Q3@W%~~S zod2N$+M4`#_@7k$3!Yh8R_B|TIQ{=-x&CXY{5b?pYVP)**#1W;3U(&{dH5%csHmMA zz>|@ciwD5S&cXV5_dWsfa-Z&Lmni1okD3WiRO7H$CD&$?My|E>OifBgRI^!>ku zk+3zkGx=w1RGkcMO+F{>KL!7&jh!7GKMDT#@_$zSKhOWpJP_yxG)7oiv@_-pvP{eP z=~RQ0GdM1;+uO|wIT&pJt6r@z->=H9%Qr1-o45SOYjrSF!zAB(i~GWf{o9@_-TrVl zwl#HE3h+FS(3_mLCm(%(gQ|_2em{U&{}=MlQ_U#Pi+TAiC><^qjs2bRZz}r5uP{WD zZS0P47Z0?4mRO8^1$8yKvissgF3@>&UK%F~yrSwx%n8m{xAk`DQTp(N}6Q z?JQJR-QU5Z&km6*_Wo zk1);6!pU3%Ez4d}^P48ztQ#Zz7>tnwszlC>BW}b)kc~5Ws?fjI$cIz$RmdoPKN8q+ z+j9)gCmOU?y-F7Ka6Swvs$E8CIELu5-ritw&aXELG2rwmdz)h%e(49bGbQe zG?WIJ`vvCfEq{Ch?TA)P<+c$Y&T!E^S;6aO4j*IH^wFv%ygLHUq{ZqY=Fk1j6s=pc z3dW5OL4uE^Ks=_gCvd{~q8WMmGm>{nR54&VTY$kG%Zr46AW@ke@;Cc2I$pCiPJk{C z+?Pas2f1dLY2L;joW2e0Z15cms)C`^wA{1Qv}59VrXDP*Iy$Ep1r8;P#V^UZhihs9 z?*7h#86AWJN)b*3zZ|A#Hye~3;fOLL{vKE{wex@d?ZxH$mGZWs!radpqr)GrD>Gc} zjEPWdW>NxwJD&dQtjbqU3u$)!GkE=txHRkOkD2e%?#=x*f&6inbN7-a;`sd0OywFf z20!#>9n_QWV4m-L0@s*$@?o9gvOp(orbzI;wq4^wEAzHTFI)Fu-`{m&ZsQxhGUKYZ zOu3~H{l>P-nZ*kSgzGYnuOiLqf(_nHyM~$VQ!7S)ZPJTx>+ilbUTvJSF{J*;dJ)V8k*@xLF{(#%rFZ4k%JO@U`Ze-OjqOh zu!>Ld^>>%3>MHXwDBJ#*Zzt)U7_Ykl`#qQ{oZmKlD!85PMrMGvbXl-2`ZcRb^dn@NH18mTOhAF1X}vXj5|?GQ_ax?z|7F5RFzBagq_g_ant z5GwE0Hnvr}Nlk*aL@Dr*o0&DyV=?rY*SEw$fgM5v&QY>Ket+0{Hv|-v?9YtHn2d2( z{AMmAK5%`}tw3@r^^e*Kd+5&Z%S&8j5wAXf$eEF)q9(1iQ8fyqaBa%{aKyTKzc4Sr zqucRTv9az$#@zo1>bhJ0+s~J?ZELrR391 z2se1H1k+oEvfSGlbprc(FX7o$S>@<|f!YqLF2YtfhLD30*2i0XdD8aEG>t2DxEGu2 zBXr0UM+gx7_eoJcr~9d|&rm)zn8gAX!_^-L;SNvd=BbNPE>jh?$yYkz%u}iZMCe-R z(^C&8mu1%3ZXRJ?eomOXeg-_Luvr9$q4EfQl*_4l`RZg!>SQkeuj02=-ev87V)-m@ z6|7rm>CMIjY+tl!h{{&U2o)e(^M+I5qBb$e2cb}ZU(X64(q|*T=7bimw~dW%&-8k# ziZ0Td!$)|Lbp#1T9i)(wnpOUx*QB|7sy%=UU-7MAa468{d~^cm<_Y=8cvp_%b4Jr- zwSIq4f(LmO$ec+BvZ38FKP7H|v99tKgHVN&=j(NDn%xqJ^zpp!c&Q5Wd+W;Liwu#;Ot5jci~= z_`V)RHsd?#%KdJ;e+tgs>`6}FXK{lC)2PkOZMjySy38fZF-s+#c$Q_3^~(>eX(*vo zhn+e*2)GQI<>3){zf?IOb6iT105ehZGm-a&phzKAE`|kKac`A7ZG#xs_cM1YQ;gmr zlhFJyGGiLI$baFmQW*??a2^k*)(H>Qt$rABO}Mg$>>B;`?Rm(|wbVOP-98m<;ER(C zG^OooyIE={4A68DM@%z0l)PnkdAv*Fzw5lXdJ-lI);sGAie1ck;$aD{GoXn)YMe6k z)2$6bA7QWpU%{RyT4O8FXGs7bg;C>rm|7Yh3B|c4?U-!TFx3ZG+g?lg!kriRD}}mhPV?RB~eP}hai}WueJ)tdx095 zvninjaMb`aJ}S{|V&3T68-0}%jSO~)t6dkY6c=s^)QGs=jw_=I<<4=HCDLJ$QvxbUT>7)_1;ob=uFVoJR5rnN z#Oq@`f1rq3nzmDaEV9O2VYcK}<$44-|LL7SRMP13nJRPGXp|TmRQ6K5Mow{G_e}A% zrP{?z4+&C`&4q=IMB3BbNNgHu6s>)fyI`?0)etmbS36yQ4%f`k)T2x@0p|5m6~&w{ zrHVm25}e3^ib)`0yq72m*N3iKLPO6;Dx|?aDB~lWgp=w@3RdLuATEjkt1FEo!igg* zA6=5x$BtG!8BW(dGs~1ZE2nRrfcjow&@R?&#^~)kZb8U)!EWl}29-gjb_ih)Yf|ss z4bR)i6nbla$@4(NVLGkpXwF&k5|;&uNnmz)fzXY`K)s`>Emx~z-IY&a5Cs*laD65T z^hYe~?BTAj8qrV? zk}d)!NM57UOBc z)umCPpm|0b4eo^3srU|l-N9U_*;R##Oky<$^ONxHSLwLW+SA0IrQ`KBq3pe`sEr)a zwK2he+$^l~KOc(>RL2-d&VLK~l}s zfQS^s{QgZlaaH5#zcUT8NBD5)jgfz{43078+jrUnkgn>CjkX z$H=X0CI|Ed@%sS?(!>hxRTS*2-6&CGH|S>+mqh8~Mgzp7zxe4v1-XIXtny)oS1o0a z!n_Y=ozc3*GZz%UZVb5@#P;XmUc{m%tgw#iXlP1X7Cro8G?rffnD3E3XtvRTL;B)> zwRtR;4y}7l5fh{{rb0g6$Lp%?NrSl<2pNL!E z*rL%kC-Mp7;I8a6E#g0v?mx8PSoA0`OE#GIF~8a$sgJo^pg7KEoF5#^2_W&)L^q`Q zI!wUF#-ZgGS&1MS`aM_cXsmsoh13dvoKl07>ef2QUX4|@skTb5CxzoUPc0muO90Q( znnYb`9tYvMBz1mozFBn4j9{DC)_cfHVfi^pe^PT;)Rg#4XF`~m;_56z+ogvQ%pucq zVa?zbNh2}|u9R8>65g}JKpxTJb@W{Vm9ewAYB0XbYzd2FDdGt*$#oY}5=Rbk@}=zL^AuxEt@kqu23yp0zG#7?M-#*d zVL^y56W5zmz6ojCOjl6bom`d!4r!+xNJX`+AGBc6#(tD%=DJDCSLFgXZu|qg+mE6! zPQla_arEO(rAJ=CJEsqdCK-K0I`sg$FS#zq%M^xlDK)V|w-C0{)mmjTW4mnWPakXSM*aDx=139DeL@k%0yAjNmp0qVMc-N-e3`-_S% zV-7gnT#(&fgr`SU@}9`1*7O7FfgfHYO;L;GT~+^a9CbP=6RNEY><_|Z1Q4136!K!8 zJ0Zr|Z-Do@}Tv^?rYPSUy%TB-cET z&}R`B99#3(fZ#_zD~)q#@Bxm!s^Yx)%kB8Fxwo!rUh|rYqB%hD#aS&;H*MJSK_l@` z)5E>O69nn!mrsa)pzW`k>SHbjq_ZnegUiPQq|WkGFn||EhqLG0+(io^s_juke+W54 zu^|)rtP&>+^R61BeQ`NVX*4>yyR_a0dOQhs4x_El`1`3<&#ZC5L(aoO4Dyc_DVEN? z*ORntrF`1`Jdoy6w8vQ?Z(@DAM6qXtplS#RS!1ld1-@B-gy|WjoM|3%xrH?H2Ni#N zMTe7xY9div9U%Jxq+uY4Om}tkI8xIMdpiIjx_4RYgVtyZN~+k0b<9tCo=z1J2Z;`W zY$tJFZo+3GAX`i!G7zg!%%lPSiq4C0_3Gh#t%$cWQ>ux61SfRkv3B;K} zrsR9=#aLvE-@18WQ(-Y+95gYhJz|qAbPA!&?dR`_11If0Xx&Y>h1D8{9DOf) zv#WK#QX#1FBXe=$Z1-nd)A60sVMH#dKt3~nOBvT{57Lc+V7sh;XGB{Zrdj+Nm36wi zWQB1aO0>da;0`OYi&S!~VZ1MTeb<|b8>~0f>k+*WL$Jh1b-h;uK3{n(coJ7PI=g#F zCX@VHowH3alJcxo;gqG~t%4Z6zd+sCHMqBA*OBM!H5vVtWHAS8Rvv84#enjNbXw_u zDJV?RLi+Lu^gLiup$X;VJm8z1^vNv9#f?3kmz#WCz;sX*UM?VWj zGzow)iS{gZyG@a#4~ui#IODu|u(_ar+|RT!erOZ#f)~no$n;3Ca2A-Y{I2_!Tc1U^ z1Fi-pMtQxu^uciu09mh+;Sldi(*|!t-bwteCD2@^hSP+PQ1h|~y9>JYeN*P6L<*>+ zp@@H?z|^~iZA1q+0tg|}#LYtO>j~Q4=L{mVJ9<~C*yG2%^@NJy857H!GGv;6hlIs7 zFs9yAo^b0F;pns;I4j1FsUb_Lu&#T#EjKmV+JvVoiIpt#HfcamTO7K$Yn9P7S&hHC zsY_xwHcY93-8Q#h&KKn%Ih5P?YBg^PIhH<>pxxNB#h#2+psT3Nn~y($ZWe9>q!BD& zk&F(Ag`~9ujM1db{9Qo-(>ic}ISl9E1Er9V7Bd{K$NFU%?T|6hEOnK<5%E~!xlOyJ zdG=oeXT3GzYQx0-&I4R{!DS*tpt|Dd@V?}lmRFS(D*2m(&JeY+4|JNvo8Blhhv%b% z?=6_&1MM7wM%!xaq_Hw@FGAw-8&N=MYVQ~Z9+?bk9}^6QGB2B$TT;A#IABRZxuwdn z=3KiIZ2Tb)-DviX->;Kbb4R2amlD2Fab#`VqS*#en`p$S+4z`Bi;pqJ7j|D1|#^bFB=@MCb{SkHpY^7MYA7f;;nDnNTv8 zS^9rFh?o{YGah<2%gu*>-dvp8!Ssdgp><(?7M>y}EQ5YxvoDpe!hTx7$b=ahyJysEYPu9x{-}P+;wU_i`@X;~)p|S*Hgo`!(nd zwI%O(jt-Q!rcp9+(X!KVRt2RiryY%nP|Z||b}>50sj3PlVN>&a>%FE@gu|tPFXkiDn(ZBXYeglQL3tj(3_w-Cf!jfejlz6<) zENnsMNb_2M^4z!Ph76FPx-LO4QQn0=kQH2<$3+tPiKI}iyv34)Ia0JUF%jUe@%y$6 z@~QwicDq!n5S#qSGfj^$u01s_q`#HKb-xFD{jfuaT;!%<1l+O-%Z1*B2fMS zm$4lsb_5<`sD1_-1Jz^akqW|&zo18bt%pZ{EzP{4<^ht&A}Ix3X!AlC%h*K0?b*+^ z%?I$pFD`!1!M%oem!T7Hz7-P13;oI3nct%4jCR7Bb&$6=+<+&OC2YlM%PHNBT%Lhg z{oMae5e#>D%h3vVVSx>7LG71zDNk>)?BrHSRI-ge9(+aDDMxwWVonIIKdNK+5O-gH zqSZX=m6SPMy$I=kEzaRwuhluhTL0TzMZ?m9EpavM+Ta+rQwjH|V~*{g&T-O~cLjqL zxlFjry0Jt1V5SI{LLSH5Zg4)*RdT>3T!%8KPgS-6n%Y(gFmCXR5Fq3qNqzg!=dZG< zGY);G=9_9pnB}$iC~Esbp(NtQf^Ox!T-k z*k>5s#On>LKZQ3_6w}Sv7SnQCG?SovqmCY>;chZ#QEq8nTa&*8`4O9ph#IiF9S)bXwP{H>U+3Em4-7tH1vZj|^}QA=9IG5YX8iGgvwhXL zj*&KWT$L|F6?ANkki1k2!T2~mS)72&+<~IR8YYHg}5{7Y&Es}ggI=2!X61I>* zT;qVEAf0&~mmx$sqZ5Rf4RR2O`ACj=kZ9F9{Lt^(tXKHt1#)0hHK^*biKG0Nt6kG3 z-WPTg7=9EP?&mR*N|$r<+(v;^5bR_zm%N-_Tpra`3K!g;t)3zs^~%0~>Tj492C70o z^5X2Tx%rYRwS}#xd)gaQfbgSky-e)Th(DmDr6o7Ckp?X ze)Sg$x=zy;BNlE}34hESWh^xtYaYmUsgb@(fc~gd(*A-GJl~3}Tlyy2AUwF{7v`TV zwe)f|txx^iN~apEAH1r6=6#Ut+-@)Fz@XB>C(V|LzB$-P;w$C0+Um>KZcihYdAm+x zFud#b%|nYGnWo<{q=I6US@jwnydrm?rX@U#MId~zlS$v)Qkc?v^gMl41D}?YTx~%D zEP`kut18rxh+lyiIr7gp%{)9$SU2|xq?g9;lfVipvhArROENWoZKI8H9C#(wuQ=f6 zS3VVl9&wl{k5;@F-39#xt-5%cbrqcD4?ftG14z*dAys(WJN_PigL(SQpe)dQVg$Uu z#$`~k0o+2>-;X_m+nGQ7=`ZU6eZw#EBV;y>%d@Shs8IGB?I{LA76aY&Ba)~D!VdiA zpoc>8MFs4{j+`rhe)GQcO`L0S`+fpQv4k&y%9v)?keQ*-4C;xASNv5SE#Ljc^BPct zj3B^{NOFwp!ZZSFM!e$v^hGONL)Oxl^KW zHZSb>PsXpxk=0U4gux;S;>aT^=TZc5QLdunO86E8RE;EmP0I_$@;jK3T>H}@am9YM zQZm(pDdT{`sCI!TOeIDmT|DDq+UdUD$q5Lr!x2Ui6_y5aR`k@FFTDIRBoKzB&Zsh-gDQU>Jn?uWec5(eb4O~%u{Rpe5qCV)zW6>&_J?zT zB101hR@t$*hZCsy6v+_jQuOhd*rUCf-CUQurR>7bA5qt#ihQ32#-bCaSJ zO%A{0frdMC5DZYv=XQ{f_~{_Ck*5-WP{L7Zb0V&PjLqGM6ae+O0M}c*U}phX-N^6D z;Yw){anZE%^XPLjLjST&TIY^6CL#8c>l=O}K0T-5O5z|HuMguE?mL8n=OQlhJq81c zDr(-rW8cWWUeu2Fcf^vAT?5Jd$b5As&$bX*dwoEA2}A8fGFm{cAxMFfp_$BFh&355 z6Q^*00#+J(GLQcjCXa0ocbW{2!U~=j!d50XhV^h9Vhra@xqiktE)H6FBod8hM~kfhje#GYb4jju^Z4g2>7o0vOscgWO# zu64=Ghw;`H(^$tZsX&upm4jCKIdy66QtGj^Qp{N<$_A3%Z|)1*0C#AP#irHSmnOj- z$(;&#CgGzn3Qf|P+@GA}rHC1?GI-b0LTTpP3)zPJKj9go5HF{jWW}Pep?|@zr6&mh zSIQW4OGAy60M_-Zvu)394?oegctA&grl1o{h{fVc7u-_8ewxkeO&+1U&L&eg5=#Bn zyNpR@7{a%9Hca=!8K9R(Q^kjcnOcmWPPfDr`q|xAvmn9F<_+iRXxf;H6+7qxD?zRV zeLuF>?M9?#4== zF%3shM(iLcIJ(S_9-WbHCFi7t1$|xUa_T2%@!nih@oopxa>5m-5qSr+$6L#gc z`x(P+Sk@yoeh^@jS!TH|9|7^1dFna_uHA58AtD;O>BrJ-1^*rH#5^~`2a$<5N1}vm z6tT%`cgsZS>Xi5Vn%_qrzqU1hI|=q?5->8(Xdys;Scpa4lR%~j$>a7!rY$(mrLpWN zCCQ+aconjWg{NL|Sc8q_Z^yM!_rT)Yq%>=fw2c*vWOe5e4#RxRTO?@GJ^<_{z}CVf zuYRO%nMS-I{lft300lLW<9nd#Rqx#&t0VF7AXw);r?27Xu_N%?_i%xKSF9>a$Wboa zZRkotAxu^QOqPuodMhx3k1;>~?&4MW;qk?+d1%4hY>DsS>XHV~{NR(@laMc_{E&6N ztBc=ftL;Ua3pkDWOB=w>K?6que@oRif&}~6_3euSjV;u`UbP9G=O1V=7KQdntz()% zjaP;S;a8ah7tf`wsXU~A1AhqtO-DN43YAs@vsHQr%ypPJB^bX-5IQkBxlO9din$eB zA_w$Z6YLZ|)c%$Jt@B!E9rRzz@K`$^A>`COTl>S33-u0+9B*Fq+ZclVWjm*-<2`}i zA1`XOI1dTzu|dKm966>))QoD{%!Nt_&pyvYAGHkjA7{8Q@o*S_{1l7FxZoX)=c}?x zzt)G!L*J0VVQwslSO8J1Y>v46Z@0MQlH{@RwZt(Y%^W(aSqfs1C9$C_PQ#SdM>P~= zIf0wt;tf(33@`=w^T`5mh{Q+(0pBZoH|?a7B*M=^VO( zY-z|yk1}5YybA<>^KbPw@k%$QG@)64vSWi>mvyvun%_|<%2{?R zPy&;L*#iVS2TR?eNdBG>@1$Oo>+crY-g2iG91!|Nic-vN2|fQ0k`4d(y)>PGtPte;R;M=?G+%G&(Z9UxRD8D^>9u6EPD%=hX|3dCwt3}Wbvj3BKvml6N2&0fYL;O}=f%&av;d=L%9O1hG zb10^N*oMk(m2(<3`buX5C8OC8uIP>piCV0b&naGBOZwNO{rza_uQvNw7h@Uo;QS{u z1p5P_%O=ip4@e!32K-O8_K%tq{$udM#_dUnbIQmQt^a00cRs zxum&}>kY9FAH20#jEyz zFZEMh&UNwZ?YXSVc?lY3n~An}<@b`+&wLr$Cq(mAXEOMiSmc^K@lijAJZMxS6EZ|)v? zXng59w7U&oC(F(PW(M$vx()XwY6=6^D#~(fJv~^0yUs z;F+XbbQBHwP|S=ziH+YD8=QoXEk-Z(*np>iLi)^mwW4;u6wj8=%Q;27FWl1oZShkl zpZm{$LuCh|m61gqqa0Ahw(y8Q2As5_{}SUuimWH+#N62~)Jaj;w7uynF38Y-24E$< zy00ZkMapE!5!ka!PgKnAx8bOT{kg6fr&$dp)KcPXIS#wA1(I26G<5NY8#AK`SV{=J9O7nZ?cc!d|3AO2TlwN ztY*KFI}(wQy1@h?#MyEMq1o+!9EvC!)0qyt3@evpjHv%a?oVPJGyG=n5cR8KNE*st z^^#MU2EXVwsqxo42g_X-uALE}mmK=F)9FWiiN9;FBc!Av(T9OVuxeLya_v@Q`u8|$ z5{48^;2O7fkcd?*ypFXwWSwx7A|_mUsX`jB*`D<+hI%pc0S@J(UO)VQ8=ANm7P&!I za2@1V$GEKKC_>%##`~~=X{Y<-TQ|5P#!?3fR!aWoIb39f57WPE@j=Yr(v-mu9F%`l zE|^*7J4&mI!0~JKxp7KHPmJfmkt`gb3R%tCXM@|Jw+_lYj<3;l;I$LAP_bj3r1m%> z7W4FRT27S1s3C>dQU!;9)2cf>X|sg0ak6u6#)e9rNpvVfNh^{}K}QU}qjvR0FU{jfs|1ZeWw==8&fC%9 zcqww^e-I*(?tEDLOTUE01W1y?Y48eO(`CbuXkN?Pzl)+8V zM!wu19ZG{_b`mn5_EZxRr$6^sHYj6*vnul$XqJO2SVo?dOLWXO?-}KMD1siI*AHcy z_=?|qAbNul@mY$0omcWANqbc9WbPd*T~cUh1HDICczs3*Q@4-Acy7H)YRor(H`S)Y zS=M&jCOrKZ>OnP2ah9<(DfuyZ3hcSDABudW*f@mK|hMh0rt<(8Rr z&T4mRY&kL{qSGGR91+6Oye#7zQ7$)l8NY1qzv3s}-}LtUg-y2pUE1E*#yd5J<8M@v zAArpmzkNXRlBCd2!hB=OxHZxU6+D~wmiAOK|Ma#zM!0gId)bw!f#rKY;CA)5fCgwM( z?4~dD-`;&iWQv7hJ8Pv44y?0vm7!Lw(U0u_>St1aU79{k3_mr65$5!3i@}0-Uy?6O z|2Vo1m2sDx4Hsi`X%bNf`lCI5*ergrblve@{k3uh;XeFkJmlK+mG@i5Gwl8T2l!_F zh9QT&H5KKQi2FPSm^SX#jht?6A~TZ2UQyFFg3!DsTMwZR*WfCqd=N)qx!+T;Jvjl0yeCw+Sx>Y-VJA$OlB2#=s zS*yNUjBvI;9j_bDx!W##vJG9hP6dDAsG=Y8TDa_7!W^6zg_<|5Lj4kD{>8$K^Fv;K# zKKVlqEa#P_9aK#iH@1p~ngh$qm2*>Np{eW46_~Tm_UA1nKx}jPR3{2 zByv-hP@j)oC?lTtIo41B|Duue#ZZtVZ1;V!Z6;N!aq;Jq62>k4eNRi>5)?=bGKB?n zEl+G&Px;d0F4gX5VTHD-d@v3{n=9jgo{pjQdjfSo4-@%=a63GMWvaB>)EP|(`7ryv z^put;tdi$-iNa0w5-RFhS&#pK7TQ1v@TcUx*@yL}092g?V(xSa)trq<{!NWndnvlG zrRYY@POftwIED)^Y_;Lv56^&Tl~{J`Ma$#=PS=Z~V06~I)bHX zj2fTnI5vlzl2v#5gsN_O$c!TUTuKJANrnN)WW#;3Iq5*#pXyo=l%Wsqe-D#2yo*n$ zbFAq89BQ7?{+hMBGYF56lRNf*J%b@UO?5Z2BtPZk+xTyI89A9YqS4yKZZBMtveP#VUjjz;$o;C2MrFLt71!z)X;_pQ8 zqd71HBP9wKwlKeqfj#U$wt_`}M`t|Gj+uT_VY&BwX3o|rN=AxJp3Xf|9jgy@+mAIq z=zLmtz_K|dXWX(`B6Y;iK4QU6d%t>@RxpdQc$u$+9JIb`KC#&@4s)arNd0}u5B_f zv}C<3)ruyE#AHnlEqG*_FJp}!hGyX+Y-^kn7obToV@Fyb*dELgwyZB444O>H^J2~g z=Ei8-_6hDj=h1IHh005Ac^~=eI!g=A<)-&?lmiyH7XDm#B%B3*hz%D#Y6@&9J4Q%s zGr;gW#g$1)cQ_0rot5xA_6xd&dc%vCOhO1w&nz0b--9D+u>*oR1{E|T$;TRqOQdW} zs9x)c3sw)7hRbkf;zc#TbuGe`XpqCl5uD6$_kyXbAWdphH^XXb&4vb2oFb_Kn4t$tWCc8N9~6#O+8r*QzQrLHz{&Z3_(&K1oZb# zM4|9wN?Uk;>wUhhKSIiXTj)&%I>dFZ#=ta3vv#i;v<`zHqf}39G}z|h>vQt|{7CXG z*1_k@^^_H=@+beTV72mQMRbkHx`JLs7)d`7^+(e!e~pp9-7(p3`7Ne+8paq>+&Iv^ z%c*>52hk+Fx}6L^_f-(aBK}_Z(qboE*#!G}bZ^psgIfE80Wu}!(*?Deq zqQzK$DtUVP{=#3&}4ee!zQ{RRr_yy6inX==s%Qc4N8KZ|2;*l0s;)TXZdtYF-v_ zSA82~eS%@fOE2dXJM1A>nX<7`M7YKKaT`&8hA%*tKi1!uks$dCy%^;Va_?@-H$DX` zBHcmaR`hD@g9v7HR?j(7DJjHluEbMf&c)py`}amAKEtlp%r2UiF1SSDHR5sK_OHm6 ztatAYrUGOZjYuARRDotJL_M%{n+uaug`nB)Z$aXP*wkvbmNv-3U#8p!AfBqp>oh!n zxth|E__`p?6}64=nw{K>Y)h!2fyNuXW;jbw5PY?=PPq0-%af@=F@~WQ6hbo@I_xry zn7jVjX4*8EJktG&`c{zd(=+c9*^~;H1NyMUKH6v(&*->IKLa1M?dVeW)CEG&R<>Bp z1_E)r#p%RxMqAwuwcHv@8I5;423{C{>H9J@3FehGRb-x<(hKP=G=t%`66DcXQOjBA zlW^5r9X%{b8BIh5B#~nT`zw9^np5@Me|`MUv$b&k(U1#<09!z$zu45LHU@N~FcD=P zwK5-OXr@O>t85@-y48a6EGto6dKIRkS5PjcwNM3NN}_-)x+&6wVjR`fS9YN>lAkS@ ze~(76dcSK_9}+L8VfS~eT~~emsUxGKC)L`Y%<%wFu2ja|{ce1u(%y=%)U4i{(a@JU zt%!(b@@&A5T8xtrS1*r7y<;*0?uQx+rF_yShK|XeWRm483)hW1vA{LZ@S}f<-slF} zimbv9{i*7{j0%plrdj94$i4+DAUa7Pe`_k`a1VBwUZWLF4am(uYmC>Li;PSE)jbc1 z;HfV1)|C7aV)!F~ASqjfKg?U_AfZsx!081mf8`5fLVs1r)LtyfV*jIGYQ1U z$Zolbacgc|66^l-MDF$yHGz#Mgt7$YZ_ob2l3M~d<(td;qF^YGb;vpTYE1t;e=MCD zluZ$#qq33=cU3Y22XT$~mqBQavCC!pt|T#QtXO(DHGzHCWoe}8S2Lr+&P|wK*N+?Z z0tU#94)6UJq11{1Nil6B1UWsp`=C2&UKRX7IjW^_k3Xe?5@K@X{541xg|c?_MgYml*_yje)$+0hnZ?CZD8hd7h@oPY;>s8imTmwFE zMOawE7>cW1mA9I{m=fX{dlU9Cv^;1mnSyjKIw)?-YJ%;}9K81Dk#w?{f4xmI#Q35B zqmD&)@l(eJ54!C`xFnwe79_lZnrW<@DyO7Uw9DgIhJ|G(U{EHYS;id_Mo0KQ`GoUhX{Q886k z+&AEMQ@^As91gCQ&+N31f3zJ-wgb6Qprtv0=U`LjfBel4azLnuJdGQiEA9grPX^{*0)s`XJMVAJ>QP*#Q z75Hspi}9PvPQM`3lSC!A5@7k6-G2*fE;^5x*8aM~OdDLT@Ip%we+2*SiX@-j4mdQH z+ndNzef3o@nA7l~rR~~Bdo!NRu+XYJD6xXLwA_OpqxzMO9d$k-zRc*T~ zUt{CdONIzg^jBqesrB5)%80z#WKNcZI?$N^g*`re_Ve)Aoy+gD~n;pVrmAE zdE}~S^SpG@^>}ggMy7u9D4cm3adB>n5*3>KL5LrEtvq)0-5SVI)3p^h8m5DSZbbc} zxEAFwA=+(cElM=~6opA>#UY*X;pwT3!9xJk(c18v;qh4`nZ&hydO?o0aw>n+ve+$~gvdcWpFF`QTX>{BivqLY>i)HGYkFeG zVStYK`CToFbsooY%~anHyQ_ubp#U9!V4nzXgsg@mD^<&Agx@IK$mNtg3w-UZSGx>7 z#RE~3mdZ?vI!7{;PTm7o81bA{{&XRNk1Tl4Vg51Ef40T1JLCy^Ydpe__>Bx04%sn^QSF$)lfXE!*C<)ABa` zcFGs&P;|YSa>t~lNda2YDEL`nz9o=55BV^_Ut9u9VSmi+ADUZO15!b|nNL>Yal4F{=6@XHo5i`>;Mop`65dL16@erhnXajOMKvkp8A)`2+0E z3URyY7Io1mC)T>5Qci!eNM;h^D|0zf8R*aGf^ciiL~;HCqtZWG9|Rw!Ze442H`T- zM~u(LyZ>yffX_uzK{tZs+)@(HW}*C_jrYEPz|j4k`%DUs6XC0XIDf^ z($v-#dKr@UxO#mzMht;4DUkO&xOQspc^;w~Gx6J2dhlLj=YX}@o_ z*pvXX+~J(&t^z~T$JIaw1LCsm76UYqa5b#UR+cXkMSGNhR1tC1CJl5jNy(BWulY`5a=xo{1XleIwHCP^ksPk!cFQf2N)0CxEMm z@INf6t?7JxmTHGgLLfGb`WTF7mG@^(d-ITN;oMu07gf@{EL}w)N+2r-y@ki?r{|M( zldC@1ouC}(Rjk+P5^w$=L_f4jm$5bi6StYU3;Q$zF*TR*KMEBEGB7YO zGm}ARCx5KCV{~R+wC@wU-G92z zk3Gg-6W7Ew*BpCn3KC^C1`$&SV>3wydlv>4MrK}sqLrPotFx+uouUJeJcFv4g)88% zoCA)6LJVkT0e>t!JUnm|05JzgPoR~Br3-*sLsg50 zj*k96CI6TJj6MHD^Viea%EBH%`S-=m%+|rt&dlEBFU0?~qneo+z{S!GU~Xk=1`tzH z){#+^0#HjSY5=6n?9G5iwg6>UV_Pc|fV`E7nZ2_a4Zz$12(bP40bt@_Z)){VY0iv) zv42FI0Y(64M>7+vziwt8CT5QRsOSNXWi&W$J2<;In*gmGT>yWhDvL}0J5Lu&BbR?-J6ru#102l% zTADhTxc*bpzjS|L{%T!}tn8fuE@mDs|9`|XHUpSiIXl`KdH#+47t9f8^{+HsovrLG z{xbu50MN|B2xw|+=Is0z<}da?-TBWt0sl+&MvjiQp8xW8_?OlH%)!dV+053Q5sroR zZ%h-Hzp*W>?BSUHnH3p(a|Zwm^S|Y$u8#kqb29_}t3lNN%nZ%nB#cZQ>}@>(rhjJU za7>C0E`LJ;sQ>R+X8i9X`M-hU{}zJ(Tj>3NBlo{@^uJu<|JVEcU!f&kZEY2e?EVhG zzjqAa?~*aH2mIYL0C~Vai^kRn`2X`Uva_=F{6Bg9S8FY^f2aF@0F!Ys`r8%}dyBu+ zFf%g$TWIAhY2{&Ns%+(AVhJ!evVZ;Cvwz7o>`l#pwpR9Lf4TivTLBC#%*_8qr*3Iw zVq^ag2^{}cnc18E*9!j9^{@Py6l6s;)OG0oHw*S(hRS~j!A0HE@o#SbqZ$PV)Bkz+ z2S!xX!2{sUz{1H5U|{8D`FsEVCd9+a?)$$9`7a=r|2!)gxd5#^0N?)B&40}Duj>ED z^Pi{h{{=?E-o(N5pV3isF|s%PJ8l0{@Q>QW6$t!G^1l|q->U!P{I9t;GxIPrfm>g3 zFyRZaPS474sl(12nG*jt(8mHk66*M~QN6e@pvIxsKRsfXr_%7fHk7exhWE4GbNS5i z<4~6NXsi#*mZ~?^?5cpkmw$|=zYukcvXhJMD2Pe_Ct}9AR*d)clKc*YE+@0*(cYAb zs($G^6yZ!K8xZFDnI?eDtuO$C{K*l?&m^rO9E!u|YG{0PWVrVh zvi}gDE;k;Qg3k!sFXfCR*~QZk_|Rzb3Hj>AV$Mdo~s^Vda#AaA-&)*4To z75wj}=oP7SvSN+R+{eRd~bk9GKmW*qMo0{mq zMW5*HR^n%Oh^A)sMse;Z^ATnNp03%k_9@+jGzwBD5W_s8Y>*b?hU?H|$3Y(rm@JrW zPi1SgVH*H^ox0ID-^?5S6hukbfyEoI?fJ{UPj5nty@6@^gC$qGZ|1iDsz zxn(UUqCB~I1Uq7|JQgamiGU~rT6i9`QN)q&MSm`fwfi4Qui_&xVjK2+}>zwJo;clh0YdEQ!>?vi3VjTq8mW?#C#tR6Qb zRt1CoAb%f^!>K6?`KGr2Htgb>#p(67%s}v#_y=2^T=CiTWnkm+;&We)rmiVk74v&s zU{3@|IXI58Ruz(3kUk8rq%A{&m4Hhm=zQUW$jt}A2_j$#%atfp5cyAA=>W@T*xf93$`VaJmy9P-1+2{Qzje)GgT)2QX5@_fOQk zB{My~8~DQ*DR{)NW0Kkl4CLRvEWvhK@xKmpoGfhJ&-dpNu=XmQR!0KI`ZV>vvVWXc zGXO;U+jqBiW~M;n7sH?}J@Hqbq{VJRlmYBB%~n2c(HJ-1^;S&g;T!z@1tWqNQ+ew9 zN2WE5Llcfz$8GPCj?ZZ>Z)p<&Q0O|{1u5DUGg`bw1fJ>{tMhH%>iXgLU!|$9S^R<~ zKZkyeLmxCxdU2sE>*+4@$F4cSO@B9fSSRK+YEDt6Op>|^m)vpG;1`YDtNY(cLYWb1 zhkr(7uO$j>=kY;+X78?&_dluPQgkb=VJbN&m?FQ(!o!34Neg9mqedjt?>vOv7P5c* zsXo`B^YcTg(DGYc)&Ye(lZJ+UB{o$$YMo&B)XDU7jGg8y;57rQKg%?fJ~2weuQp8&<7}`z&oD}r9|u=@~Bu{GgAG{LdIZ$ zm)K&>^kVAE+A`tLK{B2c<1pQdps@4rBLdZyJk4p`_K?~Os9h2(_DF_hwyB}GZHDpIx3TY+M!h^ePz6e2?~yMG}_JvTF$n}%VDNFdrqO{+4^7`?R@tg zvWHDQ(hf>*q^To=v|G-TyKen4bSRXcvLf)1Wl!;kq&=hAdRGS*i`~L~Kr43|ySdCC z6Y{~*rhl+v5kjvCW6Es$H2TM=1E9P|RN4Y@~@{s((6XQf&A!T*h#7_L;dBMV?^b+qxN$ z*0)~w!jgFgSL;=?RHm1dmMn2He^lPR*sS2f3Wx9MHN(wiSJ&{QY0BDGj!^vWA=(Z_ zW+>!UcvN^p6Q~u$AbQW<_VNe0PM))O8>t@02OqN<${d_P57xM&o`Kx$DK#mPdAK?6 z7=PY~6-ff6hh|p^oy@jtG%7x+8+AZwN=`yp7rj)!*ay9bI0#zPco3^;8$&6wr=?=H zO$m`Y#$qYr^)j~i>qk!}dC!vA>4p&DSqtx};>ERC4WXrkHsvI*^pNK2X_-uU5WTyy z;I}-mykk(yV4@PnzJVbrEUGsH2Jr4bK!2O5J=rKMy7f*})cTL4id)n>_W-D0>b3USaIvorw(=A_V=i8c%vz7-bHSyN2l6q6 zDL@ksTVjvd8+PwvDrR+QvmVdZAtS$D5TTe0B01}4&B#{=yD1hQe=FA=38Lx}Zi?W7 z`4JU_Qsgy#jgdY3#munnB9D~^0+60d$S!7+ikDQ<_?B$i-9<$vhgAW)2s zJF&s8BIbqeFl>G!ZTTz^#gqku=uT&UpvP9Y=k3ifuc4C6@CSCr91DIP2ronQAfNS; zH+O~Sx&{#9L}>PqQj{^)B>epGrif@hfgo#I0;Nch&D0apyrLCD`{;1Z4kwd{2gh!S z{_(y1cQVjEf4ler0CP?KXMg1^FHMZ<(E$AT~vMuDC`f?`G1Ablml7U{DYh1 zeRjaZs?6ZBhG^Qb5uYF~0wp{h_5v!q2u4B@eFxcsPXkLQzPXJwSm)Qqm1 z|Bv<&k1O0=17cltwSQriQ@{@=9d9#eB2URR0eC3xu;I?v zV(8OR#hF#Bi*gr%itaBJo{C!C7*8H0_vGw>GA%6&=Ma7@IuZ%D=L*QXI(%~85R(Wk`0+(s9Wv+FAWWLweVY|u0LKHNz zNBy%4R-^y)0N)KIZ#^N>B2aRjg*56U45U_@k&oU>0Xylpo^2aE$$eBJ`8k zTJrH?yZu})3)8q%e0IA{U@1@*MhiM7lW{TUW!}fEEq{@-bP6Fw5kd0wjt69PCb7n8 zRg~)tmDxRBY04{SK7p=_>AZt`lPYItI_@QJjJzK{rZ7@fRE7$X z`}N06ZPe4u4SQ?4@mWO$NH^G{xmSNaKWM~U-r@XvU)>^yd;~m=Si89~IazE2sa8=q zA7@Wylz+x9s@cQI;@CL{$)#3Bu&h!h+UnPzPLm z=AhhjgH#Fu0y!S&z0`9^ZwN-pszY8w6*{yhhNk;yM!uWJd6Zz$cHSHW^O9|SW6R)= z+BLNuLim}}e6^L&i8Yq>A_6EVoZtf_Q}cgHn7(+A9>;h2y4YDgd=}9ZAeM!5)V-CViJ?ff$8gE zh!8}uOWR8e$~OsHsCvYgCvmO^{4D)_TYJ$Rem8;{fy`?&fJt7t3T6Y!Wvdmh80`f_G9C}+ps!*lbJlLwCwmA}o? zs!sB|X}gV@;j>G5Xet`8=A%`yP#|=yRy%6a_J64b(L+EpLHE0Ra)LZUyFP6h2ZploE@{2a zD^RLdL^}c1i#{{MLOQXY-3{>?GeEAoZK*~?76T>1{wr2Bq)s#?Y{MMooydpjQ3w|b z$wq9aZml9rJ{r3-diQ(X{of&wsA^ zkH>ZVZxU!!U zX`tM%!8Ccz@WShQPzPb_sQ@6&@qeoU^(O;S8ya{p0Yij>4^^FAkz~ec>SJ}?&aV

Ë7ü6îúÓÇôE}@ßùÐYJ8ó°oõ$Ì^ÁPzÊÚ)óLªóÍ+ +Õu¥fM¼Yoþ¦Ôüm©úC‰z¸Ô|‚7›åMçŸ/>7\âek%z%Ø(Ʀ°MLp „ G ]"m1!¡¼à´%¥€& ÅJæü1îƒO¼uC‡#êíQl‹6¸j…5RÌpS˜€Ø¾°íß¾f¶ìüöÌYŒ#°û|ªàóîÿ 2Lú h;ó6#ï»BPÕ<¥kùté!»C§®ÑÑótð¤æ}òfï᮸õöˆµ–ÀÕF¯•×å2‡¥¢}‹y–söL=PŽß3¾+ùp }WÐ}©h=ЦxÔÇ¢: å¨ðDÓO1¢ëÕ¨3C­ ª•pIU \Šçz(£˜ÓÆQy¨‡»2dÈqY3J¤¨pÄÍ‘`”½¸`… dÛ"w?WäÈU¸rèôÆ;_Œ`1k‘Bú`N»5ìŒ>ÍÒ‡RZ*¥ R:üOíûkQHxÍ~_˜1Ű-zÐá„fgm8¬rGTïGƒ^íC» º÷¢ÏL1¢Â„&˜4Ä”†UbÐïÌУF§%ZmÐh‹”9£È O¼pß™þÜÕ î|—.IŽ’$ÆHRˆô<1¸FŒîÕ#bV@,_›:b×BßríMòøâ5’æ=yÑwîšßrfÀÆý@ú,˜ÖÓN:âCW<Õ|ö’øº6’±p #$ý ßäš´ä›×X–[Uó{ø½Í¼ÕkÞº‹·î+µ(µå­&y‹é禳/”‹Ïå«¥úk¥’µR­¤v‡ [àÞß +AB°è G@€F†`%³~÷ úœðFHR`R+äX⊰ãØÇ…Øìÿô¼ðu±±Ò¿0¶ìüÂ@YqŒ#° lé6¿üþc·.ýóçÿXÂßžªþÛ{Ø ;Ÿ›Žw˜*(}D7rèÊ:›N_¥ãçèp +ý¤é?´Ù»Ñ¾Þ¸Öà³Zå¾òÜi©À~ñ±õÂ}õL–ÉÄm£‘›² q:z΢ó$Ú’Ð| Ѩ A¥ÊÝQåˆ:!k¼/MÑ`Œ:#ÔÂõˆH&W%z(¢qÈãð@H¥-Åu.ÊqÚÇTH01C¢'-pq/nXãÞ>äÙ£Dø íŒWnèöÀ 7¦}±ê¯M³yP¬9&¦ç$ô¦Í•Ðjî« þµ.ôU*`…~7¦0æ…÷¾è@[^ Ú徨ñ‚ T¶ +ÞÎèqÀ{[ YcÜSæ˜6Ó{0eŠiLš`Ä ÔèÝ‹76h³C£jœñ …ž\®wÏ»(¾"9.9%IŠÑK"ÒT"¿@”Ä$‹˜åË"bSAìˆãkâÚïÙŸä=˜â3vÆoú²ÿÂÀ•¬ ÍÇ!´4„6Ò^?:íKiÈwƒ˜5ô;' 9ŠålLäê ä){òÍÚžím,¶©æmËyÛÞî%o×ÂÛ·óû»ùýýüþÞ~”·®ž~n2Ï-— +Zt½D,xiCF éÄAït[à ak˜,Z‚ -!(š ¬øcÎ nrB¿ºö¢QR3<0Eºðý‚ð-ƒyÌè;WŸÚ|¶òüTbì~F€ø ü"})Áç•ól™ôÐvà#l:ÞyFɧ4“®Ý¤K7èÜ:u–Žž ƒ‰šw7ßFmt­·{¯µ¸®Ö;¬Tì[.µ\zf¶øÈxö|2Kì–ÞÐ5Éû‹\ït¥ ýZ 1 +õB€ _”»¡BøTkza›Œ1ŒP«€w’¨LÞÅú(”⩈ƒe)[Œ[R\‘ᜩ +$+¯1E’N©qÉ·öâ5òmñ\H@æˆ×ÎèsŨ;æ=±éMGpô¸„^æhG…(£ßàç×¢Sª¿ðTÅ|&Ã0‰¾tÄâU,êbQ…ÊÔ…¢)­ÚXµ½žª&í1kƒY+ÌîŬfÕ˜3ÃŒÆ-0´ï­Ñk‹7öhs@£3WãÆ½ðä +|¸Çþ\vøfˆ$=\r&Rz"Fš§”ÈOå%bz“˜ß'–yĦ”ØW§&âÚA<߯{¿Oö>å7~!`æzÐâàÕœPÍÓ0ZL_Ò¡ºä¿“@²¶ìrk0“«?’oÜÿÌ¢³pß«û:Þ±‚wªäêxçFÞ¹•wéà]{x×~Þi·á­&xó^µPj´\b ŽÞ(kòtIä€fƒôýœ8LHô8h‚.@P4XñÁœ&1l‡wVè6C£ JŒµ))Ï)@ä8«÷Mf‡]nÕï¯{lñùýÙŒµ˜`v$ì|êùÏè‚>Ú|„ÍÅ;Ð(”Þ¦šKtí"]ŽŽD´4G¢!5>¨pCÙ~T +ÑÌQo¬M“T¯ÿâ +=m|aSX‡g@îV®m\ÒÇNÈqDX±+q@…ä=8m†t5n«µùµ ¬Qa‹&{¼qÀáõ –Ý ñ„ xNû¡@È,¼]?¿Ö…¶« ¬ÞoB`)Óñ=Œ÷‰è>¢õ…kJFM"Ê£ú ê…¿‚´G ;ýôŘ'¦\1·ó¶X°Á‚5öbÁs‚›F÷aÐýûÑãˆNg´¸â¥;WåÉñ>Ü3ñ£ IVˆ$#Lz)Rš­`þZÐòàµG¡š‚`ZD;‚èH]wüÞ­ÀÚÿÝÈåVŸÈæòMF‹öö—:uòn-¼GïYÍ{—ñ¾Õ¼_=ï×Äû·ñ>¼GïÒÇïÿÀïæ-Çy³IÞx¶X±P _Ì—-çê­>¯ßýÿûÂ~ $LAØðÁ’;f1&ˆ«jô ÁØå¨’á¡°éX†x Žr;fŽønì·KÊŸ»Ä¬Œ#°}þBÛùÝ¥­·¡ÞüÅ¥?íß§Þÿ§…°“ÛK€MÄÛËÿïj?G7Óåt6†NDС úÎKÓã¼Ùe»ñÚr­Ù|µÎd¥R¹ÄËŸÉr¤swô¦3$ãéÜð9|HE2º¡3m¡höGƒ§6’O¹žïE¹)* ˆ®ÒC m©@Ou*Ð}àŽ W€ób¤ê!YñrÄÊ­@¢©J\Tᦠ+U(0E¹àç¯F—%¬0µKöXõÀf èÁ½¼ÿµ.ôwf`×w2õKX¸Šé«»Œtô¦£ó +Z.£þ"ªÎ¡â jO£1­ÇÐq=ñè'ŒÁh8¦„dF¾˜÷‚;O6G¬ìÇ’æí1ã€IGíö±!g¼wRq\‹§¸ÞGRî')Ð{,½*½!M–žÕ?Ad‰Dq”¨ÒÈžt¢Î$V‰mÙ_Nœˆ[;ñì#^ƒ‡}ÆŽùN¥ùϦ.f­<ÙxDŸhÓ‡ Ñ%ï ™µmW(å6ŸH—òM§‹¬†JzxÏvÞ»™÷ôŸ*> œªæCêù`äÝÁ»wóN}¼ý{Þzˆ·ãM'KŒ§ Œfó çs s¤ËÙ2,ÚÈ€æ"4§¡9M4qЄƒúaÍ]+´N ʪ>¨ðVŽ!™ÂW „1hW ¬Oë [~/v7#À0 °%ïüáôO'¶®þú÷?ºsëü'i;Ÿtó_×Ë®n6oùO¨w#˜.ûÑY/:áF‡œiŸ¦Óf³Õrã¥ùZÉj™r¥D¾ôTá±x>³˜¼„Ñ3:÷GÐ{]Q袣ø É uÚm\%V(2G‘ ŠPl¯xQ‰Îè§a?«@€ÓŽI ÑG¤L«%)pZ+ +d)§@©µ*¼Þƒ>µv?½‹NX÷ÝÙÐÑÿZbÎB䳃ÏlÞÂRf³1uK<šÉ}¸·wБ‰æ›¨Ë@ÅUT¤£î"Ï¡õ4:RÐ}ý‰<„Ñ8LE`.óXðÅ¢—ÖoaÅË.˜wÅŒ°“Å£òÄ{/ôzq]ž\»§¸É[Rã+yî¯W¤÷(Tz7Bš%½+=MdG‰aQž$¦ˆúÙ{ŸØäûçÄQØÖJ¨Ž©âCËùðj>¬žjæýZµ2‘kïØËÛ¾ã­KÍG‹MÆ Œ&òåÓe³9Ò­ô/+7°vë§°~ëñXÁzÖw WÌÚaÂC¦è5Âkª¤x$l:ãÛ¶ûÆÕ'öˆ-A?»`ߨy~sê·o>^Úzîãå¿ó·-bïv6 ï cüESÖ÷ÒåýtÖ–ŽYÑ÷–´[­iÛ³Ù¨Ú¨U¬U¬ðzË…Üâ#ÌßÅì5ÌœÓî‘IÆ€àüƒž0¼ñÇk´8¡qj-Qf†BöÁ€7ú½¸·žÜO®ÕKÒà#©ð—IòB%÷Ã%™Q’+±’³DšBä‰ÄèQ!fW‰åbý˜Øév‡5·Nâþžx'xð™:ç7w5`ñNàêcÿÍb_ZçK{è4K"¿óÜ.ja)4ņ«Å–s¼ã(ïöŽ÷îâZùÐ&>¼ž¬â£tZPp=ïßÈû¼â=Úy—7ÚTbûúK,?™ >S çŽåÊ&s¤3÷$dä_æ3°xË©XNÂÊA¬Dj³Æ/{bN·CÚMaír¼”hS +ûŽ“&í¢õy]aKÐÏãÆžbFàëøH…ç#oûzíd%ÿóØ,üÏ3üv%,™Ñi:lLûŒh‡!m–m6H׫¸5+ùXºÅ›˜¿ŒÙ4LÃxFâ0¡ Ûã…N¼¶Ã«½Ú¬ñu +TJQÊ¡ð%¢_‚Ý®—€sÀ)à8p8À!R‚` ¢%HÔCª—¥¸#¤˜— \Š—2¼V`@†c&}»ÀjÒ¨¯—b© %’¹'ú“äùïžèwçJÚr¹¦Ç¨}ˆò¨¡Ûh¼Ö«è¸„îsè?Œ&a2³q˜ÂBC±Œå,ûcÁO»elÚ>:-ȼ¸>O®Û“ëðäš|¸ñó qAˆäQ¸än”äz¬ä"Ñ;E„HAŠD¢J%f‰ÅMbuŸØ>Õ…Œ®#.mÄ­—¸ôMöž<í3sÙoá¶ÿÊ#ß"oZíEßøÒiWfVFàÛò¿—É6ù=˼Ý4ï:Ì{õóþoø6>²‰©çcªøˆ2­wP`ï+„zÅ» +1¥;xûîbëÞB‹þ§{>ä)‡ËGJÇî‰Éˆhò:¦/`FˆÖusóáX²Æ»kcDÚà­9Ú•ÚùBˆGwC +àÆT ogì[[‚î\Û°–1ŒÀLàcDž¹çFøtMÁß‘þØÄw´ß€vêÓWZËiʰQˆõÇXÍÂòu,^À|*f’0uã‘Æ€/úÝÐí€Nk´™ixêä(ÓGr9x‘±%ÈÒ… @: èÄq@‡@AbÄJ,ÆN{³°‰¬X‚j)Þ°Åü ÄÎ|^¾ÚÀ-ÕŠ^èÏÈ'ž (ú º +¤m’ÆÔDÝ=4ÞAëMt\Cw:ú/` #)˜HÂl<æ b°…¥p,‡`9 ˜ ÀŒ?&ý0æ‹ zã·µA¬Õ›«÷ã*ÅÅÁ’'áâûQâ[±ât"8ÉNE1>NLÏõ5by—Øä»â ä‘o&.]ÄõqIôœHõš¾ì3Ÿé³üÐk½Ð“V¸Ñ7tÆî›`c•0?¨€¦Úx£|ïï0É{ ñ¾}|pÑÆÇê´ Èjí±  +Þ¯š÷jàÝ›xç–RûöbëŽB‹î§{zóŒû¾Ï‘ Aâák9±Œ'b"“aÚ?ŸQw|p@5^›á¥RíÜqðfÇÏFøÁÿe«Ð|°î3ŒÀŽ%ð·:ÏßÞ°c»Æ¶E€MÁßñH¨mâh h h.6³±~ «éX>‡Å˜OÀl ¦B´c‡…¥¸#úö¡Ë­{P¯B¹E†È5À=)Šnèö‚ Ž@Âú\€/ ƒ@4 .C|8D‡TÝ‚pTÈ–ñßñÐÙM¯7X¯7Zm2X®3\¨PÌòÊñRÕ`©²¯ÔðM©Ak©´±T\[ŠòBTæ£î1 %K;¨;}Wðá†OcâfŽ`> °‡¥h,G`9 ¡˜ Át0&ƒ0ˆ‘ ùáƒ/×ïÍõzrÞ\³/WÀ½á +¹GQÜÝX.ƒNAú§ˆ<‰(“ˆê41»L,~m_N^§vâÒO\‡ÜÇOzN_ôš»éµôÀcí™-w¡o\è´Å®0 ëÄwE NV›­•Û,ñN“¼×ØÏ‡uñQm|Ä+>¬©Ö +Aþå¼·V¾Žwi(ÝßTlÓZhñú™iGž²3WÞýPÚsŸë» Ò+z/$)HÁ@b1ŠA_ô¹áÍ~´X¡Þer<åpðgÓÇw5F¾jcÙ*ô«âe…3Œ#ðÏøk©ç¯¯þ3õ²g¿ 6Î_·–Ç ÷@3A/k3¶lÃÚa¬Äb!3˜ôƨ íÑkƒK4›ic;—)P$Cž÷"6‚ +Ï1tˆÕI@Aº/m] @wRép™-à¿®-YéG OOÓ°g½MµÚ´g©V½Pn1Ã[Žñ¼Yoò†W¶ò†M¼A-/­(W¡ö)sÑ’ƒölte¢7Ò!dÖ?¥ÝD9w ‡±xKqXŽÆR¤v§Ø\f´RªV +@Öÿa_nÀ›{çɽõâ^ûr/¸Ê®4ùQx‹[„K“¦Å‹S$Ä©NÆ™]ˆU߈µº'„ŒÞ÷œØÕû6âÐKœ†¹Œp›:ï>—á¶tÏuí©3}áH;öÓ9ÕÇužÝÅ|9å / 4U‚d»È»Nò¾Ã|¨N +içƒZµá£ýêxŸ*Þ«œ÷¨à]«KêŠö5X6=Ýó*OÙškðú‘^Çtf‚¼uŸEÏq¼=Œ·1x‚n¼vA£-ªÕÚ´¹Â¶b@˜Y¾\ëYI»[ˆî+²>0ŒÀ.%ðjÏ_\Ú¥0v[·Øü»Û,š z4XÒµ¸aÎÓÖUãÝt£Õ/õQ%A)ðÈ̈H +-lÓîÓ­Ò}'À0œÙ¢}· ‘]ÑŸ.Õf›Õz«ÕJã¾¥ûù2‡iÞqŒ·à­ûxË7¼yoÚÄ«êx£ŠyE‘~M¤á)^åâuÞd£÷6Þ_ÇÐeŒŸÅt*æŽa> X:„e‚eÝ61A šÓúÍ!ç?`Ò_p®ã„Àу^Â1tù¢%uÁx†‚H<ŒÁXñµé¹yJŒQBŒêxŒÙÙók±ê¬8Ë'Ī”ØÔ}-͇Øp=ê4yÖyîšÓR¶ÃZž=}nG;­èºlW؆uâ{#ÐÚ(§‚T¶‘wŸæýGø€÷|@ïßÁû¶ò^M¼§°/¬–w­*u,/²//°©zjQ“oZÿÄèåcƒ¦G’W÷´û.I—¨í^'£ýÚÃÑîf7Ôڣ̅*saxôµZÐT&ü1*l´ôÆ 'Þú Í A¨AQ8r£-Ñæ‘’§F)“¢•É1ª´XÓ+q{î³ÇD]L,«ˆU3±é"ûˆÝhòþÉ3ösWí–²lמØPÞŠ¾3þìVFàËhÔiAÕf/–y¯YÞsŒ÷äÝûy÷Þ­ƒwmå›xÇ—%vu…‚ +dYžgVž«ªxdX•£_󀫿ú+ ¯E/¡1Qh Dƒ'*Ql'¦¸#ÇŽI@_Öf»§4¶Ý=¶d=aÝKà²ÏÏìÞÞïž±ÉwõӻĆÁ§3cOl+AkÚãºÑá¹Öâ³Üà¿X<_2ÍŒñ¾¼gïÚÅ;½æí›ù}õ%VUEåfÕÏLêóšòä­O¤Å=Ð70šŽÉs˜=…ùX8ŠÅ#X:Œea˜>:áÿž,þo¢ù+šù7¢©-šøŸDcÿJ4ü߈ÿEÔ'µ‹D"Q¥HT"=‰î‰D7E¢K"Ñi‘(Y$:"‰.‹D™"ÑC‘¨P$ª ê&bÙE¬ˆÍh²ídšÍÜU«¥,Ëõ< ZeBGõ¶•)«ü‡'PÚ`@kÌ5Ï÷¯òŽó¼ãï0Êïàíûxû.Þ®£Ô¶µÈº©À¢ñ©YÝUÍ#EuŽAÅ}½ò,”_GÅy&QU"ªbQ‚*oðNÈ·AÎÜ7Ħýðãë/°EÈ_Àa—F€Ø9~§üüîíÎi'kÉÇ`“ïÇPÚÝ÷°1°»í» {·fH?xjz6:‚ÖZC—#«cæË¢§ùð1>dèç}ºyÏvÞõïÐÀÛTó–e%fÕŪúB£¦ƒÖgÒŽ|®û1úîáC&F®aâfÏhí-œÀb2–±$ÄŽ>¨M%ž%š‰ÔF +š Æ´à$dóÁˆ†<Ðï‰No4ù¡:|òÃñ œ»!I”¦EÊŽEÉ£©ÑÊK±F·ˆ2‡¨ +ˆi…HÔ$½‰D¢Ñÿ^øËûaŽ]8 +wo—ꥴn}a¾^j¹Tºw†ß;Îïæ-x‹þuwyg¾Y{®IË#eÓyã=iCWuQs¤ZT‹êT{£Úe6(܃|9sÚ½£åËõŒ-E¾KV#À0_‘À¯ÅŸ_¿þŠU²¢¿6ó~®ßS©l |OÖbm,ZÑ¡š·‘1k­d¹ñÐbuÂ|ÙÁ>nœâÃßñÁ=|@ïÓ»5ð5¼M9¯®äUµ¥Š—%-Ezí…\Wzsð! Ã71~3ç1—†ù“˜?Ž…$í±ùC˜#ˆÈÍFbög!HÈ…=îO ¹ã½;Þxá•jüñ<ÏB*¾ªw%Lz6\v<\~8J$¿gp“Èsˆ¢€(+ˆª‰˜¼!¦Äl4ÙtêŒÉüuÕÊ=åfž‚¶ïjw ßI^lïp¯$´ZNË 5¥Š•RåB©ñ ÿÿ±wçqRW~ïëŸÌ–ÉÌ$™ÉÌäÞd²Ý$“¹ÉÜ™¬7¹ä]]]Ý4MË. ›,² ŠŠ€úuCAd\@EEEQµDVÙ7YeßwèíÜOúu§Z¤éê®oÕËì.ª¿u¾Ïóý>ºêýøœÏ¹ãä×w]TrpA³}ó‹w\´cn“mïn}'¶åmmœ® /ê‡Q +‘ iCmì®5í´¢DS”ás1Ãã­HÆLAn"PÿTq“àŸ3O€_»™7'0".ƒF@ç%oGà\/wð‰ÊÝO•oYºqÔåµc.®saɨ³‰‘'ON<¾?1üÇÄЭ‰!×%ú¬Jt[šè¸4Ñve¢ùšDÑúDþ¦¯µ}~üDû?СÙ:6C'§é̤ä±scu~´Î?›ÜPþÜzäƒAG-ê­½´³6ôÓªZ$oE²zz99È6TDÞyå×nxç®GÎeP˜*ýÅîìwèÙÊݣ˷-Ýøâ•µ“.}7ñÂÒñçcN&FI{ãÁ¼)C£ã†EG>û¸¦Ñ7ƒØÜ ¶ ˆ/ +×MvE‡ž,<>¶ðÌÔ‚KoÇË?ÈsÖ›…ÿÈL¹r å¨òc•¿§ÒYº2S_×9»e^‰Ú-sêY®S÷éLOo/~¡dæ4fþ¨¸r2Ž! PSÀR ‚ š áúš_»áš¯4–Ë M°6-ÜÙ'Ý¡1•{Æ•oŸXºiò•uÓ.­š|aÙKç¾™p*ñ±Ä胉g÷&žÚ™xlkâá ‰Ak}W$z,It^ž¸sU¢ÅÚDцDl˱ŸÆvÏÍÛ÷nÞÁ7£G_ž˜=eAÐx£sÏéÜ3:û¤ù(rÆ‚ [ö€ÎܧSýu¼¯ŽöÖáž:Ø]?öÔæÞ~k¤þZ4PóéÝû5cˆ¦<¤qCõì0½0BSFDß›;"ÿ‹ñålx¬`÷cñÃOÅNŒÏ;7-zõm¹9¤@i¹R8hZ&Ê“¥Ê1*{Fe}¯½zù…’öÜ8(OnÌ3g‰Ù#@Þ¹äwnxç®GÎeP˜*íÝÙqîð·ç¥ŠSÊ6M¿ºîµË«§]\>åü·/IL8‘{81zâÙOlK Û˜x`m¢ÿw‰{–&º.I´_‘hµ:Q¼.߸0¾õÓøÎ¹ù{ÞÉ?ðfþ¡WcÇ&ÇN¾˜wj|Þ™1ѳ£tv¤ÎXôq²YôÙ‡tæ~ Sýt¢ŽöÒá:x·vw׿žú¾·–öÕ¢þúd æ ÒŒû5eˆÆ?¤gÖ C£S‡æ½=4öñ#ù_ Ë_9<ÓðØÞyGžŽž§‹¯¨ük?G§@ üBI§n–›‹'Ë'˜ÓC¬  +é”ò 7¤W¿Ãæ2¨_OŽ–vŠîîÜ$wôe·wjÅŽWË6ϸº~Æå5¯]Z1íÂ’)ç“N&&MŒý)ñüžÄÓ;nJ<´>qßêĽ+Ý¿Mt\žh³*Q²6Q¸aaáæO ¶Í-Øõn|ï[ù?½ždjìÄKy''ä=ó¼Î>› ‚†}âw «‚úêDoë©ÃÝt°‹ötÕ–nú¾§–õÖ—÷ê“~zo€fÞ§©ƒ5þ¢qC¢¯<˜7롼yç}=4oÕ#Ñ-hß#:ò´NÛe“ä>"Jû%à 4¤¿SR;Ë^‹‹'Ë&”ÓA¬  +éó 7¤W¿Ãæ2¨_OŽ–vŠ^îÂdw|ªÛ7½bçŒò­³J7¼}eíÌKß½vqÙ´ó‹§œNL:žxñPbì¾Ä³;ÁÖİ ‰¾Oô_™, +ê²4Ñne¢ÅêDѺ/šlœ_¸õ£‚ïÅwÏÊßÿFþ¡i±c/ç°¢ qÉ èŒAOiØüÈéá:mAÐ`í§S}tâë®#]t°£ötÒÖ®ZÛ]Ëzê«^ú´æôÕŒþš2Pãi¤ÅA÷kúš=DŸ<¨ÄCZý ¶>胠§tv´*&¥ýzáX€ß) žM/ÇÅ“M³É¹ €@.…t–ù…Ò‰«ßasÔ¯'GK¿ÀÝîÒTwrš;ðZå®7+¶½S¶qöÕuo]^=ãâŠ×.,™v61ùDâ¥Ã‰ û£L<µ-1bcâÁuɖѽW$îþ6Ñay¢Õw‰fßQ¼~~ÓMm{¯É®Y…{gü4=~drþñc'Æåz>zú9² è³È©a:=Dgêlê¥Ýu¬«ŽtÒ¡ÚÛA[;imW-ë¦/{蓞šÓKoôÑä¾Û_Ï Ð„zõ>½;Hó'wû~¶ÒþGtêq•Ž$JÿÅÂ+4¸¿Sœ<«^ë'«¦““Al  +é óÛ6¤W¿Ãæ2¨_OŽÖW^q§^s‡g¸ÝoWlŸS¾ùÝÒõ³®¬yóÒÊ7..}õÜâWN%^>š˜øSbÌžÄ3;mI ݼ6Ñ÷»D¥‰NKmW$îX½¨dÝgÍ6~\¼åý¦;fížÑdÿô‚ƒ“ãG_Ì?66ïÄèèÉ‘:aKÃ,zX§ëL?½G§»ëÄÝ:ÖY‡ïÒÁöÚÓN[;hmG-ë¬/»j^7½ÛCoܣɽôBo=ÛGûêu[/Ö_ŸÛÎbý´¾Ÿ~¨cêÒR †¸Rx†àwJÛgÓ+rýdÓlr. õAaœb~Õ†qÖÒ1f®„t¨rÌô +”Nsç^wÇßtûfWî|¿|ëûeß¹ºöí+«f^\ñú¹%ÓO3õXbҡĸ}‰çvù–Ñ›¬Oô_¸gE¢Ë’D»e‰–+5_óYÉúšm|¯x묢3šì™V¸ÿåø¡ ùGÆä=ñ´N<¦áó#§Ðé:ÝGgzèäÝ:ÞEG:&Ë~j«½­µµ­Ö¶Ó²ú²£æuÖ»]õz7½Ô]£{htO½ÜK3{k®uê¥ïzië=:Ð_çï'JïÂÑW€_+ëêWçâ õô1xÈ5‚ 0Î8¿jÃ8ké3WB:T9fz*žq—¦¹So¸ƒ³Ý®*·}P¾iNéúÙWW¿uiåŒsË_;ýí´‰)G~JŒÞ›xrgbøÖĉë÷¬JtYžh·$Ñbù¢’UŸ5[ûqñï5Ý4«hÛMvN+Ø3)~`|þ¡çcGGF?¡ã#4üÓȉûuÂö ë­SÝt¢«ŽvÒá:ÔV?µÒÞÚÖRk[ki[}ÑNuÐ¬ŽšÞY/vÖs]õB7½Ò]³»i~7-é¦õ]õcwïI +”Þ«ƒ£7º¿V} +Â;.žðÎ#G  +ã¤ó«6Œ³–Ž1s%¤C•c¦] t²;÷ª;jEAïºïWly·|ì«Ö2zõëçWL?»dê©Å/OŒ?œu ñĞ݉¶$úýèù}¢óÊÄKÍ—|Y¼âó¦«?.Zû~“ ³ +6ψoŸž¿ëåØÞ yž=èÈðdtl°ŽÛ®ñ÷ør Î:ÚA‡Ûê`+h®=%Ú|‡V·Ðâ–ú¬µ>h«7ïÔÔv×AÏÜ¥‰õFGÍí˜,ú®ƒvv鶤@i¿4xFà×J£OAxÀÅÞ¹cä ƒAaœt~Õ†qÖê}Ì\õNÊH rb²eô©×ÝÁYn÷·uvÅÆ·J×ϸbûȯœv~Ù”3K^:¹xܱÄs‡Á¾Ä#»÷oKôÛ”è±>ÑiM¢íÊDÉ’¯Š–.h²b^áê +ÖÍŽo˜‘¿eZþö—c»Æçíwàéè¡Çuh˜†9j]}îÕñ¿Yf­ö·ÕžVÚ]¬M´¾©–7Ó—%ú¤¹Þm¡×[jR+n­ç[kjkÍn£ùm´´•¶´Òéf¤@ tuð2+Ào–Æõû«sý„}?äŽAPèæš_²¡›²4 ˜+!M°¶!J_tç^qÇfºýï¸oWnžY¾áõÒµÓ¯¬šzqÅËç–M<½dì‰ož=š~J Ý›¼3Ñwk¢ûÆDÇu‰6«%+¾.\² `鼂•ïÇWÏŠ¯{#ôü-“bÛÇåí•·÷©èÇtp¨FÌ‹ ƒ}ôSýÔY{ïÒíµ«•v5ÓÎm‰kM¾-ÔÂ"}X¤·ŠõJ±Æ7ÓÈM(Ñ%ú¨D‰b­kJÔW¯‘!üfɉé0¸~B:q rP€ (t“Î/ÙÐMYšÌ•&XÛ Üå îôTwø ·g¦ÛözåÆéå릖®~ùòw/¬né g<ñÍãGC$íIÜ»3Ñ}k¢ãÆDëu‰f«ñ_ä/ù4¶tnlå;y«gæ­›ž·áåè–ñÑí£µëiíyT{Öð#{úkwoíî®]µ£ƒv´ÖŽfÚ^¨­yZ—§eùZT yš]¨W 5±‰F5Ñó…šV¨9Zׯ()Pƒ\¼HÆð›%c¦"”áú å´1hÈI‚ œœvN:x»• ³˜ËçPñ¼»0Θì¾îvOw[§¸õ“*¾±tõ¸++Æ\\:êü·O^üèño:œ¸o¢ÏîD·‰»¶&ZoL4[—ˆ¯þ2ºâ³è’´tŽV¾©ÕÓµv’6ŒÓ¦ç´õ í¦]C4|ndç½ÚÑS;ºjû]ÚÖF[ZhS±6hmLËbú*¦Ocš×ëqMŒkT¾ž´/bz+ªù"Êå«3wÏß,¹;÷õqæ\?õ¡È1@† je^4ðv+ ¨²a®>íÎ¾àŽ½ìLq»&¹Í/ºuã*V?_¶ò¹«Ëž¹¼ä‰sß;µøcßô?œèµ?ÑuO¢ýÎD«­_oü:¾îK­ž¯sµd¶–¼¡¯hÕD}?FëŸÑÆÇµe¨¶ Öˆ÷"[{kswmê¬íµ¾Ö6ך¦ú®@Ëó”°´'ª9Q½ÕĨž‹ê±¨ž—¦KsHöBàÕ2J€_.5¡ ×O覌#€@n +åæ¼sÖY À{­,˜DNÁ•ugžtGǺýcÝÎçÝæçܺ§ÝÊ'*–?Vºdø¥ÅŸK^+GiõSZ;\? ÑÆ1;òC­ë¢uwéû¶É ÂVkY¡Çô¥4Oš%M“&HÏHIOH/qQ漿\rþ¸-®ŸÛâã‡@† j(i^úàV}jr¬Æ(àÎ<ìŽ<åö?áv>æ6wëv+‡T.\¶dàåoú^øêž³‹ºXØéÈçíú¬õžO›ïœW¼u^þƵþ­™¡ï^Ñò‰Z2FKŸÑŠGµê!­¹OkûèÑ™‘ï;ku}×FËZê›}Y¤Ï ôižÞ—fH“¤ç¤G¤þÒp" Æ½ xõŒà÷KÆLE(ÂõÊicÐ {A¹7çœq6ðF+f‘s¨¨lçÎõvG‡ºýºƒÝæn]?·ªwåòžåßv»úu§K‹ÚŸ]Øöäg­Ž~zÇÁ‹÷Ím²ëýümïF7½©|w ÕcµâY- ôíP-¬}µ²»YÚ^‹Ûèëú¢DŸi^\äé-iª4ZzTê'õ$ªž¾@À9~¿pÜŽ×Ïíèñ³ €@ƒ 55/„@= +ðF«19T¦\¾Ãìêôt»º»­]ÝÜê•+î,_ÒºlQ«ËŸµ8?¯ùé¹%Çç4;4«éþ· +wψí|]['kãx­¥5OhÕ#Z1XKïÕ’nZÒAOˆ|s‡¾lªÏ õQ\ïækFLS¢+ “î!ÿÉ”‰g™%Àï—ÌšކK(„“Æ@ ç‚rnÊ9á¬à]VVL#'q#ãùîp+··…Û^â6»µE•« ++–å—•Wúyôâ<ý@'gëèLš®ý/kÏí•Ü)lÓ#Z?XkïÕênZÑ!¹ìÑQ‘/ +ôQ¾Þ‰éh²ÿõzüçFê<†@µ¿_ª)ø¢n\Busã§@† jHm^ úà]V}IrœÌØQè~(t+ ÝâB÷e~å‚hÅÇ*GWfêâ«:;Y§^Ô±1:4RžÐžG´ã~mé« =ô}G­n­ïšé¡§#_Ks¥×”¬ÊÜ3edd’¿_2i6B9.¡PNƒFÜ ʽ9çŒC/À»¬ÐO!'ðëVÊÍ—›+7[n†*_Qù‹ºú¼.?¥‹#töAºOÇïÕ‘îÚßQÛîÔÆæZÛDßEÅmòëy&5¸wjjðõ­ +pýܪÏGK€,¨±äy]ê&À»¬º¹ñS9%Àm’SÓÍÉÖ£÷N=bææ¡¸„rsÞ9k£YPg1ç¦ï¯rsÞ9ë[àN¹U1ž@J€{‡+@Ü ʹæLC-À[ôPOƒo0慲L€{'Ë&”ÓAÈY ynúŸáØsr–ˆG ,¼EËL1ÎÆàNi\^=¼Ü;á;FŽ ;7Mxn)Þ¹¥'ç2gŠ@æð=sæ‚‘d²wJ&ÏcËdîLžƆ €@šÈ‚ÒËa¨Þ¢× #ÉzŸbN0MÜ;i‚å° €d¸YP†OÃËeÞ¢çòìsî¿^€;å×[ñLj +pïÔÔàk@rJ€,(§¦›“ ‹ïÏÃ2SŒ³Ñ¸Y} +@x¸}Â;wŒ@Û ºM@~zàÍy½“rÀlàfÉÖ™å¼@€Û§y @2V€,(c§†å¦oÎssÞ9ë:p³ÔA %ÀíÕ€ €@Ž åøÀég”oÎ3j:L& p³dòì0¶ àöÉð bx €á°€¥¶Œ%õO©¿3ákg&Œ1 S¼9Ï©éædoG€›åvôøÙàöÉñ €ÓGH“@uÔsýñ«ÿ©ú‹ëŸÓð5¼9¯ˆÀõ¼9¿Þ„G¸¡7Ë YnúàQéLTbºR¨Òfªh)w§Ü]ºéò„làöɦÙä\@2G ¶çúÇSdÂÈÉ‚2aCŽ ðæ<Ç/Nÿ× p³üz+{æjiƒ´C: “ÎJ—òTZ òbUÞ!׆,è–8CÿdnŸÐO!'€ yÕiÏõÑÊõ±Oõ“3á<®p&ŒŠ1 #¼3Ï‘‰æ4ëE€ûåW2Η¾’–IßK[¤¥ƒÒqŸ]¶,¨PåÍTÙB®­\Gê‚~%j6<;(f‘s@Èꨧú‹ê¡]ÿHêŸj{¼úò LC¾¯…Õ¼-¯¦à n*ÀýrS¢×¤ÙÒGÒçRBZ!­«Ê‚~ªÊ‚.Æuµ©ÊJªÖˆu" º©k–<;(K&’Ó@ÈT¤“ÊR®w®$5äÚo¬J¿±^×E gx[ž³Sω×A€ûå—Ñ&HS¥™Òéé é[Ÿ­•6ûº Ë‚lØé˜ÎêJ•5Uesß/¨YÐ/ÓfÉ¿reÉDr € P3Ò©ùujh×?òË7â ‘5">/³¼-ÏÙ©çÄë ÀýRÚ0éIiŒô’4MzKú@úÔgAßÔÈ‚vù~AÖ;úd\âºâû9Ë‚ZÕF›UseÕtr2 €'pMÎsÍ·6®ëI ¶¶ÇïT’¯l£jÜðêäšoËsmÆ9ßÛà~¹¡Þ@é!)FJ/H“¤W¥·¥÷¥yÒB©f´SÚ/ÉÓé<]Šêr•«¢„ 膴Ùö wP¶Í(çƒ Ðׇ9¿æ‘ÔH¯fcœÁ ^“,è(<„@Úx[ž6Zœ…Ü/×OêÝÒ½ÒýÒ#ÒãÒ³ÒXéeÉšYôžô±Ï‚ûº ë½Iª® :ÕÙB],Ri‚ ëi³ðî ,œTN @ ÁRaNm§†S[àSÛã ~7xAÛ å!¨oÞ“×·(ÇËrn™k&¸•ÔIê!õ“×È‚ÆI“}dkĬ_ÕY¿ T]eAÖ/Ȳ « ²5bÇã:×å8AÐ5´Ùù-wPvÎ+g… аµE@5Cžš_×]m×|N#~mÃkÄWç¥ÈÞ“çÈDsšõ%À-SS²™ÔZj/u–zú,èŸ=!’Æû,ÈÖˆ½é׈YïèÔ±åRªw´­; ÎÓ©<]ˆÕ¤Í毹‰²yv97@F¸a¼sýƒ×?ÒHãý¥—% ú%þ úà y}(rŒà–©žìR µóEA]}]P_é¯"ÁßD‚ÿ þ¿H`uA©~A³ªú-ðuA+«² Sý‚¬w´‚ªi³ü n¢,Ÿ`N@ 1n˜ð\ó`êÛPÄ,¡dcÌ3¯‰@ýð†¼~9JÎpˤ¦Úšu‘,²¥aö÷]> ú?"Á¿ˆÿ6ü‡Hð·‘à¿F‚ÿ þW$˜"½î÷Kõ Jí)_íöI ‚¸‰rF€E@ Þ®É|ª_þTQýOþYP†Oà µŸjC=} ¾á¸eRæý¥^~EØ’ý±Õa–ýi$ø‹HÐ[ Ù±¡Rª.(/Xïèê5b5÷”_#m¶‘5ü¥Üx¯ÈMÔxö¼2 €@Ö +ÔÙ WG@¡‹VB7ଽ¼8±¬à yÖM)'”^nó& ‘, ²¾@Ö¨­ô»‘à"}ÝÍ?hYõ޾_²g>)Ù1UeAÕûˆ-¾––H«¥õAé½l3ëèÜD™5Œ@  ÊàÉah!à yˆ'¡7†·Œu~Ê'<–óXÚÓÃ/ +û­Hð{‘ÀŠ‚jfA–Y^dY­û‘ µ§¼ÕÍôûˆ}$Í—ù,È–‰5Ædòš#ÀMÔ8î¼* €á +ç¼1êÌàÝxæÎ #ËTîš ~G°À¯ü$YñÏïG‚߉¶:ÌÚGw”¬ktw_Ô§jØ#ÒŽÿo$xAzIšæ³ ÙÒ’-³,(Sg›q¥E€›(-¬@ì ÊÞ¹åÌA€wã€Þ/¹Ëwâ=–¯“Mu©X¥-UÞAÝäúÊ= 7Bî¹±r“ù<~óéÉñ»æ5iŠd{=+=&=( ”þ0üÝH`eAö·5‘¶?¶Fìɲ «,ýu$øO‘`¤dYÐDéß>Ú–‰Í•>&ºùu—UÏÈñ›(«æ’“A@ ¡È‚Jš×É~Þgñ(-ô‹nÖJÛ¥½1.ÐÉ"]h¦+-uµƒÊº©¢¯*ï—5|qOÉ=/÷’Üt¹·ä> ªõÒÈñ»ÆÊx, ²áÇHÏHJKÿ(üQ$¸Û÷‹NÙ±T]-KÅA¶§üÿ ,;²Ÿ²,èEirÕVbµZóÙ+ã÷QöN,g† €@Ȃ҈ˡsI€·âÙ7ÛöùÚj-¬‹-º±f¼ßJ¶+Ó ‚¤£Òé<](Ô•f*k­òŽªè©Êª|Hîq¹gåÆËM•{Cî]¹yr‹ˆƒnpäò]c˸ìºzÓ¯í²^–çX…ÏãÒ?Ž lCy[fAÖ)ÈþîäûY”* ú7‘À² K,;²,h´dK̬¸hå@7¸Ê²ÿ¡\¾²v9C@Ò&@”6ZœC¼Ϛɶ¥7Ã¥'ügs+´° è=߉÷ki…ôƒ´C: ”.I¥*/QŪì"×[nÜ#¾(hŒÜËr¯ÉÍ–ûPn\‚,èÚk$—¤Oü¥eYÐt_dkÄ, ²lDz « ²…`ûX +duAÕqU +Y]пˆÿ:XO¡Tô¤Ï‚,JºÖ—ïsC —ï£Ü˜aÎ@t ¥K–ãæŒoų`ªíã¶má=Àwî}Ê/ØyÙ¯¸±%<¶+“-–VI›¤ÝÒéœTUeU¶ë g‚úÉ ‘{¬FQÐL¹÷ä>•ûšÏé×^#9{ר&ïK¥/ª² ·ü1»ØRuA þ<Üç{G§² ö>J­³ú'‘Àâ ¾’=gˆ4Âç–Vt­/ßç†@ÎÞG¹1½œ% €é J¯/GÏjÞ‡‡zz[JM¤æþ³¶}î¶Ï×öáÚ°<'÷+nfHïJóü–LË¥õ¾(è'é”tÙ² ¸ÊïPE[Uv–ëå‹‚R‚¬(È:½*7Kn®/ +ZÂGõŸ])9{ãlô‰âEY]ÐûÒ,éU_dYõ޶}ÄRkÄzûº [–ª ²VÒÿ0t‘¬4È®Õ^¾¿ô¾4èg²|“K9{åÒ$s® €¤Q€,(¸:«xÒéµÏÑö™úN©™T"µñXìA+´ê«,FùN¼¶rg–ôaUËhë´YÚã;êJLeMUÑJUyܹ‡å¹Qrä^‘³¢ 9rŸÈ}Eô³+%goœÒÉꂬñ”Õ}Z£_õŽçCÈæë‚,ö±ð'µ§üoE‚ßó;ËÛz±Ô‹ƒîñÑåÏXù&Çrö>ʱyæt@H£YPq9tö +ð><Œsûÿm-ymÝ•Yd¥AVw‘* +²* [q3Ò·á}Å7õµ²ùÒ×ÒJß)È>Ë´¢ ¨.EUf‚š«¢½*ïVå5ûÈWw +úHn!AÐÏ®”ܼqŽIû}Q™eAßùõ†‹|½™U½éûÙ±±Uý‚þ,üI$ø>²måÛJö§ÿc×­}aÅB?3å›ÜÈÍû(÷æ™3F@ ½dAéõåèÙ(ÀûðpÍê¿ôÆ‚ ë mKo¬õŠÕYdq}ʶ!{Ðþi˜ô´oÛbÌ_“fKûú ëîbûÈo“öIÇ¥ Ö2:_åÍTÑF•Ti«Ãî“*÷„Üh¹}QPjùù|fÿÙ•’›7ŽU‘õÏViÏûTvuYØhý‚¬í%á=ë/T»-–ìïXÙÅiYekÅÚß-I~vAåî7¹y+åî|sæ €¤G€,(=®5kx–©!¥Ê-ì#¶mÕ=ÄÙúšTQÐR+¿èÆ–Û ô}W¬U‹u +šà÷‘·Oès«ö‘·E=›¤¥ÃÒéJž®©¬¥ÊïREUö÷-£•)7Vn²ßGÞ¶û˜ ègWJnÞ8âÉB²CÑäõ³ÅgA+¤„_xøI,hRÕ1Ûl¸¿V­yo_±v—‚l1cAÐÏ.¨Üý&7o¥ÜoÎ@´ ¥–g¡oÂC1©ÔhÉkEAöùz¨|,ö±Ž+V_aŸ¬­Ä–ÛX4t¯t¿ÿž* +š,Yˆôžoçb«Ãì“»µŒÞî×øXQÐù¨.êê*»S]®+ +š(7Ýw +ú€ ègWJnÞ8—‹t>¦ã1ýä³ÄT]]QVôEÕ>b©5b–Y»òQþZµ,ÈjØ,Ÿì#ÙzF»bFÉ7¹-›·RnÏ9g €@ºÈ‚Ò%Ëq³N€7á>¥ö)û+ßáÇ’ûˆ=Õ×Z<ã öŸ¬-ù±üÇ*‚luØßêwèþ—‘à/#öKu^­Ñ2ú[¿ëÓFi—tH:Õ…])V™µŒ¾K•Ýý>òÈ¥Š‚Æù¢ ×øä~íe’›7Ni‰®Æuβ h2 Ú-Y´Ö§‹©,hžíBµKnŠ/H{^zÊ7­²,È®XÛØîZJ¾Ïmܼ•r{Î9{@Ò(@”F\-¼Ïð™Ü,­‘–ør‹¤·ý:/+´xÖ²Hýn$øHð‘à#mÞýÏ#Á¿‰ÿ>üÇH0®jù9¾fc‘´Ì/ê±¢ Ò‰¨Îèb±J[¨üN¿¼mf‚‘{RîùªNA.ÕàÃËÑ{§…*šêJÁϲ [#f5f«ªöK­›-½ásK[œhuA]ÚzF+ckð‰â3] Go¥LŸƇ €@ˆÈ‚Bò½|QÐ0éo"Áö#¶¼ýøÇÒ"ÿiÝZ»ØÁwçé`L'ãºX Š&rÍUÙA•=U9@Ί‚FðþÆó˜Ó÷Ž•Ù±&º×…Xr±#QíólÕYµ%ÿÜ_lï“Ýø +âÑßäô­ÄU€ €é J§.DZïÀ3pòl'wkݜڧû@^²¥³•îXO¢FQµŒ®îôÏ|S Ò]~ã0[ÖÚÝSàwk²Õaÿ9X«+ÌxK² È캕Ù1ðEA­e´t)ªŠ¸*›©¢*îVeß)(2cH9}ït•kŸÌ‚* UjbLg¬®,š¬.ÛÕf_dëmbfÌ£Ètœ¾›2}r €á +÷ü1úôðö;=®u?je']m¯+Íu©P§ó“®­Ð"UdÝWJùNAVÛc>/ø.@¶AØ`Éšuñµ@¶}XK_d5BÖ>è~)µ:l¬4Ù÷ïµÕ:ó|}‘Ðòü¦Sí#/•ÆTÖT¥mTÑQ=äúóAþÆSÉ“t±Ê1[#fûˆ5ÑE[]Ó±¨,TÜCþs㫆Gkà†ª•†@@Û ºmBm¼ýάí«Šî*ï «­TV¨ËÑd¡ÎOQmj]TVbaËmæK¶ÖæMß)ÈŠ|ž“þ¯Hð‘ ŸÔÍw²Š TQPG)U”j=JzÑÿ”ý¬áSßÈÅŽY]tJºlŠTvGrû0×…¨Ö«ƒ§Vþ[à†ºu3~@nA€,è°xj¶ ðÞ;³føUÞ§Š^*﬊֪l’¬Ï±*‹ùÚÓ¦èÿÞGþãÛ‡ÙŽ`¶M¼m?PºGêäw kîG·“î–îõIÑ_E‚§|[!ÛqÌö›å7uZà7¦·DVq”Ü>L:gAP¾J›ª¢%)Ð/]Ü;¿¤Ã¿!p‹ÜP·ÆÓ@@à–È‚n™ŒÈRÞ{gÐÄ>›lË\ù€*ûÊY–¶rMu5®3qio,Yd¥;+}QóÌñ‹¼l©—­ûw‘à_E‚$+ +²ÍÂlË0 ‚ª‹‚zHýëHð¨ß¿{œ4Ešáð‰/ +²cnT²‘-ê9Õù˜®’ÝäÒàÞ¹ ÿŒÀ­pCÝŠÏE@: +ÕŽË.Þ{gÐ|Ž–³Ú–³½ººûN¼w$W‡/ÔñxrW/ÛžÛšù¬ö x?÷ Ÿ­í³5¶Õ^Vôo#Á¿ˆ÷I¶SXg_”êdEA þ©o"dÛ‡¥Š‚¬¹½-ÍõM‡–Jk¥m¾(èPT' Hn~]pïÜ܈g 𫸡~5OD@Û º->~8+xï)Ó8Yî¹§å†Ë ’ë%×I•­UÞL—›èl\Çl˜ÏjÖùmßmówëöl=Ÿ­°ÇÊ{¬ÈgdU§ ?Ö)¨½/ +ú½HðG‘àE‚T§ ‡¥À÷_Uôžï8d›‘­òEAVt”) ?"&n¨0ÍcE@ ädA!Ÿ@†»¼÷¾]ÁúúùWä&È='÷˜Ü¹{ål÷öªh¡²&ºP “1ò«·l —…6‹¥¾ÉÏ,_Ûcmž—ž¬(èÿŒ þ0ün$øíHð÷"Y4d‚î—¬(èIÿd+ +zÝGIÖnèKÉŠ‚lû°ú:›\8÷N.Ì2çØÜS ©Ík!€ ãdA9~äøéóÆ;#.€Ùr¯ÉM’Sµ:l`²(¨²Krë®Ò;t¥@gmcn%÷‘·\V´Ü÷ö±NAVÒ3Ó—÷Œ•ž‘†Kƒ¥??ü~$°ÕaÍ¥Ö’mÖCê/=(=æ‹‚&JÓýÖcø¢ ¯HnñRàÞ¹E0žŽÀM¸§nÄ?#€ €@½ +Õ+' ïº3eªÞ“›)7En¬Ü3rÊYËè~*全ŽÉ}ä¯4ÕŘÎH‡¥ÝÒ&ß)èÛª¢ kõc‚lµ×HòXÔc­³ð§•Tâ»F[QP©·‰FTµŒ¶¢ ×üîc™âªqpû„jºl¸§B0I @ì Ê®ùäl~•ïºS<éC¹·å^•{IÎZF?©Êaª¬ò>*몫ít¹….Ù1é„’‚¶WÙ’®šûÈÛê°§üâ/+ +ê#u•(ÈþX"d[‰YQÐi¨ô¸/ +²"¢©Õu~¹}ê*ÇÏ!pcî©»ð( €¤S€,(º;x×)³ò©Ü_4Un¼ÜHU>¦ŠUÑ_¥÷èjg]i«ËÍ’‚Nå%;ýè;'Y“çêÕa¯H¤g}QЪ}äSEAÍ|]P_ÔWºO²®ÑOÝÞôsûÜž?ÀµÜS׊ð= €4ˆYPƒ0ó"™"À»îL™‰rV4KnºÜD¹ç“EAVt¿ÊïUÙݺÚ^[é\3*Ðáª}ä×H¶:l¡ô‘_ÞeÛÁ[ÛŸÑ~_0«ù±´§—ßG¾­¯*–ZJª:eʉ‡yÜ>až=Æž‰ÜS™8+Œ @Ü Êyæ,“¼ëΔëà+¹yrïȽ!gûÈKY§ Ê!ªè§ÒžºÒY—Úèb3)Ô‘íÉ—íó¾^Zá[Fâ7ÿzCš,Ùj/km]€¬(ÈŠl³0[fý¢›ú8ÈŠ‚2å”Ã?nŸðÏ!gYÜS™5Œ@ ʱ ÏÝÓå]w¦Ìý¹Ïä>ð‚REA£ä¹‡å¨²§Ê;©Ô‚ :_¤3~û°=Ò¿á{uËèY~yëÿ<¦ªSÐ ßÚzD[Q­Ë”“Í–qpûdËLr$Àm•A“ÁP@È=² Ü›sÎFXä‹‚Þ­* +Jm6\n°\¹.rmåš©"®ËQ–J;¥¤•Ò×¾SÐûÒ[~û°}#èá¾(ÈZC[QP£žXÖ¾8ŸX³vj9±Æà¶j<{^@’dA\ Ðp _4Wî-¹i¾SP¢ ×S®£\+•–èB‘NèhT{¥Í¾(h‰´ÈofEAÓ¥—|d½ !Jçüñ‰5º;G¸­rtâ9m@2I€,(“fƒ± ŸÈYQÐë¾SùNAî¹¾ª¼[¥u¥µ.ë|¾NDõ“/ +ÚPU4_š#Í`Gø†ºLøÄÚPÒ¼N p[åÐdsª €d°YPOCC KfÊÙ>òäžó‚úY§ Ò¦ºœ¯Ó1ñEA[«:e©E枟X3wnYh¸­B;u @0 XÎóËÿÙÉØÂtJŒ²FÀ¶{Z.Õ)¨·ïÔF•ÍT×–}5ö,󉵱g€×ÏBn«,œTN @†øå„'õ¯¿rDdA¿Ч!€9"À'Ö™hN³!¸­R›×B@› +Ý”ˆ' €¹#À'ÖÜ™kδÁ¸­ŒšB@_)@ô+¡x õ|bÍú)æ@@0² .@ â2@@@ GÈ‚rd¢9M@à‚~';ÿ©›\¹>rå†È{JÙy¦œ € €ÀudAבð [A¹3ßWKTÑBwª¢£*»Êõ”ë+wŸÜCrÉ$Êk3E@œ Êééçä@ ç‚rá8Z¨ÓMt¡H—‹eqPi •µUeG¹»åzÉõ—{Pn˜Ü“dA¹p9pŽ € PÏ–«\óß _ æsnø„†|ÐÓ/Çk!€dŽAPæÌE:F²#ªÝ1íë`¡Ž6щ¦:ÝLgKt±…®¶QE{UvV…•õ“TU”ŽqpL@@ KjÆ;5¿¾ætkþSêëkžÐðßÚ0þEyE@F jô)HßÖH?Dµ)¦­qí*Ðþ(ÔÁ"-ÖÉm©KmUÖNeUaƒz«r€Ï‚Ò7 ŽŒ €d—@u¼Só´®°¶GjþT£|MÔ(ì¼( иA럾WÿZZ"-jULkãÚ”¯í1íŒëÇ&Ú×T›éh‰NµÔùÖºÚZ¥–Ý­Š{ü2±ô‰##€ €Ù%Jx®?§k¿æ[{~êûûúŸmàG2a |ʼ ãAYy|(}"-¾ˆê똖åiužÖÇ´!®-…ÚY¤=ÅÚßL‡ïЉ:ßRïTé]*ï,×6AYyEpR € ëžÔËÔ|¼æ×5QÛã5ŸÓ0_ÛHæ…x@L Ê„Y¨ß1¼.½)½#½/}ÕgQ-ŠêÛ¨–ç%«ƒÖYuP¡¶iWSí-Ö¡’ä2±3¶L¬µÊÛÊuð»‰Õï€8 € c5Cžš_×d¨íñšÏi°¯É‚ŒšB]€ ¨Ñ§ 0^š M”¦H¯¦â h2 úTZ(}Õ7ùZך¸Ö$ã EÉeb‡Šu¼™Î—èJs•µV…Õñ € €@]®Ix®ù¶ú¨µ=^ý„þ‚,¨Áy9@ ±‚K>¯û”ôŒ4J'½$M“ÞfIïIs¥ó´ O‰¨–äieªq-k¢½E:ÔT'›êœí&ÖJWî"JÇäpL@È~T¶sMÂsÍ·Õ +µ=^ý„†ÿ†Ôð/Ê+"€4°APƒ§ïå”–†KOø8h´dB/KÓ}ô¶4Dz i¾/ ZÕw©ebqm/ÔÞB.ÔqÛ\¾¹.Ø1þC@¸ET°s}–R[àSÛã·ø²õüôëÇ_Ï/Àá@[€ ¨±g ~^¿·t¯4@zÀÇAä@)½ ½(Mö+ÅfJ³}uÐ'ÑdéÅQ­ÌÓßAzG\ûâ:T˜ÜYÞ² úGA@rC éÔ¡ÔøÔöx£›Õv">0€ P/AõÂØ¸é u’ºJ÷ø8¨¿t¿4TzLzÚ¯ëWн’jÕ{QÍ‹jaT Ûb>šÜPlcL;bÚÓþ&:^LÔ¸óÉ«#€ €@˜RyÎ/„'µ>µ=ž 'ÿ §“ Ãc  €·#@t;z™ð³Í¤;¥»¤.ÒÝR7©§ÔW$ ñq•=+=ïWŠMò+ÅlO1[&öQj™˜´LZÕ¦¨¶æiW>)P&Ì*c@@Ðüš<çúç\ÿH¦0YP¦ÍãAêK€ ¨¾$ë8í¥ÎUùUõªúc‹Å~;ün$øÃHð¨ô¤ƒl¥˜í)f¥AÖDÚºYikô•Ï‚VEµ.ªÍ1‚ ÆšI^@Â'ð+óœkž–ú6ó“–Ìaø®FŒd€APLB݇`‹Â¬ +¨‡d±õ²B Ôßþü~$øHðwüßöõù8ÈVŠ¥JƒRM¤ß’>PrsùEÒ7ÒŠ¨ÖG ‚ê>ü$ €äš@u¤sÃ/jj\ÿ„šÿš±_“eìÔ00@ ÎAu¦Ë„´ú‹€,ÿ±6ÑýßöÅŸE‚?ñÉ5 ²oûI¿åã ¿ Fø=Ŭ‰ôÉ–‰½*YduAó¤J¶ Z-‚ L˜XÆ€ €á¸>Þ©ùÈ5çð ÿtÍ33ê[² Œšƒ!¨l'×E®·Ü ¹¡rOÊ‘{Yîu¹ÙrÉ-’û®>…ô*²a[GhkdQým›…Ù·öçŸG‚¿ˆöÅ`ÿÇþÉ¢T¥Yi5‘¶•b–YiË‚¦I¶›Ø»¾eÐg¤@á½9 € 6² ´Ñr`ÈfS1ëR]-QyK¹TÔGöaÞ —{ÚgA“ä^•›%÷±Ü—rËäÖ§=" +ée÷¸ß̶‰¨êσÒ_E‚¿ŒKöuêõ‹¶DÈJƒ, ²?Ö5èïú'Ø?ãë‚^”¦J3üÎòÖ>:¤ @@ ­dAiååà MßK›¥]QÈÓ±˜Îè|±.¶Pi•wRe¹~rCäFÈ=#7Vn²Ü ¹÷å>—ûFn•Üf¹=|<Ϧ‹¢~Îe´oþl=lS°áÒ#’-ûú‘à¯#¥CVöcØßY”ª ²8ÈzGÛ2±ûüãVd?n-ƒ, ²öѶLÌÖˆÕÏà8 + € €@Ö eÝ”rB PÏó¥/¥o£ú.ªbÚ–¯½q)ÔÉbm®‹mt¹£®vSeO¹þrÊ=&÷¬Üx¹WäÞ–ûPnÜb¹ïå¶óñ¼žg'쇛$½$MðË»,zJ² +Ÿ'¤ÿ þ“od¡ý±€È² +JÕÙ1kdYµ²e¶šÌž`»‰ÙÆK“IÂ~Y0~@@ ÍdAiæð J[eóšß˜ûݨ>ŠjAžÇô]L?ĵ½P{ u¸H'›éLKkŸÌ‚Ê»ÊY4@•«2-g ĬYÐ;¾YÐB¿@ì‚ P^ é´]cVÀ3]šâëy¬óó(_Þó?#Áù\Èþ¶š‹z¬@Ȳ ëd…@ÿ üA$è#ÙFóýjdAÏúã¤oÀ@@ ;È‚²c9 ¨/T^+Õ˜f x£šÕ¼<}Ó·q­Œk}\;âÚgYP±N4×™Ö:ßNW;ª¬»Ê¨ÜˆY³ [ 6NnŠ_ ö®Ü'r ¿@lYP}ÍR6çÉþÌò½}lU—óLô‹¼ò#ÁÿŠV ”ªJõ²8È–‰YË Ë‚lC±?ŽÖ,È‚ ÛtÞ² {ÐþÕꂲÁ…s@@H¿YPúy@ͦ+/ز¨¦EõfžæÄ4/_ òµ8_kâÚ×®Bí+Ò¡m¥3wê²ÕuWiU ð įZ 6Uî-¹¹r_ø¢ 5|NÁeÐ0C´U‡ŸHŸJJsüþïÖêÙâ Ë‚Š"AA$xÎo +fÙŽý±õbÖDÈ–‰YÚcý‚lC±?Ö,¨—ÔÍgA÷ú,ÈžÐ0ƒçU@@²@€,( &‘S@: ´—ºøÕրŊ.¬ú"¹ST/Z”§±dôiL_Ç´"¦õ1m‰kg‘ö5Óá:ÕZ, ê¨Ònª°ÝäÊ=$gYÐsr/ÊM÷ Ä>õEA+ùœ^ç)ʶüFJH_I ¤yÒ\¿ù»eAV‡f¥A%‘Àâ Ë‚ì:´?ÖÚªƒRYÐ_F‚ ¬q´AÖ&¨»ÔÉÿmßf›çƒ € f² 4sxÈDæR[©”Ê‚l­5àMeAOGõ|T£z5OoÇôaÌ7 ÊÓª¼ä±ÍM´«XûïÐÑ–:y§ÎtÔ…®ºr® ÐÕ!ª¦Ê§Uù‚ÜËr3}Qu^ÂGõL¼~L+•l?¾"ªåÒbi‘ô¹ô±Ï‚Þ’ÞðqPóHP ¬tª4(ým$ø÷‘À®ÏÔnò}|ÔQ²?= ‚~"yE@@ üdAáŸCÎnAÀJ):ûZ +Jýéê«,RkĬOïȨÆF5%ª©fAQ-Šj©m"–¯õ…ÚZ¤ÝÍ´¿¥Ý©íu¶“ÎöÔž*¨²¡*Â/³¢ ×|QÐÇr_ÝÂìdñS·Dµ>?¹Ýzi•´ÔW-ô¥AøÆAoú>Ò-#Aª4(Õ5èD‚ÿ þ&Øê0 ‚¬z-Ý%µ!ÊâË…SC@Ò,@”f`!úm-V¬ÈþX5…ý±¾»¶ÐÆš®Øçk{‚íÓôdUQP²YPTïG5ß/çYÓªýP¤-%ÚÕ\ZêX訳]u¹§®öWÙU>"÷”ÜX¹É¾kô{rŸeÄì7ú vÚösÖuó¥AïûMël¥XëH`¥AM#A<(<á×->ìw +KAv¹Z1[K‚ FŸT€ €„Y€,(Ì³ÇØ@àæÖ}׺Ùúk«b;.¥þ¶=˜,ÿIEC +ÙƒC|{^[ fÍ‚&E“ÊÏö­}F•ˆiY¡ÖiCSí(Ö¾±bmuþ.]º[¥½UÑ_Îv{ÌM›&÷¶ß>ìæ£ãÙ/°¿‰Äu0O{¬ßT6Kk­4È›Yã + ²>ÒÖ5ÈšH¿­ä…÷²4Áo(öŒd…jÖ2Ú.N«[³Ëµ‹…E¤@ÙÉp† € €@ÚÈ‚ÒNÌ €@# ¼h] }ë]+ø±,è_üc}ªã T"dmx­âÂÖàØçîg¥ñÒT¿Í÷{ö!=šÜMþ›¸Vêû"m*ÖÍôSs·­äÛêj{•w–ë)g;ˆY×è@îy¹IroPÔHSžy/{¬X'ã:Z ƒúÑšMåikTbú>ïg¥AÖDÚVŠYü˜êdŠÙ¥;Ò_“C«‚ [̘yçLj@@B)@ÊicÐ P»À,i¦oÃkÅ£ýNLVdQWØB0Û†ÉJ,ìoË,JÅAö­U_Øzœçý¾ÞÓ%;ÈÑäb_ÄõM¡VjCm·¢ ;’EA§[ëR[•·“³,¨—Ü ¹árÏÈ÷Û‡Õ>6þ%wN·ÐÙæ:W¤“Mu¬©6Õþx²4hG¾6Ç´Î:PIK|× /”\Šø¡o"ºt_’Æú,È.]»níZÍ7Î@@ È‚™—@†°ÔûÔV\ñŠOuªë‚¬ãŠÅA©DÈ>\ÿãHðÇ‘à#ÁïE‚ߊ¿ Fø-¼íød_›1ËšåëÓ¸¾Œky\ë +µÅºFë§o¡s–µSYG¹»åúÉ=(g]£ÇÈMå3{ÃLu¦¿ÊŶºÒJ›ëLs²B²jªŸüb±ó“¥A?HßWu úªjC1[&fYE‘–Y,i›ˆY­Z¦Ÿ*ãC@¡YP'!#€Àµ¶Ï—µ^YP£¸Â² [#öœÿ4m¨-걕bVüó¯"Á_D‚?÷YÐD‚ß¿ ì‹Çý“­”Ȉ½Õì<͵Ýä󵤪kô¶bí-Öá;’ Äδӥ»TfAÝ/÷¨ïtí ø>GÊ;©´®´Ñ…6ÉØðt+o®#Ít¸©jw¾vD“]ƒÖI«¥eUŠ¥bLË‚ì +´K÷_¨–£‚œ6 € €@šÈ‚Ò Ìá@ ½›¢Zí[¯XôyU]íÇô²4Î÷ÿyÒ¦¶¨ç¯#Á_F+ªÙ;¨Ÿdqµd±b£ügð©QÍÌÓ{1ÍÏÓ×Ö5º@ßjs¡v5M.;ÜJ'ïÔ¹»t¹‹*zÈ ”JåFz§8\G¯ì¦ŠN*»KW:èb{k§Ó¶åœm zÓ7Ž/åG‚ÿ ª×ˆY]µ ªÎ‚lo&[ f½£ÿ(Xíu™¶ee¯Y”Õ‡Q-ŒjqLßŵ¾‰¶éGëÝBǬýK[•ÞÉgv.Æ < wŸ*û«¢ÊîÑÕîºÔEîÒY[&ÖZ'›ëD±ŽêP\»­Ò,žÜYÞJÚìÒ]D +t#NC@H«YPZy98Ô‹@ys]h­³-uÔ2™(ÐÎ&þuT«¢É½¹¿¨jd›ˆYªS , é÷”·8ÈúYûhëýô@UQí fEA–ÙÓ,;šb‚lû0ÛJ>O_Y§ + +Êצ¸viI²ß˹r%Aõ2ŸYwár%× VJÆAå½UÚC—»êbGo§³véÚžbÅ:R¬ýEÚSÜY~#PÖ]œ € "² MCE 7Ê:è²õ]i¯Ó¾¸â­Øjª]Ú’§µyZÕ7U›ˆÍò[rß , ²^ÐòXÍO Õ, +$ ~Ço"feB¶‚Ìöï¶5eVôŽ”’EAQ}——,:ÚV¨}E:V¬‹MIróêûgý¤Ü¹a¾‘¸U ð¥A=uµ«.wÔ%k0ÕFç[èÔ:jí£ õcŒkéW¨ò@@t +¥S—c#€Àí tW™¯¯¸ÐAgÛè”YßkÀk•1m´,(*Û‰éki¾ôžd ÄZG‚’H0Úo"f¡SÍ‚jvþ‘ÀúE÷ñBV,dy‘í8fyÛvÞv„Ol¹™-:‹êûð«Ã2 „Ñ € € €é J+GE[˜&7En¼œÕÙB›‡“uAåýtå]¼[g;êÔ:ÖR‡J’;ˆí,Ôæ¸ÖÆ~³ƒØçU ĦûÎ?Vÿ=<æ ‚û ÈÖ…Ý#u—úKú¢ «²íìŭ»•±ò\@@@ ÜdAáž?F@Øfɽ%÷šœÕ‘{ú7MW*©Ô/;ßE§;èDj©}%ú±irŸ÷ùZ+-³=¿|“Ÿ9’ÕöLñ;‚Ù¾`Oú¨ÇöKAþXÔCê*õöÑÙÓ&H¯’…ýúaü € € pëdA·nÆO €@= |$7GîM9« zQÎöc²fA#TñÊîÓ•>ºØ]g;éd;i£-µ·Yrض|m”VI¶á×ÉúüÌò©ŽùŒñ+¿¬¥=ÖÈÖ‚õóùA}d¹õ‘¶–Ñõt@@ŸYPøæŒ# ä, zWn†Üd¹qrÏÉ=©Š*¢«t©—Îß­3wéd[m¡CÍ’]£Œi›´NZ!Ùž_ó¥÷%ë=5ªñ¾ÚçQŸöXtŸß2ÌÖ…Ý-uôEA¶ƒ˜­Ë<Î@@¨³YPéøA¨»@BîsŸÍ–{Õ/³ÆÑϪü •Ué`]î§‹=t®jØ‘æ:ØTûòµ+ªQ­ÊÓ7yú•öÑ•nºÔQçÛêLs-ÑþfÚ^¬šê»&Z×ÂX²SМ¨fH“ˆ€²õ‚á¼@@@ mdAi£åÀ P%°Wn›/ +Z!÷ßAl®ÜÛ5Š‚ž’¦ÊT>@¥½t¥«.uÐ…Ö:uGr+ùÝEÚ\¨ï ´,__çi~4¹|Õ¡ù? € € €Ào,ä¹éöT{d €@z~”Û,÷}®ÑVôFUQÐs¾(èaU RÙ½ºÚMW:èRKk¦cE:P¨]ùÚhÛ‡Eµ˜(½óÄÑ@@@ CnšðÜR¼sKOÎP†….°Uî¹Õr‹åTu +zÕw +z^îI¹¡r÷©²·ÊïVY{]m¡+E:×Ñ|ˆR”á³Ëð@@@ ddA!›0†‹@¬SAKå¾›'gEA3å¦Vu +zTnˆ*¨¢§*:ª¬.4'ÿ ã43f@@‡YP8æ‰Q"©¢ üöa¯ÉMò[É[QÐCªèGø“Ì) € € €@8È‚Â1OŒ@@@¨² úPä € € € €@8È‚Â1OŒ@@@¨² úPä € € € €À,{©þïÆÏhØGm0 û‚¼ € € € ÕPõ™pÚdA™0 Œ@@@²Iàúð'õH&œ#YP&Ìc@@@@¬¸>ö¹>jÄ“% jD|^@@@²Iàú(uvµ=Þ(çNÔ(ì¼( € € €d™@mOm7Öé“5–<¯‹ € € €Y#P[àSÛãxâdAˆÏK#€ € € €@ÔøÔöxãž2YPãúóê € € € jÚŸÚoô“% jô)` € € € RÚŸÚÏ„Ó$ Ê„Y`  € € € :ÚŸÚÏ$ ʉ` € € € .ë3ŸëÉÀ3" ÊÀIaH € € € á×Ä>©oC³„b>û @@@rM :ü©þ",dAa™)Ɖ € € €™#P….Z Ý€3gÒ  € € € :² ÐMF@@@ê,@Tg:~@@@YP覌#€ € € €u ª3?ˆ € € €„N€,(tSÆ€@@@@: Õ™ŽD@@@B'@º)cÀ € € € €@È‚êLÇ"€ € € €¡ +Ý”1`@@@@ ÎdAu¦ã@@@@Ð …nÊ0 € € € Pg² :Óñƒ € € € €@èÈ‚B7e @@@¨³YPéøA@@@@ tdA¡›2Œ € € €ÔY€,¨Îtü  € € € :² ÐMF@@@ê,@Tg:~@@@YP覌#€ € € €u ª3?ˆ € € €„N€,(tSÆ€@@@@: Õ™ŽD@@@B'@º)cÀ € € € €@È‚êLÇ"€ € € €¡ +Ý”1`@@@@ ÎdAu¦ã@@@@Ð …nÊ0 € € € Pg² :Óñƒ € € € €@èÈ‚B7e @@j{?_ÛÕÏá @j +Ø/Žšßò5 € €4º@mñÎ57ú8 €@È‚Â8kŒ@@ Œ×$9µ}ÆScÌ €! +Ñd1T@@ ¨-Ò¹æñÚFÎòÚdx@ MüêI,‡E@µÀ5INmßÞþ9ò†üö 9 €À- ð«ç–¸x2 € €@¨j‹t®y¼!Ï‘7ä ©Ík!€˜¿z¸ @@Â.pM’SÛ·™yš¼!ÏÌyaT €@ ð«'‹'—SC@Â+P[žsýãá=ÇÔÈyCödü €@èøÕº)cÀ € €@x®OrnøÈÿߎå:¼ÿ­ Ɇ€ õI«2?f]W„±Eô¹<Ñs òhN!@€Mͧj•L'zôlêI @€¨™½Ýã .UiA¾Ôí6Xœè=[Ëüñ–=zŽ[©$@€,%P./ñR&3kA>CU› 0ðèà8D€xŸÀà«Ny¨¸c©qyŒ÷rR  @€ÀXÀ£gìã( @àågœA|n,VŒçÜž…÷ ”2¸JÀ£ç*Ií @€.|Õ)]~ݪA+Æ +äÚ]¼×zjv +¾x²ßÜ  @€Àòrew{‡®éƒ%Í¥Ó5xOÓ9‘Þ'P.Ÿbt9»ôòQð“À“ý'ì.J€& ”‹“A<éê?lÖ’f*>Þ©¼'@€›Tk§¶WQPÊù*™v{ù¶ò˙Ա/_Ñå @€Obá1>möMõ–4Sï&Þ©¼'@€;T«¬²Kq¨LFœÆn½|ü0H}ûáÕ]š¬,ëŠq°2Ññ±[Ò·:Q‰÷šS @à±Hë%´G{ù¶ò'OöŸ°»(¼X Ö ãàÅ?š%ÍTv¼Sy5N€÷Èk¹qßÚš63ná'G=ÙÂî¢ ð8üXßÝöÆåÛ“¹*Oø*Ií @€yÉ·ëP•åÝG¬IÑÉ] @àœ@<²ÇÁ¹ÆË³—73Çü¥îÿ Ç-û8zsjÇñ=¹gª2» @àœ€…Ó97g @€À@ ÞbÆÁ …÷òÀ}O ÏÖþµåôXµœ•É(.“b pZÀÂé4  °š@¼ŒŒƒÕXŽ×÷ Ôé2夎Ͽe<…¦‹Fh3ùP/' + @€ÀGéÉòQ½bx™@~ÅØÝ¾lÔߎîls³…µÿ˜iSS9.Ûl3ùh/_ž+&@€ ¤‡ËGõŠ  @àùÝaw[ÅC¡¹p—í…˜š"ðD–¦÷¹zB€]üú°»Ým§Wà¡Ð“ùžíÿ µ@à¡yÒŽÎW»)ßfrq/M  @€À9ôˆ9w¢³ @à*¼ÚßÝ^u¹A; +œbûO@§ÿD š—z}(Ëz5kæ³L9ö#™\ßV–íˆ  @€ÀÒSæ?§;—zy¿»íþ“¼‡ÂÛy¶Z¾J Ï–UkU²Úâ^> +V6qªdÞMÛ•¡Œ¾&à‰ó5j"@àX-ï—\nµF<æÝq¶ólµ +Vz8ÁÁÊJÆN€_HOŸ/_Ñå Ð +ÄJx¤ÍZ­ÞU¶WIn¶ƒw“Eò†å<\v/çËLŽ{ù¶rÁ̧缠’! @€À÷ÒcèûuE(ºƒø# ³ÖG\³ýˆK1W +TsuŒ1çc7‚^> + @€À ¬üoxSt‰Àͪ7…Þî¤Q˜µ&Á¦fÙγÕò¶ólµ|¡@žúÚ«|µ›ês&mÛsÌ´>¡ÊW»Á¸ ˜! @€7 X½énËÓò’{wûôaþ³ÿf­Ng;Àqè&y†l;SæË¸¬ìåËšuâVc7“ Òv%#%@€oð@ë5®ûÄâyܧÃ7ï‰YkÞ b;ÏVËSòìš/QÆåE{ù²f8k´ÛJ`· ª·K€ + @€Õ¼U­vÇ×oùÖ0ˆ/ÁñŸº„qÐáŽC^/sx5Òœ¯’i·—o+e @€ëx«Zç^¿o¤ñF0¾½m9ö¶¦<*&@€ØH‹¨Í¼äËÚÕòfæe£þÉpü§f³ž-¬ý«ò4Û¶öi¾máÝ™ìÓÛVc/˪Cv  @€ziÕ;$r <ˆ«¸éȵ»x¯õÔ‡ +ä9¹íü§ù¶ @€ÿðÞúOÀ§ç7…ÝíéK»é§éŽœˆ÷ˆ’ïÈx;ÆOóm 2 @€þ/à½õÿ†[ȯ»Ûƒ­ý§ÌMÿÞî¹xw‰ÜS œîÙçô*K¶½ý4ß¶ C€ @àï­ÿd,ßžñ?¯ríénúµžUkx+»÷hç®û÷ù¶=̘m÷>Í·-È @€¸JÀ{ë¦dûf´™Ù<÷þI7}ê=Â;•Wã× +ÄÌÍæLì +>èé}šÿ袊  @€|*¨ŸžòÜú¼ßÝ>w€{¾ÔM?hraÞ 155U O†å%bz,“⃭gœØj3Q, @€ 0[ -Gg_bvûyE½»Ýµÿ‚›~gm¼w¾;ú–ò„Ùjôòm¥L%0 «åÝ´­Z°K€ @àk÷\ŽÆRy7øÔ›.tÏ›þa¼¯¹•oHžWÛÑõòm¥L%0¦ËGËmuº] @€ +”+ÏÍ8]+å/¼â¸©Í>´É/÷jÜçWýæM%àxPxÇ>ŽþV O¹mzù¶R¦Ø¥Ë»eU³v  @€Tå²W§ôvÓé½Có½Tùƒ­å²ÿ÷ê£Ë­VŒwµ;n¼²@ž–[^¾­”!@€ @à½ÏùÕ`w;I ×«I—[­Y¼«Ýñ×7ÏTƒa–SÙ ì݇zJ½ü»5ŒŽ @€ÀÊå+RÄ?I=ùy^ܼ/¾¹ -O\½Ç´A¯òÝùžR/ÿn £#@€ @à†éõ䆽zM—ð¾æV.>ü£÷{næÌ‚h½÷ò 2 @€?Ho(?ïË;€÷Å7w…¡å/±Ýr>Z×—•ï‹{ï© @€ ð\ôæòÜÎß¿çxïôpW ý¾‘Où4¿{¡§T y7mŸ>.ý'@€ @àeÞS¦ÞP¼Sy5þüA£½Ð§ù¶…÷e²I¹}߈ @€ÀMz¯$©{Öä»÷(íÖ(8-€÷4ï Л]?Íßa,_èCféá|¡.A€ @`Xx·ƒC´52I ùp @€@+'ÏÿçÛd @€ pN ÷‘§Í÷ÞhÎ]÷eg%œ—Èp؈y²7=^•ßí‰ @€(ßbªúöý%Š«J»Y ù  ðø§G°9¨8ºò/¿DØtÈ-à§ù¶ @€|*o"D m&êåãÄŃ䳸€á?] ÿÇÛm5®Ý‚ª~ÙÝ ÕÿÓ|Û‚  @€>ˆ÷¸tVûJÒfrã½üG—~wq"z÷îÅù^ý†Ûd/ób™ÓCËV›§·‡ÚÌæ‰’ @€8!P¾q”qnªÍŒó':ðâS’Þ‹Ggh/8øÇoËrÆ/¿ým´VQSb2 @€.Ø|)¯RÄ¡^> +Y A¡ ð8޼̗q9À^¾¬Y0³ä£åvA"C&@€ @àBòý"Źåœ,¯r$Ó;·lG\ +x™x¢@9E”q9–^¾¬Y0ÞeÉ»e Ò2 @€'ÊWŒçªdµ[Ö´WÌÅm^†· +Tÿúj7FÝËG€ @€~"ß×zÛÜ¥Þ;]/ÿ“¸(SÊY".Ô›zù8Q@€ @€7Ø|ƒk“mæ&ý× Y ÿDcÛc‰‚ôj^Ÿ/6¢ ¢Èù*™v{ù¶R† @€~+°ùW%ónÚþ¶«®N '?Ñ2h‹Ë£9nkVÈTåãP™Œ¸‡ÖËlj @€¸‰@ï .Þ#¸I‡uƒ@+PýŒ7´m²:«mvµLKT ôÄzùêt» @€ ðsÁ\¼¦àçýÔ=Íßp›ìeü¼¶%ŠC´5m&Š @€ @€k6?DTÉj7:ÐËGÁ:ÁAŠª,ï¦í:PFJ€ @€ÜJ ý:Q}¾ˆÞöòQ°Nh›AéДGÅ @€ @€ï”ß(Ê+æ|™Éq/ßV¾>SÒµq5ü² :d— @€ ðòEŠã¢9»ôòQ @€ @€L|—ȇ“ºt«fK„ú•¹¦çÖËZvˆ @€ ðêÛEÙ`Š <ºNÃÏÁxàeM—gõòe˜ @€ p¹@þ(‘¶UËmÞç‹’¨§QæËøÈ¹e˜ @€ p­@þR±ù½¢MFñµ}xhk­OH•¯vSM›y¨€n @€ @€ˆ/DçÛL>ÔËljK­Æn&¤íRPK€ @€üV ü"±ûù"ºÚVÆ¡ƒ0¬‚Š¢:šv«» @€ @€©ùëD¾D÷2ãüÔ®Þ¹ñê#O¯«eY¯Fž @€ 0C úòSí¦+¶™Ü^~F'µI€ @€ p\ ·‰m>±ý˜s$Ó;÷xgT @€ @€ÌˆO@å§ž*YíæÎ”õe÷zù²FL€ @€ pêËOµ›;ÙûàÓËßdhºA€ @€ 0Øü¼Ó&Û̸YG  @€ @€î&°ù…§JæÝ´½[çõ‡ @€ @à¸@õÍ'NŒ?Ä! @€ @€Àz‚ÒXâP +ž84}&@€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ @€ pDàd3L +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 +x–wTSهϽ7½Ð" %ôz Ò;HQ‰I€P†„&vDF)VdTÀG‡"cE ƒ‚b× òPÆÁQDEåÝŒk ï­5óÞšýÇYßÙç·×Ùgï}׺Pü‚ÂtX€4¡XîëÁ\ËÄ÷XÀáffGøDÔü½=™™¨HƳöî.€d»Û,¿P&sÖÿ‘"7C$ +EÕ6<~&å”S³Å2ÿÊô•)2†12¡ ¢¬"ãįlö§æ+»É˜—&ä¡Yμ4žŒ»PÞš%ᣌ¡\˜%àg£|e½TIšå÷(ÓÓøœL0™_Ìç&¡l‰2Eî‰ò”Ä9¼r‹ù9hžx¦g䊉Ib¦טiåèÈfúñ³Sùb1+”ÃMáˆxLÏô´ Ž0€¯o–E%Ym™h‘í­ííYÖæhù¿Ùß~Sý=ÈzûUñ&ìÏžAŒžYßlì¬/½ö$Z›³¾•U´m@åá¬Oï ò´Þœó†l^’Äâ ' ‹ììlsŸk.+è7ûŸ‚oÊ¿†9÷™ËîûV;¦?#I3eE妧¦KDÌÌ —Ïdý÷ÿãÀ9iÍÉÃ,œŸÀñ…èUQè” „‰h»…Ø +A1ØvƒjpÔzÐN‚6p\WÀ p €G@ +†ÁK0Þi‚ð¢Aª¤™BÖZyCAP8ÅC‰’@ùÐ&¨*ƒª¡CP=ô#tº]ƒú Ð 4ý}„˜Óa ض€Ù°;GÂËàDxœÀÛáJ¸>·Âáð,…_“@ÈÑFXñDBX$!k‘"¤©Eš¤¹H‘q䇡a˜Æã‡YŒábVaÖbJ0Õ˜c˜VLæ6f3ù‚¥bÕ±¦X'¬?v 6›-ÄV``[°—±Øaì;ÇÀâp~¸\2n5®·׌»€ëà á&ñx¼*Þï‚Ásðb|!¾ +߯¿' Zk‚!– $l$Tçý„Â4Q¨Ot"†yÄ\b)±ŽØA¼I&N“I†$R$)™´TIj"]&=&½!“É:dGrY@^O®$Ÿ _%’?P”(&OJEBÙN9J¹@y@yC¥R ¨nÔXª˜ºZO½D}J}/G“3—ó—ãÉ­“«‘k•ë—{%O”×—w—_.Ÿ'_!Jþ¦ü¸QÁ@ÁS£°V¡Fá´Â=…IEš¢•bˆbšb‰bƒâ5ÅQ%¼’’·O©@é°Ò%¥!BÓ¥yÒ¸´M´:ÚeÚ0G7¤ûÓ“éÅôè½ô e%e[å(ååå³ÊRÂ0`ø3R¥Œ“Œ»Œó4æ¹ÏãÏÛ6¯i^ÿ¼)•ù*n*|•"•f••ªLUoÕÕªmªOÔ0j&jajÙjûÕ.«Ï§ÏwžÏ_4ÿäü‡ê°º‰z¸újõÃê=ꓚ¾U—4Æ5šnšÉšåšç4Ç´hZ µZåZçµ^0•™îÌTf%³‹9¡­®í§-Ñ>¤Ý«=­c¨³Xg£N³Î]’.[7A·\·SwBOK/X/_¯Qï¡>QŸ­Ÿ¤¿G¿[ÊÀÐ Ú`‹A›Á¨¡Š¡¿aža£ác#ª‘«Ñ*£Z£;Æ8c¶qŠñ>ã[&°‰I’IÉMSØÔÞT`ºÏ´Ï kæh&4«5»Ç¢°ÜYY¬FÖ 9Ã<È|£y›ù+ =‹X‹Ý_,í,S-ë,Y)YXm´ê°úÃÚÄšk]c}džjãc³Î¦Ýæµ­©-ßv¿í};š]°Ý»N»Ïöö"û&û1=‡x‡½÷Øtv(»„}Õëèá¸ÎñŒã'{'±ÓI§ßYÎ)ΠΣ ðÔ-rÑqá¸r‘.d.Œ_xp¡ÔUÛ•ãZëúÌM×çvÄmÄÝØ=Ùý¸û+K‘G‹Ç”§“çÏ ^ˆ—¯W‘W¯·’÷bïjï§>:>‰>>¾v¾«}/øaýývúÝó×ðçú×ûO8¬ è +¤FV> 2 uÃÁÁ»‚/Ò_$\ÔBüCv…< 5 ]ús.,4¬&ìy¸Ux~xw-bEDCÄ»HÈÒÈG‹KwFÉGÅEÕGME{E—EK—X,Y³äFŒZŒ ¦={$vr©÷ÒÝK‡ãìâ +ãî.3\–³ìÚrµå©ËÏ®_ÁYq*ßÿ‰©åL®ô_¹wåד»‡û’çÆ+çñ]øeü‘—„²„ÑD—Ä]‰cI®IIãOAµàu²_òä©””£)3©Ñ©Íi„´ø´ÓB%aа+]3='½/Ã4£0CºÊiÕîU¢@Ñ‘L(sYf»˜ŽþLõHŒ$›%ƒY ³j²ÞgGeŸÊQÌæôäšänËÉóÉû~5f5wug¾vþ†üÁ5îk­…Ö®\Û¹Nw]Áºáõ¾ëm mHÙðËFËeßnŠÞÔQ Q°¾`h³ïæÆB¹BQá½-Î[lÅllíÝf³­jÛ—"^ÑõbËâŠâO%Ü’ëßY}WùÝÌö„í½¥ö¥ûwàvwÜÝéºóX™bY^ÙЮà]­åÌò¢ò·»Wì¾Va[q`id´2¨²½J¯jGÕ§ê¤êšæ½ê{·íÚÇÛ׿ßmÓÅ>¼È÷Pk­AmÅaÜá¬ÃÏë¢êº¿g_DíHñ‘ÏG…G¥ÇÂuÕ;Ô×7¨7”6’ƱãqÇoýàõC{«éP3£¹ø8!9ñâÇøïž <ÙyŠ}ªé'ýŸö¶ÐZŠZ¡ÖÜÖ‰¶¤6i{L{ßé€ÓÎ-?›ÿ|ôŒö™š³ÊgKϑΜ›9Ÿw~òBÆ…ñ‹‰‡:Wt>º´äÒ®°®ÞË—¯^ñ¹r©Û½ûüU—«g®9];}}½í†ýÖ»ž–_ì~iéµïm½ép³ý–ã­Ž¾}çú]û/Þöº}åŽÿ‹úî.¾{ÿ^Ü=é}ÞýÑ©^?Ìz8ýhýcìã¢' +O*žª?­ýÕø×f©½ôì ×`ϳˆg†¸C/ÿ•ù¯OÃÏ©Ï+F´FêG­GÏŒùŒÝz±ôÅðËŒ—Óã…¿)þ¶÷•Ñ«Ÿ~wû½gbÉÄðkÑë™?JÞ¨¾9úÖömçdèäÓwi獵ŠÞ«¾?öý¡ûcôÇ‘éìOøO•Ÿ?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 0000000000000000000000000000000000000000..e522f8cc3c35be472b0e3743063e99cfe78abf28 GIT binary patch literal 6870 zcma)>2Rzm9+sBP$XH|5FLu5P4IS0ue*)l@r;T)TDoMErZ&M2f(R?3L1j1XlcBWWR{ zY$_QcBkMVb>fi6z|9L&n_jT6&xvzU%*L_{z7w@l#v4)m3L?vwtS5)YGGr7Vf$XVIH~VQb zEU0#?t(Z&jdBoS3&JRVED(sG8sKTZ%r@lTeAUW4N!MB#SFLWZaP} z<#iNikTW$-ya9M~vU;x74RXG-1>aUNng@R9{(=;4BwhA$#&CVfBH(o1&yQ49|FOP}${HRK?GE$;zdXa}@y*1q(dc#WCo+wHu zAe(6?)Rfq6{BiL3N}~_V?6roQZO#=%z0VDU-Addg_52d9E+^}7=x9Ra#!*%kPxF#S zvvOV1WjF!QY}LOG`KEGvrCul>aB$kpHPV~JrbJ>Lm9l!DZc9Isi0|r5b?Zy`mdTtc z`~Gr!(O01#xVTKGM~Qa1S=loxyeoX22O9>q1x_>CW0V~f4As3?9(b-l;9IAcQCFJ< zbY|1eZP7Z;^uSrSY9p>a={>#u4xacBE$Hc+5q8RbN*R+*a(X?rH1tfT9YL( z5QabkAqWJ}cF$U!ye8S40Hl=Be$8m(u_W9d``Dj+UCya@<8b$o+m1hXCR7aOgj( zxxtc|$lH5!XCdR*Y0o6-p$d^MU#&Q)feN%<#a0a00KaH*?3|+K^8=S#RYNb#Dc-iQ zRr{Fwm`}}whB}!_CjjIHJIAjrNL|6slv);9EpA&kc2?i@f~T8~nqFDuZoEOb_e=hl znWs;!z1YrL+uhy#a0+HYLqo+_M$H5Elb*L^8pxWX8r3pB)!>1<7hrF1AQIk5_tfxF zz-Q^pYo)_E&D5}0F0;~?&wY42**1oJy_PR#^kwezr_kAnQ%dw_Hl)9F2A#dCkUo0g zl}OI*{(AqZ2T}Fyf~lv)X1Q63Br4&sI6M_*Vm#6My1R2hPmZDhX8Fz3X}#U$UJ^Fv z@j(xN4lzq`Pl(Nlb45{Z+G2$>W@n)mFR0Ji_NdT2?}M?x-ORrP(pUlJMAPby=DwAm zy%RQF5SBJy5tirujt#zZ_Q|}EuU!(TH#t42CXzSaZX?-aYsocrqs0R8!VpMHINoYw zF02z=48@u-ez;vBAClr#A5tGw?^18^VBD-j*48$;16=@p!&)1~XtgSZ%>ya-p#1zL z=TdY{jv*|vZe3OVe)3j_w~>p1O>D=k`2b!IAJX`^)drT^(P!u*&(mHaQU2Mg+W2#o z`Dfqy6Rf9~gOw}*_l_x*o(7$;)r3b{)JmY#E~cH^$cRi=Gc_0r7^H)n{fO`Bj z{P<@+uXXvQ=Oo_+NYn`TNcooZHdKn#z85n+bB)!XR~6~L*j00WX64kjb(s-=zV4IN z%HqYqGeM^+EzDAwnh&RJLG_|^A9TLrg|ZIZeSGI}vFwOaiJ3>o0mt^TRP&SylOUmu zK~PIF#AQBED70)d+O|?Tb?%ku-Hh#rAnDiFLXOLim=JC4zar7r1|G|wns_fRk8D|6 zMcp%VjhPy#ByD!E7b*`uADoL%^P8HSH7JL*nqj*1C3RnO)@J~gk!|yU)3BafXvyr8 zw>J34FK-XYHhB>5iQo}7J#17wyfsu%l*$XhJ8Yk6eWQ(0iqSH|{& zeqbI9WV;?`gI8$ax9mG~^H|}J7e0z6dUJiT5~Q2m+NX57-n@nt0pjWMEEsmt8iZDyo4*XEhr>5CPbCT}I)N?;7v?$4XU^I;8>-}S9Urppu(47x>A zFCYZPuj-*XV-Py#T9(IsM~R&IFH4tCW$-czy=p90JF!4Ft1*0hqqo%}`DRXjtBHvn z%0bE;&3N`W&wJm7q0dqqUDf#?x12m-0n&ux$PrQ>2==t)j>z3_u@0vgmUPqhYb1(PK!YHBK?+dfR(&eL|IIRB0 z8``t3;$;q6osR0=E}n{sr&}i!c-D+_N`rlv+Lrv&tQilFMA!QB-rNKp2PXEIZP9!b zc%FAha?r7-E$q4eQ;7EDtv2^9hiE=a<~65?s>MU87pR#=X-yKAIQ(fpMjpeRxE*!S zKi!629n36&f)rj=F>pj?6SxQ8chzVvkb86fiJLVsaZY%nh zV9ylF@KpL0^JNs{@P%rZF{#IzcpO4=v`LYKqxFpbfD<^g$SicFcT)8n??S>_i%oI1 z!1E6Y4+ChGE=&*W0R_{pTKS@_2N_iHVeaO|N%JqPUC5H#HFe0W+XjP6A6 zW8qM`ZBuqQ2LPp%XvyM%JGs`Pw+N{AgLqJji}t77L(?`MvClKTNj%rx9XFC_?#{j- z;rXz9=ZNKJnMd4^V9wB}In8xep;D1^=k<`UF6&F2sOTPc2oBjY-l|7rkBC1n?KZ=os7+8*GfaU^GV2y5GTnHqTJtKpJmZebC#$yBNhn?Xb*raeQT)!C zXg|V-Vdy-+x8?WPK#yX{zT>>{4`MUok!=f?cV$DFipm|}OX-Hufw#S2mE%kwS!%>B z**bz4XXRP6%a6C*H+-ricd4p@joYUuBvQ`x2w!|mM6?;Fa$%c7{#B|%(F8QY?b-L* z3zb(7y)o)bCQTly5E!~N34A%hP(3kuARytf>c?h;n$ojXx~YP6K;gB)!ZW<(AHpA8 z@_lVLsLlQM_?=^?LxzSyG=!GcK9p;S!ji2G-^!n#zn zk~l=QsELcK%b2DlyGq70?JFv_$~xZ&l#KD9mr!WD$DrqI)*I5V4UIm6T=qMyx$<}; zOYs@R=-YkK*EhFELHL`O&OKZSeCnQ<%zJC-$_PhU)QdNCky(X{^@lUHKRPy1PiL1S z9n#Lc=S%%^Fev)s7**6MnNIB)A#U$O8Yj*kl4`0J_w$Ty?YUGh{3_y?1zK9T#x>n6337*zanQQHemcD9O6MMqBd}OP9^_ zEkx{R1|3Ybl8^H?wrk?l8&zgy;^=S`9=%lmZj z{V>L;x|2D)c7hileod)-+pJ#KA*Va;sZbQ~iE~uV3Kaaq*5LUgEzDb6nw!_IFMml? z*_0EA47PAOTxsCd5;1%vE_ppq>;OJ#!Xm2HjXIrqa_$xP)7N5hHU(mpK#Nb%epD}M zsqSX<3-#|G)Tb2)AQ?FiQ!zkbl$!VLm$$2xzFH4SCG&JPcCJRKr9cu*6I&#FqSSbD z!W7k>a8lF8-%07}jbR_SHJCnhm-T|D4od_(=df~q`ruvD7)P-PJ538o&ARFyIXeQR z&&Dh!K1iyQFaCm{n!37Ea<5PZ0MN;woOKBzuREG`Wc-m3lP=Y;#Mz1*9f()i`3g*A zuVa;iRSs3&(&*}sz<}J*?JN$N4Mek2akYl(qm^BTv5JLDxQ#WnN8^JGM$PGx=m^Q( zUG~f^>4@h>IPk(%?o(LZZ}vik0L{?5?wM-#0~>}`Qd_;=p;(%o67AuRbp|1UO~>{{ z(6i=p@RPOKGZvu4pkq@0E@e~#qqdQLuEW&~Pk2Hf?S1AU=r%K^Oj&a(;EeDgPJGV<8}GqGf_@D0Ol+nbX|><|@7fz-?qA4gU(g7p zox0+_Xa){Xr+&wh?Mwxi8jdjGa(<)}E5|D$KkKQvlx=n?S^MhnjqZeG>#GOu$Fe7^ zvus>>AuO$J8o`|=!Yuj?2j)^x1%7Ow9%v>^`Y1*(qx0X4$dLb@^Lw#1Cs%eEiSsPbehnzaFE2) z*De0V(;Zy8VM(suqfcB%?cGKfu%k%$Vhwx|iCj!O*a(a6=^A@TSgcv7a}xK<|EfzZ zU7_v!&2K^N!@U-}8e?9OEP?Ngh8DH#B11wCWQ3LDDwU+)IbTT_bzpqyN-I~O->;&Q zQxv0}Q^T3$xQl9?dy0}2>SYtOI$FrDDtA<^-0^GDI{7~w@i%oU1-+aj{x3KgT+!zb z7k*5bZjPBHekrAy_)$ssW{ z#*ssm3eYKsp2mJ>X^MU8l*AbMzz!vpC+v6?w=MnU*1P^9$#)p{q`{KvLeT<3Z=gZC zR=!T3up6f=AVIgq9XH~>@_Ie!j%nzzPv)Jasz)T(ikoLYy)RXrvQ>?Z8t+RU8RZ(R{6D57%$&V210cGlPD}Vay>S1jkLxwYww$Ta zD-)w>(iX$j3AMElraC&bP<=wUwGZJf$Fn)ofR}&K2_7C_xx?HgJk=61*0qiUbkqVx z!alG{BOui1c0QjJ8}?(l)Ov=^P|5W9 z>Ip!TZ+lZ(M=gTB6m_U`x*K1TeOpp&W>Cue9KM6VyxM)UZXD3xDX`_x6nBJq^a&Ni z>1T7m3Q3p;W0^ZZAb%Om+OmVLFu zf1)?oq>WE3d{v$)^iWz1(fB;;7=9Jb*h$NH%NxWfUbjFUE7x=g6n4ux~b z><4jvoi*tg2gTTEuUNUYm;QaEr^+UT*vh7{JKHhZ2dTCaWRpo;e2pdQ0f0XCP@EQb zj-y(*R?1g9wEs02P0zS#sp&}DTq-(@E6ZBN71}S7yac!oJd#Z0swmMF$%YjkP|x4} z-lGWze3uqC>UXQVpP8wdchc0F+npI6`7(0wYmndju=oAnVoJ~5NmX2s(*D?TK02xD zpn$Kr(i1C`KkDzW?gi^-T%oeiUtxt%kkl{Ovk#Rh#7hH1aKgLch*`A4h*<=r2A!I0kj5_2_q6pc9r~w zlf(S$ZEO1n@uTp}zmwpfZd3f-59a^ruckMd=~G+){c=J2%-&@C=Y~d+<4=wkfxNZ7 zh@0$VPcy8!w;SbY0FYAb|2UVw_D3PBguOZS+|ZPXDDc(fH$NqjLj?K5LCBvEB-F{z z8OWIp6mvqk;juu73gGg{!Qx%S_p{g-k42N5$j>eQ z|HJ-+h9ST3H09*?%S;_b&T_2Fo)3H8{G`MG8RU=0I5Uw81I`5geE|`0I1CPS2L99# zP#F1!Nx6XDzcercL3a0F8W=)8A3&c?3N2x0l oES8)Tlylgx4N5Hn_wr&d(+ETqp12orgshw_lZc3>krvbc03GOgYybcN literal 0 HcmV?d00001 diff --git a/doc/images/hmm.pdf b/doc/images/hmm.pdf new file mode 100644 index 0000000000000000000000000000000000000000..38c8f06234a24f554418bdc7816a309e83da27a8 GIT binary patch literal 7242 zcma)>2{_c>*TC&0`@Z|y$u?u(vS(k%zBd?*Z5TtQ&|=A62w6+^T|$(7-?BwQku4%5 zB~p23sDAzaz3=n>zmJ)(d+s^+-gC}9_j%@X`AjsmM8RUxq@qe?q%-fJsS;0zZ;kl*Mu)MbOZGw|D zIcVHV$HGZ2{qt+9@1|F+j2@4^PH6q+{P~&j$Az}uYNx>s*+#!|<Sobva+hix&k~daPMLjldh5hw{rWTTIGmVnHFb5k^1|q zAu<8y~-RI$pd#?^w>rwCU)J@K;QM)QTl=FHIGa+$9itIvZQ3xj^IOQ+!!@ zrIbUFH|nO~#$iM6M>MOAiq&H7wUt}x4DKYI@Dlp;P3}QuLrr)z((URf{dhjzan*w_ z+y2apdGS6k8pZFa3le=?pXFoIW;3?mEwYfmoMl7IQ+B}y*FbTtsur>PZOH82@S8>G zwxl3>jAY0MG#&;dV|naC!SJ^`XQFqz*E{!c zqPI);R1lH)b7`MTJ63dpbbAjE`X~K#9!Bbrn>$zQ7fi{N@VVv#>1Ws#38)Hq$8h(> z$8dS0C_);E*$l}%0Fsb8zH}OOgX0Z>6QlLG3t`xdPo^w zPPNf}d}3qOX>QBt_Aa~}CHi%aUc|w~##oXeu=_gd+IY@%X?{7CPpc~P#A1+hKmT1p zJ^``GndPtRevEA5=X3o1b14^)2#)bfC?B!obHx4?I?_12YrNMvw0lDg(fbE_@aujF zG^9sk{Y6|LRyhvmBFY34&vF8wkMgm;p$z$T2y#h1)Wg1wJR#_9@Vj?pA4WK5J715F zCDz#a7KY1N7O-gWtgVazM9h76h-11^6mK?Y`AjN)X1%sYnnw!rb^W=mG5=u;0$T;x zH>M6`!7|u>Y)j&IxttWpgcdYO}SC)%oo05v}oI1p#Sw3r`Fb6I9|pnHTsB zS)xRbMyFr2MSgOwJEk$I$zLFD)QV5LIdD^`bWI8@p*@J3R_(4j`tUQEMx_F|lQE!Q ze$?$a?Y$dZ_LBW0xt zNy8fZFxhj$91_`GfkfeY#*$Xl`AwesgLTfM3SC2XkXTVtf_(0FU)-)5`4ZIpn=_Yh z*!dYSM{YE3*L4c+rl9vOI>N|Hc@4k=;*Z@uf(@evvf(5A^r`f#u)``-{%RhVX!$Nj zM~%TDd)*bU7P2e774ny;-i5z@j2fHQX_zZ8R@_ThwM~{iQb1NUtv|^v%_Ejt+5gmRH_t@PE>^DL2eAoP?Eu##a_2XTS7H z99#Fdt$|tuy89jfPBxj4bW{3*(S6&n_zKsUi zI$2vk?{eVc+pNF)9L_lE#Km|%mqtb89&rYw%UW@AThtXK#O;ghzUhFd6oc59j}wu-6#zFJveO?@u=w^+(;6n##~(=z>h7jG!jY zm!?C+GpxldTn2S|CU!jx4-%>L)0AU)-!T(a#Pbc^h3QVv8o5k}=q*YZ+_K}VaTk!Z zOAx3{G!tFHGYJD^`())@8&Qi&leXo=qLv{lo}=Y_&IaXrj6ZWVOG zoi3I-Bge7yaHD(K-GvgXn&}ln0u{K#AA+O%sH6za=Oz$Hf)MCJ%TmHV>x#s0EHr}8 zhC!yz;*}**lKY;ucRcpL_+)ME1?wF@*~)M_7HZ9Co|kFqp1rghD%q5SQVv+?%1ISQ ztx@El*LM%HcI$hRRt}s#NcTu`5snsFeK>DOO#6yw>J?s=*?s|tK_YUD7wFC@nik+| zdVWVr{c^ISF-mDS6E%5v#c-ORdMwL8l~<#|;ob|+c+-}G(K}KzK|aC@q~J2v{^1Wf zt-;WK+t7JWFd1czCG~I&=!DB5s+v z2I5Z&AKv(WCvhFs`sovsjZmRmKx?IMM~w&BV~@7DMkB~I8Y&&aVE-n*u!T2-A`xiL zABt(6=t82hkiD`>_i3mpQ&d}3^tnQginM7hOPeHSK?_Qp!n!@LA9F@LnQ$$V{fAW_ zYh&AY5+~XGv{9nSZUT)qt3%|h(O7@Ax5I*L0FpZP4OcaL_fILtvW{Rrt9XuTl$ znA(%Q&3!AGUb02@76Soz=SEY5Mk2`(kMusbJB0#;1{JoJ~@i;2_=+mt#5QGpmAe_YA%z zGKcR`2>I@AuSFY%<;5#mb3JGX~5$-`y_0TQl8<|oiI zB9Tu`f@ntC?Rbf;%m~6hnGsKS1-&GvyhhdraNFo}Km%j8HN}TJNG|)&w=`zTF7h0( zf|D8hg=4b2p~E0T;`nggvJg%sJmNQfgL-f1y*2!DhqdzmOw9<9)lPU^h&*h)9xd_Kz7{b05)ch$2|bXQE~U5Edp0As!0(a(PhIFB^M?t{GnVS z=9Q{1j|x}u0C0E%;(4F@E9$xEC$M+%I&i+rI>Wx`nh^A@{g!sI)%6K zMEECA0=Rt=6lkC*lOf-e4V`zMhyCcVow0atyYDokw(k=Z{ax`&jHF+fuZ*m=%eXn* z(u-r7ZHaMLWqBb=@a@4`V-Z4yy(Vfq&#B|`W%gG0;G=@J0y95>7fBi`{=<{B){kK? zf8b|DR1#!y%;nteQuhW{pJt;I9|mQ~@yiO#Wx`C28a_$ob4g#&F`C${3zl?c)@x@C znyjC3waOZP!e&-PCsdcu&b+nYTsI)&Iu&ZA-B4fZ*|6iOSAu@70@vfooUkx-t|8>I zUa5~{mpM$h-NnEoJM4WSM7y8*;lP?jNM`H~#2?rHDZ9YS&a~~@hWtJaHTI96JXLwc zpdQf2yDFfb#2APFD5-!c4T?N^;(HeF0*{CtdtOcUDoLqCFSGB?oh-M8D2RQ9R*&VGi|1|Pv6NX8a8Q!t+1bMy6 zwXtH_){AwYXI*n#lJlRoJthyJcvfjz?nsq&F1F zENMRzH1w7FV4PC>piMrtU?V4t66&%y)lAislF!j~$A`U)mbh2Ji1|sc+SNWe^DY5( zztr=!zDT<^sM1KXd~pYKvyG(DG;!}Gl=p> zfy+^kjOZWSFIQRWS{?S>>UdZD<6HYLySlleq1tU6>P^m|VopX?Dvx!x&~& zX_J2ZpdN-M=d{zZ7FgM^*u!zda24mJK1PMTi4w+G|`E8D(zEBdR)lvA-pX)X)l^MXt@hB$AI zE6}=4;m#L=KeX)Wls<8)zdgwSIV#FhdZAtrgVz+F@_oa@OgmfwuStYYsKP;MrjYBN zVYXW8)Avq7;mbm0725n~Zc|^uz1k17DFzxpUj~JEg2ixP@YTbGej_bGsFrRD;Tvb0D#X!F~MAKD0rz5sKcOd#;L7 zc^4ll&^3Ecn#Rj6qBBG9YKxCNuBQoMW+qcTLA08VmrB5MhH`f;( zI$NIJzO-u+W1P*zbC2^(GzTJ*iD&MCs3U<&e1np((J;W;@r=fPoXF3NaGrvTzKSc1 zeqQfe*|)Tk(S+xgT3#F%YLsjxBi>mP^pw@evM{M{H+l?(_&-P_(DF%B*C}s*;PK3t zj!~-x5lx%G%NZL(JA7gJg*>KU$bK)3lpYW^EX za&oso$kU#_(7A5T>5`@IxKs1F4D_#dwBDNfvu4`Zu<-;uSc<*2#HDK=!EmJ|!I`+0 zGa1t3j3|^Fx@4dI&W>w@Y1f<+(m}Tnuz^%gkBDhn(sZh_cG!!O=#e2Atp+0DeH0Mcl{M}RXj%cAu> zU5qu$YN=r*7%BFORzr<){)lc--u2CQB6^lp`7(At9$^%jE#0*s55h)zMeADnve^b| zX--?U`rCMP^;{oHJ(U#-%3AVD$h`w^YT)}mF6*T4vb2B+TUC@??9}G|vOGCsCR!*?}pJi zN%kGb6?;v5d9En+WijFCPL^{P&#TB5!}(Sg@h(<|S#Nw+PL3A!C$kJeDB+qG{jitg z^vSXc>J8VMj;grki=)>R)bVS?Uri{~7;lhXSknubI{P;7nPS?_wq>t53nxqtyIxZC zyhQd)zx^QH4ZYB8vrBIo5=rlrRrst-9Oko_Ym;K>xNP$|oO9Tz390;zF))qa@NXK0 z_hi@Hj4|#S2bWvZFdu)st!<(eWE>K0iW_fs=|!}k4Bl0NYOVN-70)Be7j(D`0SBr$yZq^_X3S6U~M_jPq4kiI$k=>sN5Bv}K{KX=%%BSN6I-^eLq=v30 zR)`Ij#7U1jGysN`{GZXmSeT&$FiX(&bwglHu;dg1bBAMCEGA%T80HE)2^E$I8Y5j{ zNVu;%AgJq#@ez(f|L!si^z-wE`CvUiaqAD(`cJ}ula!v8h8183!k|)F35=_lk2EIC z*pCcmGhp8i4u9ZFES&v&BmCQStk0(b{eOMF;ETCO!MY*-%MDSTlfh1N=L*H-028wS z%<@j64moAG<_HU4IQ9kxz!v?#a`V^vu$VaDWK4ayD|R3(NrwD}!GV}Cf&Xw2{O2W* z2Ig)Dv%3L77bqNw0Kj5kkeCD@=z&7{DTrfuHb&@``qNOz&roos?cxCXjl z?u!0r5e4g|IzQ1H3Imy3eATTD$*ym3@5a!VRw@gM#`fpo#NlZfitp^7GEt8g({%bsp z2y@E(+g4g0^w(OXWHZ(9@+im7kp$#tI@{4xw1KWuG5 o5D3hkz~{^6WrZ(k;UCDK!UrwySoMr!Ge<@!QI_mgS)%C-c8;--+#~91~|Yo*)(W zfwej4BTvAOP(AAs zzRjGT+4RRqPDk+r8DW$heR*Evn^;r{ZFzCyHyfYn^-n9r5srOKSoa58N`)Q8joEx3 z+z(qvh7fb(s0C&Gq)vSzk}3ikUCL*h+AEwz%sUQC>zWiPI-sk<2OqHv3S53p-}?TH zmOam^zp3?IpOI7=S)Hl3qHPg~+y3n}f5yx4=F;a~q_tG~!D+Gm&tF5st8W3jYVetof>vPyS5XKB+5WE&6-w#O zCeEUC-wUf1h&xDZiU({b@yD))EKl3E_ZH+5Dd^){Iou<3edo$*M!s3MtP(S+b034> zM1L+a2YwnOLfo~Yo9VS$JN>n)s+~y1kb3O8Q<2%9Ydg#KTOnoWXNQ{! z+)n^tptf^4r*e*WdAx8C`#RD4upD5kjwq}((&(h|%a9|_Mw0s6)B0H$yo0+9wgc|O z57*#eu&dVM;Y7-067l=oDJco*N`fcyf_D_DT*`O}HDYJs2q)k-dKsA8g0mjF$mKOp zB>?_b?E8$!ZSlwBG?SLP1WqkbB#0V`;N9Z^47k|OQ3UODkUmI{7Z51m+W_`@Q%VyX zM4o`(8*705uNm+s-v-ywQBS|nTKbK2NX!nzDQi9h0$;f}wyl^xm741CFqUy>J$M`Q z`Q$y~XLEe)JXi4Z#~Q<}oJPmSpFDwFH4}q7wvI>Lc?3)2|B|H}|I<%H0UK;MzUC6j z#VwELBtiWX>#I+c*%1GyUt?kIbsNE{#F)cngqPQ(b$zHi3z$?p_*m$j>Fj)-NyZtJFRNfD%0xLEzl(!t zUFC|ES$)C?r_Y3cK~(l+UH>^Vh)a|#w5qp*YJMBE_RM$4PiuRaF_<)O0DDwxS zin5Tn1iq^WjfC$5NR_c)U^|_tHPqo*)MACyx_x(Xy~`R?0vI*B_yLsFqA**D7xF7> zA1fJrpXE6^kh>ejg`FauYB_ zbt1@wJzT@dJ$ykx#C44gEoL-~N16Mz#?vycH81FJUlmTSIakH9Uhw)J3c<@K8=U^w zKESF$y1Ipir&<*C;e>GKq_ysBR8B4+(?K5(Doi4*e|(|I%Z-{*MlWnXp{gd2InUlq zzWmGVx65a+JG0Zj3E37GkuD(4!+6VjBw&Kf$vAZ4WAR`B-jRLv9NoEw`xA6-6npmX zrcQw@Hd^n2Ai&25mn9AxWgb-F0qrpej2Ng~u)+BLZ83t4jOd>&HgO&ore$q+#@OVK z?R@s!(f)Q_q<={6ihlrgrAR6_e+G5M94HMb;9x~(l|0y21M_BHVETIdrI}*pbh@F$7*eJod~mo_ zf;}YDao##?IMMR{?nO`k4W<$GwJAYM)F_df>QU%ZUVKsZI=8D zqk|P--&_TSP4Ud{D9sHVqcjRG(!klNgabICAYOoR#J*m{*B6)Po;ys>{7!@7%`!yO zj}Pv|Ox@oC>-%6=l0M+>YaYB6=DgTW_TQ2_Y`nLIe^Tf%<}Iu`74*zB<}rsagx@#y zQEKlDLrChUZl{^5545+YQ4HbN+0k}lXN$whGj7%^8NqOro$^eYo*u>1B;}yDxK)=sEtKHu_pvHyLadjT27wobsrr2r#0+ z@#-7vrJ!YAu!U-wz41YW0X=hZkNcoVCY(L_(y;PdeHQ9MB>ns zlmWh`tqiliz&Wb*j<2you6DNE(K@0JXcCiW*d=s>Y2-ASR74nADS>&<|%aMV#h)L!u~O6m3ubTSjXzYH7`d@hxt7!bl@ z(jHM1PD)#qy=AggD5P988$&TmgJM)IOf#n+yV53ydgDzp;`|F~3z#~paZ7~Z#Pb~M zGgP6(wr}Omp8$%s8VrT;^M_)6d;zX*lSA|fDYu0KeFoGA7SR@pSu>Q=oi1bQ$r<#HS~0|?I@$(e9;R<2O;a5MYVadceSfBG zqKkFsG(o3p=QNpz4P&RCWp3_ta3`GRIZM+rUy3+7Ey*U0-KCSgGB-lzL{M9o5;b6S zjI#Rh7G4JlE?z93Lzp5KBJP_uQi$2DNVm>LXj0Fw1{}BoeY+AZ7t^GdK=FfJX%io9 zwqPl4;9L2>_^ohi|A}8o?RmmSGwg;wnbF?*#K?HgkF5Mw?@!OePqUhGqR4G407^Jh zM5gZht1@Eq5OD!3&{M0E!;iaJI+NlY0|_!Dc?GY2eK}qG;RC3yY|TY{A=ReeJ{n7H zA_^18*GD!(c5syBn1+?@qU-j=+S1UqV!Ao}S^Zd~$u|`SI~A2A8euGA&0e*{DPCsb zRmLpWNhiTz_F10gu!Q*w_22Wdk2a4a(Kj8HCHgTso@nZ|uuQ|r;%v0N-YoK>4(lUm zDMSaB5Y`8V3npOr`H!mLIx+_!$5|j zVl;Q+-^BB(niTt+?IjZzx(kR7ZX$-9z)Z)O$6ui%`Sb?g4< z7ti$AgxSYo<5Q2-AA|DpV7U)a{e*GLF*kj&>0B`9LBp<@?TAjo$Ww^0Z+fu&Ok`a) z!I&8$sCWNqlqD})sa;v1sgf%7?v74Ev-Un)liW|YHfdIy@X2mAZI?RzO)$LOjG6wf z-fA@V{?0U-+}V97c6$)KC%&ogYS&~ zjn4v}Y~DG_4?eijP59+1f^Puw%s%8{91dT1c4h&)Cu_B=N@?dJf$eRR$_ZuD$Jzae z=U3ym(^smU4u_SERYTs;TK1iCzMXRGvXj~kL+Nya#69`sLnPkFlJr+Q!6b^y!+{Sv zPjU+Ue7=W_K>`&*s;C#mjYP#l&70|5rO@25ofFTj#yIlQdS4%Nv--901qGP2g0Uz& z(gLr#FnBEH>rQ9o$fJgfw4@BylLXsD^?fIUXhd3o-dp>rlf4yrl@8QX(hid)PAvxZuv zxM=|Y@Zbdl2C+nsF~aK4*bwF(((+X;BP^?@zsGcjsCkwJlv-8`d;|Cu20FZea-mjn zMXd1>wCu*O&0>s>vUXS0I;@7=Wtl!)_E&eO@+&K1NfM)b67WD|W%&h>iiy3@|FVB8 zJ@-%c%YR_X)0o!+GX-Fch|BX=pkSuT*5<&9a%~UQq`Xmh-02bB=9p zx6AR}c59B%=RtKm14WAxpgcnBaRgMsNOCQibF77@bZV*s*NG;X&l^U1$$V2^AE|bJ zsx?NC#oi)5&s$abk7?eWC-arnHO^Z)ZWe8ORTq0qG2PCSwU76T=|+Y(W1=c@7te?* zndiSHo;^{`d+0hgQBzwPN7qe0F=uR$gNq#tf-2L(kwQ<_PHBPzes_};M?b9GI0#TV zUpLD%fV~*bxcZ5oGnO6gtc8^PeE>M}trc*}*a>fWA%xg@gAS9&hb&)s{|BarN)dbUua%DISTpXjNDT<_mAib ziDf#V%ESPas{K~)$|EZbWs8`aSD108QW$N6nYmbVlF$4UzL1$Smi>*awVF=BTv$@LaQ8wt?fV29TcxSBOZ7IgRr)R|Gy z&V2}oxw6p@J%kW|b`!IB^@S%)IY^s5ujU89>&=FE<21Slf(1ayq=>!5RG#5+?$aF^+GH3tGI&%G6lX~3+`!81b-a|5LFAGNT3&`0LN$C`@gV0X zIMK}~OfTt7x*H4uzS}s8T%qxhxA+sk{9U_Asu!JixE36QatyanN}qMO#Y}X=@UUht zd~Kt~m4L{8!PB6Z`oL**33~<{gc{61^+6^8+bvw zY0kp(QP3biKm-T{!X^Z$lu7L)+9VuT7+sZ#QqhK5PUv=3gHxAppa$Xl!MWi*!!e(Tu2$=n_r}XhG|H%_@^0{0HLRB6s?$?=%mUdcCi|=TP&dWFTi*;XdjE z8bs8KRf}nkPJUD&gYi}&2e^#oxOkZoO@>32!&ISK*)AURgK-8O`hr6Z0t6e13ajYC zC<-cswQ&WKT60iYVvwX(@$OW>Hg|EA{O>VnSP|AsnB?s%ISB)NDE2{6fT)bkc8^Y# zHz>i@2Hqxkk1m<1X_t3+?hLkeMe<=?D z`61;2azR(4GdU<^gTSx>^LPCcKo9_K%!&L=jm0NWX=I(0nL8ByU@*iJ?w}W{+Xpv8 zBx-4BxScNzbrGWM95u2lw_7=vhI(ncGS^MFaPh0_+kszo_gZ)7B)c$t1@J!W?cV`37T2Ep!*~;?K z<`J+xITw899rDX?VxnFipWw%dPyG?W4-E*|I=$furIo}RgOZlbxi;vxPYgPx`k4*e zSi#Bb-)lQ`F#Ib--KPK&6ECms_67P|ah~QSNL7oJ&-cE*R@R=2&bHBBfVoP`@UXV7 z^yXR+bbu-(=6K0a#b#33Lf1E0dpM$da0lW0o`nekW&_;J!?uhi8aI#AZuK=m5@6>jy7bYpHbQ`KLMqsSRP{>D;6oD?F6IiKj1>?G__=QVN7-qDXq9tCmHMpv+2zGk%l>W+|4 zuOvG(*80-@%TjwOv@~)c(E+t<{1EBLdR(RO(g5sCA{cQBq{?~l6z<|>O@tS|YR}m; z=hRYV{*a>7P=N?M;q22MKM+M8AzZ`CZx+M*!^GE_r6Ce7Pm8Yr$2`>tFLc!J%2)Zh zv{4{_dmBCmY5?-`w$4cmD9NPy)}rKs98K?)0=qv%$fF+Xmw&raDH~A%zcLWs_jO3) z6k%&93TLy4%{6pCOpmu&AT*}&=2%Y%Pjvo+JtN}RGi1px-!;Dq4A`52*M%S|@geM` zf_jemz-GqBG}#Zk4OQ~?KERQfe^u6D%A(N7zJ!@*x#pQnWC`**rQs%V-BA@$px_pN zg!^Pt_MjD&`B=Vi{!@?HiP?gP<5(^*el7y>33QMofEC@Qjy@vc8e1U;SGn*7aw&CR zCw?-M%*GFq#YI;~G|kdpwtm3rbD_I=(y;<{_1gr59982OuMAIC+Y0$GG(gwxQi4 zsLI_J39T+FYmuQadA|pLFgJq31QDNN`6LhgkZ2=LPU=E9wO3}M%6FxkGyLl>|HQ0nzNVs|y;OtB)er$9NAv>9~`yCvLwXgF@HFtW( zpb6dhnSuS|CQA``9fr(yfA zb<&qj8g%blQ&RwP0w0J73P?9^l6V0*Vgj<>sCq%j-|H|W?L)>DO_rp5bOmA}HyaOT zbgVXZLj61<{|X8FwFAoz5mfE4z{}d@O5<5KNbYsTCkOP`b9wJKMP=+$m_({|VI}2O zjsU&2)aifNfkG7HL*HIUE_&U34-_XAX|5h;v0o;4O`j$6MX-G;nJg3=28%pE@@PX< z*_Yo)qCc{`W1Ef_3l)yYp`^k5fQ6-#Ql|=(P6J#ZjW=73Db8*oa<2k4$%i zQeV^@p$$rJtzNGXLsIO3*;PxU=X|PW{(Eiz1P5&E8eDN^MA<)@7tJh0AY`vQcG>BV zIZl?LP8NzY2l~@>xVzm~{Oa@>a{ zHIEwy^89LHw9z!eJ5=lQGRlm%!D}-jJO36!BK(8LW_`&${drOCg$rOIYKYLbP~V}0 z=|s2mBA-54yGF@z`7EzlSfg(^VtCq~R(SV@p534TY)1_$qnumF2tX_^hNR)@VVcALK{BgI0peBsp}irSbt%^x$^N z=s$oVE5ZwjvM(DHwu2~Uj>iXwu0N%7`T8Vw6u0hQ0X4e`H?SX#@1 zVOv;E>mI>DDTC5Pd_ocb8L1}De+t$wo={-)k;6$*zUk}CjyRp%R z@2edH2ONWU-5Ka`MjP52XgdcBq}87mK5`3dl7ocg-?f|<7l$ZSy_>Ha&I}W6wV$!y z(iXy_2L;A^uN^=QB~38xqo7cf(FJPTn+e*#)VQwwX~?%%=1YVyr4}%Ff%3lFR+HE- zs4~cV`g$|M#F$%b9{HAuMwpoR5yalepT5~02A^Bjmw_R-WMcklxXZu{Ka7IN2$FVz zA#x!^?UFu{SPo{c6aZeho(t7oi=q|#9s1Ar_*@n=Tg+NPFdQe$O@*b{MU<;Gu`^V`9-gvp zEyO;2E`qE!43w24z~FOV@Nh%}etTt9$~tqI*n5agmI*nq$L|BKSNX|KhpV7Oyc$0{@>m?cdlLSw$|BGoaB`i2wTwz z#D$FWhnA}pQlC&8F8zE%6WD_`Z0xHkW2CUXR+`=FS$Z^lmCeto_y6?&C; z-un^&VADs-W89MPPHN=ok!a$ZxOs}c`%g6K(W=3~0*NLet8Ko@(Ur>(?#D!C`r7?s za6xOD;TNkAmrRp!ey_WNNV(?S?&Tp5Nvx?DFg5V2{?9}p@noO251YB6uVj6*uf@PN zCa9>2>J}u1)#KiUD`?Y%3S8IsR5-bNF14XPP8T3&{rlgw>G*m zmNLkLiFg2N`9~@>uU^SN>`GG1jErXfJDREy)?rS44Ql-D^(ke(peGj+{*t@f%XD^O ziT$qvq|}p;&D75gZ%z7>sH`7l1TANJ5qhto%+c3dSZ#9= zXn2wMoovA?X;bbUS(X+W3XOopgug!3XVjj8J!324jF(uVhZ}R+JjP+bX7H<*IPwqA z8EEZ9>U8zyYeZCQpw5~`9!Kha$X7ksO&ksu|jP}CLc^mX3oOhRf^uE~sXZlIhL!ol5^$e(JLdi~du=|MUy*uBX2Y9SFa`hhRfj3W<#?oC78X z*3J|G;^Ts_x<3>#7s+_>k}%}e(eCrbH}3K!K~Jd-m^SA0F5X@D{O_~Hm2bw0Jw}$O)qOra_Z^iQ=UAT9y0NqN#z~p!-qZ}0K z1cgjH#MjR~b|HbG!$=z5aJnDQ_CfM}a)9fk#L+Ag&sPC<8~!i(M5Uj-u=ryedfJMg zwB0*FYAbr6!bZEDgMPQ=JJ^cjjw+DD-eKQTIre}H>x|!=K6M+$odx1dd8@j~F_`a$ zcLf9!_6|7y**&^7SXk>?=nhgWwE+cU$dfDZW2y$S9-2gj$X4bdB7<&IheJmx_c$AC z>?2Fn%&2k9WU$RLnb_6nW^$q~vZ+*IS4(A7l0(UGf4r^NLFNN|kw38#Yt4q=S;N|* zO>lmLL_1d?JEPjFZ6N6NR*ks#3ihbrj_^iDi^G^NpC#zcohKuf%=8Rye0V1OBb0;W zsD@aoRuiOEQ=3)O(be6qxnu~ZPB2h~#H#+aZn&!5-6nTe*UpD|hR&tkeTWcOBU@wx z|1Hf+$G@pdE6hfW$3EzGyr1ax-s8v+D77Lcd6-YPp-c{Hq}=zBIa8&^0*`1rS{}5^ z9MHuKw5f;p3AOVF{79U_8|s{T`{O;E*>>;K4&hx32G1rBgS9=RUd`8jZZ4yoK>L{) z^|K>YL1`TU?@TIV>}>MZ0WoDCH!;r^^qY6G2PSagCp7IeE*!y-_qTUb7j5h58MChT z=!kejudTFt)6_T76g#)30>3J+K|#X>HVD`%U)yu&wUhR`w25g~z5 zv^8~V;CDPfA+N`8HgRH5GI(wtFEDs?fh^%&Tcd=ZDtix4hlbb)d#voI)3c|Z91;wL zsSA!l!0z3ZN###-rs_j=tB4B8{m)Pc4>V%~*;7}1?`^)Chz?c6WIvMSV_4GI^>2^Q zRrGHg{qRIaL-3#Z$j)+syF9jYNHmmVR4!k6CAtHioPS(5dTA4NvQ)>M3%M&%-2$63@WOFfo~%plKDHyi^DtmOK6Gwcj}yX>3j{)BFL3Y*DOv$}@h zi5|R0dnwQuZKQ+PCU}6HKi=Agg#pTVt(xhhhPzv&dl?IML@lQ9;@nsD~|Q+u{!KxK>v!_6JRN#0HZByItS4Pki$8WEbBo(aPNCM zG=Gv($4hL^*Tz71h7EO&TUY`NqUoy6pG`I4F2B)0TK`%Ct5D6(qKmiNF7VmmDQLZU zf0xrfj{&3gx9QM2G1N43#;xwJo{k->k|Z*z=gNQw64U1v0FBF2_ZN%2u65`rC? zdG(r5)Bd{5SGfuDt(2(B*i6f2@C!)Fa**j`Q)`ra)JY8nP?qL*v~Li zs=javi%cE%3A*9-OXRC6`>B>Ax$D;`2JM$90a@#K7$Fs<;ATam>taQ+2WqzP+Ls}! zEEpiC*<%EbU3L3YBMRF}N)U;5L><{5ze%XQt*Oyjf!?jgtJt}GDW%3u-n6Iq6z%>R zdvM1RiFtT629^|5LT2xIjf@Cz{D8f_75RUMab6*NImQ0WX$;{(tb0BXdvxPeR<2nx zY|3f*H&8hOEkinaLa`5e5WCwDR>CK>bM&E}KIc>zPVUCC`FE7KNTig#^s#CFX(N{i zE>-kF=86IvC~U2lGWRbUxXF@hus5k0>IS+OwnSXnviPCfRYD=kDean(u3Tvzv9r21Dt%}qynj2gucLUjSe_nR3Y)mj`JS^ z{No`&{w0Weau=Kfh85128%2!4Ca^E6JeckFAt%WZ2YG@lJV@%$fboi>`j>{#8U-N8 zLI`7|9(6#{O#-6rZO-sp#wtGIrqk%bVmf<(h*bZiGWnU#haQuITQ-;fYdlKL2x;5v z@^hg^zZ|2~O94{ZJFBGYdk3-YD4r>h*zhG8YiZ9u87{ZSXPGlf1iOVhfBN&2mi_Oy1q_Q`V6}8hZ zDNx6Gcwmy>l`j>S8pJzs#r{$hq_4U21CxgT)6U+&=hDA<1q^CW@xWxh@qJ;AtPZ92 zVfpxBu4Ae7%a4*-%fd;fTaSWsCs+#%7^X8kB-B9HdA`oX%0mcusRX7J=2py@#_EQy z23Z#ykXS2#oB~!qU?aRX;6uxKm}sxK@W``7OhD^6#}u~#BU)DB)6I-}4l@&XS8xzf z2BDThWi%Xo&Nlj>$l6{lMndy%9CgY^^~?Zm_8|%xIpWUVxnDObq;(Th!C+$HE?@x{|RfQZ~YZXo@UH zJ)azkm9Mk>m*6d1nkn;SVC8Pp<%*g_p^yA%&rxRN*AubXXk1LGNDmifByUiRdOidt%uvQww)-2j`u&(a`VSB`w`TcVit}|%mxzSa5c*AY zZQ?RK(C$av3V3{F!!boSUZ+LZXO7xrx_MgQ{?D5bRs|q}d@yAv6f&pagegu#_Yb-7 zE%Y4(3J-d|j-x-KXJK2V5qr}j(P2b!;IUAHx5JVpSO}%;Uth>sQVn$SvT{E6Y^s>r z=w;x=Ty`Zo{{rPP-C7utIIkRG{1pK5h19%($nvdjeB7P@3X|mzYy4uGFJ9V28&)!T zY`pl7cfW(FjObu`dbKUOP-JnALKxc;!|y~iL)_=>XFp^HyJ}XoF4hda#m33 zBV)CNm{GL|q+1V3n{$Oj#svrJT6F4qjasZhmd2t=gI!V?k~#=YH{fQRtjG6I!T&XR z<-}e74#E&D<9}gTLfWg!L;i{7+2rRevD_0c62K7M+6!*Ey%?rZD_Q8nxa^UW2XI_6 z0x5D;Hc5o;ANm}=`JTqR{#R4te}DN(>NHrMwkZIhnDa#7P3kYnoTvC1`SfLnmESJY z!R#(`(?$WMdH?&it{I>l>1w*wT;Jv*NA+6n&XpR&CZf8L&xnc#4^rkR|G5j@fSsw?r=Vj*vKwQ z+2Jc}58Ze!BQ3*&fl`?~AJJ#i>JoF$&A+s>IeT-sDrYZtArD+3?R-rq!;lM^G~sOd zI8W_M;k?~w$@17Ppp>^VH{kb>*pwN$LzqW9E(U0@e{@#1yXpxg(Pwx6pQ6u~w!GYM zQ4M{Th~NJ~15Uj8OXM?}R?Zw1e{*M*ToDrdH?l=9X~}F1V!0zmc*yrQ*`g%E4>BJy z=@5Ik(-~_4EL7EN0;A6ME|y40>>m z4^2!H%>j+p*)E{x{zax!t44*3^L=X!lJuVqJ2(8jXe=$ z0h`AeDVx@)THhFST6@K)@v~a!Cvt@KKZmmr-vwDJ1zn4?qi;SkK{;kK&pRKjM#>N8>Tw)e6#}c4&Vn+^nw6s^JgZ}(i1n?_&NU* zfKfIR7&9RV(YN=>Jz~I|zU!vqlS)z_c!W2I(oZR?oI6Cc{2S+h1!-78MhaxMRK4H% zoj8YlKC>HrlaeefnQbx{Zg4j%lclESn3AfcLbKu9Tr*`g=1{NF^erqzGLuA!kKZ$K znC>%wA2d9tX+v2dvJZ8gC}LA(fi=#$;iVA^j*vi6}!WH4&& zgv-*J^%uZi6Z%g4a9}kIO~zBAh&-s&TD=ch84cEjhnIzb6X|2^&jv zzz}-fZf#q}s_oS+vk$!;2CWb@&lHA>(rLdJqNL}-_#_<3y~qS2W2 zF&pdct?l!1^e_P1+aF|qi^X6&&cihltBC9PKV%2Z0N;Wflxa1oTCC|_x{p9pQb$>} zy#7?gDa$Y%Yj|OgHDC9L3_K8A(u0ebjU8u(s(_*rJu=;; zRu65rR0{V<7Zyv(RZRp6^EPNao^Nrxqm*h?o0Z6;S*FFo_mYo-}4I<7n ztxgz7=mmTXjn5EgOci$J%pNYCo}ubp$v>}~k+I*k4n1RT5!zMdntAsdWf3#nrp9>w zcA^3lQ>zG@;d#eqk`3camK%92#;FLv3Q0zfIkHue`Di=3uBF71GC(%n7;y&!et5-Ap(@P*^^Gf@g}^l6 z7`WO)c5w3~cf(l48SJNO?an6=FE(ZERyW`asIdGdhq-7BtoT zXa;&$%-E{e%i$=$SwPx=qPMYGjd3|}xGujk_4OozF*Zu%ywv%t#9jNEV+fNqiV4?s zAZo}SfmF?$kB>*qHaQPQy%+({v28fdRo8??*>-h`uHtL1oZ8Z_^DivKFadsjdm<$4 z2I`DqNY&e%^;O$u;R<1bCJ{vS*?Px6$$Bswel>nZeJ>(*Pf^cpn!nWI+YaZ{xk-HT zu?=OBA(HWarS@t*Ad#}esYf&>vM!+KaMiPR_KEvB#dHj`W#dy3GOsrwU~9l{xVaWs z2fv$jEn}tk;9yB9R#}wVwQ39!F!_O3v5RkpBktd%LodkFi2*FSo&FxazS`VfVPK48 zY0~5rrlKn0K4O`|ChX4ZI2DR>IYK0g-ImM@>#NHZcDhR|N}{~K!gmv&rDFbrajS|@ z;I$RTWIDyL_rAcy{>Zp~W|9-FMem~Cfz~vd}6qR*zNccU4aAP6Z#}PCn zM3!;h4_xUcoJvl?p&kmS$xquXi=BDCu;c>u$9^FH8lk@+@ui2v?76Z3{?4rHrKm~G=gkvrnA5A~;iabO6YGdg%157M zygyU1k8bvgY+2iqxSh0pTHm&(9iJ*Q)W;l8DwB3V^F=%>=0x=xF^-3oKYlMDG8o~F zeOj!cGD21u8d|pox83A@u;x+T^w`ky`vm;#z(jMko-(ACD>di%nnv<8ZZ=W>B&B>g zHeMz9Yk|*X_((Iq3m9%hq=I^w(N?Y8;4(WNyG2p#syL`Pm8OcEPk0Fg%0}YlD%%`6 zQpNQ0$hJFdodZlW1*>Bh^GY8-VgP+8$J{)$foi4Wbzs#$Fro(;u*KaRn0wlpa{IgQ zqGwF6!9g?lEcS99TXS@Fy1}F;F667iEx|aeJNL}D-laz-nG_a!Xe@T2Zx63YPlX&~ z-qesM77`~}ReWA2;&g6agm+AVcfN9NH2Y^ijLe4~&nS~XR_^>AlYpajxb_cqB*LO3 z4p@}JNh+@pj$`#H8;`X|=Q7<974D zQ6kNO!x3d>%{o*e&)4IG@%iaA;&GSdP{%syIJ0V+F2Ur77`!MVb`|yUwtln!wK5kZ`Yca_y~*C15!^-#Bp2FVA?-tFNl#`(#D%q zko6uG(+Taqynv>Mbb;$*QLK(X$XEDm1VktI3^4K2CIuCPpAjuqEzUuQT5Wen+8#RqzVmjBhSwsc&KQ3K<@PSGKI}=Q5QeJ z+}Y%}&&3X)dChM;(8Vl<6{jo(>O_`zM}LeA^D4$2pmU9;xlL^=pe4>1W^#y@3AN;?t%NwdnQy*TY#`?Q{P;G$%F3#Zf2UMJuT;8cvP?GpiEnjWP53RNS8#t@hXE z4V6z1AA)VF5IajE*`3lm zTynq99+LBIO+|rR%anQiGi^bqsR{bGYy1)&Z}aajiFcmcuY=~U70=3XcxzHC3k|tB znYB{6zHRV`;5P71_g`5w(jDCq$K8#`1SLOPtz3CoI{F_vfgVbK9)3zyLx*BV*Y}wm zHX_(K2$_wz3)S$J95H24ZvHl+_{d`T_5Ijh2)17F+>Q3VB6B|K`6FFY(9J=N_-L|A9%0s84*^ptgtNi|tM%{F!21vrs_n`-A+9>h2AMmc zBn_vBn(zR+}~R35xR$uCXESSF(GH zQKYYSpmFh1)F5WBJ&mnVb;A8L)l?e2nw+<^dy9wjd5=YUcC*Ghv9Ze@Z9oUI4}qQu z2hZ1A^cj!sutL22*WK_KK2I>q9=4xvHX(n^g7tAoid6*X4ryZ*!g6Ew?;YH^mp6gx zp$Zmr*?Hzf?YwzIGQ&U6<1EsdZxX7xpX6W53RbD#TFo0GI^Js<_<$Il*xaAr)#8`} ze?9!dv{=Wt2TUa|Gmmq^ABJP(K%rQb`Jb%WVy>+CDs2xY-zCCoN6ApMbZeUEesu-? zPXc~Q%G3IT&S42AG4t{;j6br;L~M{xOGf;R^ZFh3h6^2d z{QDH^>6qAswddH;{PN{(HXM-!XH)w}!r?v~EJQZe`r6;riuzswhF{bl`3_W%23hL!!uj$t(}eSSqS}&D>Tl(4>Z?O|v!U8P7}W?ixaHhESo=VE zftG$-f#mi)dO_zJbwH*oQ6HgbZJ;-TLb5hHLeXAu6NzJYY5FtpGcysP_G`Bu@nvA5 zQtL(3IZah>D3~^I-8UO<6O+0eyR$JVHmQ-<@4|3UD~D{|9Pe@rx{z(0(CMmO55mPr zikE_r!GC{794Hw&Gyd|NZhEvZYad-qgZ7-@^mm|`Dkcv%A#OuVreL9??I}~3i>t| z8#^gC54$b`i;BGq=w1y{R?xegOzm7q0e>#t0KIJLZ13u1Z0ZcUj^m?~y|JpPi#7}B z!VXfFPo^F&pr8ByS~;@a#%PZQkK_9>j^h2$JHNu~=q()y9ss32`hJeFLvXtDmq-0OJr5sQ}^K!9c zu~j}|f+m1LL=rre?H)3Cv_ipGpCd%Va4Sg~wVg&Xb`?oBexio7a)%f+$YR>+jU`OMlhs^E|Hw-K$$KN8Sh<~qLM+n`!>#MPr%grUJ0{SaEwZAg z{`JS7D$0_cdhJ9;R1Mf|_VIzU$-{5c_~9=06ZJGyx~CK(hG`A0w6q-Ab+TYAYCnE1Yr4HKKD1}C)oz7Vw0iuxCj z*D8|T?8%B+Z*|h+a*4AWOmqY91P#F)o>d|%3nT^8dASlj)wE*6Pkcu+=f0s4!V=AZ zPh*}-Jf9{Bq4rKv^+dx1QGfth7F+?W0!WBt6*Jyb`&?uxYtV<=vKAZh$kQEL#arv& zKq>Ip%k~3ea{&leK?Hw{P49=0%wV%YOwI5#i-2W-8^Ev}7@qSS7k2l^l25^%;cNCF znfli}gGoGH{G6zZ<#j)?^i6G#qJOr2xs-uPt0)SFWxQHK&AAxY^BsJOj`0$HD+iz3$1 z?~K>7Ub#B4bVGMKHu`!r1}S9z^;kz&72_bjSfI&$E!Z+ZL(11#frzO?>D%o-FNt+&pcHLj#I+rGd*z3U9n3d6;I>1U zYr~1>Fw=&&^WYq82s9uEFyfl#&$NySjmNWdoflwE=VyM7{{pQCjlhnd;55q_hv8-j zPqGIFcYvVvDxtlR%>%+0MOq>mo6vh*4AGaaH8j05bLb6+ZvV`;%roC5qkg|X=o7zV dSa$gDC%(zfsTP!r_Tq_e+otmV{pjjk`5UE4=d1t# literal 0 HcmV?d00001 diff --git a/doc/images/sphere2500-result.pdf b/doc/images/sphere2500-result.pdf new file mode 100644 index 0000000000000000000000000000000000000000..9175f4ea1d30eb16aa088d8a1ddf4d76272914a7 GIT binary patch literal 35928 zcmV({K+?Y@P((&8F)lO;CCBWKq6#%2Fd%PYY6?6&FHB`_XLM*FHXtw{QZGhnY;<#=eI^`deIVSQpTTkbtx5m& zfBUO5{PSl?PMCAga{n!Ke^&cz69k`s{-NJLZpiMN|79D$q4>{#wBwm@m1m&U#7p z@qhixAOG}6dw?C!R(_yg{rS63=>K8J*Y$%^n~Brk7inA{hB@x>*B~GF=Q;9lddK~6cQKrg>p98K=PyDw)IP7%JI2H2 z$1u2~Jb(X1emmOuL9D+|??+00fHf17qdpQ>|0=@eG(x{l?|3+(cEkA7oN zwN3dr9qc3Htz0JVKi{|G_=~)D{!E|9{=-pTaL+-w=U=44S%2nC7XF8O2it$hyTF=2 z|3$F9E;f5n!Gw5${j2QzfW2FgiwErJ1z<=2i#+xNcJw0%g@OIt0DG3dsL-yTWBa@% z;-7w|o5CNo3CDR%bJq61m*x3yf9&@70sf!<@sIwoGqR)a50t@ZB?V zK7ZG3M4^4QkfJHuw~idg9O=*BeH&?W1bg$5 zT79Gri~u&EjYCG-=i?ZZs&mSM)}Fu5ZKOMO%B>@<3f)FF@^E`2G|=i9DI#8TWHhJf z*yi-=bNblktkbT~-=A&H;iu5MjI{eh>aBe55Qv>sT(ow3%jljl13vrZ#LjbAxpT)rIHepDUlr=LRSI^ZPCInQn6 za=wO>X(J7^#@>9+C46vm4tVTm@=oui!TU1g+QzSH&^aUEiO>4ZoIVHLuBLPDHL~*#bO10I8wShUxSDz!CV`*g)cI^9_vLc>DKbJHh0OZM zvZwR!k3t)lW3Y|1rTwqZI$xi&>^9|mjzBV=IYaFawZk(~)f1u)ct-4R@&Wb@iheE~ zSsID-;7A)yc6x3jqAh(trfWnWTtnwTD?`o&gWKsw9;L2%MxL+A(2?O%;+_NP3%Z>; z0_|_msQt-(i=wXMpOL=&o%#2@johT@D8w4F`7`nyfcrZ(0`7hO9^0HDSo?lVHmlHD zq5ZIn>udTHcEXE8sL^}`Is|+3k;QM1h`J`f#P6jRlsO_SwVP-yTVscmIHQ|2B8*6EMhNIjerD=`3lmy|SGXUf?F?OF5QN4lQ^H7t1yr%jog zx>L@lwQXe4`jI(C1=Ok-p-=vd0Bg#h&lxhu>DI(Ufkxv9Vho#8PaT1O0BQD-#XFD7 z+-ZNFkpVfizt3&NHPR>>21_TNrmMDfmX)D?oFmU3dT}}JZ5yeS#>V)^H014aD%u4Q zmOg0Iz2w-%2cujHZACe!d7wH1TAxjQm$~mE)M+w8KLq+w=6ooPgWe$ZIxwKGY|xfZ zPD=U6vP@@Jn`L^iU+yEhMgm1Z(NT0xnNl)LL*L09lb^n=vwTZxjWA-+$fK0!#UX={ z_%lL#3jH`opl=^&x5lTG%|$n-_4AKo#dGuTzKsYUFtcFLn&=SvJI@H>ZEEN_0y5wWFGX0 zZ4PV}w39$9vY)2V%Ej|>eV`*e5r?)Seml8A+#W5o^fl$2Bgo>=e#waYmY&-%Xe$>$ zE$DOF%~NRfdu>h;?Q(3mEiYi0<|Oa*r8h9A9x?*H9_Pl_y)YX=TQo=7(%$sei;N%= zA59~18(9%Q&&o$qooHvj{Ojiw2K{St#lm{{ejZM0hug;1b!7R8v{C}?a(-i6Puuo0 z(mzGAU$mhZacP7N#YoqYT*uQMK67r3+H@USsX6j+#hNq!zGWo$Iw{ZVe8#bjERSm( z>OGPBAi;ebS(%@Qg&LzaT377n+~%C3#ZJWl@d7o?9KqQ?>pa?to&&AXvySBwnvSe9 zwGr1L5406;^W-_w;GuxJJ~9?{>ZW%j#u%kYZo@F>ath=FTCfKY>bR|^1;ZT17!T#!$}CWtIYK`k`cdY%1UE{s%~_H~ z`^Ay5_}Vy;d~K2r%Y;+p2qKn#X#{2?EB>MNaA->-J;ynyk!UF&Xia1EIj4)>xwesm z9PhenNL)eVBg=Cz9&P)a>iU`y3n_wA zplm-QkZsy8j%p%O0w9^%!Ue zpOHhO>4B5|itgbEe12LdAE~a}DFd<(;JygwiCA5bdy4yj&Fz+r*;Zb;XG+y;WicY8 z=A3M1%+;3%KBVW`5M3a_3HlCPIySJyy*~HKhg1vb7x~EY2k93j`+zWiG#oT~uEfz$ z!4zx{iI(8?yx`+hU>XoU?@$`-B)FO=j3s4#*BTN(QB(QI(%lbdj25~7@W5jNy3(Cp z!mrF`*#u|{NLm7aIa%a}2p`@_yEURVYAmmgUSWg}S9Vpd%m1ay|(X_IZgQC6HCc% zw4vDzMhQ3>#*~aKo{=h=_l46+^_ZK%l+qk=#_CtFHg+;YbPRoAS{Pv4B26!6&nJUI zwt2xnTtT%X#~*<%Fn&QfJ>I0RIkAMifNi30(uTVVM%*LVA4Wo;@)7vojOV5aqozH@ za<@&6PuKBn)A982e@3e5j!0!_Ura2)La;YB{c04ypt@(AuD}t z=8}%3>A9ua$x{ini`d$do+ceKlbQ6)hGb+Ig}(5=)K9%KnyT3D@EdXf(0MQTy`YnF zX=5_1B_{^)XEI>t3A6Pu6^sUrTZ-^pi9FXO$n0V&?7ztE(8F1h=b7ZUl<}21TSs9;L?89Si?CLbMM-MpJ%Ae|bjwy26 z#PSl!#mUNR@^f_Tws=vl$;tPq4d4yK&bv%L_%C0Ldx@ls0E0!dC9&f=PTt*dV4La9>|4 z3bgc5)1tA7mOjCMIsMGeWKc9N7|N&6k!LDzj5ZhhkC<&FpCLdf0n2GJq(Xtp=*z0C zgRm1XDoqT2tERh59#=-GnI@rxRCoPoi4&YwR=(ac`L#26SMWNVa;t@b{E<*@MFI4& zBm99t_F-Z7KA|<>dc^pWI&N)|#$=hJ>OMlu^-T&(rl-V{m;6C1nm=G>?xCC=xQ-x~ zZ$}Vw>^hm2M$jHnpy%1pv}j@ybgX4np3bzYXbeZWFK%VevwgVVtAHJsnf#( zPQ2Pey^Cn6Mozw*8JW+QP|H)s-c#5v7ZB$2U)Wxr6QyV5*dF4$#hl_qTN0{%Fwo-Q zapvXi056Z%+?*Ntm#e@`_6u9+UwZAgf|cmlFUHu&>8I+AujD0I`(%fwC?C@w3KlhJ zW?UR>bv^Fg#x`dOBD3Ed8Bo&a#;)BlFfYExGXxhy_alUteGIP|Fs|I8nAo4($}M-E*4Aw=v=FRq0)KgE2B=5)66+nhMf*ow40PLcWUXYwVVymEf4 z;A08Bm<3@@^I6DpolW=?_F?|rw-Lzd>K0_#UoS>M@2kHtRPP=jC8MT@vmM-_Z>Cw)~ zlH)~bW?z{R7hveNCj+vdB3|zQ!xJ2FXRWYk!wg{pe_?6dxZ#iLxUEe4Tn{&j2ecM-B(7E2 znXsHgs(nS%CD>LuhnRh272|ylFK&TKL2l^hh;)y%~o-@Vo&IxK!50>zMUhqp{ z!wNY+fnUW(kFjtSOHF&8Kv~+RTDRO54z3zUJta_oQQ>xb#@4?bK6FYoof1z3J_#sAKIlAh5PH6C<|#ATil;i2W>KZ zbaW$=?Z+(97O1%CC-mn+SC)3aU- z<*m~6tXIIu$pYV;n&GT`q5zNCgd=*)RT52z<}_D6yl}a%%sduy9dTu5Nf5ot&MKMFZ*b5?uk#ka zK(alL-b%7P)V46JBc}%BPLrK4D63*eE$n1LrxBD(0v~xYZ7JK~*N-~}^^;;rvjb0z zDAbRH;M)i~;iz|fMC=?NBNCjN=Lc9HdEo@!fdctNZbYQ>*c2<8rkP}zP2)M&Ztwz^ zP4Rpy^U7ajpD!JO1+lMA9YKc$Vn~5@IyDmBZgN6*dO}4i%g0toId1n_%u_p~u53Pe z0*bcL6!GcNXUvFCEIr#(V^4(1)@J9Z%zj4d?Y5-yxr7<(N(O{wrK;%}$Pq_ylgXqu z)_-Vo*6}h+zhlc3|5nPb(s4vS-{CX1dT6R%{0n|{1wLv#8Ds1v;g>M^4h6+d<3>ip z7CIw6rs_f9Kc8r;OYAtM)&P7y;6@)6_%|Iv%)~QKRz~U|?_^@G1g39?-vy^0JvDSN zKx@X^FN|n_f6SWGQ^zMG(*N*0C_P}uvU#Ze3zm3Ght*!6T(k-4&|^Ks(s=-6QSTu_ zlw*sRh2dKYw%)PEoZ5>Ti2Ap3J+m}WKZ)HhWiM{>s=E16=mbKpDQa>yu_GU!z()b) zfq$j;fcHpHc_s=h-KeEr8C$6~C;5^haVI>L#1aix!ULVT;*BD1d=$nL!<FD}Q6?!`H( zB~hOw1KEY(=L(mvzX^rT9NTWJWEpa3!-VBZsIa0KivsqQSGQ9ck`CVUg}8Gvi)jJA znR4`cqavR`fitf0tos3oVvt?g;iJUPj)DySaH#OE{kA2)IS?1YiM`1!J&@IIN#6~!<7gD4voU6506E!YayutERmQ_`zm!D4co znVuPBF-CO;WyuP2wFwk-SD^MEq2M}`g$mJEI&QbFJe?O5$(0;OE)nRY0N?O+oVizN znmHnt(A$6?wJ-Z6KzC;TZ3G!Y)Xbv|YU@@jecU;@dt~$A#g3cTiLbE8b{0D%Sm*u< z#0mc@tT8de>m!J%P&-OihTnslh)+f-0~N=_?siX8k67)XWG=Lm$c9xN=#p5Um{2_U zNxZZ9iMt`*Iy9-^QKIJ#X&)d(8%--BWLT`J-yT+jFK|fqXU7(w6f^pPa;3Zev;$|q zi1FsiGnTwxggqkQ(?ic}4ByZg`-VK3Q9r>aFrQ=vOw?a7GF$zY7W(+*w`T>Q#ZR^`DPF*Yad>3cMV4;{1RU~FV~zQCVF zX69!xd(tn;95TGN9xaiOh4pW)jN9+b$H*Zz$7wr6+>~U5@xsZ<=ibJdL|yiYu#ZjHN%v67HfXex&O8&1fDMEH1*oSg|tT)BF!>4hX%u0X-q z(iNPVj=}NLNZWkIH(y`8j(5^I&)V)+sOi4WN3o z<;_rlx3x8w@V^#6jYQ%P*0zn`{bgeA24G{R&@Auan{Tm_!0g%*9e;7qV4?tmJT6D5 zKQ7T9FZ*9y?lLU_`~8*AqdcGtL@K%@t_MI#`Gj)Aa|KD?nuTVo+2G-y%x)fJe~Yla zZHY8rY&lM)9NxuYl{xMV&neN%%(6>F+AC@}0_URh0g?cdM8d`1|VE6Qs*H~E1S63@!Yg<9x0`=|)51pZ3>B(*99esx^1!{*4z8Hn zf9i&o9yE5p2Dv0qCB8928CahrSvFSJfK$vnQyU`MKO+BF6y5BG5`$L@{<%i#uFCf~xzCFSJlv)_h;mXY4r!e9+XP@K_ z1*H$ft-3P0;TeC&m607Rxi>`VBbOWkA1}FBUFVKx2EP`LcznZW;x9fAFA2_-J=L8 zK^}%$E5@vFvdnjjF*kD-kk;toluK%5$Uh}eR^HY!e6dP2(RC%3yaKuH753`+#2ni; zwb@Mg(8D*cO!Qn*F=v(hncU=)*UDXd^B4&+6AM3&g#hZog+fN3=M(q{@JC+oEvxJa z!z8~zAA+2vC?H#BlE>>_)Ov`3oN|bv7L)tW^4Z9W;K`Xjg31Hx6Ujc%zPGh4F{^Azt+* zBj{VBm++$3AWrkV>6zwxYD(dty_nJG%no%E*l~gPxp2 zao?fEereWKzM|Z)6ZO>?5M4miC!H*oUTTsxJOqPfL2I_KC{?QS<+03la?iJZj&B7cM zIXj~UNABXcqRchw*s5km{q(;wKiT2>Wd1sKes+);*g7YIC@RMIo<)Sy%R3;n^x&sN zOC0jaEiCssJ5+g)x0@>?npp6Yw;I@;j6Ek+BzS*No=JAZx!$9T42tK*{Rb+F)Qad8 z8vZ;%7?;YOJ-o3B5B5{&u@8-1rr252qgwR_Ba!z9FlR^y@FPb>3k!|phlre`&Jj+& z3fko-S3{vY?%ZMI04ohO-$&Jz*NfuI4#hYK5$zI9$)gw1@X+=?f(Aasz!4{0YGI#Q zvT`rJa(o?>UNYjuPqcHT@aJn-?M>)&2z^55iE-`f>6ix|U%nMwOjMH2H0o*;yV(EC zTL!Q)@ok1lj^(4DTZ+p|L-Q2li?NJTmwPng9iojthw$g?L`rci3-u{-3(yn6YxiDQ zFzWR_E4P)fsHnfpk=tE<{&a$$#@o103PYblxBAF^Qzh~oY-H7Br?N!M>ai`j5&bw5 z+UZ_P{B5B52~y(d{fT?WZAyCbzVhKr&dk{hKGfXxp1kVai;3S7?%pML_LdOuFr=FkBR$Iw{*MpHl6limtnMhzYj8JCv zEzofGRYz~W4zAe1iI*z<2LXtjog>s4yb3bw~W}&h_qN!Eb|7Yr9@rYT}e! z)YL_b$LB~&L40zl^Skd5j?Mg=IF;h95U>ad{30lXYMV<3puA3KPyu$=(!c`=8uwPb z| z4?7Nh;d&b~26+g5brZe_lh~cc?7Z!)hPPMd+1_4zjJHZ=QUk08Pdh>xqY5`ho^$8K zJ4+H=z;kuuIryfaLZSg1lNClndb^7Xhx>#f`!a<9IU>l|)9%TMs@T((7OZkFQ3mXI2 zj~AifX*lM^Ba{{KP9GRsQpdvN)@#bTi89&Dak7oH$ao+noK75*PQ#| z)kAwGIuh~LB6563#O)HWtcpLie-+if!^e*kuzxCnFMcC=ZsK1~cRk9jl#>J>f1u2L zYd}kKbXM3{V%&@OK)B{ylgFuG>2ch-$6@6uca+#^?EHr0#I5_F<~>F8E`F=7pRPlZ zTv~|QCITg#g4T^zxI@os@xk_?>+`Ai=RgRqwo{4`xF;^s> z89Gy+PipF|FcMq%yEkMwS8o7mp~u`S3CR2$O0a3{ zu?v%JM0+yV&fMKs_QVnPLBUr09Lc}5ZDcH)Xc;okB-%Pn>|2ykbUHtTYf`n4eV`Wx z^2WXxgO7+ESqR_9Av!Qc;Z6cz_1lvoxJ1)hk!E3oo@@wil zPE~N);WImne5~)eyRMJFXXJTTh}jve40S0e7haQ^`OamqS#@I2hu?^1msHfa?XDsZ zhfHo_cZ6TH=!N;dATlS&Q28AACg8)k4;IO{fMrg;Wh9=nZ*^LZ53PXhqmTnUl|K{v z&T{cxH?Nd0-@&WqbK~ymw3rQH>;v9o9CVwPKPcBVRv_#Xq+ zM#9Ub6D;Jy5`>p7xD1mq&ar{T|XBZeGu0(ie?f(p|#u zUBY|WOJ?B~nrpu`nZNAj)(%k)Gh2*?7V{-_09L)%L3?;Rn@hcEq{mLRxuKI>SRE(S zouKPIY=91e*6F$+ZV%a++}j-FDh@%#Bf;fb^{sBzk>f{R!AIa9BggB<01qAd>_sow z+a*=wQa6Jpx4uV^O=5Lrjv(g>F$*_Ryl#ycGxk%?Po%6j`i7J1fFxsJpP&l^nVAGW zQXt5_C)~L>;US=BZj^7?t05;OUgX&3teX~$jp8}rM@e~`fHXz@WLnEABTNBXSuA=l zP5k7sNm-K^ZRED3N#+B3KY@=rE6Sz`lXtTdbG`1n(H<4DY!Z^N5ZdeZm8IT;dkjB z=JSbpNQdIIDrklU`+gq*LTC1cuc(31m&UJT#04<(QkyK;1*}*o^Qo7bsOrO+tgR^h zYBKVIzdkuNkbj*Wl1R09+q*gC>y?8^8Ac1F8YoB?dQxqj5av4tm%YABFI*d)+DxU@uwMzR_k`1M*`61a(l(|EbAP`r830W=2N5>jQLG)K==g**HZAL zTw_(wO#I@#n5lt1MFi)QKd#w5(&I_;RJ)$)ifx{=bNxqISayi-j{AQhcxFY1XT02| z=F$4_b>_%Nc?5GV!ELA4dWe6Xl*bW|`oeX)Ys-crZdwPFbTwR3F*@yU9D~W<>US{t zi(L)u4t*xql68u*$Mh=@okxBhp;y_(H=TNLRTDRMooBe53ToK75A%aMJ>8DhhB?+h z#-1FfDiyqVAH_bwTa81qeD9S7e`dN&B5!eV3(uJ_<=&FQWo5WbT5S&W*Q#)<%?uVq-iOh1USWr?NBQ0P~XxgMd}7kx&D-T*NM8TTM(S{73Va!2JFqC zJ%P9CS^^RUr-gGa!GPV>aqqabVbT@t#4JuoZ$tQf8?X8UxkJe_aOvk^tnjw-I_E>M zyk)Y+Eq)V_?RoX?p@P~zoTLQm~AwOsd#i}ASo znc&`KewzFF;9l@6^QGioIPrAvEiHUGy^3%@c14_%X4mzdj@P}}r z-(Iqj<_w;Z$uh*SeF#!cPF9P?onZtDQ0E4O+P~$H*)w>=i$BVbZ)=#qw7*QT~S)g6u99RiZ zKi=tPCpisK)F{smk-yZ;>>SxT7otYF3Vt)$`=cWK3hx>jhX{q2`0QX(KMa?OXp#NA zi+iWu)G)7dbdkttOHR>PBlV%FD-P2+niSX6U+$ttJB9sc~KI3c~j%BYWAVhR)40dIoqV?BRXOREdEJH*3z zU~F2vU&BR(D0&;MMSl4TlVmlfy7QP_%**t zBcAGO+>cG0aJ}GVg1G=BL{6MY-Zkit8l#0)@Jx>P9woTI-zah)Y+*UXLdDZW{{{S|);Iceq1^fF$j}jFcRoeB zrD@5qPQ3re=oe(a_M;MaGO=o{@SZAtv;_V-kjL5dSFg6ygpc-uU)=(-R_Z$wlPk8d zx-ijWec@Ey3ue?BS0R0TBizekIht}TLik;D-zX{Mw_mD?MyC* zjM6r+p5~^en){H%Zrv6{uIM>gZ`$0TeF8KolV#iwzXAIDP_Veg#(cJ)DkSDE$-AC@ zXYS#&vt;+@s1d%hR)m7izw;G<@_7IP-%gJ~TDqJfMnVva_gta5=g_DR* zeA{=`#=LIg_uGxyxEngO-Z#ODzZBmJn%6TwbRztcC8Zo*WPIs>6sD)9y-(=AG7H`# z?;WBPnlRRD&)F>(fdZfYJ9Fcie=l_t=Ikey)_HU}ePWLBQ5rMv6}Ur`A~o2=t6cBQK7dO7KtQp@mu$O^yZU$ybng(Pip@{ z4M{d9wxoE#Wx6YNUfL(c6{}>AY$KBTh;L}jPrBQx#MVL+L&JJpg2)C+z&l_+&ahkH zJ4aSSh5bz(&x+1Es_{{175yymEI86HH$;gaLo2k-f!EkX`+ubFjf`Q0!Z@*&?54`} zDV&sUVkz%HA!d=NH5S4A4vUTGA;uH3m8;99-?L@TZHZ(Lzt%eQ;wXS$Y2D2dg7BS9 zTWOaBcXn+fh(zB99!)CK4-Q|knM zI^lnWa?AbV0N+perGv)9`+S9`)Vas<+T2mNf1x zp8SI)9xt4Y}bhE5rxxjhVq6EUmT3J;q^jgn zWzM7cBCLzCtLrORMEHF03Hjv&K6-&Hr!qGDU3Yl}+|ZV+U5y<-jK!f?y~W4^qs5il z=(FR5o>88;Yx3pMP~XRuc{O>I*A)*sGKVOG7d50id2B25ZjaR{)Vi>4i0WcOjZH*ve8UODwAGMyiDIMZi-kX7leK61BJyh1J{|>*Rjsfp=!avL2Nf|SU^IDW=$3^9yogJ&*2TIxI;|tR~mBa+g~w&R36q!R29|w2Z914Ky!5#-x2 zT#_(v1H0Le7)d- z-;2Ct!0Hg=nW}^nuvwN&nqtmP6B`~YMzjStYM?`vdrGif?(LkcNhQ=e&8xlk5lJ^C z8B|nb*Ex*DUl%&@o@U~4t=Brv&0RD53W7ZxK&?t1A_u6CgqIntKAdC}nuC3`pg;XT zPsq!OW2e*YnYB#*5cCE6O5DNyebZpDHMPh+3+@VXkywZ3U~M0<6JkoFWG-%%)v*jN zGvS$KZ>|E8h!EKp82`FiM7Y}E(1bVECmm&gX!B8GGx8(?*Q%RKNu!#HFrdpeC$WHTp!gFgVpw_`>P%>Vs8` zw#gVVo$n*45PwDA$Z1ME7Vr5}dn^iyCaKHg3_TDT zPExh!btyg7DbFd_;I^q1)NWlF`9Q{Gu9x6Hp$_VL3000qaN{c%yxjqLj=vU19f630 zwG6HXy_dvC)ju)S+VptQg2XN--|8~hdgU=_!y%+!GQD%e?1zp?9a>3B!VtOo#Z<7~-CRoo# zBrhv+wMG7sWQI`#gmbr*GSIO&Pe?a}Jpa&6Fz?%fa)>=#>;R$8-*j5{#$dk>VW5_c zpKKJZnSD}ytMPYV=+$E7*zYyVH-3o8FA7ZWPOGmw!8}ZH>7ClTQ$TuBdpjg2jV^%K z%7}e|e^N)2-ZRrni5wKsmC&0R6fZqz@fM=_ubfVVf)2TPB9w4+(t)#*O7rv2@|IHa z=AO9)c=%$J>@5`gL>~-u1&$7}g~D*fWNxOHIz1LA&7nb}G||tYG$~k)=;6Khd^omz zo6sf?5%r;Vfg@E$cARLdF0oZ}au;rQ_fb2XN?MPdF|sqso*O~d=YhzZNH03AQpRJ+ zhMPd?S7X&Ju1tMxr>fpN`lSqurW=AYWIFz%L}=0%-{Nf?dhE-TC*J#zezIN1hmlwt zVCMmtF?Jy^h6eA&N|-{SZAhRLFVc)yhoaU%{CQm)Pq^df-2p~iJpHs;`3cPvTQz3) zNRzM7iarTnLxhj~!uA$!(bfXLa|aHq+ensiT+qDMxu!EaQs4^&X_XwCb+wF=040ol$xf%4iJM(!}uUD1x1 zqu&TN)ETwxr+84T?XKfJ{Ty7n;9X*e@m3CN9V@0u-fL0#w8Jkb4+RhznR^?2H_OLd zT3Owyu?T$8$&tW6Ws6MS(ffuZddgHfKBy%*!V?dz$<^Cx829;J!E>kZ z+>4f%lUpQEx^#y25x5mXSatP{VQ<$lJ)Zn1jFOq%5^RTadt$4G*pgZ_O0dqP?tX?d zR2OWw08v1$zpST?;Q9vI>t5KRlJuPo1)fKwKSHpFjNnB;dWSx8xnOwik=1w*F802& z3-kTS3)|Bbpy(K6Ul(mfo{>xXu7;SHR~lM(A2|;qT3I5~lla7-h|Ntr!7f%37R|B5 z8xY#HvBO6#XYy`W;(`O}#sON2LPgX^V9j9JUf3eSftt9t1-m2_dc;<0QpU;dw@Qg+ zo^zBTEADvFg6~Q%v@iFV6NztLWo5;clmAZl*W8)&wqL+tl@xo9zvesl?6F^FpWCk- z@JyDfeeK&(K^G%Yn5``JN@sr^x#EatNp^m!;#cl-C@GMd?oX~lzIJYrftNCvBk1R6*y45qZz@Fid@2xmU`}Sf7?nf^D_thZZS@J(6E^-dKE1QWKB8-+7WuNu zQqQ6!B>Mo75wj#Xp;_?3$y+s#H%m7eL7dXBElx3Fx#8vm27=S!=B=s05S*m$(6#O` z;p0NgUHqq+U+|^t)oj#Po+K#-hjLgvEy9@0;l_T zoWMs{?vqG;sps`2^V*@r9uL?n;l+DK7)2&np5jMtTZH=L{choaD*j8=In@IQ(Wger z)1mF_EM{z~HD_fWK8gK(%1D*K+I=e%$Ca65mhPov9#FUxhuYjumF<(eNJk`P8MZ3c zHmMQb4$Yj5^MEA8m1+OY(@gP4ubCxtVm@G^pt*^l1MCxYRl%PomR($0e>;x1GQQIB zovmDipFVn;D6-vBoLV&XWO<@D3@nt+Q8K%!$nhSz^Tc_}~E$UXMouP5AcR2t%W579HHi|65*8P0U9(b8Lj=M?YQ z(`$w26yJJh=h=h8)X_T}J+( z1jX07`}KGIFrFz%$n$-CUpZesfxp8?U-#q7xJ9)Do&K0)Rj||-_pdlH)A#UC{53N6 z<74H-20ja&;{MWkust8*s>RAEFPncQQcfsW+%4MU987NJo`&dnBm40tI|@I%2kc-m z=ZtecbQ1mg3|+dn>3Hp9*)`fYnOtOY$x!KmYmj$C_RmI4>8&253g;#{)fK|qCoZg) z+fUlkL`TYXjT$qGv;~MEFWo95>Zcdt;)Ki0^&>vR zTSgDDHhl}pq9iO**I>PC^jG$ByVUyt?tMQYcaB!F0RlKjXTalKj-u6#ZjlDbT^ z&nYng;(-W-5#6KR;{DWZXV-gYNafc%_Z6hXOKB0ZBzkpU8CTo3-`{+}2lK&tCs5F* zREu9l*`eT$x8s5SW;9ozQWfDE-Ut`umF=BLnN=~G0WjTNGsC4EAU6*b>j*> zN%-W#GuLxCe=v8#3sNuac_p-4Px(Q^klc2fNoGkzx|SK9;byiw!E)Qkw#8HAH;F%n zXh~?y2*2XCFER)bN)@wKy6_+;c~lkF%M+Epv{UID~` z$NNLPLG^qxa{fow|KY4lbH>bFuMsvty=gk!2=X~L11mv%kJbH0=i@hhtC@(XbB9|I zqg+qV>=(nYBketcmuD#d8MpVpDf3e2q^BF{U&RL(Zt1`BQGZwL;U6N@N4SK>vDv0JVYV=(;xr-1A3Nm%AeTvRs6IjGIqmTC z=P}K&h28r1Id8lDitumLm=r`84H{o%D+zD=!B8dqd~$RNH2qTMSA;M*_%+!SN8;iu z3Uw2&{<`{;D<%fyRdT zA%8ja1qJDAq_Q13nARgVt(L_bPHh(0CeB{$NXm^&N-ZDRpU&42D^sv$%!@5wQ3EfW zn)9CF#LK}m`!7uuyhBI|liE>fHc<+fv~=w&|2=oBiQR$ePoUtwCt8GrEGgqk$)2iv zjvR#@6ZI}xOB7o~z(?^K?1b?J1E(gMRy5q2Y30RtnhPFlbR=70 z8+aYXJNI`i*`tnf^xq>c5=@}aN4XJAC#{vN>BK(4O|B;5^`e}Fle}^@c}^nR9-9$) zX^4BiH=d}%6Ur^9*gj-!@fsM@|1i|<6IM}KC<^xl6fY=;Gn8Mii6}H3k?Y_|6Wr{A^*YW-(xgZ|!O)M*oTGse1*c?Z z!$0X8a)?maP?4;RmrPKIn5DRt8g$5tWU2jf!E&P1ZGafH&2ofRh;O&En$|aRM|%x4!ep}z>z~~?#lYF1F=01 z1~fi6+NEKEwkN{J$+N-B;jb!n+ZsmL01B%TpGB}by7bEW+e?-bkcXRklCnC)Qow3( zGTMx+#89H_TXcRo{P+kAt@C$v%k1`YHC;7JKSdjYak@C2Ki0VT22hkr72-BAxcpB$nJV`G+amiYQvQQ&Zs%@&l5 zmTs-~v%;IXQ)i{{tF*M$c4aJli7NM24Y2)Z8yOBwYLh4xP}{_lk+zNLAVr;6WUKng z4yEEwZc7`cteXS(zmT|3ph)gH^XC*7t@PUnY%5E>K63hjC)ae?YO>_3@t2WlTh@Zf z!+{3B4q3S<{h{Z6DdU&7KXhy>dk`(&vrxNPETuUtYA9$cj&PkL<$C(ZR6juidHjDv z8=!#;N|+|w5^RvFQRKl(8@WC8;}`RJ!RLWiOV%`QJNvlbl|+-1ESFpLQ*j#0JDG}a z=m8Y z^1opwW7DC1q9xl{V%v6h<=i5D8*M8IvjhQ?$6DCzn)3Lg#kBI=v->#S-aYp$0o7SI zus1!L#uq)P#UXFbo>E|@guQlXsa~mb#mk`dY?oc5m%Bs3Pw}vTPZVfc!RJ1bG1hBk zad%z&FfX&n@4r0yjI<)bDq}nP6cnbu(dptbCrMZXizZEEynHfV_k`t)``}jd<_xCX zVOgtg2#rCs6$yNJ9``0GQh#Rzm7JZtI_8(i8IQuI-@0c!Ts1R~QTyoG)tvWEiTV%$ zPWX>O!HYvEe{uw!u;zy)(j{d~V!_F1dS?T?gT)EuSt$EtyUP{N`Sh0XCwOaMg%^~o z2@`H8KvFJ|l=sdqvBuXnS*oKf&1?(ig*;kQxW6uDr&}3XoH;VQKY^+L7q;UqRZ(vs zO9Cw#n6kx!6IcLuMB5g{id z|6&!m_?#2tUl@u@SFYkLx<_u<;w|h$8f*Q#uW+c3tlOcF+aX@O6xQ07>9dh8(iL-0 zjPtm|^z3*m2mVk(L9owJ)GzCzMWImz?I8jleRZitY*t|UJ&1P7Mkmy17!`)7-xy>? zz=y?_QAS(guYDh%^cu?ZNf+Yw*lsbi4ySB>2$oD=Ku0C;Z`VFOrw^_S@%oTZ;UsbW z$JTY_rYp~pm7`;JI^u*{!Bg4rtipCw^?g+MWlcu)J_pT+uxx_lgm&D@H4m|xlIoqL^rsVw;nnjZr})AWs&{Jw zB?rD$;+qP8GdpNl;+GJRFG}`$yAnuhLH0@Wic*aiQkzs7SUHuAq>8n=p0kMS-Zl@h z+A1@@o{YChKg@lu%SardANEUBF6CLq5S-lMPaiO`J|K`;kvA^D35` z?FvmYql^@il@T-@C3{SPnNx^LVjYz}c}A26_jYApQ1I(6=%*0+S7Bw{A})aOGFV)> zp(_rpLUHB4c?_x~ZUmZitq(=BCBAa96-Lq0fpzX<4US5^O^Fg<4 z$Y}&OM{%N+Ytz21~*68L&C02~M$Xx=NjdS}WNZ+V37HRT&FEW_%of zgDWN4h!K!MK|b}AAZ+0;E3+Y=(KGAN*^UlRh4MKCuR$X6j2?zw&NkiiQQT#+v!xSlXY6&Oy@)mz8S2F?^^;Nq zKWE8GQMR+&?M%Kix+%5DPhZZ{yj*Af#?$WlB~h4dWVmbGVt!?VqQrecS;>25wq8)s z-?luA5uZ)4g7M{omOK?puUI^RuXoxU<|=#~ethVN z7oPaZC0nHCzEl0ftn#9Ni%%`GX8;j%9SM9!=RSfeJNj7SnW6QMcH2*8^#o9&d;~Vb z(ux={3a+sJY3TOrX~*qB%lsZ zV!Tez&fcXH`O8#qIq)jbaBi3S5Gmpkvc$`{Id;8QDKOKrCmg)A{iJ`?S;KvMqw=Xr z0M#E>f;a*@V;*p<1k-9R*~uv()K@68<3v7yR~3IWn)f=u6D8`dQTRiP z?1FJDaa5LTNwG|`1TXlv=k$`FQmf;w+fyj?<1~3FP>^k0YN5tlm3`7(PuCVH2Fd)& z8Bpyo_m6rfN9dlQD=)5$oVMx5BxBUwgJD%r;Gdk_kWk*?^Q8>Ld_MW(E)5?Nbq(;$ zIkrTOR*8$`0OrUt477U5KA>T>`26;vPV#@}9U+^X^;W;&Urms!+X>wiMaeNVul*lZ z`;Q#<@aE}mC?A>ePIqYKSl1%&BY=&$TiSS_&7X>}5!~WBN_Mqb;n!L;fzX6t$e1N7 zuhh$ouA}TU>47O5*Go11=o0<9_C|~nd+1rcK~Nn#nXZ_hHOAA$EshLyx{!u@cXgU?A;qI3IT+cItA5>=- zn9n&qj&fzd4vA;v5MkZ-!6uI*_v~du>}*KR0cl0_lV<1O9+Nl3RV@KSDl_<%E@nHT zK0ONW`^Yc3bI1#=3&{>!^VU@U9d+bKN2+s8a+|RhFO9G!`@*SssKsm{ z;iK!_e4hC8x8|+m8aHfQK)dYqC)lU2L~}lJx``Euho1mlpVSSI$@)%_sGmClON|<7 z`%878cvQgH*(cv(f9`FETN^^uHN`W|?7w}+?$oBtH7{ z34Y#~-Uuh7DVF^oua&RDXR)8;M~k<)nGby%)E5*apX~2T@kgIG@>}9?EcP$L{;!-? z72?(uf8;u-&j_C*XWCiAJm2CHe@I5jPEDQc8Et}H?yAhmaA48xBztZm*jx~GXQ&Cf zY?PNJn@Nq;GO>705B)2gjCKd+lwSKdC2N6LE`k5?#73vzZD<$I3Nnx6nF{*q+sHC& z^z=A_+xzTH;%u0O%f9%@M0f~*Hq`tb~&)i9}^2Y-S zfA-EMuPQA2#DxP+*Y)w|l^;t`eE-S-+uBaVos}S(N z;Dc+)!BNs59Rtq*wJM^3$_y)l92qOGTFhH3I)cgxG9(#JSLA@#&OV25aPY1T%Cc+B z@kJ>0^twV#G|3R2%VTbO#r&k}USV1T6`C|1W^!OIqhuhMH)J2fvw0*G9PIFXMvJ{q zCOD}7B65DM+}(+$R!pF*Xq|hTs zeQ79)WY0}noZwaZWR&&q;@N%I*3jIE58K?Dluwa6X6)lxk};ZM+vXt}^cLfO`uFsn zQ)-~H%__IUN6*utHxp>Pma0mA!gLZ@Tk)c=++3QdMcmY(m-j(9uX%TDnF+uSq0rXD5RZG(+9ufWhmh}h?eGvL*L;HP@c1RZaUTNu zDDfv`L*(WNpB%hrdUR!2C836Us$TJ#R4-2Tww(t;h)>D-is|vd?r=eN1VWj`I<~;K zgh?-Y4p7SM3-^7@rbAO~qf#`Bqy#>jB7e?ULZPIR%af#`h*Z}kX%Tn&1?Bd%;7I(s zQeNh4!yj+jSVv*xjZ*yHBy^N-Q92e|>~5i6U#25g_Ds>NTY6@%l8#h%0Y9HWWh7X3 zF$1ygVz|J^N0iHrFe%sG^x;h%Sp2whJ(ECi(g&R$$jv7wgEtEC_he=CGCg~KHWa&9 z$ur=e*nMUHj3Ywsw*V=h$oF;!xW zhV6td*E&f|ZBW1gh!TaAlA-5|HM9B14PDZ!#GbXK;~DV3c%z9{i?0l^D!jJXSpH>J zWU){3UKagiu+Odd^8yp%0N>elIQzt&y1DX2KaAZ8b23tt@CG@8%AUnL(Zgq-8~BJt zAsaz>VD4{}M0CJma?E-#n+hmYy^L`viORtPO8+^;7)i4aZP^8X2AFX>HG1S=)X0~1 zW7p|q`Pn{Y!2yk;`4oK|RLY%6UUngWMWaS+DR^ZqkVT?!gu=SiEzYj@SVC$) z8*i*y9P4sK8}Tz^X^ynx;)dc+bNWe=YcA!QtGU5WEYtO3xlpy4Hm9$1Fs((dd}x0b zw@j#UOxojw4k7YuKmz4cgzKZ_yFByET(Fb$$m<5^ehSGHe0nuyq1+@tGCI>|1lmxFC}X)FKnfr!?ie> zRnn2`ZFIwY#RHD;ha9-qm{>oA0vy}O$^$be>>FCL^RcSL&^ge!UA&?fwwEYnw*m&% zi|t9x*giQt=1%&AjB8LF{m6y{%JWH)tX=$pcy@X%_D?#h>2HF!2}$31@t!|7{PjZ@7IH+Dej_^`=HhwiEMUZ*pl;fmoOY1cn%-#gh_4G?cMW`tZ;EM zq=|VC2aCqGTC%%~#WKa-meAbv8CY-f^5>G+W3kk9=2Lay+?r8)QUe({^_g7%5x4RuVp*eAnHhL;g0avqg6m$PSN zt<25}#%lux`jm9S3#ap>nfI*qL`7OvMzotsQ$#~P8TY-kF8E&A{kkNhw4pErg+*mzeK*mbH=b?&|S`R z2OT8W5HFmLl1q~+f%W&cAkx0r6GvF$Lq#p_qe^7rza3;F%{49GDO-&(pBRVi`&iEb z+2OR<%RQ+f-rLx=ics#e*+9=tPfeJtT*SX_n@3<(67S0Kjw;qq7QeQ51KCy{o}x*9 zPilU0#SQIHdK2rIWQi32p4(W+E}7)*G0m_KwNP{!#Autk@swz3hl1-Z%q%mkTxN0} z1U!0|$Aw(fL$j3vaV&D$4tAx-$say)xnhcO+FH3voE9?xy62;KZDWq$RttOpj_@fw z^cDzCVqHQm%ezJ%Iz8eQYGpgxhX|=axye~mpMtYIlLC(>L^1OdxwsxpA2y(4&)An@hfB@!3CNFI+f(W>sqV@bEKkA2NjmMa+f#jm{fF4 z3{eTT+kFTGzdWt+`}dJ`lWL=r;B&1H{P9+kz13Xf_nUEr^N@>vgYU1nwULmc}mBlHQi@$ZFG zJxMwKM2A<~)`EOr-Q$X7KY8zKj-X8e{em*bt#Q2b?m76y8}wk^(}MokMk=z6J-1Nj zFSgOG64g>X4^&lwQ|M}%r4N+J(TDYdG77IHFw07LV8RXF)a3fpJH;pga}N45z9MN6 zr#9Q9r!a-O$ovFeBjU;ginNi(w}ahk^JJnmLsomC8(;GC%HNXk;YQwDp52>z!MB{{ z$Ca{+q;>qbJja~btRI33sQYm;ZU`}|i!1ZJUi3L~GWyxr+m@`1zFp-1lARr{635nZ zfFH16Ha(H16`s+)C-}=nOLp}w{13suC|N!p4Ak)A)dY*o6|%+2&d`U4yikHa`d;A2 zMJQ+-WhTez1IaGAT|<`*Y*b>gn+w`y>6XYp&_>j-5emF|@V~p7u()*9qVErHi3U1G z5XhJzs&xK;@JGh2NMD?5JEGlW1a}x&L5Mh2_*Aex4t99!YW&4p&n+(xHop7ldIZS5 z;GYgZbRtjqXzVzoUv#4rbp}ToGH-_zQeQX~cQAT*?`3gIbD41uS;+z~%}=Px3Ds=` z&FP0UsCX~U;z~X$CD>M)q={{)NZKdA_}jl_W1UmJ@)bv_q($PL8}H#*%FI0*dNa>R zm)=9~ruvFKjQd#4%jTZ;@FJ3XK1c+(KmSZdXn{&jMyD2?t2g}W1Pi|#=Cw3XhURpS^C&muZJJcjED4uBACP8(%XOj8qe^N(qIk zRkGKaU!HsYbb*hHo2-|;qzD~2U!iLPe;G~_r<$J?MBGBrE)oYWH05$_vbeb1A z_E=zvYs{R_PoRX6*NRY5tLV8pxWwTV5!cO6OlqmA6#lwkJn3_vy2U1p8h+_+B8M(e zcqj=KZr74oKBNeX9m1%78ejP;p-+`EZ*sm53V;G@ol&9qUc-F{?{;0|FFD7qH1$L-oH+Zx0A+*ETXd*fab(>eo_j)EV5Da;fjN0zOGsn7WO^1gUp)13!JXA>NT=$9AzW6%8JBhP5_HimIdMW-vW7944KP`a&th8MQCTOQ^^U)U;q&$C%3wLY0dj{tlD;8$$QNQe)ZiFAOsKDP3nqZ-F)hC`Khoowm_n1{v zF~4pGP=Q-keKf@YM|Ev=z=`z`u8i_<7XAz#EBKt;S7C}3YFSWNI??DS+s3@=oW)C? z|KP0>f$}Jr;&rG@$4mZ<+{~y8{Rr$%iSU_O*dk^fnKaeZKeaz3?1fWt9cgKm=tD8z zyiT*Z;30#EcqV4nZ1RdUnR!iihMU-k8eUKyHeLpf`u+vQ^G~kfA{4yV%I=yeo6wX$ zlgFvLi+=ZGea|8lJZ8lyi5x*JLrs`s+tz!u?CN-VSvU=xOz4#MoDF<6u;rU_-uqfZ z*T>?f%SFUx5>?H&(cR%gE1xKcCRmo{)}3U(`|@=mR@b&Nk|x0KMW0HUF^{PwS|9xi z_{2>TwBK^4lgt`vzK9!d!h77a_@BQ7zugL{m5{s z3S9tkhyCN?z<0Rk2vX2hLg0Oe+jTBldrIzivPbOE^IG-85>|Y~R+;fz){H+E=vm;e zaNUj*YnK2^+HN>qxwigzEW`Ld!bhM>pTOZCzVe6}Npd12r3RWZvV;R(b@Sw>Q~7B+ z?SD6pYI^;$SINSDls?goBamG(x_`@qzUB5%YmEF^_$ie24=Age@j4smJbD2aXbirp6`V0Oo=gXUwTJI!Ge=3+&fr;WaZ(^;T=@eFo-&0R5P7n5BC|U@9-Pi zSkOE0f`TX=^k;xee-nB%+^O~4DYRv{z2$mp>8u*=E4fz>OL|ZcPSIIq(^>FDp$dzR zpkTpz^b4oc<2B}=UO1WIaEDCnfaM3o17xm%)vo3I@Wsz{f|9$W_2t=qi1~ zEvt@eonE#%A9u{W(qsD(U%hQ3@Mw+u!~4?n7@($Gu03G`mdf(H@T{(RuG;I$Hd187 z_aQO8g`G@Yn%PD*A9-1aww$@s+>#jWj7R>f2SkZ3KrQeIl0R>3nSX{A=g6LM3bIQ1 zft1DG5@sDBOD%X?S9hjo&LM$Evz-b(Yl+=D{Z>>cZHSlQLK(kZXG8rb4$ zsefqATH#|4%%>6C)u?FLwuJYP4PDsASC~E93Kes8Ss9rWM%@uU-m_wKBxrX(-lop< zK!p+>Qp5@GHIN(P$~2NyaDHJ=68YC!pZZuu`!bZBzLCi{S^L50ek7LK63;K0Cc(+G%17_v!_GT8=op87b>u8O>O98pPh8MCy+2K{4@S zkl6t#{SXlw!l#a!m$|W}zmvN%8`>YyC<4U__LcFQ2*@*n25nT_ID&lZFcnTMS_*Ep z8l76~$72q39U?EjF5mJXDtryn^EYd&E%x!)C#cOLvQ1WAo{kxLXDlOvXL^&~2S$M8 zdg{MtHC#?Z4P{^1II&Agv#XIzb&Xh9i;51iX9bh&@EPqR8g?VRJlm<44n-TL5S4(q z@<5*!Y$_*r>EZAOgo*9#ZcO9=YG@cqmXxVE*9nc7(V}fwZrDC~{a&(1#jlm0$>@DU z?!;HFQbj@+>Ks`c;yKD3*P^dEh`a8vLsTVUyE)P{Va8m}BP{(YBBCD|0biL4aK5rQ zSxUgMO3Y|}q0g>t&&omEVkMASUI_ZtWMxzxXt7@_Ka=5*qaK#Pm$VW)a6JP6w=&^d z$quuQ5qYpm&t1})#!B1wRgZf^>Ew;Xn%O6}x>iv;oDyFnREE1{~9jVgO#NUMTJPTrhSZQYjh))vv8lpH_Nq%45GuRK5hs$FxF{4og9VMPG zY}wMME%txUPu%TFD(ufE>_SDJg5*H_OpfOW`fI7#oP@=@FNn75^{D;3JAPb~BVF=v zJ>dXQ7}SnYj`>m2uF6Q$v2xmU_8F@4~oUDE2 zjtnW{*9893L(i9dA$&uQnt6^?-_WSV+p}e5^|!m^xoxB(ru@YxsUBZ3Pn*G)j)&Nx zW-MQ&BowQil!|4osDyVYsOp&e&REYTU+y$C)@J9N!+nw15n@zWx0tEt=j6j#%>+Ao zqs$;YpB%-n(F**-Ll#C8FDTZlqPg)RC?FW?mTNq9q>4|-93AEH?N97DRdI)sUXF=& z<0tWrZO@IY%_kj#mN|t(uW5@pa=S_D8`*)s`35=uY;#8Jli-hw$H>s{P(~@};xV&9 z#cij(F8!E*@S>&X*uFA9*)t|z#V4f9T}Hx5^~EW6L}^uw~r*jNpC*qiY`# zYu{o{oU{R*;$0$xg5E6Txe_SLhEQJ;1@ufacJmP=TEXueS#PYlXE#TXd;S@D45WL= z%-1|4Rtg1cGb{ZNuFIT#hy3KDi627}-pW={u{q24VZ=E{kjY*P@=a#Xu45#;*uD~{ z?yvGSXwQW`ldTc+kP(I!$l%TqM10Uj@h%6mGm9zX>r?g#q60<>36vsX=1z@eK6?{Y z>^{lc6dS3i?m#0&_#iHGW1NgAnUR8wd|dEiv&tdp~gJZl2(62hCcoBbv>&#EULY^V0SGowMXg>pMz&?kbCnv%X={y4Zlur zpHvBN=^uLp1s)$8l4#*Y*8R12sT-fFKwc}~ZW|c~&6N)+0~~E5!sWKH=^Q$QV8e(L zs4+Cb;W`_v7vEDGD8zF^Q6jBO>ainkVhBk+6 zGF*o68ywS1J3SNO#kC>TJX%g4Sw1gyRa}|6c*_qD==rbY;&z-Ei9Bc*k;oVPRW_WT zC~~-aF;z^o0*4pnU(V1`c)6Cb7e`RB>6#P~oM5e?pJMb+Yr5>S7lrB7KwZR&JL7IB zov|S&Wd^=+yl}ec(6)HnmUG|T{?z7KS$tPQ%6Od#;S^#f+~8v2osqf z^sU0<)Rd{n!>6#_iq(jHW$O3ESf1PDseEOv2*2N+@N?Ie(cRimi?R=ju8qKBhQAVVqK<);O7@IU$^I_7XXqH@QGKMi#{Grb$QDuu&dImv$|A0z-~@XP z#)^J%mvF%}T}h#!wmj6F?NEj|L;iN@GlF{p)YK6^Zj>|gnZQS<6gWSDvNG-Mlm?24 z5GwhH*qx~t5f&nw`C1t<;RCj*=Rsc^2Ogt9gOA=L#QVa^^YGdbA(EBh$vvOsc~C}{ z5Quo+l&A3(Dke}?Ew*HqXSj7p z|IO!g@0x3|Ry23!jO#(Zjfl5MNts}w^e+MH{wy^Li45-^N;%Q!h@GELo+aYl6l#&> zN3w@-k;K($QX8k0UYwk~sGAk{)|p$h}{o znNXuk=tU%v{{z*T6`{XLiMe$SoQS;tgH{!OMpv*X?au`xKOx(PPuzV(%m!wUcO$y_ zYo2n?>=1I2fbRl$hyWg&m_2i#s1O}-WWZ`3Qlb!?4v)r}D~mY66Q{URO61RyLJ+mJG}4z8gD38CgQV#%u*G7z`eJ*{Km2W85-=R5EiKFPw^ZQ_-5+ zWX4kK5LX?9Mx*S)>9oZdHm^uQC0 z$Uye^(gOM5D|^YH4661de@h94s7HUBC-)VIzL7&Xm%7F1gCZw1P_pvM4^xvSD@(#B zc@yv9h4uRgZfVFRygr1i>m2EBRE*n;&VfTPMz(?mhSTZMO`^#e z7lCs(_{@-Lf6N4n!h?p^`^s>@>!G5^I_Wb~C0Xk6%i55;ob*G!Ld|3!)#F>g{cMvF zMIqw!ktOo=l7xwktY2sGD32p(mo!OXhYKy&LNdvrv3ktC>w<{joA!Xo4vh$h@OV7$ z%TrqPIbKjsVL3?6MByxKuxC!@1s{IGVitd-$40>8khEmw>RU`+7n$Bp zgpXT*59!@*J{l7jT9{4Y2+*#^n86m((}jS&sGGn$*UQO*%TjvH&lxh*O>2E z`)IMtnfZ?A6YD4)8BVBhRI?sYM!Q2{4wo7Wj}0-p@DX_Lu$VI9^&Y;qX(I^R=v&Sa zSkni|ho$51pD>D84o8dc=FgQ6$LYGaeVnq76n<}Rd^@W;lwnGG)eU{z&hc%#Mbgd% zSs3vA$J(lBlxO3&Tb&l)@NCWfF?#f`eHdX+A#xM=Xj7(zbDY+Q;Z!!9{=dGiEn9X~ zg?1^gs#KbB8j}A1-X$;}3En;S&t8KPQ4uC!6nhnRr^^J~y~P25zAtuVj=4u>T+AX) zu*q)O3!rAnzbO%P^ly-&@nuGh85`nGDAuHBtom(ZQDdCqLXM{IQCu1_v}jVDk4y#f z4amfhKfpvh3obALbOr!EK{~(~rMSGnQ5lQT_z_wVebj1h{f2s4DHy_js+YapW)CJ~ zu1p6rJrZscp0U|Rt_QOr-CkAlU|#Aa(`udx{_!Q#svR=SsqK)^x1YrtAMbgysbtPB z+kB}t`ve8UcVh4KlP!!QYGat^K*r*a5)UW#x2U4Ar>wDMUi?3{t5{0r+TJ#n&L7`8 zhY0<>2S)h($%B8@Kf}K5p;9oaSHu{wyvey+FCW?yYbHoc|IE?3Tr z!E79-a?I41&IKPcgdrp-rIms=>vtG%^>6Dd8-Ev`@}M^-1z*Q(yR|WyzQR7-BfV#2 zM-mSAeK)v#C4#cfL4l?nHgn2vjinmG(L~ZR0JrvdlvuS?Zts~(q7M9o&@*PZfDN@e zDe&4urt$xd1R48`pPY-nVX&T~3Zsk`&nyb5lzR5JG_i3o9$!d&;EWA51=nyOLnvRURiv~4~Rf~qFMgRxliu_=rt%ffBUTbMVpUOTfA=f zC2g6MF{8RTbx?pxX`5c-h?5tJC54A`Ra^%8@K2L2er{XB-Dy@H!z_A4lt zG8{XP^)luh+{T;<*+7SGle|ldvk>dY(AH}rCknuR5WWLChK=cO%cjh$b|R~_jK8pl zdJTc`X({f}^DwCx0=eekFk77MR{f$@QN#X^{Fm%qzh8$f5%G3=O+-?f#RGfd!iX4S zjWYh>2ih`WeFH|0BfFQKpn>|ChZWw#M4^8~KxqaQt&*DCWfD zwM>H%jTKuRtsnv_)n+ovWP)9(4YEsL;epGdGmjpW<0JTTunZ6s7;@;AxSi5YecMh9 z4DlIGarJNG{F<+i?CZLECZD?ThrC5Fx1qSw7{yvE&MD{Om!=3M-1NiBP%jydy*BQ zpMu-z=ybK}3nhMW0b(p*Gr8Y)wekgb{e(-MvZ0O2v0~o?$MjotIKJB?W@8k9*3HTn z$_5Ov0|_=f7Bba7ARd)WmCzXD(zR&xJvFELxGmc3RuAYWfro@ZIJD(2nXvC+K>F7_ zL=Z!SWl{0*$px3UEs?>el!Jo35B(MeUKzefl+8xAJ-Ahkg`6j2uKmot&BiFnQiERO zSfzVJ!r6FTSn{QAk%H$XiS*RwD_c3Ko-<|`6SrGF<0%v7mUy)F91m0Vdt_)aOMND} zaUvpc={MQavy^&Ha$D4$+vZAAo`U`dFDa#mgw_ks09Qe#ev>paUA5ozTmU^}DdXh( z3}U^ScHO2-#0AR!VEZ+T&U^9c(=a`~TALlJI{)ktD4x1Ik#;{!CfG7sSy*(Y#1}`Y z@aB_!ottTmheA00sVTCrtl3G2pidpMr>1Sx;0BZFvNdbfo#lL^l&0;`@>FE1r+{c9xSC(5 zRI(+E!DKeRW)-5c-E0{5Zt>sGN6&!S@VhVmpXHgk@82FRo)-odNdEAdCI6&mO-okt zPpa|3r4TsRFZsi+mkXygklz4hd9(rY0B2E<--E{#1@SbzxG0tBply1M&=4$l&1-~M z6|T_n==q=djKxkP(ZY59$7)=d<6>{nZDyxvSEzf>HkV?f70X<6bTW)^&m0C7|>#EVy2`_4VQpEI+1Y{D1Gh3Kj<|Lu8OExSPKA zeGTj~8gI+&WhCmsZ5+k_y4dsNUZr@J*F>0E+#y2c(`o6F|FZC?6s^~b|FSTNO<&5! zc&>v|h+>9(w$ovyppA#ibW~QJI@M(=LmO*0`Qm}L4&bNftf@^ULeE*}YA=Q_c*Hd* zyCGN}x1omIHWpIwB{uhj+HAHD_(>Aavst%xpO4n~w!UmYmhx?O zRXTK=6xsM>V`;^!=To)uWr~W5zjpf3zIzvj|NBYY(ciGS*6B8molDh~!XEWo5~OFh zjV{MJD69E30?S;}Qt%BFdX$9aAiDcjH6)Td8tUeCT5rOvId`Pc{6l$tas zk)|R=sS#-yDfKC!<~=DG!{ByW@gynRuJJJH<&2CrA2;H0KRs3fqb99ZYiJx*6vk+a z4(Jc@t5k`JaEPyXKux-tNGcN!#(|%6jq%1 z$>*OgKYjL*7tXq`?ND2}k2~<%gVEr|?xo&r@7!HiO{Ok+>%t3v1D_ubR}`Ok<=(<> zQFwg+(@SM(1qW{N;6ryKbF)|IuaTx9?7D<90pv(AH;XV_yW%|9tSCe&gD` z-+cIU+mi>nu6^pyEBVf&7yWp6S^Ji)TY}Ww_KwsoFTMNbJsX~DJ81c`7eBpyWya0@^tkzWZd5`mJz(6@#NU55vAy$Bacm4aMP zm0mMc6HV47dVP?VnDPRb$#A$E_Mk9AT9eek%q%d>sT3#!e5eL6Lb%_tBeafV@C)1s z0u2?Wl4)y*N-fcbWVcC8*B@`HXn@ZXYTCd-;AI0&LqU9@f@5BAc+FrQNtsOJAakk? z5*Oke6D!Pv!Mtp86I@~;mu(x&Rc1ukz2McvT~DZEne~V;8eE}g`L^SYBZ>J{z(bWW z%HqW?1(39yKF;fw9L_nV5`m~enBdwpTz0%lG%`<;x!-^?K)i7}fgnxPOs0`Usg>2h zv?d8fV`SX%()^J(cJRot)BIX3FXn@8GU2SA3CYmRbwz7t(n{L=$_$rUX+rLiSk(+- zCC8;Cj1Y;e^yS@!f!@p6fvQn02W1EXs+L_ZGOB65CSt&vkui^IN9bglAI=XV>ih1b zLy;^b1t}&eU8oeAWisW5lSmSD9#n>Q$tXbj)fK`n%}-Do7#L4YO$k$q;D_T_N+y$7 zl(8(w;6yB%_NZBndC?VMuLi^!Zi#u3P{Slxei=K%SQ13sG?W8(LMNb(?;&Q`9P=wQ z&8u=rS2e8^Bf1PQC1S-y_+oKQGS#>umNdz3S_wB9JGZrFN=~K6ZM#=f@i?% zhVDbj3A{|I#q`4>gfnw0e-LXTYeNUpCWVg|N?~^0^E_Qt-}Cu@_P$(ZiD?G;ypi** zN*TIWU+zDKeG#K%TP>JDC3I_-e8mTjAw5JdH0xlX3Os9C|sET1HlH4;=YL>0GsM216)^evvEV~r8U zL7JapZ4XupXYah`+AQOaQ)PW8%tKZ=5F%DP9XW#)mZ*!WC`k!f2R>BYsaQ2pKkUe7 ziv!tJU8p!gP~M~yYoS3#U8v8q1at$mVb-tWf}{wdpy?{Qv7-Q1q_G=21+*q0A()3@ zGc+AhQZ`V|45u6qW{;o>VsqC|LXWsDWp$>3@}M{yga{>(lr$9CkTj^{B4SQljY8k2 zM%AmtBt4lFWL-$yCgDQQKu>n4XLLBBj{=rz?I(brMV6Qy|1ae_Tl2XZk`gDvIOA9g zu760^G(|%tRHrG5s=@n+eaLIlG)aL+!a|y&Bw@fGN0Swp;|pl80k;>@6h)R!l+|Py z*$ZS91xCgRG);#bI_{j7Jn>vyJPA#MCrVS6hNk0^u=b=Ha%KqJ3xb!O53eWovOu`c zEBUDY7{Yxyv@Rv(#H7}%$YM`cR1yr2DvM!1nDf#7Z-xI4k!T|#hocMT2+?(QzZ3GNy!xVy`nBzvFt?tN#i zSv_6VJwN?-cU67$6_g61;tVW|?1+?u$FaGH9Hh*ownkQnyu3`ZreDmREJ!)Q8YL!i z%g;`x4x~)tpADT%MNN%uO-%Xu5gnZzObu-i-7-(S$6^?{zs|qv^lSD6{OGdW!$GJa zIsDq}2SgUum4rt6lEwAgeT%8AwCl9;SX1z5zxbHza}jY2AhZ{F+x1NUrr?`=^zQ9- z<|)?qEo))I_jO(1bw}bsbA?tQcKPSTlIz1m*Xz;5+vSz-YpTH8MC{|0Z~N<8(Yw4( z>65%?uaxa6yXC*aFO#JsarEk*FvFrEcB@HL8 zQs2jX&9ma@KgRj`7?vRt_+Cy3bi6&I`FiF!=nFibbiF{h98LVb=}i}SyM6t={@kYZ zdb0jH82fhL^zQ9G59N$+`cZNCqD=OxuIuKj4c6Ok{ihg@pv`xiUlV>)rM-U3B641& z@{V)-l!YL5giBd86McR5ytVqP6K_yMueXXdE>H@D1GPJc5cq7CUzt^5yWy07c2j%f znNWWQBwc44I=k0n%Ir<pk6XWJ(PZ{?zuf(J;;23?01v?r{{2;p^Uz+*b&G)Z^~>+F z$Q*8VX0jw#`MPo6Hz4Kn+{5LSz#CN1p&071`Qf$tIIb$@5G%C!BW~AOz za+=>sV0GPI@adU8n5A9a%$TI9=cp5yF1Jtji2g3+DN4kzs;#O|#6L-&y` zRQESu*jGAlBic$%^WH^$zlB!9ft9JyD}n{Vce`R4bvao9q5cu z-g&ef;*_jZT9WK*AI+T4S5BZ!YG(wPCvuCr*yJ}&S!t7N#*yI4eaUA^$Krq9k?2_5 zpq`fRD17d2w!+8F_}Nr>I-%U^#X(y9Bvy|>F5Rg~>wY9=HGR$f`SxgT65{rd!w*ur zOx-h(uZ!9W>(-8NM_p4dB;~Au?1grnxz2fbd8GA9n#u~4O|9Q`m3}4X+8}zEI0tZ(#o@{KFHND9Kspw^%tcLXI!@%WIAfGP0M9q z|0)tIlnEy$fh|^A8|+0%#fdoNV*r3wsM!{)0#|%pb=1MH2h`fyM4*)i7*GnXXPgpo zWE$#kLQSg_WtRJ8oofrNwG_k0T=Q0GshiA*|dBNGvsT2H>C- z=+S@6cFS*Qh)gh1^%PpJ7Q2y4(V%XZJR-@>)Ujh?Ol!RFJWz@vk!-bEXUreT7FDeg zdyJO34WF;}a`bt0cYyR==(n*T)?A(@oZ~nNcdf0h=%5 z7nbWJB(I#lrV@NPFRuK(4J+`6o_?<1&$*0Jt$o7j<)(&Ww+>~vZ_1Rx#U>l#`8Gu! z3PQ?KhJ5G;)4CCg-efL?x2@?)cZIZThIrrjh68oHo+_#5OL~c=%?Y zG$SXWQpb*Bk!7yp>3zaEs}n*Kh{yRznxD2REnFTDH=ZGyao7*(StM%arMth(D&NsE zkU>+wG|`;cmiCAYfNZW^KG@#jxD%H0Q31IX$E0TBw?rx|C$q>@LICd_6d;lu~!x%H%U;> z@yW>Z><7x|Q|#~DZ)uTl&t1b;tAQR`N#_Ry2+ z_I@5Q=_D;!UfYmsQkkI^eUGEUQ9RsEid&MV7Fe-BO8JvhwxtvIOCMt^|7YdfLT&c? zkowySj^6RO8r8s|W*S|y?qb=e>`I+aE8B`8$cH}{U(;}^TOiv>dpQGbTRHNb6i1Rr z&~F6~)vaxms1)#(`k9S1E&7#aQde}4wzSP45{V{+-G0)<88*6c?(@}Cp|;@z>dfP} z$aZQ8?RB9ThY?zJOFgGdzu@g*jO@PQd2&}%Ru-*NU=ULQQqwTc?<0rPz_B(q_R4bES`BIXNotwz8{t`v zIG64shgmG9hL$Wh3f{7xR!&RpVB&>zQ?X;vFz7+q`+1~a3(`QsQ7E8AONn>Q+;UgU zS1->@2F=H*X<^wQJ{_t>q-C$ok_KOp5)XoQX<~}X>T@@(mfbwKlL&FfG;s4Xq>iHD z822IBT@(}Mt$S8T;ZfMUJEqX#G==g~qwA;W2jV&BL@k)1T_`G+ecRqw+16J60e9Z?z+OkbkQu`GcN}?_W1!Lk!NHOQ7ms6$d_Zqg)6O{nvNt3FE&I%{%F~VyND)o@1V!#d-6rN0()9<9c z>_E*|StVxI*7s*|LMOUM*ThHECSHEk3zHWoDmC0N1<2$ce0Q)QtIHvv5{9Vjl9hEm zNv7c&V*zr2F6SLAhsDUKJ&sxsd&ARI44Z0~m^>MupaIp!_cxU`&@Jp38IKlO|96{t zKhWuMJSe|_?+w2kl5d$H-cfFiEO(^%8|k6t5KX?Qq~c0<+cI(@ZZ2%jC=5-ZZqMm{ z@(7TWQc%?M-Lb!5JA6MWwW$kKj@!OVJ$~v=?MIjb@$L*wXpe1=VPJrAI0a2J7Y0)1 zH|bG)QV!wnXbU-y-#9^s=rjfBX%Nde7HrIIvp`Y?VNs>g-r^=Y@iZQtR=n+8w^K*a zmZPGJ9^|-m(w>72`l<1BOLHE<0r(*yqyURA%h21Xwqs68)m1rCuzz=!oY+mR6>Ckvf})rl3M{0zK7jI+A7nej4~;-*mcGx+*c?? zn4M{|XbI`iOMT%J12JwzYbm%eM&>Lbsj3|+tYsxf1`_Hs(ni_Z10*O*@*ARO*ncog zHB;1qoQ4kC1FSBM$S;2OGxr;XvCP+KfU`i0QJwcAcCsXFw8_@#s zmeoo-1WD2ahN1kV{PJQo3x2AMEUmmU+7d|A@Qxs5dq5^dJ|bgcTu zhHn%HB+KPK?-M_&3TBqbDHLJ|6+EvtWm9vzMguVp zo0LyDh_HtBhLNuLv@Q;m4=0I96XNZiqIXpC!ErG!4~tB0e3SMr-AG_^J`NhD;Pc+H zoK|CJK)opV5(|sxId3n+>l36{eH#U0On9%Tg!^j3o9a%IjDoMF&@)k+e;q2ZrE6HC z!;oRRD<)y9)!Gn{ynx7|!XU%BGRX$t1b!$ij?6_sFl3f%2oQ%smV!eMkDX#FL~jGf z4Q&D!ron)EFE>khGj|$5M8+Xpna0x{t*V1Q)=JJToS!Jfn9=M1wc7)sL*!&|6gUkf z%4zUHG}#fk!5tL1E^)6LV{4B`|HQ$EFCy+E0etP$!8)ZzXhQ12-pQ7=ivKaJc{N-! z-1pnHru^tk83$JAv0)8`FDqqqT5QZWMUFNRxMW_;NRI!y)^pY{JPb!~j0<&AAIUAe z#jVkSXC~NIZlte%lE5u&6*RPj-<%V%5bXf%5OfR@OqbLzcQR6_bwt<(l<){ge9xXd zwQ0lOg%F~tLoJQ5zd1pkC)fp~0c(HJQh@fYMvT5Jx)C|p(^h=C!DyFL_uK}=E5Ws> z4Z?+!Cf{*J9kq(&Ck{uD@7Sd)sZ~d@NJz%UMb2mysbH054UZiDu`(}g9!%~9i&i#6 zRItdC;f1ZX#n{1uMlej1FA=6eXPAfm^$QzP=AS2{E}4;G_fPZQr-2U@*+G-eUEEdb zbKM$w5!gf)zSPV(xQo)UI3VI9IHYrEg;mp;vkcxmAjh3~TIp9tW_enTOw*Gn9|r5D z)C?k%jMYkuR@q$5es8?_Iu{AwK8@;|g8kL3#Gh3%QU*R`IByBs5?5T(*s9~L3&y-y zKY@m=m9vLNs$*oK<85W2-}VQQB$G2fZlRn{6N}m>R0}Y>T~CI-}GFh+qUoRL+MsB8};1g(_l_F+^)kd+yx+ zi~Rcl!A}V%#Ixe}8AHtT^(1QCsXaMf#J>`+5L0ljOEV2cIiiYJ25`EL_6vzk*@NgV z?quwst{gD>ovJcIX}iw%gGgppU<=CIct6METlyQVkl*RP%(Bwa2drP^bNX)=L3Yi2 zP3NRAx4X$Nu5gEkF1DyJZ?p<#btzf=I6v8=DETK_=oD@&5j=4LUz zoikjA>IKiAX2xS@KUVJ}@j3iZszc^F|9c^^;%Kx6)%UPw+ppCJ*B^I3Q9B2u+)3)K zf!y4m!iQANLuLq8tVOP8&74;~$ed?WJmIy;Q&M`5Qq`|D#P}j%@^&@*Oab0Vxv7q& z>%ez?z&(|&zR70Tdh0g&C(Pt*tZQBHt*It27LsbuS)WAK~1Es^FC8I*v7k1Z!I-R@)RpS*E=>>&C`2a zPV9JxbiRCXua4R?0wh1k*!DV~N4W3@ht_AseawpSLew;mgXb6yB;NiJ<7FkC{K!xE zHfrV&YWX{h)ODP~bsFK|ks8e<4xZ;6&0fwu8v}uJ#LQuD_o(=CL-I14;AGOwJxH(2 zmtval`owi4kYM|V^rZoeJ97f>qMmt-hIuPPyk!Nn`(yxb^%Ck{MFMB*tNK@X#xn5) zRnSmryy@J#1bClD?>2t^#TPbrboz?5CaJQb;lRZvlE-=F zb&vgwt6Mw99NrI5l?-rn4mdkM0G9?q+#E02R4*H7BY`B_{!f; zs{?q$^l;vzjZ>h-kfOzyZ~y&;UWN}d{~>rGW(lfnL$r6P_ac`YfJdRo#~s}3h1lvCRfTKhl{Gf!p zLLe`5WtNaqm=F35u~q54Ji`SKZ$*5)Rnsh5yDi^MMQCRlZ``|K0Y1EsYfeYuGts)x zZ`V^%pW4JEpje|nrI}Ur_vKXxaTcS<?8g6{U?{ffCiVO=0KQB$t2~O>13Od2dIvK2Q#3UwckD z6^YzM&8Mi6%?rK|#w*kewqZ}5&VxjL2Bv&6VV-2j z9*tmyG71h386P>}xz!0{(3ISN?#$zX?0ou){=s`CDExU|nLJe(hEg(QCJs`4p7_(e z0Tcf6t3nk^(6%gHl_OH#&&Ep+g4WFNpu8j>1NR>#(%Y@HdVTd}k+?MjQj>zvbRF(k z#vxvV3WM>azqASMQxw(Ne9GfE#6dIn@dH^-N2n6#|w>E@B=Hu&d%Icm!`wy@+9P9TL^AD#$Sb31h z^%86gOw+y<2wdBB-ZKfdHodpJvRi{6v%fyNU_)k^oua}Q=g~gE(avTHY=8?SQCGpc z%heCib5WV_QzUo|smNeB5g_pP&*#uT!QG2*6{$-#(sXaIttdWFc){tlTJNyMjjpjZ zGQa8!|6#xA>T$U8?lOPgTPT_*#BKyqChc2ygTpBjGDeJ&0__Sy;X$0?pdH*$RNO|6 z`#SC@gj5^yKI_c&e)h{5gcPUTF_Qekf^M%KW!!o|+7~i0nx;CGb#JzB0DQ_ggr@NY-0kR$?o8CGhYJef#vqWNIcL%o+^iFil`8*Tauo z{i0wj#mS=bIeC77fw<6X7_Wu@Q7i>o&nq$bF)*m|joiBsElUW6D>$T(qq%NylDt*- z3;(y%`bE#XAuGTDhJBd%xUtQ82SkQ{7EU6Mq*e3f3e$vJ19lM5N6-mwaSK=Z&`y;(u#tiUrTy6ZIPCTa z81RN@Ohm&Lp`55H?;%WJB*W2b_Efb_JgNtn;Uxty^Ha$HjRU|gxy91L=mR(v)z{M#wMhb8>W%_TJV&DEz5ozjNuxX8EoY~3x7G# z<`FbPqkV+420ofK7J*T(aGwm}Km%e%Avl4{i#|d|Z#jYZhU2MUKXY)#_UeQ1u~|Km zUg^xrM8PL`z272qQf!Kl!vTojbaZg$FokoH%At`)8Ms~$w#1i$UtSQVW!6Yot0;Ps z@C(nVq8lw?^NjCVFH(E0?Bczh7Lig6z#n$prqj${M4oJlQ(e89x)Qq?l{@%)D7K$x zECZO>W?c=L{6Rhwm)f;xK0xkk5h7fRmNL>R2Na*R5#u5R3ONIe=G52neIYdyfVZ__ zgX72!VjMW_HF`6&W*?z+2(@?hldUWKF|YACADmeM;xkA9EpglE!@yd#`n_;i6!8;O z>r83)Kid*KdgwE{rT>{z5WIWuk2V~%e{1ILD1i~N1$y}(Shy1)I>F$$dH2|Pd33|3i$MAEX#q|U5#O##C22{$O(~h%a-u9|_eA=U zw(Om%fsATL*W2~)t{1};JBjXNAY}S)YO_xOKipt)gT^4gB@8HbBp40Uyy{Xs(6TDb zq6Bs-I{Kq0*+w3nrCq~x$jrc(ppy&(D!s;x_DVyuZ)Cqj(r^x0PY_MlNM3>OG_!K} zwva7jEY?6{=-vY#MB0k*m-)ux%veN{q0=j9-}~?FWRg7BHI}H`%XcAX+UN+C^O;iQ9vp_q=ayHJkZVrh6n-jUHC`6eJ7;P#gIzh z=nLQ~WBo+(3fsQ2M5R#X!%uexZ=H?IFhgV$%e5iFKG}s_dj;g*0sAv{sq=2*`v^Zp zaOZixzi2eauuTtkt0OAxFBJ}8fr(|a0v|VqZBExj+%-QY)OeI18)!oou!s-I12Uk3 zIgaxC2DEz*lZg*$F5aDnejcCi8dulUoB-$~IWHuggt5@?3^8w_%qz`k@#jil4g@I?VaPO8&9w6qrdX4rc2xqL zvN50=Rpy?a%8j1LWG5>zP44&u!#u0s&0XPz;xaL2z4?5IzCNg*37ttPoKV=UH}1!q z-LI6wK{z4LWGvqArI%+)cezuA`LKW1KRVe?^QV*ojIxUbrNl@D_vWc=)aOanrW^0L|6XlsFS~vTo{#bZE)6%9mvyciTF8R*yg_rwWWQs;=<7$T#Zf; z&(60m%8#eEG?69e$0HC4C`UD&8D&X*nHgbkvLkg z?(wjoN!r|Wfz=HityNHCvVH?3SJzI|ho;Y1{zA~XGKPS#e$ok?d;Q%~+WYj$W@O;W zFTC1-q=vvMhW2NqxfB$00NHZ96PG+C$>eN{k?NRmTMg05OsRqao@WIP>q{||b~(Z0 zQxxDG9l4<6$A~0!2y-@(|1oa~@$Pu^ZaVfb2(aJ7gcA1cVg@E-g!Hn@2ANN}2BsFe zf8nv-&=rlVUqzPPA@;FhhgG}s&hh16j+fM@J=h&|EYOx*P$&#(WvIvR!*q|4S3Wwsp$HUF$Io6DLVDeT0ghHrky{mEVwMBVM$@>^DN>uy)xY6+L6=N!~?J ze_5q~l**vC4tfpBlv&pb!U$Et+O;X~eWt$tGyMs!Jm6>6D?ef+@ zL7ZfE+l~1C;j1j-L|$ZJ6`QJ34wO)?TGCQPoz~bzw`$q^?ui;-*<37bbphA}LQ%_P zgawBI)cBB;y9s8D4~m!7O5n9W@B-$=bmT>ILkus=25-r z*7k@8YITERv+<*|@eQNWEA@7rT%H)U$3#`xl;=iOI51VCWmQ4SbCN0?tbe*}ihs0h zs$-YT+9mUlFc$I>H5gFYPI&)E#0rAYTNC+jxP0Q)Uh+0M+f*ZUJ1;Z4j%m9~679`k zbYt_U;PaNt8x)wS^hB{>mu*rQ0Fh{fSjH-#N0!uzhcQPqVddDS$C&DjJTW5826~`U zhqe3^Nfe=iHm3(%kiyQE%m6lYN@(kh-ro^T=+|3WuQ86Dy(+@~bz;a!lexKoeSAnh zP&O4zeUx7^a1sMbOI&aSu#fOZX%2H8DB5h{ROw6cLJ|A8eEzU*RPrKWKhRwh=V z@Yf7zR*c}}Qy!As;Ch7s+N2n7O=D(-=S82^*}ihCB-MP?v9#*%@P@q)EeCyCRp)Ad zbZbJCB?5bW%S;sB3-z!tkKs2(aYp_qpmLx~igVppGc-e$WvPQh$I1ijX$cEot;d{) zg*Np$oA(pGn*48)p%3cWkEi($UCTEQOgt05OMi7-e_bkCiR@=^+>IiH5*O@l1{qMm zL`C_fp)=b8QXwI)V*Yg5pmtMeF{=-@4;7guF0?s*U4&dzv2-GOO&C*Er z&`N%^(L6NNJiIe4DKahD``fN37my?u_~`!`_Rvdy%&McmsiwcF|I@+_vAZq<^|W_7 zVA=A$Q5pDt)d}#@oJRqBDmBc$P=H`wlJG%!tD-UiP=@B!rRm>(0CGr%^_)3v)mw)7 zOS^H(LSFf?=r}N-#KpUZ0C+&iIx3ja@95c@q}>h#=ZQe(|BfI)W)YHkeehQhcbmTZ zdQTmv=@#O)*wB#tJ;w`e#~2wK1!K>cqSd(De@C2E;E3WF&n}zO1iH`tn0E?%Z!sk!q;)T6C(W$%A_7Gj(M|8uiKs@jfd445~M;{EkYiR-%5pA0pH+ zq0puC0Tz^G*-1eVV^EOEz0~Ej14HPP%~N?UFZ zDht&|M#;9_#q9q;@QLr!^0;CIzxy;BSCaUJt^8)uXJ}5qFI^AW#iJ@bSwJ(ZgLH-Qxmlq$~u|Wg0(=Ur=E<@7b2|g|X26hQ|$-zCnfE zGWc0=*}Bq|Q1Jx1GQ*?unVR4Ga`;&g3cYDT0Hx^QHu}0V(foM_2iMI3=ixtu=;~W~ znvCKUk@>aAsA=Hn#uUV-e-P^Fh8i=^1`3HtF#ph!2l>Vju{-5w=cEOO>`JSeGym|A zFXDnnA*QjA6e#_RJl^`Ua{?_DX2HZ(di*@Qg+)+y4t_vL3_5%L=?@{NJw_7hp!!G+ zB!Z73lar`IB6Kh)#AFs0A*9)8kfQ!**LRO%lL~b}Hsbw@9Eed&eW%>FlS^|2B1VnW@bK=P0ptOKhtp_!ek=+!PXB2ZX}eWMZp)V@3v@M68f^qVn0lhlIFLiERon79PFCfd1^c2D9CM} z-}VL?T-0=TVaj5OwpodoOAfAA-Kxrb6#lho6GGQdOyvtp#D`-yOAcj)8sNP{40(eC zV=XvwJX?s-Eu`55JqZBkleVuZi5GL>>g3_DhF)Saw;b?+V<#JyD<|Y)2G5_{r%sqhSz}#X+Ao>cf(=5Nn_v z?3gaT0@jIZ1SqfTf?q=gQ4iQO2L_&Wx)o(0C2nx+RNR{}ct7!3g$dqNjYCQ>z!EiR zcLV30;aCrbBgMFZe>1);pxvx6wIXt#Vt-EMCmGG|DMUyK6KB76G&gQ@{C?p>7)6zyox&N%y;^d%-elnkZ@A#x?WYF-gZ zAK%#hsN;+#zxXIKPhDe&`iosJAlSRS3k;teuY$w0d=y~@&dA>ylaLYTG7HB|HT}Xe z{%|w2ISUF^j>VGabND9&E5{Q36(s+SfQ8p`yTj{hr>I;huqx=!^3B1I-`#!I&`o+l`aa_AsIum zaaz*Sw*trdPhxoU(S{B`q1$1Y?#MtP%DvHL|_tVpYQz zu`wU$)WFFmwWgIQhQrG!V7~|iao`65YZRrHB*KUQxf9}tfv#{0phkeC1Z6+dYA$<) zWET-7&WVI2WyJ<=vu`&AJ2hQ7g=olq%~g9JVqP)%T7Rvaqi&wbpnovOGi*MR1aoB_ zQD>@}#;3eJm1Zt;17UgBK9&smm+-(8J`-MK^#1(pnstHR!!v!vk8{CJ&l!FpLslu( z>lmx8HBuG#J=w?XyQdbzlTE|1VZ-s=Ty4=@?cU#ZU2TL!ZNx{P0X*!f$M6>92OX(5 z-IVM@nJ`RxcxCMzGNv74|FP#RtM5a!f{)f?iCYl}%)n{4&#-5N4_3KPDpjXxsE(1) ztV#WDz_p5g0nu6Mr@U+ex4jJH|>Z6;Lp)GRD0#De$j_g9+B&dEa1C2Wv|4K3ia%504&z^$aFJxk?c_$ z(0Jv}mkULwDhqoTKI+JB_O_fZvMV|{ zW_VNdvXR=rJ5#T>B7Lxv6xrJQnJ>hqrOzx?9SOVwA~NF6o23gT4L`4-U{SVRe2N57ZTBrjJz*t0BaR00- z*!RHBsDA4^>ch#V{we9V-md*L-26vW#d0@+pWg}?wynK^uN)%Hi^v^56qRBkL8&v% z3|}PKOJy22aW4CHWf$G*Bh)1 zjSbxBEiRZSKR`F48oW}HpUqyGWVEYBX=)dER0rQi zO3wNf8WaXBm$sUnj(z(T_^^H)O(_qJ5ki>>cDI8J-ouQ7d04WIX0iy zN+*UN;ekAdx!yV`uIj*~YEyr%o!s2b&=5{ypXhZ*$P~F_S^kiq$2q<}#D#cAy{BD) z>w^s2=m;pZ0*&F?#x2V=Oc|(#LOZT9SETvacFcxOSZ0gCVvZ(8Luq^o6p}c^*LH{K z?f@g^9B~bKktB_r3DvO!O&JeO^7 zvLy^~F+U~~1HPUkqfR_T)3~abTHwls_Dj7y*~;25<()|fpS@ZQsk>h76p`t-@nRXV z%^)GMbyYK8fxkNbeSxL_Rr$`taPzAp0ZN-kSFk{VLFKuZ5dF;nGtGw$%$}J{Qi9$Y z806k`va$1W?CFa;^zmR$cdHrUWnApr#3BJ9l_vDvIbng`Iyf&X+Mq&93w2jujB5d^ z?N`(D&pns?aXw{D59%6=t`iq;h)7R98hEQR{2{@cvTt0$!7TuDFuhrl^Rl%*S6yvc z9xw7kTC#26&O$>2+3y`UgwHm_eLU2L1nOTQA1pxs6=?pAKyM6+K%T!V88_-@NRMEV zTbZ^cBd1N7PNj>kL~`O1(VoFh0+Rp4ALi)26SOuCa>`aN27;bRe%CIZ9e4w#3_-lw z!&7~W%!M7J`ZcQSH_NC0FR=h-8(5*Vgu!fs1(<>$`@=Rw`F%$}56{|L*winb>a=dg z4us$j3Yb!63kkqxQoiLwNr=fYC?0VFJe2ykYg1pD2M74;952CYt+Be7ftrG@j|tti zGZ&@7;SA*N$%|X|U4HF!r{W!0(gySEBHLqdu|ayn`-RWn*ZS@aj}mtd})zuwucXV=~E<`Q7l7#ORqS`g^}k>|yI@+|wmaRT{;ksq4}vtzLW`5llS zCI1)Q{SBT|)+a~t+LVq)Oiu+22N)gagqdsBCYre7Wc{3PdA!@F+qPc8ng?8Bx$t7S z>)7GnvBJOqZGDs}JQOG%b>sJ?;`cS<@9Xk5QPJ2Q=wEHtWHd*0qM~?&Us6dpvyy#A zN3JMixdYX0MlOU(ZGND$61Ty&;+ix-ur1=hxrG2WTZ9}c6?()yU_}-eq�N z*>vv7rSD!Ct6&z~Dx0EE$Sa-;5?9oS@pl1iO7w`5;N3f335X{iN+H9 z;bLiU@i&ZcM{GS&eEhHJFpy=N!OTYeyHQr+f--;Xi2+19IORp5X!Nxg0TTav8!4FZ zpFTG_O4$s1y|zI3Zv9f5w|q7tEd98cbL!%dba}2I;x0E4N3t6^@p>F*#xq7mmL6Uh>sw_cDrB=q;hWL{;^tPPVNNn9BG*Pej1GX>hlw-{!O!lI_S6knN{1pw#K{Q1*dleb&eMJ2=lRM9x^mTir=h+X^n ze%p?l(NgkZVC{>gOvp%wqIRhih9sYI*?7T;wB~L;_y~W?)wi{9)y5M1BONvJ6i;cP zJj4Yj{xF^lplnl^`k+5FC@YkQ@E_$L$Fu=$P0h(o^tH=YoeC;HJ-~mR%rcEp($zSv zF+|Lyfs(FY@Db3(WL)t65JRJcA$HtKD9uvAt+D9tz;t}qd1BM%`%IT-$ZO^=@c*fw zy{++A@(H){{@`!rk3{Kr_>gMRSU*xD)*CRu7HuXC>950EPh013yTKjjraGh&4_YP?Id_jMke>@nu!6ZaE( z29Z2?PNw%GC&Gjh=`Y1hET+%5n8&0Q-$}(3-Q<(A$QUS4Trepkwxii4wGu16gPg8d z>1K7uRwxK#x*HXs%I;36*UaT`nLx(8%#8RvOFDMK_EQUvpT(5VAhcN)lDMv~lQNar zz2m#mGZ69_w8}~?2|gEaUxsLwW;F36R*Wji{pBzxs*^aIF`?#BAn8aAe*LN5f=jjX zfJH8tV?RG{i9cO@NPYYqZ19qW6szY<3(DXZ4{Pf=s9L5_K_j@s1P3vv+hhAoWS-)_ z4V#LFHaJX72RJ|LjmrD7rRy~x+B8s#Y7n47!@Da>{-4*-^eZ0ia8CIWEypi)mp`k8 zob5~LYEcpke5z2}n!h}4Y1fM0EW@7Z)WS!HcLP8}NBs4v zS=cp(LFhRedjDX++utwef}ut?t}h)0E7#&SRWm>ajf7Che-rtIvZM)f@Y0iD=mIu9 z8nXN5DIhQ?mXp8LFrz4aURjbmY@Cr&nNeC>@`p?_NbAh3*f5wbyoRJ_F0g%mAwL^l zXPW;V;rI}MQmJqx&zV(SdO&|dQWEi{iu1>L zL_fueOCBw3fL%Gb$fktNXVzimTDtrquKKSgs@S*;E*rO#8Nk7e^8Cvp{@^o0s2D%L z-!Xq++YsRX&`YZ3;By0w?+Tebr9(zghsln?T8 zr@;mT_KmxWB`8$S&mA9@M$RalX+9;#yTnX(78a$%zs6O7IiyTg!z~C;;gYWxsI(op zBz=3g()#N=(xKOurg)+E$dPh$q1R*?qK3+CohASgG-6!nT2KQ&tb^WQtBUzhsl z1Poa&S{Xt`RD=lRwQ7YGA+5)jq+_fec%FL%bDKZ5hpubB8ci%mRp50l_np*mXhWK7 z7aq&$-c+`#eAuA`RC>6%LwbJ@m-IYW)Fx>gWY;_>l_|K}vN9?l-okXnlbKc@x4*%Q zq};JvOYFr@>~&X1HCIA4SNqfM$#G{2ac8>j*uCGeGuyHAQRjXRV3iYVpVp>&XJV|%7B4^DS>CZ1TMOAf-Z}sn_E@cw4R?-IQi(Am4oT+WzZ6K~vKtwDPO=rv5 zBNdua`FzdixLC~Rq+;w68etA)38sftRpwxNJf}uSC~Y2^b0{- zDXH0X(pJnQwqCPWL_zf)&fi{^D<3UyjFv?{JDApfN>=8W>!7J#@NCYq(Ood7{M~V2 zv8V%V)^yu)f5=tAkViv_9N`mq%B7TT7}ki8otpP1p-}^CCegL_ji&wIY7wa;AJvJw zDzNNx3hTmO7MH{~X0)Qrk$;UtZbINh&u`K$=;5rqPS#9S)7)^o7NieAW`EF8L%daQUqC{zc3aL2w}V!lx!!;z*^ zC#F|5bCAMIRhyv=v1u}0Xvb>VsPg;J!(%q__u&)!h_h=1S^F|Aa?cf|_D}-Sd&_xT zPY6|P167kEja@$Yo|)3-2Er40t>=@xe|88|ZQlY20lPC}a_IT1m!%pVv^CKHWCK%T(RI$U_g#-D#Gq(Xs}(jrqgsY05X+0a^>qeyWF<2$LE~ zfeZIW^4CN|eWi$9)w=04FaH5P_&C2!<^F_t#E!Ob<3x8>nEhZyL>&akbXX|*P(=;Z zDBuY#)Nvl7ECBHGlG$H+*ncKaZ&<4VY{Uo)q76((cV>`6h!~iLlasVUZ1Ss3IWx2; zRIb6PmPvF;T9(N^pJ{o|D@`X_5~+oYDDZ7W1xj{LM^pChnjMv{#$t;d#yKsS^OM8m zrjqbuwa9w59d|_MnC3ZWE@C( zj8&TZJ3u61@Z^L9UIgyB{VFKhbK5@l!|C_IUo*{~M6REHpSrJtV*V)EPvZw({9}`C z9T%y?gy#Xw@$|rU`9eH7q?Q1R(Q^v2U>s-akU~>acR8&FebY1%&82f;Lo7}hB%7`x z5f_jSjZiMX=O%&N;LZ~WYB4c-H@E)Sj zk7;BKnVGY2!oVN7qV-b9K|)ni5u^TL?9f`(9;8^7%Hczu5*m@%9a*tolM8rt&5DE=J8UMoh5Q%|r;+BT%KJz=l zI6_$+nLubK1UaZ?$R!&VDwki`qy(WAd@%9d5=aL&L6U50Nfn&aizhPrreC4uEXo+7 z*~2Nvn6GToS2;3yE#aQD5q#XH029e}_U|XYp>rsrsBP7J-Q9K?VinfX`^4E}@zq@Z zm9J+jUU`2nk3F2kDQeAPGdk^e@0pCGJSvcJ_0nuIZ+WQ%eL>V=se~ng_**TTG53+7 z!;(}LIytJx&ZS};=Ba#AzRnnu690~qCB9sOmGy<4%_LRRp0MZaaQ|!{gMcjmbk|J9 zH)cfccY=;RCrQ8Zx#VGySO8{IT+Xx_bNNH<`rx0OIHwU4U=5o%iWZtlAeD?F@;O4 znOXd>P?jmqG(Z|o->f}|q~{uYNRn4QL!1}6;MQX%tZ1C@g1WpvVr_yd4Gs-tQMfjs z>%Drze@ZZ@JJYO9etD0g=DEj2KUc@y-K_+v<`w%68Tv1zKeS1!}3Cw`+ry!fK71 z>I=-TBok-CMwAU{>XCOi#DvdxOVIXqcKl``-={IYJ*9JkT^S4e2XgXef+&0U@-QOa z9EM&SyrUnXTFWYLR!`r1w95Biyh8Xs%wi9EuMT+MH^)9TgG~?=Ls%o0Jp6m$mC&Yg zr5StPNbGEH@0cZWLNDwWFk$da_;PW`P^^1v11Wq+w;WI_&(8Kr-C`s2^W@Y9@5ffY z$Tl~AP6l)tA8Z)Z3o}E>C+&!ji2~v0-S+7)27)^YssB$a&mIre_I)IzB&Eppty9ua z%$c{D33*2vG~RDx<_wcDGtCT!Qs}|Wqulh8B9}ywq#}vJtzVK?Poi>56zSnn+`8X= zP`B>)-tX`C`F-yB=j^lAS!=Jg*WPRIv-dhHNl>{rRT9kd)!BFBfymNO_t>#5bpe?p z#xtvf@nPxYQdVm{E6z>s@Hc*YdXO{-9lyHLv8lZq-Y5XR?CavY6;aV@VEvrGouQF69YntG8tg zo_a1=shzOvbyI$kPV2U@pBu_;XZ~v1d4r=h*7J6;?h{dQVMRTWo|520y=v84ym*jj zq7#>#&{lX$pfkvGZ0aRx6-HJ1>=_;U;>X>!zX>WN>Y|&RQ$dHRJJ8rl5QjKV-i+4O z78trHb>}0$>zf;v{tQVyXKMO6XzxOmg zAoX?n{x|FKFK;Hro2*NJJPbW8ySuJ^!@_-g)k=4L*s`y)PRXyW@y>?6HJav&G_7Eq zzgBmwQpWPxYt&@XCtDRGXY}0i(^XV)KdIc)cl~HEeq7U&^o@R?B#AgLQ4(OyI@&)(;YR*1r;zK6(xdC z@zMnmF!(Ll>53`U*|B`ljO7BOJEL`Pf4n!1Mt<=x>+UBxxvO^jvyQ|is~aahwlXnl zJ3iY3YrmwSeZ$DXmYSvO#+swjm+CI=3SKZPXDF=^@s*mVy>+Bt&s?~r_ru34(*y0F z=IbS79njh8eY=FbajMAtQ1HBW+M!w}^}I6^cyFbPIwd?{wm!7hv)6hRJ6BSa@~I%uElKXohO*EHxd~B9EyZ#N z6%ALp8CjHV#@282J`|~%(>bxay0_MP9Fy7>UE8pFdrDv3Lc!Lk@#B6~2cy|Txx4(A zIL>lraP79An472*zn|9hZU*CGciipH7i%7Esr4_p^>ipPw!a&(JIC~xetz@YX|ETy z-tF^q)ld2S=z=0HaBMcuHg)lHgOAkTZs$cdsm?p(*R1evewtZ2rR}a`SZ|e+wpvM< zpFu-rbk8|7I@Yy)y~pY(B`=zAR#QWqai!R+EdKsvZiT{~ALKWhn^);(gJN>*8NU5)M&;)0`-O&*G@UsCH7m5YZA)8t{z%d_ z@4asrXNC@WL~Ad)*kx~Y)KAwDNV^Ti((ZI@D9JRJ-I)6sgo=;iNNwfELZ^PTYw;U){b}Xi;)Wvh$4tHj+ zY)m7St=vw^^Gka2H8|n?^1eFKr~J2+<>Q_5VjVB{-QG-}+5Oca1IlFuLF0v+%FDy< z?806O)#x}_cVS5Vrf=CTJ`w!vj-i#Ai$AP*W374Rp>6)i z=E%h_uSpu)lG6_m3h_HX59tQJIznpb-L!j7kL$5e94+tD@I#hEoNdYc8*d_tZWzuk#W@G#H-XC+7jQ|kc0*o zhk$_)PR#J7`){-(3*L=O4|kCI`5Gs8RV(M~we?{n5k0Gi&kj zThBf)FpS;X=MYzLC#ZN$%IY0SZRxkLjxO&yuFcV}-kEzf=p8w8YF-Lc6$zoBlMW{P55{rWS`Jwul~7dEfx6DVq@H&PlJ6cYz- zFl$Ek)RsG#aL%tO%`M3Sji1XfRM&@pSiw+(*)rLa!y0!FDimb61kl|$y&IM8Ei)Ck z#VO~;=eoHazD6|2_?36sz`wC0Z|RMx2&ydg_rZIVn|0Q18rczhZmmM5(b6aUzxn#> zKCBVAua>3Vl*$`0=zm?{1uiNKOw|aP0RbNHqD*Bwxp1&>3^U#v+RW%vZf)T&tw2}^dvW{ZCO!o zPNz&AuiILiznUpmgqiH-Yg>r&ww7qX;vzY)L-y-@FUIo^<7#1AI|$icB&cx4PpeZp z30|q@#hspect2efYMXbB>3icT>6MxL8S9%WyH8GEHC(fH|Qt90twVTUWzq`6KE7Pv*uVA`Wy&;*j z_C)eKKIMb+@fWy(&n}avIPV6`Gh{~hh048ha-UMcd0F#>xaCU&6%>+JPf1=q5|NE= zhHYj!_B#(QA9lP~exno)*6T8WPS?Fysiz7{N}7~U=MPGB{dK5sW1+k&KnV16gDJXLMFRJW^AZ*}nZM zh?~3+w~mzW(pb1<#H0PZaom@mH=bUcoi~49h`#KRtxfK+*F2BGye?|OjvK$7fx3py zKW2s5Lvb-bCx8)T*|4e^>d?64&#GvS)XdxRHbQhwIqgi}DdF{qj8>`so~;L(fA5wy z3LnarWLtc27w^B5S%7usGR_)gTnX7Z=cvk#%6t&N>Ak1N&dz(mD|-7~o5xdLV9C6@ z7(Wn&diw|Y+p)1AVwSiR{MXVPDIgzI&vtsaTgj?oX-zB|>bZ4kVbi>xbJ_Y@y}8qO znklYJF^}JL(jYOEx9MKCL}}aOr31^u`jCM6KV6WH5{&MIwRKp7@b*;a`w#E6l81gT z8zL^Nc(v}jul=%$j`xsF8}=vF#Qev;eO~RwKR$c?GJ)Pm7GC70^-p-GB|%CQu)rQu zl{1C1AFDUd2L};o?7??o2mztkniECZon+0oqqL*{8nPIOax%tjW@H@`H~v3g%IqD$fSVIMkZbBGC@k4q_7nNYCOuEsRHs6!dBoJFqA-OKEnynlz3jASg45qBadr36AGY|~{{%=Na* z&=+KMS(qpc7y*)n@dXmP%oH<0LI-6O3}c{)SEQk)7*B>XBozwzp*$%>z|ydIBRtU% z;)+>eNTg643gNL73}7kdaOq6Y{U#ZLCsRy_R4SswaAag8Hj;=Hii2T1jYflU1eicD z0&f^eq6AWw%t#>71@%n`!t?w}CXiq!WWutAVKC1V#$$2tmx`=`I%1wk$`cA8v|?6} zFkEVi!4pX=5(h^!LMUvU5gw1Qjd0*H;vifWo6RN=DJ;^Lnnd47_+3>10qP=xCIBTm z7+RcgHX=5~Scs)OE+T{0h6p9n$?730mQ2FHQ`-LnLII2Ywf+Dx*#HnI(HWpua-*z) zTQJ2CaCm|dj$(vEH3K*+kZlxXAN@1V%;YOlD0T(rH2XV!Ak>L?hJVQ9x>i5LvJwU8Yi2E3QO_5acA|DcsP?5|>q!o~cFp3Pyy2p>Tu zk^n>Dft(yRohuZFu|U6Mi9~$hTF~wagHDApGXY2`Ps&HkCdQ2gUpiUf^U!fX=d%RC zrWn~ozYXV0F=ntx%!>dfg{5I4SSrF1I5aW~M-AW-2uJ{lj3WdD8I!01K?oJ0fe}C? zQH-%7$)vIPJhREdL@n?iHUEVvCqQ5n1FOPceT10`^bcMC9HT!RBbW|MF_Ea-1Eufh z-fx`imtm~`cfH;K%!la60VYDnj=nV=9auODjs)&xJO$vvsQWwA1gTK0&#-V^Z((T& zxrQJRgCz~|01i@O2-yqRSjZg_OHhAhjKveNI4qe$f_(LvfIB|O*8mGSi4ZZU9!xea zQ4%Q`V|0J6v?ZdjnFE7~#j|9@T1;OqP> z6C+#|9E2yTpe}gwf+%D%kqmL6Nf-fVYz*dN^nwImU<48wtVh0w;f(QMy8jc5OaYVp zcQEh()czhuz>$gnNlPVxg~)fb1RU)zU{oqt>-_mW{D08mafH8sQNgm{3$0Yl;_(qN zNEr>mF1%<2v Date: Fri, 10 Jun 2016 20:48:42 -0400 Subject: [PATCH 002/197] Added several code files and gtsam.pdf. --- doc/Code/LocalizationExample2.cpp | 7 +++++++ doc/Code/LocalizationFactor.cpp | 14 ++++++++++++++ doc/Code/LocalizationOutput4.txt | 14 ++++++++++++++ doc/Code/LocalizationOutput5.txt | 18 ++++++++++++++++++ doc/Code/OdometryExample.cpp | 15 +++++++++++++++ doc/Code/OdometryMarginals.cpp | 6 ++++++ doc/Code/OdometryOptimize.cpp | 9 +++++++++ doc/Code/OdometryOutput1.txt | 11 +++++++++++ doc/Code/OdometryOutput2.txt | 11 +++++++++++ doc/Code/OdometryOutput3.txt | 12 ++++++++++++ doc/Code/PlanarSLAMExample.m | 25 +++++++++++++++++++++++++ doc/Code/PlanarSLAMExample.txt | 7 +++++++ doc/Code/Pose2SLAMExample-graph.m | 15 +++++++++++++++ doc/Code/Pose2SLAMExample-graph2.m | 8 ++++++++ doc/Code/Pose2SLAMExample.cpp | 16 ++++++++++++++++ doc/Code/Pose2SLAMExample.m | 14 ++++++++++++++ doc/Code/Pose3SLAMExample-graph.m | 12 ++++++++++++ doc/Code/SFMExample.m | 9 +++++++++ doc/Code/VisualISAMExample.cpp | 24 ++++++++++++++++++++++++ doc/Code/calls.txt | 7 +++++++ doc/Code/print.txt | 23 +++++++++++++++++++++++ doc/Code/whos.txt | 7 +++++++ doc/gtsam.lyx | 14 +++++++------- doc/gtsam.pdf | Bin 0 -> 819397 bytes doc/images/Victoria.pdf | Bin 0 -> 62588 bytes doc/images/example1.pdf | Bin 0 -> 4430 bytes doc/images/example2.pdf | Bin 0 -> 4025 bytes 27 files changed, 291 insertions(+), 7 deletions(-) create mode 100644 doc/Code/LocalizationExample2.cpp create mode 100644 doc/Code/LocalizationFactor.cpp create mode 100644 doc/Code/LocalizationOutput4.txt create mode 100644 doc/Code/LocalizationOutput5.txt create mode 100644 doc/Code/OdometryExample.cpp create mode 100644 doc/Code/OdometryMarginals.cpp create mode 100644 doc/Code/OdometryOptimize.cpp create mode 100644 doc/Code/OdometryOutput1.txt create mode 100644 doc/Code/OdometryOutput2.txt create mode 100644 doc/Code/OdometryOutput3.txt create mode 100644 doc/Code/PlanarSLAMExample.m create mode 100644 doc/Code/PlanarSLAMExample.txt create mode 100644 doc/Code/Pose2SLAMExample-graph.m create mode 100644 doc/Code/Pose2SLAMExample-graph2.m create mode 100644 doc/Code/Pose2SLAMExample.cpp create mode 100644 doc/Code/Pose2SLAMExample.m create mode 100644 doc/Code/Pose3SLAMExample-graph.m create mode 100644 doc/Code/SFMExample.m create mode 100644 doc/Code/VisualISAMExample.cpp create mode 100644 doc/Code/calls.txt create mode 100644 doc/Code/print.txt create mode 100644 doc/Code/whos.txt create mode 100644 doc/gtsam.pdf create mode 100644 doc/images/Victoria.pdf create mode 100644 doc/images/example1.pdf create mode 100644 doc/images/example2.pdf diff --git a/doc/Code/LocalizationExample2.cpp b/doc/Code/LocalizationExample2.cpp new file mode 100644 index 000000000..42f19de9e --- /dev/null +++ b/doc/Code/LocalizationExample2.cpp @@ -0,0 +1,7 @@ +// add unary measurement factors, like GPS, on all three poses +noiseModel::Diagonal::shared_ptr unaryNoise = + unaryNoise::Diagonal::Sigmas((Vector(2)<< 0.1, 0.1)); // 10cm std on x,y +graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); +graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); +graph.add(boost::make_shared(3, 4.0, 0.0, unaryNoise)); + diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp new file mode 100644 index 000000000..9be7dce99 --- /dev/null +++ b/doc/Code/LocalizationFactor.cpp @@ -0,0 +1,14 @@ +class UnaryFactor: public NoiseModelFactor1 { + double mx_, my_; ///< X and Y measurements + +public: + UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): + NoiseModelFactor1(model, j), mx_(x), my_(y) {} + + Vector evaluateError(const Pose2& q, + boost::optional H = boost::none) const + { + if (H) (*H) = (Matrix(2,3)<< 1.0,0.0,0.0, 0.0,1.0,0.0); + return (Vector(2) << q.x() - mx_, q.y() - my_); + } +}; diff --git a/doc/Code/LocalizationOutput4.txt b/doc/Code/LocalizationOutput4.txt new file mode 100644 index 000000000..902b79f79 --- /dev/null +++ b/doc/Code/LocalizationOutput4.txt @@ -0,0 +1,14 @@ +Factor graph: +size: 5 +factor 0: BetweenFactor(1,2) + measured(2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 1: BetweenFactor(2,3) + measured(2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 2: keys = { 1 } + noise model: diagonal sigmas [0.1; 0.1]; +factor 3: keys = { 2 } + noise model: diagonal sigmas [0.1; 0.1]; +factor 4: keys = { 3 } + noise model: diagonal sigmas [0.1; 0.1]; diff --git a/doc/Code/LocalizationOutput5.txt b/doc/Code/LocalizationOutput5.txt new file mode 100644 index 000000000..d04162f20 --- /dev/null +++ b/doc/Code/LocalizationOutput5.txt @@ -0,0 +1,18 @@ +Final Result: +Values with 3 values: +Value 1: (-1.5e-14, 1.3e-15, -1.4e-16) +Value 2: (2, 3.1e-16, -8.5e-17) +Value 3: (4, -6e-16, -8.2e-17) + +x1 covariance: + 0.0083 4.3e-19 -1.1e-18 + 4.3e-19 0.0094 -0.0031 + -1.1e-18 -0.0031 0.0082 +x2 covariance: + 0.0071 2.5e-19 -3.4e-19 + 2.5e-19 0.0078 -0.0011 + -3.4e-19 -0.0011 0.0082 +x3 covariance: + 0.0083 4.4e-19 1.2e-18 + 4.4e-19 0.0094 0.0031 + 1.2e-18 0.0031 0.018 diff --git a/doc/Code/OdometryExample.cpp b/doc/Code/OdometryExample.cpp new file mode 100644 index 000000000..c2b6558a4 --- /dev/null +++ b/doc/Code/OdometryExample.cpp @@ -0,0 +1,15 @@ +// Create an empty nonlinear factor graph +NonlinearFactorGraph graph; + +// Add a Gaussian prior on pose x_1 +Pose2 priorMean(0.0, 0.0, 0.0); +noiseModel::Diagonal::shared_ptr priorNoise = + noiseModel::Diagonal::Sigmas((Vector(3)<< 0.3, 0.3, 0.1)); +graph.add(PriorFactor(1, priorMean, priorNoise)); + +// Add two odometry factors +Pose2 odometry(2.0, 0.0, 0.0); +noiseModel::Diagonal::shared_ptr odometryNoise = + noiseModel::Diagonal::Sigmas((Vector(3)<< 0.2, 0.2, 0.1)); +graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); +graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); diff --git a/doc/Code/OdometryMarginals.cpp b/doc/Code/OdometryMarginals.cpp new file mode 100644 index 000000000..e1b4ed411 --- /dev/null +++ b/doc/Code/OdometryMarginals.cpp @@ -0,0 +1,6 @@ +// Query the marginals +cout.precision(2); +Marginals marginals(graph, result); +cout << "x1 covariance:\n" << marginals.marginalCovariance(1) << endl; +cout << "x2 covariance:\n" << marginals.marginalCovariance(2) << endl; +cout << "x3 covariance:\n" << marginals.marginalCovariance(3) << endl; diff --git a/doc/Code/OdometryOptimize.cpp b/doc/Code/OdometryOptimize.cpp new file mode 100644 index 000000000..ee3c918d4 --- /dev/null +++ b/doc/Code/OdometryOptimize.cpp @@ -0,0 +1,9 @@ +// create (deliberatly inaccurate) initial estimate +Values initial; +initial.insert(1, Pose2(0.5, 0.0, 0.2)); +initial.insert(2, Pose2(2.3, 0.1, -0.2)); +initial.insert(3, Pose2(4.1, 0.1, 0.1)); + +// optimize using Levenberg-Marquardt optimization +Values result = LevenbergMarquardtOptimizer(graph, initial).optimize(); + diff --git a/doc/Code/OdometryOutput1.txt b/doc/Code/OdometryOutput1.txt new file mode 100644 index 000000000..cc34e8ef2 --- /dev/null +++ b/doc/Code/OdometryOutput1.txt @@ -0,0 +1,11 @@ +Factor Graph: +size: 3 +factor 0: PriorFactor on 1 + prior mean: (0, 0, 0) + noise model: diagonal sigmas [0.3; 0.3; 0.1]; +factor 1: BetweenFactor(1,2) + measured: (2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 2: BetweenFactor(2,3) + measured: (2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; diff --git a/doc/Code/OdometryOutput2.txt b/doc/Code/OdometryOutput2.txt new file mode 100644 index 000000000..acfa0b95d --- /dev/null +++ b/doc/Code/OdometryOutput2.txt @@ -0,0 +1,11 @@ +Initial Estimate: +Values with 3 values: +Value 1: (0.5, 0, 0.2) +Value 2: (2.3, 0.1, -0.2) +Value 3: (4.1, 0.1, 0.1) + +Final Result: +Values with 3 values: +Value 1: (-1.8e-16, 8.7e-18, -9.1e-19) +Value 2: (2, 7.4e-18, -2.5e-18) +Value 3: (4, -1.8e-18, -3.1e-18) diff --git a/doc/Code/OdometryOutput3.txt b/doc/Code/OdometryOutput3.txt new file mode 100644 index 000000000..e346ccb4d --- /dev/null +++ b/doc/Code/OdometryOutput3.txt @@ -0,0 +1,12 @@ +x1 covariance: + 0.09 1.1e-47 5.7e-33 + 1.1e-47 0.09 1.9e-17 + 5.7e-33 1.9e-17 0.01 +x2 covariance: + 0.13 4.7e-18 2.4e-18 + 4.7e-18 0.17 0.02 + 2.4e-18 0.02 0.02 +x3 covariance: + 0.17 2.7e-17 8.4e-18 + 2.7e-17 0.37 0.06 + 8.4e-18 0.06 0.03 diff --git a/doc/Code/PlanarSLAMExample.m b/doc/Code/PlanarSLAMExample.m new file mode 100644 index 000000000..0231d52d0 --- /dev/null +++ b/doc/Code/PlanarSLAMExample.m @@ -0,0 +1,25 @@ +% Create graph container and add factors to it +graph = NonlinearFactorGraph; + +% Create keys for variables +i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3); +j1 = symbol('l',1); j2 = symbol('l',2); + +% Add prior +priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +% add directly to graph +graph.add(PriorFactorPose2(i1, priorMean, priorNoise)); + +% Add odometry +odometry = Pose2(2.0, 0.0, 0.0); +odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise)); +graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise)); + +% Add bearing/range measurement factors +degrees = pi/180; +noiseModel = noiseModel.Diagonal.Sigmas([0.1; 0.2]); +graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), noiseModel)); +graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, noiseModel)); +graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, noiseModel)); diff --git a/doc/Code/PlanarSLAMExample.txt b/doc/Code/PlanarSLAMExample.txt new file mode 100644 index 000000000..507a6b5ec --- /dev/null +++ b/doc/Code/PlanarSLAMExample.txt @@ -0,0 +1,7 @@ +>> result +Values with 5 values: + l1: (2, 2) + l2: (4, 2) + x1: (-1.8e-16, 5.1e-17, -1.5e-17) + x2: (2, -5.8e-16, -4.6e-16) + x3: (4, -3.1e-15, -4.6e-16) diff --git a/doc/Code/Pose2SLAMExample-graph.m b/doc/Code/Pose2SLAMExample-graph.m new file mode 100644 index 000000000..0e384359c --- /dev/null +++ b/doc/Code/Pose2SLAMExample-graph.m @@ -0,0 +1,15 @@ +%% Initialize graph, initial estimate, and odometry noise +datafile = findExampleDataFile('w100.graph'); +model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]); +[graph,initial] = load2D(datafile, model); + +%% Add a Gaussian prior on pose x_0 +priorMean = Pose2(0, 0, 0); +priorNoise = noiseModel.Diagonal.Sigmas([0.01; 0.01; 0.01]); +graph.add(PriorFactorPose2(0, priorMean, priorNoise)); + +%% Optimize using Levenberg-Marquardt optimization and get marginals +optimizer = LevenbergMarquardtOptimizer(graph, initial); +result = optimizer.optimizeSafely; +marginals = Marginals(graph, result); + diff --git a/doc/Code/Pose2SLAMExample-graph2.m b/doc/Code/Pose2SLAMExample-graph2.m new file mode 100644 index 000000000..1cbd020d0 --- /dev/null +++ b/doc/Code/Pose2SLAMExample-graph2.m @@ -0,0 +1,8 @@ +%% Plot result, including covariance ellipses +figure(1);clf; plot(initial.xs(),initial.ys(),'g-*'); axis equal +hold on; plot(result.xs(),result.ys(),'b-*') +for i=1:result.size()-1 + pose_i = result.pose(i); + P{i}=marginals.marginalCovariance(i); + covarianceEllipse([pose_i.x;pose_i.y],P{i},'b') +end diff --git a/doc/Code/Pose2SLAMExample.cpp b/doc/Code/Pose2SLAMExample.cpp new file mode 100644 index 000000000..470f13397 --- /dev/null +++ b/doc/Code/Pose2SLAMExample.cpp @@ -0,0 +1,16 @@ +NonlinearFactorGraph graph; +noiseModel::Diagonal::shared_ptr priorNoise = + noiseModel::Diagonal::Sigmas((Vector(3)<< 0.3, 0.3, 0.1)); +graph.add(PriorFactor(1, Pose2(0,0,0), priorNoise)); + +// Add odometry factors +noiseModel::Diagonal::shared_ptr model = + noiseModel::Diagonal::Sigmas((Vector(3)<< 0.2, 0.2, 0.1)); +graph.add(BetweenFactor(1, 2, Pose2(2, 0, 0 ), model)); +graph.add(BetweenFactor(2, 3, Pose2(2, 0, M_PI_2), model)); +graph.add(BetweenFactor(3, 4, Pose2(2, 0, M_PI_2), model)); +graph.add(BetweenFactor(4, 5, Pose2(2, 0, M_PI_2), model)); + +// Add pose constraint +graph.add(BetweenFactor(5, 2, Pose2(2, 0, M_PI_2), model)); + diff --git a/doc/Code/Pose2SLAMExample.m b/doc/Code/Pose2SLAMExample.m new file mode 100644 index 000000000..561a07b1e --- /dev/null +++ b/doc/Code/Pose2SLAMExample.m @@ -0,0 +1,14 @@ +graph = NonlinearFactorGraph; +priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); +graph.add(PriorFactorPose2(1, Pose2(0, 0, 0), priorNoise)); + +%% Add odometry factors +model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); +graph.add(BetweenFactorPose2(1, 2, Pose2(2, 0, 0 ), model)); +graph.add(BetweenFactorPose2(2, 3, Pose2(2, 0, pi/2), model)); +graph.add(BetweenFactorPose2(3, 4, Pose2(2, 0, pi/2), model)); +graph.add(BetweenFactorPose2(4, 5, Pose2(2, 0, pi/2), model)); + +%% Add pose constraint +graph.add(BetweenFactorPose2(5, 2, Pose2(2, 0, pi/2), model)); + diff --git a/doc/Code/Pose3SLAMExample-graph.m b/doc/Code/Pose3SLAMExample-graph.m new file mode 100644 index 000000000..dde5ba85e --- /dev/null +++ b/doc/Code/Pose3SLAMExample-graph.m @@ -0,0 +1,12 @@ +%% Initialize graph, initial estimate, and odometry noise +datafile = findExampleDataFile('sphere2500.txt'); +model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 0.1; 0.1; 0.1]); +[graph,initial] = load3D(datafile, model, true, 2500); +plot3DTrajectory(initial,'g-',false); % Plot Initial Estimate + +%% Read again, now with all constraints, and optimize +graph = load3D(datafile, model); +graph.add(NonlinearEqualityPose3(0, initial.at(0))); +optimizer = LevenbergMarquardtOptimizer(graph, initial); +result = optimizer.optimizeSafely(); +plot3DTrajectory(result, 'r-', false); axis equal; diff --git a/doc/Code/SFMExample.m b/doc/Code/SFMExample.m new file mode 100644 index 000000000..cb6bdf00b --- /dev/null +++ b/doc/Code/SFMExample.m @@ -0,0 +1,9 @@ +%% Add factors for all measurements +noise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma); +for i=1:length(Z), + for k=1:length(Z{i}) + j = J{i}{k}; + G.add(GenericProjectionFactorCal3_S2( + Z{i}{k}, noise, symbol('x',i), symbol('p',j), K)); + end +end diff --git a/doc/Code/VisualISAMExample.cpp b/doc/Code/VisualISAMExample.cpp new file mode 100644 index 000000000..345913cd9 --- /dev/null +++ b/doc/Code/VisualISAMExample.cpp @@ -0,0 +1,24 @@ +int relinearizeInterval = 3; +NonlinearISAM isam(relinearizeInterval); + +// ... first frame initialization omitted ... + +// Loop over the different poses, adding the observations to iSAM +for (size_t i = 1; i < poses.size(); ++i) { + + // Add factors for each landmark observation + NonlinearFactorGraph graph; + for (size_t j = 0; j < points.size(); ++j) { + graph.add( + GenericProjectionFactor + (z[i][j], noise,Symbol('x', i), Symbol('l', j), K) + ); + } + + // Add an initial guess for the current pose + Values initialEstimate; + initialEstimate.insert(Symbol('x', i), initial_x[i]); + + // Update iSAM with the new factors + isam.update(graph, initialEstimate); + } diff --git a/doc/Code/calls.txt b/doc/Code/calls.txt new file mode 100644 index 000000000..2afd2fd12 --- /dev/null +++ b/doc/Code/calls.txt @@ -0,0 +1,7 @@ +>> graph.error(initialEstimate) +ans = + 20.1086 + +>> graph.error(result) +ans = + 8.2631e-18 diff --git a/doc/Code/print.txt b/doc/Code/print.txt new file mode 100644 index 000000000..da8fb3b2a --- /dev/null +++ b/doc/Code/print.txt @@ -0,0 +1,23 @@ +>> priorNoise +diagonal sigmas [0.3; 0.3; 0.1]; + +>> graph +size: 6 +factor 0: PriorFactor on 1 + prior mean: (0, 0, 0) + noise model: diagonal sigmas [0.3; 0.3; 0.1]; +factor 1: BetweenFactor(1,2) + measured: (2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 2: BetweenFactor(2,3) + measured: (2, 0, 1.6) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 3: BetweenFactor(3,4) + measured: (2, 0, 1.6) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 4: BetweenFactor(4,5) + measured: (2, 0, 1.6) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; +factor 5: BetweenFactor(5,2) + measured: (2, 0, 1.6) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; diff --git a/doc/Code/whos.txt b/doc/Code/whos.txt new file mode 100644 index 000000000..592fedca9 --- /dev/null +++ b/doc/Code/whos.txt @@ -0,0 +1,7 @@ +>> whos + Name Size Bytes Class + graph 1x1 112 gtsam.NonlinearFactorGraph + priorNoise 1x1 112 gtsam.noiseModel.Diagonal + model 1x1 112 gtsam.noiseModel.Diagonal + initialEstimate 1x1 112 gtsam.Values + optimizer 1x1 112 gtsam.LevenbergMarquardtOptimizer diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 38b601d23..9d1e6831a 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -139,7 +139,7 @@ September 2014 \begin_layout Standard \begin_inset CommandInset include LatexCommand input -filename "../common_macros.tex" +filename "common_macros.tex" \end_inset @@ -2129,12 +2129,12 @@ loop closure placement h wide false sideways false -status collapsed +status open \begin_layout Plain Layout \align center \begin_inset Graphics - filename figures/PoseSLAM/example.pdf + filename images/example1.pdf width 80text% BoundingBox 30bp 170bp 610bp 630bp clip @@ -2662,12 +2662,12 @@ reference "fig:SLAM" placement h wide false sideways false -status collapsed +status open \begin_layout Plain Layout \align center \begin_inset Graphics - filename figures/PlanarSLAM/example.pdf + filename images/example2.pdf scale 47 BoundingBox 90bp 220bp 520bp 555bp clip @@ -3014,12 +3014,12 @@ A Real-World Example placement h wide false sideways false -status collapsed +status open \begin_layout Plain Layout \align center \begin_inset Graphics - filename figures/PlanarSLAM/Victoria.pdf + filename images/Victoria.pdf width 90text% BoundingBox 0bp 0bp 420bp 180bp clip diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf new file mode 100644 index 0000000000000000000000000000000000000000..a5b92ec27362e7b2a3153fc98ed45406a4a5e2ac GIT binary patch literal 819397 zcmb^3bChJwo-pdNx@_CFyKLL8%Cc>A*?##Jsefh`E zT(KiFSNtM(;EA0VeJfXBxDe?HgpDv0F3QS05E)fFiy^n07DxX_ca#{>4bH5b+<4?K{zr z{ZE^3v5F1IX#^3ZdNv3&ap=C}d8+ZIzUjcKm7n`QI*|i3&w*D<8H~^!^12>;kFY5= zfVlPIx8ah|7B!;nF}iflRDn} zkc2a=vIk#l6P}x^fE1_VQO)VH_@I%__}k*h&01xrb{6f)b2$Wx5O~rIC+;WlV`n4F zO!xwaw&@$!_=(Cw2WkrtFVxz{QTM7b!L0vS`L`s z77StRXYmrz2-2bP(#ug{SrT5A`mQx$2Io}r#bj1Q_Jw$(kv&a|$ZnETJpCM7VW)>A&Qb4?|QXEFnWRRkgfQ@h}P;8{; z8S0=MBlt0fUP?-*MF6qN%=t7lvcv4gdrP6+FQKU9PB5mv%F>q9|LuEzyIm*OWGBW3 zH(hCuUNmU6Qr1R2M?Ofeg^{Oz`F8@RFrjhMam6%@J={Vbc_j=%NQ|wkt4$?$66*U6 zT`mi$NDRqt_R-}QS?q#bNo|s}!-VM<(lmxUsy4SX9am6dr`hw61b zB6iu#9V{P%_rjt_+!{mtSK>BkjSbtZ#~%YnLa=m{(>$ug>7%X===n#ZWar@n@(B~r zrk0)UEr}H%lK^HNis`HiS>0lFSu|3np(pKeb{nh!K8>`JuB7N#Rj>XYvU6yYy&l{Y1BcxkDYB?0<0V58k%z`y1ZQr-L2U*2%TD2KP7)UPFKfagjR{v zpQR0-D@!1kD1q z)WjnL$Y-Z_$(UK20zv97%M9&8sxZhFH%1Yd3+}2G-GBfakcvW{YEVgAmO~R(wUI4u z`%>LA*vz}y3)E0XY<{{bc&RPe_+&4j|6W~s*ksI3H^n4^bncx0V$6m)bVm335U2;A z$D3#nU|sQvUkTsfDT|M@#Wr3m786!6CgnDH1zLeYfM;5MyarQX_ev=!F5cUCyLmW= zIFxHDT0=fcA@DQVnR~8XO+pDs6R6RH<6Cj6?bw%PqcLyfYi~Ej?HyzJ=5Mtb;4VO0 zZisuqrAn$*46M4GLDqeikEH-(XSRIQnDQ7WgP|>u- z$>6?DF}Gyogy}pl`hA5|vU>-pH|M!vYnehL17@1kX5KgMv9rSN>(kE!n6bo^ zJUD6bioD>McXLU&`B}*4A9G?7{i+~~hm8MSO$hZ2 zgFNpBCDwDvjnJ{o0;d*p)7FL})_i6CIrw0zsz@ip-Kw@?M8uo{Bj8-eKKvn>^=cm4 zD=Q_fe3awp}oR_2x&qu{&Q-hs9 z{yWKSerMl_q*33Q)8Tx==Djj$r4O||Phi()0S{Y!|4PX+?sOAw@s8Ukk*vwUpeXKz zTDJmA9auovgzpPCw?z^K!Lj&d;x!ty6~HXRi0+tE19o2m3zQWc5Ro3-f7@2?<*02# z4sC6l7ZYV>emR!^91jycu%q@+;M>LQh?|oG z8`2tP3&ue`duw)jyt@>}XuSg|xq#9-uWNgi5r5AI>bljOuH2V8cdTJCV#+}3CwvMt zNh8)BKwNi`@s{Igss{l>zcXiL`7JQDAvpDjRX2Qp zyIM{&hBx7v2)!3&CMSRkoT7-zxnFv}+Bsv9J4gK774ub|9qk!M*vA`zn{$J|+u@7s z#U}>Us*b-~m5IuIzr*KP&C=R2{XNG>q*Yp0d{KUvY@{n_B?tadh0KAw+V4eg`!tUa z?~HhfDibmcg1$a5mnM+O*mUCdvi7P;Jv!XZ^__(N>b#x?!H$6D*mnA!E9%q$fi_|X zNTPB6())=CBX8)s7R@G4jMfq(EnYM-eFHcx4a@T;>;r&V8hlF?pLTzJls$Ggr|0*; zI8-Gg1rA4qE)Gj@?H{Z8vUR!;+E`u?d~K>Z5c!hQ5CKG2`&}N&vT@M zGo5INp=_!EvMZxI89G2^GJJ!cmM6uUMCqUU(KBIY&p^#Va^#L8=fRrPQq@HY+1tuv zzfhNS;yuaXxPYjd=7km9X5`I#r_`L_X0#f3=!~Bqu9WB29nZdmQ-Es3KNEKSS&AZf zHqZf@Ax31k-q?}ebxP(e7we4Cay_@f|HF|c8I*8c$n@*Yjafa}72R4;=;U`RQDSqS z2mQS}$i{)8GfaK`HP}`9@aAe{GqM*;x!GAIl`mC73;rG4CFXb9D`z9#h&yFnbVbO_ z=-*G5_^?m!oX*E%vMMx%yG{Ao*w>8q(c_99`@4Tx7CvLaCtWC@fhTTO z=zQ;UnwL3o9IzMx3JfpTq_*7O)Yiql(xq5-$Q(|g8s1-`iut1(@l(bRTH7xG?6We{ zt7e=Qe}0D5_8Zaj){5O3ym)N?o>n*oFe!=(vLem$rxUpPHNAm(t4kC?)Lfv|G|C3>($yBi`KGb?)t|^i@CGFL;_TN)pX6<#wRxUpY6V zy|4V~uIv~p1MLvwMUz(B4+;%56^9xsg=u#82oT*(F11W9%Yla<3eGD2ew}8WD$9ukAahs-dZ$n;z%du-SQ`&HT`Uy`PDFj13`b(tCTw0}q0bx4X z3=FG!5tW6Zy`$$oGz2*IEuXsB_IK| zYY0T1UlcF;c6Jv}tVT%E%z2{dqfsc83Fft}ua_YORm&Jvr8w6(dR?nECk%^|{5#8) zYjA09R#T9X#IbO@#;hbd#c?X}q~YSH8GHTkh^O|$dYYbdFD~KReqPU4;7hIm-Ab=9E5=wa z-*GxrwyeSO*jOZ8y6U16sJ9mWw>nUHQE{r3ZRXNjWgv**2GtKM{~-&ZhKq3T>jGr* zLyd}v!?{Eazm$HE3h`vCbrtFQp)&^7Tz`E^-UE~Z?j5AkCK!oF$c9w1`ql&5&s=9A z5aM`5v4q+RjafO7P+jfd1kC_dO>0Mr>LxhCKCNBxLs@0Ihz-SYUoSx1uQ~~nj*>9| zlQEF8>XDUopfZQ(8}ti>VQGqW>a3b}g-o2`I(qqr#kZ1lM__waqBu7zhd7N&uoYKS zLu&z~IOHkMRi9Xrho5UAr&a4l-y0ypnl6UkgFsah<7J?u*8&1NCa~htE*9>4`Qjze z;6ga(AUL6V4uw_s<(8LP2Mr7#=`fJxv^Njk2C>s+Q2bLBWd){ke9jIAN(WCCHmZpU zxSsq#c^vYTT)^LpR@0!+A=|v8Iuj}B35K)Bs{Ffdb44(H_LX%Z{oWnlqo)8aEi(qY zvNm@R9!{WaGwnDEr$kE=%zbm&&!30lGr%ndlHxs0z?4TqR((A*=`4aKbE{vK4#@eO z?&MZh;;6qVo4{3r9joN5eh3L0QZWf0Ks5-NkcQu1Gi+{$sm$kb^er&ZL+o%51a5T6Y$i^92IhsOnV z8ljizPiB5o67vyCuJw3>zXFuPR1W)BvwmBXe!^tQ)QAf$u}{-2s2CP+AJZOqA^*~_ zj+mbMcvNw41i|3xTNxraCu)N1qeuj*L*|8q8*xYy`aL0mxPNKJj!MzQ`et<;A8luWMATwXu|si8ie( zbUI&^XASnjVF80+Wig;oANK)pSm9o&Y$OM$vRI-^x7z?wZC#KXFY)PwNJpV0?1b~K zDt29kF&Sz|CMzVjE(>_++x)Ova~)x-AZSp|X?t#p0LLjcC^SYVe)I?(+S z{Z?$KV}_oq8UIc5V8X}cbsx;n^Kfcx`gowLRUjR7M#~+-t9$^1JatF4&o&lG4yY-^ z>~ua#Y>new5dZm5LAGa_9~zJuJ+i0>$R~7Y-8kR-w&t7b)S6Sr&kG}+%;vrMDuQhd zH17a`eFxq5#UEks=io>=s0Vye=TK+LAiL9p6OZ2h$1Ja{^gWu*J!X;fhpBPu zu?hN+EZdm?dSvpC5;~ZD(X5`xj+Fwi`%|g54UUvV^IxN{ug<=_IakY>2dh*Lc-m60GT8qRP0O_ zp)vOtjBAHh1~M_CZWd{^EqC>sG%+MtZkE^TB4?-wZtafHMx*<(i@!5cebVNzw=<1v zX|HVFI!kYvAX!^=BZ9}#+FzyXo5D{}i$d|W%tc8L_oWXE3jI?uB#2iS%>c`;qkvU? zV%5VSiWsk(+^GwaEPaJtBF6Ih=w~Y4 zq-4&1wZ0J$ytODgDDfn5i1Z@>j~QhmtQD5V)%rQw8#a(%Yho1ETx|j0G6dX!ZPtTh zp=%lu6gX^Zd#>_2s?TI&N?q3#T&gKAP*BF;vk9zq;1hE>9fDuKQF=KXTTIw6N8G)* z7TGxWJ~H^6f?Tx2!A~6f5Ek{=me+1~`d$NMW8pq&W2Wus@!@$7YQ%6c(Ic0uKJIe`d)fM2o;Kg($ zX!!~}bzrLe*b+VYWLQ~n`_)T&Mbs+R4t(&Cw<&}T(*O_)%4F0MgsttMEj(78sV-q& z=6R-K+*v-=U-!R*D;n$ePRwIbBQ&G_%pGhpRlQu2&h$Dire7kjt{oi)3H`RtnU$iw zocWgIInvQ5h+>AKU4;hhZ1-!U@9p?!0Ee`BQBTat6(GUOZSb};^=FxvKRD9&{0hDAzO*_4dR5KE)@`fhv!|ot>IWVv-`e}{?`odWF*!?=m6JuM+#f8XXYjb? zqAae%#L2)B0MmWvx6oLlGuSU+e{Fx)e;%_jvHrI)n~H}$fRI5$-pCSQ>|*5n zcZ!&uqYVs$kdU1_p*G{6{48u-^jutAgiK5j}E0Xu};zbM{+$Ls&Oc>lc^3M!%+^nYL*AZKU;Af%*cVA40YvjOOP z7~1JO8QPi{*|`Ip^v#@|3~lsH?2Pp-Yz)o*B$(US(A%4sQo%6%{Q(Mp66IWMjQ;5O zpV0iBBx!4ECt_jjOvv(AeEtODzkzJ5i01sRX$tVZ5bfF>ex0HSsfz*QIyDMAl-*g4-PZAz%DzyVja zyyR`#KfZpSBY=r_owbrs)#prk+*JQi^i!8>p5Bb^dN+EUl)u~V9;((KJL71vFX!`F zTGH?-%v`jq4GJkiNTiS=IAX#%=7SzMPk8GqGNTr>&~ruXP;I$BAkLPU)m? zmq=DD7&odZvTQXPFX@!nz~R4N!%`&vYU z$TqURO|d86K`A~DX-FvL*=y6#od=F4zxr;r|3PdDx*1fTMG0EUIq?{utcXRJqp9CC z+H5}RS5@Bgl>^ppZj{YZ3qy_&CB)sy8X2xQuDs4|kt&yGh9)FQnW!eP49{^@o!#yG zxN^?K&aUBm2!bJPLWsguFCs18t^qhW>##$y23v{g1tm-umqfnQMGizB6|s$Nj_l;G#(Ea zVgcz4@DsxfFlh+9cMBxm>%K-f3(y{`N#wZ8iAfGb7OMzXefRMc+>bAW8Nr8GVT>KGLWolxnH1=@&e1mYGFP7AX&UC=(0@@wI#fuo0g)b)2H=YidCPh{ zy+~OE*heG7yv>Xh5i#O$;u{qqL@QX9gAooRG)v2}!v!cg?g{yr>vY3KyB@ipp2FTt z5v=uX&d$WtXxkPBa;gHq1_rI)ZW$OMMw;Uiu4SD7p)Re;rY-ODhMGQG5kJK|?gJkrS2^KpXpuKxy z9oJR>tW9h;zv;}7G+Q|A5^|AK_tVeJ$weypn5Czsu~F!MRDI!jg-=h zHT@g^MI3oqf+v%HP5z|^$iF*Itj;!Me%Xaqe;>UMf&PS8<`_}oLB|lAL@?=QR7Le1(oBXkm~ipesjh>pn2+?>tV={y*_EV; zC3B-oZj*xYNv+73knZf7&SCO(i5u-PU({OI9Ii*8hkw4y`AyfsPXF%MGlrF^7tgLC*$I};c4e_tca?Bx9BtgPDfmg!|@8~@ZKnZa(c=7=&^ zAe+E$F^>@3&?%r~F)D9^L(>@YIVE*neXkw>q^oe$RD2_2(&4N z>~g&4bCn)wvV6qmM5A-;$zI+D4ag3}V0fe9;)v``?Q#Z)Gzr*V+fJ|Js0c9qX$W%m ziF$nC?AGYk^?0kB1Bxj}Se=K1HDuU{ar#Z-*o8sU#cImY5xK`)aILPTIv=kms4L31 zz$v+5yG@2Cnm_VErNCxf&6)0PdU>fk_`#^*3t6Eie;cwzEGjv4G?c3Jn3aiHd<;0b z+Du@&_7PUNk{eE6o>02{Z9s3?`qsTjA4(1fUXDWtMves*GMAkbmsO`HcYuI#E&6rk za^q~}u)1ZaI%Xi1U(X@W4Fv1t9O!o$`RE*qs>i<6>CwXEX-4L{?z+$V$GWsTT(M;C zska4rLhh&p$8q|wNo$=HGw7>_ZAyE=7+clCNKI?eMii`N9d{+YI=9uKR3#Z1wwbMk zE#c3UL@VQl)i!874$#%bLOGOi^s@Xa?#)BT;#^Zb!X4RsRuYB1v2lrI1)E*f3N76H z<=L}e#R}Tym6cOvrO|N{!cPDWY8rgz%zhV$Kq+|^b)@`OOX;x&qiOE`ac!jtIvB8g z;vQSz{u-_l=dB%R&mY?MGFZW9EmsYFl(z{U_Xc_ZxKdIXrcs7wGjn&@kkL$wDRQ(V zv_rsal_GgHiE$WLzn-4(*tm}5fmJ80*H8tQ8{%o;X0!9mmPFHffjrNBihx!;#~Zg} zRqIJx_KV$U(^_&`KV%ic_RD#9irLEeK!|&`vU+puL&9&C?-k>NCt!ARU8C3pq)V1& zrdo<+F)ca^@!d?H`MbTXWTR6cmM&{oBmpnovgp#ZTMeXB;cu_NK>G(r!sHKE&q-oHr8jnc~&fS{JzQiC(C-a4qo?<~%M3IfB0wm{9D0XWEvL)LjAY8C%9R-V ztwNUFrwn{r2lzdr6Z^3nhfln8y-+Y&aMA;x&+yKc?ekx!@ zXAYhrB^<~qTBaatolj&H@{HG$cjmoKcV0+6kX0-||tIvOGi2;zh6IOOa;R zWu2v4%hH8`5fUJd>}Raz)VUM*R%qa}q?3K;k>+9B6=8Sa^{RJ??OXYjR-u1DmUf9A ziG|64WravaH%L=Q?I#tFzH@OS9ML*PHS4g!Y<}4n2BD=Y4N+-|M8!e#*e~0Ke|K zq1&hT;Aod9OEZ!sUboq0JQ_DhueTql*J-emdFqB2#G1`MYfX-o%-CaqijK4Vf zpbse{b7bCQumbPlX|jf_0(XAkYCw9;j&Zv~j`hNV-vE~i{$}iezV1_L0hSX6<&~}q z^i73VtqD>Q#(#xV5x~R`K6V(wJ`vvJZh`D}4&7}Xh#V>RHzR^b5eQ|lWNXMvYTxZ0 zuvkIx3yBN|4UZ)P%23#s*^}2Gz)_Iug^_Dm{WdOvq?@z?!ggZEzzcc(b3z2pcXf;q zil_yv%@CS4xLv^&d8$X76jEIo%=bYVa=G7i1rEUyh#hoa zKRoX0#~V|qeE)P!Cs_C3#CcetTmjAr_|S;Ng^aDsUd%x6zZj8OVrAqFy*hZ47 zJ&kp+4d!*HJ*r;N_P(AEM1K$kgwYTtd_w&J3e1AUruk)x48i;~?m*t!aQ2~P3*9Zn zzHoR3$}@$Yymxqcu{(>y-juo#PAH$HA^F4)C}*Q8jMB$jLfjx=&X86fP`iFj%n(jr zI+~ku?(hu(TM~Yv;!(oaA4-*X*7oQM*@7GAvDe|W>JYw-m9ZoG?-PECI z&TNmxnepzki*_5}*)QL39+oG?MnNF;P3H`rU17oo$QKKIuW}`C*n!^yYc6fQQn!TO z=K>S2!5b`z>4(M~SlJ5wrs1T{h``N;fIbnFqY_70+RI6ifLKZqZ31D@`_Y=+5bruC zy%hI&KwpQjPI3TLwa?gOe8B0E)gign$1cJ*_ym4PDNnZ`sH>6}y;3#2B*$aUahWT9 z0&gup7x=&!&D68N=pw_zp2jtpX}D#y1^DdMT2;N!deUDNe6n#3`{3~kXR-ISW#j3>v%+7--NU%$-`@_QJbF29DYE0os|mTv)$jH6#OpG1e=F!NP`0O7iW5F?m{>s3 zXa=l&f@TC&f@R>ZXQlQFSrZ<%XL`icx@K^ab5N|O0~F<&9$52<*hD4d=FS`3Sxm5` zdT?A98dpu!GbY+_m5WfR8uIb5F1L*uM%hgkebmL98cQvkt}UfXJm&c=q)5`|RAr57 zz=<>t8iVoJU!#BaqmytM!h z-#`~~8YVrY5Q@Wy1g(!Nz)UuDd~37)1|mvAtBsdilX(bL$~=T+d!3kJ+7u$Z>grW6 zLX$9x7Zc3PNj_SdJ$pLFi&MtloOexZ7mLhqEq~?gY#S?CQzP5EW@nw0_7o!t38S7iE@h*T$=yLK&B=8z0GIVT&ZmS!Ch1(rL+ zR~JDquCd$jxMq@N9G~Cb-3;dhKUt|*ZUV=%CX9rYu9dH;lq`kn5v#c*Ut_EkgC)~1As@d#(FU&!1#*a64y$cQ&~KPirJq8` zKIwa%t)q6gA@5W?S8=c5c{fyxV$6MxZ^}I1*eoX;hM-{5Wrr3LCBdNa&ug2gfT~g# z|DOb+Mx?b=5V;%1FG+^z6XFg5O7P!_GNXgmBcp_PjDq#F@x*kCFET2(m-M$+?aJ$2 z_CxCB(DHtj^Y8T^PFP;{))p?(OUGT5o2!#D<6pX?@>EzB^Z!8i6sLPAL!aqkr1t2H zP9;`XKA%wY5T?{l7DAGNUYaf~QhP-;WkMFL%qx#0)>$^jif+X;rl%Ge;4lK9uL+>U zeSRX18K%fTKASz$T=zoZk=#tfS|lQYE&?S>MOm9GiQ?csSqJad@LXW3kp@-0Yv}!1 z)Pj}zJcdp2<>?2GYEqfBU;R=H8Sj=4q3Kc&p{dT=b-;8gjNdK$>V}Q|QVS8cb6~7A z@7?^S6o?V7SU$&JnqA(f?$)J@Z`WR@?Jn_(0CF!UW`=k;h9NHE&b5VZhl2lmZEjJ# zzZ1mu0*kf>a;1C~fe_r#M5PO}8(Z)~fA3N0)$Tz0@C#uv0wURXJ8+8n`k@E5rO4h8sJbUR3& zkyBwg0>|G!`};r&(r5ZX7WZHaP^(!~#$r|Ilzfx!aybZ;_>z!I*`*rhoDPJUqge?g z(e!n)iL-m8`&c!gh^fMDvx)fRvj=!u1zgMavy>ua-G|9LY*1X+f_SX^?oD`Da}8>_ zk*NwLUwjf6TO~_ukcT*+heyFW#-W1ZWWf7IL5S1{c~uEF^av~H5hGyipMdnL!S52e zwf`#Rfy zy4@;-%V%Pe4EV_HSyBOO%USrP9p2fLf9*VZ^09xRT253ZArbC zy(gDUN6)K?S>cP;@M^IHooav$mep`zV+vihn2&oqm5Hnet^Qe zeQ?-keSl!OWbXrbaVr}gZR1+(NYMc&T~ia6#3^qt!herQQYQ%At25dNvW_5LY0${7 zkaOHkC-YRBXbSUIg+Qqnb=&F8kuN1Eyme1Rze+>*K7^Afh$cKjb?l);gMF`~K|@zh za#CeBaNIaHBAAYBPs3TVfY{+_@*TvNU4Jy?-gj$|=atEu-fphQ0&We}rcSMT(UMI| zEz+f&Z4mid68}(v(PBYA1X~SD6OCggPCw)aBmD-7upq+L8|p5X$<7A^8ulSq8J;}}jWetks=uo_cncbjMjcw&S`!i*ftFz7 zPY~2bqMK4nKJJ3D&fF3>YnM=AP}}CRKD2%{RRE28MTtS5IPvrT!i@iPvE?aXPksOC z9I&WRWl4!Bkd*G9$E<)Y5F8*-O8w+R@)Q%6AwDo!=6=Pow}*85iFE6Ws?Rd~6P%D9Deb#5ix$tpEz}gy z`c_4>RUCHAEd*M_urbG7BYy@XdMxF%`0Xfnk|#N|d*5nZRsT;N_OHMXt~d@ZAKkDG z7>agi-lC~_2czj{6i${g0Bm-%H51hI_B9^^2`2Pg9r@ldT$0IU|Cvvi{=p}I6Yl?P z)BmN!ER6p_?_7-kKjod}|Af37|B-hT(0|A~$v@;>e+EM0UzF}IO8bLD|3>NlM|o%d zcjcWwm}h!ovO6* z5ao;lU(mh5A5cFq&ipaPTAjUVf8rF6u7c2Ywr86jstbUMTgRe0L=R1qVxp z<&n((xqAxf9iku8!zcf2e-F3&DSyu2wV2ZlznewR+rpp^{Jqaj9O_zdQs_aI8aEe< zUkHj<e%&~(o^IBv$%0lD#zB2_l0c*A%ac|6s!qytz zLze@K%B+ZmZthQB>C?`&Nj{9Kc6@4cGx9cjlTfFIS9CZ5Yt^bQm0Bs6NH!wE?IW^{ zTVnL`bABBQ;5^`tL3FNu5PXN$2k;wk%L&^)R9e4O;=VxA3k#iNkNpC@dF6|ZhGa*ndJ@lt-VP6D4wIfV1NQW@oXs2aU)fsmjy%ab|9F= zR)_OA`WptH)9cPBFm#vk=|5j~tp7r_S^sU-mbDrnL=3t9jNrP$N58KP#{W@sq33u4 zDfA~Qks)g_if=Pa=6aOC5I<$Gz@S&#I>WL`8?&mf`Z#sCG3H{gy?H8hLLL| zEnv>POcsBKokEBf?~GDcB}Mj&rSvb>ew-F% z!+xZrl3%uHE6dInEh1Oe#<2Xx7CaTacH!l=;v_b)`7_1_U~wm*M}`G1PG#y4l2#k9}sEUfR=v2^QoWaF-45wxpyCen59 zVJNHk6!GDgyw<~DkpqIh0hhd)>bgQ(i5<8?N+7`TK$0E|HY{rR;zYo8h%kvY!A(@U zZM%vx<^k3gl0woo4PQ~R{CVQy6yvzlcfe-Iax<6P-4826+DC{Izf+!Lz&X1Bk@`hA0s;2-Vzg5% zO-rV8c?kgbbBEuhzwQ@Z>~cFGtlW_(H5jLTbV$_7LoCE8OOI6)nbjwN)pVx?K!%rC zVA(8G&pbgiu`el-+tBmpxz6+aj!OKJuj>4YY!?vNJ{7yKh+Xw!85ZNyW1E9$rRpY}$R=z1q#%)hqW@Mp<=r<3~+O znCIYHL!dREXzhv^_@@os+-WWoq?EAO)pIi91Ru#WMs4NIWOc$v&sA3)r5$~`ItFxD z@<*5C9Jnw?s;FyEHJcPp8&ywT+ezTQ-+S|^V;5raRext7(G_J2R&S*?6#9{@_L>!( zE~G50s^%h_XoBBFo5e8gF5-rNeEK}@mYy45fKA;@I!)_Zwb_s!Me>? zrD8P-W;9ZhsG3lx|65|s@uSycsWB+ko8f|KsTG@gU7Y4~OWgbnO|&dJXzd>oKIo}it;OINL@OtT)rGLHZ1v=Ncge25^@fJF`Kmc zM=-D0nxVJf?oc|~1@uVCGGP%5gYHX&jw5#`zQz)K8dmA=2?t&!>C2^XYL~Q0aURL> zxmlKS>?rUeE)NsJ@NW)lG%Tj*bzCSahaAiZ9#W1jToebL8o`a-LoUMXB7;~>taVVy zKf9cZGOi?BGaWUj9jT~ (akip655p_oj`NaF{C!{8s$;lDr3f1Xkj+h@} z(?x1bD44XB6Xo`Py&x%!lno($vP8i2BAtIc-7tsc!o79Fk*$=J$F1QE4eR1Iu)7l?q4M z+u}#M>e*s?ah-2mig^uYG=zbUNnQ*Gwz(&A=K&(cU9z%P-eTMQe7;F=YW!qtGq?L@ zAM{2asH>4*GKhNs#o@&k^yDh0k3(q@r)kd`VYN)bp*4P^q>LRt?mE3Yj7G zLkftsaTXu4v3?>3FW*N$Vc=C6P^B7~hLoh_H($4gqp3=?%VYQa82qr$79U9~hctzo zrzyy6sH5f}3Wk`hXrH#Waih1_J2Oahb~};;V7MrcX3c1N$ZuGthe`Y(W61K|AQV^Q+p}>{;|+Xb05HrBs8aMD zk~`>DFqS<@W(b6Px(=i;<2PzUrqUn0cUF|4guGzWyJ4z~{#`CN#_u4w0cLv)zp8Mv zLnw71=xleW&HE|c`ao~z?SVeQQuZMC2?7z=bB9-72psIJ1!%xgRv1nBX~{&L0p8zK zjJw`;vD`yVhRScF^lL(sqbC+Ov!9^zypcgIb4f+7n3Jd?Wt3 zcp#{Ta~=KMuT$}hV0bgS-UF2HM|Zr+9j^yhHVXfb6Q!Cy($un*=l(!@L|@`*Fufsm z5R4IAM^Iyc)V_BIsW144G9nuiwjp1P2CS7m`E$SY4R(_olNB%(#d1QS31}CZevxvT zv)bfj#CD9TCE_);b$#t8n#L)83kH)nvTw+x=nEWiHJO^0G{;P&3^hsJr1u0D5r$jJ5KGSf70J5tZ}_*53A?Dy|3j1kuM_aJmAlUOLRO!foe|eV$h(^3_5}6 z1jVu7`-H1LX%qe(A18bpxtrrt>;0P3D?;BIr^*|=NisDbBHa)^=oe0{Udcr)3X+Yc#KrTms9%H>uJXnACZ}=9$pitUR+5&7pwb@F<|}+#jmL0Ls|uPWJe;V?@T@3~q3g&mR$rL%S_8Jbbh%K^OdFPl zJ(w-nW-1MYQ7`CoE?Dtey#6w|9!bu?#!dtbhiRW+PIENesIZ_=6=eR>A@1ThpubR< z-D2>uHJ~95eolTV-sJ$kj$l3TfN*Lbs%ifK%pDZ-7Yo!u6wVVEx zfv&T9YvLI5cq{nDp(jY#0RK|cvs8F%WTyzO@s7cc@%KQsTAJ0xi|#tJmF88XC%X%P z+^|Q>d21_mewh+miKmK-MyJ9D%i}ttV3c2s)9;@1VR)lgN+EiuHXIY#%6piEF?Yrnh$7>Gn zAd~!U8O3bc#}0#ITA*6}gJ+LrOgv7;`p<2onvjV(@Zg-%n|9P}@hziX;G%Dbts z!9iEirAtQ0;w*HR>^(BEbhXzQ-QvpSs|cDXT(sMp#YInG$90C^*~3qv zBw1;XC0wK+tOS@ho^o$-ZmsCukDH^A8y8(3U>Av4*NbDr4K>eNPzr~*Okt%tg4amv zs94p4l-^coJu3t?QLZ?owa!(nt`+<+nL?AB!X#P2EAaw;g2~#%(K1ORMd%DipBHH$ zChm(iiZ(K588KDiTQofl&Q~dD(E$<*qF)bVB%X zQ}~G6iGiNeN|_SdGepQXb1Jim??QW>HXd`VYwRgVD1j+PIi{c5Aw&o>*N<1I8yOfh zDlcJtF${4vV=aBX04~5<5;h1Cd4s<=eXT$_%!o2bPgI>ow5@5HQ_qQMNk=6t%8Pak zH!6TgNLbi7evvo}8+!~tJ|~cgOKK+vZLftGMha+yTCpxylF6n3ozx9&R7{`Fa?Wp52izAv4|B#7qg3o-khE@)WZ zp7A;kgU3$lR-d>OThzC}GFwQ0^;J%j_I=UT*AC>fN_=DV1&Wy9&1mF?VX&{3vHSU4 zLY*PT3yap>tOkf+M>p8be4`1f8`HPrD`r@#^WD#%IXw`7>5O2S`>UTFT;PM^oi6rR zZUb7*dn?l@;z_-dv@mI*W0w%28M!u@LfyVb{B%;PTG^9OeLzIBQCilubi}N&zSP_I z;~SucU-ZyJf)pOvae5yC2LhhR4T=i}LHRYg_0hdRUmj2vkTr5G;tP8C)AB}z(LWt{ z0rrfou(EK(=oi@6pA)2X;>tl7 z$zSYy26gduIFHD~?7{r2Jyd zZFjoOcl0fGuI+X>*lwEHZa6q@k|DZSLZ`=f>z!_zuiK2N+=?%xfa&VQU2om4g*FTO z^_mrM$Z`lCq2<(D5y{qxE9pu3BO3VV7EFIe?-)Q&nS*kc$Sey8#mTpBK^@W|ghrok}^&1n;^? zq;g`QjyEJk0&gInL3X#xaf0SCcL$e{c0Hbncd=5KcS?ICxwv`5DY`n1@@`VSnr}+H zGHwzq2fcfW2iE7yetO}R@RD2iGtxxlo7jqITqUrO!hB;g>MmD25qi{P5~Xxig>u@U z2r_+kG}{$P5{Y`fwL1*O}HsvX=R~-6L#o z_`Go}ba17fA#o9@QJnn;-C4%MayiWcz%q8Ns;QKs#A(q}HeIY(a*5OenH4))s^8Ln z+wx)d#Vb$Q7wbfItXdF_=DDKp{A8tC@K9GUJY;VvetQRbHI7TexI(gAuCn5rPX4#p z=P4`Q);WA{FUhZXoOme{@@yQ-#IXa=QHMLES4K=uxv6o|pt@jhRBOeDWC2PO>qJx5 zM$yq%1ASCDANQ?<=wrozV{B*h#3O2lo`A9*2lFK8q1?lrpZhz>bm|*T(XFjaFm2!_ z#O=}k+73?hNQ0Lyt2XZCB$$}4oTwO8m`&95+O0;b;J^gs8-c>0{kF|}NrXtTO3f64 zN+5^S0p5JhrB9>u{bYR3m`_QRrq3Lv%c-q^iH*F}V;^IBd=>&s76O5LHl|N~o$t!s zIorD)Z|qko@?nNnHIUae4L*nny*S*HM}LHPC^qKF-b}q(hR3tOXDQpiVHTSaVS3#U z?%sEmcN!Zrvl)rT^Gv zgPHBmjl2KmE*qEHHnD$p+4$`079y~5o;++HA*K7-u=>kwlidd0jbJWsX048HAX!Ip ziv0Q9?uA&o?hvEWO2>&ZLM2gzkJKz1YigvPGZmcE-6{Cvaq(kuk`4uUH_SmY@XZ2o zPN1)H$NrCS1|yx+XO-LG~G=z&E)i^`OS}$@<#(AIt(NU zcHU3v*dPgtC1a&2-E&uoK|<^l&8w^JgIP;GcXM>}0B3{fpVR})u5kl2oGah~rB>~RRhORabZuDD0% z+_kmhFrqA>#6rU?;Cs*!)%3|vxwYL!e@cslSF~-3zJ?O@22P9|sx!R zID6f_{}RSdvRP8m z((_YYYmKU;C!wP38IX$aT_7Kn9XT)-d>iAbA7DinlUS}4u=+DcKkl4nGQ^9g_{Hw@ zQQnzm0s|`+uUH>^Ca=UY=7#rnBxX_Jh6MP+(+y!ZlK3+mqzJW_x0P0pAPz1nwAhay zsfCj$)MA%2jy8)34=jpz8P~xN#Hc#V^p9{)%;j%?L`5vb!u2Ne3q2QHkdypHGpbwu z3Ih_tJpNG8;$b&NR%S)V*x_<++McD2N{64}u*zzBut-^I_)6XR*rI}LHrqFR=Ur0O zhGv`DU`Im~&uy-I+8EZUgxIM%3`JYSJ6F5+OVq2BGGhD0_`t^*JM=_^7UPwpSQw&@ z1fa5N0EZaH0oRIuDjc(7S;DwMLadfXpLb^AGsT3$Kdd*9_eskWN=nh95;snaGDTlZ zmVM5oEL0MJIz-6J5a+d|?F$4K=ZKv%mBi)JJ7Afj}3R1G_{_H5fSxR zRGJW5&~s+(v=e2XdnkT9(gq+y0H5um)>on0RFa@nv>w^xC0P^Nak38FNbR9eXEc{4 zRz`j0Lq!)5-%rAqI@m7N61UHg7HHb;^H$a5$Y- zl91u+@U7{V3l)J-2)ff$q*JQ1syO@7+)*g7v#T)~`c)bySYoC;fdsc3;h-WYQtvwX zwbhA_q>)1<`6~Jn0NTaLl9mrVtb2+t5CmhiOOWRSuO9drDzFIJpwG~uT`{i`_`EHu z@Ur;VpSF!T4MjW>XDPWvaSziKk0rd9S2oP&9M-&3W>T`f*C40 z`4gkogn&i%-j+(8-G8#-NbR5=WW|z~?aVrB_VI!7^ywmY1Q3^j55CMDpvls$c5}+raGIZ@>#Iz8;hM z1tF{XIY(M7iu+#cp-71&1ml+=%YYalw&1oL)#tdqjbr=nbIR!=AsAwc@gt(A-&`FP zfzO$B`v3W1X0?p)rEntePI2JcO39}K#XUJE5s0G2*xz$Lh&zs^xwmV^e$&5EkNZ2vi>1pW1B$Khirvj^d7WAhx5KVO~N^@?FP`g&4>wP9h)eh0916z)6ZCLtyr^Ul-duGY9UX5 z0q(N$s_Cp&S}W$rvyA(8;xr?(1<*mvz6o zioS24{7F`U>dg?R@+^{t%npOUn@0NUGJhBfqLpL9z%1GkI#Tbdg$}krW1POV8&?Qv z&my~IRu6-R`6AzZ%s0c(ngF{7e!?T4;o0J$*$4M#CqW!(OLYe{BX^>QA27%Kz&bG! z&!Pza$*S`P9{=^hWRpNsW@BX@uwufzTm6DcrT9!eKMurEs$%69DJMl@1WoWc{HGgSg#&!t#^FAAl&8 z^5iJ6A3>LvKO_hj?sQ(Xd6~oArJZ!h!H>YjO(FF^y#pZCQ&Lk+ijW31H>X#cR?C<| zJS=XD5Hf0dyF;MhxivXrK6DKx7xQr=H`j>FCC-hWzf|S1iO}YZMJf@4XMNF|F(~Nj z)IX~#lK3SAo6V^b8p!het#Acqdt;s3Zvb%!U(78HWzKY68q4ShRu|!N@ zBsIuE`z3b#DDW~{)^CX@p_VP*YeRg@sA48kTXl46Lt&B{aZt`f%$n$ZsQc|$0zNE~ zHeplgqU)Ud{^)e$LakU_hHD(!7d?nAg-nDxFg$lrH%avqk7Y2`z(yr1Xz?xki@np8 zA-(nf*OHOpuZjM@O2)s-4>0~Sy2t!K{x3j-_1mAr z#=-b+smH(aF>>}c28u?G1R4Z%-+Da)x}SeV1_cS|l#E;*3BIrX_h6p_8v)B-vq*)1 zOYclN$OHm91qONo*1uFe3g7S930VK}LkRvoaL3kyK?vx? z#4-fuRdYn@F-i*RjT<}gRY-9m4FT8+sT!5>JD&OB*m@)vQ)QdFiH;uUDbTQHRGd4k}A-kcTFT=L*dZIdsiyd)%DP}XObA_^Xz<4BX!NkMLcrJGm zu}*l29x&E_b1QW_%X5pIlPp8W%122oDqlH_1Vwi82)C9Ip4(*Bw0aSg4FXC;!OpGA zs$q<1$946h$ZT?|qScUDBR&8FeNt53bT32%3MNr3ko1ozjI`CSs2L442kJB}dB=$8 zc2U(uc~hshMxJo-5{of;?r3pjpQkWk@G#-NwnNj|i>lJfyn=fo0||;a>%JOO)`bAIpe;;10E+68MZ?u-@nD7PO$jstJ1L7KKbWCCTrOe> zM8#>Rg!cNjV&$N8c!@o(`)o|aISJfsMYF7@Tn_rEgKb^{4%T8T&`b2>y>PxMzeC>s#KV(cslnb z1)DJznZicLW9e&EK3$)0D%D6ly=4G}@nELz1z-H8900gee0O4C{TjJGZ$4W_;^X?ram7DsWa3LME4$QpB+!W#DSeeQX~5e_ zE@%|rrdTGFkTA?K3WOueqi7pK_ZPtmp=D#r%y73vihEq!8(C;v$SpKsJbY3`ho^!% zE3MqwHmc`|k$m}n&B~tRJO~sIS80_Kzn(O8$ls|{by%gxLw3;0dUY$u390RZjg28| zCMVHC@7+f-8t%J&I|xZgyH&-{M}csf~*Pk5pYW zJ%F*zy5`&4>P9q#i2C6#YM-?vLO5M)3{ts^wi?YXzjEVh;`F()mZ}r*}~Qo|_ThpfaPqCdDB2 zR;%7L@$aOy&8v_!w=BtkBrwBpM~?RqM;JaNT)686*Dy(EWY@atUWrrKRQxt^dpO=2 z_;8~Y`*z%BSG$li(^I27tayI~MG9gCaURhlTtCBdC6wQzh(u^^!FnPCpxeTTa=Ze_ z5$rU|$QTo(&<8LC*tn-DAp=NpXtzkUn91M^+7)b2L}x&PpnyW>n4%w;7u~8wWz$b} zB7WjSh}Flbn}Ax)GWGsptv8xz3{HrGSWh7azTb6Y<-rGl8}PCQT6ia zp30OK=56CPrv|(rry7m=@ zqn>a`8+4$cXsZh%R)!u?4P{ASc8Xq158qk#sa=1XWFyD^&aB^aMy8Gj^yzW;2**1N zkrhb_L|F}bZ50&5uoS?6KU39axVnL{b{{1-F^K6yUvA({xq4nwEIeMe$qjJp6(^&5 zyoXj;07{=9rzG{|4f#BZi8XL46vIQewH0Z|+>rl@b6MD*d`P%1;d2u6GD5pf_36cp z;5&%k0fua;Cr5(NUr}ag2Loy`j#tMRQAgtSIK;lKUv}%(b$L7a@pC!*`D54#@RyHQ zon$8PYZ{W-7?2xBTl0RkmrYL?AvakV(0b%g^dX(*hro>*x>*J{4{EsE{r=iZf@%7x zN>KUlsZAAYV6uEj86=`+#s> zQ9?%HoT0&-u;Hi(-OnE|Hms(DYIfHCCZ$OB_2I*{FeSYL>1iU)rS<;m^q3;7j)xu* z5?wlFlf*6R&V*@dm?d7jfEfGK8#1&Di`WzjkSgf_-kk)dwpPCf&{^(98dVR@?$0(3 z95@pXC~zh2%9HNVb(x{-TzzkyOK*VtxzJhL>w}(y@auIk6HMe)?0L=r-)o?iuVp`M zZxK<7JDdVJ5suA8-~@Ufp_QBEF<*69n^!+)1aBjDPYC<%sN-uhKTh7c&*8Y7q=h6f zi-Z+KP$1jgCEuD85Z30CV;ma-Tgr*HtjBks#c>W4ae`D3e(tAk{ z7j2|C$muGqM2>QvzfETEu`;t5r)SSB@iS?|!O;zEUvD>;J^piPW+t_K1vc(xxK1mU zp!(ewI<8Ur1ssX<>(q&bv@CYLsS@6KfyjxFP?=fq4q3H(H-rh5tY;L~b6a1Gw^Y08 zJYvt?w;{lgwr-U)$QVk}0Txw&{97TnC8^}fDd{3=Ot`rlm)$;IPqee30bm&i{F{EO zH{T9LIY~F3*Y3ru?i!IklZ-nM;{GBC1(ei0@#T&?g**8;e)vxFQ#^|)=Ac!rX%I6j zd7s(MU{A@AvFm|tyM%(AlrzJudD0n%w%(YPsn0NfH7ng%=b1(tIR2E6x{HQPa08aI z%*GZFb&2@>Sy5VN1z>g#xpR>20<#PHJz()I7{?3&4nJpY4V@h&tR#7vgIsA6^wuVP zxAuX?`$DJ?A9`5Rrmwz0%qE5;(3AIl;fr@Iv;xEHdAL!qi&q}x94L{CGMj7-xsN*~ zdi8Dp=O9~`YjuvxYs$p@-8J(>^x?Bu%5VexN;%S3L9I!8+UlVwNzN;@8IO@S$FzJ( ze?d8De3&owtp=ENOq{=EB_D%Apg3B3vGmIXa%gZ#dSPO;V{#w|tL3JudtKITMIkP$ z;~d$lCfd*@04ubEt3Q^t7!z1uNYj3dEy_IWz7B%x$Rq7SbSuDD>iLRu=C$50jG_mt z!>I(;SDPLeQzN#PGo=)*lP~|5F#1u%pot^cITp|?81p*{YnjgcQ$;jYU|(#$_BN;ef{Ef!>j7yw-aim)Z`kwO>#r;GwacKEdgeSE z0M*cH*idcYzW_TdU9BwmzaSKIXN7gWg8b?-BK-c*ecd=ENFX8*8tJQp0AzS^ zDS(x2u}Ssi_=%M6>n5VC+;{Fvi$?cnlV$l@x6blv(R#xzRo$Qs`gR}Y!VXL%WPuwL znWI?CTJkt+^%wvLHw{3Mu#>OVp`8vEG!}^z60rgvNit!EM~-DZg}uQ~vW;p2>Mkug zM3ccKW^Zo0gI-||gLiSY#?@#DK`>ziQH13-vgH66c#vVl&4+5$9Y|sriczlAFTA`N zhYHJ7R3D~fGgq4$LcV41D}}e$=jKUYP|uT4L6suH5F>JO z?Jj~0Vwz@h^fPonxe-xrMFi=GZe4!;MsYJ^lnm^-{gckBbNqFGwl8{j^L4d1Y_lbs z0oRWQQds&_Lierb!9#bOKRRsm(&M+1S8MFNcNkwYten?zg;WN8fD5WdEbKJ&2J#>k zIEJUl!79uPnf&%{jumn=uk^}|C6Vc^J7OPMt+d=SS&7+eA6Z>#B6MI7_`oW?vJE@? zHdZ`geEUr~-x8~vEo?>tDGE?FnGOsUSt?8K%cgj^Du=qhjsg@h*OS6}~> zQ-%^-0>e8QKjxHO7f*;l7cj3YJ|Sj{j(x5HWpuW(zuianU_^^20__Hh`ui#RTT0I@)1mwm3T&fh(UzXrfvjsu$X4>d}H#|b}ix?U{DOqB@;=Ov|Z zrMhO*hVnocmeEG7mWtECvfUf}kVH&MS+#GiJjV4vh|mruy(ZIv@Va&jc`oKgUB*DX zv6`-}d0{tJ!&t_VhZyC(h?W5%gvW2p%@*`;9=2XFG<8uRXp*Gp<~*Bgl|n4ObBj!i zGQi76Iq;y?1X($ag(k7a}Dg}*+_422@*cqEJ0@mA1yq52b1*tkBV-LC`j(mh#8K?vHFm6Az% z-?MGcxz#yK*TZ`i`b|yB)FioIqLdVo<+i}hhB9f+%gZ1vKFYwc4Q37XvIU*1d zr~9RW`LU>ccyV!!?>8voZLwu1h1C7o+pk7eE3dC1_?$yyCdOuRzlf+!+FV^Tit8pS zEf$4{RMI|PTOHFNKU@murRku)5bV20e%BFn;w!4;o2|`stz}}^Bv}lXBuy)-IwRH6 z_Z}@*T>a^HC5{Scjl4*j?X9&0E(2`@R2?olYv`VSh2tp|GHU7lqE5O*qPnLI~X2+{i^=h zNo_R5@z@Z@OV&vkb^NxJHu=_Xi1K>Ulx?2X&2FSxCEAqqsO_F#?iCd+v`&$M{#Tz=U?V z1 zXl`Azz<}5G8db=vX0=2FVX;_Rb?F2W*mTpKti>)iZCb)B&S?<+Rq_Z5c&PKyploF;=3pJ<7(2*PmoM$8lqp9|c(5@+Cd^@NXH=LM znKv@JPayzNaR%T{^FA~ji&!^s<^*q4FB&IBIEZ2=S{3u zO^DvvI)n#5VQm~-!wOiv?IJft_SkP3`28zBa!!vPMwBISak-e@&J{Zr;?*5SGFfVT z@v-*gsg+U7!-tpI*F@OeUHm@&(5axO*r*{P`p*&P&Mrz5n-N2ZnNjAKTRrd=k*ifg z4zYW$qYj!&Bjflq=do9%DKESIYA@`*MC z4J4aNRLu`Mr0S`t;-Q$ABek3M#A(r{e(ki%Iz<}@b0OHm?{B|j$?<72*kflCr*{H;Dvgj9}nk>9l%q*&mr4`J->X=bTF{SCn(iyDZz*|Jap)B!U0lMz#kW zgrcv4?Aa(7SVW;DtZ;E)#*zT^w;Ie3k#3A?WsB&5K@t`Vt*MD|686tHI#ec4MdDf* zW~;{eo(5;l>$|6=q<3M%sZH4iLX;o&8K~2f67&jY-L$Oy6Wp}?QlnrarJ_H>$*+HJ zPoMSAZ7r?t%BlQ$*&4EvJ6JeeiX@G7ovT&3tY2flqord?@Gil5CQ=$iwife^={fN1 z-bel==AA+icX#|Q!@KX|8MZBeq`TwtRbq)(Felbcbr{7I@iz9HQg!RaI-6$GjT76_ z6GHLB?x?i!wiJG--SPA#(O`^02^Y7ONDJILKeYyTqGi1f>Fdr`DSDRbD0+08D%wvE zJ$(={Vx-sy$fy?oXA;V_3%aeZ$b6ayzbH%bZM89;cMN?AQIUuJ!9NCYKy~D@yF0#v ziZ~mto_&Ba1az30eRhJAFvtGCqnSW<1PP2(GmJnj#2`ogcqe^*TVn6=Q1vOGkvP!0 zMROmb_>Ozaa+G@aT41tlAvg5)b3f&b?`3>g2Ox%sMmTONU1n=u`?++%-&*}2h+Ebz z5oBLG@9*pZi&Nx9u9tzPa<*OCyq}dOKB^ulRE0KLQ?aG#vE6~D_7XFWnIhb%9k5ct znD(y0e?-x4lRnEguPAAqH#g;8_jCeO;e9L_LyBr54H)`}bMSYKV<&{la@Ym2{|tHK zU|B!S#-Dbe_n%_|c4UY#8VXKe&DhG6xHug8Z2Hrp2%eD|r5jHEn*&^0C6~-jCG2-0 zO8@;qIVP>`UgC#Z%aXLpL@Nle-+?V*wz^P@Cb4Y*rv)tfy=qf146DdV&Dza9u(9DG zUAH5Q9zkeDAi9O-7b$TbpETo!L%^O#o$0_hhlU;NVn{EjahPVc4^bo?t`aRSJ!=a3 znwn>u{f;2_Wz380;5xf>u8BU4?W?Pp1G{vBgWB55Z=+XmWn;Srf2 zLRDHg>2c7GKHj)stRV6RYbEKZ37Y>y48l8(Q0!+GVJHcaQU<#J_liLa2qGBunGx~U zBN+Mw?i^$IU%0>u1QWw>@6Up;7f5|9i6x*%dSA^RG(+1;5kXhd59Ntg&x0BIrlTrS z5S99ny?JakeDq^@bgDD?@3Z~E*1}i+@--H~P@FsZdBMw6oiusK_W^x?z3j^x(!Wx< z47Gl`WQ!CB_<5FnXs-3#EPsEZ{n|>vg4>qhc3ws8f%#V4;>TRo+f|(QXVCcd?l}AC z2BfOqn?jzF;WicPXI$SWsrNPRN2)Y+N+`oXp_>&k0&W)CkBl@iLjtnU6PA>&WP;M= z$e>}Z0qPM0(O0%S{z+81n3V!|X~VBH&Q$6f9ONgQ&}@VEa3NxXBm@U6! z$aMlb2bN@5?h+mjv~zMT9Sdang>?pGKzAdXk60Webqs!JWA=VNH2aL5Ou@Acz-n zrXYq%?YI$XW=;Ir6sd!uf>;__ruz+1;qf$m_o}}iUKX@<)qy`TK8hp^!l5BY-yt62 z-*vasuu8W8BHF?FrAA+xb~|9K34se=A}FM#rBZ3J4nLDP^ytor=&}>(lzwRRw&M;% zV8n^D0S~+GX|pp@_P}&uo;|D8+-qM>FzB?Hw5|e%I0#n<{~q91U{xlqi|Pm5nEx16)#h4-uEqbB`k8$o7r(x$@pDCLcn%7w?@>~m=+T6t2y zW{silOpN`3?Tfuf8y*$n(cIH}*{JjlqXb3J}k>Ka9?HHlk zw>kB8y)2`T^$VCuvikVHR!8jr*(v?69v90u!2LI?qeb;ihl3_qpFcXaF>9D~{qXX6 zbJb?)Ta!-qzYC6eN!(&xTD2F|&1C0>j^7_aAry4VBQi5QtcIDW!UOq%KzhEp_QlQc zYHc06ulMoEMfB=K?Xc8R_PFx&56Yx+5bb(ut<4MNZ87ss#EknB{70+JN;ZZ2lXLg< zl)-5?m4(IE;q-1~=w8N3T)S%xVM@%b zZ*N;yfiOQyR0x;-4pXtC{0;UU&{w&xPPGg8+-(DDy?)+XWYG5drQ-$e<7Y;&>YAL6 zD9iX<+Z1K2nf9x~fRs_X%=6cVU*SyIKHblNA8&NSPu=9^^f;!xD48~y;OF?Odl>?9 zZTK}WPxKc>+a*(3MeZ=Nv1%N4taJ1v!&!Mwj$`RnD_P?mYQx-ZLsNAdKO4SE&Y|LJnOQoemj@1GRk-T<2e6Gz(!-^sWO2|YRY`jz9|s~c zCB>^$BmHBv^tTtp;_tNZv35lE`h{sNdn`oW(!h@03fSaEJ~b86yO-peJQJHtkZtutizPIyK&JCFZ5cvGU&EYk4(fY7{1- zOYBW8Z&K-s3 z>%Nro`+wyLZ|F$#8_dSGA&rlyRK zfh(oaQ@MhJh$!p-V`e1_u>O~Kk*|3Urkpfb`qb4*V@L_)l_TTg^|{S9VXmlD*huyF zymoh27ZV0@2zSlTLtPI}jje=)>@+ScGr4xgZIl{+V23Y?t|Ml2hBI+vnqk zbD|1&v%X$1H%xu%GTZg%I~oi8Ht&+j*~Ss-V@u@Ps|+9NlZWiURT$acN+rJU2N|DB z#9&+on7h=OF~GhVPcdnY%X*Ynvjt?Uxx90F9@ae9Ex!Ts?GWpYv{u8DRcHNSxzkZ2 zk+;wNFzBFR@Sr}93L(B1I|^+iWx%Qg2f)*U8iQkqD#)Z+;Sr+;5K`Gy>W$rq>RTY{ z>)0ON%Szo!Y{Xm}sRHhqJKOYum&gH2frnMx+qVR3@9hCEsRqOcWO+h&SJb#_Xy5qx z_0Cm7)!hAq`*^^s+i?JM%ix&|er}%xxPOivmqyUnwlwUshFE26AU1Oao=ldBL|_|e z@s1sqJ84*e2v5GqmQ~TpLU{CL4yax=ziOxl)j~q(H^iLju!v!r(S|PM$s7KQId}j< zf9lx8S#KPk0PgR3w^nzTM_knKp@hc_DIi31sD09L*;H}lXO=PKO}aB)rjOq~Ehy6U z-_K6a{{r`9(xAfkzsxxpV){-0du8+ki9krrfHV-x3^pI!lu`P1G(j>SPz$RD zGY7eIv}7C;#02aEt)uz4DR$73-4I__4dF6Cj|Ph=O~wFm0&cl&P@mqxqWC* z8_2)bP@$;azrWQ!sKml20fGNqcrUe3|Dt+yZWW4NHD;MA2?CXQHd_H|=XW>5%{su% zD~Hl zLPAaTCi~Kn^p*b5}qIqkDh-basU|Xc288HFiRqSdRKzskP9V!DZSQlP~Yv=6e-X} zwjpux7E?i!%gbEdCnH_M zSYZunTwn~Zi)4e@P11oqCyrV=(*2%JHUPvADIeb2e-Ba-pPyPZC7yMJ9L#T*cgjnH zWQ5ALBs2)TfF%;-mKEWAJ5;y<==tHX;dEgGCp?s&P`O!1-gIp#2HU1Nv}D!QN%o74 zOKPrmL-CqRWA>)jRI*IaAth>dIBOH_9_azCBcUfcGl+e~t*-1!ROM9h9*IC>sePt7 z1uXe<%=du-V43M<8L3J4bcdYI>=40;BpWx-#@MB7naRVIF*W^X(9RcUXt|+hybj)P z1Y)HaB^RaQlj)_fC(wCwb`~LkQ=2KdZ6V=etf@jdiULDTUR0u2(9E<~CAQwHP0}T3 zO=SL7(hnHcEMBAiqd_ZAPbPee5h{X$Vc&(Yfr&57z3n%P@tXfyMY8?x*xwi#|HJ;q z{y(L++5b<_+YaCMH$`O0|3q&i|BK!p1vmO{Zt?$+0*- z+wA}F@cjqB&G8Qp-9Pwkj{iWp|DE4vpl4_QI{^1&j3x`r@%v{u4p)e~0aqBZokodn zT&yZaDfo%mX)(3v=kx0I@qi6pBq%fM*Wz@0zx`un zDqA=0QimE|a_j@P;XVn{fd1W6qnnwx8XgR%P5BiEXXH+#u0KXptVj)mSbLXRm30?u zcjw2)qy6LDj{T$2r_0Br$*bLc>x-eAoq=`AIw(uFF%rZS2sSr}4V+MbWp9`OHqT0d zye|dq9u6Zgu?vli%8ftVlyxFUHouoNSEbg~p;?rGGAd~=9fT7y&%716< zquS;3bSyKwI&!-BN#(S_Zcc*Z^|W9)g+z7VV;7EfDdyCR>n|7t^jd z-(XC(q-n>@6&{38WNe^hItvSZ3zI1NZxFZCWEFXv$gtLrjDd!*sS_}HvKZ*x{qd|y{pka2{)Z+3YrG*?Yyk*Gnr z2`7IQR;2l)#Ue0)lQE9Axrq!h%->g(JzZQgbbuT2=d}ccL%zJGzraT}Djg?cET?^< zRU1+B()l4a2D{i#AnjwZX*=88aZbDF2h*WZAk5fe2x(f1Iw3`NKxbnR-7#Ez3S|xt zW`xN+KTE{uGV($8GgS!60z%tb_!!#7R7QwS*? zDh1j8&T-ULxr&+cKkCa6Ta@^xD273XdUnp)8}wOdZBb5%{pS7X;ecf4UZz^{%b z0yu7KJ@b?$uAgJLNZ5lmF66?vUBiHDXEWAUGw$uATEOfR7guRxSE=ZsVVewzlMXf5 z`CTje8Ptj4^RCRb4AoT1#;n((8)!aq?S!UixVu<81%XbJ-92?<14B7vfYQk6`;5F^ z`V1!p#=6+ZlGpnNV<~_5I)N>3Y9|)HIBM|$9%jjwhVHoDK4{FeG_@|CM1jH+Kyx%%;poH>;2pSI4iY%%p80m36z)Ts{rrbQ7``l8@d|& zFGmNv$Fy4EA2g*>)>lX*aYx*7fj=te4~&!FnO}2DSO@RCxpTu~S}+Gn(ozg4MPriE zCzGu?@sSx`6L~7oTHoYoH&0U9f2Ge!Pu;;|%o|;q9D7eYYFLed|M6rabxo9JJ6xkl zqpd5$`trPgI%~|q?I`UFwFOdAOZ;k@SZZH3pn2DBCnQjUAXbpC_Q^n>Z{@0WO-(%< z4TOv=kRlC6?LlgXJ8>UL!4_%+=-9aNQ+T>;|C1ncTi(kW;&Ro+eW2E;wN7K5r(H*W zWW?cN4cFGv)%twdryGqNFCK)F8zu)-$Sz$3kIwfInSkl(k*+(?Ac1!|2L5aiTFR_O zd`Bp4eA2;y5X$N*u@=M6+yNOrjd@)LD+ii8P&ir-f*e+j+NYa<;)Ll@2n(z#m)1lxZm$p0pTo46+!rArp z7-cacIf|no+kg*KmUyJt7l-ArAYt&M+bbK!5dB92id`PAfMdz0d^AKM3!gCohm>d` zW(g{7$7Wk|kjJ=3!P@IVi0oH5gs*QSv$`W@91-9zw5UKl=T3fY_DF=85M899N3S`r zkMiDx^G+ti&aX2{f>U;a`p-k($6~=o_ve^uPOLZ+%A{oWP*pI9zfVo$EbGC(t;Z=9C0A9Vi9C~k4Tu~PN;Q1K*VikOn zbL+R^SLP~4tceXm>*&?&L82#i581iS;iwmc=ifNYa4yV-%s;M&@*ZEDyU% z5|9wUE?bY+tv#?`98Y`fTehyD95P0@SxzBXZ>nq;j>fDSYYlLdzFKc0>wE;%k-5jbG6kK6wq?m-xV^d~;BAk&dwY$Dlp`*m)ML00A*UK0z6jzXam ziQriQl7Cdy3>gqoz0g93Jx%0JAE_tIRFa%pZ8^HbrBy^A&YVGiSe~5UZqV_gBYikC zR?ySM9!ehgUTq8nWqY`q4`+gGouxSYo|4;|5678%O`ZI3|jveJCW#y|C z^ZvkOvJX9^aY|*;#BB3>xfiStQ?m?$Gl;A@cLd|`FF>|VWA+8|> zk6iB3&d|k1hQ#T;hGN#i1jiOkzTJCcS6TSY)BHK88~n65)@uYChA=ySHe&KTq_Kfw zp6_o15xLtwnJ1U2wj*qto21ch7Eaens=UdISM#1-jLrQm*usj+e-XSG0*Up8AwxOE zJ+0k>&8d)zZ!YS=vt2h;_j{?L7eOE7bI@kD{#>2`j9GXJPc0Rxec*x!G|Mr6IN4S? zpS$=_owx&F#kI2MM=8^1%d8wm$hm56y4^FYhv)}7W%cr5L(^ZNP;9R#q{yqhW{si( z^RCT6oj+m@2t3EoD>7Hn8y_)lF7wd4dcxA;#j-X$Cu-MvCJKnPrh^kT-`;nz+ZS&n zL}M3W!RDE|cglLH!tse+ITvD(ru7y9Wmp#Pd%98bI6)mZPoODAG|b0k&j}nt=7w|t zk zGaFTi#VajI;L-U=BUY2wUThzuPqZoY%XjT^;~olSmB#dsrFn^8$z`Mk2;*5t#7Gvy zPNLzPO0E`Os_Afh1&pj_8uXqz9V*d|7|>LUo6E z!CS1E1BT7Dtu-L65RRCMyg|>sQ{e2d@%fR@3ZeK& zpb)QLVujV55tp$$M|+uPChvbzVO4r=Cg7oQ{dBIPp(g~dTniz-Li4FO6 zlv)9HM4%{p5aewh&0A_5S}*5s-Bk%!#&{QU2gz0q-cT#O-!f1 z^?+vs4n$6i=Z#6<@snwQjz*8a* zDI(7&Yu&S)E8xHC2|0L~6=w&3${qG(p}5)4V(f?@T3|22+)q$wp j5%CJ9qNE5{ zQ?{AV|39?7W0Ypgx-8sfblKHq+qP}n?s9e6wr$(CZJS-T?OR*l-skLf&spc*`~7); z%rQsi%=wNnGa{cSA^=?!G%OCC;2Q8|UAr^<`SE=o5kd!P0JUqc@ek0~RctR0xx%?h z;L2lmBCxxd2#w}$8ix~Wfc;3ac~QBDB|9SxR>K1QV{v7Gh>7rTc+7}$d5sE>Cej@g)9?lZeP z`hKr!P#RKf7VD9pH3!NpmUM$%D(Zq7?#+I(jJ)F`y?mz#E??T*K~hp;UByYZn<}lO95XK!KQK(H*5(`#Bep!EM9A zxUHw898iaFYg}^Vsh!lce?U(z9tkWJagGO->Sk>Eqi_+9T@jJ&aZbzVD?#*Ai!-w@ z6(EbYHx~2|VLfCA)7Gk%?}`tD}L4~Fvh@tZ_iWXZsTUwN&F))^5*QV=f z$9@EGs&Ca{@4#>uR9qJwY`YhaI4UNGsN!z?)uQIdS{u$jci~rRNFbXFy>2XWl2RtV zzqp@UCPVk_iJ7w8>nhUhq|U=i=Hpn+MoTk49Pg=qlhNqM#DH!$v&8wLBf_sPkO!!( zXRXJ(Xzz?`00vZAcRu<45Nk0lDRpj<4h!t8s(xVWQ}UbYmJ2D{lT~_ajC`~Ffb?+Xw5;wk69O*Ut(O7sd%&GNTrFw5 zb}hHtBgP{N?L);-N+|#3qI~5xtRo{-`+6Ja>l9oM`2MjhJv=7}@7y!Vx9nyhVv+1{ z8^cCxBpCOPn@&1PL4OlVpAEsh6sUzcaKPn=+@TiM9|F$)*FEMMpLQ2HoHjvl_CN>a z1cmS4eiL-d8_xBn3Y^NP_h=rtJ!w#Nd>qPHf18ZrT*ftU_eYF&Rp=0`CdPXr?F5MN> zpVfw+i$mO?4^X`;diV<;J=Yc`IdLaTt(`K=8ERA|yzE`Jm7qk$Hi6o6i%}N9{`z8T z_#C_y4o`vI;?VQnIVT$sCGfx{mGj3gtJI4ulJKCCkIYYmC)o_*to7`q`8}gX&7phn z*jQPLdd16@gQq6ci=_F)0I+VcCy{nnp@+Vdr&{yvZy)awjgQH*cz^`5J;xGYJy8-r zMqU)t=O=bPY4A2OsP_S%-#_BlR!z>8 zOvkl3cZ|%vytUDX+@5*a#w84xpBRo9GhC@zqo8Tp5)&~9&xKll=Z({|HbR$VR83L* zX_q$ZBwt`p1miz3%5;{KHn{X~Wa%amlw=Z+7sp_Kvd>v=k^RUcPf=?c*&OZ z@DqEfc_8gJmivU58pXB&cU349k;hnhwp9ahuYU;;<5<&jBvLs&-N1_3%dAG%s@+VM8H8~Ag& zil0TOs(I}>Ovg84j>yU$P0w5raHwJM%(`ffBUXS$RoZ*$!WR>!{v;J@`K`b)$fjIk z>V6>P$g^&dvGzsK&_2qwh1BltJ=kd-x+F~XTbf!Q?`}Ufcd*ikY}C3RtVYXCXG^j9 z6_2IVq1#@pg-pvChK{-o8OoYR7I6Bpv~$rKVbp0VKL%GDU*31lWj1^VTvftcfe0pW_P%OPAk#%!$l5Mx0jQG3 zx^^r5GRO%nq@M1zB?xzgm|I+89Ycw5#>R6FTCn<%Br9C|gsH1z`@khHVtMT3@4K2! zu*IEjydBF2Y!jchkd7cPQf1{v2bMmdB)uUEGe-jC+2$3muqAx+F2s!2zFW+JRjJeP z8X-1rp>}PWEhzj!ygEA@9jzQ zRJS+mlR5iN@H*A95C~(f8Fli*+AK=#(v~N5ztzOPgiXGFl7i|=ZPUOW0?c~l<=uN2 z;*6$5>sjp`IXSr&nAKr$%pEKF4HKw>b)j-Hdz^y2=p23CBF9YT$_94*XoJtdI^#_) znsTx_LsAJFGvEM3$Dl4ii{Wtj3YeNhiwKEo@P|weM7DgmOOb`*aR_vp;N0!U6;JH3t?-#^J|akQfyOwdWgfrdLY>pKx@qB)E-;oMa1KjRnSejgZ+ zzY0_;0$`K1oP*C^?0Lp4sZmgWJ>E4p6tP^46B9aIJ=)<3vc2|B1ELfaarI7OP*8<(2pS%3XF1V z1SlVo;~H>VIYt>M!+G>4i);K)WV-=5+7*Rx|F7AGX@L{2*@jVtsNf=8ps3SGjg4on zZGWcdBE=;Wo9x!igD-OOojv>1KX>7!lbh9#4*>of9Fm(PpP01w+xEZ{PX3y==f8s# zx-Z{}e`_VDqo@DVC?!LA!upgMs_U`p%E%jt(KGf9-mR(Al4|oR)Y6o?uhmb#EQEG# zl(J3jVJQm9XlQa4EAShd+&k>za&Q?>1+tDzrH`i%+*gV)pyeailC_Wa7mrti>cKTX z)ZLSIQ)p7_*lOl;Z3oe!?M?>gi8vy7c7wo7ZbxHN3JKR)3P$nO9EFIV9kc7T2E(f#&zf*>^F=%W$8berw#Ro(jBgqx!H7GBR zi316%q%&BbhX)zR__;+bd4mD!Ss#SZuj5gB6; zKA9g$4m40tY&YEZZd9IlJ1P#0N2yTG!|CBVb|ds~Tf3>YaWV_TGng~-<|{{@r#9+6 z8OwDnig5=-b+bQan8x#r+S8q>p!|L-_6Cq`>hs3PJ+16c>z2`Rs0t*id1_0f0|(O) zS83K7z|(?Z%4|D!bSz2kSGn{`&IQRr(km_?v zKGGd9%eW|t$g#_QYRgv`l{)aMgIV8+_^Nm+W3hj&FM&*2C;o~rYh4r}r%8Vu|Q6vM)PnY5XM}W#=qj87y29E$Y*$cFu7kf$&Gij-Ln_sY2F{$7=UWZR5&Nk287W@-6sC>!c-hXR}~y}DUf@SXj- zq=gJhqNjHw1sKU*7plTOne;%YI~DWF{)QA~y5YUDboOXm z$~gn3Rd^_;N`WR)jhzp20}dN~SO*lLv6;8le%>2EOl83tyBlPX@^d?oO0}n|Cjq+2 zx}7nk-9hlpJ?uMnI^!U$OWQ4#$#|~Yi(iij^AVA zuoG1k`_e7YdUDWO6>JtyWyqCb>23E9k!lw8tVSBxDbHv?#`w;y^!8OTj&cB{l0e<{ zG9!spP@iJ!5yP0NavnhPAXpq$T$Q^feY7k9U1e_Zw~?lwtw_p{8zuR$A_dia5qoe&>HJaw{MDhR3zU?m!00uz++5n*Nj|KqcKeBK8denb@{Qv7k z{+IS`bc}zh0YJvk+S170&gIV*|LJJ|9_{o$cW?XOy0(3l?7!ChpKRM$ap`FPYTNdo z%KJ>TbpL&MecyAYiV$dkHhbn7UJ7 z?LNAn1gcN4L>@0ha`T=WK>b|xTi4ImX0P`Gn>_Dz9vid}vcFJ^SP%@NiyuX?cJjDCJLHgpZ^G#{ zxU}zYn>VbtS3auNHgzJN@5YlKY4kg~PCg4fJfcot2?lW?ra`FizR&L%SolhS13TX*qTIB6J` zM3)w+hxYwQ-Bl0u=|Cc{wW`J^Db^JvLYzMfN!$qzJP1y_fy_nlrpO3Mmk5?;?50c6 zmsDUNRHTNGX&Qp@lH|BLe|0@w!(sT-x5MNZiX3r{c*lIe**e} z;6h`;!gcBX;tcStuScL{?3`60iCbZ-vS~5t@ z;-aa8(!oZ_F=l)O?R38I$ zNh`F&SCJIJN}r&|C&f2A=35PxiBX^S$SUHPOhmno)9q5UJm+A2M67Wz3WuY z(my%pZV3qzxE-au>M+y#+=Z#kfurU&^N!@<0*r?c76FF4!=@q|HEoDimFft6!$3d* z80dzSprl1tORo4G%_%}ijuahVTTp5u*O()0c9j^QCQM$Y!M+kzPNA-NWioeF z?E7mFi{^Nf{kce1A=_ges1Fg1D7|OCVv6r9YSs&Lb3Dw3 z>}2-~d9*8*UkT@H(6?yOJB?;tit>u@Wi^mkUX!IkPVxel`RYf!+SFb_16tKk0$!p6 zm9d2Rf-SAHV3n zmLGW=E}<)&?WH@fldJdNg?S4_Dss#0@h$qdgsLrxxYDS-MBgeT$h)#9pO%SNc(m2| zU!=66+IiL0IodCyms}P?EFc{_O}8EtRa2*~1lESLjGZZG-St+n7M3Q((@FGo79dC3?F6#o$}_)8zy zKcu(+^_Kb1UF-h>7tsARofPu_H7;QI2QJV8`-7N8I@*8rDEzNi`CkJArauJ?B&`kf zEX-W>?9HsL{xmrF@>>1NMo#n3*ZgO#UH|vsfbK8Sp??Plbbsy6{7>M3f$>j)gQ-wL z7O26?dn5-*7&!}x4<~5u%U=%uK$TFRC(wbr0byf#Xpt>Mb7u2{+i z&kd}njfSq>!^5WYLm8LPo2dtf?{olqD{*1);wxK)I}-R;o?aXJAt3V2xx=MP=Tqm8 z@0StTjbG>>ZR>N#tIM*1koWM>8&6=gy^EAi1hlsi;{}*oOU`iN)GTZ1+~t?bBTtnF zH`nd?C_|RDz6bZY*Qxf_&dUR0hXlMYL@K|uY*@q$kaQ0lsov9lz*h5RNp%!X*4BfL zHY=7mqV~sfB-FJVk!Zjuwr|kM*vC!d`&FFZ)9#qgS{2RO+yR+V@PfS5fG+fejg(N2 zRlrR@gz_xletfZ^e=60CBGk+@)QsXLpCYF0K*De{5hN15!`=|8Aa!->Yv$iVv>+a_^TPfPc3L`z;MM38~%C;20ykoL|FNQ|u+Gj?w#MuiS;*H5KH zWtKdBQ3yyXxh8t#&P3nC)B{c#IvgsZ^ccv`%o*reS(JQqrWncj3emSwiiWXfXB#GL z(T`9Wv}%(e{t*2fM)7Qm`3`P9(?j%%rK}hPY!m&ErVF&xEH65}zEf9OmT9x=^87 zNEeyu(j!BTTcrfn(oPhQe2wTBvOPUFz(_kJ)ftMbnj}~w_=8B0`9wPj|IkVLm=RjC zP%tws%IL>vFJm5YTuAFuK{6*WDovr!=c&jbV%FuGqKEI4?8}m(=5fW|&W0(9 zl*JKv{u+iP<#KyzjXs&J=eZkQ0+Vje1<3Ui!I~_bJ?H)+U2dLX7hhh3>i&bUP4T0j zmtzltt{45g!kX#7ktApriAB6 z)r#ae&mTDPQQ_s!?}+?hQH6sGXIbnwZvh7rL5HsELEk z+kZlXyfPtjvErW>PJNDjQt{5A=o8HIe^9C`-|?J~A<M^)8rd+T-%lJE+WOj-r$1 z10Nt&Wh>LCEvvqnkejgxPgwnQKdP(Im*L#+`{9~$f*wvkX{HQK)65sHC;ir|?rPih zLxu>M#^W>D+%|t6sH$E>8w*EKmh|YQGk=KsvXWR*LG|y>>m!(X<)dN&j)^{;Y7|08^$a5r<#y?_OH&*x%RZfxsB1?Q=<{96WVS5g}2Tf+O5J|>9qr>z1Y5#8H z*}4*oPaJ#=Mug!wt zhM;f0BFyz0f;t^Oi9@G4s@g_#6(;U%?MRVfEOQIBR!OIg*$D!NX_|)0i$F}pcu?}5 zL(xc~MkuFx`CmQLflz-bf;zRrB*670b(ISq^?aK24jX8 zW&1v_RmoiL)+`37_|0lTgd>ygei`2@RE+o(Tor1>^OVS|b{iSJ@oM zp+32rLOig~a3%SO-_QUZchjXa4IMg%Ip6M$5|OFPP+b$477k007WZ}awTwG2dJ7hb z9J5=kJRnel(JwXhE0$D*e#YZh_!bIO_XIo?EOvL=6hydiv&ZpfY`2lgXw_0nqAl03 zx@zF*h-I}-;aAj++Sn);?9YyM4kRajCk5;BmX4oI94v$oj5u9N>5Eon>6}zGU_LT5 zz^?{K8E@KIM{yrcJsoFDkvu7T<}5p1CA!Q&3>ts%Q&cwAtzk#>W! zYr;8~7N0UQSvDB1>fWr=UKj*qPk@17d!%HBJ%c4NOt!Op_Wn!zUT3C+oQb>y* zyF5Amf}3)AMptj-Zbug&t?o|D?p|yMDl?&ZX_NtX$!;%2IhIr3IX`H&RPZ|Pv1$gA zi_l`)fSBt?3Ar>XgoN~d^V?@^{2renrW=6)8d>H0sZ$VVcgo>m)p>9?uG#sVT^hS` zoPi2`Rc-yqNg`9r)P4C(ljB9rcrmuR08j+;cr=7Kcm!HuFyScc`veCjRW=N0XtH>& zIYo=FS6%yn9DE1p%N-n{o;NO>>>)Go6808v@G)Nna{2KH?=R|<5;VGR)I{Qx{b&?u z9J7RcnlWqe;NdDI8F}DCxZM4pk*n*MT4$+Dkn2D--|;A%G3A6}w#;L+e`lmaViLif z#IDH}1%F?xw5qaK+cQd3E=n|>!s;QkYB@j=Y1qgli|@Dne$^*^F@u)KA~du@iAFGP zOm`GeGUtzN)gXW9@PL3{g+?2#OKZ3g%I$t6_+pASP@CYKS|p)WC?K1TH~t_HBAwqU zsmJEpWkr72?~rhMl7N05P4X3Vn!C3A(YzKHi(9_TDg$cZ?;;NgjNwoO(KZqH6{*r$ zLc(%@b2%D`Ty?uoUIFHfCd8<$(WcP8a&!^+N>NufjAt``=8VH-2Mh>{wKWb;p#NbV z;>ik5M>J?lj7AX7P|bjl+%&Z6m*=%KE~+<=(V7jA)GfXkpwX%dHIOe@{l0oLh#k*> z_}l6N8=v;qT$SWD4jqXN+xw)<3p~-Mcj(Hbm=SnHZ-6l4sUj{V zV!`lrx-lqg{7N`-*MwFWjYlmU;cUtNdOv2nP#E~(cKV()!k4a>F&7j5j3(Cb)7d+l z3h+cgoht8qibsmmu7LqtMj9|0CN6YyIpv}zY^Kfo;sWXd{Ihow;@)#nH>6m8R~0cF ze(;Ct2;mEX)myWzZ@|@7Tgs2y@%CAW;4e`#+MpV;#~M;rZYmjdvjdg2gd3vkhKfs*O)qJ z{jN${svCo-ljS->h|PM0$I_c)UY1AyeNekxKlC7LbTeHqKVUn5_|q@ao+kPwEtE}$ zCL=2edPkA*4hTpLixxF}?M|N8doC_ReC$2&qMV(e{dFin9s7@Q!j@77zng#89|F zv~al{FKWUa&sEsuhXE`ciLN0t9lCx}jB8e)Z@>jQ&&<2tgKn9|?jDa?^`Pq6pVAGF zz9VnS$@uLF%Xp+8fSs3R$Y4si;Cznh>c~OC6>` z4Fb5>61U}$+ZXLJUFp9+fKqLi|3FtqNB8G5L;gwa=vn_JtfQl6`pV+?SI#M=XK!cb zjH~e%#!8F(*Wdq;?LkNX|AIjy{zY2%AA(VS{ewaKgBkt-RH6Ix^1**yjjW=ODz&hg zg^{$Lr4cSEH4Po}pJLGe5{<&}ry2B@?d$&`gZ^*BQRu!Z$p6NqzZm=1|M!>cf0NhI z(f{>)|F8NwI{LpJ!2hR!6go!6KO?YH`ws~zxtm9mmcLtheTeCzh1L=Z&FwGKQGAKTvmO$BOKxspd9k-d7<)n ziQuSgjam1vQ9MhxBc?v&WdJ%;blkwS$F1ee2>U?GmmTpE#pVG75at0wQEmnAVXB_0 z#vy@ZV!G+Jobyqr=8@tMw1FjA0Ef4WBv}ha`BJf7oaki?MKmJ=$jhpad6m>Ak)$7^ zUgzkEpz4l1*w!VWE&*4PA`(W`AG|0lPMf80<{v?~*k;d+oK`&TPk3R3N(;q#wtd8) z#NyOK61TR;I@Uo#~6jt^X7R<`2ysyQGI*OgAJL=go2r+jf>9f-8IU`M{pHyX^b$k@7mg1ck)j!~6d>RAc*(yE zI3b(>A@Xt*V2bqX3KJlK?j*>4?EJUe2)|5l->S~u1Gn(W57 zv2&OC2T9x(xA}txz@*h0OeSPk(<9u+=j!`?q`Of0dFCjfed^VIjBQS=t5q1FQ{0ph zfH8;f>ODUsR18|ltApP1cb0QQ>%9$%Q{fF9sweRUjuaWjzJ(&m%qpRa8>496O^AQ+ z5rb`ysf$k?mT?D2gdn?bSWQx9vwX?pk_*1c_ag6?0MaJ06WeZ1Fpmv{>TFq%+O8@t z5rsWL)wnh)E<7BS=vwpMx!3D})TaQI7Ewhs|2}+;fnn}xt~u~E#{l$qR2a1A3w0;3 zV`OjxB6br4z|?Xxd&~VTl1B&qzVIM`xw}-1k3?=R)l9-Iv^PPCxdnZro_546` zZi5)q-I;^ET~YBR2f$oJrWL7omrKk6q~I_mpcS(>mt+PPYaP)(C>IbGdYckT7oQl+ zHjsK&%l0Le_rQkIq{ZhaDf!9j3FOFjyPu=Q7A0$YqdU4+i++~6IM^dzDR|C!z~ied z$L$?=|FgP>C{CbZ)>e?)7N-sGDR(;#>|+jhA?!ro^W|kAQ1o3f5*Kqf)>d_R@>HCT9hO9C}Bp95x?O z-HhsWtk%d`GfTF|87m6rT!LHRJD63u!Usodt?f1=H%qHUDhLPhx#@6n3*o+*;ZAIP z5j^IQM;u4e)lvlci(TR=C}N7BeiqbyEhobLwEfs-8fT1H)6w<)ei;-BunWH$)5gK&w_zFjLlCk$qi*JEZ*gE2fP1S{R zevyK}RyN<;46J5m_I0d-0N?=t^jS^maoz+JN^&?%$9p(vn{1#qeDkbel-1@R-HKAw zJldRG`Z2h7L)>?$AKZH_S`MMNfZkoBxO5yF*DyKiMK(p}G;Z%M9a{)zwP_f@#0oU@?Z%QKWSyHIu7R zZ))>s<3!3>6ANxrK99qZ@o`TiG+M)Op^ZX%fQKX%vlBF&MGOjumBvf7I_vwH6GQmt1dL@QqQMA>aJKj53pZcty248bo|ATQR z)Kh&eH~+*&Eifn|SfByNLL@6Hqcz=GK!ZV!fi7KjX}R>`D>>fx^SsmRm9+otx0$A} zSgN1K#X1-QnJ;H)XuV(vC3zVAawusTA;bWo;^e%cT%t;kvy;v>32jgb7b>Oq81nx#5~v?MwV2E2UvXmy>8WA}Rxvs8gX+kl}lx+NBSgV@g1 zoba$Li*`>*-R|`sYWWGefn{5vBUw@odbEyhs>^BI^+<|IlMaLm0*M?lD$5G|waFYq zd!*`*k>+*=t`#X)ltt}B6IG>O1{XMK6~kdl5%`gU_=}2@r}z>2+f(=V;$q$?YNH%K z@uO}mN*_AT**A17G}0c1Q|j-`&D|D(49Sx44iTtRDoZ30QiO!atww>H5+P6p$O_XS zIp+|@n!f4oYsA1I#$D$*Xmwkv0A2HZyv#Xu5%-_p@i}o_cjSb*q-CecuBxR6Tn_m> znfen35KgWvDmHg3^p{TP#SO#NpCq1}8OkO!^|4IOIUncl1dqC$hRxcw&PFt#$}002 zm|O5TV#xWfE}2Cqm#i#|8zOM$8ZGVXemR6(p17M;yA|3F=vBNqILMp);-p(S?%--X zfR!2(YgI8ZW^$|oHPBFx;M&I&!EZd3i|$e-3_o`t_`2TO~D*%DT3sCoQ1j6~NI$p(T^VA)FL zAqYGD(W(X=m)xeUg^$g5rzbt47HQ4F9J5sTia26jOifwuZlKDB67om{TOAb>4ZHiF z$}Y5VJy#u#M0TPA*FuA_$OcR3z5Le0LZj$#B42L0Zp@TqCcM9m&h5`v!whUjfC7kQ zgaY_p*XNM~{5>7ErnQ92-_l`qrWY>7r})3CQXC8>a&n`&+ z!Kymg;sW9c0vADiyA+(J^nHKcZVD1Lwv}fMK|khx_8515b*A=%eb_d6x?SxUUOe5L zjPDZm#uv*gMdAbW$R$Suc00&U49n#onc@GntAAMudysbs7>lgFUi|3 z?I`I7q3sXdxAjv=HadK`HM)AE(appURXD`{t&*AfxfySJ#LUkiPX&K_8{gSAjNwmS zcFH#@TQiIdc4+%_*Bc6tRMUhzsw`;^n)gG#z>W4xu4ASzo8A2~7H}9Ud9V=6e=fCu zQw6<8tvGSiwuo==yGpcBV%TK2&`(Y*yM$;Ag^k1ZVw(kSseJzojMk&RH6k9y;{f6i z+v#Z?NXoJm{55U>;BEX>3kf5m6S{jCOERPO$YE&+Sqg=m}Ie77OmH8a%5Q4v@~Z<_qMg zH#3hwVDr45G3=-f{NYvUXxEPUFI9^mHdt_Bu9QJ2clgQDLpNV6O#AXD0&Zt#Q#9UL z4Fijx{MIV8W4_@CmSf$uINdZ0HO^9|Q>;TINGZQUe4qTa2ap0iVT=)@2p^$4l;BND z8y&WV<40K&zg>rl5GaZU;r-GZra!SsA;i3M{gz-GKiUOk)W70>(QM;;?UK6ui4t&HmT5) zMnjQQgKwG)>D8gobMIe{n5`Ru28ViE+}bn-`65~-da#cgK;MQaP+)d|A1bm9l&I)C z%oe_3!&Tb5b_`ggEqXP*a;txN7X?LVQtZ56LYb}ei6f{)sTq3NOXvlgjqsS$)CI_U z!(L#@nxI5jY7`<_L7Ex;28`ScrNY~HMc)%4<_b!viO8oquJhwa6FN`JoWq$#;Z%46 ztGym`5d29sY`3K|mbk>NX8Kzn@;vVoa0mOYc7&#tWiXbk|A&+OoNtyTseco^nk;Oq zL6<7UJ$6x-S>a|tn)cZ+{vyR5*Vcun%VUgxGn7wAQ^f1F<3w51C1(Hf`_%;(53aG9 zH}_>=bjdq~zN=V|gr#D{b03fBAq{MBr(SI)*9eANk0U&MXgeTdH2u5hSyB4yS<_u0 z_E)DX+?6^75mMB6ZvEAL$|n9P55VeX84b7 zZ47@us{fy*k{W!GZ-HMxe@`U+{&(VS3<~P|N2~nT8o~cf>6-OV5pN@BJxd!4Bf39L zx*7g|=xO_Ut^Y>0zk1pj{-~#onSuGg?`i8$9kKcG*feG6Cguvp$QW|Tm47rAwzU(#%e zjaj5hs_%_7d*5BUPr82uS?Wq`_dNgPrm8Mz*o$983|nsP8S|x@qNj1WUZ5EhaNh$zA+y3Fuey0XU@o4BML4cB)?N;atOrIo7a3)Ox7_KoG(zAFs z)KM_ra4e>R(ZF7eeyKZ^@$I;=NdHbSKCIvmXu+5&LCR`2{oq>SAw@Mhm;7XMoe;IQ zB_B0RIzhD}QuE;2O(Y{|xkNak{F5RP!@rF|M4WGtyZ}#!yW<}W0B_CjzX2~0kCxj{ zCJrUHBPFLFjDQK>122Rf%=jZ1UndM)8v?geg51A9@}jx;h)D?<40IxG3jD#~M!bbU zkQ=~vI2R8F1TXa<6i|aY6sr%O4k=PFNCBh|dLnK6Wy{J*`xrdBg~prm$8TA zSb27eUr>kFJxDnIPrn17cz4H4uJwEYhI0X6KmfkRc{oMZ7WoR=5BOjMoGG4p-*4Y0L_CjI>KIno+e(VwxO4yQ=X51d+W_>2DwM>ra z>()+s>$?QEX64QHjXS&|+ljW~SV_Wn^$M^~kI!$LOb+^9xkR^pLqtBQIFkmG@4L9;?)7K#YwD1zj!aaJM? z3&~R6l){}$B=^+JA)1FYW?+#qXsK!mMEHmnM~>w4)krad|eZX~TaPTkjeqHWZcRd1mSrWdT^bPBr)5UkauZBsU_j%A$`E+sXds&SdVp6HgburN| zuoM^GcWqZ$;G6&8-Jezuu(C7#mOk-KcOBrvNAd<*v)`YfT49M|9iY-vZ8Z6Pe8DJ{ z+}AtdkO&ypYLOB-+OR~YIc7@A=w_vMgvqaBCUm$FndMfkVG%)@Yx+S}qozZN4XphT zJ9I!k%8-t{ip`N5jV2b6iz2fuYN!0Zp1l;&950NZ!yavA@FEoN?<)weLE{;f#hv5Q!6E2JN=smm6suW&fFBDIM3iJx0a4zXWCh+cow69vmQDA# zMw##4jWigafd|dBt2DIdK+XjEv#EhXI)FPvv9o+O>8p6iRF=h z2Vy)rKF5jWcJmb~W&{b0@Aqe(WbJ^Vxbtrn*i~k$N|M-DC+jMm^?eDv^u7t4C7r&?t29z%t(AHFu*%a` zJUFGSjOA1q`|_IUs2R1`>S$C!9%`k$A9qxN73$RHT&|o7P_M9%`8_1@m2J;qp}kjv z5vK?%W{gCai;+faECg0TH>i9rEaPJ+N{~mA7cAJDC#tJAveF-i~dL?6-&Dxv)nZ zKxzd~5Q17zY2 z8U~$My0^Gb0MP(Wem5rma=|N_R)E#=hUI3Riq4RW$3+-5p3gc9=9c#6pMi2tG8rSB zD|N2eA*b0q;~U@$ZVpdX+qyKNMi!-Y&m0gj2(M!W0&4W&y zGjI#7w^1%7Bi{@OW#NRiB;PE)Av0rQHqBlF0b#kFfoHPuGph83;yrcFVLnu4%Aj=< zD1Ilzuij=2`}sAx9CV?)ZuADpLostcd>m%sbsgi6C^~ThVj_ffA?3|EQeIkAfUs?K z%Jz$?E{r98yDIZ{J>co#?IPbr#?HpcXQb(8N*M=!6SdA8T^1tfa6(F59uTq z4Q9^QiSbssraj(Z|d}_bXC$*kchgIY}P!EV@0mcRbv$d-{^Y3-V*A z0;G|JS9f24XxK#0K2Y6T2hEPxM14vh&yk%^?wiQDG7hqe@50e-Yh&rU-)V|$^t@pv z3>t(hka_pT+2{n*vhD8kO$BxNB!QK!chb2*p0Q4imdc7LV;v@QBxenLy|X-4VIotK z)T+?Cv{B%<5ZI8e0ZCp0-{xo&_W&mFoZ!wIiZimhDE9y^0q+Qf$a?-R&fM1pYz3Gx z99N`qfp4waK@%dj*iYLFhT^uryMFRa_DQKIexrKb&@Lz|pr%n!qFQ)2l3H48T4JfP z026n!zbVv(xSb};0T0T3K2tj`L=#ZbFhalRrCd%o}&oL2PWBaq8c?o22 zF^Y_LgKJeiuI75`6$BqPpJ9<@b`lrO)1|Z0jjtk33RFoI(WP|BVu zw#PSHs=0M(t~D8SPcM4HrmK*6at<_)1RS%1aJS7aTNrBI&28O{6C!%K{h7NRbGaQP zELj7t(TUHs_a0^Muys>-33C-W@S8jDs$}X!U^vV*IaC@QODTCQjX;3_0Hj!&Ez5!g zljZqB;+4JDc9O&HN0uab=|DMwY)t=J9Y=vcP=s-3FTd5RD}oNj4QPKABQW=A>48ZZ zA~dP&(&qS2NP)h=>3n;hi1~xnn3t3ch)va>YtPxl`EnbZEkRtOb1LJK{pl-e(Awu? zg?eL?peNn2t*e&4QY9&lJ&Jh)*#fp9fanihHfgJDZQoOEE}WRDwA=!qEZ=A+!vNd4 zr;M#eO5G{0>M3;AY=RAK?jQ%a#XgopZ`^qkgYg?}i-mW|g(D0kkQPE9F{{XK)BGYV z_%gIu#yT6qa?@_O(;A?Rhu??Xp`r0uggl6Ua)jhoGQ&w2Qp_9%xs$@pyVTuxaIU#p zb;(zv5K38!`{9)7`+8KzrD~Ag?a-K7@IHGmt5}` zQYu9{r$8~E*^?$4Qp60z6crP=S)qETdye!OA-*D1%1x}&-GYE$KX@0Y<|*4(PZAJ) zhQ#fj52(BM3~zdgo4jzSX_gxpV)7q9339yH%wuxa@{j6p=+VTjS?OkJv-%3c$${no z?hR#(spf`xl=!LV1qZsEIA1#qoHbEgsN1~Rmhfzhs&Z+N0k*6WV&u9Yw%Y5lB)en_#gWo=c+&#JCL4#lQpJ%Ef`I2-0>FkRQ6$$HgX1LDFs%hJRa&&IOQ1R(+j^-Ft zse@tb4akTCYn^q%cdXg5T?55Rka8nbK3NGYO#=0iY*MkcQ&+&-PQ` z_{8N$jH)$3AYci@L{o`-YQd=wd6u@}qmDT#LTf3cI=YRpYMnoRqa2P!4Owr@Ykub3 zPEOoHU22=N{B%34vQSuTwc#L=M`|4#g>>PGZzUgfjUWuDY@?qdN1Aq8!v?V*jNs{X zz9w&1|ETrb7wJv}g{&SK*3avKSMaC5$nJ1K#1<1jTq|Upur9P{Frt@*z@M9!LpEw; zZa}s+TeIsJQD^DO7i|BEc@Ed=cyM>-_h-pZYP707pNP+Hbf2%nj7VqKF>*2a5%24d zs(fEJ<5RLR3N0P#Bl~*E{Oy1KQ|AS>4rh&P(~@ zDN|A45Y=V#T?ay&oPpzsX+uv%BdgX|DbCg!6>X+ZT}z;KFXfg|o2AuR4WoD=K5KNKLO zK;mLq15lR2RO1j(3QuYgB>SYA8J{vj%1AaspcCde6N=A^^PPN)T;(uKi`?*8bkvd` z?Wc@ngcQ0T9eTlKCKbCOS*X4gQ*Mm{GpP((V!!V4IYuuDn&BmZ#aDOGVDS z`TOr7{VCNSgYHI+^2nn@<4H9BNISmF@q^67wc!rpu22S0CEb{voj@|-P+G}F)K4Dn zXXoVY4qshhu}NVy=xOZvFAT1+H79Y(c5oI8q-H!rg9wKdCa;i%A>7Y?>-nH z-0cgYuBw0C8^-bL_0wI!*Wam}wLZBEF6H!e_e_LLb`JqD%9sx+4zTie`|J8;aXQYj zrap#+Zgy6Pa=y@0qfVP!ANGQK5E}JX2O62hvOE};P|s8k3U;R*FX6T{2F^vmAX5V6 zsi3(0&r-Gw8Gn$^_a;1(7t5$#WECD)Q~vB*7tGNApc^bRvFQZ|48>?N@&GQQu5GX= zZ>iJG;~DM4+!A7~jXJK+QO@0~D_Ok+ak%dRf4;Ly{CF(!x|cnB=3Nf{eY@&gkWjqL zk&r+Y6qGdJAvz8F2BV$5G5jA4OZNXxeE-|c%+AL7f9hsl*R%#r8%KM~)XQP)`%P;4 zK-O8Y9D*qo-f+80|Cj^~i9s99pwRA{@QI0`%mFIJ`caYEX zbRC{YBjno?!XVSWMLzV0jfD=%lA&f{sJ^-0woL87F zZ{Kd5X1YI~P>on8?{4VUC5Dl$adBP-j5uJdB@I#cd?$~>x?@g3=YKR*J)x>zC+>Uc z;Q&OQPJ9~iA8&k%=GOgM`nVhB<)&-k604G9;^^eX+W@_ z6ZTsqc5i!h*Gb8=YDI*l!1D@c3HaM76-Fp>%ZQ{Gi$McY_`#*RI>ycN4e9KP{PoiZ zPy4TWnmOTZZTV;q4t_SX)BP?Vq|wB-@%njfye~Ocp$gbG<@aAKhu(xq#k%bS$wbPTsa#j~M78TfX`p?l-|6UKB2QKifo)qj*MhV1j| z2@eLxxCrvivCPIo;8U!KO{yjI>-KE$cE&ox$+zF_YJWOgUlj7n|BwPpkYEJ|fkw(C zfu#i2qC;lCzj!F7T*2LKcb=8#pto^2Ac*`0J5XJ%hBQN&OHE z3wEevZA!RK#?S$7IAkyN7N!*`nfANWsOrT#o-n!(JN?egBt4^&Zjew7!j*2n74*A2 z%|oo$mXhazl02s5<{EBG<|JIfce^R!s7DL(e$_fk(d~2;8~d;XvcBP?$n8NnaIt`o zs^nd=4y%bVLN)eA2k>E%1Nc?mD(#O~Jpatk;`peun^#b>2=ftj=(D=SPc}W6JPT8kSrfQ2 z??pnXQB7C%mb2(>EGaI!{AQXZspmpBpz6E;T2UYCuZp3sQm;AC84m;s3QcG zJ>fY~C4C7!j7t?#E*ldLeay!VqG0MU8iNY*V>Lx}8J6Xfmj_XVJVK62LRX+=PpJvX z_!Su=Z4BIpqS|mssRO+;f5#td$@dnur6^c@gw>;Rsvl#)+F5aexJ1Lv;MT*%yE$ ztRo4DXp_acq!Z%zx4GvSpZBb# zDWA7Zfww)0M~yWaftc0NsTG&U$F8>%(5_9_K5r=k?^7{P*FNoU??uFUozkayFP_P} zGrA*s-s28?^_Y(XpWm-`P8U2&iN-qIjLu7Hni%;Xuu9*hqhdB6%1atfU8FK6e9W?9 z=|08!cpH=<;Q3rl33R-_p!#^^*y{EgDQ7Zdd!CP94-{1z^GWLBGFlaT-2|zG)HAx_R9xi^$<-VI#K=MqhEp zs9n3&qsu&pemdnKCjedqk%pIH&Fz&R&$f-KGEO2gIrpEQY&IV{#yq8n-CK^aO4ceZ zhz_+*<}Ma1r%e0!hJ2hzBPQ)x{Z@9nSoh(d)-5s<0f=idFc?9r*4tT`8 zv%}w0)6fl0K5rm>rP*Yva~fG4YrU4{)IW!|c~Je%l6}WuQaXQHYoj(kIk1epd5qn_ zsb8h{bKWo2yJ3zQ3y!a}^1P}a{AVZ@{@jPnSH&$SY}Z>PS}L(^i&enDPec|7V-5^F zTg=op=*yCdQ*rPoe>fVUW?Re(Z1GK%aeLohU~6j=o@O50pkh!x!;FXn5jN*nyyPG1A$9k;P_mVWmE}gi=!{I4slxUAiCHuK5iO z5%I<<9zv_tVz;u%>QwELCq%g!+IEZ#sf`bvM~aa|lC74T4EbZ(qAE3FPf?%m!WOGN z9lW31?7@AO2CU5qHCAWvW>rpP7;dohS99MBX?$;xEl$%9AqYRIVn=B%u$LnAI>_An zawfv&lBDpWRTl6{67ZVlq;!~WGsQg@mcrUa)&J6ba^B*ZZ4&7MzG^(6%zsG4yjloQ zZjfNOahPA?VTg3kZ!8=C7VB&U?N zp&WFzD6W**h8fVKtC#CLx{zL~d5Ax|+SE|&+MxvVLy01&*mz4k-@3?MUPwvGfDi3x zRwrD+i`2RBt~E{ZzK~|a0OtqaNPu@M?_n#UACfr(YHI~W`s{XY0DuBoS$rC0R+?w) zW>DwLuD&Gbh&w|nl?5@e>)Z_+>4Wsr>@Dv6vc)51$(Bq-ZZ9Pjr&ae)W!?wzq()gE zMT+|sgNHNP%iPPjz>19WlSf$++(`)qFB348TD;|R+DHZx+Bj9>V4J;D4IPC_9Xg6d zRym7j5Ahc)Pw|bxo)#mhM{Si`INiZ+J%Tl2KRl*o5viJ$?ys9x64TI=LQ=gpQJ>nD z_KFMwt#6#UZ11t$@Jsorh>rT#jJR!4cLvLf>bPvn>_5K95R9`!qEtJ9p)^Oy+hBTE zZe=;G7XFfL!r96yc!DNL$B&M{53%OoaHJL9NOIgg1#mp|$$;f13hFvM8+x4gAdf%C z?BxDP{mO4z5NjQMC+O%O-Wiswi_Fqu?YdNdCu=OY^Abs=Q?1fVN21gBb#LLo5GRrMp5cw))`uy9)Nc$=Di| zfZ=9p9nNn>btg2!rB){2z! zxQeohj&qA*l-v7PvQ268)X~}7_j%uT9{sf)r)A4}k{rQVMzA3OEq?4}_kA2?wyjR< zzK)~Wh_j;Ksi$>BhiFRM^dk_dgW0}K8#_TqH7DB6CE z7c5mMI(*wnkod#(oxE3qmK9zng$|~@ecr48xJCLICurupt)$havD1Ps>RLwEx3WoH zqct0#3UH36v9$2J(Pse-2{j!*?OIEQMQ-c5_rVH*UHl0!%>&IlNxb*9#b>UIlqrQ|QGKY=H=a?bk&9@!^ZYk0HpR`C(1&Gt1!o6>6v` z1+HlyjpgE0`6~)$=+yMO5Z`>=({2Q*!C}bdQKO{9yXNk=D;BF)=cWS}V^uXV ztr4D&Rl`%WH|9x#E=dT7fcwE5+m@@Y?%av^phI`D^V6kHqF@*f!P%S@;uo!Y z*GOQIS-m=D&|ox#@=~JeXXpmwI2J_BnIN6XD^`8lK33e?pywQA%vQs=h1HLKKEh`U z{OC2uhlpgiTsMtVL>qfkVQ;c*n&y$0gObJ@<=mQfBU`tQXdh>$WE}~^SMC?DIu=nJ ziR`e-DE;+Q5!;Kwg0QAmoAMkC0sy+PBr?bkjU{PNScgyy5t?H3u6b<~S%ge&+to6J z9haA~ka5n?!mj@*vi{V;KUyzuBC^FgEmTB&`pv*EVi7M$lDY}SxrzRFy^&yaED;ID zqV#Htbp1iYFSGZ{ zTMo{*iWlb~yFr>eR{VqH*kYJEUsO_It-Ea%DFHhdI%gb;x=^S0>@aBzKtdrX>OuV5 zPp}$7N4phgH`n#dLA2$h=&~0nHjSkB zXp3%UGR?w_M{p2!SP0SI+-4PW7sYmhH23i`QiM*yGDa}EaqtI8#A<=P*XMYDQ1gb` zsUAq0FcQ%-A_$d`qXw@zy(;HcfQ21==p||W+@yp&EwtQq&MMqrD21P$VZ3YsZr?|B z=^YI=X-Q)txHLiPBq6Dy6(X!@DN70z>NnIv{&fHsuO!KDfR_G^%OJ&6K^uG)GVlQI z=gOGe@>gFo-*G65eDwwxbJSQRNkp_7|3fML&qX1pNU^x2O6&(?nn2#NT50=0N$P-5 zWtIbf&RBe z#JmrTGYxiT6`Tcqw|*USiXtk&D{DY8t_hYtxzLA`!ffv$P ze3(Mpte``sJi5A{KHgCqW}mY^X=t zBO^i1Hv^mnC|aIaKjE|x4wecYKS`Sw9i4Pl(#EliISUkR*8TEZ<((DRFcv_X%YD%= z`a9ZmPSmEY(Eu$D<<<_Qyo=QTv<@ZIJb_~f*f0txUv2WX#%_%|LhJ_;KH)(88kSoI z+TydiSYSSkBnEY`mshgxNeP$3a$X)LsqEx7&3&4o!1Q7)BvirIgH>70#!mlwQP4{) zES~4Iy9%p^mu&fC9DqLMwWb{AqXBE8GfgxOdM$-s2-^JWPzWttLKEzV4bogN@LMf6 zh5=*+1ojpB=}wi2*0{#7!=bUH&H{qL^PIzQvFN19Sah%-l1+r@tYNqzjbTF7=}{hJ z=P7O%&in~T*@Y`pdAg%iw9zJ7$+(5{6NDJj`~1FlyTf;goDPixW+6m5^tnWn9FQ8^ zfB~Bl51?aWzv0k5v-9DKh4FE z_0&$|xrHqQhgWc$bHbOR>>=#~e**>6B=yQ24drVc;CJClc!a|^6gsAIK zN~6Eso+2&c?Zc%4YS(GVfrpl3hBnKt1oq!(D!$yJx67(|?83zjD(Zz*`+C}R!1^RNXEoQ%xM-WW0qx&j2-{!Wu6~+Fu0e@TUiZIKvAA_&kw4< z7&@3y@kXfgB|_C{4e~yGw_!!h_;Y8J6;sj=1GBsjsi237WUoQ%Chj8jwQhr~2-HQE zY-;B0-9%}b?GbR{?bFybL#t`cn1^m3kz&t1EcGfQvOFxuX6cBOj)QcPYle`BCTgWc ztE{i*GaGNeFGRq$&!YGwfB0@%;>RKx@fkLFByR=M0$W_t$g<tnWLd~J zWa6>p9Xtc==f37a-2Jl$Lv8j*ll9q8mB1LQz?MQpm;;5;(1Gw*Y>TmPBN|Au>b>81 z*{~a;ChfUM2ElpfTfS+gF-UQN1;Hzza6GmVsL#I0R}m6TAXsU9afSFHdUiF4i@@BsXf;q;DW#vT;T_Wqx`~pJuWr)&PUCk$Vb4Kb=JYo4$ zO?m9TP1Ji!d<{F6>iB$(Sb>bkpcedc21_T44_izecaSO#9}9l z#ATA)WfuPEi3-&@7MAA%^_#3)Haa}Vn5q52{z>uGmgH47-s!ZdTcB>45BV(L&8f>+ z0N!qo^p!r88&f>*vaVUQx>+lIoJ9qs+q6G#^$N;CMLb9Ao7#6+hBEPZ72t4boXG-l zJgj%4SCenJ_U2^Kpg=6F_Z2!__8i@|!YivA8ePRklT=yJNWgLv(bJ;Rru$*~^_?9< z4lfr(B|QwSJ=R_i+?9SHH~VWg=nmQ_lsfY@xNB7jmWra;5=t zrW^8`$W^z=f@G~Flm>fz`IFIAx0k&9kedy(TQ%qwtcS3J4id4jLlSQC0lZ9=Swf1T z-e|XkmZcAJ^p`xm6>;^JP4lSjwtTl0A)TqbvBV<+d^n#r98bdLqI4kNZ)PIDw24VT zuta@HHLV)x&#MsPC`SIAk3%oXex}~9y13wduGP!Ae)Y@Ih%kr!ax)Lps;?=5_kODc zt!c#a17?iXGQ~Dyh3?5u;XamdN94^M)OJs^$cG=yuRQylF`s@n%-7VRQx_$tNVW!k zI`*O`nml{=`bOVTMPaR5ph$URUD!D>%_$&8-CEaG-q+Er2att2)LKwVK_qil^)9Mp z^@J^i@(eMBZkUkXG*3_L)UZ0lpW@TJ9RAFVYi`wB=T0Oy2UR{DzeqIv4Ha*VA`%7$ z2^T5;rPUFA$b`&q;oSX^^kVj!?$K*4FzjVfi7Z7Jib67YE*4yEk?;#>Gb`NHH~A{& zz+D;IDhI^8(Z(xxyw;4cz`R6neYc(x>D^Wu-TwNr2<)0cscAt-+735NqhQY=`Jp(H zbuIjF$qH($-sQ3E;=s9wxWOz(MWIg4Be3BkPh0c>*X0Lq^3E#1bE}u=$dJxn7NTp$ z;G8gR?9=H7x!4bUBjH5GL60N7Ybo9jODmf(paCX;NKF~%K3C6Q*I9YW zR{`%WxFVhYQ~=M*FP~lS6#F2qRirM(P{Xakwxak*{uQgwau-zE==hPqF4fbb^U{V~izY*n@mUQ}b!Dj`|5dEXiIho4Aj^KZBd^|(cEXQbXm#7U$yJN&V zLU2Nw#mH|{?R1Jcb;3k<`B{(gAUEdpvO?gm_)Sjsd5R~PRnT7S2{KxX;?BAQ2%a@XgcY}AeiAC7!Y!= z4=wp6wwY0V1g{z*pK_Qu4tCAuZd>qF)?v(!@HfOCa zSb+=?=68nnxB+uVD9L(@tI7|Gp7A_9!#}>*7|+c4hgyMP9ELGe9g*a(s zJ_k<^2#5>4h4PyFoy3r%_P!B%Jt8ppQ*a_VMAcdtPy-U5LTxlH`B8&Cpu9DU_D#+WO%B4qk97rq5+Fai?+B`w6wz-m+|49dzX00RyIQ#lS^{#eR0WRKJaq* zylKyHbVObqf+L=!7^(rY0qDS^3#S$Q#VuUrO*2zw&q@Lml=fxoXSX}RqsJMhHWm$C zhH#{;d;l|sk_qN#2bPCk{oK(x>zgmEKV|nkO z%>na}X|Wl6c6$JB)5+1f{S4M=3cGqLMZji3=n7vlZh1kdrfDO7t%B%j{5prPWY5joNs4mGuEs>%<|DBM9e!!ZLq6X}42Hmhpz zBrdrOY$}(cMSt1vMF=o0no5X2*&+C>3>lWekjdzwG-ke+9}1}&!+BX5G&qdyA;f~r zUc+|-E4DET`;c!gzA|-%J&WpJ^FfvsTwFR4TubaO+6bUlwf-Os8d>}l#VSME?N74= zjURiD|I+))AqZ-{k0)F9T00tfdx{`LYz~{4Sb3zOAAvQn25|Os@9v>IT7Jwr_eP0sLqfvYgc~pvd zVPCozAUH*5za@U^ygIpM)q$sY{jvljh=6NXrJT5;)~1-mZ823Ay?-kGL{mnrqW@W? zqwD=mQw_i4Wc&yu|`%7-!CMKX!8x= z1e(_%mq=R??ke9ztSPfd5@cEh%}2k3y$sUlVu(4Upf`SzTn`GU@<`uAKs7ovpC)%qQsSg2or0=S8~lNbs5%yaIN8`+TWWsEs^4vDABYvvQZhm|=Ykp?AOJ$E z^!W7^rNukNXhpsTfh`uSGCCF>!r&*UFt~L zokx9kuVz%~E}~5Fm|LpNsO7AG6&l#_Q%~vmq<`(WfpEp~*NroBdQht^E2^BI19Pn= zfuvi*f9n+Jn+jlJg)kNF9*0Z81(y)+jsw^kLlMA(6Ni1$J#<9;S`4oEgRTIkGR9XV zudwYqb7V3_KJ08~(695cIVP}dLfJM%=x4j&8&CiId%!^YK2_dbTtEJoaPB;hkC%;R z=(cG=u5|>31Es?L%uq3`mY~OtZky9J6??;v0Wlfr%L?3*fm_A}=K<a(t+|R8xCP{3{v1>>Bg&P!;M#8QZTF`;C-{qLEplFoI`Ly5i48DrBh4yJX>b=xppFD75THoaRZO+=<7ZeBBlng49kbCPLHpc1 zKbIRmlgdn2Vi@1^2ZVZ56E9rjgkUo=WW9THMco|L&xOn-7f#9V*BcGs%pX=tVZoo0 zWiS*U_R+~Pra9lMKye+O4~$Q@6L<$XW)GeB4|`|xL{;innzilnv>q<8^B?hjgPv%-HzR;F`IqBrDsOPU}|9f3~s_%WOKRcNN zC6AuWX?D?MTJwKyz8sTl-IS7ZKN7A{Y*vfZ1e23bOI}%*Qt+`Qr7toc(9nmz9KSog zQ!=5oWZ3>ep09GULh4ns3|M}IGjxS+oc%sasov+0kh&JeqU)B2RQQ7hDO4v(#pDht z;c}E>)O9bt$-{Ki?ysu&QVV0tR;N7%S3CibUqc2*=*Ov`spBKdzKir-B?NESMAPq1 zDs}hiGDXgsLT4ypg=Iv(P@LGa-;$pY(@x6JK6Prto25@U(&gkm8n}`$H^b){*NikV zoi;4Aq*zBu+m=^MuAvms478^2=s=ofO~B2uVO`7=YD@iM$%&;k^fM}6JUjneQGOhi zg|ReVSp4As6vU*THWCfeLazp}_YfYy^vu~zhxW4CW>Z^!YX05wi7-mA?&-LoN!rY0 ziNzHSwN+4kx_%2NTh~s|kE+K|{)*SRHUSU6dD;nBc-v_y?R)-WJvR948&<7PRD)+3 zO*0x{CI!LdPr4fC$SFrbG(F#9s4^kkRzt8hS1PZM<57Xd@>&d`RgU-c90^BEOD5>> zDLfGk%#2m!zq+@Ccy}CHH!WKz7)bA7KnVMEF#(d$gZtQI0?lSz0#XXyYX_fJ;tO=Ye-JGn(0|YM-sDv| zlGFPYQebh9VDtnB;;-R1uOvT2f2ZURxo$?oXR9-}36|0J34unvyYT`tn#@E1Z06*L>M`4j#X|4hiF-nE zW3Jsb0`T_hiVvRczaR=9-gMY_B8Mzbo2L-znoh*NU3j1#VXX=gFQRzSZX6H})`BM8 zXX8d?;~GS!RqF0LIzKaLO^B+nDlLpFvty`4$*2I879^F~S^flB75+$BRVJ>Ov`QAi zq0HqZYS1CF9dZ80h!qH?yCL%L;qsYVYsJg>d|Q>o^`gx5Cc5oDQM50e!IjmIoX<-( zZ%AOS(gWF?O{PhH5J;pRY!M@m7Ew|w9?BHngqdTT7Hy(E_RN4dAK;Ec71}Z?k|06} zX+{TkNdi4zG6%P%T|!f5`0<`#O0VA1YJ*|o{7nJ+uM$H-oX*XKJH!R&17=e~)kpd! z0jAL*G{ptS;11#c2+g2w0)3}!b8feBgt{)Jz6ht$I=J#{pX2fU$hT65_74w%9c1tL zVIr*_79Mh1V{^$NHMlU6;w6}hH3};>^ZbspQg(0xkj)VHt2Vsiukr$VKu;!?PU`=< z(f;V6&V1Xtiob&Y_mN5@dUchLLqw0~;I2PIkvSA#lh)@p^1SODU{Qvo_{a{i>?Q3_ zlnC>7A>s%+KdvaNcwm?LG99|UH~dqE?P?T1is_WiQ1GRubezafT(?CO zSmk-`93uln`8!Iu;o*9oJvlQkC_wm=iB>jH=07q=z?NMOuGKV-K!1*rFI=Ak&Wqul ze#t|W9onoAK%Exjt!d1t@VM;PJU>)wm84v(`Yo-p6V`CR)pFFYS#_cMN46nEQ6g~A zzsgANwNwuc^%Qnn6l>^*3@isYCp*=BH$^p2UX?mJcBnl1Fe_p1qxqEcxYVY$VEu8* zM}z-eGUQP$`{^wIv1|4Ak&$Q0XXUSq^RG%pEs^;O8h0b{A;bl{n}Pb|P?3?osc1~L za4F#6*U^81tPuOjG#J%KyT=Ml5|>)+>zBcoRm>e3+ISmplHGNap0eubZma2T>;GJ#huK_K0lHdy9nh@#UMTc@ z>vaOW)EAL}-b!^-8*(7jYa%W%@2BWze+UD!>e93yJ#aZhBf3r;wrVXS{H5JkWx;R! zn6&KZ5aQz9!*DnN@H$GU@l3RA4U%qqyo&??)4x;T!L#s5J-Phk#a(CbzdumLYPbfw zE;lqJW#)LI?inF{Kt?|>B5yV7_S+L@5jY|LjboS1VGLR53pqBa@6Ew>j%k-26Ki~3 z2RVmyY6gMAU$aWY?~|ot{6d`%E!hT(Fhhg~87dAZ8r~yK|FV&pwx+>pH}IWc|K_*l zL3i#ChzL~_I!#&?lcXWtw7I%60`+<&{Wx!BKYEqhH+~1jpO&J&`&{9w7!YXE`EceG zq}hpqU=tAFNqto1G=sxv6lC3?`Ud(=Z%%y)KZS|zB7V+imRp0AG`^j4j12p9&a5yt zmcLB-R%vy?C_ohDWr@kpb!I9@h@VD=5{=wT;a(|FmP^pxs;FZ6twYK5PT|gRt{SXZ>L|QaV?Qw*wS|%ZGNs3?gckT2I=Dyn%#{Qi6XL}B>T;;bQBe8 z6#E0N;U7CB060Sw74Cmxzerr71AcO&#LrY`yo1vI#HRX%K0!>P1G2fJe}RsZY@XUc zvormR@PxZl|A4)Vb)^5Q8lxwM8hoFWpD-&F!h{x@JOXAKvCn3XCz>r!D06;OvI6!7 zp?`oX9Ns6J9?|1{9-ZF>R)|^fB&*cE=IaolSRYweafLC_d`BkrSAIZ*-qHJ-bK1Jl zmQeBpxG=$@@tK%C_^|t$;|slOf&rvxVYd3aGf@3_hlV!I;4Z>?glOwqdYcSm6_EHf zNvWt|XeZ>wXM6B?Oh{^O9!!#r3NGr0dUO9IHZ5NVU?n`f%mK>UKDisllT|4b9{d`X$;pi2}yoi@(R&6{iA&oI}a@fEP2`8i@Ux6{mYu} zE({q=(KbsFGs&UNsymg>pM=-9t%GR?2q}G_3HY$==E)!|QT)C32*Gc$psWN3F$+l4 zEjXbF_DGi1HURRrLe>8$$0is8c9Q~CZ=-GnxZ~_3KQOYw^yEhzUQ4`yMV z=WCz9^u!EEmp;^D9V*$x@>CwpLibb#T3c3@e}5)NgWnA=di0gmZbn5XB#nhUYt(}#Vjx|HN%RGJm#q)s zLPRf{K@ohT8#tO7d{)z+(eo4Q;;c3g=_Z50fL=P8vm(Kf2nb7xV}Ojnk-;P*L4!et z4MHQD*dpO#7R=i|&-sC=?)c!Mq_1E{je5?}-=rro?XIXlGX$0^;aT&BK=Sm?=1Uc8 zIBnyt#58mBA;eGYW(oeAGjTxJ^kfwbhQ*Tz6JSp6&WMPVFqcU*Dh$qC+K6YN?`rcHI<>zS79;8}O!>xCp-3MbUKudka#x6Hq+;cp_{05rRw z06TIh0$lK+Dwy0A&m1Z<8#yR(VZ^=kcm7)~+-DYud;0s^6^d z8Oc=~DY>SL^p>VU#i>p)X&Tg)rhCPyiT^=%n;525b0h>w^sG!U`%)iTBgLF#k(%GY z!kjenMP2<~qje+EYd4^9EhexcD=^$gA~B1l*e z2~Et33D{-ZZ3=R1x^@g!m;Iir`Z3t7V*0KAMkzx)a)C0Z}f>eZZ5L`#0yHE37_Qa+1lVRSvDimOw~lP$E|^rm3uaq z3XWCg-<&(oMVgn9I=sm%#Y6&A=9=kkB-u(o zH*RBH4d}!U1XO^?M#3FUUYpOdz=^enSjIm_F^FUH8V00EAX8TtZ9sTf!u>9}@6JpE zg;0JgNSIHUK+U5qE1moCu|wa@6D(iTMo&w?Uu($E|5QT$RfrYr&=6bba0R!m9j`0y zos`5FSe&-IZPhW9*Iy^9%<@qN#(tf% z_^OfYv36{OCBHA8@0=HLR~fh4K5ZNbcRC|Hj`p0gLN!f!*geaDLals_G>U<5f*I#0`N;{e# zbZk@(Q@vGSY}Ju*)wbS3JDHiQfdP!fA;H_8kO@-9s@ySNuTxxouruMFT5r2NC)a1z z@iAaX1uFfGwQH73s1iUGnPyUXp-AJY?KdkLewi&gvl*%wHHFa?KuF>kSIZ5oy90!n zbHvrl`8? zYgaYXHR!A3pD$4CKMIN64Yt2K;32oUcLfO)=vQ8N3envTGEsAFVf4;rkl^*rK_T^} zflg*G|1f)bk2V>^;bu7}yo&wdE}=+3NVy4Ze?eHFuMWnOk|waw!d%S-5baWcV*B0X z;%n~}f2?;|)1#XDvdh%vI|Aafw>r+x&-}qb+cNK*K|w8WW*~aAB*h3t|mITV*NIob6`8PuSPYUGLkO=q%aml3N0DW3Gv+UZe zEh!mI@@xuiR3)M#r-;_vheQC`DDDV*-@TxfQJ`bCQZWGdLbOx6e17BwH)8=%hT;vglPu!)cGv9K>DNB@Yv1g$qwxJOemqQucHJq^Vq6X|glJ5N|JYsmUYN$y5T zKpG^F$e!=>Dky!*P<9s><(<(;^gf=g7*}@frgWpE`rlHBR z{;7Q%X*M)eJzfS7X6{e;><8Lc_~`>-4Y$cSJN=@8OQ)rqvp9Q;mVkAGXlf zWZ0Yniy%PoNmc1keWZr#Cp0sfl-W{m7TEk&F#)%V(ynrcn4AH2|3QPJ^XV!5KdP0@ zF;a_iVtvE!c$=`;+XuF^$R*p|8@BX3)Ysbswlu^g`{|XiI1`lqNLbwI!{;b-Fc&?* zt}UtebS2^%9F!PqBiEWnM9Oz6m|o?;PPv|7n$DBIb1re%SAQddo<0U}*c*o^%V4M; zb;D3c$PZaag;J$g&|ip$R;6dCwrqi?`-eO)?w4ae+`$Uq7e;z&9?Fiv4B)p%dXoGP zvWHt7$E+_7;gjTj#C==Mb$!9v{1= zh~W-UvmUz?Dz)xGVK&ljplFv!}X*lUK38`@Rfxxl}$5DMZNsXGXY?});uHw zSr?4Q7F;EAK=zxuz^a8#ga`I z9-Mk^g)#D`L9H^$@`b$Oxj=CR^=Ln5pqRo9vk0abF?D!u45pZY26Lb*%4rm)SdX)X z{^j3cgggA#Gx?`~cO81tY*VQD$ba4_OL4)^fBF+WkYs4alU%{@dmlVFZe|+^i144i zFg!`#4t={ZhtITnt<76K9}|{-TFyChwokmekQZ^2or)#ekC=M<9c#)nK~{BT-YIdH zsGhKzWb`1h059k$nK(t1aa*b+K|-lo#?po`$`W!{PGcxGefFz-?O#4DR%1Qqzide@ z2E=GI92G5TcKJVKiHL{l2P4t{)+&_GrS?j}Mo>3c_6VdcNpn)ISd_P`BJNxzKpCQZ zeBm1pxYTobn#T8NCiKFhrn+RG&vQ#~94Ctx&kIdnu349rV1p1vlf1udYs5wD+Aj{< z_FN5Dl8ysvUoAcdk98<$l}e#Y@+p-~7Mx0J?B|0X;f`#5TMK7x4BkJaqk5jg84ZNH zxZu+%SG%UB1^Q$K&- z;IHHpZsqOaZ{?3b9kCNs}bw-A7qU(l?M0I=B=lxv%lNoj`dYZG(v0~V?}=d z7dQ&`dcs`^;okG}{&;s}W}MZD@qF`RIYgs2W{(M>LK-E`Im+uM4@TxU#?v$RGg>-< z94JqQ*AoZ)lp@KxLIx(|*E@{gBo&z?VhXNuNm-=ya3+*Gitl+!(68(E*h*WutIgVvO?8pcfk@#uOj7cVe}v3uV2;N zt}zr$*TKN6haTtfu$&W$3eBj#bQ~nyh}~962kJNCLm>S%E* z!0OT?+OyA^(6&|V-Io#lq-U=A)R2Mp<)0v%GCH4WhoxKT@|(Eozc5jy#^q1gxSjYr z6vP9a4>pa9%P-5xRaZ zRthwGZXktnR)k>+r~J?JknaNyjr&R^UnpK*J2;m{FGyXe6q4gyW2QQP6{WY=d|Smn2*vQg>hy^c~zw>u>Byhu&J4V1+&+M9TdMy(P{NHBeC{xFXX^>p>_+ zx)6oSC`GcMS6cj*B(c1f)`R!YQ%#^H$28yqbAL;|gKToj&97Mfnj;uBUCOKt0CRUr zQLl*cSF?j*{AY~m*QNe_0|rc2t#qLx--K}FwQ7ZxK&{4?q+=|fcwT!1^P0KaLpLIsq}RB0QKP%m-M<+(k5sdWYs(>l_`AK zwlpln-$r%Al9^GTaJa*YB-^uJPwd4`?DbGbG*d=2Q~UdUAjg#{#Fgo`XHULoZ@Opi ztIqWr$Sfz;KBG&8`WMzvLKqCTI7@f3Bw+@Q_80szK~!~$YYph6EM*Y0Qr1S+7dNN* za-p{MunD(H3KFr5HD-|AvIeWIoYZVGWhZ7FTd&zGqNw@^72qJtQGk>`PR%5r6GH7UEh}@% zanw{Vc=5-g(L*q|obWWLSkw^`IMcS=|Kp}`$g`nD4)^8rmTM`yFtkx2do`aeT*C(D zOuSp|J57gw&>|uyK8iCBRpc`36y}A0vbY3(F=G{FPWcsS_W{*;MDQYvcLAH!%e%UiyG=AGT_Vk=f+&O+>9d&Vw zAZ}l#M(DXA(;kY4C%2f#^a4>u|E_9Wq_NKj-7{O-+< zdTKkXyQDo7c7xY-L>*GitEYd^lMcn76mg{?gPuT9|MGS)<>;WDj&S zWgl)?5ov17w^<=v(vsN~9H+LFg`cZMHgfE_B09%4FWK|p%CQe$w>|6S*N`ve+!WDQ zvr4;Tnl+~~4{wu^TQ5CpaRoD0sU9C-B5^~eCMB>UFfSce0nuK&4zZl)*@J7d&0ctJ z3OnZ>tALol7g^8a2HpZzB$zQCSpbRYagF&&uO{w} z+fLdk6QxyC;jhHSoa}G)vxjRp^UJ4;tsA@W5EFg>(T&voX2+cwz ze5g}GBNDv>7;CF+?~-*YYM+naM0vUtx`DKm5Oz(v@^vb6)#P`ZQ{>Y4-Ypy)O1!5~ z=#MWGw(L)lDA>mCX_y|fJMl&lD(VP0LVG_Df@_9cb0ER;_*INcU|T<5Ox$k?_#>NO zNfx!F3ig@BGZ}r81aLX?GP-EiaI$g68=Lf1woG0Ns26QmU-xO4$z*#6^2w~PY)W6$ zwrdjhcb$irg|+k)*n7+q%;ewsdbZ@_#sKi5YmAj?0~HCvIz2**Vz=+twTv{t|&4~f8p6fVWJ?%O0QWfeA7ijsu3IgH$f#EOebWZy=P7rwr6nM zTH(5gs1ifLWLACChwWJ#-%y)taQbwkntlsgT;|%J~Hf!U#wMDl*HLv)r(#5nDI`}nolR-sW zSnAkqu2S@E&nYlyO7-A4(+N6D3CKIq==Sq!Y{hn}I?fj21$fAa@pKsNJu$hjE@^++ z1s;VUNSbk?96ZXy@OX3SdTp>yx=zkOJ~WcO&5AHI42;NzS_AM{xr@Of;G zeQExjf`Ay@8nNWzoq=~;o641D^m#+Ei-UtxrpQUXur=iP!3*K*#UTT+-`kt;;X}IR zFtzfmEbo*pHZmh;=Qdc~+XW)KT-do8;AMP}VPJ2JbR`Pf5!{Ia;g`Q1(jmSJ?!~7@ z+P3|SaWXT|!Alrgv=^oYWM_N#>1W<^z;<~)=t$iQi_5D+C?{Dnux@I7(k9pz;n_-; z|FTc!tr?vE70P1C8U(09m{*cU*2ExBn?``7`+U*(q(N#2^)HGWs9N2)qJw^V)qiZc zEhE|I$^pK@D@dr{v{frC@DxlU zNQEqbze&!2lMZ8o|8grod59=r{9Nm^->tA?LRNJLy+(=S$!Vk{!N&zroq&OuCe1Iv$A({+KQR3QnyUX8$O6f#R!V zv{+fGJhTGR__VG_*-Vhw~CqsvP7Dbv4+rJtuf5{Ur>>t^WidAD)nCOXc7 zaaZ!(gP9oKhmTL4;NPXTipWBN$#}k66V+^%|2|cIEZI8*N$piYF0A_JcP;2YZkKUi zW+b2mbtphsHyt6i)!QDhjX5DKII&VJw2>X?XL7zxD`J6Cq(^dpd+`;+OQv0mV(*ty z1ni3@7$)LXYI3$C;2RefMbThJM+ueWl}wj>6Bi%sD6>oEm$mBEI25HZDsZZZek=K| z8VOpZRByFd5b6OvT?v{3MN6YfCsgl6-*2gv>h>jX?VspsUPAPRB4*aJca$e6`lt`X z*4N`DSGOa@)9AL~haRCkyrP_`WYDj#VR(T_T$9(3a!uO-6Ke+otKPkO)ni+?Vg9Gv zCX#i^>fjAtS0LvYGk=bBzfnfNuQoz4et$-=5RW0)qk7_eohWph{DP9II|Xr#8pof= zKKn=B=CDHn2dTPVmufWAbHDB{JNDbMtU8YewB{!crnnll(Sr6>@qbRCjZBp;?%K;j zFTB9QAfp&Y`4=3#2m0`$$!a3FfsFlT4mgedO>V7nj{Ds@(ERDO()=t+?q~e~nvRK9 zahcFMpg@~arMo0<{LS}4P{9r9*85+Fl{Ij_Rlcc< z&nutzOnx4UE(i|Y+ov4=D>6q8F^3CgDJa+h$oV{t@~^U%ijZsb%2_C-b&A77)c;M6 zc;%TZyXenzWoOYR?!PJ)+ zzLYvNH`~nppl`K8TS@6_yhR?-sUIT~p24Ygb=NPXZ)h9cU3SfRJ7ZnBrOqUHB)=5J z>|7Ery7zJ;IPP&8pN&dPW-et4dA|jGKgnPnJ#>gb-2aws#mH6ocDH086ChrVI&|q; zF+!UHHcqugWx!##kPP-8uu!ULA*#+-Qr$%P=?(=V=B6w(?{N>er$4v!DUs|gyYM#G zw#in21+%8ky!F1HTM%Q=eB3sbyuP*&0j7NYyYy9??S#1z=GcV@W=kjc<~p<`xo3`3&RNp z7Q+MfFT47v>;w84;s@q^uZeV)sp}B@(iEy%3cyTKUng)?@+frg)R3ADO*BZnZk{1} ziCiw#J0dlkF?rXPGKt-)Q~2^0C}j8^;LmeCZJ@_uu>qJCpdC8ag1JG<$9$Dk+LhKpxf}8E%P}dFORfCT4PO3GL#v! z?AS64z1lOKmgrQot){y6V9!3+y3IK8baE?ihnq%mx~3>HP)4~Ji!0;9_R(WA+4OKr z^`{M2y7H|dI`8^CLwC=uO9t};7+jxtcPaCVgG}9ibKzWRbz6>ZN5;x08|yF27}!#n z#!>PW^mEU`=ig##{)B;ajEe=3{VPe!2v-)tl&34^{|Onvg64MVugT-lUGWqeDGb{95Q*IyM zwkEp=ISZ=q?M#||(eW`!nK#%*^u(@``F%Q z8D8TCf!cy<;OE0HkfTMWWWXhtLt-#;ci&7y`;!7ulCGl9t!jK|2|Z83XR8_jQxI67 zs+!irLY2N_QBI{dzEVg$^lt_g5c$R|7G?@h!r?yHzfJ-ola6@P`u}0|x1EOeJ)zeC zXR^TB49J)H>gu4T)mezl@eQzGn;yApy86AL|8EXSUxddP+CqP}x1RAfvJtijGxq$!+_UoBGBE_-}t3PQgu^nM+~G zz#E~-{WRjp*4iV34B`7{{)ZzU zb6YVep6bbk&Vd;N9rpF2^?TdrFhZy2YKAl5^Jx_x^-{*~`po5^?oZxiV}LYkk;-_f z_r3aZ14qDrY~I*vLMTK{FsF216&EYWKDSW6C|u_Z4IX-}B3i#~*f6k>A`0-y5B;1$ z!lN`(L@Q{mdIl|1ZkUDMSFZLwFmY8!Wp;zE=`+rhvA)SuAKT93c1!MrIYN(Wj!AQw zCG?7>ay3-xo#r8kS#ZH^MW6glt=N4@NiFmf?&UvX8~?TfgeZR~bU#_B6S!a#{{Ekg zSr+2YeJxXNwrnZLISNY=&>}6wzy1GGJ$;EwCsFq6awxG53&2D8p`@b)109N~!mKPD z=5w5&{WgftNNtWx^iks*ogbL#=4@tHL_g{6F^UUI^D}I>AN98^BrPY>gE~?qEh{%f zVzcz|U&4wubdEHaE5mosk3+e~+3cE3<4*svPK1Wg?4JSl^A}J)qMQxnDb!CO;xG5$ zzt9l$t>}OMs=!%e!@PRn%EG@DI`dHApzx9dX4@8;m*e>{Gpnff{CoJeb~M%croEYCjLQYW{bLhslY6K zCW5blC=(WpU0)1wU{G>N!-G6<+Tj6ca;6YQc%5mAc*zZ&zE^Lf!%>cSrXd}*k;5-f zlm2~y5M+UH;K4!IWRhWh+wDvD#+RT zwIKvE#2AvBXAjX8a-q^yG`c5wHTTT>wuAzyUKkG86Bo`_57_7^Qc}O2fBGAVQkC{LK=QA@PK624at-S~ElM5JaR-U(ehQv&{6bBg7b??iKB6HCWa?vd&z zVj&DpO+vcUCwtoVz$v+fp9)$d3iVL23-^v~$c%WsiNiS~@--N8fU7#}fq3!#5k5GT zV2&qXlMcF7A}|e80)YqxY#3u3i>BTc0t}^v(Eqo6!tRmKqwv>*0Y50+lc#weVnwM` zJk$ZyzI?1HxyPnj-R{u$`2d-lvnDl55*4X)a4NF_6 zD&44I4iYJHJ=M`QG*?SI_f@g)t0^?N?kC%@RKkVD_7af<^}}}N$LEeAgogFlYDn53 z6K6c_cBa=wFm1N@<_fLbFuK#DsQtCD;UuE#rbfw zs(Ms}rgfZH#)SH=&;$$x#b#M|-41*+kZ;4}L4VzwIyatLAQKZF7<_8w_>oeDdO6fg zV;AWVy_r6=%NhOIE7k~uIFNF+{70agse9R<;rl$xlG<&WB}dG?x00NTy8Uxw@-YPr z7Yq|64)ifal@It4l1d^zf}hrMSHB}aM3BB5d%TR0yyZ%{5HrYF`m)hWtG>+@p}CF)%}gVn3V$etJa8T=ANZg= z`mS+0HU;^|vfi5&M?>#0wzYZs&vjv`Kd$O>`#QL-cYxzocRQaRBaQ_@Y8}vE`?to< z2&V*74{mQP^1xfQwh0VZCUR0GhX>1XK)&5LQ}e zW2%F3M?Y?_-Lri#gzFuKFcPp+1x+XWmnee?XZ`w&sna@J%JE5Y%Pk9TSNiBz@MRV; zo&@aP=Ej5)au$^SEea=O1JjFRALAT6hvByO|8qD0XT4^&|5tj=PWI*|jwZ}(|L3aB?Egq9!~OrN+RXm1 zn#2734B~dS&YzEfh(Y{$EMg104e?E)I=lY?d! z->RtIunTTlHGR1SXPvRd;={FfoUQ_@CJt;W#+~3@Bz0Oz*EiKRmzp zmCq|XghsCj^Vc^^Ztr{(YVWTXe)T8sX}7Pv&uzZXH%)#Y8y}AcgfJh^5%=zz;@_7{T6b$+!#MEG#Pb#3oC_-60Mlo@-%H9UF1Ak03; zUp31!(7Qj#*qqPn_aWxXv-~Jj-lcFMA?@qWhMJJikD~rT-LuCk+$DeE&Y9=h`#75| zu%aLI0w8RVd*Z}D1?*Jlke>@|H0?Y_w!6N|0*BsvmGtZ*{dnt7Xy9d0Loxb>YX#b3aK0So|F7Xk`dk^k<3xEj;cv}VWO71G2 zsstLnw3BTEeSc;25Z1#EddND>-*=_#J=yu4-amrA1K+P=-)mTE^DmH+JLuS0Bw}VI zs3k7fSRDEN7HmXweH!B?@t&S?9&F_4_?0ta61`${kl3NcvpWJgT>2}Y|80N6Wuz=F2?boHjQ!tKLpTZ#1B2&)8lepW172a;m`1HQ;! zm)WrBF6uUAo=8>*Rfo|vQJ&psu zq4)085A&2P&13?;*3CN(8BXNSlN)Peus*$OWO z@FV!vEN-wfyQ$*0VV}sn${k=_=WEu}Lr3&#!69WIPVE!RHJ<+q4?Ebo&pW|NCb7ng zuPl4nlveIrb>xZFGn#8pq)73!Hw5?Jf!l8v8`etR)pt>dk;p}&*<{E#A{2r6Og|~9 zjgfVG8MigHtZ05oRAOTypt4T@Ie!$pEXkLNO2Y)=lak1)Wj3+|ex`Y|F3}1EW25yz zD3VLdXjPdgYOpb$evac3hny?L%2jxe0jz7$Rh-DBuV9fmqzf z_4CAzu3GqI$ANM+e9o9Ywi!xXC>e_EUuBIh$w|4snSeSf5U$^7PX9lMMD(D^!WHey^w9y#1#T0l9Ul$HyUISXcC0f=X%eQ(O>pmm}#1Y~dFiL2T3Ivo3=_|4{c}KzIGC8=w34%YnliJj$i^^U0knagd4^CV21YRW zj0tYTY!Iz6>JtQMYJtC|M*43Yd~yK1$f1oSzC0~Ls|0lQw`_ZvfT8Uv-{G*A(C7-^bKb_^H(}eVan`-jJd!Qzo zHr5L7m@n>ysM`luGYuFTf|Jj#rG9#_x}TZXFW(Px1;#dx*S#cg!n+)v4PG%_7qf?w z9#hWJfV@DARF7_Vv&%KJnd{%m&y3-6{L77W0IN{awwLkH5pMUBCIZcout@@_2xr@| zNa*B*yl#l5JyW3BJ1GyV%~%giR79dbZmuYT?8O_vLfTsyp;b)h5*8r%91YD79MaX} zn(<;U{c$yq%baoEHt~p~!795jB+0%O5T*c{_uM;sa~S~NAXjmmITfL~oY5^;QRI3{ zV_Xp4MXRNxj_?;oi9UMXlX`_e$cIe_7p>8PZL6hp2W}h-Omv5UQ71+Mo0rVv=X7Lv zsz8+-YXQJdn`MTWdXuIW@X#MFg1u(DCDP;DaRIs!6HzI4e zm`DotGp$X>{-i+j7aS~q)g|hNeMZ#bX0Pt=;C~ni{RV%C`80G5eS}H&;?L;EipT0% z**C4&jb@D$p1gV2zPa=5JI+`B3q_n$(&lu^C^8eD1soIsC6%Y4nKdM{D2$em%il&| ztutA=Jym0-OAzMpl3HMXT$;N-U{t9>)1w9kMK04ccjJf*lTNHZ=X1slkGS^&R4>${!FtYsAY=?Nelf67j~;MbL2ve%WPmO zE<+I_|1!;7_v*}abc5@vkZxPzS@wS3(eSV~*7Q);(vKlhkx_7t0lAN#9?)X0c&eKa z`Koq%R3ZS-Mo-`k23WyWFnlcRGd6KAw1n^kB{qysb2xl&HV4o|SrIyvg~VS*W-HJJ zVNK?HFc(_IN$0G-htth9WzpFs5NyGBHUOLjE(j)9CbsP1y+oy$HqR#*I~p&Nxa1zU zP-TW~>vNaBh{JMX4X2(&dKZMLm-=$`BC(htG3>>Rhv%4~jI3xHNXkmR{A(3M+ zo1_R5ZuICD&=G0?3=#&=Gx`c~@vRqBan%I3``hH%&HQMC6JG@^5{e7wTq8ejL>>Hs z&Hu&M@7N?4qp)ygGkbM=T-IHbYp=$Ddm4yOn(s?>!FzG1Q z;Dh1u(j9Xz^^1p)X0jo54SopH)x%HIAAW=ny)nfqIV;%;BgY;)#&bGYL1e6FDD4Tf z1H?2wHv920g-0!g%fl+L4Uvn>@!90~%n50?V?T_Iu|hg8yXF)+nA1xa&o6NuL8d$y z9y@Xp94(BP%gHF9uFROfAHde#F``F7MQcY~>V)$ykPV$0QlEAWolW&Rn0#yIpwO)k zpt>LJ&BRea_Jnwp04B47qNhgKtj)63M>!dngY47Hvua`kHBNhtY)+3^>m`slmqvic zo-tI8D}C1}!~Me}R@Y9>r;YAPmBYgi#a}kR^iH(N@;@@@M|*{{iWy;4+`;qb9bQ>ov57uPuF0y(zX!8=heUEQr+Z1}OX#;q&qGd+Sea;i zCJNTpsKcQSPZ4}`8?7Z)HC-NdIp7}zg^D4=YCVQKDGq4%WIet3pIlYf<02 zhOo8{T3EX$CymqKoD(xO7?f4SM_h5>Lde3LlYluC<1v`q(8yy2%izt4iV)Y;a;5@L z7xS>qgr8tu=~3vrLyRf*)#W5WDk5VUB}xmlz2+p4sKrD(DgS6YBwMj2IQ8AMrMY;l zZlja0Y@F9%bl=nKZKGsHSP27!=Yn^0$*B0Qw8uPBa7HMW7fHAYytlJ|J6c*Oki5Ev zVcYBLQ^VEYD$VBAgeUWN`*FREO&BY((qoMjO~si}+eNWszQm^5kOGMXDM3dqm8K~tDe9L~d$r7lGm!y&B27hyVGY?12R8#9*XMSp6aaX_O&U7pb33!cD zv=sxrtpU6S2;LhQJn-kTZF=@S#&g@+#0?myAr_bg@VhCsC38 zJG6yY24e}QL4l)H&yb>s0rvLSz%MG`cvsH&V0SyB@7HvdYAGwQw?wGZ_@&zb_04i^~)7Ke_Cj-#t~$uwS!LyIU0 zX9?jj*vw6J@T^_<&esOm&0tCDHt?_&XATA`*O(X?ItN)GFhw2!!6`lnRoIM`tGTI* zz-?=;EZV8oHTk|wvYW)oU2@kK^$T3Uq5%u2SeXR+37@>MHBK|f?LlmV0j>b96&a0H|BtGGg zHgOD6!2tkZ^Cw0uD9+5SyOk2V$4XF=psi=I%;y)O1lmlBk?K%|F&B+vD_sy{fIcA? zT^#7-;=G94pl)n44J3COG4#zhnE=Ko>4(i`F@p@bRWfr@$Dohl2<6)x_OKh$$&%?G z+K#3thU0g{EKK#&kTDI*Q@&+ovsDbJuoe#)(|erPh>x^$T*m%ES}rm;MM{0dX2}-SxI$BXjL~;|5E*O(q=jscAPc#BnYY7vL9dJW8X;qyC7vt^+u zK=8w{LTB7!wa|O*7ZNTPqKA3z2weHAkJpd#{v@Zq`UXpQZhI%{h9Aq{;ZF2t&0T{w z&yRAkfoVRTGmrj?{*9pIK8A^rFRwznxt4B(c0* z8X^jfGQ(Nsp%^c2+)dgCgJXzd45Xd&37}a2ZQl&xnqs--aUu#@JMmy!Jno%tE1xU^ z8)QMk95H}Yv5nY~b=sg;x+27e>J}By_`3UZn5R*4Z`M;3-(s2Nch!Y5gcI7FvS1AM zu~~tyEiyj7kk;K{JgJ+s$-uZ9(HfPM^p}R)37Qzy!?ZcaL|Og31(w= zN+$l@EFz)044v)b)UO6nSvqYOp5qkX{V=;Bd|6AHM-8TTCOApE7*cxVGvNp$lk_qs zQ~cKJnYY_pyweeAEDiSiDGVVerhP^cSTdWI21=87E00W}u8xnWZ%Q-uq*Xqd@uns( ztE-``3N=Mz`+^6X5Ga|O!hp6@ZQYtB2T6zB=vn){-|h51BmK8V5DZDK$OW?Qc&!<( zBzs@_Sbu=YaI#~2s4p^ciH3iZsHaPDN6^Cd+(No>{TT7GW)C#EOyF7-B3gp)p{NE2n<25u#`$Hj#OA++BM7riCqc?c#f%}7~k4* zVaxM4;qqTQ;P1$7LRG-XaaiWWk9kLm1R({i!9j6&Ofo>mq0DKhicjfiSG2G%!!9Z+ zn`G#$W+7V<(NRVX>L<<(=ZNTFKZ(>i@wvwhDy44wU0R+7rU59D0v60|P$}UBp~=1G zhg0HFe9Q-_h{sDqn{940Fv=5ooyMkLDC1viUmH0i(6j8o-y zxE5?L!BXU|ylHMm^o@ZG_yLeLRr2^kp^%1>0j}I^DC@S4!fu|zV$`F9YLZ;G4_ad? zJo%N@{2pKtjnimXN7H6wVG6W-D=J0`!Nc>W2gPH);>Tx=1=lUX*eB9Z!6t>JN7zHi z67~th1?=;F=1%ih%rad@qi7#$Bb74_qWl|MERCM#rFyUMzAljbmb}!J&cb;RZ~jejLi9%te4(*E76mo&W1cA*=P zMFf0o&WwUq11k(s=Kg+T>9Z<>6o8qJOI}L8?}N1-#c%M*?lPf&^ng0`ut!rye0?(> zAjY3YSUAxrG9_e78?JG^W*~Dp5-04r$&s&)RZ$>(jlqP$_PVt7N$C(mxRT1!k-Y{$ z2>dMpx)a0JS$$ zsh2u2PB=GPm~@0**^|M_QNi%rF4|Y{*qpktX}pP9DNJUkLz;LivpMgn;l!w7;3xzA zVB~o}S1FkikQ96=Wb*(nrK$@yWCCx+w%i!o(Y!Z!PrA4|4=WPvK1sbv1v?&b{U)T@ zi8;~&v@^}|)-#_3C>X#}c~$-b8fN%YcWEoXZz3iT;eGEi|AN~?*OE}lZz7sC7CP0< zR1Y>A-Y3wI-6U=bN1Eh);Uyt+Bs4TkFMy`#rl^8#dqQ#4m!GSk_9}2Aguf=^^3k1t zt2z0jZ+sy(qq*;Z<&luX;r%o?uH*5kHuI7{Z4|wq;Wda77en`_iXGh|+AMXCw(#6o{uj#=H5#8)t`;xjo6Y{1jD_&3>LFJQ z9#V~icep;-59)Fzrrr}kScxK!wAzo2p!6^WaVl{1!M<}>1(jHhvm9gk`h=k$s`!WT z8o*RV-bbnSx~K3q;&pD;l1-(&14Ii#A~9S!8WLlT@{$b#wIBw2$$PUw3?LfIbAV%E z+j~8@Sy$NA{s>EQyM8bq$>yxcq&33E6xPcR-ZUkFZVE=AF{JFAJ`=O{TQbJ;<6e^) z#3j`kGXJXMO9m4x8?SK!c7sUy@EqI%JIOQ2vvFuL#&-N4| z8@qS@28x;Pn=yIKFpS_aw>J{d#r+Jqv#X3+xfmN9B4!`7;1OL-G!DM%86G)UA4n6` zy$`RBRVUGu{x$GC1hc&@@x_a8N_;b=XE2PDiFmOu-$S#8z8%>r=k&$h_?BK12}Z%E z-^*tOJ5X$(4Vk~45WX?*LFK2dCiJ<98;xlXTivP5?stmHErx`)Hu=F^T~^s#Z!$0B zd z_v^Q=O*c0jt#-R%9m?t`mqm}v&q4rdR9bvY;vWQdB!qIJil~3Uy27u;CIy27UmTEf zUw!d97>}Ds0L7YkLPa@;nxzG4_gquF{LsXQ6;d=jp)L%6!p7#|)mSiX+d*!YUwq;N znX%WgFru z)NeO2C|&@5QEkb(m!W+}-3EmGU@yTwnGxL@u-|v?9tR?PnDL~ZdtVSs-V9(#&|Ygn zyoi~(U1H(f_r?|dn;O_sF1s)UqD8ln<{P6o-b@V7p}rganxehf%CM`6|9!fQg74=r z^*s+Hke6PfSb%<-kl{sN=bV`i^yMvSGM_gGL6o|cv=UlS>M7W<*9lT;BR#~lY-w`~ zIA%*=>=#+xVH3`(Z_OoNh_~Kvki>P4FiAB%I(A9e>Cq{{baX*od!036vpZr`o$oGI zm!iHQo>Gt|&?>(kuxDBsd&Q8$6<>InjK-%Qvm1?9u0l7cK^9f7w;V4Y|$jO@Xq?2)07tt4}y zxOf<)m5BGp%&?>az(A|MYB2y08_JO^f=Hs}v*=|0Q3>6hbC=xgTB#%E)oK$8sh4=u zgp+C%M0Z8m2or0haKkE)rxf!oKlQ4mV4STJ+Eno?QxA>XV^fBo-)xWgB?5Y>2cD)E z@cMVhEMjHqir?{%WCB*#E~pk#MY2vNVQdW`sV2MHg1^cbj|wiyvH$>$#%9ge^=B#m z$a7zFd<7;?!%=Tm2GWBA-Qal)#OM~3Hu*-+FxlSjQQi8S?Ym{ZT<5AO*?KVk$JWT$ zMiJvSyBTm75wZ}eucDQ?bqm{XFewh7wuM9V2#|sYM##{jp?eTx2GxZTy#5bAHer1x-R@PDwo7~CUh*kF*HMY5#f(A!oc^$8U{S33z$pxn1=7CD$kz(e% zzd?w-$D45aywYd z8T$S4Qy<<6d&83K<5Vw4mF%sKGLu=-Yuf5=!orBI_YD>-6DqtwYzWA4cZje!@BsA@ z=2AlMlCJC&wwJU^kT5W_kdjE-EPn7rZ_YE!KhrTR7bD?i@_K0~Vski+KX3&676DXGPMe!zbNj)YOiKfKd;K|kw)7rbjW&5M^hNXZ!VDOCMaPa z_dY4^Jmyz{!3E%6neWb<*s$rhWc6O$RSIQe? zJCItV>j1};a<6#J+Jl5x+FkyB?u#w0p$G$dsGVjG0xIlS0J^Lnj}{`la0flMJ~l_u zuK;j@xUdfY@><_3uC!fjp*AXRVIK&GEf$LPf;_u%N3*11_nOI=heeEFREX%5v!&Vh zSH2N-TQFVLVop@w6mQl2&?Nycg5M0w)Q+czPSwqJzLHW_gBFGGX7Sz>wYxY8-cU9N zhP3y)&CY^0gQqw)xXm*SKlf}(Poha}twQ9KPhTT0uh1CJ09&!6y+6BGXveS&_7)`F zszO?RA5BW?(snlSHhG3gRoN#fB6|eS$B;OFVSeY#?cAzQUCZoWbm{wZ*l}X~8pG2D zwlgvm%@UNIDdMn^+wW^JuiBY+g!e&ia>^t`shUi~x1dX|L5rZT*&Z3A^o~{ukZJQ}h zwl#3ztzdw=4qr2zvH)JOos~d_x29V1b!tfkexg;@S%SdyFai75sNngoJ_+ULom@k`!MPt=% zg3BKjIm8O+^8YSyb)h7sJE0iagl{uxt}mL+E8HE6SFNo$l`NYa`T=$9sPaCI+`cqc zK6Q@1q%huthsMQ|4<&KF-IO=RcDz_>D*krc#VoM2^=$mk?fPkLuok%~0x78n9<#-Q zXGeL6>TfrTL}l=8N6bYWqT{^t3Sp&;Wbw7vz#-kM9M&L3>;78QoXyv|g95}oKr@<2LSF(T#Ngqh zcSFN6^CytyJK>i1DAYxAdCpf2c0p*qux&{ENm_{99!2cugh4(-ksHp(oW7j8=MRM9 z@B58Rp<`(P)U0)6=ydePPt;@H?o+6DD!e?f(m0blbb|2_J_vU>J3dNx3AE+HMDkE}(wi8(srIO;sx{aR~Ef9Kna3U)0Kns6I z-+8;2pm{xR)7-$3O79u`KXXx<5?U3F)peV z9Xqa}Yes(KL|s18lX$67mi1kXl0YH^XU$7JX}C@{A>Y3 z+QhiTqF+ak9epDA&dFMuYRy-~>_pe0{w!XLNd+TCiRu(PwoZbf^^7J(;)D)L11r6f z?;!=+UR-s(t#H%Jqx|&RHR#|fYGpSONE}?F@u9?dq>2rHQEqY`J8swZb(y10xlPHL zzf=?2azW{3~2?jDc@U&AV2XDO*#Yg1ARH&BMxv_Z=@lA`rb>W!4!W_-qDKkx` zps<-&1^;E8cL5|z^Eyk&D3|)2CZ9D<&8ywBCDTIB=W><05$C#Gk1a^P(|OWs8qe|j z$j-GhQq@*QTZ{4wD*EDji^Eup%#6punroy&MySn@qEJP)ocMepT~kD5#D^(I&I#tF zO0jD5L0c{6Gytf$2`S>FfcBF~9~UQAYw!7LYk_4UsWUDO!d1+wQ7)aQhoNdrp|#HW zwIf?K@*zsm^p0-I{(iUZ+j{QvreEZiZ+DljW&g$$J%|PbG(6#X?&=?tV06JzAe1iI*z<2LXtjog>s4yb3bw~W} z&h_qN!Eb|7Yr9@rYT}e!)YL_b$LB~&L40zl^Skd5j?Mg=IF;h95U>ad{30lXYMV<3 zpuA3KPyu$=(!c`=8uwPb|4?7Nh;d&b~26+g5brZe_lh~cc?7Z!)hPPMd+1_4zjJHZ= zQUk08Pdh>xqY5`ho^$8KJ4+H=z;kuuIryfaLZSg1lNClndb^7Xhx>#f`!a<9IU>l< zl-7&sg^5#=AwW$GE=YK|) z9%TMs@T((7OZkFQ3mXI2j~AifX*lM^Ba{{KP9GRsQpdvN)@#bTi89& zDak7oH$ao+noK75*PQ#|)kAwGIuh~LB6563#O)HWtcpLie-+if!^e*kuzxCnFMcC= zZsK1~cRk9jl#>J>f1u2LYd}kKbXM3{V%&@OK)B{ylgFuG>2ch-$6@6uca+#^?EHr0 z#I5_F<~>F8E`F=7pRPlZTv~|QCITg#g4T^zxI@os@xk_?> z+`Ai=RgRqwo{4`xF;^s>89Gy+PipF|FcMq%yEkMwS8o7mp~u`S3CR2$O0a3{u?v%JM0+yV&fMKs_QVnPLBUr09Lc}5ZDcH)Xc;okB-%Pn z>|2ykbUHtTYf`n4eV`Wx^2WXxgO7+ESqR_9Av!Qc;Z6cz_ z1lvoxJ1)hk!E3oo@@wilPE~N);WImne5~)eyRMJFXXJTTh}jve40S0e7haQ^`Oamq zS#@I2hu?^1msHfa?XDsZhfHo_cZ6TH=!N;dATlS&Q28AACg8)k4;IO{fMrg;Wh9=n zZ*^LZ53PXhqmTnUl|K{v&T{cxH?Nd0-@&WqbK~ymw3rQH>;v9o9CVwPKPcBVRv_#X zq+M#9Ub6D;Jy5`>p7xD1mq&ar{T|XBZeGu0(ie?f(p|#uUBY|WOJ?B~nrpu`nZNAj)(%k)Gh2*?7V{-_09L)%L3?;R zn@hcEq{mLRxuKI>SRE(SouKPIY=91e*6F$+ZV%a++}j-FDh@%#Bf;fb^{sBzk>f{R z!AIa9BggB<01qAd>_sow+a*=wQa6Jpx4uV^O=5Lrjv(g>F$*_Ryl#ycGxk%?Po%6j z`i7J1fFxsJpP&l^nVAGWQXt5_C)~L>;US=BZj^7?t05;OUgX&3teX~$jp8}rM@e~` zfHXz@WLnEABTNBXSuA=lP5k7sNm-K^ZRED3N#+B3KY@=rE6Sz`lXtTdbG`1n(H<4 zDY!Z^N5ZdeZm8IT;dkjB=JSbpNQdIIDrklU`+gq*LTC1cuc(31m&UJT#04<(QkyK; z1*}*o^Qo7bsOrO+tgR^hYBKVIzdkuNkbj*Wl1R09+q*gC>y?8^8Ac1F8YoB?dQxqj z5av4tm%YABFI*d)+DxU@uwMzR_k`1M*`61a(l(|EbAP`r830W z=2N5>jQLG)K==g**HZALTw_(wO#I@#n5lt1MFi)QKd#w5(&I_;RJ)$)ifx{=bNxqI zSayi-j{AQhcxFY1XT02|=F$4_b>_%Nc?5GV!ELA4dWe6Xl*bW|`oeX)Ys-crZdwPF zbTwR3F*@yU9D~W<>US{ti(L)u4t*xql68u*$Mh=@okxBhp;y_(H=TNLRTDRMooBe5 z3ToK75A%aMJ>8DhhB?+h#-1FfDiyqVAH_bwTa81qeD9S7e`dN&B5!eV3(uJ_<=&FQWo5WbT5S&W*Q#)<%?uVq-iOh1USWr?NBQ0P~XxgMd}7kx&D-T z*NM8TTM(S{73Va!2JFqCJ%P9CS^^RUr-gGa!GPV>aqqabVbT@t#4JuoZ$tQf8?X8U zxkJe_aOvk^tnjw-I_E>Myk)Y+Eq)V_?RoX?p@ zP~zoTLQm~AwOsd#i}ASonc&`KewzFF;9l@6^QGioIPrAvEiHUGy^3%@c14_%X4mzdj@P}}r-(Iqj<_w;Z$uh*SeF#!cPF9P?onZtDQ0E4O+P~$H*)w>=i$BVbZ z)=#qw7*QT~S)g6u99RiZKi=tPCpisK)F{smk-yZ;>>SxT7otYF3Vt)$`=cWK3hx>j zhX{q2`0QX(KMa?OXp#NAi+iWu)G)7dbdkttOHR>PBlV%FD-P2+niSX6U+$ttJB9sc~KI3c~j%BYWAVhR)4 z0dIoqV?BRXOREdEJH*3zU~F2vU&BR(D0&; zMMSl4TlVmlfy7QP_%**tBcAGO+>cG0aJ}GVg1G=BL{6MY-Zkit8l#0)@Jx>P9woTI-zah)Y+*UXLdDZW{{{S| z);Iceq1^fF$j}jFcRoeBrD@5qPQ3re=oe(a_M;MaGO=o{@SZAtv;_V-kjL5dSFg6y zgpc-uU)=(-R_Z$wlPk8dx-ijWec@Ey3ue?BS0R0TBizekIht} zTLik;D-zX{Mw_mD?MyC*jM6r+p5~^en){H%Zrv6{uIM>gZ`$0TeF8KolV#iwzXAID zP_Veg#(cJ)DkSDE$-AC@XYS#&vt;+@s1d%hR)m7izw;G<@_7IP-%gJ~T zDqJfMnVva_gta5=g_DR*eA{=`#=LIg_uGxyxEngO-Z#ODzZBmJn%6TwbRztcC8Zo* zWPIs>6sD)9y-(=AG7H`#?;WBPnlRRD&)F>(fdZfYJ9Fcie=l_t=Ikey)_HU}ePWL< zs~m8cl8Q$WhB`Ke0&h}wK01PGoB0CFJ0L<>BQ5rMv6}Ur`A~o2=t6cBQK7dO7KtQp z@mu$O^yZU$ybng(Pip@{4M{d9wxoE#Wx6YNUfL(c6{}>AY$KBTh;L}jPrBQx#MVL+ zL&JJpg2)C+z&l_+&ahkHJ4aSSh5bz(&x+1Es_{{175yymEI86HH$;gaLo2k-f!EkX z`+ubFjf`Q0!Z@*&?54`}DV&sUVkz%HA!d=NH5S4A4vUTGA;uH3m8;99-?L@TZHZ(L zzt%eQ;wXS$Y2D2dg7BS9TWOaBcXn+fh(zB99!)CK4-Q|knMI^lnWa?AbV0N+perGv z)9`+S9`)Vas<+T2mNf1xp8SI)9xt4Y}bhE5 zrxxjhVq6EUmT3J;q^jgnWzM7cBCLzCtLrORMEHF03Hjv&K6-&Hr!qGDU3Yl}+|ZV+ zU5y<-jK!f?y~W4^qs5il=(FR5o>88;Yx3pMP~XRuc{O>I*A)*sGKVOG7d50id2B25 zZjaR{)Vi>4i0WcOjZH*ve8UODwAGMyiDI zMZi-kX7leK61BJyh1J{|>*Rjsfp=!avL2 zNf|SU^IDW=$3^9yogJ z&*2TIxI;|tR~mBa+g~w&R36q!R29|w2Z914Ky!5#-x2T#_(v1H0Le7)d--;2Ct!0Hg=nW}^nuvwN&nqtmP6B`~YMzjStYM?`vdrGif z?(LkcNhQ=e&8xlk5lJ^C8B|nb*Ex*DUl%&@o@U~4t=Brv&0RD53W7ZxK&?t1A_u6C zgqIntKAdC}nuC3`pg;XTPsq!OW2e*YnYB#*5cCE6O5DNyebZpDHMPh+3+@VXkywZ3 zU~M0<6JkoFWG-%%)v*jNGvS$KZ>|E8h!EKp82`FiM7Y}E(1bVECmm&gX!B8GGx8(?*Q%RKNu!#HFrdpeC$WHTp!gFgVpw_`>P%>Vs8`w#gVVo$n*45PwDA$Z1ME7Vr5}dn^iyCaKHg3_TDTPExh!btyg7DbFd_;I^q1)NWlF`9Q{Gu9x6Hp$_VL3000q zaN{c%yxjqLj=vU19f630wG6HXy_dvC)ju)S+VptQg2XN--|8~hdgU=_!y%+!GQD%e?1zp?9 za>3B!VtOo#Z<7~-CRoo#Brhv+wMG7sWQI`#gmbr*GSIO&Pe?a}Jpa&6Fz?%fa)>=# z>;R$8-*j5{#$dk>VW5_cpKKJZnSD}ytMPYV=+$E7*zYyVH-3o8FA7ZWPOGmw!8}ZH z>7ClTQ$TuBdpjg2jV^%K%7}e|e^N)2-ZRrni5wKsmC&0R6fZqz@fM=_ubfVVf)2TP zB9w4+(t)#*O7rv2@|IHa=AO9)c=%$J>@5`gL>~-u1&$7}g~D*fWNxOHIz1LA&7nb} zG||tYG$~k)=;6Khd^omzo6sf?5%r;Vfg@E$cARLdF0oZ}au;rQ_fb2XN?MPdF|sqs zo*O~d=YhzZNH03AQpRJ+hMPd?S7X&Ju1tMxr>fpN`lSqurW=AYWIFz%L}=0%-{Nf? zdhE-TC*J#zezIN1hmlwtVCMmtF?Jy^h6eA&N|-{SZAhRLFVc)yhoaU%{CQm)Pq^df z-2p~iJpHs;`3cPvTQz3)NRzM7iarTnLxhj~!uA$!(bfXLa|aHq+ensiT+qDMxu!EaQs4^&X_XwCb+wF=04 z0ol$xf%4iJM(!}uUD1x1qu&TN)ETwxr+84T?XKfJ{Ty7n;9X*e@m3CN9V@0u-fL0# zw8Jkb4+RhznR^?2H_OLdT3Owyu?T$8$&tW6Ws6MS(ffuZddgHfKBy%*!V?dz$<^Cx829;J!E>kZ+>4f%lUpQEx^#y25x5mXSatP{VQ<$lJ)Zn1jFOq%5^RTa zdt$4G*pgZ_O0dqP?tX?dR2OWwtf!6O`UcwTUf80N^qma_o=2oVLa>L7;6*@shdy$- zV0iA4)p!st_P(;p2&9THA5Zbk|!$&P=@@`k+f&=Qt0a}VeMbt-N&0yJH*doG#nz*+GyCfBQ z#8zrj#>wutN{MBjbCe+~?s(CH?@BMUFZY-eiEmzIWyO_~|4#SU+?n&XU%+6M6nl=p z<~#T7v0rAN+piq(OqQyB?b}g77b8)att|CQXMY{J;)rKSc7CejSMGBtDUh1v>@MF& z^2;XM%AZXqH}5=T7h=R|ggMs`s%sgaZRR77kdQ&5DO4ihl{RaU$f*ts*fp})bN#pt z&pxsVAKpGD$I6El3h>S&dbcz9P2fkp^l&;_3ee%~D4e2{dHrjqZN!MN#mYud>_kk* z5lC0ht1-+5Et-yaKPG-Isl|%Xj=Zmo%+TYz3y&YJ1NtvI;1HeM zMJMm@`EZq0^}?B1vF~tsZt)kfnXg+WB$MYu%ra~pH^OdO#3&j4KQcLLXDKwzP&>sE z64*bR1U~o=FO;<;cYs6`Kk5KR%eM5uFmDN?^ zo-$I!gZibntqzZfs`q~&O9sy%R!Nw>Uy|WJ!9(2u2RvUne`JR>6A0W#x5^Hhp?z1j z4@Ap|QWFXSr~7xDz(-f^lSqB3=k+D?+M&cA57;Z=#d}5=MJ8CD;zw>Cf?xkZMP`DI_+T2c+ z?UTDmM=SfV!Jj6U zU0hm!JC3(9zS8lXtz3kkK6;ucvfWagS~T@!d7?KAER@bsGP|kB@gBMJ#Cgl)4X1Va z^!cB}qDE3iYTs}CdEoaie7ajaIvVh!IT>BitmOW_GO5VPf5)pf_+9Q$u=$Vo>L0Se zRgEk2<|nc$vgcDc_|y%pThqKjo#2Efo0{4;_V+!=J@((PC){#W8sd2m(KDxu=i!_U+o+(Ml^L>0@IbS}3zr#mg_v6dBMYRN-{+MJ{u+$g# zuQ)N&_wY~rH8S?&W97sKJ`0`V{?d7{Js;w##mXozn|~!zPAFI0E!yK8Om60$hUj=B z`|&0_3O~FD>|inHjB`G868-uNUAnjFc|Q0akdkat7&&qhq?tsbNb z=O#JT6~fymF07Z^PukK%N6K}L8Z(Nt1&ARp-6|vMs`)D3MtKgiY<}27b*aE6_ko(2 z8}2{igv-qJBR<1hMh~&isU+f+OVj>|&u0AUMv=cXAyCd=kM;aTYS)}3fLL>q{Ky({ zy;>8ld_EbHx=ggsDKP-zfe3{W-J{*&{nTw|*L!D3<<~p+6{N&VX%Vs{dUanJSKGGV z-+aLb^TB#2P|&ATi(f_Aq2QOI$pzWTO8}Z!QdBd(!q*8dEB30e0FxX;B(LW&%i%sq zE7H9y@JHcw;|e`V_~gPf*K;_3Fn7WWQZMXzCA3>l`9Z^w+;*BtW=TZ4mKmPmX0|)Q za@)wZ#Z%-ri9d#DNodRnzv8wpG6)e$6+0smfxO!?dG({`i>t!*EPhq-wX;?DWaMX) z?I;)8RV(#g0mOmF`$N1z^?WjN{zumT;jBw@#>`!>5jH@*X*%2p@;NpGD?xmZ)%{23 z<2QY)nTV)!hg%V&Tu;yJ7sIb3?LC5*XDI&}xA(s(^HS%eryJ>C#RnH|>A&((e^>0| znW57au}Y$|y4bv$+Pr2|IGwn$$D4PZ_(_z>?j2n00OLmRYwFDFa)fd`L?QjtAOHRX zdX{m@pXYq|;e2$d{yqQvZ-4yfKmW%c?eO#GG0m`r-TL=AZ@c}9@Nd+Z6hs#d8ee5A32*zsP$m3)a&!qa{Zi&v zgfKbyHQ5wL;^Hd`brY}ty84qVCI;kIu+hnQ&x{SJA{g$j*ZpAe%81$U&o<{Ioid{W zPWY~5N-X8F*s?Sse>wC81?g*~vK={?)+0Bqmc<)RZ5G%j&R*ti!EPK123GK^Pb_v%fU1IFHIG^Lr4mf+EHmXQ3{u|bnPquJ$I{#-GS*(py0kI zT7-lwDdS4Xo~nC}9EBYd^)6XU6k9~VNAVi$gzx@K=Gr5K;h9Ajq=_Q~rzVpP9obLn-O_wh)=Tf-0Xt&I?hPaq)0u% z(2vcWqk$0xr(|ctKj|BCh)~#2k*tiDOi+mBWVH5}rMQ(EbjXTisr_=na>*+&}=yNXo6 zkwavOZ+uhk5~ncm1e==yC9%|pe=>93Q4c+z9HI(iW0rB2 z`1)B<;Bb@87L<&ZZmssS!kf8MXQl9~w6xWBWh{J&D)&|mu>EHn84gWqlPDEX+r*QR zwvFi^MV(k=tNO_frQ%L*OB<%Fn*;a1kho8vNbWiF=M)#M^xFt*D@(mTa{7TM*L2uw zvgE7rmyu~()`H2yfd;=0S-B|vq33=n=u^9-;ryf zkJy?w;omOU&Mo)yzhNe0)1iH$CEHkH+je&4+#-D&Z7T`01Ob!BTG;HG^7y00wDR1u z`#9d-J@+gD)mb;NH$9rh7d@!OA#cu}QedWpy>@7+Ua51%%b@gZmtCWmyF|j36sEq>>EbabNmv7mCQW3#d@^45 zgyoF;;8yeI45r*+S*vacjX|^(34C}S_a-S)e`f@hoSnQn=9kDBkHV(kx@SCGH8YP< z`{>!#ocB(N`Vaw5_>V!si$f@Xas-{Q=7%NHC1p%v!O3WPX9K*0#R=tEDEnl)%N5W0 z^p@}^cxzyV7nG|B6K*I#QZA8{_s%Y{#@9Aks-rB;YzyXvJX%w@zbY|*uHr1ZM{d~SE$l-YYyG>gaHx;0+o6x!Azr)` z*4mcovym>+6?0FF^SHzG?072&{!l_eu+LG{FYBU3p-~0xAp#zKb*V*cR$%%)h<3_G zC)8;e6^5wa7-U7jhsBmrMqA;peIK9n8p`uY7vlEVZZWeCr)+)*mP}tjMYb$YrxS|d z)$<~!_`(vZcWVMA2fkI}n+kt3J7`$qmk^LIO7?oY5=d%6_DS=KQjHf%4}EI>^|jFyKLCL`W3n<@h-%Tyj8XWadduQ+ zG-!VR@WxHy771_@&l^!XHB>ls84EvVd>ns+D<#^95s*PaKJ}C!Y~e2}vmu|+GwcHI8j@4K!dow#^b-xA1Sj+o zEMJPhn6N`Z^_`V|M*+PQ$V+g970a4>qxJs#@^*`0Z0QP{jN88OSsf?bh=g5CR>muM zs5d5iK0HE9x|yhV7jjAUlospflgCGDu|~}cF%SLi^AIK3jt)sK_c>u9xH2i zh%e(0j8`d@QA)DCx*OrXI6EAn68pIw#3=$7tov*+l6Iz;+u*Uk1I;zr8&gMY__u^5 zn)i>A{lF!=oR*DcN#KPgP&fk$%Wt>IF}|Ff(dk1aeXgw7z$CFP{vjxyIC%nx#QWj( zpy!j1^wht*yWQmZ1NMqPV-O!fe6K~J_s%?!O6p#;AkaU~Hr?}4+-0(}r4wyu>~*8P zh&C1(>cuVflTrgeXUR%YwzJ#qOujR^DYeK?U(VCKTxb2p)9(5uQJ8IHxNF>Eer1EA z#C<_o$$MtDUQp2AwmggxpG~lW@#TV+JQZP35XI+}LiQG~pv!;vg}ue#g+z-D_ottf z7~e_Xv1Ai^+2EgkR;)F1g!WMjF0Y-f((PmUM|=p1G6m$&@w7vMe^PGwM4(i!SUiER zciJ50DtsJ%eCUW5p7_ZnTcqZ`Q~krN@}hr>Pc5=%01=|YYxhS49G>3^|yiU)~-lY@y%T#YU@G8)7ZkPHHDdG~c#LKujcD+|AFw?Rp9K5vs zq<_>|!+m?B@~KJy)gM-ZI08Fk9&oG#(`qi+VW*JO5d@1rAGPA9yC=(665{Y&&hmrL&*8CZsl{D^pwQxbVWzhS17aNL_UC56@N6E z_d386CF-tG_(O~Af^jTyRF-Q=u}rfBFZj3T^pc-atK+TPQz-P~G!=IL%IADQt^cWC8U*COvDfQ`9Z+IXPNpNg;%+~PV)cC}gI z*IG1z(1c*fm?bN()XR*nqwF;4fhil;OEvxI68*aNMvM}B=vlo%P#rs)BIP0!E7Wy2 z*|EFl`2;m)_C6+1aK4(>-J$HvP0o@UFzdlSa$W-V(vji4s$R^fRrFnM>DWiTd=U0j zd!`!)l4xZu(H;`$zp3FB{Y;-Kmg9FUVK}$ut&ohD_RA(2M&pADga%I2{iD%>xVcqw^CXXZc>}5mjY)H-lX+`vtX6N7@lQ+aw zEdfI+Gx(J*W;>!jJqqvRvR)GCv-t}9$S=8b$P29t$qrld)>Qr-b>v4!s&h?po3R!z zjj$&B!l`(u#cUzrqwC##p7`^(=B?uzH*8!$yX^HR*r%^Vb3Ssqi4}>5p8#E-)D4iy z`c9FkpF06djT&kDOLd@lRKVETC*NX!?rn!#8$#4I#WT+AzkSKIl&I*r>`>Upww&}9 zZ_yi+=4m>nu68IiUa(SAlp}2>~h+Z{$l2Z5E=3HSxb#B zE5m-Ss2yml5b(d?gKNpbQPLkB1J3}pDx!eO3@d^h87r?^%v&oug31XpBpFUui@i@KIH><3a(=Dc-HE1FOrWf2oPKVEvN~!lIB0p^KW%n<GnccF#9Z^xBnpU?Hv0tEChPj!QRotX^zE!*$Iux#M-VSAw3DBRrsjft z#q7sS#C$yLU=J^SX()U_w=4qYM`>sD!0Q&&(ond6KK1Zs!D#sbP`!x@uIKXT$-pw+|;3$`bc}) zkLoDYU#wyE`Yih}6DX*HL%&BTOm7}JPguC%4F&#_C9?@dlw<52os+w8V~}HZ+dT(u z_BC4O%IgO66Zb|WYt0NcM^K+-H>b>5+W5h#Mcq;hZw|13D8Wf|ZcDhNzMTF$Jw>=Z zrsw#^rS+~tgM5nj?#}9tcst(9PVocV+&aRvsh#G8ns za6xtiLYc)nw!pW9NiTX1P|EBJ_kGN!LsM*{QZ$RC1U{Q0f6iD!p`?<_lcb@DRM#YF z5qJ6p<@U7TNc_4|Ugm7WA8*=NM`7fRQvBW|bd+yVIu={(ZlPXZrXyDNOwp`cdS=Hwy9h zWM%X+J$rsO6uVf-GvJ@teP#cQBSP-wMgPbDSj>HIY+nkyPW+T2{C+H>a!4cLySK#2 zJ{ZfHi-Ot!vSPmZA<8D+&8C0zoy9r+;^S`dR(*3iJ!k0Rbq^W?SwAZI!R1zP{09*5`~nKq34S=v-!vkUDB(>p0%ap8SuY&qls3F zuMDv&ytdd_{$*BVu}|_|7X4(f&#n0L0u$l@-`RCI`^28Qx$;FnjNJ)yGE$WA204Pt zp2a)S!)Kox_=rUz8$ozr?r)StbiiS9%z7}J3Mf>)jBzN5%E1Fl|2f1MNwW`a*#&(Az>vBXJ@iSv-j0i`bm;&F6El5xxr2>)AeGxP_>yh zr>}D`twpYUXnz*BOsH{8+T(-{A@XbGS;n3QuSdNk8E#5I0_9VL>!annJoC(4u#^3A zK4Jra%h*@AEm?Uw920+54a(&n4z=$KC!?J3=`Zld>F{HX$#w=?1url{LAv4*Y`!SB zLqV?6dQ7fO_80%$TZ07sedyKLw@w|m>~r18eoAumED7Z{TeU{KmX&0yx5>!=F&;rL zC2KD)Y^9#VwK$no(vjA9Jtq*SU-dU9NWms12ZS=8(OmSv8u$-IncOW zyrLJjmndbo0tVKL?McnpJ~=$*PWpt5Yfv2h$c6;U^GT7cUHpM~c6u%LPdcjUZ-Teu zjdFw1J@84g)%MBhcG+_U^fw_G!FqY`*Mp@g?xK_Xpw=9TY<6MTlJj(zFdQ9t4j=A> zNo~~a-Sd#FaB(uEiFpqPi^jHEvb&4LGR5AO(A@MHSa0(3=aSfCvD9?tQ+46ono)aF z0~t8=nOz5A@}+b_T*wR+tz$b}U}RL%`;2C=`OR>uDg0d zALPs62gi3g;0qaLmNmC&NvK zmk}m%9+fqhvu9+j%+3nNYXb)Qlyt%ir}Lzl_pJ3qMOsxxw3|v(L_m?zRCrmG@wT`mVCZ_CiX zM83jv#;{?~UCwg{9VFKfFPx5&OOq;r_4l?Q(!SUeM_A%RMJ?{5N@U`{9b_ZTH7(yM zTa7WF7>DfpSkD33;k4MxJ*gqy+t{{>Q0}wYK+jE2O_;1)#J_HvM_^SF@5=FxD%MXH zzqWV-*;XE&qDg*FYJPIX4ed~R6YH2{i4^~y+gQjhndI#;&9D!(P;?o@Xq&q6lxS&( zg6l2JEHkWJW^x_`JbIVMg76?vaT|zF)yG9;5J>nH=Wjor32&q81$yrmMg0no60*@v{G4m6- zxE^DnRZYF!T?u#R_fKH86DVhM;s%+Y3~?q7Um3N# z+xzfdrE3^!n`>M768=v)m#5j~G`)h4fHVAtoad|&d7hjM7xyds_mOpzYNM0jba}R& zRaH)|(z}vr5O|Sv@S@CnzR344@IQ2VnAmY&YjHq)FKO*rviU zxW4)dWQPU=gnU!n;m%l5UqDAwWKuez(~n($jvT@#c;OtuPbjmKCbGmKUXbH-mxA9M zu}mi43SO#t()M98J}zs4|9T+M=g$Sv^YWGXbIwf)8oyKH&hHj$+*RD77gg}dA%`in zJ>~39*{VQ!{uz%lAX}e7X&FDA-c!mDzc3|w@~LVw$ZH;)lxhUR8@gf=xUm!50uH#hxLLo3a=$F%Sw4*!VTWkrYyw2{ZRgWYQLWTG`gR(qivU-I+H-;(g* zM&4VV-J5#Bx18n2m9mSZb^N$I$DG-$AA$;~`*AXE2r;UQEAzcx^f_`e`q|jqmaL4v zUF83gogJN)bQff1dGfSvc<{H z(1(Y-P=Y`DUf{^P)fbfXh>21gn)Z-*38UpN(aFnW0JWpPV$nQ;$U z$pSCUPpHZX)oldL>4!9^crVT3NomqL*17(;1`sm zuwqNwGtbvfaZ2sgO43{EU5n2r#tzXt)Fdw`o@m-8L3fK@5As(CphJ)K`~)rsJa+2q z)$M4ER1>dC35BXvve%hko_qatfsc!ute3r{2pu?Ip=$zv8BPg1>2sgD z#U_jze(7!^hb~ZfC0!l-^4U->GbPn9xna=s4=fC6isQK9%=!+i(u zCW93j>0Ue7<$)4z)Of@WKP%MdysG>_(IT!xA;;ld(S_#r?U}4jj>Bhv8L*7@-9l2d z)M)l$hq8M9*53@(K5}TPK)o~US=ll#ImfOv^+Yb5IQzc>)!%dN>%imd2or4(40)4`+U~(K$GU1whldxTE5ofk zR7mJt_lgxF zwNRH=5Q@Eq#F32P%i^ANDbQ#rHK<*=3Qafwtb!(^)I>IAl*Bjti&$)lcSrL zGLCiZD!?7C{bC0uM4!*Cc>`3e8{E$A&r8U^WKVwb48ijR-zWCZnhaTT{+UzgKNoU! zj&!<4D@W5xd%Oz3sCP1_Jt?JAOT8k>?XLMt4X2@zp4xaccCvf9zA7=*8@3}XDg!rx zr?Zqhu^<8~Kq?ESHQ|G&$oUxctlE{~I5Yo=>f?KffVu>J(P%+1;PRNYj#LR(>78{Y zxoCzC*H)U7p2?AaCGCj7I<{MCfeqE2%8aN{61cWGn=&q*-mFIQ25cLjbkN|q->}z+ z4MsznZ*)B za2r?~L!bkcZD`9_Ue?uLk~l)XLi3LcPhG^K~P=M+rxH-I`H!b8C+2 z!lX{UrpRy5U$n>LnaNt0)Ey52u~u_+bU8TQq8`il(e8q7GP=D1iPRgv)B=nScPDmn zl@=JnxD1q-v-RPhG0U!Ru-DXPe%%BFP~bk8`bqgBd$4SjKWm1tJ+ z=mV#W-F4hlR=HQLosY388Vx)XGIj=MOKWGWin8LntA{pawa#xOU|dFteN})9htu)X z-asbs*;=LhhM*pg zKwcUrssp-@I7rxxxD3V1#j8rHVfXrzJb^FvncmTI({*oinoVl#8p2PMBCao%nXNPhJ;%XnuMDZC@vK9kIy$Rk zrlW{%BJyt48#s}ex$tLg8w|qW#t<+BPLHA!&2(JWv#CIGhLl z=KRa8SMEZsJU%T~KL=6p zoa8SkAMJ6irxqqB{T$~ivoxv~MW}C^qPWMoS#*~aU~6XxdY!B|OZA~@h**6s*2KX6 zo_%*8>nAh(dItFDQH_)U+-P@@*!> z2y+0KwbBMhfY&(#sw}MrluaX6w#LPkIjym=p=NQg%K{aPs`&EsQ5~+SW=Nyav zkk%A2%_kL60X`<6ZaS1*R~?7CWKXT+gqctNbd}Zgn81bsX`H$a#M`2gu@bIXtu8fR z;%;0aUP@1D1JW-$9$bRr2OGm7n$G zNV>%Pi93qkggU}^8)tKa9S#IHh_CyVZL)Y_B|GaKDn4QL8Wg9|!Y?D{F9q~ z8}u}h;lMREW{|pyeiDqoc&c}6BtPx1=J%NDAOkUoot49 z-FR0=cXZDHVaof2>CVEDRq1^g14FsD4DvN6G@a^2=p_`B;U1&3JySNgUTM#46k+_gEXb9j>@4klN^P1<_lkw(Csc4& zzjyo!qJffHb6WZF@j<`(B*-t1!U+QIT%5t`S*VYGAv95BdWxlrg4SCi3IdGt6iaUB zq6oPW9Nfd(OSuaUW&6+sotSW!ee&CA>*?sqNpjqP6wY9wYV$}=hjxiG>{b8nS1`^m zD@W0b#GTm4;gOkZc~Q!fJ;r*0LF>{^y3aJfn}Xuwm9C#CY0PB0gY=>uC-CT)iYMHm zqBz1rqf;uRBMeKLv@FU1F>>#VcY}^x!gR{@^WQev0(RUU$G0GZ4ehAeo ztpi~g5y`ZW3y9PdM~~aMKDxP1;}a)@1z!_bK{(Z>h-tFf=BiSBrz9$F$ z&0{1ThU45EHO3nsQ9C{$g_ih;mfHrhSq*^Md)h>S0b4W&twb8}wrtD&Io?n>mFh!mt6U*GhDo~)7%+#Lu7q%!c2K2^5yd88Li^-wtjLRjk?XcQPy;b02T zr!@c`+!y{lNgxIzdD3Et00aw1AdUyj8<1`15ugceF$xM4YW##U`~6nLmA+~_p)VV7 z{FtoWWhXdp`4FGAYd35p9 z|47oYrJ$G`)7{{+ufSBySP1XHlN!(w{oGBnBY%i{K0(D-IE44}&Y7ozjpk2htDY+@ zZKK#3TyCJLRh;KN=eQ>$CTzE?ZLSie?J2$|2q+#tc7oZi$kJz{YdLoAAATL`Z5wP% z@X2I&N?;so;=aSC+EW~^Aie%DrcD7dwz)S`>Y*PdpeAZF?P z&CfM>kh5&Ns7DVzUF6pui1@W{Ly=ueNNx<)W#3`fb~4lCww~gFcSf=GTq_rWO~TuA zaaZRAQ}6CLrID_|q3&MHTmpK5%_^Kfj7Rt`>|vQv0T~$@fn$(_JD?W1_O%ZA6ZDZQ zgqKfjN9(tkNY>Dwh_nDIj}8drbo__EeftYZj&jt#(yEY zw{vbBms4gp*M1@%VyE?L=EG>xZPIIfobgsg_ZWtBBiR?k_$Ny~MahqT(Y2YLU>qoT z7qtw12Ct2vDS}UpHlO_DPtD%}@q`t)fF$j@uyUdXzX58)8{ayexV@B~^| zK;*SaV!luB5i3RE;PbCzy1YyRiwH-cdJSF4E=Na1Bg%Z$z+~J7ZYn<((8UJFE94K1 z-69@%?;E?nSwkR9NZuXg$vtqF7fnG3bK6cTy+x%WlUJc_a%J2^9$$~P`M@Q49wJZ) zH|qJN6SNn2Uxi&p9uRG?0pTCx?Vr+Yeg$`18th83BPfZY(9@UzF6KKEGgl+cz7DNJ zO%MD@GnQGJBh@E93wql|R9}qQgx@^QctzOQ)wlf<3<73?iK{X7t;jaFGHOY{E#2|% z#sI>b2a{5^RPFq-pEGI}k-QLO{6jB^-=QblBjurT$Cr~egd9BG_#ru!v;Yq+Yvb@( z${4Sdt{iukogB2wAqH`s?kn;J>`nvzBQ(+dHOu{PF-!uxx5qPD_vC1DvS%-Hm(3#) zip|d-!GAjQwNNDJj}<(7tht>`Tb#weCy$-3Gc0RWSX_^y&IP)n!O$?}2Num0u}hP6va&i3O>gA*1||xKh+p)6 zvPVCM2;RFL$RFGkrVn}g{F&4Sd22-^$Ium}#gv_Fl>2aQfE;XeI_^hnG6ng26YhO* zw~)21kWb!;1LVR@rv&Alfaj?-(y5!DE?+2hB0>`X4ZN6+n%^xE-s%jO71r?`sDkPv zs#-&FISoq8N4Op;x8W^30cH~GO5FBpnd2~hf#8tfcMaqg27s5D#^ab*hJgE%|J(vk zu>c_pE_NuLI+CLoxpXK}-VQrYUACSI>YU#~N0l8#g)P}V1!nxL3;UN4rn+GFkQFE` z1`M9(YB?f?;RaKH5|bkqeO83)@7auXqanp}1Wm7NKXq6yr1lxuF1LVW{qATjJj0tm ziT$Oz5H?ZS<}R|$%blH#SzGMh4?W0HBm7SLn;D0BQQA_oayCYxk20y+-*qD!ycJKyOp5vU_C`GMDPWcNl zh!M%y%CRy!4vgNYo@c*Rgv_7L$`p)ZqWe3tzf8oL`%ZvF_63G4y^q=ToaYyeaGf$M zlB%EGj<3bFXFUjY2~HZ}FYar0e_ACXiV*HS#FO4VCIp2?SL&MHQp6IQrLsuqheFdX z3o?!7*LqBJo(F{OWIp+g!bL-b-nemJkN?(q;M9?q)#ntS6yBw=sxg&40>$^~GeGk# z8W!!@k83bGJkylc**~1>28zG2M^E394T{zDgFoH0;l)Bm*GQAug_x-tO6x_Nn-BII z@M$QqpH=~>9j(9&Uq!+9XIF|uSx&oFdpD~cPk)U$Mn0#&#gr|xQ>w>P5N#LIhfBqR zj)i4xyFqlju1RCsd&KK%GAD*uKhc~*RGSAM4K3ck&Si*DgAn5|6|JU=aNjm|+pzb<+gmE(QZmarw7}(f?H$JXiV%qS&F41 z)5{w~gJJ^wdIKCcXZfH6NKqoK&UIDHijN+D#9tF(E z*%w3&1n&h4o6isr4N8nYpFgRcnww%sfao$T_vEqE+Dagqu3bcX~Q!r1KUz zkYBf?^M7!eCdx14W}0&cvGA|m>&uO%=+?c;S>HiG`&|vL9};P!h%5}#j`@f7Vv*p< zpPI`GYD+6?jdecwnkv*JkJh%>Ql{{?xk4d6JHbU?K1Kt57y0_T8OfgF84b>P_9yT! zzlx3}0Ys*0BpCX@i+#_<;NdHJYPdbBYEsOM<{XRH1AJq>hG}*jjSKE~_$V|5Ks{E; zec$XMh9!Gl)J*`Ma!|Y=rIpr=`xFR{cF1^C(}Uc&UcZg@*{k8G$ntAXdA^foi6r&* zVas)dn~HYaDC=>NieVsJy%kk(%Qo=Jg6)T*by*`1_w$aMYw4jJ(jH>X3Y_8)vnWtY z;Bi-34{Eu>27IcTXH9gi#n?KFC+SqDB73cHN*yK^Ql~)inS%&PD2kH<*w0-t>>h2; zsj+?0bMEqf9Ix)MReK|2dRHIs263mUkr)!(vp0K-7imDmQ) z6F~EmTasF%lFfCxQ~}&a&9n%Y z&J@yN4GXZXXi@H;?5c`CnEBC=&=0bt{$yKA$Cg1ZqA`|JL*gQ{l3k)^eBsVlE1??7 ze6z`%QCNg7)9fVQzDKD;a&`?_uk@q3SA1+wLB0zSvQ;xaPp<;f5R~f01<`?}FmX9!!7vAi?L+ zYfHJ*zv-xZjlqZUdljgEjkU^Mz3XkLi6-RYK{guPc6FLYiVZQue0giz`AfCoQ6b!h z1u@@a9>c==*PpObaQMDgeu!koDr$DvJd;|dCovYbaX8ESNt$Qs?1v?yN00`GIx1^H zw!;g9p`LdOWCaq%z_BihX1{!r2(gf?VYfwMp!dimXRCAD&sV zWc#z$%Bv_SAaDeDdmHqF>r&;jKt-Yd zEA}JxLc3cxlos*U#ZyLDF=G(ebFVK9!|)JXDoPMAn=Mz+O9_E33jcx8M;JQ?#P|b3 z^7*P4&0Jsj0NEVc9t0h&I`9s8XK7iS+Tp&3o<=|hJf%wJbQ3z){)=BlbHZztNp=Yfw+DjbT{0p5Ys2-@!NW zz^p<^lKFRPCqdKD+9URBVx--NqY=f?z<#52AYwGCChlJXAgV>e!3(HV?AgcHG((ql?_& zW4N+dXU}}LO*|^b|7I_KqlBJVpF!tvf%^rAI zOW#^(*Dh4xPssg4gZMcb4(ZctuJ!rfmbrxygo2C}Zf{3HQ=4hydrOl713KY9(Li-D zyTp?wMVok9l%s>Q$PKGLCpssGC`J_nb@tVYJ%#&L-L%#2if!Tpj!DBG7LKSjIm>gH zO)!v~HF@_bk&jZ`8Xj@re?NK}nK4RvleO9t5!s!xug=#edB{3wE@ZDCNh;<9e1X$b z7Ka8cK~Dpy3Y7RHvM_5mZa-)N@EB3?bXl<1wEX&xOa$njZDSyx@TDiN9|hg)Bo zT*orE+K@nNi~SunPDekZ>!M|sgtA_-UCK`n&T~d?woeWb>z9SlwU>n5G_yU0XFO65-O&uwop0>?7_YkyTLbSZ1xHh{5v1K=Hi zsY2X#;4lj4ElWoWMe=E$wMX;}0*&jWWsn+b)y(b5Ywl~*pe*rhpYzwSg;v_Wf$fa7 zNvWA?nddZHs($mZm63&U^z(DWe(iWZ7m2hk@b87& zB55bD)C?xL)RhWOF`SJ0oKRk+&LA{;Y;ZJQ*5*3{eRsIa7ahiZ9Xik@Xa5b-ya#%k z7MFO#zl|@dctQEt)EqJP9b5t?0hj{An;=(nL`XtuZ8)TEX36rhYHlZ8A z9F(;a6QvFl%i5Rf)tg;%W0zidJ5M?^$)yS&YI zd7_7Wze{Y)Zr8LfowCJbOD!h%;XP_16`3|i(+zV`RJ^hRjcd*SPP&v>ZMf@53v6@L zd{1rI6;IBbu|yW`Fk~ab?!YLf>agTy9^&pX2Ibr1RHUNOx+jIV{oTA-d5grl53Z48 zAw)pUr&#CRkd3|we)3y{5mcUyDVLnD1!rtdH}Vy2LP>s4!gU42?Xk!#Qu11&oJsc# zon3Wf*>?%4V7h3>)vW)W{AJntQeti(NX z*xd)6a(#Mzp;XRNXSxfcck9Z%QU(h}dA}WeD*ziJ{}doLNeoFogQgY(9Qtt?y-n-=UFh1B$Nr%;~mo^Am8(6eWpFG z5eMQVGRhNY`ItcqY@E%!N;EJK(6;_n87Pj8rBVtt&Iu*Onm(bker;A&3={*Y7*D%M zkY)2Es%CNWggS?1DJ(@Qi20QTGT?;dYRGV)b0BL8sDsvMNBICDFq;I?q#$ZbZmb@3 z^w*z0Cpu6mXPBGBs?39B}UE`C|O%cGwWUk9z(s)~rrsG@pg>V!@4QIp_RVL7` z*;U=2g-UTruI`QB0~H?7NS1t&kW=1Z++O07<`w1HaVM2haC_Abb%uKW1v(%pMiNM1 zrrcqmP!N5=1dUF-Z~r)Ig?_?}&Y-np_ z48_X}^&f4xtzBxVJFase`7BrW6#o8&2nR%vmYqR0D7H7c8+B<^RiuOfDX}466jFra ziTBiO%T77^lZ4NDHHTWd00CsCCsY)lAR~_;$_~k_k8@WPVJeK_#&94p!7WOhGHf_p zF~TjttT5jX0~tXM5Y`lTdbomwsK*lEz-|#Rex}CHg@on89nasTWdR9`M9Z=T+{18Z zYq)|CZzi+n+>IY!9R4fN7cfaEapM^f5V22H*qo>+g!*8dACWd}hL<>w6eiR&2=`{r3S)}Hp9mNiahrH3(8pUK3S_2>P?UM(Is6uLgTHIG z&JcwWa0gr#M2nDq2WlSz1Ckp66#|I@jD17}A4{w&><_A5m_H)FF&*g>cxAlgh^!wc z?|nX~I0l%EkTIqnJ_BonKxvi$X)w;Ad_1)r0PD`4B)A&XCWY=!5rZ_Sd|%v>_#z-c z+Mg0kj~O7aSjVBpVTNJ`P(Kby{}g3>H8~(=JK0thjeV!R1#=wm6s%y%BG#en9t_B5 z%&kI-7o4Ff1q?6saG)7*7^6_=IMfn>G>#~Kh+RUUK*}V(I21yX7%&hih~O}88dk6& zKtUp5Kev1talrdlaG+gA6frYo#SznRO8){#W=j4KAR~sNxJ!bNI7J5J9(D28Fn)pV zoLgb=V<*7hkX2X1#2U6c}wJBS)zc! zNPcbmtml`a{}wy>^~(XbEwi{-YCOO#FJ>6m<08T;CA11)vyy46g`#P?-tmq)5a#3$ zwDl>!D=@0p89y~=Tw>mzk4;zQckmgq*C$Ouc=^{Fki%34-G5I~s0# z(pS`;OI!qxvni=N^Vu`e1p@7gnpL448$WFreW{>;YC@PM(U#0#nkJm9kk(nIL9U$V zPYD~+=QGDmcBtbg zv$vu6F*={;EIBQEr}k{M=Al=m`e=ivVKe;@Lx`#9a=I=jIn;uwqHMJBbpWCsi!gm| za`n&VFf1`{I*t?Agco>M`fw@XnQ{D^iID|PiTzG#h*ozi(R&3G^dqwLV_`cW0B0ILpMXTlSHW#FjwbfyuNaqFD)kp)Ucg&H&BE*W9=v(DoS5M{C@C^PutU zv`nOz>Vxh~Cf3lXE%}iS2Oy~Kcx;LZVW;x8LEZrQrTQM-@EK5VGnEo^dCGwt(%&7_yFGpF`v79yGMar1mbypI9-QCX zpE{0}3p?wha%IodIY_>M7((G}QovaYy3pltNPr!u_d^|#+eZqrJMIaY8G&Zu&^9w0 zT)N0jrI(fT1CV^Zg5AxW=n=?5KfGEAfC`ZBYP!cp^`je7;H=`N;bp@7Sv2n(Y|Hys zjlHYne5~5k*xbVDFF>k`Z2Ebn3UHNq-yv)ZRBjrbFFWv@6>3~JkobKjAmMn5pI#ew zm>+Gk-qz;#n4VCMf~EV7oij9@TZI-wg;w0TmKsU`WK^h7=n^E#wW^$ajdFhB6}R+7 z&==ddBswfo#uOQFD*7!&u|f(7Tj}rA!qXxbpz^*F1?|?b*{Qj)9a0;$rE*DT3Oh_K z>DzSKM0J6FE2df}FGk#U6wS!`Ftl*mp$FGgQx+*)+HRu;oa3ok!Za|hsA(M9Jx7fe z=Dc!gRvE)G3=@fzDNSiD1^MUo2{NakwKE6)BPb;g3#qlj=~KGR!uJQit~~lv!q1$p zg6dQ3w-mft*9UM9X}J?hZ#ljh{8PCH(>G|`1GbNgF$->B@g;`i*2vmmdz>M6j?5W# zsHz5t`VBxJ=rmf~nK)6DAptQbX~Q@Cw{$Wm!QUCPl%LT@4SA&5v&?V7IrGqOo{Mdn z&uPo9(K%xr;W)Sx2?NPazF;32rS#GOg%2UJ1#^yd`Gw_;6kw3?%k``4yc&A| z?y-#2Pt%E*pzoZ>YotsDLGR1fb7QqhXhGuk`3)+ljEf{h&+L_|x5k}zXc!70BWAB4 z_>0&C^+oN$Tl>NJ`JvZKKHY1~q`Ix_Y!&6?J;Iwfi;b zB3~~Lyu!Y!a|Mx4Eo?)U53dVAQDTT^y() zbAdHzE{ZtkvezcJSqM*c#;GCv+dh7FrmoFnsWg3rnxdrOg=Q!^8Kf@5Q2}WR+qasq zS3pNYO{PUt$L9^2QwWe<_51I$S*O@JkH+<^N9@l+r>(+Ay#FwLIbGX3$8HdBbU)*{ zJC?TBYHzI&+g@ai`%&=9QHv(2MH>n=5sbB)bmIVIzF)+@TlN~^a$BW+A$?k})KVt+ z22ZE%23w2KsES=gg8MM)-+!=+u13YP3@sTg(jFL$_F8iyR@(P zZRp*n^s`&imtk~$-ZV$U@BR|<-^tt;itYoCg%9^t^c#6;hCl%QdGH9^jexKR?n-Ng z!-a!o$td77QHBK0;{L@WNBjNQpEb5p6 zj#mZ3i$;#80*s+r$O-VGqq*jy3 zxbbfcYs__~_w@FX9M@xXnj4)C?q>qT-` z_hTdP;9P$<6yn8!@Y;i9ru|ENM@ZDSb;dWd-v6Rj7Hn@=ajnq*GDNmLf8OS#0h{Zm zhz)1f5BR?r{^4zkw5Z&WrRNy3Z47el?d_qM>t_i~+shH`=PRe9XwNhMf&ghKIlETI z%6W=+tUfLQ20J2*F<#ZVbE)Fau0xj@^uT<1gB~@M8ZpT8k>NT1J{dw!Bs6Yt75{h>9tT$6qMspx9Y$_~W3 z*UxyFT)^!VK#R}$HKvz&7*b&FH!PvnpVnbWkrnc2m_PFo;C_mq{`4}wJ5kV;QQYO9 zVvI?Wd>Q!zwlCwCFo(2T^crUaZ6X6P*UmmU=gyI3uerq}1pT5~g(Ty3)dCVNON#c0 zPsAnGx(;ZMupg)6Go$_t`Y7s;6q0pepIe#|U*HnLCq`uSiYl?kSOnpWW=v)rCeApb&Dm!06F&u-ueut= zsz_eYm})GVAw4E)N_bJ{(;4;fD-NALV^Q7CahrQE{=hmW+iR4I=f&~kq$63NFc6@8i-G+<8OyX=!Q zGl)mosA&TOExB#*l1Qw_c{1C~#oEn>DP(k$6VHFWo#DH0M!C54LDL9L+QcrOP%MZI z#*eXD?aiuqtIqpyUC~~CH0C`t%*hw`CT9*! zF;t#^f+i26DkVaPgKLRz*j$`gw8?=Ab)S+mtv(mx7AmKi;chVDkycwh+aV4SPXnuO z6(HZw(V5tw2O^%5w9c@GoSnLkdv^3hH^j8#1$tkpO`J>JW0~os@m6x_^p|UAFeS)E zZ{s{yQDsWq^3VO!l!3d<*>D;tk7G0ji`qx2voY`g!;A9r5VPB=Tc20`z9icpUzAH= zC#@W-&&$|T<%H{ji>^1wQ2ONVyzX9@e_(&IE=AZ7YT}S3T6M~LsSWOZ)JE%Vt)=Sm zoM2q9_Zbh)>*A!i)Y#u-3Nb~vJ4XV<-YH$cMkXm6_>#@S6fY`*c3c)GYz}Azny6FL zeb&bx=tG6Z)$ZWs{H@Q;4?3FMJ2|mXzibn+b-2S4T_;!ubfQ>1(Mv{*bo9uBwsc+3 zkRJlQ(o6$GA3NsfcYlBiSUS@Wr3w3H(rGBsovU^J^>iq^uUA8ik`gmk@~jNP$cPF> zeMM^$Qe}X%&SE2X3H`>BOb}9T+TYr``%ocWWP5-jwz>uf5)o4-BoKp(m4h|i9lqhV z(G>TM4ELn&SOd`??YthvgPSGObfBWUShIdbc5)xg zjCypW=5jDH=o(>4vEYt!9w2x(7-r}^RZ`1aONqCOde9xjoKUoaZY=H zw!QxWmj&*O0;cCu+feceHg_KfY8~<$K&>_W-iLh7;v`$H$rTojYoKkT;)9DBAym`sWkh4SDvN zEbQ8z<_dpS6uP6CPx!g(ma%|N`wRO6|HdU2^LZr`ffbYArl51Uy+GA`!56d72^aMO zYvKVGSEi|hv0I1*7}4qi1c3TN9}13``v_>1FywyuUdDDKa}a)s#pL*QG+Bk=TAYCm zX5dnc@YU+y==Avb0@R}wfBJ7+E*rytak>AJq||;iDPuz?DEi;d22TGJsYGoZek3YE zL0dNh&41KqV&k6rQqR<~G~{^i>V2>#FN7WDy>5(9vs5UBQVV1lNah5CjDCGn}lx#tO1 z7A3pUW2gflfN*8- z*oi=sfL>l$lz?91AFT=!&?_0cIT8HS7IAYD`|b225&lzWRAm1-H~T-&&CB~UST;^S zW&(Oe#-H(F{|7FLKW{h)7&-niT8acedg9Ohf2fa)j7&e@^#7ncW^Jm;*y6CmT&i~q z4!`%GqXK`uXpQk0}NMYeDAb zY)46efucs}1geugO)P>uniU+t%?Xxf^_aoJ5LfBD5n}j7`wpH<1p0LRm|gC1eHcXu zDFOwqqz8?&T?1fTZ@CcFvBmu9s&JlB93Ga)onDT9GxZHX;aBjN_F?K)ZT5)ftnZ|K z;5YiCJx>&~@HNC}5VIBmex3Uo2KDcdV7-Vi3CtI2QQpqd2HrznmJMDX9zRJ! zfK_gweVwgN7!g(qE)cLM-^cJzp=flG=Yl-6F2bd8u^-$$_KQc;TT^lofo$=%_wh6L z&63{wC$*jDi?%m9CZ2Jt-u0gh7D6kgmPu>trSa&j|;(Ok{WAB5Im^`$OnW* zusV53g&_71M@iWd;UGdL3o)8OmTBJhxv1*D7N~a3@4-@fX#}zQX9}Ap+o1Z6m|I#R zN>sFS@lvRblb(spR#aw55NX0W0#`JnMOYRO02PFP(*C^&>r$|wUpKGH-G$X|xT&i=h9vg9czQ^aI6gCydTVZ;RM2&hyWQlpn zT!9;|$2x#HaD*3T>LP)%d{JP=bXs4=7NeJxwHq-k3yl}E&fKUM%!|FvAoLOh;}le0 zVcsVRyk@Ky%`g`Cvr*<3E=FeHj7nz`&ff_UdQuYZNS%zQf>aWNF~U)XOLap;=~{v! z5r#owS0>A7bNT=YA`EuZmHQQm-hO**3wd9Y)G8=?lU092hxHuW??mbKM?ap4yt#$q zU_#SbyoH5two*Wr2YqwE^);YdX&`36`+cZ2z@Z+*01vVjgWAr}n9)kU^~2O_ucmRE z1k=dR>=o8nCw}fkfVnmd4`ZYxnmNFtM@SFAn(DlO3_olC(wt}j^0bel04IJ1agf3z z5KpxIPdj;&&sE+uU%;Q`A3Xn!Ludbov-M>M zHLCSiZLq;~yiK2i zja`1cEVgc4i5$m=uH&Z;uS~!9Xr<#T&ZW;y-KHBK7Zd?!x3l{;-SWooux(&Irpe~K zkvPgKXP)0_Y{2R0F?Dw~3MdI%B|(_*pJrN)kK}f1h0)nb?68{Sa61lr&X4LbO@EGu zzUmMZLiLxslf+8jp){Dyzxy#e9|(fk7WYDXr8M8{WD~`-RhEr^CmIG+X1$`f5!1aB zuz7{FunjhrWwURFPN@H?-*+T*d=I;t>~m+w>j;q(p`o_)zJVf75zbz@J@wOk-1Go- zBZbwGC-lSB(3j|o)PD@OTzm@M&jZZ%@v6rm-&dq-}cZ<;YWT&CE5A7kIO+%SZxmZ^phCaG{b z%ymyw$lLNjQ^;Oti>_XmiRbl_#M4AYI*|-1Bb7^z?c$N zey^64Dpn~st^xO}_=HCn7!M)O!JH7@_4T=H&SIY{snKaFCz&pttxrZzyY^jNs}*@p zB#>&qkA=^Qd$rp7w&zkh&btdYy8Yh79O|Ab(|4Kvt(%!1MegboF-%swfj4o7ewXTS z6ERr7=K$O8o+H!~E0-DcBnSJ&W(7eFHU9f$tH+-+VN=J=l77ev+QiEv!=Sb%VN>78 zQjC23Lax=4I36L0e_^#KnkNf#n#QduxX>xcP4c7D7^9ai*#L(yZu5Zfl9^b8H_cD1 z1hg2~zX1(;2o|-W`_Bhq_yEByhGPR&Wg3KzU>no}-Mn}GHEyw5>81oPjouvA8E}F3 zMXpy66$$fviE-PQH_%mqiQ30#^@usUK!C4~gii9*?&fb*7tgi^-Np7tB)1VXcg`s(K!mWaMnb2(stz-P&GbDjUD2; zmJk4Uu|+3e#x4ozOEm?Yd;SBM#YTl7>y@%LE8Vj^?9G<7UmM#-b{pG`Q`AhXLbMt= zg8z*6Lni&6G1Y8(B_(dDs(V&Vu9uttqYSDZa#RSt+MTjO^V#(-WmA;oOH6qP<1h$j zx3XCsNFFrRp}5`$q|{9Mf|bNfw3byq&|^XIT&F~z&?FNnEFV`*MQmT7l@HvsvvF^r zN7c4`a(?gfC7jqi^=-ppWS*m^I@;^nXJV9RGEK^B>9?6B{$zzpI>GYHGS> ziX-_vSML~4<>9t(x@L^7h8me9Fee(ZWxg28v6;fB)W{I|15v~rE!#eV(pZr!1STi0 zBhRobDr@U{YcB%8(E;OdbM{@me1-KOf|JBSQ3?V}Fep+%l|&XU+uAV%disK3)T)6l zmmCW|n}`qDGr;TMetHUlq#{w4e}%vxsbO9R99^8w7Su+i)C0@`!Kp+poPXyD|BL4!?W3h=o>tW~St zya^lNd?}VlWaCM`8K=`!!;yMv95^Q&n!A?)CV06p%+?2ncZrucE2xAb>7s`wWG&*3 zc4u!!`yz^kmANT>ypP{R`br~!s*_on4;Rc21KCF3uqp9hkij!Vn4z$DewlkZ9qOTs zmh|U}@P?*|j}3!?$u)_SatH!7ILYxacsxzD7=*=U+36zc+|w!r6*UIH?u!jkM2vDc zb{M~`A~T{G8qn@-zr5YjY2!zY&_x8&;@~GRNlhJ_v%-iIBF3z8@OzBk02d8}8Cckp zJdrm13!2f@duo1Io^&`l~RJ?~c2t3Z!}PoX}oJlEj^eGcN=x_jLL#`nfQ zi2;Be20^15Ocea>QhawU9fl)!0Oj4; zHyhFn!Jo7X2RU+SJN#m~e>%@ge;qhzSWJC*TC)adUw5Z zGjYh49dgj?op>>5%f!<7D}zs~)g9CiBytI+5KKIwJ(9KQ5-h4&c3EHc1(2=TO%Eoo zNHf|u6BKrCQg*>(#R;W1Lf|m(Me~4j@Vk2co~o;q%zJcw-943Dca5Bg6s}WY28-Ha z`j{o*Fz&fHLTu(%HeJfOs?HFK+U=|Rbe{#k!oA>K&AeGYe&hD&^EZ^;6|R?-e;O5@ne!UKpGra zGzs#38u0B=EJ;I+Y@l22w{c$FrfB}TR2->|!;qfG!oxl>og9%|68d>mn4QWpPMrfP zmPI*xHA8Zd8In>4l9Pnre(7U3iq?=JG&YlWeN<*PwX$vgIyb4>!vsd~#nb`NuLV%f zETDN~y3Z0b_s%YPy^So)Mxdq&@stRkX3LF#A+zi9#7WgNN?Ii~MUeshP)E+ga8-_0t zL=4dx6>f0bfzvLB%s55YBMe+f?z1gb!pFVlIswgG@$Z;Z{Ly3SM^rufYtUI#N7LSU?4XO!fsrv7 zqoJf{Jzoz>_-cD>KR!vkfF9q>rFgZb?WQ@~!o?2&*=z{Ogr#KnCbv^qPbM=jP$1@z;(^bTf4Pgod?YUpM*J{ zShysQ3OD@0-d@_U47lu`p0k`F)x32wm)s!a<6_yD(oIm_t9r0 z30pUkb%Fn8PaC?9?I_+3JlzVQRHQHf_Vr`9(RCtE;}7t;{6jimWy-L6e2WW-xOsk> zMo{j7cbssFO^jmp+T)6r;by}DkRn$eN$iKo5g8~|b`VDKobhv!FM2HR1wr8;ecT@e zA>w>J*=MATuQll;4ff>}BNO$-jv8>vRm_VhPAA^aqu-Orjj2xK@qSNk2}G`k$Ig&i z&;WGhf$EK#+4nI<6du9j2osw3`PKPqujJ>*mO(tmDjrFGH(1E(q}w)Nuh?jW1|mZs zQf6zLs#0?IimM&mH}dxHQZ>KPAHRXGr+4yzHmt3yFLLX}zQy*BZS9dO%E6HBD*s=k zy>(FBUDqv$ySo$IwUNdh5;REA;O_437M$Qtf&_PWcMb0D?mC_4&GXK!sjueVsi~s* zqpPbpz0W>t@3q$EcQl*N=H=gJ-xy3JcIxoA*qKhpTrsyytWSR&lh(?vH!Ip{sEh&U zWCge~nBuQ8*;LZ^4i-}Cf0gzmVjBd;+sHykqHq7Wuelq;H)Pee=GQ5`GS9^3N%J$b zd+@Y@b#u5o+PpUOv|&`;)B43;Ry(XnM19?4{hC8O_eO4#27~=mg)DbT!LV#1v%mne z39mTmc}}1}oYo?>U57J{LH*vW?N`G@`5G zO%XF(ka3Cf_t)=l6*kxjepc#g--2oLh#*wB)@3IJ6*_sDg!9vNHekAnB&z0e5h*1# zfD9*@twpCpU)Xb(ki{qT^BZ}xT8_QyfUqy)C*R*@_(#?Q8XtM}e;fYVx`oM$&chb!@u~xwmM2TEc^F%*#>TZCVoO;)eeRTHKEPo84q9S!n zG*(qPB*t0FbK6DAf=`uOY_UeeB{#Iuk8aSCLGgLBA|=hT@UEKirjoQ; zV+l9q^#curev<;Lr1WaEBp%mXZC({&=me=e9NFe#O=wK?DX|RRW&H!WN=iq1+G$Q% zAfOj|5h>@av*YC^K{E6eZ)&AUdSAxVR=dX^5lFx*znQjc;1U8#>F) zJQ?*ECXMtbOr}~$gA=~9{XnK>a6Jx20=b%(Oy#3ib)KKU2ySY=9;h6POjHjtGX6wV zc?SDRUEV~GQ*22$QPV6tT-Rr+@2~x{E*d4by9WNVw*GUy&(s7bY$W*aO@n|3;+(WI zn-D$!BhXYeH=9YJEJL~odu9E8x_wRYzzsbenUxmDAY8GQmlZe)y7>#eEmM^p#fYhk z#ykTqT95As$Wg0G;Wi!^10`uD%ZQ7b8 zmo)5|S{++5;KFz0mKJtAAm%a$fzZD` zLQ@4psK&kAbz_QfzXIBI+<=tPG?Pt_(ri`kIQe&G)R58f%iHdI@!fJlcBQzetGqJF zbg~Kw3Iq^=6n@=9{wpORSVigNHa{XVy*T4P`svWfb}+>>v~j%(ZR7Wu{1443&mY?U zuUPZ1t;@#xS3mjR%F9d6IEyyRz>8Jg+=gM{z6&&SI#g&SD`h8ca2LgVmgPJ>#(tc< z9)>CVm5OyTQ=^4qNXWfWJK#N8Rw-tdSC&1m5VNUTgESQtLlno*6`RIjZ&=3nU2+Z8 zp^n2}6)XG+X@z&W*@&5fp+fg0=AN!TXOa+WZLMM(RitPOclm^esi*V?>4;fe6&i$% zwx<^y)sHc|*`HWxCKA4lo6R|3V&P}rY3VlHvZ#^qHrmg-1u13?DGRX)!8p6@UWyhT zciC{mmBX06Qtod0?Q07>HEZQ#b;YU2xJ9S?FgrJ&hso|+x2+-nPzc+oq#NAq+>H?p zuw0~C?~MOt696B{U$h&r7z0@!nw;F&~dl;LaNKF2fSj#$or{2nY9k zjMHN|xF%G{W>|=?R@O&@(GIW9_9!rN%2{R80GTD%z%nbT-PvyfqRd$Pk=Do2M`%4i z4Ch?yMH-juY>Lz{pNOW-(pS%SHEvV9!Dx_UHF-F}4>FmxlxFTAMY5B1ZO_8Z=5LR9 z-5ji14}(~fKY{CWxx)bz*o#xxAOv16^t15C3xA>Hf}wyD8HW?C=dBI~)4|8~Z}aHr z7-HJjv+mmx+DCbsbYq~|7ZiW6aqrIT7?P{jl{Xf%$7aS1Au*>0(?Wwu=FPD^ z^p3+V9lc5IWi+MEvDM6HUdSpo3-uA}FM%1P^}|4jow0hE{xbe0*Gxs^dx7i|))E=c zmcID#lCw?DVV+qtm^*(hs&^m<-=t;BwYQ~r(KrxdqugPw?4T}pp7$uy#KPU6fRO_< ztAG3KQpD%mMM#$#z$5at>^eQGcYy7#z|C4c_xH`2)`@CqCnCBswJAYXHn+9mK%8iZ zcR}}T$VU`qFKSG#mN^%Vl#shz`;URCYvecD(zoOrLNw<7lYqO zRF5vbHB~)dv0|yV)|{W0IDhL`_YWAAuL?hhb?8Xkx=rsF1`Y=5I_*E33xCU+TeZiJ zs_2(jn1jIU*$vZ2-AQN)A)7BW|IIqqXTS80E%}}A>tGaZY5=l=*IOl3RRT@r0E3Il z2Pg(HaxtY{@U#E268v1DCLjJIY8?%9EqK7DH zS^!<{puVC1V8$Gv3oev2?DtS>8(@=S+SZVed z+Z#&cOE*l+Z-R#gG2K(ua?x^D~|Yo-hUWfwei{GmqboU>)D?Qz8Ig z7WVJ3lW4j8&mRr(P6vhz_nde?y^{*X`11LZ%nQA}9$yc>O1*-x$O|v5tvbaB1A%x?LsH?xL+}m{XV}=l3Y_x`gW)5yMZu~ zZT!MG@b=g+LHd69AoO;(?)$Rt`+RvWG%k~%1ts^p;+KF7e48mfv+<9SoQ~oLGNK3> z`trQSH?fEk+VbMY?^a&Z>nbZGVfKAY*!Krp3WXiTjoExyu7|B7Lx{OC)PkRUq)xrU z5-a=~oyupM+AADIOgj!s>zd>#I-sjU2OqKZ3Y>mU-+KQ9{c}@R{Y|a+`i!K)$m&eJ z1#R1)ExmVdD_xuCk|izYm8Z0)KzoQEot(n+y};>BZ9(C?Pq-G4SWVJXxMO^~q0}Rs zROo%g_syQuy?EIRkCKJ-O+fj2KM=3StA??x_RGWVcE_vRuhvEDrj4%y-Y1`}ObiIiOjJIQR7M}gy~tpzsgX8r4f%yVTLBc7nL zP4Z+D_(`plj$+r%HC-hYydqutK9XL(v|Nt*cMD*pWc?dV5wkdkV3{u&vLKTbv|o5` zIkCMmw|Y0CV-Xct_)F#`D?r+#H(DPZJ$T{pQ++AeNqk$(aXSG794fZMJ}&-Dgp4fV(Bv?x5b~2Q;k~c z;y5)yksxj)hIfqxFyP@lM-aBtL3$xQUO=FLZv)utjVX<+5PAH5Z>$0K6EfgWz7MXW zqn>`FHTN0mkeD5aQPg+__`h;-Y+Ep?lp25KVJzd&eDE~n^U8Z9$maOmc`oPUi#>){ zIgO4(FnI#GY9a=AY#EEX^9Yv8|1C>9_NR}!91hrUY|SN}YNt~Jr>#J9U$q>KF zuQAnp9yaoW)LPINpMuyn6mKU6_-6WRser9qGxNQW$n5k)W@#*}fa7>Z(=m=eAvN9; zs}o7Bs0N)d(Chh4W1KM!a1J^FkodR?3ZMQ7XcS^Y5x!U=Dk)Qw;u;`i-AZsOKI(88 z;pH`PT^H)k3?{_}J{o#wIy;|dl5qy*+bYJ-~$3I8G%cm|Ca9-h=htr0pD~;|BLNJd$(SbHO@*)Wg*&>xRXP zLJ}eg$5gmRVjTz>Ng>5YanAbkdoUh5`dcRUFdARddvg$xK09vPgKT35>h@dbMflxO zLnlW5nud?zlX$+%xXuJdM+{X*N7$u11fN|HG$Gu3Mxo(&$k3echj)+0J$2}F5Ev*4 zlu{$Y{7$T4130Pb@t^*Us{N1@D5@^~=Xjy=9gc#7tzw$KhBuYbou|Cl^8nEv`VaV` zR-kJoFTq$$^4uxYkROGM$Vk!ZZ-gYFz=uYb2IJ5bRmn+W@zo9_NIJj`+~?k9^*WHp zW=!J*r#_YwCAkndC&t+IYgRjs<3a;@cJ9@tTKzGCP!Wl9R-(&o!s?T&4pJh2Zkh>ejg&o2j zYB!bNBLO31PR5}VFS7?d@Q&=O=g7`Ayq}gagL+cZ(6MK8gO>Vk5_KVOrL9M~qGW=+0;N9j))zMY@ON&IAWg zSMncZ=Fgz6nEgLO3fNiDStJei)xf-&78t+Yeru+fc^%Xvz&AjNyvE~rNPX}jEs_#P zA{eN%jZteDMjyzs3RkG#Fgx4FCsKJ@OWB@E21Cl!hYt*uinE1eI?h{%4JBUQ-@WMR z|3OUEW+WCw3zkb}%9A3^bM`TEoRR$3xS-U1l8ZpCcAGgr!{}fI*mq|^VPkyLJ4#bM z`v~=di&SuSDq%lPD2Nwe42ib~$@RtMx%&>&Grz;2c=IRX>Bk3G5~l9&{`GyZD~VWm z`x*ytg*h+Qll`~kb{p@lp(=7chP;JUr-JU8hCHV5h4A~vUJC7~w5BRaUP`0IF1HJ9TpM}422^LW?sqtWs>+!S?&7_cJmjZt{&heo2` zuv8ov$E1fP+U@?QgLwDxblS*kVeKTaRWwdG<#WoTo+7}A9LKA7w1=FgX~7n%dG-dD z2m^ZN;vWC?&{gekGI4vJpz$HZH^Jbw;?U0kJM@6*=dk#pCn-Gw4eL+Lx&r5@mOI{t za=BXF9@ufe&C<;oCXH-QaM6KcPui10tGNnXu_c97St0u_^83)<)tE^%Y>ApM)4c8Q z-ld>xSZisqw~|W|Rl%FfNF&6uNAfblsg%iv4WMt@#9x}tn2H;CZ&v@a$XCc4PDhc; zGHiPW)*_})S3y{MG(+yBqRFM(H_%B;@V=kmnBa4%^u>S>W|OvvqHt1L%IqzZr9wgF zqS+YoS?Uy{sv#OV{Wz6YIn*0(l40lHKD2-P6v0~X`bUpTINd;dxs_I#Id_HvRCFt$eb{0%TnS7jE+%OFW$oI0KvtJ<#PyQ z#6rY<<36#_dIktiBwC}PQ8wZti2X68}GEYnFR!C>-5mgTU7 z`5W~==Vc#l9!a8aIwDK-b7U;>)N5gxx`Wx-XnVa$_(dJ|XV6lJ56mGf5A+v|VrE(} za<@K9+Qz`ec#OjJd6dF^&ncWurHka1Gm;6a3hhM(m@X&2C9=Aa-Ymz({SGNAWaB)^ zoEz1k+(>fY=mDKU&@!LOz@?qSs8E`2Jv|dWr8N~j%te^iR)|f`t)r*a7lcCwCf&n82BTs$cM{yh@+un@`4Lnma4J!>2*ESzzGW1FdE51f%`0;E{a#0-Un!Pr7KUy(}r}CD?g7y^L~+ zVY;||;z&17jBkhrz2cY-zF*i6eqOW{kvh2v|%W{KYHV5 z+)zJRc9$dewg|r9Gp2jlm(H9;-hF z<>kS0AE5dPF~SEvu+c^M z=wTd=Kznv(0jDQxwX8~E=OT{nZIj9YWz);i^@!(J z-r!pHopQdNa?7%l+711WX@v26vPp+Xyx}EjuQq~-6qknsSYMxH>iXWk2d9JmzNgYZ3?wFlh#2Q+A~KUv**dn9bQ1^yw?Z z&N*aj7}yY|IJ+e>T~~3Y;K1%N1en+0(+!hP8zjaqi(;jsdI&Iu{7o=^rZrI?XxcpN zI2`Z+s#s{Ksb;@DM$vg$?wX-BVJxb$2SevLco!F}f!K4@6d!T@b05*bDwQ`?u0^|75=`7E>-)sIc8$ zri-*>hQqwJ1Gi4RcUkoDjnghKyvRZtK1opNqiPINjEBj`*!oyK;-G<~$|*a7;=+$% zFcwMXqB2k`>u{Hu!aCZsJ?a8|m9Ej8MiOrtOw3z>RQp7K@WXA&wCpyOs@-VQvqNg} zb8D<5oPE0$l1VDJBF?1`wRER>*cLV@@1Ijy|5qgT)XI!UsqZv^Z!PE?IY_#ovi7J% zjPiz2Pv;!YGsTCYur5nQ`wH<&MFtMK!<5`3;-JEO-WYn$zRl%!Ikwwo%^vzZppIvt zXi)-`M`%6vfGQYCt|e2Bwb0~F4Q1du@g(zk!$>cgcgpJ{)y_}V#xSzzTg2yiiz?qS zjl1(CzOuT;d2{>CqHT}rVz()#+j+9~@m?|Q@X%&VRC(^=8F2;E{I__})t>Wi+V)M< z)E0)3b(2rb85`u_V#k7@%CvAK*ORqV8fQn)-6X})4=Xbc0#we|%`$ahFNPzYZv2;w zWqTV-Aq8JA0IqCn1)L&I+*@7{5l-Hq-Q@8h%QxQtfa#$^kJr7{v&Zwwa&jFQVl6Wn z5IRl9>{D<~%WNuni}=307C#Hk)3R9JZ=`T)vMEZ+v>=vaKhWXFS`-tt{4^*R`n(HW zUq*Ga4tI||1*Ke`)n9-Yy<>{Y(OGP7PpTtIzp4eS$QpH8*lUkyn^)YjY}($b0=TgZ z%z>?tdboc@POV>L1)Y6=)1(V#R`JVUXdXN{a{1$o+*3FAkLYsoWnV#+i2*28`@P_kp&ZUjTXPWEESNh*NUdqWJa>)cO`-v7pIdok9Am=AI@r??m$Hz>%8w>%y z+Zc*mq4A)%*b|@pU7Ja&m#^<|Ew~8f7%st-Uh8m+ndthVA}haUK=@I z2&VcYWGx|#>hr*2o*l(X34y3v4*vQ8^cJdN&K7mk6__NuG&`M;;xhcAg$-<~ast7s zpbbSB3^^J56oXY!R%=DEh-!6kWfpWx<_N0(NiE`nzm?<-ydcduXJPp$V2~dm0)zr# z69QE7q}CB_BCa!xw$enYXhSV0bi1S8RONPVP_ z)Iwwibm;#55i!d8Sl;^>Rr=3faVuZ4LcvXvCAmqlctva#?m&(ff4$sF;@K3YMWcwcZ{C*Pa<#=Tovs4v_qW%@G zQ>Wx*?T1f3Nd;s^oS-rd&I8R;``g*VGgUkOofSN5J*m-TE6ZoAN5J;vT;Q2!&@cUo ziF#QA!XGDI^+$w1)FEK&bcR6>bdSH$D{0xBYlD7MVfb3Ao7u399hkJ9Ufb~%!?!}z zbqXLc@$%|wTcEoY<8E4lRJBO?eDCdTVd=i;XdUSRn5#4o4QcC2Ypw-B2dF|~j+YEo zY&P`~8-&xya|m8pW${LG8D5!rsXI`U{1i=;&|1x;GV(*)WveYnF6p27%c-*XIVg)C za7te-pQ~{Wt+c0Qjy`-BPI5}-75L!nJ+3R?~%nG2?Kvw+0D=*Y{L2w zV|eu(vuzQ<AolVVnt+?@l|B#0qNQ54H?5`ennjhs0dL@5jlU=bscLHGcCejti0La4fh&n$)~)YZ`Eb6gt`S%;8vJoZlD?QN)29n;9QdrLlG! zs$^}wfFn_VtE}CWS)qY#2{Z9>%`=(E66AGq!%h6Uy)vRe!7afE_sOL6K`Scrv25YI zN{`8j$%2UeSS~PjE)4MrbdV%~72U@6ULv9DTR{g`x$p%t$#n@6Kbc8qV~5CMBCEri zW@#^5v2gpG=x(0AT7WwIKlN#1GjFQhhS-uSWbO*=Wf#M*@0aNDd2zTv<+bbjp>Yf6 za`+22s|SUXDufX?Xj=_{EKkE97nF<#Aj4`nd5UhwxOEA)pI5LC*I`K7293)bElGK43q*x)HXh7;wbrO#j6W6yhi^ z`t~|<(d*`Wp!f%o=IU`4+hua+v{^E51nZ}g$wIMVuDIzec6pf`Xh6z@J+LC z43_$8N!B(N?dUO7cAt+uxvL}89yZZr#<)pqT-m79Cw+pj=8>VU|D^G0NCK6OmZRdR zk|>L$wEYSoC^p_11>P01axR+m(Ww!5?L^ZWCH6v#$@%)sfifdOy;y|8 z@_28JTUeets_?K(FSG>1cr9Dot=-2d(BuzDje3Rr!9gK>$)v_;t}AMa&<3TmRg7dRXW9y6^w~rjNo}CQ)Z*hb!_H};u9f0+yl8G^x zb=l-P=+@~tV35!k!#@OXR#ce$VpMV;K^?Nq zFg)+fX;oZJtSHyslSNeWGhI>_0fN8BeX_>sLGaU!Y0p->4EJG4&Ev*_EWc_9Z6uBG z4%PbnCq>5Fz_l5Xoxckq75>3vwZ7z<_PnV2!UZrB)kkPssPFiS=|H#iBAYf@yGF@z z`7EnZSfi^yqJP?+T6p({p4}h^Y)1_!qnum|n z+dvdE#}a@;*PqfkB|M28#jN{QKuxhU)cL%(Rd#^%j6(R+dqYplZ?8V^Gu)z%G*_o( z%_X61C!_iLwzHNAnmyzE%Tcp0`AxJu`)K1OlfACIJ!DB<`8cG?g!lFue3!SMcSA)3 z!w1&UjHh(AjfNVSl@eQ;Cv}5N{#{INaq7=`t>-NKryOt!b4zJ395eH2?ISoSMNpcE zPskHIBh|$CPQm)b5($icUetiSiF5wCPgXyEv1$MPuAU$}QOyGbpul+VwH>IT zqzR;b6cmauxIk@tGeY~D8rQWy_4)S7yonK}RQ(1oP~LajYU29^l?HiFUvEa37;}qF z!{0K|h~ncvgV-DS(|4Q0z;pBZGBD(pOw2zGcNv&I)+mUKAZZntFLaq%dcf&v(W8ya z`*T@%+s0XB;(crqV|+AeI}7XTC%2?wR`PB4k;A36Um ze5}72#Xt}l|3Mg%cX}>SSTX|w_eKT#4*z5+K5b8IxBdB8j(UK~&G4-BHmpYlolc*k0ToVVYG+)zW1`%s|&d_AM#lOU@V17+n1 zF!0J}u1)#KfT z%4yLA3tZRt|8cTXFx)tg?iWnauALCVg$%fILk8)d;9K! zD`tT1)N!y+k1twc0>`uZLmqcg9;vA`bPUOtq^Rl(3-IHI%{Q*F?JabX`T|gcqAt_p zQv^YPq3cxVygC+xEHcFN1;`@WYF|enPZAz~PP`@B&{rlgw>G*mmORLViFg2N`9~@> zu3pKpb|oohMn*IL9!=#i%MgdY237v{dKL?C1S{=sHUPQD@F7z*!%~K~eZjayqi2Us zt%xJ#&HQkzou;o4Tz}4&dXU1=Z1nI*V_?mr*OLngf63kLVLZFA#Qu*0q|g(W&D75g z;k0km+M4twRa!sF2w2YaAo5&8nWL{av)JY$RQDkDIoX0&(4yQs zGA}LE7a9SJ3VnU5&!{~Gd&ZH+9WOCQ4>jbpdW^w<&EQunvF9J2)6?7u|Jv1?uO3#d zjyh``ejKiim9KoTn>6;XB~sX@^)Lb2w5`WFZ|kv2u}xXp99Os*a`VBY7xzqA)*oua z8103f^H%89IP?qP^6Mrc18e9cuRwPGmwWPC27AovFHTQ#_nIGOs`NR@-UQXR1JF6^ z&BlJGSGDLX_^1UspU5=qCR$4&xorMX@#h{eoPoX5JM^Lk<_e4y9EA_l4VTyRT~N&+ zCDW59ol5sucIt}~i|$jwfAkB_uBU$(IuL$=55bDA6cPtdI0sA&teq(g#K#3;wSUNC zE|T%$Ct}E|q21?;Z`|cef?iS^Fm23fUA()l`RTL84xNPUD72;vf8$RVwUn4$kH z=?fmf31}}%xw)wP{tc;*UaW{dSDi{cw=lSD((z-;W1W^vEt%Uem^*H-rNZqg7N|k! zt!z<&B|M3rDl!BSE#40JOXR@|4-EsI-Cu*zV$4>HdiR*D1oO%;j(@NpPhKJ%=&VSo ze{j30@)u}*{Td4by)D;8)Yq5iEqJifgnQ=-&@JTjjExPyS;F4jc`_2oO!vUXhi9TcLODo|YKW$4H9}f7wpukF zUES@POM-Cd1Ort_?CM|Z`m0*qZ8CRt?R=PL=v-RehX^q>(nVJA-%~xl`ZjfGhFFR5 z*aqB=_Y=R~yB+BRrB=iw5A*3Z6v;u2lThdBT8Q6Kw=>;k$9T40pW{49@)WtBMGB+CK#Sy0&Oj zC`Rk~sphQkUKAb(gQZ!JLgwm#h$A}eLo+Ko=bH?E6zhL{F}28Y59d-Cw3z7LNf&su z$X;tQ4jC_4jj}JS_>Lw}c)+qL7Ic|ZIoky08M-kugpP5J2nmd!t*KK5zvKA{c|Cr! zi5rEI!E^I?fx)8^(dk8e${rv9O&^%bt3&i_;gTE;t4OyJuG>l`qYi zvKQ5@JSrsjUqd0(--HchPhIi7w|Q$I+EtN|{Ya9HVo7D!y*)lx(!Fi;!50|~B6#K_ zJIe*`@>tIy(NK<2IVJE)bo)Iy{hB_+;nFF20+`&`ku%WWoEFXOZEa6IE?N9Uz2tpwBVnn{b0V zA1fEUyN@;f+m_9lO(09gVY2tyvvSYf4AfqXpvy2aiQd^gRg6eLq{uQt!z<$4gTxW^ zD&}UHqg{BJ|B}i&lb_nP-cy2Z-nF|D)E40FX4;+5C6{1wjHD1oRbFPh=Q_G;r?&3d zsF@7bZ27jS5$f!2>hV)*Y2m^Br(C2wb zQook&=e1X!gJv}zRPZCgK+&}9{kN!gYu9{d0Eq)EwGz}OT9|Y7@iDA*yKh0~7`z~| z?;7fPhs4w{+o4Van|WcHjPzX_pyD#}xoJw`hzLUy!$GE-y?hO)QV&yF6y!|YQN<=d zf#d^OWVQ2H=Lc!abdiYfbBtw3@wVk%XEbXfhUN~5u@R&af*l%p^%_vqzS_)JxpA_s zl&Fe0Ov@(l3rLDGv$G?NS$~@#M|De8UI3~ukf^1W<%2;ToQ9=>6^-z@-u5SJF^tx-gXdXRD{| zpw2OFSwq@LIEei2C7+z`3wVz~;Y-$!BJ0!}t>g$FJM*me`|4=HTbh2p2k{SCL9D#P zs5;Cm`LVWJ>GIcULam%DorN@8i}1;9GLNod4`!%_J)&NWa_Yu(+;&= zB41V7Pca|KUB5=rYrjPC%UZ|B2&yOrHz^uj7b}uJP_>5Fx(rfg!2mhUZX;=M}P-Q|!;2#t=Tly88o(TQ_cH<(fIeri`X<1C>3{JgAc= z80Vk|vAYdnC3I3NM;GepOHPIU0!q$5E z>Hb9>FG+F@_9i7mO;7uR9NKhT93J2vL#}Uq?d9|f)Pl2zj$&50eVvWO{!jF{CZyUj zpkzVeqo)VC^dL9vA8}~M4o`j>{_8aW`yLI`1`9<@W#P6VRu zZO-tUN6SCrrP1iXVmi8kh*bZiBKg@@tRAC-TQ;ZvHXfxWM6~U7c{_R3lZOzQ%&Fh; zu_~8E75q(P9z3YaEroUbLKt@wV~{k335xgtYc^OfefUqGc6c-OQ-xFf%cC1qWee5UR;k29pwOG_Y-g z`ndn@by{>?=7>$Eo2Lctf4vD|WdI_`2UB!FA#(_fo8r`W#ma?mq3(I z3)}h;u{Sjw9Yz!v9vd}qJ0wYhg-FWw^@W@zMel1~R?e56O(kP1oecb_%dU9GU!Xju zTMHo;=anIfy#heKd@yYwHh-%dAGalh!esfw8owFmiU^tfUXvj5)i&t7qs zHwKv{LJ#Ek(*zy59J+Tp-inWT>K@^3D?wQrp^%W10!}cp#$bACdmR--lpntQoCq&E zer$7imG69t`mBRbR|cwp=>|YveZU%vd{qD2#dKJ7i3iCL!{V!0<)#E&7ewHMrcdoe`4R>3kYnoTvC1{`75!mER`Q&g3q0(@GAdc|Uzy z+XPUKbT!>-s%v$TqkJuM=S+=Z6;|EI@$7Id6;VFg?&v+#-u2HU#krBLtuF1Hs?#`n zallQiRWr0Cd<7n*ioasQ`m)*}$tOp&E5eoi*oz`_S2(Xn9Aqbj?9dgqhi-hQk(S{> zf2mBK&*-zMb@939rr+Ax96dRl6|)z+kO!`ib`sLaFl2%zjW}CA&r^F-IBqwZvplv7 zDCDio4fs67H)V$J5arR1ivb#J9~~8Ku6lw=b=h72qv-RcE-yD+R70P|6ZB)L!-+S4 z3x7t_%$cL&Z|(ggUI)r1wW)EDawtIU! znb|+PW&p&w0$n;3-;&`fmlfcmqI!_5A<-$`8TQT!C~)*|3UL)7jgHA#F^3zF4RvdDO1 zRio)WARy73DW;GDrXo}Ag6^{qz)OI)8Dz#&g+z8IM|z!z8oDD$12&H{k~b|;HNP`_ zZS57KCdg``pU4r`{SwMTau;B(5I{F<0O{4XgZG10{)gY%-o?L}bKW_>j0+Oi7aZLj zMsgqqgp5Cv;vxA@C9W49;6v<^p`A}vOrCGrFIq!rlv@kK4H@bt*gO8dNEpyS?qi;S z59dg>L#lt258H--8>TvPf3yJd4iNZJ^nw6s^JgaU(i1n?_&NU*fKfUV7&RdX(YL4K z8a7}`-*r==qLkPN9_9(6^izsT=XPN&f5$msK^j(ofgG7NRc|`K1Lu&}7j}d1Qj&!w zvrT%#4X!3-($v%(Q&P25XjXiiYsRdG9BNe>-i3uoCXy(zv3o{#(|xAzgZk$*Z73_m zw!zL5MQqAUFz6<-NCOb092hnQE>l$*ebPJXO#7`!mR=O`3FCH6LENGuTePD5IKG``<%#%_MquqsI_v9Pk(xkHf)q~3I=7Z(^V+^ z?rk^F2T1!f(!@!W!)*0KflHE+@JI|O0c7bR=Jo`6wf(XZ<7hk`JX`&HdBe^?ovq4L&nOb(p0c{TLkb%kI|phP zq2MB1wykK4xWha=70@CZL5qw8T~Ou=R<}b*KL@p8{X4I0aucOLQjn7LDl_Z1Q0@5R z^SK(Fy>r-Y@W|OLd<+=#jo{I@q)t)+NSndeJ~P;sofonVV$L(oP8dk&1p*B9FA!%; z6*lF}Zcd%B_yZ_7x z5ZQMptJIT$J4|)XXt&z5@zL>Z6|~yaEbnsda$Go%dQiA`tHRw$p=VXtx<1%-2=JT` ze!dZ{;*NV*YtsI7EhUzi0kY}FNIDn@LMv_xm1z#BZ=CVX1f~JUz||hIgPSLr8^$Wm zKp$mGS3ZeYu_;TJx&gaU6p@mT-Z|bXMl=#vmz~iXk^W55psD6Z6VRuk##TLE4oCS- z{89(xJq=B249kJTb@`PkuP0%Q(Geo&rH%;_ckOHTK}?n?MqJnas6l&#QZ;j4UT!tp zm2_i>%naJ)%XSVy@AjhY-nl$0f0N6eGi zgk5>7{iPDpaHWmWC>_J09WEtoEz?E*Isib6F z>Y-53fn`Zy8%h(6(tFGc)rsQ_RfF5JSw&%*@Bk%BP<1_3)m8o6eP0COu^L)s!^8D((3aVHhnMLL zFhtwKD#?8vgGYa;`Y%DYp3olIK9;6XiPhu*QM-#>5F*QEr?n)W1UXwivO%2&>Q1T z|5$CLG)7VwAK$V8v)kc)vf)wQ@!Zz-|G};1$UuFwl|HWiQ)kqXL5PIrTHtLyKXxLxuJH^ni<`Ak)$BEoBKZrMn@pUSqU zPL#1jJhDBGyO(Tcxq=OGtA$n1O6c6a6w~gWI^612GtGd8V)W=SdTeobN5;V(hMyw? z57CQew_slyd?p7u&)p?jd%a-bxhvU*aAz>i#{MJYy-(GtX)d{?J}Q%a=*QE0%1ash zv=0@;xuwK;UOk`pxj3!6H{kJN3~;v9ZPY^94o9S1Nb;fkD8@CS0dj1Cg*i zg&hXDY>v`9g#Aoo-X!jDJCu)9dil3kOVdFw32C-}&*hS-f!A)m-GfX9_rjE*HHMrn z(;5l-ze;(R5ubNrsgs}VCeON#Jw7%;I-d8&BqqCtTY@V?FyOD{80kf8Tnp+KLuWk} z!&5|BqbHNfj9SeoLSFA@i8IR!nZz@$e?y&`rQ^*TsQU$PhowoLXXqgI^IW*RQk;}YBUzoZ zdR>2J|2`q(+nta4%37u`<6r0qI?vD2eca+#>iSq@za>3*?Y)m#xYfQY$K!2Et*^BH zEXZw=`svpVhX7^^=lqz=q?zU9fiUA?GA$^nX1#vnZRHej;{3IJ|Ige?DY0A zm)%wb8wWnO4R@sh&Wb&@I?6r3Rumse48LUr+Z*1_JArF%y}0t2r4kzwb?JdcPtoPCl*`_f4*h>((z*Bj)t!mD@gG5V&*R>hQ&y~yAIX>- zUJuHC(!mQ0L8mhrUegkq)-vs$q!sd0pOg8xQHPuSQE{7I*7vkp!p^m$DnC&_86uLA z&Tk$>qSSU?d|ga6kHr-O@QU6K!ejZo09J!6B_FmS|49~X%|MWEz`OKHo2U@hn6PH|a{au% z3)Bczuw2S7v>@u?EgYAbC`OC7%woJtY~Xs4f3Ggxp!(>tXpQLoY;5J@M(@MsQu|bo zX9)cD^b5ms3*UilKJ72#35nEmOT@ zx37N^@YB;@ww`oPDlv!||4u*$Aeqia5PfGZ5b#j{_Ge{V7j7#*TyyRE8-C7Z%RX!C zl`b6qW4g^kY~0G`Yur>(&EGv19FY|lGlyrwiD4Wp1QzC&rax4Q2Hqf}7>#GXW7Sha z+Gu&$T>I7%2TjC<;Z`ca+YaYpIsI3HBj1{jS3ZOFf7`ku#QB>;9@Z?{16)oh>9pe_ z)d98-p#0v0kmUBU_LR!uH;i_in774tocD9p&h)APYY#I&UBbI<)t<4aHo(}f%fMLE z6U7y3)_pCa`|H#dty|PFsh&hjgrbe1{v^B0`<_0e#}@ zz@+b8S5cSL^+TZm9qui^eApcfsv7LRwv@P(HeUZLqcQCQ(k%uIPmmKj3ln;v~| zS7Rw&0^pWj1J};qLz_=5>ALjUkml|Oi|=^T#7(^CW(yXlTIBb&#|HtQ*PjrbZ5qq} zvyliZ^ZyFd!@~1_jOj^LS9bWziTY(WI`@|Xs3IZTRMm}$mj+3rUZAsnVMGKiS!l}HSXGVXCB_tui+V19!RWh=k6lB-n$?T=RX;hAM;H0N0r zc*;n%BbOmYMx6MX;LKab zsp7w0h5hq|EXgjoRQBtn#|7z3T!;calbOOe#L|xonhmrT*TZGoTsuBt6?gJk}?e+c6Yh z0+=axv#kZux+v_Lb>^8GqTGwS-bU!2CJ%irA0FOFbh3CY#jP208rT#pG!rcb zNU511{r*ONoMP$*bm>G0z8aZ-9+V0%QYw+2xC(MB3I$}ktv?2*-G>bmrM~^rqT(c@ zTOzBZN8{Kyy`}q$>DJ%fH@-kJZ4Kt>^0%J##Z2=ZI^gzSqdfkF;&;Z+7G!#2EVI<= zqfyOc8c^JDybK*M@oW4KW3I$6gW0dy&VzuRLD^hbioGETefFec$!FyU?OFxK#izAo z1aQ%r$yBK!Hyz6P`t@ln{7hU@B}q_z@M)%4C=2%;RXNt#f(2c*B>EYmSBjO8Z^}}` z5vZ}nFyM=?FG9|}9<@B)`F)V0k+rzKuxN=v^cT3!`Ny-OBIcTW^K4XO%*ezXZw~~u z1|yAaxDGsR8U^;9ib*;%J8Wo098nYNeH`kESz*LP;#!P$`2p+;R+(H17u zsy^khQ>NTHDD|*Y>NXB&IHG-5fAkp`APAE5)aaw|%j;8*vF)EW32+vun1={7XT!y~ z`6qDNyQRofTs&b=R%|RMJ7-iruxgZm1a6;`B_;a%NQNYS)0+bY4>J)GvS(-EmO*a} z3fZs|V!qlT8Y?U)EZzJMR}?$niR4CkwBG0~fp>UO9^Rn>jUb`V1U1Nf$EmOb@P?43 zqN(j!>TZe2K~U{Y7-fTI5X$Hv6Py&lj-KVwCN35iAQQb@%* z11Gyid&3l0{0j%!X4D9{=3F+~q)-tA$~EPE-MS)iXSQ zbIRZzIWAJ;OyLI(1|yKV=s&|<%+u1$t<=T2FPsNTUCbrAvK{x#R~HWUA#2W4>}M}> zJNnQfvm)?Y2OoT(qqrwCVJq*RrOWwOJ2ddSj`zEu4njY;1>g7jD;*X5Rfp;i2kjt) zmN7j|sq}SL@FeW7I#6+2g%PhPZq6>^b^}kM&!HL2ex41s^+-G1d82f9_ZITBWfcFb zw2chCtjo$rOcTSMN@4$2n;m{@>2gp zfWCiz@A!$**t~}SzZ&}f&pnj>A3uC{mjA{bVB!A%ipybT{vUBUY|Q_kZK7Z^|GPU> z;eU6BQUZhO_+LHQ|4*0!HrD?mcPRBQ=8c21mC^sHH54oJ|Afb3XZ;VshU0&S$N4%g z=3wjKtm{XzYhL4&nPCT|2p%(oT9#91phBC4hQ#_ zx%U6oDGE$Cm#^VlXOiwczC^5{$GgxChIT1YAbG(x+~Zu;DtOs!^E!l<*59?4jpUw0 zX&@>|Jb?AAH|}%q$zT-Y)1xyd?&#?KDd2PYI)M0d_WJIY_oH_&;O!_NKmPNzH~#aQ z>EpFlXw>E7a<=zva9Bt;FFpVD-I?FOL8x`~*7LnxfA)O~Lg4-99^2}>wgt@oQx*LsZ*69_>7@YdLjyS-T0N@(fS`^isIyZ7w=%p>q`&*`Nd#`CQ!@1edK zw$33@$MV|$E$6Z}*pGX+cl7M!?zZRe+3gW{L-T5aU-qUM!N_|X8|iB&k>~H%XBVvY zl`V#M`D_t)J8vAjnzGy3S1(_K0Q)i>$y;IJ@W->Gf%~J&Zg+|gzviRM<=5H0A^4m; zA+9{xFZb9U;hFS&1oFSlv<(hy9`lF(?>q)1RTS?zvn}mH0h?sfr{FiUMmB6?HPh>6 zLNQ0)e0i6b`EuAV6J#6W#9Zprsd=2?p>wm=|GC)hlP5QU>Q=ymzxHufZa>DCXtqoN zZE3q>ZA!1nNbSPo!q|W8-zD1o8#4fe6J^1q6AjRb9$XiV9=(MbHjIg1)*COl=c>6B z;;In}xcn-$-6u-C??Y6N7l$2mXNvEBkOscZ5rgIL1D%kIq&e@mYWp`U7(mGNCY3t)1$;BD*vGha7@m>X_7X7DCe zN17K(9OF@hjd$L|4|IHg_Ni@t{^2IyY}VDjimJ)H(BH zsTB5R^S|o5A8R|dxl7OX#*;kn49&*}V9S6E;j2Bx&{XjG`s_C3wyv9U8+x#VA1t=| zpW5CUeDV2v>p}JS3%iRC%Xmy|JJqn!M!8R_I5c{jp{Y&35|8QPckC%_5ncq*_TsL} z*Pf%3vP?7^0=O)1mUQOC7l`-#gjxQ(b>#i}+Vpu8fhEY)y0;hA%TZVd^r$ruDr+Ry z{I9rLIeg-nph3HNy{|J~$`5F|@^E(|e6=y4BDq~l=Lb(=-FL!sJQMFtSI-rC1d1TG z?v2dTC5k?cT${GH(c>5PWW!v5U{`Rg~p3^eY1xYk)} z#+7mk4CmDI-(Qg%{fZp?OlNDik0C`Y(q7YVcx#$9ApqLbl?01q#m<%}5MN=V;)RfzR_JcYvLVI;6Sds7Wpp zdzB2qwR{a|0YHMbvF50-!2`PExX`xHmT*Kro=P!g*dWOGinEjQ_3haM6 z9piBC$U`t$-T#pIp{_ri#5_HYz1sR4%Nqn4IGVn3ena3)7`2axyUhGq%_+j_iw#d?p=Fm$8&y8CWhcJICN`+nH2v6^ zv)lBXB>o8$*EBW@Yk9Oo7NE1U|gfih&C8RkObd};kB zK^+v>>C4!+>(LWR=?hZSQk-KnC&^GxkD-he7#2*uE5!IQ+~GET-C3X-c|sFuoj8Ic zQ_L*qR>V8*MlMh3>}h>oFY1~hTe>D#6NX(ONup(xbY7}sw*6S%0>yQDBUSPE^Lmq`WdwL>2^;^p}9 zb|ju`4Tl`)h2ED+0~oEM>reU+wD%in@z5)tX^oupNE-QsPj|q=QVdlBd5-E4!IlFs zqrL+L0$bSkj#CtFagaGO909hVS#goY9L6a~GUGsE*5V9tlGQ^WzrLSD%>TA{eU?0i z8Nfe50~_4)=&O!HPV$V!#-K{-KqD1-p+NKLPczPvXH+yq`R#2a%8Lf$V$6~8BLNv@ z$lh_?nVJ3KKFt-Y4sNV+lQ`3~@91avoF3Y~#*n=d#|F5h?%oDO{YF{dwA#}UVuD~6 zu<$U^{f8&JjOK?Vejc#hFM&Phx(AYX^ALs!+KqDUwm>JHHG)nhgt~hSZnr7o@{eI6 zHv=m64CmELIg+&WIunJRG+kjqQ>I0vtNL;smUAkLLyR^WhMl{##9Pws@tfsh!95f= z{;`{GPz@o-K-mO~{@io}jD`Gc4qZIq&rQJcgMhQ#nQ;q2=C%s<4Do0>eh z^<`^`oe!{#M56vt{d0{o@$2^SL*#+FyW(~jP>8I1GP`Gb`&_vvOCvGVCY#L__`Wag zVQ@_rhh{=H7bTn`{z8>id-A1(q4^&o;jV;`IHNs zR|^liW}F&5$6QtfEUKJ37(}B?=w*t@ylzoORQK%_=C`qJ#SU*5_=+1633!SNAqaRk z&8z~$VV{nFarTqYaV*f2`94K`vDuA(?ESbvD<@WTuH|`I-gLl7Fl)^bCgD4T1J&w0#TlYj!e}ro0O*3uu#-xrzwoi)v@%pZ zzl3yY%R$9c641eEFcI|K{$N$$r_!z!5uI6E5%h731?xgz2=#GD{`K^Iqs6hKO|XX%Ah+MErL?UXznFaUrg5zB7Y}_id`t;;Pyw zn#4%Q*62!rmR8u4r{!0921$SVF>Y-gY?A*>TqdYG-2tGv2Dzf<|LC*-#@d<2%|qDz zeT{q`|2aAZQ6E-EJ+c=q+@L+NfTLO&|uE@}+7rY<$Q3x~?b zpRR2!23f(t61dO?rLS%P>7B`k z_3@DCj#iB*swpuAy&0a)j^R>k-5O>K7sUvG&3odL2FUMv5^jTPp*&>qb9B?qn4>et zAmZl^yiUg|O6c>Urvxlg@QOM6tGG-(I%fX>gm}=b2NAM_Z);)>cEp*|(0z)qmHNe5 z-9poI=nC{ki@Zqm-Kv?eb+a+v!c)Mjx(MsQ=uv?{8Z-a2Ep@a%m?039XkzJoc(Sa1-Zw;co~ zF^tr58E*m;5L_%|zYp>A$0Ha{)-T>p1lN8~rEGH6!n-2jN8#U)+kPE{nlYxKR@ah! z5G&!|(pcNQe9xc1hGFzkrvh3`_&=Ip-vop)vGE-TR4QKNAyGYRY&w}Ob}JfoV%U~p zYAuci_hUqt3tKnq!E))pJ$nxojMz11L4ShFA_xa2d)37zhXcBn-3YjCzu`%-Bf0mv z2HMvL-r3sLeP5RYaYSL9*{5MfevZ3%C{fe*7wG!>XU_BCv}8h$btED;9PV4hZm~b< z{)Mp0a}nDx{pI3!?DlCdD~G&NjYME8yi6o=Bb{S?X3lsE6VbN*&ZmuZPX0|?@F+`4 zdb;9ma6po$eWVP<5W;%oH!s6p&u$Jvo7R=Qei4-AB_K^TbA)(|raG+N)V$B3(H_YG zY+S=Q3lXGp&o}%5s5%A2L8yr}uMbNT>ux96Aw^^`WORJb^vk-m`G{k{ZF~2*Cj&s> z^sPBnpSQJy`vgxBmrqjl(K>WHA4WN8-s1O_6|i#q9kk(uU&DvrTvQYzjV$=X?8w}>o3$G-Hr_L9lGB%VtZawMSYY4C?Y z_3cUark7Cx)WCj=3rIS1S2;aV!CNp)T*6~}63@3C1HOVTxPYG|{Z3p@BGuAP$X|`% zfax$O?RQ=;m`)#WCe=)o32s%?^213ppDemq7s1(U->Gd~@8RX|3GR|WpC*d2t=^h< zz7rU})g?K6IPf_WFdakS5c?lyu@wUgWrfK^EXAcKoii$ z>pBHB_$mf4B(tZEp0qT$VRpWmP!X>q0G350(gEkK6nxQ@A^Z=JKhS6B+*UQZ_wyDV z*iB#1x6&fCdU7ZZ5rV-#RXYZ&L($KoUfeBsx7NESn%@v3wU@XIsSPHex}f-uyqP6{ zIV?fk0rqX8U;a-q1{w1vgK%36$WIdiL`*t|zeX%=6i4ym$3qgqTJ~*10@Q}vCn!Js zU7P}BG3mSoVsMo4#1h^3M;ZMDy#Ui-{<^*hTfJku>?f{D`SFpl8{GGg859qK;h{_U z=B^1+#wvhvX3c}ptZ%l*LO@Jtu%^g|zN{miG@`OxCpE-*Lr^v6#T-~1#xX>YKYvgA zDaz^>woFKO&3k}*m*5StY;?iCV(=I27PvmQeG)`i9)JFGN!CeKlip6h`grUZ*P`}B zyl7HPy*&FW|PP zx)0}`Xd|9u;|+vI$M2@fmkTD^2Er~9PIAu`SfIcIFTq<3&5?uphpl|UD(?H4*T)N> zY--xTfxQ4Pcy()%Z+g?9F}itJ)PF`6VuG;DK3q`95ZuU?I75hrr^R3i24FfF+YlM( zQXD;i=ICQz(!%2|x;Q|435Ta5Bd)jA9A>18s!t!|6aotGSlXvEQFx@?vj+z`@oy6+ zSaN{BUv6@zQh*n(;#^1FZ}5<0z)A3ds4k${lk=zGvLHl1I!w%tIaN2O#_#XX9?^d6 zV@{l(7aZ>gS-mcjix>gAdsY9oA-27)Z!Su-d|5i>-;Zz%NnD{XizFgvhz%WE`b3o( zv{U%7rOS@+3(c5q!Em0cCZC|sA&OYYLlfNT$pLbNMNvua| z>InD47csQ;aVH~KJ;97V$ z8RMO$J7|h5rDa|d@;fxy1A9)1bg^2mu+Du=zGcd{UVx4;^*(RiWE2}f58m~XXmdy0 z5Ps1ZMqCq>#)OH%UIs=$k+~TTEI)`@u@-_sRQPC(ukGPdfONpk!`Wk*C+B2`M?I<+ z1@0Ojh5=Q5^g#)h?nk|s49HmuEDx;L*&-FYk-i(I<`+~m>pDKtX=0aap!2`{da^g* zvfj;x8;s1KFC0-pzh@O-Qz;xuh)r!bD@C_t6%0un^H1?=i;@+xY53|gL7#|c-M3(T z_#32^pyAS-0fy-qc<{iW@K5a_J}l; zK<5P@KP7V8Xx0RSuMR%Vpm={gmM_d?iO}68>bMF!C3!oZAL zs1?|*2qB+Szqn0|FQ#CJvH~?FAfOaB#@1%;5yQ9r>m*2cML9vL^s8s%&=5rpFxU%o z!w141drQ`Lm7>}}ybZChfaF6WTrRk2E&lEj6rhknLvA^_Ig|^BT=1@f=R*Y;2EPjU z`GU0wi$qd3ZD&;Nu0co+vGuG~f79kyZH3#OLs%gT&uRA`s=i+v?4lz5AObUy0OYY< z;en?-!mkXh(JvT@>LoJ?dx3dg#b9Sd>z&uW^NnnJK@xv@vnmWE<4?EaCyxkrL z5EKkO8siMu75Y_bSXTsfDC=QRKW>GzWCLT!bxtg9UM$Q-V>ttk)+j-YRDYTR2?s4k zd;P!W5`^FXv5Hxefb$oDihzn(1vW6(?QxG72>_Qby*HS=9PoxhaQ|kLk`zyKnaaz8 zORNbjg?+yn5Q+pgUI{{k0A4tOetf;>Mbr*{Hjw_FVHd7tXj$1V?#B3OP4P8ImuEka zmeFZ|_{9qt6pwBL-MpxG?y&)rl$S$%iXn)Xx3ms!NNaH(6EOIyyp6AIeRp1K$qhx^(7X{zET|dBMafCW%NSOiZTS6#xdQ><7mgsi>6x@0S;AGbnv9)Gk zfoN-5&MR#UO{#Rg#FLcw6P4X_Ir4~CZmhYn&&W`0p+mD_c})onKcRY@Pc4UeQ9#(* z5Mj_*dz}{vjL3Ppn!$GzVp|KN0IC(LoLT1D5K4Wz!{f64D^m@?D?iXX_?M@EcujCc z%j_m;-xX0Oxa>5i{!<3}DnOuXEEq7i3GOZozsE)??*t81jH(`L*Y6E4QmA?$ z9I^itYR!6;K=C@b6$q~DR58E}!Jem>CGS$q-lm}x_=8D{Z>zVZA+!IXspV5DHQaz9 zR-xC#a|x7<(STUpq6Dc!SS6)H!B`PkWn{OS&^HBEV)akYhn0*y1CMF##VY*B7pclr zNc#nxtO>*-Iwv(^rv2+=zpDs0uPTLIVH;8VB(#jr(;UBa74+$m6nBWW1Sxsa+DSmK zDN!5G>KBKJB@G>KXgQ=xF?;~8&sA5){C!R4h<8xC_gIWv!ig=KXnXG|(3WfLZnB7v zAgCf7mx<@WX=WSa6?^_H212bb;hZ=EUm@Y*$<_(1+N|QAXuge^_j41OKGWm+>5X>png|HWy^5rWLbx<;F!OLnB8`YPkHl2 zA6>yS00~B@)JjRNpJ&z=JWKq-<_0!6#8)bnWO4FQOd8HthS#LAar`;thlK)TJ=F>$ zehjN0{m|QdN=+d`m_71L@oEyMf^6ddQRx-s>#QRN8=i;LRt(`w>iGerCcEwKi2 z4aVCi0&tS()GRY|a}PX;?{2KyPZCNuoaY3@U@Zgm&~q0xQjH^k5FQrLjOoas)PH8&iPHn z^PK}AhB3yAhUD-f2)iua1yt;a*gzFmLu`nIBc^wxB8hAe)KA zMX66B;_P{Y6Gbx?VGra{iA8rz57Sr&FAfDT9IpTR#(qXq0E3i(eXda62Z)ar3A~Zf ze@2Ul58d4lMLl*pK7MrD43`f%y7Xh1(~h_tN4i>G@YH{TI7S-6WF70O-NwvP-uYMj5mDqIRm0A_5!z^$Hl7Ov2b;-J!$R(EJ066o4@T39u$F1i)>M zzXDJ=e<9tV_yImfM^hj2YwjQJX7ppgDWusSjFb7<3db*1Pnd3y2)wE9LzfD$g}+1U zBYY36xPS5p$pPRS>XEZ>jTipH^ETk)cnLWencA;L&%pk?5Erz?E6>~%X} z5L}w9-_y@VJRnhb=xkjX#ORvKp3!l+Oc^lTy|vk<4Ik8P0AhhsQps?RQ{IiK!~%1D zg|h6=qMl>DC456PL;y?w4aW+-tMESi!8?2Ggi};xkg{#20!A(j=AB?M577u;eWN{( zlmMNUh?psWBpi(bY{r`VK0&`E_8|P_c`RnhAJ&SPuu+aE#!Ghw$LCJCIe+Flui-kE zcZ`L!dCIq=3c?-}MIcq*Y&@a*LPqocOh0S=(Vv?SnQj2kyK1UaY9hbZ=^GmDTNPYK z5Ze_W*NM?v?f}Ds#xp*y4d+j3!!rpghx-f0F=1npu%l3WQ}Y{u7&MK8#X!g>0C#nYifzUSwQ=Yyo z1|d9xmSO)10c37HkHLhzOvCF1s0GutLnX2KFbO1M0SveS3_x?4!ut3T^uvVpR$=g> z*NV*nCueb4!*wv&7^PDY0v*>Q5s>IKIDVg+i#BTBKM1`)TyX6Cd*^xLI-tCfTiZBN zTaXb!ja{4Uah7l0-Rc~#Q~D}N6;u2{d4FX z3f?P2;oxWr>AR?H@Vo^2NMYR}P_Ze(ZVrwo`9&QYOZ>$49(DHVFN*BiW1!3FR+KoJ zx`>N_#N)VUVe6LkVd(U7kmk>)VWD-L!tzj42v$7DO)s}{hLR+VfCNm|DNnOjT$`3{{6o`b|$2w&21 zx~p64_0$Q|H<9!9hXCNz<0O1Dx^tNz zNyS*!!<-MLnJYgCev%aGWGM;Quc3ml%u9GyOcBz&^{=%Qf`D4*3E8%TG(Qlqy;)m< z<)PAM@@?1qMMg>A&_>hX@572o&JH^;n|{X8lSDe2LGNhIaWB#iIQhwfsW*cds$|F+ z?n*3}dlKTH2dqA%DoiF0z;Z-U)4@Ks(h+y28tW;8I_3{oBUS5KrKz^cnZ8z4Q1f-P zhRGEeIO7UwV^&4c-+NU=-c8ZgffHv0xGnV`MNf`Ep7`t7pZEl!mad94F|OhbDB zOi|U&pq`GO36!yO1lAM!%*r9sU z8fQDD0IScToJb)lB%Z@UKCu7odV+Zqil2QmCOAb>!!%a#y}?0e?I)IERlMx@rSFR+ zQY>JC?LL@eYRS$+DGQ^#1wSXge99nA11BA*Iha!-uXAZ+ZPfKFE&4-7e0cl_+0?4( zL~@8}NTToW^HR6n=~A>MvV?7L3M)jpOw#BU>}da$s=bCMj?|`d4Oy=E*#(Y_7oxGv zEy9l0c(AVG+K?NTvXgJeVo>cvBP<}dLpnDcq(Fl^B%C28D0+(^L*Oc_nB;Y+YsV=D zW66d2xd%9rr1R^~1(>=5_+cFumeuTxo}S)`#Qz$qhOv>PaOTI8l5u6k+)z7u3g#b@ zAtDrn_jS3WhNUq_H3`=NZu2@7d|UC=f@vh4EEUPV&?|FC3VGifr+w+bDYBU%J1%hk zjv##(+ak<_Hd+@syrcd(n~V+pr)T>BhUG0J_n@r@NR2KCmQ);XH6YbBzLIpUjN_zO zH_Hq~u#coj<~s}Wq+k)p3?U@vQvTq~C1WC$AQ*C)BrAJ?G4|g~3Uy-dypASbasmh{ z7zbQoD<)f>653B8tO32w1R^k(yHh7}s3HY{euF=B8oC^^c`%_wGo!AJMqQREpt%bq zwJs;3Ux3o{7JJY4LEvt5K;l}2h3~t#QZ75zSuDw?Z zdTRFLzk+yj#6#}4OEQ9WlqHqCi*oRqKo@2liV_OQ3C_I;l%=5}IM`KYm4fFn%(I0X z3Gu2$h)l3X#-2)G+2lN83Z&rI*G%>Y*r6Da!|jegUL~RCKUs^w@mQr*1F*tZf;qO= z@X?B0=ar-61& z4YbJ(Q!=B<(ZaIb84?U*Tj=Y=vLNSyrvz3QL4otd3(0X9EEQnvLyO-}S3@qf;8D*p z0wRfjunGG*B|l~l7-vEwvO3&WqUaII;kJNT*)4H4h-sveGk1@-8d09v2Vq}_h_gdoM1|aS>spF~G|BS*dxYy$h_fTMRGZmsFy=GIOY1C%p<<#>xIZ zo`D|q%?u50Q8`rGT%g@k0?@tGAwJ65g4V+LAvJ9YuR~z!F1=Axy~l;biPlSN@_HMp z#6Vx?`+mo31{kZ$lfohD5J)&X?^2eUks0DHA*MD~c|{t2ETJfnEHBpe@b&~H;f0Ya zrx?&;%vdH=s zu|G%!uN30#9R{ersL=8h+4fWF%^H&~MtOwx4+P+AXXKsq-za$*lVH=rD_QvohvL_H z2y^_u;V!870LBCHVbL2$2b=n~r{>iK5L2V&F-m0n`c$&m z=P0(qU2!_F!55^5;Q!R1`p^LA-xj)A6uit_x7!)Yj->9Xt99GUK< zwfAT6zeAUSZGNRUH;8ayZdcZ9l=hA4AejPBWu_Rh;zZmKZ?mizNH9bO_DsZKs?|8) zm9dH-9HgDG=kL;6%a=bWL3iTW!Ei`sSQg($gRVtlB%Pada0pmjE?assWK47Sx^* zVP?g?#J9A_tKC|Coav~r6F~A~B!$tya?Na`mf1E{m&lJ9kLwMerP(79OupK#v~$w* zB%&M=G|WJD@@Xc)?O%5S)}Y!=n=J2CLT8*h*FOBgCUhiJXcRHE7b^*anRK@TNBSTj zx_E`P$F_X`ASdqpuKg6K0h%u~HYW^aMXm+;RkVby03~X!sy7P`Z&0yKu=xoRG`Jlx zy>UhpR*z%YU`q52tq*DHdXY{UMczU$<`_~R-&JG5rWg8awc8)qsj2jLH!`D14Nw0G-8l%w4a(21uY*)uR}Y=%TBJqjL6F z2c(V%ItO#VlyI%DRGe_r?|R7TsrjN8fo}&qYho_B^ot1&mRsmDvvP2XJX_|<)0@kkKKoMR;&!5 zv;wE~F1NWQOiShZ;Y`5-wop466O^WcP%H?Vh}#4`@d%}M)F1)Vh8G^>JOLLCi^lTN zcJj$=4i%+v(!$5CKK3C9DkM9>Mzwf4llo-d8!NKyY|;~WYqGgQ((Wu7_nNp7y@zOj z%OBIM2u##YvnZuov`{_ql5R?XG6Y3!n2N;kxL7B<8Nr3(?A-89Bo^<3-ZbkF>;oaBtB= zjMuYNnF%fiA07?CMo=2w=Qz<2XF7M1GBVLudGr@tJt3mX*-?TQOGOZh7enmoqbX?5 zF2R>%{Lb*J_zQDFVM#Vn8Hb=H%nxT^)RV}MIor9Ba1C=$FFS~_{z7YQCg zmcZ4|CfUW8Mw>ipW1j|IIzBKuM88r4uE46u1>(fVTco((QaTHjI^^ncEi>lcH%48-JNI8yj5OF za;4xrMZD-XL(d_Ct~pKG?yvG6D4zM@;;S9rDzfy5w0Fkv9PsprQ#l<|zw-eqZ)A3t znK(jtzi_~}_hcC>pipsE*Nlh^tx@A}Nn;(Edy5~g>d-<%F58`DSRn>_kw~4Bn!;nCnlVwT?YCXXO+S z;BNQ`f#R7j-U+59Bl&AR&SfDE%C1&{XXSL{i`B95;Fb?RwSgF^uCj3ex#pi}nN*5Q zT=P1?>~`K=Ag392Wth<5`KE8gxj(jqjo;*xpAO(ne5aMfUryXL$1LG*G>Y?rGMiZu zc}3lPGV#L&GpJ__oBWQLBpp1YM-auXB{bnwesJp#2PgMn?dA-c7@=|hW4A(*1zyrx zDe1wZK?q8loeIndKs%hQW+(LpZs+_!%-cvJ`%!R#K_MZ4k%~$LA~xYf_@@B7XfR*Y z#V&}kamwpyJ38!sM)`sc#7m&}nSO=#4-@-O_ET-Oy7?PuFgxlJ_H3afom(XL=S^~~@|zY-@g=A^Hk0eyO6Y=r!{XTyMQ3mriGrH$ z5YyQZ;+YK|pIB@Oa^HS1}ubk z;tw4@sx9GK=w($c#JJ8EJj6%DyCyeMemNboePdfl+v1w0f!=Iaoq@D+=Bh4o6S6=k zsc1<=%Xn^f+~n0V8nK2^w^e_dEcov~R8s?aGui!DQu>5rCu3mb8S1~DrSVEY?A(5d zfX27Npo!(|RmV483)}6xT!65-({Q#@nOBQV=8%uV_@BcPJ37Qg1S`NW z){l8`;RGbpj)g0;z96M!*cr}Zt%bxMq z(NJr}SF*e1WAc{9HnvP4n}RoaCr2GRXCc6LjiICOSHSg?sj>-8{Rtt~udB#FIK2}x zN)zbwSjx3;jYo7N%L;+P^!&rEFcIHwJ%5eEdz}IjI1avwWLE21#a8bh&t{cYj6eA) ztUW)a(RjeWq9kNVZoIL1Zhk5Xtgs2bv&qL->kv8OQawLIu?)y5ZOPPUevX5tkdhl= zh!HvJym76POCqB#u1jM=ABDp~Awa!amcL!Hp-GDnO^u>HEsmT@ zf{J`ppl%b5yjY6d+II=ZycrN(p->-0wn|nd#HTC1&3y?K4pLOa8?$z>6uY4zlRL9a zaf7QlhRbW_rAJo@p_90z^{cb4f)FW;98gf3N~_Q+m5%7FguM2@4%(s; zuM?EhLC!AwhHF73up;=88*BwkzEzQ(Viy^KQt|)BA(CE7(hf%ik-|{K6REc@?yoy6 zgALDYnn%Uc1T!#xV`XBsa?KzVztpig^$TVwmS$Bx*@GPh`kIJH{Q89IEVeDIc%H(i zF~YS6Z5k8ZZGiICk69*$$8@%pfYB4qgQ?&_%OFGc@3l&B8k;?U3;ZICz-IWYJ0W>9FQ3MeKi*c zpg(k@^W-vWk2%pvyda>Wl(~60RX$D5r{{r=U7sB^)_SN2t>4b z2L~MLyUeN6hw!JSl3Li^7HHPN=%5{I*-&w3@?^+pjKh;IvPN z1|V^=k~u-2g_DUYztl;^BW(G^1Q-x@xYkI&vz}cSs}$E9k>>^^=ozk$PPO1*NE+nC z@D_dhGs;F36|_)a#_EU9i~+gMgv}9cqE#PS!)A9|;f`J5O4z48Hah6sSdR+&PH1}b zWEcU#nxS|yy}bJ;HEuoIsKQ!Rlt*E@GT{sp>j|Nl!?}iES-cr3mZ5UnfVgZ&Xalw^ zXPi)(@nbRY4F8{M(Mg?(^$g0_MC&@p_-5S&RsL^ME^L2NPo>XDcCp&`F{aPK(@b-ssVKG zEWeXNB^6+#howcn5SES`Yc*G7s{M+s7H^PII$37zd-DM3*1!3waEuS1B!y;V{xUfI zOUsP0b$@BnHWT|rP#25oIgN3!n`}mdGz}1GIh#6iGHa21TzMJoP4b0Uant>UB?0O> z2RwPVyackX30178gVVA8goA!M&R;smSlvslZzP$)9}|bd+!+_ThBqQq_3KhM%i;ti zm|Tyq-AHYWP>{xYGyzQ3^g~BNot^RXB~^T)Ywfkn9ah|R@z>W0Xz=I;X@4!=!V|I% zKlR$U#A?Me>6)?Rd{;7BFW{aCZZQQDJ-+)%=uA&Wglb{nC{@)jF#-AKrB{7~VFS;E zSIigWy;OI&o-qQr`3TTcakkKB2!tgBfSCcTC_@WJfojKL+QM_W06kYNFrV1-_pCb# zkD)Vg7(#}{zmOF`e>&NL8?~8ge^W=mR2yYqoywWm-8Bd|_~NQKAHYW%{5dk8f+yk@ z1U~wyz|m?}q`ux2QJ`iVasC2EE!LC|%{ed@(UTiw0e*B#fM7(Ys71-YfNFv#=rGV5 zLnE|}G3O2<4%K0|fX7UX^RysV#iZ3u_e;>`9>o%%G>p2}HL2ZEP81|GN1$)K;z~;* zKytDln$mL?u_99rEUihpNbj=h0~x6`ri~{lI$Gr1G_M((HzAv4_eucZ;|Q997@f@f z-9aKyP{05%0|J=9iwie2yIa)23t*<3t)Uh2v|-BDcm{-T?NL_;#p&_ibc#C5iyGby z6es~e*_ACcI_TCXws*&xFUg>V{k+~J+dbYTQ()2T74v;Npw${ zSy}}(EG?n7<&k%;=Xcwz7#X_>&=WO@?gaO(6k>4^%QgX;`X2vcVgSQY?Tm>Dl$P*# zcj9&ceu#DGElP_id3F|HI+ca)pUSm0c^Z(SqnSwAsz}D2s44*^CCtRy0M#WdIQ4KP zRwCk7HVKgc1`?&$=)~e#x{P>J33h+T1yTO(169L-T%pdL7QO`H8m(>v!&vW{7Qo?cCdz%sk5dg*=TPF zo0(I$p0gdOJI5QKYx?Xhmv=|h++Km3p?Mq(oAdgzLaU8bi)IjSgaPc1Lbw#34cB3G~jC21nLyD{8Odd@W%6FnW)m~>tf#qR2g8j> z4z;MeMlzmSwq~7~n`WW~2J+4Z(dI?4(l+awM7~7vuA4aqwE!gI=&8uc4tM|yJ3UIf z%;2*j?^5F*c>?pV6NE(OZ4JVDlMhsfkLpv+;*N*_-O4K{C|4$d?qw4f(po84PeNqe z(P|fJ(fTw%H;K@0)=s97B~<(Sm9wms<{*`|gh5XwNNN)^gZ>N+b6C_SMwHqpZk_8a zb4)h#?n(G>lWtCcZJ~v%Ad&Ddbix!0lIF&9h#r6^0RigrC{HG&t3kuVVGIyI)@1lq zNZWx_YjL!gm0yeb+~Gsb!s|Nd)7qN}P+bR4wcccEmlp^emxWYwz`6X0d&{HwI@KL0Qt-e{7 z0tgqz8leDKKDO2mfT^<<7XZ2iFJMgx`z@bNhQKNTtTY+g1FsjTVeBn_aeqW;EN694 zIk~?~f$v((WWCPue0+F!Ymh^ZTx?DpKvL-2!wngjsyn{`b1YBWMaGv5 zG^~h<^gZ7XFh9-b`k*bo_7VFtov;Gw;rWIZ*4P7P0DMlNPU=+ab8!@5I z#K2g>VjT&Bk2%V{7gNw+Ws~DTGz`S+xKZ|s4`8$T4kEx|oPeIev)2}vD42CuQoxJ| zpv9B`xO}McoC&f8HVeQlSw~C&3BtjqLQM<1K=h@mTpP`-x@BF>H!)$ZC-(-RcH+-L ztpng%J!t|xR~+Pt{x~)idJnxcF~!YE%Q)6 zsOj9BEdk`$NnP}$LyTLZr1)w^03Q4^Et+9X^2dy;SqLLPIK&z?JRmOPg{#<10)c9I zE^}Q1OOW5w)Pr^zu|dwyp%>$ZJd21Ps!C0jSZKGytwDy4<-9zzR~;*IRKtuOg@uu* z@+gn5EUD3TD`w)Dt2&=WLi>DoR-5R^QBO#axCb`8&CV1U zQ~{FUK8g>DyG*kE7_0sLSs0U!q{WSE&9 z0CJY1lxsS$7g-}~-<8#m5pT&tDj)h%33r~Vw9M-?zWfPOXGH=%WSmPDfT0y@=X&JiE?;_tX->oB8|vUUD{sT(N8aNg{Xu4FQ!+ar$+cdFS%@+w9VkD@G`D$3at_5xwo*!(y{ za|kx1b*NQF;*B(bWk{6sEqSL3(4vD&=-Oa4pEdR6F6l}?dXpXW03W^Zg;s2}r(}Ie z-O{wyT=4+NQ~}mk2}~ohQ(pF=b{h1(C8?Dk!$LHSgaP>zKKKLxKLi6XZ=VBrk^q1+ zc&;Q%C=URbuLY^?_QCYR=xkw`0bue zOUAsmjK%7-k}sfhWyO<7@;xr%8cPc>5l29YExMK#3K=QHDF)DaVUsmJJ8cp(U#J4e z?l+vd&I`cJ4OXrqv=7s4)^>gKi)C;ego~OZbJcj%kC`mm=fFr;XL2kEdJHhC&n!o4Bv-)rB^ zph36)1mx8AAPXnLnfq~B>gx4$&>zYZu-eWb*F>=ZO=}K~L*K1<*${VQ7<` zstLO9#5DnJm^iut_%DARx=Ed#dOQ@3Y#u0(gDX=?R2=$5RCrhufWJ?G(vvL3lIj-# zx|QrLvL@_g$p@Rt@tN-Gx+bb0wzme3SwdYk#?k3!1DfktQu#4JPa1rgye$0-kW%9o z;7d8iEHj4J;TI(0=t16w&PoB~R5wlLH@cxIDQ7^RLtLnVNn9XXAoB?|ki5GCshaN_ zfvi_?duq?S@|uQcV)`fxE0kiOYEAEK;tQ#;?)exXKwrexZ$({2tO-d(+6!!l1*2ZU zpc0cpqijRGtNINht7*s=z%(I7J$mMoeFIs-+W;;A;lcaP2d)52HxT$Z5daS^u&OO0 zW`epy*4_NW>wJm;hrmc9wrJyKH#E>TQNH=o34mw&0GfKaJbqk5XIEDS;JNdUMg!!# z4Ges15iW-jG)&PVPhq8J^2|wB22g&Oz^bq(Ru80!n~0k)-$=evw(g=(&C0@kZPOS2@?*{FTpq4M ziR7%l1Dt2UYs|2ngT`eOj;78$jnF>a*JUaTvsICNjxh2PU=DspB%cWz0pel_u$6ig zj)~_7G+2ke$m(xer^?{!@c{e5lSD6A;f_z{j$iXbX4&-PTk_hkx(x}crm$FfSL&lp ztY<#q@XohBz$3=2x;3vN=jDeO znsf4KM2rYA=FqeTqB3Z~%U<#G`na)a?_wD9lL-ATyXKi!CM=7`e~CmZzL30S2{OM* zizn!pvEnUa_#hwmAqgRz#_>~C_4Qml3VEC>W7#zpY$+QX;<^ql4W7Jgp^-%+=m9V8 zk+sBkyEK_`vm%CIeE@G~6?VJBdJ#od3pJ>(q?bn^t?;Y$+Xx7GJL}nA z0Z-PrcZP8wG&hrRyV*b6~f}WJ78>s#K}T@sdi*k_!YzpFg}BSnbUvfft$f@!h~b`bmk}lS}OC!BsW?F z>J|a?+W<|$^6C+wy=^wrjR(7K5!oZybhXiDOg%q;_PGL;GCn-!m~s)HDg5> z-T(5VHaC<@F!YsTWi$WWzbLuv{pa6s8kNsj~+DEirrVc%Bsl{7TC z)o<022j$>ry)Qfp?}o~AG{a$`!0zE<6!UZ00H$r2QGXauBj6olt`UGYAc~v=?YpyD znWyTo!!5({Vy-bg)%+ZbU0016mKznRRr*YIV-@a)PMuZHvb56Q@EBh#M z_wxljri1Eo*wcX#G~5$ZQ>#7zHn1Glhma)D1!~uFxpBw2p>{o4W?=HPziO7$S%5jA zRIP2vl^lgiH4V&2DZ(L?`dnJ*wNWCwUzii>MVjX<+I8&I(H zI*Ufs6EExa z@3IRVZ>wnnIsS&GBrj1EzMBWFtoCtjQ5rw6e)yI6WuFc|ejZ_3+|Vzj@UQ%hruw1M zL;$T9x051_OKMRDJ?Vb6fbNk%Py(+OAa@VHR2jKO89gGFx3SeDQ%96@{!Xl6UZ`{T zLDkJfRqpE`5ec?S9^KI@<~v)jvB8)jMr=stRD^Q zQvq6i%Q_-bI0}bmqp+-?w;&O44GVupWP}aPgj{NGK_)2|*~0Iz$g(OF0k(ilC^kFs zU4$)b^%jrD!0%dG%u~#+QHD*ya-@QB#8Gnx8y!i%w{e+X!bMvIar)W;bamndKnl&s zx9$x99(aH%cT3S*4AGG3B@Ws$S$1FO$;smo88{{LNp1jghjq^S9rsshp(WIqEaT!N z(1^|iZtYIF^s7!4z;R*H{q`Hq*UD>byhG zCSjQ%oENb= z+3(+Es+gSF!$=$kX;q4+CaqUGq*kP}YX$Ihh!X`x7LgWALM4YdbQM_=Tn|b=l!)ux z!Em=#Wn!2Kp-n|0>amT49rb8eGh~V=?jA+{w8)@7Aq>ZW*`%t{WkF#o}?Wpv(wGLX6U)dTO~ zh?aZD2#N{9y3kh7n;SF>cvteC1PKXlMvp|}x;UqAZ^{!?Ww8Wjfitb8U_)^PE0Ak_s24r0stSpCXJ@wz;Pg`VOOoZXrZX5TLtn2=hjKv_5}sop~xb5ffK z-={zt-F8O5DnJu`ukltj9aB{wg5VpeAdSA>t)qzhA{~*bb3GX=q%p^_^k;Ejutp;h zn%koSirAR|z*Kaqu9BByCpbX$QDEE`Q_n%6?uF!gio_)vv>>j-BdoJO$%@pe%2g1B zJtZl|;hByy%&E5mxJwH#l!cRe26|@7$&Glg*bSnYr+U&fqB?a{TzdveyRYil0PlwU z`?4dIF%;#cDRv`B!1E)l;lyA@;eIHqJo%XUu^MZXXnrzf7+#7o^7srCleh8Sh3E?J{R5e+q)SAICg!wrb10UNz!j=IvSsm@+Ap7D|m zsX>@^7ZX#k8iCRF-3V(S^ZsFXfCVVUXx2Ron^Kn~fwgJWz(ljpvc*V%Y@z72<4gir zuf^<{q3HuW+Z{6m>Lyy! z&Y@`ZBs*@Fv56_3qRDKymVCj1`|CJdTkeGd_aK18l@yYsqgxbQ`^hFKacfju=MXHu zEsvv^C7H#ug^5~OPnOeTK3slKOOfU|ys`SieKE7Hy3g_&6Io+P8YA_xFNSKepcB+3a4l;VQl^AaUzI29K?qv2Ocmtf+i7BQop8uF zLpO+S>q!IyJtoLRGbSKaBEHS0CFD07k_5Qv#&MyFCR6JN&LI%tfk?XJGX_f)iGt(p z8AeBpL)z*Z2E9<3a0VXghb{%`jQLm6CVS~U1W`v}o4!S5b}DO?|4j0UvP!!^`jOhC z<{2>k=L5%P-X<+hbM_ixY58FuBr(644Z1x;wrfQ@`nd4y8=HwdyOC3>oWsXJg-zc#q1v!fWGbD!DP(%*WyX`D0h8Lmms`%|D~%*?A=n3R1Z%lntK=zJCy!$keztb=Mmr|6a$tGTw4FZm44)(ljnGX%36PBYS!V zGcAu{Fsg)JC`Qh(lW-Vw;s=b8StR0M2m`Fs7vfymW*i8ozr4-v7GA#!V;e64my3(SZInL%L{G^xG*=u6IYp<20XMuID;^5J-Q6$+XqSfK)5NYVwc2DbzF|!Q#m4t$Mu^bo0kBv#L2z-!wlYo7L>2>Y#0Iyil#Kn zX2fzZseZ!%K)z#!3Qda4G;^d$rR**PqDa_QapP+Z8Y$wb+%p>dprW8&rN$r%79ziJ z?XGi0!D3lO@<2qY-Yfvxr1FsbPYnXskkUFxU+UI3q&yF@$|nQ|2?6QOoKVpfK(0hq zeFWEs7642)NIU#)hamN7)3;b7+zil;vz|zIeT%rBRO!Y59N<`}Y>O3k5+$~XH)P$3 zYFe>Scjy$))H@KkpK6J~%HFi}oyQ3KV0n_bkof8S{-PNym>LgKDkg?(RYRbvUL9$pvK3K?7?l#~@3 zsY50_rlifRT09e1R;)dqUi*ao=3FAy*xw6E0e@mgKYb{r=nJoUt=KuSyk5qwvM@En zy_ym~W`ZtfDF4Ni)aAnAS+az(uwPidIlsWlFp$65BS_Ern;XalgG@?9WgtF=yXtk! zOLWTIH5%ygNC~?>FDKeD!L9@2n~fZh_G8JWBc8Lv7>{e_9JtGeWBFYO9+h8aL0of& z4aCp5D$)tHApKF~Ix)L}GQ@e|3>!79bh^UoQgQ=;u*Q_4lc^xBj1Mi~+uS43dPNCT zvl)hwIEOW;I^;kMLz&`;`kq!&TRjS7Z;~RbMJlqvqiGToS6ry}7(O`=iGBS?jRpG#&;S2T7k-U zIdnb=PXG<@vQCH0J92KPOES7S2k^KdELN)LlYRYCW3WmYmq`7u>lF0Xxomlgx;IHKDPrFV^b`>*OOj6Rh^|sIR})DPTZ`e^ElTsl44E3c zw;OO>Zc6frrDTH*GFJTcf0P!;Oze;;>BoG3CVZW0Jbo7dZb0Rc!_Wd$!8fHP5TpaUUa&Q#Ur z88Ja6;WJGC!<-crJz_qga|%)~XI(OfyVyZ!$(D(Qj=K`+0qc(Eccr|;h-H{`A_e9-1Hxc#Q~KzJEjE^)^uoDBSX{f2kP1y!6|3~CJeEUSLIkh}kz4ZD1XsR*(FTPHVsr11f4oi<*ix>5HOq7{h$ZwgW8y(^X39Fo)V*_E0C%ID z;jpfioui65tA=&E_hY%MceC2s9)=wD8oOSG?ON~cJV^$Nj(~6qR(>c{xDCN70Q84+ zk$wuWx{a(XKx$k(dT0&&M&HQT5F`&l{rR$A2un-9dOjY)R5{Y!22Yj4C{{*;5LA4` zjRB)zbWy&=L&`?!L#l^#nn)wwa2b?i0T;Cc_d2<(uG({1#O^+oLJ3{qvZs1!p_EbJ zGg&U;E4Ky#>!1M)Vh&5F|4an-wF=K<1Oj;O7$~|) zGDvu1AFR?rlVbGNwadgOsG{dhCQz-|65PLYWeTAKOD!0V55d@a^qD0JJ3w0^J(Mr) z4NgA786zwF&{!4*#KgIV`)l7!k7?0g(;3a7eyT_4k+BPmwO6z(TiTnZ$cnJTkfIcL z=ub1We-l~lj%yc>5I-Lv=J|>h#~u&F{R|JOuI`faq;~J{Fw#_u;Q#4P+hI6X7Bf9o ziQ7qtn$+PNlOUlo2?naXiXiv4yQycOIi3_HzDyZTU#mW&w)BqbRo@}q3X>$`URnBA7+-zZ50nAZ>S&W=qC9>jE zk;AWPiKxUJ?srbA5Pdb(12E1>8*3ykhuoAHTFXN&K9-=>&!-VL{83n~X5CTh4ns}` zhs(1E#5U`Qw{;Ze!Ev`5v)8!Wny#me=@K!nbBC-vML0{zt*YYBH5GPXc(BsJxJ^Q~ z2m?^=f_~)|JfEuw{mCa|acgiw!iz#ySVv51QtVO8gV5kN3yXHLt)dxs~a# zE(fg0I~kb~T%{qfNbOuiRs?;d+r&-64YMM|&1dD{J**BR%5w3g>-?6kwR!D@IH2`2 zqY)d+jb1Y4In~F+&<|uXm1ep{X3;dwr{;-lXV;SMXinIl>JK8dJsMeK(xI}9Cf7;v z(MOk=kRASslZo@g8Y2bktlWTVKlfJ+^86v?$zu@Fe28Qd(2CY5vx7lm_)EiA{k zqN=PX$pycM#pH1!x?-x;{ZUs)jJAL*N@^l>eG~PF_#Ot%-&wa955CC7#=2U|!~nE< z?6E}FOuYu1oofpKJ}vf3ci;A0ZcnwwW2+=02HU?mx`DvB?ia=^qH&41>bp~6@)S~E zI3Tg-;}AIzV(73$gRka4&5TGzyqn-v&&{e}Gh`br93~IpyYH52LKIs&Bd6r{72S}EAq`KzaZCzz$tq z6!GP*Nin9JjJF7_!TBErX@N(k)`Rq{xL*=+D=ssamB1gl?%oC(gT*8ztAR2q)**ja z>rptZ%KPIraIXG7GuLP@f7UJX<_QmvmRq1l%^h4kF6wM}aq#IL&&#?vw>Ua-Yco-& z9$#w7gd(z{X>sYXPaES4cJHkHLOzo0+khvLzkd3P-) z$t9|AMN_!!DZ^MSXR5SVZ~wO7(018J0-|M_%a<`t}M4MIFc4IA4xYz#L$RarOcyOrwNn` z1Om~brAXR%Y--(Q$wuGY&ol6(kS)ut4dNLM#E5)$0zXI{KEbYh8H8mt&@Ud(yz#<> zgbxr-VtP8mLwq*D{g(_x!uDdk2rmaoWz&qcoC5_4gQ)sANgWfTBY#=r#YI`qwI)yo zfR<%L)Bsk(1mZUz4QV4!G%s6EAZ$`9K6O!!1TqIJbXSO6Ahgw*Z1OIUNyPMEQXaeM zVuDZ*XMhBj&J!fXWRTfn!_Q@J+&pduNSc!bp`}ZQgEAx~z+rcvSNa?wV^lFBEB@K5 zHqDrRP@I%6FvRL8Z4&TUnilJ_PmnhB_p2YAN;%W^EDW-`w2cR8jF>ZK6b1SoC*qhh zFH^6$k!*u2A9V7AWWxZxT_YSBTA1&fZA;E_&$u5Y?^0k7pKbcA7B(~6#cM_Nj5Fk{ zI*b+GUUgcUfx#xcnR7&W07j-&Fdl`KC)XYoHK!Ji ztR*G5)A7&0I5lszEyZC6$G4wMf|KMiCXF>fj1?e@86?yTdx#$lBG&@wSGep2NdeTe zriJtlq*1v@fvnrElU8*Ccu<6Us^~#xER7IB2r=5-d`&Jh;z=S=$ILMVUw30B7(}v2 zn{L&LBv}Dzy*kLWY0XU}B@x@Wl6;WfvW?aX$qe-fVvZ|P8cLgdy@b z^i2?TKqTJd;_k}$yF~5)@nuLb>KA0h{%JD3G!aV^Nj3}0DUA$|ejTt#Li)aqyQEHv zHlvaKPWO70x-|Mn6TcV((obZh$vCc_s_&%W)U>I)3!-d9!UThimU8-h$&X>!M&4B! z_h=So6gTBvJ(LTwWbBWScvD{kwFyTaGQj!96iDi%)&XU1Hp#IdZfdneB=0MUjEqey z+cC(DuZ3XSEIsLFjs2M8*-t90_A{o2wrde0n=Tf8aTWI;u=5s}c7v{A|;wIka&LJ)$mGY!%F>OzP4@LcvgkHRjz@H;ctB=S zEo6I7UPz;t5wghKMCpB|*-DHgCd)^goO$3bG`f<=*%*N&qjn7O%J5oV4&uRP+Kh*z zO%E@CY#sMNl!!GR@9Jm2L8?uJydH}Pk^zEne|ny~nmz=n$xfim!z&!3RPtrIX%Ml= z$gig~Fl9JGWjtO-WJ#w+A~I_=UsDZYs;o?Bd^vU?Q2)QXsinL;YC3K)VgGQ?H{#p9 zOYcBG{isfmnM6Nc5u{DJwI>i?#Z7&WB8cw|i_|aLW^@TF_?CJJRMuf+JT5P*m%$Jm zM^9jPMMmhBcm{C_SD@%@{^_GwF{3sf8WfGP2e@>^2@S!*%}&e?p~7hfLaQsKlKJ$mK-3ydt`Kkvv>r zZpsNbUiKvsGw{%4JgEqZDAHGn(kD_rbbrW$UgXwNM-9Q1d zsa_}|z0CJt>38!9AryN+0h{LJo7uzq9~{Kcb&#d$zoou2W)Pn*(s*Z^B&mE3=;fzR2#>0rdJbneUK_*^s}ag;%8bQ<(Ax)b0xOf`soWEwm~nMC^24@vduQ0Y(9#N z@28D+4bsi3+?AyO8GWJ+rRL0QG~T-^pKf#HE`^FPMtNwGBocvbkIJq$ZF=V1nilL|*1CfziYQ!9=U_+mlolfi)7&&4q*b>g zbdd4w2D^5=7y*b!-ngq@BZ-YHL*FbSC)RAU^^-bkkfdZhYeS-N{M-&_MpPbl*TP3~ zjgY-gU-{xGAu9&IIrtT=%$2uF)rezA++@!&j8~`pY;1 z4vP(^kQZC{$q0a{y#p8m0jAgvApK{O?^es*$@3dNg!F8)_(M0@eDE}hgi^p0LbPCp zy>??pIcfX;ops|f_5Xv{{@K=ds*bfw0}MMFK3UDW z(jZ^hMwMe?0y!L`vM>*M7Kr%=!0CUr@Wrz9 zVJNc&5!-RiPg@C)QwW5HrbU6)eR_)xX2;Px`cx?1jLXx7v?v43FkD1g!8|m(J$mXT zjQsk7MxnuYhm4XtdL~@JuL%H@?g?P=TsH;v+R`k*{JcAWAKwBX)@NAe2CR`=Q+)`F zh83w>30zrcR}t;oRLMvNkg#flJJ}xBHBkY0F4wKpdyNa_dVVI6Yok8E{C1$)>c$vm zWmG}85W)cSOoZSqdrOQsHC3Zvtj0wI7=1S2qFiiHjer4EoqdbV+^bxB`*_^9NilkfyQZ*KtyXI%5L=p!)HpsIM=|}(V;p41-n&_^n-z1Wz zNurXwzp+u)f0stUWD}FsnmH>YBV6F_=7M_CJ}4Q zO;8Mge&ixeB)Uj~MOX7}lbK5n7Lw$KHWNZUrb-IOnT=%uzHgh>MfnBn?~pyK1IY86scLWqvvmq zh?H7h-QzP=0U-rbcSTHsKt?x2WI_mY_z6gK7o_JWyi4w2n;dUE1R*Af^!=?M(m9ZE zPTmy+iPztXpzE9zNn;A=(Sj+`uLrj3vpYW{$BcLJuvZNx!%u5I@KsS5FFxXzBnh zDF={}f}qVA9)ZPP`tDr2rCE@PyY$k^ucvw~K-o>-0^@W@{S^q?ISfx^wQ;9Spt?(w zyjcX&EpF=GxaWCz6kb5Pp$U94!)v$|>48>nie7@WloUjL16i6wo77O;PGB|B6A_wV zel>v)u+8K+{C^vgy=t+>x-mbiym?=?PLNJAKHG6(c#=#)q_+tX}`)k_q#VKa7? zL1}5Kjh_{0kRIjRgif1b^t8#spz2Ga&?`T>0@5mhce%a*^75`-A`3{1b2d>+04C-F zM3FStGA$5wO^Y5Ik2(e!x<(TR1kEFLgu1vm1bwF4OEGJ`D z=aR!2dj=U+1Y#~3)g24OevLG!NH^)lBGd znHwL1%u=}DUXx7aOl{7wEpF;*5)mFwH-z2HQ=>4{2$Y>719I%VyZJ#<@cP_DbW^`} z{gPv-1t9Zij9A_Tz^Ss>?6(U^?!$*pda8)HL5hM~5lJZxq{%f%UJR8f^=Pe#N+_91 z;mo_T5+FS<9YiIBrOhnT28I9sU7g95B{{Ms_fAEUkV8~O*19R^Q%w9tC;!_Pk*j9U z7uI7or~`LM=27FNT#t<^7z6I|`6SfI+XLCLE}v?{2*_D2knWDqoxcvkO)wn5 zeOaC=C|OSj2uI; z7M5^6h+%?5;I~Y|SVn*3s%PpD^-;UKpmA zE4on(4&3s+RWche>Ao5vqSIQ)^s)tEON@NZAax=JGGi1pPF`9ad;7l26YW&l&LtVxd=Ld+LX(8q*)2LE(!KS1q#YI^_g%K@~{)A#2gJyIz-- zXXJB*LCP#(E-uAF)~h%eL%UrEEIq*q5HMq$bb++B38bv?7ZHyUQ)d3W7myMrnE8E< zkt-_UAAJmWujek9CWRLI2IE2i+(`U~?^WU`n@L7F{y2|^yy;X1$nK4?H)|K<>2W)_ zNIs>m^d2VIHsj!BSkM6YG66E&0ES;N-!o)T9rGy7o)3(zR4!SAZe7} z6rAFbZcoPd6hb9!Kps|Syi!8sSRLU^4}7n~+z}b7D<%%VYLC1UPScS};B<)_ckoF( zvWoT-Sc*ZQa|FaN>T${{RVr|r&zXAwlP*O$J<%tvw>h9T@lWuh=MhsuCqi$06Tm43 zSHJ+aznQK7%C=5*P9w#>pM{G))&)>k>p(NfU)GloVE>a(02B)4O*uu>iGp}tbbmd+ z8`LNB96Qw6kn`tvc@B|zfz8K8l)3%V@=k;O#nIjROz2e~DeL!BVY?En;I*%a#m^X# zvUd(DCZjBX@dW_Ogi_MO8>=ztqpa(R)EFCn`MWk=-8F9qz)k|}6QI`6I~TY^DB4zz zT>!K!Z4E5Vm%!VGcWnb~5s4GXd*BwCEK3=xU2xL@Yn^wxZZaf zxd80oPMu&nn4`@<74VxWKa^oyjkLfw419-l?9&g*EzCAVm?ka1^@8(@t z;EwM|eEU#j+bAzT!S7~=C|{lifIfZ!+=>N&yFdgMT>|h2 z67`4YQ9DTGBRCb5`+|u^NuNFdwTd~|jR^rX3a}NK0etQk zyIrIZK)*O`H7`2=Ve>dvG8X{(0CwAxfKtqftbHp&fYnvXOSD<`U?aeSj{s(!Gh6eo z1q?v}mPz`7|AgP}5wxYg1k7=CtV{hR;3i<4vMqE7m>U3S4lMVXdMs0Gq5>`;`MjgsaK*tme+T(<&UIBLo0?c(1=*}3e-v$pW%DwPc2UVLMTU3G3;9xcml7VrZ z7Kci)0eF%|hP`}L5Y03{z#8-o;PQ(C@HD`_CSeT!jx1v7T!h2H3UNBYvA{u0bne&z?F*u-ZB>5XjhnPUvAQ~Kco-ak%) zPjqyhRLS?@B;GH#et3=dJMG7fJ)&FrVOPYJY|1xw)}YZ18NTckyk}|$;1LNrWWN-e zW&oCND2mlq?@-uwLzkdwrh|4I$;=;DhS0&3Z%YpVA)w_)hH$3+e!yFPMEw{GxqW4y zH?Sn4vf!O*#a2WBwoa|8l3D_ABQ~0t@utjgkBNfj5kxYsQC-y$e=Wfe94K z-aUX?@g*`b50D5tO>tm8xNh-_i5Q(QI8GH)N27FyvJ-<%pZsC6Y)@yfiOKx?`z-@t z^q5hybBmfanz({k{I~4x3d*AfC&_&gwH5R>W z9eFWxUQ__nkEjM%w82vjqlI}{%Pl1F$k{zivYpKudd0Yi<4_5AdKk(11A9hPd7&j?L@G_ zEG#X;1u_Pp0FNVuHmU`Pq~nG1G~PjG±ky_W#Go)-!O^9J*(J)r9dS0P*H@i49E z6~dV>znwzopJM(H?H z6*mcZ`6@x}mJ|i#Hv;KJivryX!dUy+iM|ypu))v&p{%`tT)98~zLikD&}(4_MDt|V zLKeret8qM$99b@>;M~f5xzi{dd|3(@oVt@6y}pCV&*6TjH|~ z0DS;XH6fkA!0Idf=ip2`851=<@9syb=B`Vz7DxBiY+nW2lValy9x}Y#e z3RXfld70uYu4};hG)UhPbaJ0B#U{=M0+7BTmyG6~KgX;>cYqy)bU)TI)O#%>;bG=Z zU2u<}d&=eV`7aAq09|W$=b`OyIJuY+;!qUT! zdj^0q>5&l_^PuTdUC-}?VekS0;B1W}{;=yU2>B5hlT#VS+s|~4VV%#esiJ-K()AGl zr2#;y=GyCE3s(7viTiFBkdzs012c3Kz!MG9Njd2e9fyS-&W@v@NOXtkW%c z^xjI34CQ zxwi@cTHErClnz-$3GYr_G3jL-8AQVTJ{mRe(BDS%@Ym<$NO z83IcT0GNLiIBEcJUlnhijNJJ0vm&9A&V+z%6tDqXuO|1g@02vsM6{ zQ~UzB^+W)MO8FEUWw(9-I5qGZTR|i_z-<(AcM>xWaGP5J41>{h`^bQg_$f|+)B5f~ z!EymSN2PQRrY*-j>|`MzR-c~I2GBhKn9xx6&=TcKJ-Sb6u2K^~(LjaYfA;~->1g_9 zCN_!g_rTrEZZstT-G0ab-x}_IdD>v?up8P`V1fwX;;Fs3e#5b_G{8fhbPnayK|G;) z1;C2RTmbF^12|g)fYPM=bIR26k#pKWz@bC%4VALJG9#1vwMqGcIh%R~aCr`Z&hDM+ zB+7TVO-F=27?Ht@9hmFe>{^92iSOa8!&x_SG`1!Z-n*k!sQ3Xt_YOpY6bBW~Rxts_ zaNhDeSq1Q_On|vHOsQdr7o<*M0GOo#Kp#Xamx=m@@{gG}w>Q~wbkmI#ow+t|A(9&A zxu|hE1ZL!l+Ao2Zp>_4D@o>1`Ww6mDmyiLoCj#p^K;~c7o?ipt0d8u{xKr-i?F?ld z1<)a*0(%CW0stK{fOC8VuszaiIwgP_0_lVQc6!^dZgIt~VzIO2+7cD1efNN=6awJ7 zXGk`nTliCMmDS@Y=MSJQL48McYv|4bJjeTy3v?>L5+c^{a5})w917Sg=gGlY*0wPE zoFU8dIKWPnd34uPRIHXR)7@EKn~+;-0giNF=(^}-1v7F0+o&Ue!T180T@`Ts24I0O z+jkkG<*5+ME(rnbTd@M3Nd&;jh*(Uh)*K+wvWDIfz;gouL)c4FD-6{MT#fYjpJa>v z{*PCN?l_8NxhY^%#1I5%Q^juuZuPU6yjRvM0niF^8krGAiml029<6p#B|v&Ju$xn! zh`L+Yt^(GF3QLy;jQ)Hw`{@K`k{a!4tyd<`0k*TuM{=*2vd(GR%)M24k+Gg5)coayzPc?1HFP@NFrTB1;?u{}%jufDp#&5`-9${Pp#FB9LLdXroN`Z_o?dksKq-MT!=J4;c|? z7OCLJVkqCeR%Ue8!hBDgFcn7)%wgSPl#l~pCe0d}dw{!$2*7-Xz;ujTO_)}J8wtE( zkU@8|o8&n4Sgo-vzJSJBAfqOr!TAM%X$N#s95wXoY%^h|tjz-03LSp?yk7gY8i)z% z)Ef5)g2Xkz4lQ2b2@kUaEX!yUp2rc$5(KQq-55s=7lf#>v!T|23YMn;-tw~G{k{j< zFZHd(?b{1r{e>2`Rwhudu;OJ90vIUeo8=o zaN&>|%P5Tg)i};^f}jkJ}*`%?vGHvl}l4zP6z<&2&Dmh*Kg;|~C+2_csJ zQVR=!16E;|=?bXWc;ZaGz$^X63xATkVe=(>JKYbJAJ$QP?PdPxEkOfqnk-5g*>4f2ymB90w`ku zOS}7snJ9oUGi9AT%B+4}rxZGO4(Fh8wKPA`3%tRZGXQ;ifNjXJhHLErXA;eokwyZT zDWcqt68y*64FGik748~608Z`)94QoOI!+Y6`);U#vtW7Vj(nafNgzq5jCWIU#Db5W z-_sQ)1X)L_g;c2k#!Db)mBm?n(Av0*J^`8lx;eEcfU@8bvNKT&U5Zl!u(dkdFxV1E zKU;?3DQ}-k71qR7V+U|Qfr~4Kvuna9X6S7J?sdj)k^yc`Z$jwR_#%x&umS*o^T^!* z1K?f~fKze+1|mAw_l_ z87UR(BausekoW^60swjc)^I_9N6vWya3xb<^9=V9`dB_jP_3@QHBoTX6Xgfwd9AFE z%qj?A0R_77IH{PZmV&fwzJLl-N|uxLZ47lmf!Hk)dR3<4%eCDixHci#JdtiZqRyP& z5XNVnl$C(_4}rT`Sp+p9!nq5$%sO2h2eLeQ$USx6MYRqV!KbEct8?x62EMXr9mehV z6*h+*SO41q~+z3GHi0po-5O}2vw_{q7-94%w?Jk9o zI*j9-Foi&MpK|}f>TGowdzds>rw_7IXL(zZPCXdyx#hWGZWS66`1Y`yl#C(MKt9zH zI>I~-_(j56*W&(hoc>z_~M8P%n zjT)#5tK9dSZRL>NbGC=11F>9=Sjcf!C+L|3x{J`oCdIxX$4JEn0TG5=N*W}j4x0ee z21Xdqb-`QPf*NA~%z&xKqo(be)KNtQz+)o!Ss$kftt@h%>=r?ZiY%SyQ`%0EMb;u} zdy#F*4Vh$4R}1`04l!xo}+BQ=ElL4z7@C%<_qAy^5RZ>JUW0G z4!@C*gJ1UaZN6;6_&wMKy5r77U*fopL`A04zl&9G%UYnaNT#`Z3I zV49_QzvVE0N#xCIpUfV2pJ7nSOf{kkz_C#U$PEW$^kwq|^bz3NMJfUqLplGHJ1pm+VSojO@}QfD08VfLWEbRX z*$->9CzAj6O>8-THMVB1D41?mXm6U3o|UJ=6R+BwcXI;x1n0hY2{^58 z;%Q%jpEPkjRA7t`ppXk(zi`r-R@=C-Eyw{_x~ z4d@{_(o(^7Vl~num^Qj8fuYtl!N63b&~q*$HFW9$&bI<7b%DP%`O3nK{`BdyAF_XME~Ef5UcEKh5| zue%`MC%CtV^64tdjF9p}JAAT)W-F?4uf85avr`TN#$8I8@=mAV%9F!aB#f%4K_awX zB323w!1OkccyvyH@t>%2eX>B&ORS`L$=qt`$moqD`j$ zuqBu!T(RXMtx$SL2QM1~AeU2vg+Z;OE0=Z~#W`ILU`8HbyP&O6#uFFnt%2N9;miXS z$p3hP>l{^pvNOD^Zc+A{Q}@}9r4#<@-J^SIq!EBQFgbZJZ!`WsRtJy)vHu(ASai(ue*O{~}}bnIHg?`JWl2 z>?#-lG~XLE=pPoKLb=F?M<_cgG|#avBpV;bWqIV~v_E_Z4>-dgPK8O3&2PL68__0C z*V`sbS~B}14)Ecg_y|m!b-s%fe!~gf@v?+SDy5XtASJ%bt$ql=w#X$>A5qT%;G9PH zF<}em00^{s>|z7Um^gNRU5EkTgaB+2pzH0CDffoOCLA9z_XQbof9x0lE4KozvXIBY zsc8X!E0+SUHz6p?q<5bhBnMbVu1|h4iHh^wA+F?V85XrN=Jbv(R^MqU)#epldWQhJ z$Ju+cJSPdTErl#>qRw5&z1)Z!OyGZj-5`xgg($5jZ;hqTmccq0y5-mUY#G~D0d|h8 zua-e_P2+^0Peyrl6~H$1`9WXp5?1QI?}Y!wZftImCKJ{&pZVHutft6oQt#oTayi7k^#0cF@Tpa)vfDTHqQfXmVnMA z!UX_3!6d*{r~>EoYVsr}lYPcrj`^1h<=ZCUK-Ggx>V5DNQfO!Z&S!&Iw%_!iR%VsBm@^ z&grUWJjxkXc+0b{?5J!djf@B)(FRNXh3=i}a}jXdtPCf^yduSXXC{GjUAHm!;zuN) zuij~QN<08y!N?8XE0G~Q4$JGLLI$JJs?3fHNp&#^Q+cGETEjVPx2h_-lm$Rn=ELJx13hQI z(YakC;ph^Mco)G_C41HcFbU>hCqsUQy8fwsp4cxLWehLQHU zTYP}R&5!=T2QpR!*q#D!zObhP(^|%=I9viSI-@7hRH+NBOo!0=mKQr3BVr!`ZYU;H z+)6{gW`y}#rq(xPu_Cevj~G4 z?u2GMn*vVnwL$p9!6et6d34W05Qf?vXUx_09OiZ7`0JcOopuQ0(NFLUZXvmO`*9>B z?-N&w@G~hcjG6my8>h2oq5)ugT>G9kS_fcTe4P1us)k(~$j%;_#)WxUYH&mQ1^BR6 z_YKqLjE|v%1IHmZAbS88nm(mYde_o+EzJ~!ZbfXBt{FofZ1iH>EaAU9JXhsk$J6;z^emv5&oNt zh`Li!;f8-Ica_B)T>L{-4L@&}m1Uv~$~*Jd?;SCTHWc*+==;|EEW>=1cfO3WD$TK_ zWpEbJ7@j)XnP18VkuGyPTNGsp*Qhfyl>OX;E6z`uoHi+}tSP^eaG|uEBwnTRNNQ;@ zu0FbrIVoy9%Fj&`YfKZyP+;mw%w;fS)r9q&qzCBr?yl!_}!D^lKCn7pwqCi$?&iU&1~AxLa+d{xZe6) zv$}6;IW0J-rZp2^XN{rDBWXKl6+HwCP0LW$Qc|9+kSiP>Ecn!SIhgVdk8wdnI5>uv z=gOPxf(VL6YW%vL&N8h0uVIYmpqi~Q5f6iVS*7B&d4(VTQo5E}P+S-rvgx!bOmdi_ zs&rWXi0)E;=uq8t{4<&UpHd53-=Qym;LfL#h7pi1@2@NdJ&v%qdI zY&6me(BDtj-`9D{6kpRX|8ZJj3v41%T+*@iXi#7`pg z6-DGZkS7ZVBAG>6?fIYIxGN6sGYoRw4hI2?mPi0JHv;H9Yb=8*;8bb)U`dJ)hDmsQ zQ~~t>k=9OP3Yc{O*a;p0xkX@_k8-nbqC)yxp(fP!YBd3eOE|YXCk1K~JCfQEz)+YO zn4t+!3^0GGQ!CgD+&EsoHhY5TJ6rI!X$IhZ>tqY-a{bb`RwVKYeB{KMd+x4L-EnGc zX`LE5e(?G}87tsr$pCYT1njuc@HLSO3lQt^dtW`GJXb`ZcVLFv2m)XXONE6@mZPV3 zNhJYb)TK&Y+D0G(13a_Lssp`xYs?S|?2~?MJldt}zNLwGewAyxp;o2_$q&n0xv(5@ z7zpCE3e7u1eVWL#mKF&)k0?MAtEj=U?z`kHLn81HeDe-~+t!ruLodM*N&DrQ`NYaQ zvsT#$nDz`sfW(0@o^iNf9_PF@v}3T+LINK#mCcu3WE;n zjAl7S8Yo`z0!$Dy31%hE^8o2HZy@_5pzXK^)H(zmj0^1-Zp95D&$R z+zK~HpK}0d#>oT`PDcz@S{A;7bYVM@@RXKyj5UmnZ}AQ!C(%4ftYn>TG$nlg0CfjP z`G(GLG{8Kx%Ts;G2rA@e-6;ByOC=O&QYXLS$Ib}N-Bik}0>Zy|K4K&WB z&LtSFqn3jhXSTl~PwtsI@;i0Tv8ZLI)C6iClt`nnZtGhh<=dRVn`Dr<8B!+Bjr|yb z4LnV$)R4?f_8d;y@jDOzyVW!*_Ygey5=^x#TfTHBpHBba+_y^F2jmoGTyJxwNkwS8ou=IT|99*^)fC2c=c7RY+^ql)YAuMJezLskS|x}ILS$0|l8k~}o(W{%iol28&_$SG zsvI`~u)B~%%A3m*(fkofeHNO{G>bg08g-mKkS7Ta;@p6+sNoFTPQpgkVzbq|MxWho zY@I?ADYp3&NsP5Sa{?7e-tKgryUWl|Jw1!AAWfGc+5CD$w07{-#+9`EgYX6ZdKSZB z!Pxz=OLiyMfI7?2h>Q>H=$3O`TyWZX!L*aB3#n?_yP3cRQjU1|MunP+b9s0&%R~Db z0aX_wl9q*VirTj5yJ^7uaN_t>DNm++Ua*I1)7Jii@XCN&Q$g3A?tGR!KvGTSf)*B` zCK|!3Us=p3K4l0y(&cVP4@*0!T`CfiL_mp~7#B%YL{Mvj&r`eA0g4_6+Ky%n(Kw3w zuBn10XlgkNKw2onD$+IBi1qEv6?vGTuPjKfZt0g%USCxxwR2F zCcvgopHU?~A)0w-+%1nQT}Va1>}htVPjoQkY~pQ^rsggv)?@ROWu4#u=kGXZ0P?$vN`SsmUTjD?VF8$-6wuoQSej0tcQRF(TL5Rq6`O4a7C;kI z-bcYLJ7KPqwmnQh26vSx@A3s8NG@%U*l`@|oZtY;W{u=-%NJq211Y1gTNh7K!!KzU zaT!8b)_xUWDR}}?nD`0ZfpP=L1{+W%z5)zHk2d+H+$~=KJHjAPoPr?4L`?`ju-c7R zSS($@^yW?hv_F^%%a#d9Jb+#85733}0y0X= zjY@7n0xoz5;@N}PqIkg?u^QQr41|DM+p8!u z@BnR8miLk?fn&x`4YIE-^QQ->@h`_NgC|7-YAJx_%>hy!3W+jLxmZ9c>U(DbY7&5% zO#uH;GUo;fu)>?DKIC(!>ty)|%yyOBz%9e_$am@A;>OR@EqASd%gzcnYrPeE0L|5Ru&D5_05W+6;{ZyMm*`C|QFfpJi%_Xh z4v`~4OIHGPM<2km77|n#@qgUOD147dFwM1K<-lg8=FwfwzWMTwra` zAG<{pwLtNCN7Cy_X4Sl%7LK4d{ReO7T~4$pADX+oH2$Tm9JGh$82=jM&XRPFtpLf z%K^|E>sWpo%=ON}zP>{y;+fa9E)2S)H*L5m5(ke!FcWKKGX0YD)aV8;@0WPGt|LHs zUki{y9UF3W?8fXQ6$siRiCG{eaTW)$kb(fqmC{D3WPw-q8Z3=}L=9Jr8UqY8=ql`i z2e*W#KyDVmxpe0}^5S!tHn}`P<_VHHhrY+4F}H@YO~Shqx+qu@0YE-x-Tc|$IExGLLDOH zgP_7-{AW22|LbJsnOWCNlcuHJl!=MgZHT3HDX2W&!V~0xU;wXdXv>uGr(aL7_k?7> zXaU^?gKwf!cVOTP{o}35l9=)mFUkzPpgf}h9aGM@cuj$}S(BhuXP&u*xlU4^qeQr$ zb~h<0M^m2%7Pe0KK0SP-AGgk-bO79%V(#I_q51U$dHn0aMc*&TV! zH@{0W%B;JuJ*C6&wV9&3wGR^}ft2+G4cM-|5}lNn9AfxRo7)Xrl3^UZ&&-up)p0RC zR+4V%8&UUtJa^;W0Z4PyiiHcu{LFCUHHtdnlqcTqVPS?@ZJ57jv%H@2QiR4WypHlV zzo5|aw^^>33kAC|e11Rs41=yXyNOWj=cVSDv|<3l-_(!mYEZ-1FP6lrN*x^4IRr4z zx;y@Y3NjC)-7W{$)1($u$7lXiH@R!0ExU=|7( z*WX}oYNw&;OpP=3v({7_E1VsrQv z9VzaPX3N~wO;EBO%ao0`DeqVcWpm61Eg5&p`htYe`yh}e9GY-H(S6W^kcp_3@*F{a z|2I?Y3@rT2i-@KdJtbr2C@p*UZMvc%zH#QXRN6YcNtN8S>yg;$nR z-qC%^nl3L=Y@Z8d14_zM|CG(GP@W>C+$D+M%gk-{)r9=+H&1OZ*`n-e3CiOa%S;aC z<=iVXJo=l-vMh1sdlk23Vq%BekuA!uze0|?X;`1v;`W{K^A9wi)QmkT>n};|(j=7O z>t>_PT9gfbovnx3I+IRjiW74Fxw+q!*{G&tg*9h4$13YR;%Dz*r8UQ}96g$?$zpDi zE;;d;`*tkJP>vO%v0LgordM>)wHiCX$mt-iTax-4Kmw> z^BqZj%5x-I!&`R&@yk{sm--c99z;I7Iy>ut-rc7!Z70tS(55m0v$4$ZlF06dfT z)mQ{o`FXz9P(Pyk??jpizOVcA=L-Y$F=x!hr$cL90d_aOwD+!dio*3>$gPxMvhF(3p_F(qz(x*WYr z`*Zn0y897?K-B($Jj?&Lb}6D^rOtM7TBn5vkP8GrT5b~2`@`9k4dD`zbs1#aLuh9X zw8+)DK7(*gZ%^F`5RqqVM&e=1tzaj()wGxx*kxZjiVrMArpmcVSuO9=c1wM07-{vTcw))HgRkwn8~%9@gC}Rh=Py z&6EQ_KIN?GxX2E@{D}x;^C5fau3+-zsgft8>!H2^4Bcag#t9Md=I)vx2Y&wDM64B%&b?~( z{ZBs?h4Apu(%S(T*N}8*NIo;u&9mLfIq> z9Ae}oaujvJZVzp_xjJK#mA3m9+5^m%~SZ9)I0P^sFEJ-t4<*|z2ln7}#B*ZYoI%yJ-GF87KN7A`!)+ujN z%dRkqv=|}sO33c90m+53j+@GT*TTgRw+o1p1$a5S%QLEv$toNg|UZ+bQh?GMaru)@cD3CU|Je+us{rZf`F~TUjUbA0qpJ zY$-8BP8G>Gh#)Tl%lik&2qK#utH|&m+qh?)CRro}9byt0W9yF^0%OPV4Mr5F&dD&uX1p){d+SVl+B@LvAv6 zAk;eT;qz5vN|BLs9~7#})4dxbRc=TVVV_YNZDqPu!Cd z`$I?d4RqU!LX<1&kP3fi4-G6*@}v2DBxV-EDL)dn!ef>4l039TWr%u6WEz+{Ib|Zb zsMcxaPUPq=({66=GCS(D##J3Un7Fo}9P%(+OD?tiAm0^1%E9fOIzHru&7}Rq1+^gZ z3c!R>AUYG2OsL(b8!v;@vOt2yO2em$CZA@WYlN+{hM()DKTkb3P(KYr=J^}%%bl)l z!qY$I_+I`DA=Th)Sw&6B&`<6`I`;>%1yt+6Va@0=sUfj9OA6yB>f~Iq$ne~+43bdb zfX+Npr{iwaIin>KG2AT@_khq<*DAK_)>oBn1~~-+(pGYi1r*jHA3_INyn34<^baVk zvr6l3RKY>Nk(crldF#MZJ+-xFpBh`@XV3ou>69N&eM6Eqvks;oe5yS^wfq3Cjri{D zr8S~D9e(M@s$m1)7Li(sa~$SFn{uv_q8w~>j>gNXhQvCo(oLb&8zmH~f8Ld7U1$&^ zr;|xnzC+l~8YcK4`B@GAJ%J}0Do%602W1hQ+YNXAZ?@iCFfZUL{`2C)_ z{-1%jmFrAd!-8Yry)GI1)Iryf-WKb|n03WSN(tyE$0^kHI`i9jCx3+KnPAn#L8 z@cZ)=2r_k{WS>1wTFY(G&WIk$@|c0`E&OtM-Z>*Dca&NPB=P&PQBu6UfX4 zaJv-c0)WayJ^-W(A{I{^kQuJVh8B~qNgvpShn8h^fSJ<(*53e@g%VIbNzGK7fXWD< zOh;vV$$Y#6bDIEwDr&@%31HfH7@olbSnzKX-AwH^eoe1a*ezM`&Cv$$ml?zvduGt% zER?&XI~K5$tmu>~5MaQR?~BNk-8ls?Nwk8S{{g061YCGgKr&_WZuh7^8#!WTX^D_! zD&lss&;sifBtU;trnQCv2_OXJS1R3*BXHxCtLc^itO%{XOS;|!_i5x7y8F*<4M@L; z@h-@H#z#ce2$05S!p>T?srf3{S4ODMCeT@6)S|r$p|*_vxl_aW&8B7aNmve5Q@*l`@Jt56a2E7@juMU(cK2D*l^1f`K z#4zd5J1+oMnSui8G&St?usX9;ve@Oi6byCp|7FUTVDl&4q^-vms~9HA+b{Dp2oM$? zj^)}f0#=id*=wqQb?CHzAq zKFFEQ&NIP@Alo2go##YDTR-`tD2S^yOu|i&NbgdJq!=`S=0WnZLHJ*`6ES)ODeWjwTmWzy3Z$J- z#Hzcz%sS5*nWZN}Jm5o}rA9V9u%M#Ik7Py0b zbce*E9R?`j4r9)6fRulAUunihK#j#SyCKGh{6>+;Hh_eb^L`^-8Ni{f62XR$pC4Rj5{T=-du&iXXGLecHZbMJ> zOh8bCb1R$$MU*-_TVtKh1fis6#{gRUhxt$Kfw&P!ao7=GA1ZN)oGm&J(EurVx*y1y zoHPmE4+JLSam--1td8) zeG38`czcftJdl$J5jqX9@TV#Q2<&FKXW%!GqekrpEIsBk@~ErPvo@Sq>&63+bCEpN zCUrpWRQdM4BbQP=>4 zyC#xX)sO8EN6d9+z_OM1z&~6{3~i_ivS1&FikXDtKuT>fqi9SuKFD?nsj5uVd2#zk z!LxiKl}doo6;5TG0(PG`z6%rxLP3xc==Dwn(REsI$WiNs&Gp+_6kuCZwV3 z(rysQoHFcAi<3|0&e;TczTS<*%S#~3uEzt)umW=9LYnL$$VI2}l56$+zf~Wf z@^A&Y45;kl&*Fc&nj0sRjf5cC5Rh_Xalg7j;N;hpd1X;#5&~5oWT7xrX#=wjOXV-+ zsx>H(ZK+mZ^Caxws~Ns)k2DHbfVF6iH={=T=L=tQ&N0Zvt0E9pho_8oRp>Loc}dnN zh{4j#DHxKswKVwq5FOnho@NeSi=jxH zYV==cU%eNtxB;``yBQ>iOps%o+63vOI><>dNHPL)ZYD^|9=CjU8i1W>g&$j+wqY|% zo(-BZ190`kvq96f08E*ubhatQM;1VtaWZioB4bl$cR7eGus~3*85mouM@+phWU#=T zwFfu{TtHn5vg_omqDwDwrV`}e_6D(?<1BDh-WPTH*eWd{*vi5%lO*{oB2J5MnspE< zHbSKxtv<+ZzN(#`LUqkAds{}~ExZTW+qJ4=lc$4f+IJy2JTZOM`1ZD%Jew2z~yAr=#iIBYYOb?{@6DLk{00-i0+k8PgkLzR3iL~{$z zKD5Jni00Z=JQOpnYo6{aLa)w##SG-;^AW}Ai7mpAd0mLdR$1Hn=eHkFe9Nuq(y}5V zc$c_+=*w(G2$KUa+Y^A$xFNPVt`%pLJ+X_Leba6Xa0ikCE7GDA2Xy8oh)hpnX`-P> znFvf7V#A!mRi`;IZgG!Do29T*+ZXVIRN1cY(a7#yr0^6-!x$-#0YTN{uovxqg zk2)S^CyH~*odCOYKgJ$oq1keW$tb_#=h@th3{tJ5@d6`wV2*qA0Eh3N6rz4m->Q zO;!Rsi9F;ID-wmfGt62pxX*5 zDQ)mrLIpE%EzFt-2)D)Ck`5c3E2f7f$pfCirYPdg=vV5SsL5*-lh)+!0N=^)wE5#j z!~0n%8;8i5{Oy3rC0 z-OCVc+PaMq?sdIFuQ%%`-`iPVFtJ{Hqe?haZbv_}<u#>`Xq&37=WQRQO}pi+clwvycZa(;4-n7cM~EIgJl3;wy+P+8*yqrP_%= zU>&#$Qe%i*LK5WxAeFOtT$Cq9{hWAYFYZl%Dm|A7Ez}aVgHe>h${^?tBsei=O*T?Q z0FVy(m4^3$y7RvzEXL+-U_xLY52nK(wH7gGw<5uH7R_ioYB;D|&5Vc+*0ZQdnMe}~ zt;c{rxi^|C6`_S(dTjj1sIWOlM`M^SA+$~o`6DB_apPGtbj*-*U3_?)W=sJsJlnP$ z+1!^~-26(rOP>8fM(sd1S#a8sIxE6-na4Y%yMoIZgrMSYw0dYFOM;W*NY2X`c2qTV z;ce;3^Utjvwy*o7fE&6Qlu||dy1`G$T8NN(ioZMFaKQP*@lbb9fDCx_9xLQG8vh_T4lY z%jayWsF(Puz}RS|xjFXyoWr3@uQxmxi8HVzaQ(K?@*B_A3vj)q7@4Iv1AH?apui1_ zN#3Z@oR@Vq^ChO(ohCI8Xh9f^A+wb$3Er`^Nq#!I)VhmBtgo94+Sdzk#4z`~B7)}d z0d0{gfIRj+_T}t`H2h69pf(4$W2DtL3N+yTYc_6Y4!|Hh45ULCrrw6?gBu%d((Bl# z?G1hP`4Zz>&hYZj@IrbNo-_r22IVRg zLq`hFE5DA#CY*TgRV3*sif#)W!Uy$XAtA>3evy`S-D4)h)1OW#&jpJMhNaBLB`>RS zYw5tdqYCi#5S9env0+cwr}U&${Tn9d$#TEYALTK^yRw$B+0t6|zWn7EQJz6+;-7^? zr&9N|(NP7n08gYryjfW*!hBaDe7sCtZACTAfI1hj?Y@8sH4Pl{B+Ym1+~9|?*n~Z8 z@JX+kc;Ed&fv{Q#QMN|u@(_htzTe}l3N=065K(ho(?s5Q zg*R2oKiZawxSButv}>fH<27?4ls&L&i2K})L-;tBWeGYtBE`L27LnoNrUbgdI`~Tn)m3W9r{#rs?F2tExI}6tJ%`8r6uwFXoAT&EV2)(fpA2M5!~2^WKys zIDaO=uw*>2QVf530GO)@wJ|W{aXM288tBDxnVlC7Y;158+RtjLIo%p=kxvvPRte}b z(V7$HHqA6~DJ4!(6X~@46c(HJqdcy5Zda`n#W>!D+dQNZm4urlp3kD3G-Gf*UdKsb z$P!yM@7&o|%wfQBJupb{L_88XJxbJtZZo4Gtykn`66`uB@A@xAevM)=+2YG*YAP9P1@+#TKh69xho>lt=`ZY1!%b?W#& zN(c+OK`Dcg#|s5l`O)b4;=2eF4JPPkiUo46Y;zEUYF?bh+4+w)1+Y`s(2(e z3;~7k)Xz(W{4${%LHQb?%P)5*ysb?GPRv#Zm+v$`__G^-`bU1|5R;8#yJW7%U<~C< zT;^O%-h%u!!5|)#H_t>T!-XFq{G<1P?QWVs!fD;j=iDj} ziRY`*<}=cZne*%>W8nsd3FCU8{ooR*a3eHWT0HFLG@|~>{P?)?6cLJ681+Dg=Yxj` z*9ALeOB4SwjLPLH)*b7uQHUuc>^X;(g~ZM!7*^C$I80|EVZCn~kF+bn;!TT$NQ0+L zBC$6yNc&7d^ZtDDJjhNaitmtJ;)Kobx16llQ+8&dHW#+KGZF4QQ@1IR`x_mh=tr0A ztU}d}8!*Ti#ag+jgVcMbp^ir26ybABb;W1pF87LbY;z*y@p_ILK$NGjeZWscGjxL$ zD>4TGC$k1H-xk_Q0tMOx`^zrQJ^;oK5eHeF;0}xrF?-R^(bam^SD*63Hag>_C$T%5 zu*1zs1Tip}d)HEGYU19edg61zQ4;@l&b;`K31H6Bs<3!KBnNlLuf`&yQ?X?ifd$C0 zC(tLG!L)lH@pZrKD@j$MP*I#aYm_lUof^V>I}AtwI5!bEu6>J-DM&%t;Sqt=HN)+M zegSO`^8kmaJ8KQ`)N*A1bRPNVOev>~fUk$3Nn<$d=_T$1vJZ%vk_>;hRsq*75(s0G zQ|Z^<2RV$z!rb_`2{-s%c#XbE0jORzU`&GubDIOPDId|YIDqnSMx{4>Af{003akEp zGa~2 zMYo9s>mQ`nj42Nz4Kxl^_+Xufi(Insct3qPIwECSRm2vkK0S82tp=gu!?eEwM77|L zI0&%or_|^^rVH`^e5QnHy~*4Pl9Xy0m1U^-Xhu4pwQ+!I?O-c-I<(6JA{g&Pzv%TG zV1sz$uc6yRC>y3$SnCkrHjS#0MZKFNQvk~bHU-q6;ujd)wx2wf|HF$8*QFj@7HRv8 z`2cTVt|(9k9y;JEg3wWm4Q#M5QwDFfz@x#D({?mj|8}9CGy~3XRVAlCH;N%}YQG9P zone+&9U5tS!7cFp^0Gyo2nFpW9gPyJ4SK(FEIii4^Jdbe4y6(R(ygNTetILK47jPk zk=w1zuPlxoo&>C{i#Y-iHNG}Ovcx_lnm9C0*$|mn53^|n1+B1_Wwe`5TuvA9;QBD9 zD3-n)St=yFuaiOvQIqut2a{HmR_$^iLid-U>pkc2U{a=E0aDf_*|HCZ+r^u=w+9>P z(t?{I%JC+&m)wkhg#bG-KtC)*{f6R%Q0v#_$4Ro|J+AR~7St*g3vg~NT;>@lGXs2^ zgwPM^Yfuz28;<_tH=(Z*iH0Q_JiAGo=|@fmq+cAW3X0D$<7;xjtL)twOrXtyo|O1v z9C~liQEFo?vqRBn|KlPp7yusKFb0K!4z$rTLf}!ir7>XY}EIy{h|4^4l;uT+ij7(USd9!rRf|rc?+Z z&c%8$QN(ZjUw2hJnFepkLq@2 z&;JwUP1HuOl!-I)5O2I1#){pP&Q=)`HIPRG-B*J*cbQgiky}uS&!Jr~6$|#7b#Q}I zHnK+enwJW<_2(8#$CfhxkUUOx$%|Mp2}dC5_0IzzPQ z>4?RJyD2@Ms+7f8oyWfn8|A5`=R$xhOheQkP7q1L!R$gnV4wvIIiVP7JfHlSFOGAu zGFx#niT}Il1Q5ZaAcH}Dl%0BV@GKJ=#MgGHjzMp~3n7P?EUT{@6&~r%(Tw{Jg~ZrA z1+}mY<>NYE!$0MCvS-}k+_5O_+NKOD5XM3MKKE(o^(`(*$hXS3I5@x;X_aE2?V;bk zD9DK%t2Mn~FR6sVW)oxl;ZqE?DtTjvxH(++#^&d-sa;}Ypdd*=%?XrP*<#kMImoj< zDx1EEw&9&33}lSUm_@#GZ;#NBRu;dgHA9wIhnUlV2728|cCy{U0hY|G<&_MVd8=f1 zv6^ornO>9l;2wUB!Sn`!Y^@a?}D`(ozc=Mk`2O);W`Ov`eUiilaie372~ zcLMIA`U%2EWYRqQOxPhV{Ma8iKZccv?yZznyMmR69moGTiUhPJG9VSADV!dQep}EE z4CTN!kClK4#3FZ4A-WT_qs*ehwrZ$hpOGgsQFfLa@lw63wI3G$AUC9#;{6MHifG{Udw^}Ey(doF{+c$d zb4TyTlgf-%HnKHAqane}>|<0Wm{^?>SK6*q|QE+_*|}SsuXOWiSHPGS@xE9}9X@JE0WVr4sy)$nLc@ zw@^0&7Y&~UWY2DAYcHYH)YcQ==o65MM8t%*i}zFJODtL@kq^CcW9;WnZ?dp3Z^$qc zRAY^_ju)*^t-HaCfjex#-|CmIeyn%E{4qZT_IGb1JH~LS!f(i@g2pLl(oQy4QUJLH zhOj?BRSK-Fxh@7-Q=`it*^UU3E@;%<7eJ;~Pa%iVNK%LTm)=uQeS<`QVq%2k*{9)B zE#yp!p@2mXlSdmLZ1=Dz<({;qRJ}5>85CX^+I{^%?_q}-bB&LA>V3&S8d#=H_q2O)VNJVbT0MQd0Ld)bjcaa{-c1~G9(#02tv;9 zno(Dd$%Ku*WKGx4C%UDqj4ttY@Niv2tm*W(hgJQ5?REri2c@iZU>8pxMzt74R$LfO z(_{*5tmT`Xdb=ZAyBb7=lxZBTM|V_8bn2BvozcG6#)y1BpZa6r=<>I8*>&V;UQaV}6L7yGj zph&{Ng>(mCNOs>E?*JHv`_W65sZEmwS@L2YxIH&O*9QWfnJLGQ9ow6J?9^in_FP!9 zo=nv-+hl+ULr@_c%U9(fW=H<@p$8~N?Mm}iMt`W$UgOX#jnj`ixS*bhY?AtOT$9?5ml|GO%pHJXDUE>QT z_f*#<<3(w?*%)xL)uB34fdPo-8_nQ=F;559m7(S?{@q^;h+0}yfIO^_#EViNZP^%R@qUrod3bCg=sBbz0T2@0?pP|^-o4v4)^mNQEZ8LvXNeQkX8>e2&?CAr>>`L=>^sN9jMD%q$m1qu^ zhSsTZqnU3Zrbq-|pMgon&IKFPFm?WDyyW9o%SoLl~l3=6t&z z%V{GauTdLvldQ*en8A@VHdIj>N)M^s4Fc<>c_ktk^Ly#~GXT)@O*5b(^wsviZYfX$ zY{O&z@ydla#~;GI(hBGhwMP_~ZFxu9N{ssobod{YV7flQkDlLs!-{xy?p*6501<77 zJ!|jK!Pe!E>W1@!u1XoxhwoCbE^H2?k0?HF!4c*f3@YDMN#0esf>u4=WgQs6;li;s zEz!cMQ5uyn5c1VewS95<`q^$j+q6bIP2Cfua?AC{MnsT<0f$33)T)U>$Pks6r+|K) zOZLyqRQHe*?o3We#BjXO2E$)fptfwkIjE}0D$L6>SLT-aTVU-T--wE`#3;$R^8Oez zGO*y%c;w#+xHcsQn{6j;=(yvNK5{p$$3(Nmb#%Wv-Rty-zFK1<9QcRSpE!??!H0ZY zRB)^fUU5&(Gr2d95AQOnJTU}lsGHGnG4c&z{OFtx*K zZ9QBhCDfdPySo;2!DT+PY$FMp;m-hW0;@9gIW|N#-t_?mnwhy;*Bgau>D-IWgcxCTmd zF1*M&TKf&jU|ydP(GFcHIjS$ph39z`X zb)zk3+Cfu{u~rMmiE%bmt^ENp7HBy4=Gvh+33$9sg$F|=>4%MVSN60XWQ(pK@ZG_C zlgcfmIsL;CiXxD(gy0Vhw$!EeEL_1UE(%}+qIfW`MGE+fJP$=y8BXib{y+fE!(ovU zP@M0I*EF*Ch!Q_>5X*FaUl}x?pMpeTUOdtsNZw|44qEW$JV49`CimoCI zLW*G+d+rs&ubYsAEw8{JMN{!B*C!POxja*9;V6R~*6M9LAX`!6d@uJeE# zD(msObzq|Xz7?bLL|LxqVA0g&O)11B-#yutGYIFE9_=&dfko{CA_uXgy359QZI!+( zRO{F8__lZ#sfFKEMT_*nV+Hap`%?ops_s0`$t$d{T@$74SwARB{|w{a!oeP4T~KYL zjF`oJ?WcnHTqcBC_sOAYYvy0WR;lzoUSIjQvqXkK93Mtfly*Sn#U8odrw9FIH*qHC znE|c4cz(i!!8mJNUJYU^QJJ%B;ck+JrOn3g8dFlhL8oz~N6@<^#mHt=eCxbPQ?%TS z)7|%nV4kgm8g|QPiXCs3jb^m{DG=bErXcwdL?i{YrAP!N1@jFsqr5w@Y6`0)>jhLC z%#hl%zc)OhZm+8^`5FF(JN5bjb8uCw6G zUiG(d+dbi79M10JRg$TYie;3fagsupPO%x&$;Vmk)zCn@`ukgP@w>b^|8!;W6cpDb z$FYG}2XY=Z*^e8C>rQyjt=7(Uf=Khr8@cM4u{}wSN$v7CKTqskzZ@$O(l@&TR|A3V zu(Ao3Rq~eN9`azDFMb<2`^B|yj-RtdWY=V=eU!y>#Tf_7dkzW4DTt{_((aWEh}NgT zis&|aaf+HQ-O3f)C`x3GkGU!m(r5T#b(YEKawy@vag!4Q}{Mw_(7(bt-Wx|A2isCa9nErt9txe zu@-p#TAMXDr0(tAzYOA_#za|Sv66f!_^8~U-8J81K< zn@VK*tS^{e8?v~)xE4^ae#mwFs_GR}yX)dSHns0T*+sxnZ61X%&4OH6`tYV$sGxR3 zJj!@9@`U|5X#SsKn3KFG}d+|H_mhC@mW>n9%abZIPlaw}u`D1GrHR|i z4ANS3eVhOElZLz3s&4<5m)uT8Eiirf3aGl{*DAV(zG<>Eqj3mCp72<;ZYB)|^M{QxRN@{8O^lhIXbsRQQQ&{A=;8j#yZ) z>9Pm5=g!gLlY!^S^K}o7u*W;fFS4Bf`U#MdJ{sZn@LCiWFZNt5F5?i?8q?=%Rq5O1 zJe-;DVvP1V<6n>epqA7M0y3jYI)atRb-0HspY zV`|Mo8@?Od?Mj|7j<|qy+KK_`7_>shcSRM55xHZs;Q8O+CepBEwR9&iS*|5vqaMfg zrpU895v&c)Z~%pdx-mxuRGcL*ojphd)0~(Kq#OudG^@;2INK?;xy9b>6Po~MvIzMz zGX$@G82NkR2mbzKKnAYby(3%um~o22*KF6RVoqw0f;LXu0GiUAagn|jo2o6yp?R%; zVM8{N-@Q`daDlLF$54-lBaPM|P)Qfofw*??6qpd~*~}L$n(ODbwny@5*=zXI=kOIG zSF!5op?V`La}}F-58XmtACBn{lJGu57wSH0`o=c1L+UWnJh#H~$w*+*SDQQq_LY-k zxmqAL^Ka=S7=@afL*5h5QGd5<#p1t{RGB#47>ebMBAEBPn`k+HNW_o%z?-;)oGDxu zvLdc;wIYp%-Ig=sND||jLxmfBIy5?gb#Brq$N9=2mqXK0zh8ez_x(5RFz?iOwP7%+ z6+E113J}B0Pl}GZ@QogM~JjwKC>Pc&TZ+*ks%TKPK_^ zde7RuBdb?9;@bcIT+rRH%q=y>D_nqy?R-ZZp{A&Q^wLD8&R{iQ*#y)LRu61 zLBo;zsp6=t5HeZsJ#kd#VB#-BreSx#{=B5HBGY^5l`$M)eEoTkqqsJdI0y#0* z|Nd*b2yS5RwrE2bamSxJ$tClyNOq^e3~n#WYVT~Li&mqXhOBcS{qxnj=kHW=?C2xs zOflfok^oLrt)MNLDi*L=$kBwk*A8cI)BdJk=5_+zWC+Io3}4ym_VWXygL`-Zz1 z1LQpi!rVVz-VB09H61(ejC5OcZaf_$fe_)qLFB#%QC&G4>+Zq8Pm1!1>CQQk;)3=c zc6qVJaLQlG3fmpD4^x;}bgzY%TVlhw)Y2kjmIVFpt!bLW-+df&nv{7+m-E@FKhPHQ zgf&wmTM6b2l{zwqd5n0=bS*+~`i!y8eoj*TGJ;f0D>e$beJW|o-2C|gn&=Q4-hN>S zO~0G{^AA}Ff{(|JgO|Qx_wlM$Nj6!&h&N*)nuq>Lf>lNuGw zz0mg=$<}VgN^!NT35w#QvkL#zG552 zYYA5QUGPJ}syg}xlTfA(pCHbgn}bi$ZqRwwev#!@BIV^Fc3H)^s7c-j<@^@uzdJR+ z*XS&dPjHPX@_pTIXDkq+=xUBEkwmw%UxAENe`Bm+Qeuf%3HdkTgJDe<3y1we&1#P+Q?LXZhng&n052V_Y%fthoCAq3bj zaFF~lDPsDQ0zoi$(gllMA7lVe+m$tCCng}=P>urEcL)JBpMHCLBIuuc``a7dBW#)$ zZQezRMLwZs*leMFP|lFYd6;neMjs-q4>22|Vw(mO9{zB)duaW~;et$*quxZ3w4AO` z=339%ZMBIy!jOUE`x|QLNG3vCiaz9Y{AuH}U`klCIP8NNd;l8Xv=*o(me{WcuRe8O zY|E=`qxq&J&Og`~aJ9zKN2YH?wUQYRG%QA42~*~Dk_ylYE!&a>kZSq%jQU9wr zKe6#Ogb8_)JBSAF@yV_8G(q4(2~|a*^4xUOn0zQ)(TQG^tl!9Q<8EwDL1?JOZcqxl z`RtPH#uD!be>%aTX!TbOs~5Y@Nd;v;D9;Ql$ha zQlgC{fIVuJZUbC*>WwG!N{9OoDG=zzP-cnh@XK;Pg0x*wH+b9n@$gHzM?y%S2}!QA zOW6M?@Rfd@Xu{~!9e)Ax@JK1lZ?3hk%Du?5R(=r<7kdF?Pp_uOzX=b>dG5R^q*5IbNIAnseXtvVIbM#cUq?y4J?+g1a-EFf;37T2a?}_ zK7#ODbeFAwp1Ah?A;OXeUcPevKp6}_ZT>5?<#*S|B>4Q~Ad7sz+;Kw6 zwgsLc*6xJL$2M_34=1hPk`2 z(m>mMoXkatWQCZN9VK}W&6h`If|gN7-tm+|v>*eMo93Mm-_(EQ)@g7{*IGZeFP1R_ zPQkKX=Z?usV<=O~V`!xvD!I&EL1i9Kavml>lksIq!i$`H@dXRkzka^UYJ~Zl4>gHM zuyS(z_JLe7=lD;zANmz!us76(2$trDb{>aB=WHL`UQ^>uR1XLE{S7K&jaj{$&7WC) zqL`m7E^c)$Nc8kzEuwFMUUtOQ+<9U!U4{-OW=DHY6#k7GG(UBJC4BRt`n>)kCq8>t ztu+^v_Sa7(DXvE4jYhhi(=w=@NAKqjX?gVCJfjkubgS`7P}&Z=LE(fsaa%m`?CX9L z*Vuj)cefQzl}CzVKnBlgyjki|qCv!Z>YRdZ|DL^p&z*~C(Knm0)awZ8HTT?)HrpJB z5+1?m{xJwlyjO@PXb;@;CZ3^PF0M?2%g!qfznCrXdnhZt9PmACd!HEjm2kudM`Y?d zq%stM+c3O{HwTiteWdXXOzAZdwd?dn@zi)FCeA$BwWvKtNu_tZ(~^4nl9k`zkN=J> zD5w8Ki5J&C@+0D2R%|Wvexuel_-U&g!{%DjgI*MC^3sTti`)5=mXeb8-8E=DR+jl^ zS>(z)w&0LI_pJ?1THN2YDAHfbI)AS8-ut*Z9^Jb6)xQW3J#O!=zT>^Z%;3qA8<)rI z3e~=)&e$sZ#3_Vv_h53w=gGTidt@ukKK>)=(s_=_6f(4GAR^VXLyet*a?koNyKY;z2Uk@|7TQ)mZ1 zp&h$OM&9+QP=6qC1BS5I>rUEj1OuB`2#{S}aP5~y^BhxeU1I%{}*?scpB3$FU88ou{f?Rds?{phkH7f9SqaC&FgDrCM$ zRihN*@K-UGk1jvuo2G?G+9^@YjY3qcPIwH;!hP0Rx8O#`N;^d8 z6q}~0pF958H@TFKhv23@W|E9=EiU)sOB2W%(roRCSmNx|(zYzgoyYk%!#TUU@QdhQ zO$slpf0u7a7Kjv0s5Y+FUf!NI7B2rYaBU`;-dPWk*Fvtr;3fMowq#|4>#|B zlUk^pYE-O7hhFGqkTw`kt4`|BB9&W`spP6v!}@g|1u!Nk}gOnne+*VYzZ{y_%3_|hwul~t)Q{O#_718Uv9!Pc+A z;I;hrC5c8*nhp^_m0c1L4PqcV1gC0$`$59<20wn2#>^AJ%|lp(Qd~>3Kh)rSSMiIr zdn_}9;h>1rV49?dFF&qZV>_FEwMMI`Z>#gXLfLkNs;u-vw#Eij4+5>s~RO z&E!kQtMG1?x?+zCY)=%WHMh*M2wEKlvfDwr#D9;Js-p33G z3>VVqP(&Ja69c4a;pki?0>FW%M%dh_qkTR0bx93g2|NM+j-DvdjALAPRU~P&f8C)c zSbNeJvyqhi409d;<0c|`7oze7b8vy#%rVHJyzX$@R6rP10UItIjzaQ04+{2Rk5#{J|zDmaI-BEXB%_ zTE-?bMD~}K)Oe2%_d_~55jz?3ILlB;%o18%B&{KKL+ef2g=`Y~RERW7#fSI`3Jk-^ z1TR=%tO9M&wMG$gWclwCJ2D>$a*>E&8@oy!gyNX(--&j~{s3&@X5UkgA*0A}b8`B~ zWLGj$iTZRP9BQW|no@9;Y<41MDOqQ{LXyV;9AadVMJ6%fFv)(TLENt82a9D(C9b7R ztIQ87M85=Vv3Y|ZL&_|dn#%PVYbAV91aNZV*@r%uCzu;GW;DUATAYcHV~)T`_Q>6X zI*5&VT>0za+p$*Sx}m3o7`qHtAA4A~@h?NL2E6`Qex~k2{X+ib-OmKd;eN(M6hnBY z5G?9+DmrI69c)tMBjndGobP;^!IkRXG!fYTL&lcOOPqCYQfq2LN}UjYh`)51 z7DlD(qJDK|SDvAIuS}p)Ag6o^Z^qw@{js`~nk1*R(~M8_>ZvOkei>#Q1&n6YUzGlp zzjS~#2OtC5!6l6!isW`%zKew`%4Qd*Sw>lATSi-k?(zT7r0+=%PHx9luY#O3&eNAs zlS(a=`OkN>sI~~N+pKd@$P1P}FQlCOxS>4my+N^|w=p_oIwU_NJ^VJVh4`Jz{DD`C zq%1Bat~)N_FW;}unf;j!fd&WDw;txSM;2F>&uKJiwrQZWglZLCwAj+*$HiW$HBnLIPTw}Y3+-;G_-0Ub|{w}ZdMey5OTllGC4km{0V@D1~m zWV>dMWgliA@r|_D8=|$s8y*@SwVHCJWnE0_*wTNC6)LK$Kd)e)6EEGW5v#MR{HAYL zqV{bX&m@_{NKmrfxLw;%N?n;#pVO>C^Rh@>v!Je^v|qm8=*u{4mTKKRRx)RxvM8pg z-y+|lWY>zeI;m!krNppAWca;Rn@7x*_`VTCV|1QkvSR$0s`l#QwvKt%Ov?bWp1A|(*z*hPGD4)?PcFS+SI{lH_AYQY%u9NN3PYqcR%w zlJpwdlkY7r9WN`yg~g-A3-~&H602=5Hq2!!5qcdJ41WUb0`-Y36@S~d$Jb4jwu<_M0ocVX?ehm8P z2hVOPDjlK6ZV+{~}%n_%EC= z>%y1ojW;^g{7eSAc5nMm6I}lD)UW-Skei6NA^YhXv%RQUsM*+OZvXA_*RWKll;&