From 583cca94827f52a988ed8a174b51192af797de72 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 17 Mar 2026 14:09:17 -0400 Subject: [PATCH 01/12] Steiner tree improvement --- gtsam/inference/BayesTree-inst.h | 226 ++++++++++++++++++++++++ gtsam/inference/BayesTree.h | 10 ++ gtsam/linear/GaussianBayesTree.cpp | 8 +- gtsam/nonlinear/Marginals.cpp | 269 ++++++++++++++++++++++++----- gtsam/nonlinear/Marginals.h | 3 + tests/testGaussianBayesTreeB.cpp | 57 ++++++ tests/testMarginals.cpp | 236 +++++++++++++++++++++++++ 7 files changed, 767 insertions(+), 42 deletions(-) diff --git a/gtsam/inference/BayesTree-inst.h b/gtsam/inference/BayesTree-inst.h index be466e43df..dd37a64c95 100644 --- a/gtsam/inference/BayesTree-inst.h +++ b/gtsam/inference/BayesTree-inst.h @@ -364,6 +364,14 @@ namespace gtsam { return std::make_shared(*jointBayesNet(j1, j2, function)); } + /* ************************************************************************* */ + template + typename BayesTree::sharedFactorGraph BayesTree::joint( + const KeyVector& keys, const Eliminate& function) const { + gttic(BayesTree_joint); + return std::make_shared(*jointBayesNet(keys, function)); + } + /* ************************************************************************* */ // Find the lowest common ancestor of two cliques // TODO(Varun): consider implementing this as a Range Minimum Query @@ -387,6 +395,21 @@ namespace gtsam { return nullptr; // Return nullptr if no common ancestor is found } + /* ************************************************************************* */ + template + static std::shared_ptr findLowestCommonAncestor( + const std::vector>& cliques) { + if (cliques.empty()) { + return nullptr; + } + + std::shared_ptr lca = cliques.front(); + for (size_t i = 1; i < cliques.size() && lca; ++i) { + lca = findLowestCommonAncestor(lca, cliques[i]); + } + return lca; + } + /* ************************************************************************* */ // Given the clique P(F:S) and the ancestor clique B // Return the Bayes tree P(S\B | S \cap B), where \cap is intersection @@ -408,6 +431,157 @@ namespace gtsam { Ordering(S_setminus_B), eliminate); return bayesTree; } + + /* ************************************************************************* */ + template + static KeyVector uniqueKeys(const KeyVector& keys) { + KeyVector unique = keys; + std::sort(unique.begin(), unique.end()); + unique.erase(std::unique(unique.begin(), unique.end()), unique.end()); + return unique; + } + + /* ************************************************************************* */ + template + static std::vector> uniqueCliquesFromKeys( + const BayesTree& tree, const KeyVector& keys) { + std::vector> queryCliques; + queryCliques.reserve(keys.size()); + std::unordered_set> seen; + + for (Key key : keys) { + auto clique = tree.clique(key); + if (seen.insert(clique).second) { + queryCliques.push_back(clique); + } + } + return queryCliques; + } + + /* ************************************************************************* */ + template + static std::shared_ptr rootClique( + const std::shared_ptr& clique) { + auto current = clique; + while (current && current->parent()) { + current = current->parent(); + } + return current; + } + + /* ************************************************************************* */ + template + static std::unordered_set> collectSupportCliques( + const std::vector>& queryCliques, + const std::shared_ptr& root) { + std::unordered_set> support; + if (!root) { + return support; + } + + support.insert(root); + for (const auto& clique : queryCliques) { + for (auto current = clique; current && current != root; + current = current->parent()) { + support.insert(current); + } + } + return support; + } + + /* ************************************************************************* */ + template + static std::unordered_map, size_t> + countSupportChildren( + const std::unordered_set>& support, + const std::shared_ptr& root) { + std::unordered_map, size_t> supportChildren; + for (const auto& clique : support) { + supportChildren[clique] = 0; + } + + for (const auto& clique : support) { + if (clique == root) { + continue; + } + auto parent = clique->parent(); + if (parent && support.count(parent)) { + ++supportChildren[parent]; + } + } + return supportChildren; + } + + /* ************************************************************************* */ + template + static std::unordered_set> collectEssentialCliques( + const std::vector>& queryCliques, + const std::unordered_set>& support, + const std::unordered_map, size_t>& supportChildren, + const std::shared_ptr& root) { + std::unordered_set> essential; + if (root) { + essential.insert(root); + } + + std::unordered_set> querySet(queryCliques.begin(), + queryCliques.end()); + for (const auto& clique : support) { + const auto childCount = supportChildren.find(clique); + const size_t numSupportChildren = + childCount == supportChildren.end() ? 0 : childCount->second; + if (querySet.count(clique) || numSupportChildren > 1) { + essential.insert(clique); + } + } + return essential; + } + + /* ************************************************************************* */ + template + static std::shared_ptr descendToNextEssentialClique( + const std::shared_ptr& child, + const std::unordered_set>& support, + const std::unordered_set>& essential) { + auto current = child; + while (current && !essential.count(current)) { + std::shared_ptr next; + for (const auto& grandChild : current->children) { + if (support.count(grandChild)) { + next = grandChild; + break; + } + } + current = next; + } + return current; + } + + /* ************************************************************************* */ + template + static void appendCompressedSupport( + const std::shared_ptr& ancestor, + const std::unordered_set>& support, + const std::unordered_set>& essential, + typename CLIQUE::FactorGraphType* factorGraph, + const typename CLIQUE::FactorGraphType::Eliminate& eliminate) { + for (const auto& child : ancestor->children) { + if (!support.count(child)) { + continue; + } + + auto nextEssential = + descendToNextEssentialClique(child, support, essential); + if (!nextEssential) { + continue; + } + + factorGraph->push_back(*factorInto(nextEssential, ancestor, eliminate)); + factorGraph->push_back(nextEssential->conditional()); + appendCompressedSupport(nextEssential, support, essential, factorGraph, + eliminate); + } + } /* ************************************************************************* */ template @@ -447,6 +621,58 @@ namespace gtsam { return p_BC1C2.marginalMultifrontalBayesNet(Ordering{j1, j2}, eliminate); } + /* ************************************************************************* */ + template + typename BayesTree::sharedBayesNet BayesTree::jointBayesNet( + const KeyVector& keys, const Eliminate& eliminate) const { + gttic(BayesTree_jointBayesNet); + + const KeyVector queryKeys = uniqueKeys(keys); + if (queryKeys.empty()) { + return std::make_shared(); + } + if (queryKeys.size() == 1) { + auto bayesNet = std::make_shared(); + bayesNet->push_back(marginalFactor(queryKeys.front(), eliminate)); + return bayesNet; + } + if (queryKeys.size() == 2) { + return jointBayesNet(queryKeys[0], queryKeys[1], eliminate); + } + + const auto queryCliques = uniqueCliquesFromKeys(*this, queryKeys); + std::unordered_map, KeyVector> keysByRoot; + for (Key key : queryKeys) { + keysByRoot[rootClique(this->clique(key))].push_back(key); + } + if (keysByRoot.size() > 1) { + FactorGraphType disjointJoint; + for (const auto& [rootClique, groupKeys] : keysByRoot) { + (void)rootClique; + disjointJoint.push_back(*jointBayesNet(groupKeys, eliminate)); + } + return disjointJoint.marginalMultifrontalBayesNet(Ordering(queryKeys), + eliminate); + } + + const auto root = findLowestCommonAncestor(queryCliques); + if (!root) { + return std::make_shared(); + } + + const auto support = collectSupportCliques(queryCliques, root); + const auto supportChildren = countSupportChildren(support, root); + const auto essential = + collectEssentialCliques(queryCliques, support, supportChildren, root); + + FactorGraphType reducedJoint; + reducedJoint.push_back(root->marginal2(eliminate)); + appendCompressedSupport(root, support, essential, &reducedJoint, eliminate); + + return reducedJoint.marginalMultifrontalBayesNet(Ordering(queryKeys), + eliminate); + } + /* ************************************************************************* */ template void BayesTree::clear() { diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index 02c10bcd88..12ba27033b 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -180,12 +180,22 @@ namespace gtsam { */ sharedFactorGraph joint(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const; + /** Return a joint factor graph on an arbitrary set of variables. */ + sharedFactorGraph joint( + const KeyVector& keys, + const Eliminate& function = EliminationTraitsType::DefaultEliminate) const; + /** * return joint on two variables as a BayesNet * Limitation: can only calculate joint if cliques are disjoint or one of them is root */ sharedBayesNet jointBayesNet(Key j1, Key j2, const Eliminate& function = EliminationTraitsType::DefaultEliminate) const; + /** Return a joint marginal on an arbitrary set of variables as a BayesNet. */ + sharedBayesNet jointBayesNet( + const KeyVector& keys, + const Eliminate& function = EliminationTraitsType::DefaultEliminate) const; + /// @} /// @name Graph Display /// @{ diff --git a/gtsam/linear/GaussianBayesTree.cpp b/gtsam/linear/GaussianBayesTree.cpp index b35252e729..58c9dbb952 100644 --- a/gtsam/linear/GaussianBayesTree.cpp +++ b/gtsam/linear/GaussianBayesTree.cpp @@ -119,7 +119,13 @@ namespace gtsam { /* ************************************************************************* */ Matrix GaussianBayesTree::marginalCovariance(Key key) const { - return marginalFactor(key)->information().inverse(); + const Matrix information = marginalFactor(key)->information(); + if (!information.allFinite()) { + return Matrix::Zero(information.rows(), information.cols()); + } + const Matrix identity = + Matrix::Identity(information.rows(), information.cols()); + return information.selfadjointView().llt().solve(identity); } diff --git a/gtsam/nonlinear/Marginals.cpp b/gtsam/nonlinear/Marginals.cpp index 15653ba8ac..cbd4c7f596 100644 --- a/gtsam/nonlinear/Marginals.cpp +++ b/gtsam/nonlinear/Marginals.cpp @@ -19,12 +19,164 @@ #include #include #include +#include #include +#include + using namespace std; namespace gtsam { +namespace { + +/* ************************************************************************* */ +KeyVector uniqueSortedKeys(const KeyVector& keys) { + KeyVector result = keys; + std::sort(result.begin(), result.end()); + result.erase(std::unique(result.begin(), result.end()), result.end()); + return result; +} + +/* ************************************************************************* */ +KeyVector uniqueStableKeys(const KeyVector& keys) { + KeyVector result; + result.reserve(keys.size()); + KeySet seen; + for (Key key : keys) { + if (seen.insert(key).second) { + result.push_back(key); + } + } + return result; +} + +/* ************************************************************************* */ +std::vector dimsForKeys(const KeyVector& keys, const Values& values) { + std::vector dims; + dims.reserve(keys.size()); + for (Key key : keys) { + dims.push_back(values.at(key).dim()); + } + return dims; +} + +/* ************************************************************************* */ +std::vector blockOffsets(const std::vector& dims) { + std::vector offsets(dims.size() + 1, 0); + for (size_t i = 0; i < dims.size(); ++i) { + offsets[i + 1] = offsets[i] + dims[i]; + } + return offsets; +} + +/* ************************************************************************* */ +Matrix informationToCovariance(const Matrix& information) { + if (!information.allFinite()) { + return Matrix::Zero(information.rows(), information.cols()); + } + + const Matrix identity = + Matrix::Identity(information.rows(), information.cols()); + return information.selfadjointView().llt().solve(identity); +} + +GaussianFactorGraph reducedJointFactorGraph( + const GaussianBayesTree& bayesTree, Marginals::Factorization factorization, + const KeyVector& variables) { + if (factorization == Marginals::CHOLESKY) { + return *bayesTree.joint(variables, EliminatePreferCholesky); + } else if (factorization == Marginals::QR) { + return *bayesTree.joint(variables, EliminateQR); + } + throw std::runtime_error( + "Marginals::jointMarginalInformation: Unknown factorization"); +} + +/* ************************************************************************* */ +GaussianBayesNet queryBayesNet(const GaussianFactorGraph& factorGraph, + Marginals::Factorization factorization, + const KeyVector& variables) { + if (factorization == Marginals::CHOLESKY) { + return *factorGraph.marginalMultifrontalBayesNet(Ordering(variables), + EliminatePreferCholesky); + } else if (factorization == Marginals::QR) { + return *factorGraph.marginalMultifrontalBayesNet(Ordering(variables), + EliminateQR); + } + throw std::runtime_error("Marginals::queryBayesNet: Unknown factorization"); +} + +/* ************************************************************************* */ +Matrix covarianceColumns(const GaussianBayesNet& bayesNet, + const KeyVector& orderedKeys, + const std::vector& dims, + const std::vector& selectedBlocks) { + const auto [R, rhs] = bayesNet.matrix(Ordering(orderedKeys)); + (void)rhs; + + const std::vector offsets = blockOffsets(dims); + const size_t totalDim = offsets.back(); + + size_t selectedDim = 0; + for (size_t blockIndex : selectedBlocks) { + selectedDim += dims.at(blockIndex); + } + + Matrix selectors = Matrix::Zero(totalDim, selectedDim); + size_t selectedOffset = 0; + for (size_t blockIndex : selectedBlocks) { + const size_t begin = offsets[blockIndex]; + const size_t dim = dims[blockIndex]; + selectors.block(begin, selectedOffset, dim, dim).setIdentity(); + selectedOffset += dim; + } + + Matrix intermediate = + R.transpose().triangularView().solve(selectors); + return R.triangularView().solve(intermediate); +} + +/* ************************************************************************* */ +Matrix assembleCrossBlock(const Matrix& selectedColumns, + const KeyVector& orderedKeys, + const std::vector& dims, + const KeyVector& left, const KeyVector& right) { + FastMap keyIndex = Ordering(orderedKeys).invert(); + const std::vector offsets = blockOffsets(dims); + + size_t leftDim = 0; + for (Key key : left) { + leftDim += dims.at(keyIndex.at(key)); + } + size_t rightDim = 0; + for (Key key : right) { + rightDim += dims.at(keyIndex.at(key)); + } + + Matrix result(leftDim, rightDim); + size_t rowOffset = 0; + for (Key leftKey : left) { + const size_t leftBlock = keyIndex.at(leftKey); + const size_t leftSize = dims[leftBlock]; + const size_t leftBegin = offsets[leftBlock]; + size_t columnOffset = 0; + size_t selectedOffset = 0; + for (Key rightKey : right) { + const size_t rightBlock = keyIndex.at(rightKey); + const size_t rightSize = dims[rightBlock]; + result.block(rowOffset, columnOffset, leftSize, rightSize) = + selectedColumns.block(leftBegin, selectedOffset, leftSize, rightSize); + columnOffset += rightSize; + selectedOffset += rightSize; + } + rowOffset += leftSize; + } + return result; +} + +} // namespace + /* ************************************************************************* */ Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization) : values_(solution), factorization_(factorization) { @@ -144,63 +296,62 @@ Matrix Marginals::marginalInformation(Key variable) const { /* ************************************************************************* */ Matrix Marginals::marginalCovariance(Key variable) const { Matrix info = marginalInformation(variable); - - // Deterministic constraints (e.g., NonlinearEquality) produce infinite - // information for the constrained variable. Treat those as zero covariance - // rather than attempting to invert an infinite matrix. - if (!info.allFinite()) - return Matrix::Zero(info.rows(), info.cols()); - - return info.inverse(); + return informationToCovariance(info); } /* ************************************************************************* */ -JointMarginal Marginals::jointMarginalCovariance(const KeyVector& variables) const { - JointMarginal info = jointMarginalInformation(variables); - info.blockMatrix_.invertInPlace(); - return info; +JointMarginal Marginals::jointMarginalCovariance( + const KeyVector& variables) const { + const KeyVector variablesSorted = uniqueSortedKeys(variables); + if (variablesSorted.size() == 1) { + Matrix covariance = marginalCovariance(variablesSorted.front()); + return JointMarginal(covariance, {static_cast(covariance.rows())}, + variablesSorted); + } + + const GaussianFactorGraph jointFG = + reducedJointFactorGraph(bayesTree_, factorization_, variablesSorted); + const GaussianBayesNet bayesNet = + queryBayesNet(jointFG, factorization_, variablesSorted); + const std::vector dims = dimsForKeys(variablesSorted, values_); + + std::vector allBlocks(variablesSorted.size()); + std::iota(allBlocks.begin(), allBlocks.end(), 0); + Matrix covariance = + covarianceColumns(bayesNet, variablesSorted, dims, allBlocks); + return JointMarginal(covariance, dims, variablesSorted); } /* ************************************************************************* */ -JointMarginal Marginals::jointMarginalInformation(const KeyVector& variables) const { +JointMarginal Marginals::jointMarginalInformation( + const KeyVector& variables) const { + const KeyVector variablesSorted = uniqueSortedKeys(variables); + if (variablesSorted.empty()) { + return JointMarginal(Matrix(), std::vector(), variablesSorted); + } // If 2 variables, we can use the BayesTree::joint function, otherwise we // have to use sequential elimination. - if(variables.size() == 1) - { - Matrix info = marginalInformation(variables.front()); + if (variablesSorted.size() == 1) { + Matrix info = marginalInformation(variablesSorted.front()); std::vector dims; dims.push_back(info.rows()); - return JointMarginal(info, dims, variables); - } - else - { - // Compute joint marginal factor graph. - GaussianFactorGraph jointFG; - if(variables.size() == 2) { - if(factorization_ == CHOLESKY) - jointFG = *bayesTree_.joint(variables[0], variables[1], EliminatePreferCholesky); - else if(factorization_ == QR) - jointFG = *bayesTree_.joint(variables[0], variables[1], EliminateQR); - } else { - if(factorization_ == CHOLESKY) - jointFG = GaussianFactorGraph(*graph_.marginalMultifrontalBayesTree(variables, EliminatePreferCholesky)); - else if(factorization_ == QR) - jointFG = GaussianFactorGraph(*graph_.marginalMultifrontalBayesTree(variables, EliminateQR)); - } - - // Get information matrix - Matrix augmentedInfo = jointFG.augmentedHessian(); - Matrix info = augmentedInfo.topLeftCorner(augmentedInfo.rows()-1, augmentedInfo.cols()-1); + return JointMarginal(info, dims, variablesSorted); + } else { + GaussianFactorGraph jointFG = + reducedJointFactorGraph(bayesTree_, factorization_, variablesSorted); + GaussianBayesNet bayesNet = + queryBayesNet(jointFG, factorization_, variablesSorted); - // Information matrix will be returned with sorted keys - KeyVector variablesSorted = variables; - std::sort(variablesSorted.begin(), variablesSorted.end()); + // Get information matrix on the reduced query system. + const auto [R, rhs] = bayesNet.matrix(Ordering(variablesSorted)); + (void)rhs; + Matrix info = R.transpose() * R; // Get dimensions from factor graph std::vector dims; dims.reserve(variablesSorted.size()); - for(const auto& key: variablesSorted) { + for (const auto& key : variablesSorted) { dims.push_back(values_.at(key).dim()); } @@ -208,6 +359,42 @@ JointMarginal Marginals::jointMarginalInformation(const KeyVector& variables) co } } +/* ************************************************************************* */ +Matrix Marginals::crossCovariance(const KeyVector& left, + const KeyVector& right) const { + const KeyVector leftUnique = uniqueStableKeys(left); + const KeyVector rightUnique = uniqueStableKeys(right); + KeyVector unionKeys = leftUnique; + unionKeys.insert(unionKeys.end(), rightUnique.begin(), rightUnique.end()); + unionKeys = uniqueSortedKeys(unionKeys); + + if (unionKeys.empty()) { + return Matrix(); + } + + if (unionKeys.size() == 1 && leftUnique == rightUnique) { + return marginalCovariance(unionKeys.front()); + } + + const GaussianFactorGraph jointFG = + reducedJointFactorGraph(bayesTree_, factorization_, unionKeys); + const GaussianBayesNet bayesNet = + queryBayesNet(jointFG, factorization_, unionKeys); + const std::vector dims = dimsForKeys(unionKeys, values_); + FastMap keyIndex = Ordering(unionKeys).invert(); + + std::vector rightBlocks; + rightBlocks.reserve(rightUnique.size()); + for (Key key : rightUnique) { + rightBlocks.push_back(keyIndex.at(key)); + } + + const Matrix selectedColumns = + covarianceColumns(bayesNet, unionKeys, dims, rightBlocks); + return assembleCrossBlock(selectedColumns, unionKeys, dims, leftUnique, + rightUnique); +} + /* ************************************************************************* */ VectorValues Marginals::optimize() const { return bayesTree_.optimize(); diff --git a/gtsam/nonlinear/Marginals.h b/gtsam/nonlinear/Marginals.h index 6e2b316912..e57d76c18a 100644 --- a/gtsam/nonlinear/Marginals.h +++ b/gtsam/nonlinear/Marginals.h @@ -130,6 +130,9 @@ class GTSAM_EXPORT Marginals { /** Compute the joint marginal information of several variables */ JointMarginal jointMarginalInformation(const KeyVector& variables) const; + /** Compute the cross-covariance block between two variable sets. */ + Matrix crossCovariance(const KeyVector& left, const KeyVector& right) const; + /** Delete cached Bayes tree shortcuts created while computing marginals */ void deleteCachedShortcuts(); diff --git a/tests/testGaussianBayesTreeB.cpp b/tests/testGaussianBayesTreeB.cpp index bb1180903d..d02eec64be 100644 --- a/tests/testGaussianBayesTreeB.cpp +++ b/tests/testGaussianBayesTreeB.cpp @@ -319,6 +319,63 @@ TEST(GaussianBayesTree, shortcut_overlapping_separator) EXPECT(assert_equal(expectedJointJ, actualJointJ)); } +/* ************************************************************************* */ +TEST(GaussianBayesTree, multiKeyJointMatchesPairwise) { + GaussianFactorGraph fg; + noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1); + fg.add(1, (Matrix(1, 1) << 1.0).finished(), 3, + (Matrix(1, 1) << 2.0).finished(), 5, + (Matrix(1, 1) << 3.0).finished(), (Vector(1) << 4.0).finished(), model); + fg.add(1, (Matrix(1, 1) << 5.0).finished(), (Vector(1) << 6.0).finished(), model); + fg.add(2, (Matrix(1, 1) << 7.0).finished(), 4, + (Matrix(1, 1) << 8.0).finished(), 5, + (Matrix(1, 1) << 9.0).finished(), (Vector(1) << 10.0).finished(), model); + fg.add(2, (Matrix(1, 1) << 11.0).finished(), (Vector(1) << 12.0).finished(), model); + fg.add(5, (Matrix(1, 1) << 13.0).finished(), 6, + (Matrix(1, 1) << 14.0).finished(), (Vector(1) << 15.0).finished(), model); + fg.add(6, (Matrix(1, 1) << 17.0).finished(), 7, + (Matrix(1, 1) << 18.0).finished(), (Vector(1) << 19.0).finished(), model); + fg.add(7, (Matrix(1, 1) << 20.0).finished(), (Vector(1) << 21.0).finished(), model); + + Ordering ordering(fg.keys()); + GaussianBayesTree bt = *fg.eliminateMultifrontal(ordering); + + const GaussianFactorGraph pairwiseJoint = *bt.joint(1, 2, EliminateQR); + const GaussianFactorGraph multiKeyJoint = *bt.joint(KeyVector{2, 1}, EliminateQR); + EXPECT(assert_equal(pairwiseJoint.augmentedHessian(), + multiKeyJoint.augmentedHessian(), 1e-9)); +} + +/* ************************************************************************* */ +TEST(GaussianBayesTree, multiKeyJointMatchesLegacyMarginalization) { + GaussianFactorGraph fg; + noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1); + fg.add(1, (Matrix(1, 1) << 1.0).finished(), 3, + (Matrix(1, 1) << 2.0).finished(), 5, + (Matrix(1, 1) << 3.0).finished(), (Vector(1) << 4.0).finished(), model); + fg.add(1, (Matrix(1, 1) << 5.0).finished(), (Vector(1) << 6.0).finished(), model); + fg.add(2, (Matrix(1, 1) << 7.0).finished(), 4, + (Matrix(1, 1) << 8.0).finished(), 5, + (Matrix(1, 1) << 9.0).finished(), (Vector(1) << 10.0).finished(), model); + fg.add(2, (Matrix(1, 1) << 11.0).finished(), (Vector(1) << 12.0).finished(), model); + fg.add(5, (Matrix(1, 1) << 13.0).finished(), 6, + (Matrix(1, 1) << 14.0).finished(), (Vector(1) << 15.0).finished(), model); + fg.add(6, (Matrix(1, 1) << 17.0).finished(), 7, + (Matrix(1, 1) << 18.0).finished(), (Vector(1) << 19.0).finished(), model); + fg.add(7, (Matrix(1, 1) << 20.0).finished(), (Vector(1) << 21.0).finished(), model); + + Ordering ordering(fg.keys()); + GaussianBayesTree bt = *fg.eliminateMultifrontal(ordering); + + const KeyVector query{7, 2, 1}; + const GaussianFactorGraph actualJoint = *bt.joint(query, EliminateQR); + const GaussianFactorGraph legacyJoint = + GaussianFactorGraph(*fg.marginalMultifrontalBayesTree(KeyVector{1, 2, 7}, + EliminateQR)); + EXPECT(assert_equal(legacyJoint.augmentedHessian(), + actualJoint.augmentedHessian(), 1e-9)); +} + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index 344a1f56c5..6b732a4064 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -27,6 +27,7 @@ // for modeling measurement uncertainty - all models included here #include +#include // add in headers for specific factors #include @@ -37,6 +38,136 @@ using namespace std; using namespace gtsam; +namespace { + +/* ************************************************************************* */ +KeyVector uniqueSortedKeys(const KeyVector& keys) { + KeyVector result = keys; + std::sort(result.begin(), result.end()); + result.erase(std::unique(result.begin(), result.end()), result.end()); + return result; +} + +/* ************************************************************************* */ +KeyVector uniqueStableKeys(const KeyVector& keys) { + KeyVector result; + KeySet seen; + for (Key key : keys) { + if (seen.insert(key).second) { + result.push_back(key); + } + } + return result; +} + +/* ************************************************************************* */ +std::vector dimsForKeys(const KeyVector& keys, const Values& values) { + std::vector dims; + dims.reserve(keys.size()); + for (Key key : keys) { + dims.push_back(values.at(key).dim()); + } + return dims; +} + +/* ************************************************************************* */ +std::vector blockOffsets(const std::vector& dims) { + std::vector offsets(dims.size() + 1, 0); + for (size_t i = 0; i < dims.size(); ++i) { + offsets[i + 1] = offsets[i] + dims[i]; + } + return offsets; +} + +/* ************************************************************************* */ +GaussianFactorGraph legacyJointFactorGraph( + const GaussianFactorGraph& graph, const Ordering& ordering, + const KeyVector& variables, Marginals::Factorization factorization) { + const KeyVector sortedVariables = uniqueSortedKeys(variables); + if (factorization == Marginals::CHOLESKY) { + GaussianBayesTree bayesTree = + *graph.eliminateMultifrontal(ordering, EliminatePreferCholesky); + if (sortedVariables.size() == 2) { + return *bayesTree.joint(sortedVariables[0], sortedVariables[1], + EliminatePreferCholesky); + } + return GaussianFactorGraph(*graph.marginalMultifrontalBayesTree( + sortedVariables, EliminatePreferCholesky)); + } else { + GaussianBayesTree bayesTree = + *graph.eliminateMultifrontal(ordering, EliminateQR); + if (sortedVariables.size() == 2) { + return *bayesTree.joint(sortedVariables[0], sortedVariables[1], + EliminateQR); + } + return GaussianFactorGraph( + *graph.marginalMultifrontalBayesTree(sortedVariables, EliminateQR)); + } +} + +/* ************************************************************************* */ +Matrix legacyJointCovariance(const GaussianFactorGraph& graph, + const Ordering& ordering, + const KeyVector& variables, + Marginals::Factorization factorization) { + const KeyVector sortedVariables = uniqueSortedKeys(variables); + if (sortedVariables.size() == 1) { + GaussianBayesTree bayesTree = + factorization == Marginals::CHOLESKY + ? *graph.eliminateMultifrontal(ordering, EliminatePreferCholesky) + : *graph.eliminateMultifrontal(ordering, EliminateQR); + return bayesTree.marginalFactor(sortedVariables.front()) + ->information() + .inverse(); + } + + const GaussianFactorGraph jointFG = + legacyJointFactorGraph(graph, ordering, sortedVariables, factorization); + const Matrix augmentedInfo = jointFG.augmentedHessian(); + const Matrix information = augmentedInfo.topLeftCorner( + augmentedInfo.rows() - 1, augmentedInfo.cols() - 1); + return information.inverse(); +} + +/* ************************************************************************* */ +Matrix extractCrossBlock(const Matrix& fullCovariance, + const KeyVector& orderedKeys, const Values& values, + const KeyVector& left, const KeyVector& right) { + const std::vector dims = dimsForKeys(orderedKeys, values); + const std::vector offsets = blockOffsets(dims); + const FastMap keyIndex = Ordering(orderedKeys).invert(); + + size_t leftDim = 0; + for (Key key : left) { + leftDim += dims.at(keyIndex.at(key)); + } + size_t rightDim = 0; + for (Key key : right) { + rightDim += dims.at(keyIndex.at(key)); + } + + Matrix result(leftDim, rightDim); + size_t rowOffset = 0; + for (Key leftKey : left) { + const size_t leftBlock = keyIndex.at(leftKey); + const size_t leftSize = dims[leftBlock]; + const size_t leftBegin = offsets[leftBlock]; + size_t columnOffset = 0; + for (Key rightKey : right) { + const size_t rightBlock = keyIndex.at(rightKey); + const size_t rightSize = dims[rightBlock]; + const size_t rightBegin = offsets[rightBlock]; + result.block(rowOffset, columnOffset, leftSize, rightSize) = + fullCovariance.block(leftBegin, rightBegin, leftSize, rightSize); + columnOffset += rightSize; + } + rowOffset += leftSize; + } + return result; +} + +} // namespace + TEST(Marginals, planarSLAMmarginals) { // Taken from PlanarSLAMSelfContained_advanced @@ -189,6 +320,25 @@ TEST(Marginals, planarSLAMmarginals) { marginals = Marginals(gfg, soln_lin, Marginals::QR); testMarginals(marginals); testJointMarginals(marginals); + + const Ordering ordering = Ordering::Colamd(gfg); + for (const auto factorization : {Marginals::CHOLESKY, Marginals::QR}) { + Marginals orderedMarginals(gfg, soln_lin, ordering, factorization); + const KeyVector unorderedVariables{x3, l2, x1}; + const Matrix actual = + orderedMarginals.jointMarginalCovariance(unorderedVariables) + .fullMatrix(); + const Matrix expected = + legacyJointCovariance(gfg, ordering, unorderedVariables, factorization); + EXPECT(assert_equal(expected, actual, 1e-8)); + + const Matrix expectedCross = + extractCrossBlock(expected, uniqueSortedKeys(unorderedVariables), soln, + KeyVector{l2, x3}, KeyVector{x1}); + const Matrix actualCross = + orderedMarginals.crossCovariance(KeyVector{l2, x3}, KeyVector{x1}); + EXPECT(assert_equal(expectedCross, actualCross, 1e-8)); + } } /* ************************************************************************* */ @@ -258,6 +408,92 @@ TEST(Marginals, order) { testMarginals(marginals, set); } +/* ************************************************************************* */ +TEST(Marginals, crossCovarianceOrderAndLegacyAgreement) { + NonlinearFactorGraph graph; + graph.addPrior(0, Pose2(), noiseModel::Unit::Create(3)); + graph.emplace_shared>(0, 1, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(1, 2, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(2, 3, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + + Values values; + values.insert(0, Pose2()); + values.insert(1, Pose2(1, 0, 0)); + values.insert(2, Pose2(2, 0, 0)); + values.insert(3, Pose2(3, 0, 0)); + values.insert(100, Point2(0, 1)); + values.insert(101, Point2(1, 1)); + + graph.emplace_shared>( + 0, 100, values.at(0).bearing(values.at(100)), + values.at(0).range(values.at(100)), + noiseModel::Unit::Create(2)); + graph.emplace_shared>( + 2, 101, values.at(2).bearing(values.at(101)), + values.at(2).range(values.at(101)), + noiseModel::Unit::Create(2)); + + GaussianFactorGraph linearGraph = *graph.linearize(values); + const Ordering ordering = Ordering::Colamd(linearGraph); + const KeyVector left{101, 1}; + const KeyVector right{100, 3}; + const KeyVector unionKeys{101, 1, 100, 3}; + + for (const auto factorization : {Marginals::CHOLESKY, Marginals::QR}) { + Marginals marginals(linearGraph, values, ordering, factorization); + const Matrix actual = marginals.crossCovariance(left, right); + + const Matrix legacyFull = + legacyJointCovariance(linearGraph, ordering, unionKeys, factorization); + const Matrix expected = + extractCrossBlock(legacyFull, uniqueSortedKeys(unionKeys), values, + uniqueStableKeys(left), uniqueStableKeys(right)); + EXPECT(assert_equal(expected, actual, 1e-8)); + } +} + +#ifdef GTSAM_SUPPORT_NESTED_DISSECTION +/* ************************************************************************* */ +TEST(Marginals, orderingEquivalence) { + NonlinearFactorGraph graph; + graph.addPrior(0, Pose2(), noiseModel::Unit::Create(3)); + graph.emplace_shared>(0, 1, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(1, 2, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(2, 3, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(3, 4, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + + Values values; + values.insert(0, Pose2()); + values.insert(1, Pose2(1, 0, 0)); + values.insert(2, Pose2(2, 0, 0)); + values.insert(3, Pose2(3, 0, 0)); + values.insert(4, Pose2(4, 0, 0)); + + GaussianFactorGraph linearGraph = *graph.linearize(values); + const Ordering colamd = Ordering::Create(Ordering::COLAMD, linearGraph); + const Ordering metis = Ordering::Create(Ordering::METIS, linearGraph); + const KeyVector query{4, 1, 3}; + + for (const auto factorization : {Marginals::CHOLESKY, Marginals::QR}) { + Marginals colamdMarginals(linearGraph, values, colamd, factorization); + Marginals metisMarginals(linearGraph, values, metis, factorization); + EXPECT(assert_equal( + colamdMarginals.jointMarginalCovariance(query).fullMatrix(), + metisMarginals.jointMarginalCovariance(query).fullMatrix(), 1e-8)); + EXPECT(assert_equal( + colamdMarginals.crossCovariance(KeyVector{4}, KeyVector{1, 3}), + metisMarginals.crossCovariance(KeyVector{4}, KeyVector{1, 3}), 1e-8)); + } +} +#endif + /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ From a67db3eeb5e346fe23dda78a307fb9a555a65afb Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 17 Mar 2026 14:09:26 -0400 Subject: [PATCH 02/12] Timing --- timing/exportBayesTreeCovarianceVisuals.cpp | 168 +++++ timing/plot_bayes_tree_covariance.py | 548 +++++++++++++++ timing/timeBayesTreeCovariance.cpp | 704 ++++++++++++++++++++ 3 files changed, 1420 insertions(+) create mode 100644 timing/exportBayesTreeCovarianceVisuals.cpp create mode 100644 timing/plot_bayes_tree_covariance.py create mode 100644 timing/timeBayesTreeCovariance.cpp diff --git a/timing/exportBayesTreeCovarianceVisuals.cpp b/timing/exportBayesTreeCovarianceVisuals.cpp new file mode 100644 index 0000000000..03916103ab --- /dev/null +++ b/timing/exportBayesTreeCovarianceVisuals.cpp @@ -0,0 +1,168 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +namespace { + +KeyVector poseKeys(const Values& values) { + KeyVector keys; + for (const auto& keyValue : values.extract()) { + keys.push_back(keyValue.first); + } + sort(keys.begin(), keys.end()); + return keys; +} + +KeyVector centeredWindow(const KeyVector& keys, size_t querySize) { + if (keys.size() <= querySize) { + return keys; + } + const size_t start = (keys.size() - querySize) / 2; + return KeyVector(keys.begin() + start, keys.begin() + start + querySize); +} + +KeyVector evenlySpaced(const KeyVector& keys, size_t querySize) { + if (keys.size() <= querySize) { + return keys; + } + + KeyVector query; + query.reserve(querySize); + for (size_t i = 0; i < querySize; ++i) { + const double alpha = + querySize == 1 ? 0.0 : double(i) / double(querySize - 1); + const size_t index = static_cast( + llround(alpha * double(keys.size() - 1))); + query.push_back(keys.at(index)); + } + query.erase(unique(query.begin(), query.end()), query.end()); + return query; +} + +void writeKeyListCsv(const filesystem::path& path, const KeyVector& keys) { + ofstream stream(path); + stream << "key\n"; + for (Key key : keys) { + stream << key << '\n'; + } +} + +void writeMatrixCsv(const filesystem::path& path, const Matrix& matrix) { + ofstream stream(path); + stream << fixed << setprecision(12); + for (Eigen::Index row = 0; row < matrix.rows(); ++row) { + for (Eigen::Index column = 0; column < matrix.cols(); ++column) { + if (column) { + stream << ','; + } + stream << matrix(row, column); + } + stream << '\n'; + } +} + +void writePoseCsv(const filesystem::path& path, const Values& values, + const KeyVector& localQuery, const KeyVector& wideQuery) { + const set localKeys(localQuery.begin(), localQuery.end()); + const set wideKeys(wideQuery.begin(), wideQuery.end()); + + ofstream stream(path); + stream << "key,x,y,theta,in_local,in_wide\n"; + stream << fixed << setprecision(9); + for (Key key : poseKeys(values)) { + const Pose2 pose = values.at(key); + stream << key << ',' << pose.x() << ',' << pose.y() << ',' + << pose.theta() << ',' << (localKeys.count(key) ? 1 : 0) << ',' + << (wideKeys.count(key) ? 1 : 0) << '\n'; + } +} + +void writeEdgeCsv(const filesystem::path& path, + const NonlinearFactorGraph& graph) { + set> edges; + for (const auto& factor : graph) { + auto between = dynamic_pointer_cast>(factor); + if (!between) { + continue; + } + const Key key1 = between->key1(); + const Key key2 = between->key2(); + const auto edge = minmax(key1, key2); + edges.insert(edge); + } + + ofstream stream(path); + stream << "key1,key2\n"; + for (const auto& [key1, key2] : edges) { + stream << key1 << ',' << key2 << '\n'; + } +} + +string argumentOrDefault(char** begin, char** end, const string& flag, + const string& defaultValue) { + for (auto it = begin; it != end; ++it) { + if (string(*it) == flag && it + 1 != end) { + return *(it + 1); + } + } + return defaultValue; +} + +} // namespace + +int main(int argc, char** argv) { + const string datasetName = + argumentOrDefault(argv, argv + argc, "--dataset", "w100.graph"); + const filesystem::path outputDir = argumentOrDefault( + argv, argv + argc, "--output-dir", + (filesystem::path("timing") / "results" / "bayes_tree_covariance" / + "visuals") + .string()); + filesystem::create_directories(outputDir); + + const auto [graphPtr, initialPtr] = load2D(findExampleDataFile(datasetName)); + const KeyVector initialPoseKeys = poseKeys(*initialPtr); + if (!initialPoseKeys.empty()) { + graphPtr->addPrior( + initialPoseKeys.front(), initialPtr->at(initialPoseKeys.front()), + noiseModel::Diagonal::Sigmas( + (Vector(3) << 1e-6, 1e-6, 1e-6).finished())); + } + + LevenbergMarquardtOptimizer optimizer(*graphPtr, *initialPtr); + const Values result = optimizer.optimize(); + const KeyVector queryCandidates = poseKeys(result); + const KeyVector localQuery = centeredWindow(queryCandidates, 10); + const KeyVector wideQuery = evenlySpaced(queryCandidates, 10); + + const Marginals marginals(*graphPtr, result, Marginals::CHOLESKY); + const Matrix localCovariance = + marginals.jointMarginalCovariance(localQuery).fullMatrix(); + const Matrix wideCovariance = + marginals.jointMarginalCovariance(wideQuery).fullMatrix(); + + writePoseCsv(outputDir / "w100_poses.csv", result, localQuery, wideQuery); + writeEdgeCsv(outputDir / "w100_edges.csv", *graphPtr); + writeKeyListCsv(outputDir / "w100_local_keys.csv", localQuery); + writeKeyListCsv(outputDir / "w100_wide_keys.csv", wideQuery); + writeMatrixCsv(outputDir / "w100_local_covariance.csv", localCovariance); + writeMatrixCsv(outputDir / "w100_wide_covariance.csv", wideCovariance); + + return 0; +} diff --git a/timing/plot_bayes_tree_covariance.py b/timing/plot_bayes_tree_covariance.py new file mode 100644 index 0000000000..1b2f54f5b0 --- /dev/null +++ b/timing/plot_bayes_tree_covariance.py @@ -0,0 +1,548 @@ +#!/usr/bin/env python3 + +import argparse +import csv +import math +import shutil +from collections import defaultdict +from pathlib import Path + +import matplotlib.pyplot as plt +import numpy as np +from matplotlib.patches import Ellipse + + +def load_rows(path): + with open(path, newline="") as handle: + return list(csv.DictReader(handle)) + + +def to_float(rows, fields): + for row in rows: + for field in fields: + row[field] = float(row[field]) + row["query_size"] = int(row["query_size"]) + row["queries"] = int(row["queries"]) + row["support_cliques"] = int(row["support_cliques"]) + row["compressed_cliques"] = int(row["compressed_cliques"]) + row["reduced_state_dim"] = int(row["reduced_state_dim"]) + return rows + + +def baseline_speedups(rows): + baselines = {} + for row in rows: + if row["variant"] == "legacy_dense": + baselines[(row["dataset"], row["ordering"], row["query_family"], row["mode"], row["query_size"])] = row["median_total_ms"] + + for row in rows: + key = (row["dataset"], row["ordering"], row["query_family"], row["mode"], row["query_size"]) + baseline = baselines.get(key, row["median_total_ms"]) + row["speedup"] = baseline / row["median_total_ms"] if row["median_total_ms"] else 1.0 + return rows + + +def filter_rows(rows, **criteria): + result = [] + for row in rows: + if all(row[key] == value for key, value in criteria.items()): + result.append(row) + return result + + +def grouped(rows, *keys): + groups = defaultdict(list) + for row in rows: + groups[tuple(row[key] for key in keys)].append(row) + return groups + + +def dataset_label(dataset): + return dataset.removesuffix(".graph").removesuffix(".txt") + + +def plot_ablation(rows, output_path): + joint_rows = [row for row in rows if row["mode"] == "joint" and row["query_family"] == "local_window" and row["dataset"] in {"w10000.graph", "w20000.txt"}] + variants = ["legacy_dense", "steiner_dense", "legacy_solve", "steiner_solve"] + variant_styles = { + "legacy_dense": {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, + "steiner_dense": {"color": "#ff8c00", "linestyle": "-", "marker": "o", "linewidth": 2.0}, + "legacy_solve": {"color": "#1f77b4", "linestyle": "-.", "marker": "^", "linewidth": 2.0}, + "steiner_solve": {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, + } + figure, axes = plt.subplots(2, 2, figsize=(12, 8), sharex=True, sharey=True) + for ax, (dataset, ordering) in zip(axes.flat, [("w10000.graph", "COLAMD"), ("w10000.graph", "METIS"), ("w20000.txt", "COLAMD"), ("w20000.txt", "METIS")]): + subset = filter_rows(joint_rows, dataset=dataset, ordering=ordering) + for variant in variants: + series = sorted(filter_rows(subset, variant=variant), key=lambda row: row["query_size"]) + if not series: + continue + style = variant_styles[variant] + ax.plot( + [row["query_size"] for row in series], + [row["speedup"] for row in series], + label=variant.replace("_", " "), + markersize=6, + zorder=3 if variant == "legacy_dense" else 4, + **style, + ) + ax.set_title(f"{dataset_label(dataset)} / {ordering}") + ax.set_xlabel("Query size") + ax.set_ylabel("Speedup vs legacy_dense") + ax.set_yscale("log") + ax.grid(True, alpha=0.3) + handles, labels = axes[0, 0].get_legend_handles_labels() + figure.legend(handles, labels, loc="upper center", ncol=4, frameon=False) + figure.tight_layout(rect=(0, 0, 1, 0.94)) + figure.savefig(output_path) + plt.close(figure) + + +def plot_ordering(rows, output_path): + target_rows = [ + row + for row in rows + if row["mode"] == "joint" + and row["variant"] in {"legacy_dense", "steiner_solve"} + and row["dataset"] in {"w10000.graph", "w20000.txt"} + and row["query_family"] == "local_window" + ] + variant_styles = { + ("legacy_dense", "COLAMD"): {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, + ("legacy_dense", "METIS"): {"color": "#66a61e", "linestyle": ":", "marker": "s", "linewidth": 2.0}, + ("steiner_solve", "COLAMD"): {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, + ("steiner_solve", "METIS"): {"color": "#ff8c00", "linestyle": "-.", "marker": "o", "linewidth": 2.2}, + } + figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=True) + for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): + subset = [row for row in target_rows if row["dataset"] == dataset] + query_sizes = sorted({row["query_size"] for row in subset}) + for variant, ordering in [ + ("legacy_dense", "COLAMD"), + ("legacy_dense", "METIS"), + ("steiner_solve", "COLAMD"), + ("steiner_solve", "METIS"), + ]: + series = sorted( + [ + row + for row in subset + if row["variant"] == variant and row["ordering"] == ordering + ], + key=lambda row: row["query_size"], + ) + if not series: + continue + style = variant_styles[(variant, ordering)] + ax.plot( + [row["query_size"] for row in series], + [row["median_total_ms"] for row in series], + label=f"{ordering} / {variant.replace('_', ' ')}", + markersize=6, + **style, + ) + ax.set_title(dataset_label(dataset)) + ax.set_xlabel("Local-window query size") + ax.set_xticks(query_sizes, [str(size) for size in query_sizes]) + ax.set_ylabel("Median query time (ms)") + ax.set_yscale("log") + ax.grid(True, axis="y", alpha=0.3) + handles, labels = axes[0].get_legend_handles_labels() + figure.legend(handles, labels, loc="upper center", ncol=2, frameon=False) + figure.tight_layout(rect=(0, 0, 1, 0.9)) + figure.savefig(output_path) + plt.close(figure) + + +def plot_structure(rows, output_path): + subset = [row for row in rows if row["mode"] == "joint" and row["variant"] == "steiner_solve" and row["query_family"] == "local_window" and row["dataset"] in {"w10000.graph", "w20000.txt"} and row["ordering"] == "COLAMD"] + figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=False) + for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): + series = sorted([row for row in subset if row["dataset"] == dataset], key=lambda row: row["query_size"]) + x = [row["query_size"] for row in series] + ax.plot(x, [row["support_cliques"] for row in series], marker="o", label="support cliques") + ax.plot(x, [row["compressed_cliques"] for row in series], marker="s", label="compressed cliques") + ax.plot(x, [row["reduced_state_dim"] for row in series], marker="^", label="reduced state dim") + ax.set_title(dataset_label(dataset)) + ax.set_xlabel("Query size") + ax.set_ylabel("Count / dimension") + ax.grid(True, alpha=0.3) + handles, labels = axes[0].get_legend_handles_labels() + figure.legend(handles, labels, loc="upper center", ncol=3, frameon=False) + figure.tight_layout(rect=(0, 0, 1, 0.9)) + figure.savefig(output_path) + plt.close(figure) + + +def plot_selected_cross(rows, output_path): + subset = [row for row in rows if row["mode"] == "cross" and row["query_family"] == "selected_cross" and row["dataset"] in {"w10000.graph", "w20000.txt"}] + variants = ["legacy_dense", "steiner_dense", "legacy_solve", "steiner_solve"] + variant_styles = { + "legacy_dense": {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, + "steiner_dense": {"color": "#ff8c00", "linestyle": "-", "marker": "o", "linewidth": 2.0}, + "legacy_solve": {"color": "#1f77b4", "linestyle": "-.", "marker": "^", "linewidth": 2.0}, + "steiner_solve": {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, + } + figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=True) + for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): + for variant in variants: + series = sorted( + [row for row in subset if row["dataset"] == dataset and row["ordering"] == "COLAMD" and row["variant"] == variant], + key=lambda row: row["query_size"], + ) + if not series: + continue + style = variant_styles[variant] + ax.plot( + [row["query_size"] for row in series], + [row["speedup"] for row in series], + label=variant.replace("_", " "), + markersize=6, + zorder=3 if variant == "legacy_dense" else 4, + **style, + ) + ax.set_title(f"{dataset_label(dataset)} / COLAMD") + ax.set_xlabel("Query size") + ax.set_ylabel("Speedup vs legacy_dense") + ax.set_yscale("log") + ax.grid(True, alpha=0.3) + handles, labels = axes[0].get_legend_handles_labels() + figure.legend(handles, labels, loc="upper center", ncol=4, frameon=False) + figure.tight_layout(rect=(0, 0, 1, 0.88)) + figure.savefig(output_path) + plt.close(figure) + + +def load_key_list(path): + with open(path, newline="") as handle: + reader = csv.DictReader(handle) + return [int(row["key"]) for row in reader] + + +def load_pose_rows(path): + with open(path, newline="") as handle: + reader = csv.DictReader(handle) + rows = list(reader) + for row in rows: + row["key"] = int(row["key"]) + row["x"] = float(row["x"]) + row["y"] = float(row["y"]) + row["theta"] = float(row["theta"]) + row["in_local"] = int(row["in_local"]) + row["in_wide"] = int(row["in_wide"]) + return rows + + +def load_edge_rows(path): + with open(path, newline="") as handle: + reader = csv.DictReader(handle) + rows = list(reader) + for row in rows: + row["key1"] = int(row["key1"]) + row["key2"] = int(row["key2"]) + return rows + + +def plot_w100_queries(data_dir, output_path): + pose_rows = load_pose_rows(data_dir / "w100_poses.csv") + edge_rows = load_edge_rows(data_dir / "w100_edges.csv") + local_keys = load_key_list(data_dir / "w100_local_keys.csv") + wide_keys = load_key_list(data_dir / "w100_wide_keys.csv") + pose_by_key = {row["key"]: row for row in pose_rows} + + figure, axes = plt.subplots(1, 2, figsize=(11.5, 4.8), sharex=True, sharey=True) + query_specs = [ + ("Local 10-pose query", local_keys, "#b22222"), + ("Wide-separated 10-pose query", wide_keys, "#1f5aa6"), + ] + + for ax, (title, query_keys, color) in zip(axes, query_specs): + for edge in edge_rows: + pose1 = pose_by_key[edge["key1"]] + pose2 = pose_by_key[edge["key2"]] + ax.plot( + [pose1["x"], pose2["x"]], + [pose1["y"], pose2["y"]], + color="#c8c8c8", + linewidth=0.7, + alpha=0.7, + zorder=1, + ) + + ax.scatter( + [row["x"] for row in pose_rows], + [row["y"] for row in pose_rows], + s=10, + color="#666666", + alpha=0.65, + zorder=2, + ) + + query_points = [pose_by_key[key] for key in query_keys] + ax.plot( + [row["x"] for row in query_points], + [row["y"] for row in query_points], + color=color, + linewidth=2.2, + alpha=0.95, + zorder=3, + ) + ax.scatter( + [row["x"] for row in query_points], + [row["y"] for row in query_points], + s=36, + color=color, + edgecolor="white", + linewidth=0.6, + zorder=4, + ) + + ax.scatter( + [query_points[0]["x"]], + [query_points[0]["y"]], + s=70, + marker="s", + color=color, + edgecolor="white", + linewidth=0.8, + zorder=5, + ) + ax.scatter( + [query_points[-1]["x"]], + [query_points[-1]["y"]], + s=70, + marker="D", + color=color, + edgecolor="white", + linewidth=0.8, + zorder=5, + ) + + for key in query_keys[:: max(1, len(query_keys) // 5)]: + row = pose_by_key[key] + ax.text( + row["x"] + 0.12, + row["y"] + 0.12, + str(key), + fontsize=8, + color=color, + zorder=6, + ) + + ax.set_title(title) + ax.set_aspect("equal", adjustable="box") + ax.grid(True, alpha=0.18) + ax.set_xlabel("x") + axes[0].set_ylabel("y") + figure.tight_layout() + figure.savefig(output_path) + plt.close(figure) + + +def pose_block(covariance, keys, key): + block_index = keys.index(key) + start = 3 * block_index + return covariance[start : start + 3, start : start + 3] + + +def representative_pose_key(keys, covariance): + scored = [] + for key in keys: + marginal = pose_block(covariance, keys, key) + translation_area = np.linalg.det(marginal[:2, :2]) + scored.append((translation_area, marginal[2, 2], key)) + scored.sort(reverse=True) + return scored[0][2] + + +def sample_tangent_gaussian(rng, covariance, size): + symmetric_covariance = 0.5 * (covariance + covariance.T) + eigenvalues, eigenvectors = np.linalg.eigh(symmetric_covariance) + clamped = np.clip(eigenvalues, 0.0, None) + sqrt_covariance = eigenvectors @ np.diag(np.sqrt(clamped)) + standard = rng.standard_normal((size, covariance.shape[0])) + return np.einsum("nj,ij->ni", standard, sqrt_covariance) + + +def exp_se2(tangent): + vx, vy, omega = tangent + if abs(omega) < 1e-9: + return np.array([vx, vy]), omega + + sin_omega = math.sin(omega) + cos_omega = math.cos(omega) + a_term = sin_omega / omega + b_term = (1.0 - cos_omega) / omega + v_matrix = np.array([[a_term, -b_term], [b_term, a_term]]) + return v_matrix @ np.array([vx, vy]), omega + + +def retract_pose(mean_pose, tangent): + translation, omega = exp_se2(tangent) + mean_theta = mean_pose["theta"] + rotation = np.array( + [ + [math.cos(mean_theta), -math.sin(mean_theta)], + [math.sin(mean_theta), math.cos(mean_theta)], + ] + ) + point = np.array([mean_pose["x"], mean_pose["y"]]) + rotation @ translation + return point[0], point[1], mean_theta + omega + + +def wrap_degrees(angle_radians): + return ((np.rad2deg(angle_radians) + 180.0) % 360.0) - 180.0 + + +def draw_heading_arrow(ax, pose_row, length=1.0): + dx = length * math.cos(pose_row["theta"]) + dy = length * math.sin(pose_row["theta"]) + ax.arrow( + pose_row["x"], + pose_row["y"], + dx, + dy, + width=0.03, + head_width=0.22, + head_length=0.28, + color="black", + length_includes_head=True, + zorder=5, + ) + + +def draw_world_sample_ellipse(ax, positions): + covariance_xy = np.cov(positions[:, :2].T) + center = positions[:, :2].mean(axis=0) + eigenvalues, eigenvectors = np.linalg.eigh(covariance_xy) + order = np.argsort(eigenvalues)[::-1] + eigenvalues = eigenvalues[order] + eigenvectors = eigenvectors[:, order] + angle = np.degrees(np.arctan2(eigenvectors[1, 0], eigenvectors[0, 0])) + width, height = 4.0 * np.sqrt(np.maximum(eigenvalues, 0.0)) + ellipse = Ellipse( + xy=(center[0], center[1]), + width=width, + height=height, + angle=angle, + edgecolor="black", + facecolor="none", + linestyle="--", + linewidth=1.2, + alpha=0.9, + zorder=4, + ) + ax.add_patch(ellipse) + + +def plot_pose2_marginals(data_dir, output_path): + local_keys = load_key_list(data_dir / "w100_local_keys.csv") + wide_keys = load_key_list(data_dir / "w100_wide_keys.csv") + pose_rows = {row["key"]: row for row in load_pose_rows(data_dir / "w100_poses.csv")} + local_covariance = np.loadtxt(data_dir / "w100_local_covariance.csv", delimiter=",") + wide_covariance = np.loadtxt(data_dir / "w100_wide_covariance.csv", delimiter=",") + local_key = representative_pose_key(local_keys, local_covariance) + wide_key = representative_pose_key(wide_keys, wide_covariance) + rng = np.random.default_rng(7) + + figure, axes = plt.subplots( + 1, + 3, + figsize=(12.0, 4.8), + gridspec_kw={"width_ratios": [1.0, 1.0, 0.05]}, + ) + heatmap_axes = axes[:2] + colorbar_axis = axes[2] + specifications = [ + ("Representative local Pose2 marginal", local_key, local_keys, local_covariance), + ("Representative wide-separated Pose2 marginal", wide_key, wide_keys, wide_covariance), + ] + + for ax, (title, key, keys, covariance) in zip(heatmap_axes, specifications): + marginal = pose_block(covariance, keys, key) + mean_pose = pose_rows[key] + samples_tangent = sample_tangent_gaussian(rng, marginal, size=4000) + positions = np.array([retract_pose(mean_pose, tangent) for tangent in samples_tangent]) + headings = wrap_degrees(positions[:, 2]) + heatmap = ax.scatter( + positions[:, 0], + positions[:, 1], + c=headings, + s=6, + alpha=0.32, + cmap="turbo", + vmin=-180.0, + vmax=180.0, + linewidths=0.0, + zorder=2, + ) + draw_world_sample_ellipse(ax, positions) + ax.scatter( + [mean_pose["x"]], + [mean_pose["y"]], + color="black", + marker="x", + s=65, + linewidths=2.0, + zorder=6, + ) + draw_heading_arrow(ax, mean_pose) + ax.text( + mean_pose["x"] + 0.35, + mean_pose["y"] + 0.35, + f"key {key}", + fontsize=9, + color="black", + zorder=7, + ) + ax.set_title(title) + ax.set_aspect("equal", adjustable="box") + ax.grid(True, alpha=0.18) + ax.set_xlabel("x") + ax.set_ylabel("y") + colorbar = figure.colorbar(heatmap, cax=colorbar_axis) + colorbar.set_label("heading (deg)") + figure.subplots_adjust(left=0.08, right=0.94, bottom=0.2, top=0.88, wspace=0.32) + figure.savefig(output_path) + plt.close(figure) + + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("--input", required=True) + parser.add_argument("--output-dir", required=True) + parser.add_argument("--copy-csv-dir", default="") + parser.add_argument("--visual-data-dir", default="") + args = parser.parse_args() + + input_path = Path(args.input) + output_dir = Path(args.output_dir) + output_dir.mkdir(parents=True, exist_ok=True) + + rows = baseline_speedups( + to_float( + load_rows(input_path), + ["median_total_ms", "total_total_ms", "median_reduction_ms", "median_extraction_ms"], + ) + ) + + plot_ablation(rows, output_dir / "results-ablation.pdf") + plot_ordering(rows, output_dir / "results-ordering.pdf") + plot_structure(rows, output_dir / "results-structure.pdf") + plot_selected_cross(rows, output_dir / "results-cross.pdf") + + if args.visual_data_dir: + visual_data_dir = Path(args.visual_data_dir) + plot_w100_queries(visual_data_dir, output_dir / "results-w100-queries.pdf") + plot_pose2_marginals( + visual_data_dir, output_dir / "results-w100-covariance.pdf" + ) + + if args.copy_csv_dir: + copy_dir = Path(args.copy_csv_dir) + copy_dir.mkdir(parents=True, exist_ok=True) + shutil.copy2(input_path, copy_dir / input_path.name) + + +if __name__ == "__main__": + main() diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp new file mode 100644 index 0000000000..3681e97852 --- /dev/null +++ b/timing/timeBayesTreeCovariance.cpp @@ -0,0 +1,704 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +namespace { + +enum class Variant { + LegacyDense, + SteinerDense, + LegacySolve, + SteinerSolve, +}; + +struct QueryCase { + string family; + size_t querySize; + KeyVector keys; + KeyVector left; + KeyVector right; + bool crossCovariance = false; +}; + +struct SupportStats { + size_t supportCliques = 0; + size_t compressedCliques = 0; +}; + +struct RawResult { + string dataset; + string ordering; + string family; + string mode; + string variant; + size_t querySize = 0; + size_t queryIndex = 0; + double totalMs = 0.0; + double reductionMs = 0.0; + double extractionMs = 0.0; + size_t supportCliques = 0; + size_t compressedCliques = 0; + size_t reducedStateDim = 0; +}; + +struct SummaryKey { + string dataset; + string ordering; + string family; + string mode; + string variant; + size_t querySize = 0; + + bool operator==(const SummaryKey& other) const { + return dataset == other.dataset && ordering == other.ordering && + family == other.family && mode == other.mode && + variant == other.variant && querySize == other.querySize; + } +}; + +struct SummaryKeyHash { + size_t operator()(const SummaryKey& key) const { + size_t seed = std::hash()(key.dataset); + seed ^= std::hash()(key.ordering) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= std::hash()(key.family) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= + std::hash()(key.mode) + 0x9e3779b9 + (seed << 6) + (seed >> 2); + seed ^= std::hash()(key.variant) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= std::hash()(key.querySize) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + return seed; + } +}; + +struct SummaryValue { + vector totalMs; + vector reductionMs; + vector extractionMs; + size_t supportCliques = 0; + size_t compressedCliques = 0; + size_t reducedStateDim = 0; +}; + +KeyVector uniqueSortedKeys(const KeyVector& keys) { + KeyVector result = keys; + sort(result.begin(), result.end()); + result.erase(unique(result.begin(), result.end()), result.end()); + return result; +} + +KeyVector poseKeys(const Values& values) { + KeyVector keys; + for (const auto& keyValue : values.extract()) { + keys.push_back(keyValue.first); + } + sort(keys.begin(), keys.end()); + return keys; +} + +vector dimsForKeys(const KeyVector& keys, const Values& values) { + vector dims; + dims.reserve(keys.size()); + for (Key key : keys) { + dims.push_back(values.at(key).dim()); + } + return dims; +} + +vector blockOffsets(const vector& dims) { + vector offsets(dims.size() + 1, 0); + for (size_t i = 0; i < dims.size(); ++i) { + offsets[i + 1] = offsets[i] + dims[i]; + } + return offsets; +} + +size_t totalDimension(const KeySet& keys, const Values& values) { + size_t dim = 0; + for (Key key : keys) { + dim += values.at(key).dim(); + } + return dim; +} + +template +shared_ptr findLowestCommonAncestor(const shared_ptr& lhs, + const shared_ptr& rhs) { + unordered_set> ancestors; + for (auto current = lhs; current; current = current->parent()) { + ancestors.insert(current); + } + for (auto current = rhs; current; current = current->parent()) { + if (ancestors.count(current)) { + return current; + } + } + return nullptr; +} + +SupportStats analyzeSupport(const GaussianBayesTree& bayesTree, + const KeyVector& queryKeys) { + vector queryCliques; + unordered_set seen; + for (Key key : queryKeys) { + auto clique = bayesTree.clique(key); + if (seen.insert(clique).second) { + queryCliques.push_back(clique); + } + } + if (queryCliques.empty()) { + return {}; + } + + auto root = queryCliques.front(); + for (size_t i = 1; i < queryCliques.size(); ++i) { + root = findLowestCommonAncestor(root, queryCliques[i]); + } + + unordered_set support; + support.insert(root); + for (const auto& clique : queryCliques) { + for (auto current = clique; current && current != root; + current = current->parent()) { + support.insert(current); + } + } + + unordered_map supportChildren; + for (const auto& clique : support) { + supportChildren[clique] = 0; + } + for (const auto& clique : support) { + if (clique == root) { + continue; + } + auto parent = clique->parent(); + if (parent && support.count(parent)) { + ++supportChildren[parent]; + } + } + + unordered_set querySet(queryCliques.begin(), + queryCliques.end()); + size_t compressed = 1; + for (const auto& clique : support) { + if (clique == root) { + continue; + } + if (querySet.count(clique) || supportChildren[clique] > 1) { + ++compressed; + } + } + + return {support.size(), compressed}; +} + +GaussianFactorGraph legacyReducedFactorGraph(const GaussianFactorGraph& graph, + const Ordering& fullOrdering, + const KeyVector& queryKeys) { + (void)fullOrdering; + return GaussianFactorGraph( + *graph.marginalMultifrontalBayesTree(queryKeys, EliminatePreferCholesky)); +} + +GaussianFactorGraph steinerReducedFactorGraph( + const GaussianBayesTree& bayesTree, const KeyVector& queryKeys) { + return *bayesTree.joint(queryKeys, EliminatePreferCholesky); +} + +GaussianBayesNet queryBayesNet(const GaussianFactorGraph& graph, + const KeyVector& queryKeys) { + return *graph.marginalMultifrontalBayesNet(Ordering(queryKeys), + EliminatePreferCholesky); +} + +Matrix covarianceColumns(const GaussianBayesNet& bayesNet, + const KeyVector& orderedKeys, + const vector& dims, + const vector& selectedBlocks) { + const auto [R, rhs] = bayesNet.matrix(Ordering(orderedKeys)); + (void)rhs; + const vector offsets = blockOffsets(dims); + const size_t totalDim = offsets.back(); + + size_t selectedDim = 0; + for (size_t blockIndex : selectedBlocks) { + selectedDim += dims.at(blockIndex); + } + + Matrix selectors = Matrix::Zero(totalDim, selectedDim); + size_t selectedOffset = 0; + for (size_t blockIndex : selectedBlocks) { + const size_t begin = offsets[blockIndex]; + const size_t dim = dims[blockIndex]; + selectors.block(begin, selectedOffset, dim, dim).setIdentity(); + selectedOffset += dim; + } + + Matrix intermediate = + R.transpose().triangularView().solve(selectors); + return R.triangularView().solve(intermediate); +} + +Matrix extractCrossBlock(const Matrix& selectedColumns, + const KeyVector& orderedKeys, + const vector& dims, const KeyVector& left, + const KeyVector& right) { + const FastMap keyIndex = Ordering(orderedKeys).invert(); + const vector offsets = blockOffsets(dims); + size_t leftDim = 0; + for (Key key : left) { + leftDim += dims.at(keyIndex.at(key)); + } + size_t rightDim = 0; + for (Key key : right) { + rightDim += dims.at(keyIndex.at(key)); + } + + Matrix result(leftDim, rightDim); + size_t rowOffset = 0; + for (Key leftKey : left) { + const size_t leftBlock = keyIndex.at(leftKey); + const size_t leftDimBlock = dims[leftBlock]; + const size_t leftBegin = offsets[leftBlock]; + size_t columnOffset = 0; + size_t selectedOffset = 0; + for (Key rightKey : right) { + const size_t rightBlock = keyIndex.at(rightKey); + const size_t rightDimBlock = dims[rightBlock]; + result.block(rowOffset, columnOffset, leftDimBlock, rightDimBlock) = + selectedColumns.block(leftBegin, selectedOffset, leftDimBlock, + rightDimBlock); + columnOffset += rightDimBlock; + selectedOffset += rightDimBlock; + } + rowOffset += leftDimBlock; + } + return result; +} + +string variantName(Variant variant) { + switch (variant) { + case Variant::LegacyDense: + return "legacy_dense"; + case Variant::SteinerDense: + return "steiner_dense"; + case Variant::LegacySolve: + return "legacy_solve"; + case Variant::SteinerSolve: + return "steiner_solve"; + } + return "unknown"; +} + +string orderingName(Ordering::OrderingType orderingType) { + return orderingType == Ordering::METIS ? "METIS" : "COLAMD"; +} + +double median(vector values) { + if (values.empty()) { + return 0.0; + } + sort(values.begin(), values.end()); + const size_t mid = values.size() / 2; + if (values.size() % 2 == 0) { + return 0.5 * (values[mid - 1] + values[mid]); + } + return values[mid]; +} + +vector sampledStarts(size_t maxStartInclusive, size_t maxQueries, + size_t stride = 1) { + vector starts; + if (maxStartInclusive == 0) { + starts.push_back(0); + return starts; + } + + for (size_t start = 0; + start <= maxStartInclusive && starts.size() < maxQueries; + start += stride) { + starts.push_back(start); + } + if (starts.size() > maxQueries) { + starts.resize(maxQueries); + } + if (starts.size() < maxQueries && starts.back() != maxStartInclusive) { + starts.push_back(maxStartInclusive); + } + + if (starts.size() > maxQueries) { + vector reduced; + reduced.reserve(maxQueries); + for (size_t i = 0; i < maxQueries; ++i) { + const size_t index = static_cast( + llround((starts.size() - 1) * (double(i) / double(maxQueries - 1)))); + reduced.push_back(starts[index]); + } + starts = reduced; + } + return starts; +} + +vector generateLocalWindows(const KeyVector& poseKeys, + size_t querySize, size_t maxQueries) { + vector queries; + if (poseKeys.size() < querySize) { + return queries; + } + const size_t maxStart = poseKeys.size() - querySize; + for (size_t start : + sampledStarts(maxStart, maxQueries, max(1, querySize / 2))) { + QueryCase query; + query.family = "local_window"; + query.querySize = querySize; + query.keys.assign(poseKeys.begin() + start, + poseKeys.begin() + start + querySize); + queries.push_back(query); + } + return queries; +} + +vector generateRepeatedOverlap(const KeyVector& poseKeys, + size_t querySize, size_t maxQueries) { + vector queries; + if (poseKeys.size() < querySize) { + return queries; + } + const size_t maxStart = poseKeys.size() - querySize; + for (size_t start = 0; start <= maxStart && queries.size() < maxQueries; + ++start) { + QueryCase query; + query.family = "overlap_window"; + query.querySize = querySize; + query.keys.assign(poseKeys.begin() + start, + poseKeys.begin() + start + querySize); + queries.push_back(query); + } + return queries; +} + +vector generateWideSeparated(const KeyVector& poseKeys, + size_t querySize, size_t maxQueries) { + vector queries; + if (poseKeys.size() < querySize) { + return queries; + } + + const double gap = querySize == 1 + ? 0.0 + : double(poseKeys.size() - 1) / double(querySize - 1); + for (size_t sample = 0; sample < maxQueries; ++sample) { + const double offset = + maxQueries == 0 ? 0.0 + : (gap / max(1.0, double(maxQueries))) * sample; + QueryCase query; + query.family = "wide_separated"; + query.querySize = querySize; + size_t previous = 0; + for (size_t j = 0; j < querySize; ++j) { + size_t index = static_cast(llround(offset + gap * j)); + index = min(index, poseKeys.size() - querySize + j); + if (j > 0) { + index = max(index, previous + 1); + } + previous = index; + query.keys.push_back(poseKeys[index]); + } + queries.push_back(query); + } + return queries; +} + +vector generateSelectedCross(const KeyVector& poseKeys, + size_t querySize, size_t maxQueries) { + vector queries; + if (poseKeys.size() < querySize || querySize < 2) { + return queries; + } + const size_t split = querySize / 2; + for (QueryCase query : + generateRepeatedOverlap(poseKeys, querySize, maxQueries)) { + query.family = "selected_cross"; + query.crossCovariance = true; + query.left.assign(query.keys.begin(), query.keys.begin() + split); + query.right.assign(query.keys.begin() + split, query.keys.end()); + queries.push_back(query); + } + return queries; +} + +vector buildWorkload(const KeyVector& poseKeyList) { + vector queries; + for (size_t querySize : {size_t(3), size_t(5), size_t(10), size_t(20)}) { + auto local = generateLocalWindows(poseKeyList, querySize, 16); + queries.insert(queries.end(), local.begin(), local.end()); + + auto wide = generateWideSeparated(poseKeyList, querySize, 8); + queries.insert(queries.end(), wide.begin(), wide.end()); + } + + auto overlap = generateRepeatedOverlap(poseKeyList, 10, 32); + queries.insert(queries.end(), overlap.begin(), overlap.end()); + + for (size_t querySize : {size_t(10), size_t(20)}) { + auto selected = generateSelectedCross(poseKeyList, querySize, 24); + queries.insert(queries.end(), selected.begin(), selected.end()); + } + return queries; +} + +RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, + Variant variant, + const GaussianFactorGraph& linearGraph, + const GaussianBayesTree& bayesTree, + const Ordering& fullOrdering, const Values& values, + const QueryCase& query, size_t queryIndex) { + const KeyVector orderedKeys = uniqueSortedKeys(query.keys); + const SupportStats supportStats = analyzeSupport(bayesTree, orderedKeys); + + const auto reductionStart = chrono::steady_clock::now(); + GaussianFactorGraph reducedGraph = + (variant == Variant::LegacyDense || variant == Variant::LegacySolve) + ? legacyReducedFactorGraph(linearGraph, fullOrdering, orderedKeys) + : steinerReducedFactorGraph(bayesTree, orderedKeys); + const auto reductionEnd = chrono::steady_clock::now(); + + const auto extractionStart = chrono::steady_clock::now(); + GaussianBayesNet reducedBayesNet = queryBayesNet(reducedGraph, orderedKeys); + const vector dims = dimsForKeys(orderedKeys, values); + Matrix recovered; + if (query.crossCovariance) { + const FastMap keyIndex = Ordering(orderedKeys).invert(); + vector rightBlocks; + rightBlocks.reserve(query.right.size()); + for (Key key : query.right) { + rightBlocks.push_back(keyIndex.at(key)); + } + + Matrix selectedColumns; + if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { + const auto [R, rhs] = reducedBayesNet.matrix(Ordering(orderedKeys)); + (void)rhs; + const Matrix information = R.transpose() * R; + const Matrix covariance = information.inverse(); + selectedColumns = covariance; + recovered = extractCrossBlock(selectedColumns, orderedKeys, dims, + query.left, query.right); + } else { + selectedColumns = + covarianceColumns(reducedBayesNet, orderedKeys, dims, rightBlocks); + recovered = extractCrossBlock(selectedColumns, orderedKeys, dims, + query.left, query.right); + } + } else { + if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { + const auto [R, rhs] = reducedBayesNet.matrix(Ordering(orderedKeys)); + (void)rhs; + const Matrix information = R.transpose() * R; + recovered = information.inverse(); + } else { + vector allBlocks(orderedKeys.size()); + iota(allBlocks.begin(), allBlocks.end(), 0); + recovered = + covarianceColumns(reducedBayesNet, orderedKeys, dims, allBlocks); + } + } + const auto extractionEnd = chrono::steady_clock::now(); + + volatile double checksum = recovered.sum(); + (void)checksum; + + RawResult result; + result.dataset = datasetName; + result.ordering = orderingLabel; + result.family = query.family; + result.mode = query.crossCovariance ? "cross" : "joint"; + result.variant = variantName(variant); + result.querySize = query.querySize; + result.queryIndex = queryIndex; + result.reductionMs = + chrono::duration(reductionEnd - reductionStart).count(); + result.extractionMs = + chrono::duration(extractionEnd - extractionStart).count(); + result.totalMs = result.reductionMs + result.extractionMs; + result.supportCliques = supportStats.supportCliques; + result.compressedCliques = supportStats.compressedCliques; + result.reducedStateDim = totalDimension(reducedGraph.keys(), values); + return result; +} + +void writeRawCsv(const filesystem::path& path, + const vector& results) { + ofstream os(path); + os << "dataset,ordering,query_family,mode,variant,query_size,query_index," + "total_ms,reduction_ms,extraction_ms,support_cliques,compressed_" + "cliques," + "reduced_state_dim\n"; + os << fixed << setprecision(6); + for (const auto& result : results) { + os << result.dataset << ',' << result.ordering << ',' << result.family + << ',' << result.mode << ',' << result.variant << ',' << result.querySize + << ',' << result.queryIndex << ',' << result.totalMs << ',' + << result.reductionMs << ',' << result.extractionMs << ',' + << result.supportCliques << ',' << result.compressedCliques << ',' + << result.reducedStateDim << '\n'; + } +} + +void writeSummaryCsv(const filesystem::path& path, + const vector& results) { + unordered_map summary; + for (const auto& result : results) { + const SummaryKey key{result.dataset, result.ordering, result.family, + result.mode, result.variant, result.querySize}; + auto& value = summary[key]; + value.totalMs.push_back(result.totalMs); + value.reductionMs.push_back(result.reductionMs); + value.extractionMs.push_back(result.extractionMs); + value.supportCliques = result.supportCliques; + value.compressedCliques = result.compressedCliques; + value.reducedStateDim = result.reducedStateDim; + } + + ofstream os(path); + os << "dataset,ordering,query_family,mode,variant,query_size,queries," + "median_total_ms,total_total_ms,median_reduction_ms,median_extraction_" + "ms," + "support_cliques,compressed_cliques,reduced_state_dim\n"; + os << fixed << setprecision(6); + for (const auto& [key, value] : summary) { + const double totalTime = + accumulate(value.totalMs.begin(), value.totalMs.end(), 0.0); + os << key.dataset << ',' << key.ordering << ',' << key.family << ',' + << key.mode << ',' << key.variant << ',' << key.querySize << ',' + << value.totalMs.size() << ',' << median(value.totalMs) << ',' + << totalTime << ',' << median(value.reductionMs) << ',' + << median(value.extractionMs) << ',' << value.supportCliques << ',' + << value.compressedCliques << ',' << value.reducedStateDim << '\n'; + } +} + +string argumentOrDefault(char** begin, char** end, const string& flag, + const string& defaultValue) { + for (auto it = begin; it != end; ++it) { + if (string(*it) == flag && it + 1 != end) { + return *(it + 1); + } + } + return defaultValue; +} + +vector splitCommaSeparated(const string& input) { + vector values; + size_t start = 0; + while (start < input.size()) { + const size_t comma = input.find(',', start); + if (comma == string::npos) { + values.push_back(input.substr(start)); + break; + } + values.push_back(input.substr(start, comma - start)); + start = comma + 1; + } + return values; +} + +} // namespace + +int main(int argc, char** argv) { + const filesystem::path outputDir = argumentOrDefault( + argv, argv + argc, "--output-dir", + (filesystem::path("timing") / "results" / "bayes_tree_covariance") + .string()); + const vector datasets = splitCommaSeparated(argumentOrDefault( + argv, argv + argc, "--datasets", "w100.graph,w10000.graph,w20000.txt")); + + filesystem::create_directories(outputDir); + + vector rawResults; + + for (const string& datasetName : datasets) { + cout << "Loading " << datasetName << endl; + const auto [graphPtr, initialPtr] = + load2D(findExampleDataFile(datasetName)); + const KeyVector anchoredPoseKeys = poseKeys(*initialPtr); + if (!anchoredPoseKeys.empty()) { + graphPtr->addPrior(anchoredPoseKeys.front(), + initialPtr->at(anchoredPoseKeys.front()), + noiseModel::Diagonal::Sigmas( + (Vector(3) << 1e-6, 1e-6, 1e-6).finished())); + } + + cout << "Optimizing " << datasetName << endl; + LevenbergMarquardtOptimizer optimizer(*graphPtr, *initialPtr); + Values result = optimizer.optimize(); + GaussianFactorGraph linearGraph = *graphPtr->linearize(result); + const KeyVector poseKeyList = poseKeys(result); + const vector workload = buildWorkload(poseKeyList); + + for (const auto orderingType : {Ordering::COLAMD, Ordering::METIS}) { +#ifndef GTSAM_SUPPORT_NESTED_DISSECTION + if (orderingType == Ordering::METIS) { + continue; + } +#endif + const Ordering ordering = Ordering::Create(orderingType, linearGraph); + cout << " Ordering " << orderingName(orderingType) << " with " + << workload.size() << " queries" << endl; + GaussianBayesTree bayesTree = + *linearGraph.eliminateMultifrontal(ordering, EliminatePreferCholesky); + + size_t queryIndex = 0; + for (const QueryCase& query : workload) { + for (const Variant variant : + {Variant::LegacyDense, Variant::SteinerDense, Variant::LegacySolve, + Variant::SteinerSolve}) { + try { + rawResults.push_back(benchmarkQuery( + datasetName, orderingName(orderingType), variant, linearGraph, + bayesTree, ordering, result, query, queryIndex)); + } catch (const std::exception& error) { + cerr << "Failure for dataset=" << datasetName + << " ordering=" << orderingName(orderingType) + << " variant=" << variantName(variant) + << " family=" << query.family << " query_index=" << queryIndex + << ": " << error.what() << endl; + throw; + } + } + ++queryIndex; + } + } + } + + writeRawCsv(outputDir / "raw.csv", rawResults); + writeSummaryCsv(outputDir / "summary.csv", rawResults); + cout << "Wrote benchmark results to " << outputDir << endl; + return 0; +} From dcc51033c6c7fff089d0418eff4013ad641c3c2d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 17 Mar 2026 14:26:54 -0400 Subject: [PATCH 03/12] Docs and readme --- timing/README.md | 78 +++++++ timing/exportBayesTreeCovarianceVisuals.cpp | 51 ++-- timing/plot_bayes_tree_covariance.py | 243 +++++++++++++++++--- timing/timeBayesTreeCovariance.cpp | 50 ++++ 4 files changed, 378 insertions(+), 44 deletions(-) create mode 100644 timing/README.md diff --git a/timing/README.md b/timing/README.md new file mode 100644 index 0000000000..9ede106040 --- /dev/null +++ b/timing/README.md @@ -0,0 +1,78 @@ +# Timing Benchmarks + +This directory contains timing executables and helper scripts for GTSAM. + +## Bayes-Tree Covariance Results + +The Bayes-tree covariance paper uses generated benchmark output rather than +checked-in CSV files. The files under `timing/results/` can be regenerated from +the commands below and do not need to be committed. + +### Build + +From the build directory: + +```bash +make -j6 timeBayesTreeCovariance +make -j6 exportBayesTreeCovarianceVisuals +``` + +### Generate benchmark CSVs + +Run from `build/`: + +```bash +./timing/timeBayesTreeCovariance \ + --datasets w100.graph,w10000.graph,w20000.txt \ + --output-dir ../timing/results/bayes_tree_covariance +``` + +This writes: + +- `timing/results/bayes_tree_covariance/raw.csv` +- `timing/results/bayes_tree_covariance/summary.csv` + +### Export `w100` visual data + +Run from `build/`: + +```bash +./timing/exportBayesTreeCovarianceVisuals \ + --dataset w100.graph \ + --output-dir ../timing/results/bayes_tree_covariance/visuals +``` + +This writes the CSV files used for the `w100` query and covariance figures. + +### Generate figures + +Run from the repository root: + +```bash +python3 timing/plot_bayes_tree_covariance.py \ + --input timing/results/bayes_tree_covariance/summary.csv \ + --output-dir ../BayesTreeCovariance/figures/generated \ + --copy-csv-dir ../BayesTreeCovariance/data \ + --visual-data-dir timing/results/bayes_tree_covariance/visuals +``` + +This generates: + +- `results-ablation.pdf` +- `results-ordering.pdf` +- `results-structure.pdf` +- `results-cross.pdf` +- `results-w100-queries.pdf` +- `results-w100-covariance.pdf` + +## Notes + +- The benchmark timings measure covariance-query work after optimization and + linearization. +- The benchmark compares four variants: + - `legacy_dense` + - `steiner_dense` + - `legacy_solve` + - `steiner_solve` +- If the generated results become stale, it is safe to delete + `timing/results/bayes_tree_covariance/` and regenerate it. diff --git a/timing/exportBayesTreeCovarianceVisuals.cpp b/timing/exportBayesTreeCovarianceVisuals.cpp index 03916103ab..483b21c021 100644 --- a/timing/exportBayesTreeCovarianceVisuals.cpp +++ b/timing/exportBayesTreeCovarianceVisuals.cpp @@ -1,3 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * 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 exportBayesTreeCovarianceVisuals.cpp + * @brief Export representative pose-graph query and covariance visuals. + * @date March 2026 + * @author Frank Dellaert + */ + #include #include #include @@ -20,6 +37,7 @@ using namespace std; namespace { +/// Return all Pose2 keys in sorted order. KeyVector poseKeys(const Values& values) { KeyVector keys; for (const auto& keyValue : values.extract()) { @@ -29,6 +47,7 @@ KeyVector poseKeys(const Values& values) { return keys; } +/// Select a contiguous window near the center of the trajectory. KeyVector centeredWindow(const KeyVector& keys, size_t querySize) { if (keys.size() <= querySize) { return keys; @@ -37,6 +56,7 @@ KeyVector centeredWindow(const KeyVector& keys, size_t querySize) { return KeyVector(keys.begin() + start, keys.begin() + start + querySize); } +/// Select approximately evenly spaced keys across the full trajectory. KeyVector evenlySpaced(const KeyVector& keys, size_t querySize) { if (keys.size() <= querySize) { return keys; @@ -47,14 +67,15 @@ KeyVector evenlySpaced(const KeyVector& keys, size_t querySize) { for (size_t i = 0; i < querySize; ++i) { const double alpha = querySize == 1 ? 0.0 : double(i) / double(querySize - 1); - const size_t index = static_cast( - llround(alpha * double(keys.size() - 1))); + const size_t index = + static_cast(llround(alpha * double(keys.size() - 1))); query.push_back(keys.at(index)); } query.erase(unique(query.begin(), query.end()), query.end()); return query; } +/// Write a one-column key list CSV. void writeKeyListCsv(const filesystem::path& path, const KeyVector& keys) { ofstream stream(path); stream << "key\n"; @@ -63,6 +84,7 @@ void writeKeyListCsv(const filesystem::path& path, const KeyVector& keys) { } } +/// Write a dense matrix to CSV with fixed precision. void writeMatrixCsv(const filesystem::path& path, const Matrix& matrix) { ofstream stream(path); stream << fixed << setprecision(12); @@ -77,6 +99,7 @@ void writeMatrixCsv(const filesystem::path& path, const Matrix& matrix) { } } +/// Export optimized Pose2 values together with query membership flags. void writePoseCsv(const filesystem::path& path, const Values& values, const KeyVector& localQuery, const KeyVector& wideQuery) { const set localKeys(localQuery.begin(), localQuery.end()); @@ -87,12 +110,13 @@ void writePoseCsv(const filesystem::path& path, const Values& values, stream << fixed << setprecision(9); for (Key key : poseKeys(values)) { const Pose2 pose = values.at(key); - stream << key << ',' << pose.x() << ',' << pose.y() << ',' - << pose.theta() << ',' << (localKeys.count(key) ? 1 : 0) << ',' + stream << key << ',' << pose.x() << ',' << pose.y() << ',' << pose.theta() + << ',' << (localKeys.count(key) ? 1 : 0) << ',' << (wideKeys.count(key) ? 1 : 0) << '\n'; } } +/// Export the unique Pose2 measurement edges in the factor graph. void writeEdgeCsv(const filesystem::path& path, const NonlinearFactorGraph& graph) { set> edges; @@ -114,6 +138,7 @@ void writeEdgeCsv(const filesystem::path& path, } } +/// Read a string argument from argv or return a default value. string argumentOrDefault(char** begin, char** end, const string& flag, const string& defaultValue) { for (auto it = begin; it != end; ++it) { @@ -129,20 +154,20 @@ string argumentOrDefault(char** begin, char** end, const string& flag, int main(int argc, char** argv) { const string datasetName = argumentOrDefault(argv, argv + argc, "--dataset", "w100.graph"); - const filesystem::path outputDir = argumentOrDefault( - argv, argv + argc, "--output-dir", - (filesystem::path("timing") / "results" / "bayes_tree_covariance" / - "visuals") - .string()); + const filesystem::path outputDir = + argumentOrDefault(argv, argv + argc, "--output-dir", + (filesystem::path("timing") / "results" / + "bayes_tree_covariance" / "visuals") + .string()); filesystem::create_directories(outputDir); const auto [graphPtr, initialPtr] = load2D(findExampleDataFile(datasetName)); const KeyVector initialPoseKeys = poseKeys(*initialPtr); if (!initialPoseKeys.empty()) { - graphPtr->addPrior( - initialPoseKeys.front(), initialPtr->at(initialPoseKeys.front()), - noiseModel::Diagonal::Sigmas( - (Vector(3) << 1e-6, 1e-6, 1e-6).finished())); + graphPtr->addPrior(initialPoseKeys.front(), + initialPtr->at(initialPoseKeys.front()), + noiseModel::Diagonal::Sigmas( + (Vector(3) << 1e-6, 1e-6, 1e-6).finished())); } LevenbergMarquardtOptimizer optimizer(*graphPtr, *initialPtr); diff --git a/timing/plot_bayes_tree_covariance.py b/timing/plot_bayes_tree_covariance.py index 1b2f54f5b0..ea56f03d40 100644 --- a/timing/plot_bayes_tree_covariance.py +++ b/timing/plot_bayes_tree_covariance.py @@ -1,4 +1,14 @@ #!/usr/bin/env python3 +""" +GTSAM Copyright 2010, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Generate paper-ready plots for the Bayes-tree covariance benchmarks. +Author: Frank Dellaert +""" import argparse import csv @@ -13,11 +23,13 @@ def load_rows(path): + """Load a CSV file into a list of row dictionaries.""" with open(path, newline="") as handle: return list(csv.DictReader(handle)) def to_float(rows, fields): + """Convert numeric CSV fields to float or integer types in place.""" for row in rows: for field in fields: row[field] = float(row[field]) @@ -30,19 +42,37 @@ def to_float(rows, fields): def baseline_speedups(rows): + """Annotate each row with its speedup relative to the legacy dense baseline.""" baselines = {} for row in rows: - if row["variant"] == "legacy_dense": - baselines[(row["dataset"], row["ordering"], row["query_family"], row["mode"], row["query_size"])] = row["median_total_ms"] + if row["variant"] == "legacy_dense": + baselines[ + ( + row["dataset"], + row["ordering"], + row["query_family"], + row["mode"], + row["query_size"], + ) + ] = row["median_total_ms"] for row in rows: - key = (row["dataset"], row["ordering"], row["query_family"], row["mode"], row["query_size"]) - baseline = baselines.get(key, row["median_total_ms"]) - row["speedup"] = baseline / row["median_total_ms"] if row["median_total_ms"] else 1.0 + key = ( + row["dataset"], + row["ordering"], + row["query_family"], + row["mode"], + row["query_size"], + ) + baseline = baselines.get(key, row["median_total_ms"]) + row["speedup"] = ( + baseline / row["median_total_ms"] if row["median_total_ms"] else 1.0 + ) return rows def filter_rows(rows, **criteria): + """Return rows whose named fields match the provided values.""" result = [] for row in rows: if all(row[key] == value for key, value in criteria.items()): @@ -51,6 +81,7 @@ def filter_rows(rows, **criteria): def grouped(rows, *keys): + """Group rows by a tuple of field values.""" groups = defaultdict(list) for row in rows: groups[tuple(row[key] for key in keys)].append(row) @@ -58,23 +89,61 @@ def grouped(rows, *keys): def dataset_label(dataset): + """Strip dataset file extensions for presentation.""" return dataset.removesuffix(".graph").removesuffix(".txt") def plot_ablation(rows, output_path): - joint_rows = [row for row in rows if row["mode"] == "joint" and row["query_family"] == "local_window" and row["dataset"] in {"w10000.graph", "w20000.txt"}] + """Plot the four-way ablation for local-window joint queries.""" + joint_rows = [ + row + for row in rows + if row["mode"] == "joint" + and row["query_family"] == "local_window" + and row["dataset"] in {"w10000.graph", "w20000.txt"} + ] variants = ["legacy_dense", "steiner_dense", "legacy_solve", "steiner_solve"] variant_styles = { - "legacy_dense": {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, - "steiner_dense": {"color": "#ff8c00", "linestyle": "-", "marker": "o", "linewidth": 2.0}, - "legacy_solve": {"color": "#1f77b4", "linestyle": "-.", "marker": "^", "linewidth": 2.0}, - "steiner_solve": {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, + "legacy_dense": { + "color": "#228b22", + "linestyle": "--", + "marker": "s", + "linewidth": 2.0, + }, + "steiner_dense": { + "color": "#ff8c00", + "linestyle": "-", + "marker": "o", + "linewidth": 2.0, + }, + "legacy_solve": { + "color": "#1f77b4", + "linestyle": "-.", + "marker": "^", + "linewidth": 2.0, + }, + "steiner_solve": { + "color": "#b22222", + "linestyle": "-", + "marker": "D", + "linewidth": 2.2, + }, } figure, axes = plt.subplots(2, 2, figsize=(12, 8), sharex=True, sharey=True) - for ax, (dataset, ordering) in zip(axes.flat, [("w10000.graph", "COLAMD"), ("w10000.graph", "METIS"), ("w20000.txt", "COLAMD"), ("w20000.txt", "METIS")]): + for ax, (dataset, ordering) in zip( + axes.flat, + [ + ("w10000.graph", "COLAMD"), + ("w10000.graph", "METIS"), + ("w20000.txt", "COLAMD"), + ("w20000.txt", "METIS"), + ], + ): subset = filter_rows(joint_rows, dataset=dataset, ordering=ordering) for variant in variants: - series = sorted(filter_rows(subset, variant=variant), key=lambda row: row["query_size"]) + series = sorted( + filter_rows(subset, variant=variant), key=lambda row: row["query_size"] + ) if not series: continue style = variant_styles[variant] @@ -99,6 +168,7 @@ def plot_ablation(rows, output_path): def plot_ordering(rows, output_path): + """Compare ordering sensitivity for the dense baseline and localized method.""" target_rows = [ row for row in rows @@ -108,10 +178,30 @@ def plot_ordering(rows, output_path): and row["query_family"] == "local_window" ] variant_styles = { - ("legacy_dense", "COLAMD"): {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, - ("legacy_dense", "METIS"): {"color": "#66a61e", "linestyle": ":", "marker": "s", "linewidth": 2.0}, - ("steiner_solve", "COLAMD"): {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, - ("steiner_solve", "METIS"): {"color": "#ff8c00", "linestyle": "-.", "marker": "o", "linewidth": 2.2}, + ("legacy_dense", "COLAMD"): { + "color": "#228b22", + "linestyle": "--", + "marker": "s", + "linewidth": 2.0, + }, + ("legacy_dense", "METIS"): { + "color": "#66a61e", + "linestyle": ":", + "marker": "s", + "linewidth": 2.0, + }, + ("steiner_solve", "COLAMD"): { + "color": "#b22222", + "linestyle": "-", + "marker": "D", + "linewidth": 2.2, + }, + ("steiner_solve", "METIS"): { + "color": "#ff8c00", + "linestyle": "-.", + "marker": "o", + "linewidth": 2.2, + }, } figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=True) for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): @@ -155,14 +245,41 @@ def plot_ordering(rows, output_path): def plot_structure(rows, output_path): - subset = [row for row in rows if row["mode"] == "joint" and row["variant"] == "steiner_solve" and row["query_family"] == "local_window" and row["dataset"] in {"w10000.graph", "w20000.txt"} and row["ordering"] == "COLAMD"] + """Plot support size and reduced state statistics against query size.""" + subset = [ + row + for row in rows + if row["mode"] == "joint" + and row["variant"] == "steiner_solve" + and row["query_family"] == "local_window" + and row["dataset"] in {"w10000.graph", "w20000.txt"} + and row["ordering"] == "COLAMD" + ] figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=False) for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): - series = sorted([row for row in subset if row["dataset"] == dataset], key=lambda row: row["query_size"]) + series = sorted( + [row for row in subset if row["dataset"] == dataset], + key=lambda row: row["query_size"], + ) x = [row["query_size"] for row in series] - ax.plot(x, [row["support_cliques"] for row in series], marker="o", label="support cliques") - ax.plot(x, [row["compressed_cliques"] for row in series], marker="s", label="compressed cliques") - ax.plot(x, [row["reduced_state_dim"] for row in series], marker="^", label="reduced state dim") + ax.plot( + x, + [row["support_cliques"] for row in series], + marker="o", + label="support cliques", + ) + ax.plot( + x, + [row["compressed_cliques"] for row in series], + marker="s", + label="compressed cliques", + ) + ax.plot( + x, + [row["reduced_state_dim"] for row in series], + marker="^", + label="reduced-state dimension", + ) ax.set_title(dataset_label(dataset)) ax.set_xlabel("Query size") ax.set_ylabel("Count / dimension") @@ -175,19 +292,52 @@ def plot_structure(rows, output_path): def plot_selected_cross(rows, output_path): - subset = [row for row in rows if row["mode"] == "cross" and row["query_family"] == "selected_cross" and row["dataset"] in {"w10000.graph", "w20000.txt"}] + """Plot selected cross-covariance speedups for all benchmark variants.""" + subset = [ + row + for row in rows + if row["mode"] == "cross" + and row["query_family"] == "selected_cross" + and row["dataset"] in {"w10000.graph", "w20000.txt"} + ] variants = ["legacy_dense", "steiner_dense", "legacy_solve", "steiner_solve"] variant_styles = { - "legacy_dense": {"color": "#228b22", "linestyle": "--", "marker": "s", "linewidth": 2.0}, - "steiner_dense": {"color": "#ff8c00", "linestyle": "-", "marker": "o", "linewidth": 2.0}, - "legacy_solve": {"color": "#1f77b4", "linestyle": "-.", "marker": "^", "linewidth": 2.0}, - "steiner_solve": {"color": "#b22222", "linestyle": "-", "marker": "D", "linewidth": 2.2}, + "legacy_dense": { + "color": "#228b22", + "linestyle": "--", + "marker": "s", + "linewidth": 2.0, + }, + "steiner_dense": { + "color": "#ff8c00", + "linestyle": "-", + "marker": "o", + "linewidth": 2.0, + }, + "legacy_solve": { + "color": "#1f77b4", + "linestyle": "-.", + "marker": "^", + "linewidth": 2.0, + }, + "steiner_solve": { + "color": "#b22222", + "linestyle": "-", + "marker": "D", + "linewidth": 2.2, + }, } figure, axes = plt.subplots(1, 2, figsize=(11, 4), sharey=True) for ax, dataset in zip(axes, ["w10000.graph", "w20000.txt"]): for variant in variants: series = sorted( - [row for row in subset if row["dataset"] == dataset and row["ordering"] == "COLAMD" and row["variant"] == variant], + [ + row + for row in subset + if row["dataset"] == dataset + and row["ordering"] == "COLAMD" + and row["variant"] == variant + ], key=lambda row: row["query_size"], ) if not series: @@ -214,12 +364,14 @@ def plot_selected_cross(rows, output_path): def load_key_list(path): + """Load a single-column key CSV.""" with open(path, newline="") as handle: reader = csv.DictReader(handle) return [int(row["key"]) for row in reader] def load_pose_rows(path): + """Load pose metadata used by the visual summary figures.""" with open(path, newline="") as handle: reader = csv.DictReader(handle) rows = list(reader) @@ -234,6 +386,7 @@ def load_pose_rows(path): def load_edge_rows(path): + """Load pose-graph edges used by the visual summary figures.""" with open(path, newline="") as handle: reader = csv.DictReader(handle) rows = list(reader) @@ -244,6 +397,7 @@ def load_edge_rows(path): def plot_w100_queries(data_dir, output_path): + """Render representative local and wide-separated query selections on w100.""" pose_rows = load_pose_rows(data_dir / "w100_poses.csv") edge_rows = load_edge_rows(data_dir / "w100_edges.csv") local_keys = load_key_list(data_dir / "w100_local_keys.csv") @@ -340,12 +494,14 @@ def plot_w100_queries(data_dir, output_path): def pose_block(covariance, keys, key): + """Extract the 3x3 Pose2 marginal block for one key.""" block_index = keys.index(key) start = 3 * block_index return covariance[start : start + 3, start : start + 3] def representative_pose_key(keys, covariance): + """Select the queried pose with the largest translational uncertainty.""" scored = [] for key in keys: marginal = pose_block(covariance, keys, key) @@ -356,6 +512,7 @@ def representative_pose_key(keys, covariance): def sample_tangent_gaussian(rng, covariance, size): + """Sample a Gaussian in Pose2 tangent coordinates.""" symmetric_covariance = 0.5 * (covariance + covariance.T) eigenvalues, eigenvectors = np.linalg.eigh(symmetric_covariance) clamped = np.clip(eigenvalues, 0.0, None) @@ -365,6 +522,7 @@ def sample_tangent_gaussian(rng, covariance, size): def exp_se2(tangent): + """Evaluate the SE(2) exponential map for one tangent vector.""" vx, vy, omega = tangent if abs(omega) < 1e-9: return np.array([vx, vy]), omega @@ -378,6 +536,7 @@ def exp_se2(tangent): def retract_pose(mean_pose, tangent): + """Push a tangent perturbation forward from a mean Pose2 state.""" translation, omega = exp_se2(tangent) mean_theta = mean_pose["theta"] rotation = np.array( @@ -391,10 +550,12 @@ def retract_pose(mean_pose, tangent): def wrap_degrees(angle_radians): + """Wrap an angle in radians to the range [-180, 180) degrees.""" return ((np.rad2deg(angle_radians) + 180.0) % 360.0) - 180.0 def draw_heading_arrow(ax, pose_row, length=1.0): + """Draw a heading arrow for a mean pose.""" dx = length * math.cos(pose_row["theta"]) dy = length * math.sin(pose_row["theta"]) ax.arrow( @@ -412,6 +573,7 @@ def draw_heading_arrow(ax, pose_row, length=1.0): def draw_world_sample_ellipse(ax, positions): + """Draw the empirical 2-sigma ellipse of sampled world-frame positions.""" covariance_xy = np.cov(positions[:, :2].T) center = positions[:, :2].mean(axis=0) eigenvalues, eigenvectors = np.linalg.eigh(covariance_xy) @@ -436,6 +598,7 @@ def draw_world_sample_ellipse(ax, positions): def plot_pose2_marginals(data_dir, output_path): + """Render representative Pose2 marginals as pushed-forward sample clouds.""" local_keys = load_key_list(data_dir / "w100_local_keys.csv") wide_keys = load_key_list(data_dir / "w100_wide_keys.csv") pose_rows = {row["key"]: row for row in load_pose_rows(data_dir / "w100_poses.csv")} @@ -454,15 +617,27 @@ def plot_pose2_marginals(data_dir, output_path): heatmap_axes = axes[:2] colorbar_axis = axes[2] specifications = [ - ("Representative local Pose2 marginal", local_key, local_keys, local_covariance), - ("Representative wide-separated Pose2 marginal", wide_key, wide_keys, wide_covariance), + ( + "Representative local Pose2 marginal", + local_key, + local_keys, + local_covariance, + ), + ( + "Representative wide-separated Pose2 marginal", + wide_key, + wide_keys, + wide_covariance, + ), ] for ax, (title, key, keys, covariance) in zip(heatmap_axes, specifications): marginal = pose_block(covariance, keys, key) mean_pose = pose_rows[key] samples_tangent = sample_tangent_gaussian(rng, marginal, size=4000) - positions = np.array([retract_pose(mean_pose, tangent) for tangent in samples_tangent]) + positions = np.array( + [retract_pose(mean_pose, tangent) for tangent in samples_tangent] + ) headings = wrap_degrees(positions[:, 2]) heatmap = ax.scatter( positions[:, 0], @@ -508,6 +683,7 @@ def plot_pose2_marginals(data_dir, output_path): def main(): + """Parse arguments and generate all requested benchmark figures.""" parser = argparse.ArgumentParser() parser.add_argument("--input", required=True) parser.add_argument("--output-dir", required=True) @@ -522,7 +698,12 @@ def main(): rows = baseline_speedups( to_float( load_rows(input_path), - ["median_total_ms", "total_total_ms", "median_reduction_ms", "median_extraction_ms"], + [ + "median_total_ms", + "total_total_ms", + "median_reduction_ms", + "median_extraction_ms", + ], ) ) diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp index 3681e97852..5b16cabaa0 100644 --- a/timing/timeBayesTreeCovariance.cpp +++ b/timing/timeBayesTreeCovariance.cpp @@ -1,3 +1,20 @@ +/* ---------------------------------------------------------------------------- + + * 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 timeBayesTreeCovariance.cpp + * @brief Benchmark Bayes-tree covariance recovery variants. + * @date March 2026 + * @author Frank Dellaert + */ + #include #include #include @@ -27,6 +44,7 @@ using namespace std; namespace { +/// Covariance-recovery variant used in the benchmark. enum class Variant { LegacyDense, SteinerDense, @@ -34,6 +52,7 @@ enum class Variant { SteinerSolve, }; +/// One benchmark query together with any selected-block split. struct QueryCase { string family; size_t querySize; @@ -43,11 +62,13 @@ struct QueryCase { bool crossCovariance = false; }; +/// Structural statistics for the support touched by a query. struct SupportStats { size_t supportCliques = 0; size_t compressedCliques = 0; }; +/// Timing result for one query under one variant. struct RawResult { string dataset; string ordering; @@ -64,6 +85,7 @@ struct RawResult { size_t reducedStateDim = 0; }; +/// Grouping key for aggregating repeated benchmark queries. struct SummaryKey { string dataset; string ordering; @@ -79,6 +101,7 @@ struct SummaryKey { } }; +/// Hash function for SummaryKey. struct SummaryKeyHash { size_t operator()(const SummaryKey& key) const { size_t seed = std::hash()(key.dataset); @@ -96,6 +119,7 @@ struct SummaryKeyHash { } }; +/// Aggregated timing samples for one SummaryKey. struct SummaryValue { vector totalMs; vector reductionMs; @@ -105,6 +129,7 @@ struct SummaryValue { size_t reducedStateDim = 0; }; +/// Return a deduplicated, sorted key list. KeyVector uniqueSortedKeys(const KeyVector& keys) { KeyVector result = keys; sort(result.begin(), result.end()); @@ -112,6 +137,7 @@ KeyVector uniqueSortedKeys(const KeyVector& keys) { return result; } +/// Return all Pose2 keys in sorted order. KeyVector poseKeys(const Values& values) { KeyVector keys; for (const auto& keyValue : values.extract()) { @@ -121,6 +147,7 @@ KeyVector poseKeys(const Values& values) { return keys; } +/// Return the variable dimensions for a key list. vector dimsForKeys(const KeyVector& keys, const Values& values) { vector dims; dims.reserve(keys.size()); @@ -130,6 +157,7 @@ vector dimsForKeys(const KeyVector& keys, const Values& values) { return dims; } +/// Convert block dimensions to prefix offsets. vector blockOffsets(const vector& dims) { vector offsets(dims.size() + 1, 0); for (size_t i = 0; i < dims.size(); ++i) { @@ -138,6 +166,7 @@ vector blockOffsets(const vector& dims) { return offsets; } +/// Sum the dimensions of a key set. size_t totalDimension(const KeySet& keys, const Values& values) { size_t dim = 0; for (Key key : keys) { @@ -146,6 +175,7 @@ size_t totalDimension(const KeySet& keys, const Values& values) { return dim; } +/// Compute the lowest common ancestor of two Bayes-tree cliques. template shared_ptr findLowestCommonAncestor(const shared_ptr& lhs, const shared_ptr& rhs) { @@ -161,6 +191,7 @@ shared_ptr findLowestCommonAncestor(const shared_ptr& lhs, return nullptr; } +/// Estimate the support size and compressed size for a query. SupportStats analyzeSupport(const GaussianBayesTree& bayesTree, const KeyVector& queryKeys) { vector queryCliques; @@ -218,6 +249,7 @@ SupportStats analyzeSupport(const GaussianBayesTree& bayesTree, return {support.size(), compressed}; } +/// Build the legacy reduced factor graph by marginal re-elimination. GaussianFactorGraph legacyReducedFactorGraph(const GaussianFactorGraph& graph, const Ordering& fullOrdering, const KeyVector& queryKeys) { @@ -226,17 +258,20 @@ GaussianFactorGraph legacyReducedFactorGraph(const GaussianFactorGraph& graph, *graph.marginalMultifrontalBayesTree(queryKeys, EliminatePreferCholesky)); } +/// Build the localized reduced factor graph using Bayes-tree joint extraction. GaussianFactorGraph steinerReducedFactorGraph( const GaussianBayesTree& bayesTree, const KeyVector& queryKeys) { return *bayesTree.joint(queryKeys, EliminatePreferCholesky); } +/// Eliminate a reduced factor graph to a Bayes net ordered by the query keys. GaussianBayesNet queryBayesNet(const GaussianFactorGraph& graph, const KeyVector& queryKeys) { return *graph.marginalMultifrontalBayesNet(Ordering(queryKeys), EliminatePreferCholesky); } +/// Recover selected covariance columns using triangular solves. Matrix covarianceColumns(const GaussianBayesNet& bayesNet, const KeyVector& orderedKeys, const vector& dims, @@ -265,6 +300,7 @@ Matrix covarianceColumns(const GaussianBayesNet& bayesNet, return R.triangularView().solve(intermediate); } +/// Extract a left-by-right cross-covariance block from selected columns. Matrix extractCrossBlock(const Matrix& selectedColumns, const KeyVector& orderedKeys, const vector& dims, const KeyVector& left, @@ -302,6 +338,7 @@ Matrix extractCrossBlock(const Matrix& selectedColumns, return result; } +/// Convert a Variant enum to a CSV-friendly name. string variantName(Variant variant) { switch (variant) { case Variant::LegacyDense: @@ -316,10 +353,12 @@ string variantName(Variant variant) { return "unknown"; } +/// Convert an ordering type to a human-readable name. string orderingName(Ordering::OrderingType orderingType) { return orderingType == Ordering::METIS ? "METIS" : "COLAMD"; } +/// Compute the median of a small sample vector. double median(vector values) { if (values.empty()) { return 0.0; @@ -332,6 +371,7 @@ double median(vector values) { return values[mid]; } +/// Sample representative starting indices across a window range. vector sampledStarts(size_t maxStartInclusive, size_t maxQueries, size_t stride = 1) { vector starts; @@ -365,6 +405,7 @@ vector sampledStarts(size_t maxStartInclusive, size_t maxQueries, return starts; } +/// Generate contiguous local-window benchmark queries. vector generateLocalWindows(const KeyVector& poseKeys, size_t querySize, size_t maxQueries) { vector queries; @@ -384,6 +425,7 @@ vector generateLocalWindows(const KeyVector& poseKeys, return queries; } +/// Generate highly overlapping windows to test repeated local queries. vector generateRepeatedOverlap(const KeyVector& poseKeys, size_t querySize, size_t maxQueries) { vector queries; @@ -403,6 +445,7 @@ vector generateRepeatedOverlap(const KeyVector& poseKeys, return queries; } +/// Generate wide-separated queries spread across the trajectory. vector generateWideSeparated(const KeyVector& poseKeys, size_t querySize, size_t maxQueries) { vector queries; @@ -435,6 +478,7 @@ vector generateWideSeparated(const KeyVector& poseKeys, return queries; } +/// Generate selected cross-covariance queries from overlapping windows. vector generateSelectedCross(const KeyVector& poseKeys, size_t querySize, size_t maxQueries) { vector queries; @@ -453,6 +497,7 @@ vector generateSelectedCross(const KeyVector& poseKeys, return queries; } +/// Build the full benchmark workload across all query families. vector buildWorkload(const KeyVector& poseKeyList) { vector queries; for (size_t querySize : {size_t(3), size_t(5), size_t(10), size_t(20)}) { @@ -473,6 +518,7 @@ vector buildWorkload(const KeyVector& poseKeyList) { return queries; } +/// Time one query under one covariance-recovery variant. RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, Variant variant, const GaussianFactorGraph& linearGraph, @@ -553,6 +599,7 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, return result; } +/// Write per-query timing results to CSV. void writeRawCsv(const filesystem::path& path, const vector& results) { ofstream os(path); @@ -571,6 +618,7 @@ void writeRawCsv(const filesystem::path& path, } } +/// Write aggregated benchmark statistics to CSV. void writeSummaryCsv(const filesystem::path& path, const vector& results) { unordered_map summary; @@ -604,6 +652,7 @@ void writeSummaryCsv(const filesystem::path& path, } } +/// Read a string argument from argv or return a default value. string argumentOrDefault(char** begin, char** end, const string& flag, const string& defaultValue) { for (auto it = begin; it != end; ++it) { @@ -614,6 +663,7 @@ string argumentOrDefault(char** begin, char** end, const string& flag, return defaultValue; } +/// Split a comma-separated argument into individual values. vector splitCommaSeparated(const string& input) { vector values; size_t start = 0; From 663dc2e654b20362b3120cf45cdefae2f26fc779 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 17 Mar 2026 22:58:45 -0400 Subject: [PATCH 04/12] Small queries --- timing/README.md | 14 ++++ timing/plot_bayes_tree_covariance.py | 68 ++++++++++++++++++ timing/timeBayesTreeCovariance.cpp | 102 ++++++++++++++++++++++++++- 3 files changed, 181 insertions(+), 3 deletions(-) diff --git a/timing/README.md b/timing/README.md index 9ede106040..685f9cad3a 100644 --- a/timing/README.md +++ b/timing/README.md @@ -32,6 +32,16 @@ This writes: - `timing/results/bayes_tree_covariance/raw.csv` - `timing/results/bayes_tree_covariance/summary.csv` +The generated CSVs now include the small-query families used to benchmark the +legacy common cases: + +- `single_pose` for `Q = 1` +- `pair_pose` for `Q = 2` + +These are timed with the same benchmark executable and appear alongside the +larger `local_window`, `wide_separated`, `overlap_window`, and +`selected_cross` workloads. + ### Export `w100` visual data Run from `build/`: @@ -58,6 +68,7 @@ python3 timing/plot_bayes_tree_covariance.py \ This generates: +- `results-smallq.pdf` - `results-ablation.pdf` - `results-ordering.pdf` - `results-structure.pdf` @@ -69,6 +80,9 @@ This generates: - The benchmark timings measure covariance-query work after optimization and linearization. +- The `results-smallq.pdf` figure summarizes the `Q = 1` and `Q = 2` query + families; the larger performance figures focus on `Q > 2`, where Steiner + localization changes the asymptotic behavior. - The benchmark compares four variants: - `legacy_dense` - `steiner_dense` diff --git a/timing/plot_bayes_tree_covariance.py b/timing/plot_bayes_tree_covariance.py index ea56f03d40..45ba46f553 100644 --- a/timing/plot_bayes_tree_covariance.py +++ b/timing/plot_bayes_tree_covariance.py @@ -167,6 +167,73 @@ def plot_ablation(rows, output_path): plt.close(figure) +def plot_small_queries(rows, output_path): + """Plot timing for the legacy single-pose and pair-pose query families.""" + subset = [ + row + for row in rows + if row["mode"] == "joint" + and row["query_family"] in {"single_pose", "pair_pose"} + and row["dataset"] in {"w10000.graph", "w20000.txt"} + ] + families = [("single_pose", "Q = 1"), ("pair_pose", "Q = 2")] + groups = [ + ("w10000.graph", "COLAMD"), + ("w10000.graph", "METIS"), + ("w20000.txt", "COLAMD"), + ("w20000.txt", "METIS"), + ] + variants = ["legacy_dense", "steiner_dense", "legacy_solve", "steiner_solve"] + colors = { + "legacy_dense": "#228b22", + "steiner_dense": "#ff8c00", + "legacy_solve": "#1f77b4", + "steiner_solve": "#b22222", + } + figure, axes = plt.subplots(1, 2, figsize=(12, 4), sharey=True) + width = 0.18 + x_positions = np.arange(len(groups)) + + for ax, (family, title) in zip(axes, families): + family_rows = [row for row in subset if row["query_family"] == family] + for index, variant in enumerate(variants): + heights = [] + for dataset, ordering in groups: + matches = [ + row["median_total_ms"] + for row in family_rows + if row["dataset"] == dataset + and row["ordering"] == ordering + and row["variant"] == variant + ] + heights.append(matches[0] if matches else math.nan) + ax.bar( + x_positions + (index - 1.5) * width, + heights, + width=width, + color=colors[variant], + label=variant.replace("_", " "), + ) + ax.set_title(title) + ax.set_xticks( + x_positions, + [ + "w10000\nCOLAMD", + "w10000\nMETIS", + "w20000\nCOLAMD", + "w20000\nMETIS", + ], + ) + ax.set_ylabel("Median query time (ms)") + ax.set_yscale("log") + ax.grid(True, axis="y", alpha=0.3) + handles, labels = axes[0].get_legend_handles_labels() + figure.legend(handles, labels, loc="upper center", ncol=4, frameon=False) + figure.tight_layout(rect=(0, 0, 1, 0.88)) + figure.savefig(output_path) + plt.close(figure) + + def plot_ordering(rows, output_path): """Compare ordering sensitivity for the dense baseline and localized method.""" target_rows = [ @@ -708,6 +775,7 @@ def main(): ) plot_ablation(rows, output_dir / "results-ablation.pdf") + plot_small_queries(rows, output_dir / "results-smallq.pdf") plot_ordering(rows, output_dir / "results-ordering.pdf") plot_structure(rows, output_dir / "results-structure.pdf") plot_selected_cross(rows, output_dir / "results-cross.pdf") diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp index 5b16cabaa0..b5202443de 100644 --- a/timing/timeBayesTreeCovariance.cpp +++ b/timing/timeBayesTreeCovariance.cpp @@ -264,6 +264,12 @@ GaussianFactorGraph steinerReducedFactorGraph( return *bayesTree.joint(queryKeys, EliminatePreferCholesky); } +/// Build the legacy two-key reduced factor graph using the pairwise joint path. +GaussianFactorGraph pairReducedFactorGraph(const GaussianBayesTree& bayesTree, + const KeyVector& queryKeys) { + return *bayesTree.joint(queryKeys[0], queryKeys[1], EliminatePreferCholesky); +} + /// Eliminate a reduced factor graph to a Bayes net ordered by the query keys. GaussianBayesNet queryBayesNet(const GaussianFactorGraph& graph, const KeyVector& queryKeys) { @@ -425,6 +431,41 @@ vector generateLocalWindows(const KeyVector& poseKeys, return queries; } +/// Generate single-pose queries that exercise the legacy marginal path. +vector generateSinglePoseQueries(const KeyVector& poseKeys, + size_t maxQueries) { + vector queries; + if (poseKeys.empty()) { + return queries; + } + for (size_t start : sampledStarts(poseKeys.size() - 1, maxQueries, + max(1, poseKeys.size() / maxQueries))) { + QueryCase query; + query.family = "single_pose"; + query.querySize = 1; + query.keys = {poseKeys[start]}; + queries.push_back(query); + } + return queries; +} + +/// Generate adjacent-pair queries that exercise the legacy pairwise path. +vector generatePairPoseQueries(const KeyVector& poseKeys, + size_t maxQueries) { + vector queries; + if (poseKeys.size() < 2) { + return queries; + } + for (size_t start : sampledStarts(poseKeys.size() - 2, maxQueries, 1)) { + QueryCase query; + query.family = "pair_pose"; + query.querySize = 2; + query.keys = {poseKeys[start], poseKeys[start + 1]}; + queries.push_back(query); + } + return queries; +} + /// Generate highly overlapping windows to test repeated local queries. vector generateRepeatedOverlap(const KeyVector& poseKeys, size_t querySize, size_t maxQueries) { @@ -500,6 +541,12 @@ vector generateSelectedCross(const KeyVector& poseKeys, /// Build the full benchmark workload across all query families. vector buildWorkload(const KeyVector& poseKeyList) { vector queries; + auto singlePose = generateSinglePoseQueries(poseKeyList, 32); + queries.insert(queries.end(), singlePose.begin(), singlePose.end()); + + auto pairPose = generatePairPoseQueries(poseKeyList, 32); + queries.insert(queries.end(), pairPose.begin(), pairPose.end()); + for (size_t querySize : {size_t(3), size_t(5), size_t(10), size_t(20)}) { auto local = generateLocalWindows(poseKeyList, querySize, 16); queries.insert(queries.end(), local.begin(), local.end()); @@ -528,11 +575,53 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, const KeyVector orderedKeys = uniqueSortedKeys(query.keys); const SupportStats supportStats = analyzeSupport(bayesTree, orderedKeys); + if (orderedKeys.size() == 1) { + const auto reductionStart = chrono::steady_clock::now(); + const auto marginalFactor = + bayesTree.marginalFactor(orderedKeys.front(), EliminatePreferCholesky); + const Matrix information = marginalFactor->information(); + const auto reductionEnd = chrono::steady_clock::now(); + + const auto extractionStart = chrono::steady_clock::now(); + Matrix recovered; + if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { + recovered = information.inverse(); + } else { + recovered = + information.selfadjointView().llt().solve( + Matrix::Identity(information.rows(), information.cols())); + } + const auto extractionEnd = chrono::steady_clock::now(); + + volatile double checksum = recovered.sum(); + (void)checksum; + + RawResult result; + result.dataset = datasetName; + result.ordering = orderingLabel; + result.family = query.family; + result.mode = "joint"; + result.variant = variantName(variant); + result.querySize = query.querySize; + result.queryIndex = queryIndex; + result.reductionMs = + chrono::duration(reductionEnd - reductionStart).count(); + result.extractionMs = + chrono::duration(extractionEnd - extractionStart).count(); + result.totalMs = result.reductionMs + result.extractionMs; + result.supportCliques = 1; + result.compressedCliques = 1; + result.reducedStateDim = information.rows(); + return result; + } + const auto reductionStart = chrono::steady_clock::now(); GaussianFactorGraph reducedGraph = - (variant == Variant::LegacyDense || variant == Variant::LegacySolve) - ? legacyReducedFactorGraph(linearGraph, fullOrdering, orderedKeys) - : steinerReducedFactorGraph(bayesTree, orderedKeys); + orderedKeys.size() == 2 + ? pairReducedFactorGraph(bayesTree, orderedKeys) + : ((variant == Variant::LegacyDense || variant == Variant::LegacySolve) + ? legacyReducedFactorGraph(linearGraph, fullOrdering, orderedKeys) + : steinerReducedFactorGraph(bayesTree, orderedKeys)); const auto reductionEnd = chrono::steady_clock::now(); const auto extractionStart = chrono::steady_clock::now(); @@ -726,6 +815,13 @@ int main(int argc, char** argv) { size_t queryIndex = 0; for (const QueryCase& query : workload) { + if (query.querySize == 1) { + (void)bayesTree.marginalFactor(query.keys.front(), + EliminatePreferCholesky); + } else if (query.querySize == 2) { + (void)bayesTree.joint(query.keys[0], query.keys[1], + EliminatePreferCholesky); + } for (const Variant variant : {Variant::LegacyDense, Variant::SteinerDense, Variant::LegacySolve, Variant::SteinerSolve}) { From 59f8990890612a2510688b728f38facf3b973fdf Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 23 Mar 2026 00:38:41 -0400 Subject: [PATCH 05/12] Repeats --- timing/README.md | 10 + timing/plot_bayes_tree_covariance.py | 20 +- timing/timeBayesTreeCovariance.cpp | 274 +++++++++++++++++++++++---- 3 files changed, 256 insertions(+), 48 deletions(-) diff --git a/timing/README.md b/timing/README.md index 685f9cad3a..def0006d2c 100644 --- a/timing/README.md +++ b/timing/README.md @@ -24,12 +24,14 @@ Run from `build/`: ```bash ./timing/timeBayesTreeCovariance \ --datasets w100.graph,w10000.graph,w20000.txt \ + --repeats 10 \ --output-dir ../timing/results/bayes_tree_covariance ``` This writes: - `timing/results/bayes_tree_covariance/raw.csv` +- `timing/results/bayes_tree_covariance/per_query.csv` - `timing/results/bayes_tree_covariance/summary.csv` The generated CSVs now include the small-query families used to benchmark the @@ -80,6 +82,14 @@ This generates: - The benchmark timings measure covariance-query work after optimization and linearization. +- Each distinct query is run once as an untimed warmup and then `--repeats` + times as measured repetitions. +- `raw.csv` stores one row per measured repetition. +- `per_query.csv` stores one row per distinct query, aggregating repeated + timings by per-query means. +- `summary.csv` stores one row per query family bucket, aggregating the + per-query means and structural statistics by medians across the sampled + queries. - The `results-smallq.pdf` figure summarizes the `Q = 1` and `Q = 2` query families; the larger performance figures focus on `Q > 2`, where Steiner localization changes the asymptotic behavior. diff --git a/timing/plot_bayes_tree_covariance.py b/timing/plot_bayes_tree_covariance.py index 45ba46f553..5d824607b3 100644 --- a/timing/plot_bayes_tree_covariance.py +++ b/timing/plot_bayes_tree_covariance.py @@ -7,7 +7,7 @@ See LICENSE for the license information Generate paper-ready plots for the Bayes-tree covariance benchmarks. -Author: Frank Dellaert +Author: Codex 5.4, prompted by Frank Dellaert """ import argparse @@ -35,9 +35,10 @@ def to_float(rows, fields): row[field] = float(row[field]) row["query_size"] = int(row["query_size"]) row["queries"] = int(row["queries"]) - row["support_cliques"] = int(row["support_cliques"]) - row["compressed_cliques"] = int(row["compressed_cliques"]) - row["reduced_state_dim"] = int(row["reduced_state_dim"]) + row["repeats"] = int(row["repeats"]) + row["support_cliques"] = float(row["support_cliques"]) + row["compressed_cliques"] = float(row["compressed_cliques"]) + row["reduced_state_dim"] = float(row["reduced_state_dim"]) return rows @@ -224,7 +225,7 @@ def plot_small_queries(rows, output_path): "w20000\nMETIS", ], ) - ax.set_ylabel("Median query time (ms)") + ax.set_ylabel("Median per-query mean time (ms)") ax.set_yscale("log") ax.grid(True, axis="y", alpha=0.3) handles, labels = axes[0].get_legend_handles_labels() @@ -301,7 +302,7 @@ def plot_ordering(rows, output_path): ax.set_title(dataset_label(dataset)) ax.set_xlabel("Local-window query size") ax.set_xticks(query_sizes, [str(size) for size in query_sizes]) - ax.set_ylabel("Median query time (ms)") + ax.set_ylabel("Median per-query mean time (ms)") ax.set_yscale("log") ax.grid(True, axis="y", alpha=0.3) handles, labels = axes[0].get_legend_handles_labels() @@ -349,7 +350,7 @@ def plot_structure(rows, output_path): ) ax.set_title(dataset_label(dataset)) ax.set_xlabel("Query size") - ax.set_ylabel("Count / dimension") + ax.set_ylabel("Median count / dimension") ax.grid(True, alpha=0.3) handles, labels = axes[0].get_legend_handles_labels() figure.legend(handles, labels, loc="upper center", ncol=3, frameon=False) @@ -767,9 +768,12 @@ def main(): load_rows(input_path), [ "median_total_ms", - "total_total_ms", + "sum_query_mean_total_ms", "median_reduction_ms", "median_extraction_ms", + "support_cliques", + "compressed_cliques", + "reduced_state_dim", ], ) ) diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp index b5202443de..132752b979 100644 --- a/timing/timeBayesTreeCovariance.cpp +++ b/timing/timeBayesTreeCovariance.cpp @@ -12,7 +12,7 @@ * @file timeBayesTreeCovariance.cpp * @brief Benchmark Bayes-tree covariance recovery variants. * @date March 2026 - * @author Frank Dellaert + * @author Codex 5.4, prompted by Frank Dellaert */ #include @@ -77,6 +77,7 @@ struct RawResult { string variant; size_t querySize = 0; size_t queryIndex = 0; + size_t repeatIndex = 0; double totalMs = 0.0; double reductionMs = 0.0; double extractionMs = 0.0; @@ -85,6 +86,68 @@ struct RawResult { size_t reducedStateDim = 0; }; +/// Grouping key for per-query aggregation across repeated timings. +struct PerQueryKey { + string dataset; + string ordering; + string family; + string mode; + string variant; + size_t querySize = 0; + size_t queryIndex = 0; + + bool operator==(const PerQueryKey& other) const { + return dataset == other.dataset && ordering == other.ordering && + family == other.family && mode == other.mode && + variant == other.variant && querySize == other.querySize && + queryIndex == other.queryIndex; + } +}; + +/// Hash function for PerQueryKey. +struct PerQueryKeyHash { + size_t operator()(const PerQueryKey& key) const { + size_t seed = std::hash()(key.dataset); + seed ^= std::hash()(key.ordering) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= std::hash()(key.family) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= + std::hash()(key.mode) + 0x9e3779b9 + (seed << 6) + (seed >> 2); + seed ^= std::hash()(key.variant) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= std::hash()(key.querySize) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + seed ^= std::hash()(key.queryIndex) + 0x9e3779b9 + (seed << 6) + + (seed >> 2); + return seed; + } +}; + +/// Aggregated result for one fixed query across repeated timing samples. +struct PerQueryResult { + string dataset; + string ordering; + string family; + string mode; + string variant; + size_t querySize = 0; + size_t queryIndex = 0; + size_t repeats = 0; + double meanTotalMs = 0.0; + double meanReductionMs = 0.0; + double meanExtractionMs = 0.0; + double medianTotalMs = 0.0; + double medianReductionMs = 0.0; + double medianExtractionMs = 0.0; + double stddevTotalMs = 0.0; + double stddevReductionMs = 0.0; + double stddevExtractionMs = 0.0; + size_t supportCliques = 0; + size_t compressedCliques = 0; + size_t reducedStateDim = 0; +}; + /// Grouping key for aggregating repeated benchmark queries. struct SummaryKey { string dataset; @@ -121,12 +184,13 @@ struct SummaryKeyHash { /// Aggregated timing samples for one SummaryKey. struct SummaryValue { - vector totalMs; - vector reductionMs; - vector extractionMs; - size_t supportCliques = 0; - size_t compressedCliques = 0; - size_t reducedStateDim = 0; + vector queryMeanTotalMs; + vector queryMeanReductionMs; + vector queryMeanExtractionMs; + vector supportCliques; + vector compressedCliques; + vector reducedStateDim; + size_t repeats = 0; }; /// Return a deduplicated, sorted key list. @@ -377,6 +441,29 @@ double median(vector values) { return values[mid]; } +/// Compute the arithmetic mean of a sample vector. +double mean(const vector& values) { + if (values.empty()) { + return 0.0; + } + const double sum = accumulate(values.begin(), values.end(), 0.0); + return sum / static_cast(values.size()); +} + +/// Compute the population standard deviation of a sample vector. +double stddev(const vector& values) { + if (values.size() < 2) { + return 0.0; + } + const double sampleMean = mean(values); + double sumSquares = 0.0; + for (double value : values) { + const double delta = value - sampleMean; + sumSquares += delta * delta; + } + return sqrt(sumSquares / static_cast(values.size())); +} + /// Sample representative starting indices across a window range. vector sampledStarts(size_t maxStartInclusive, size_t maxQueries, size_t stride = 1) { @@ -438,8 +525,9 @@ vector generateSinglePoseQueries(const KeyVector& poseKeys, if (poseKeys.empty()) { return queries; } - for (size_t start : sampledStarts(poseKeys.size() - 1, maxQueries, - max(1, poseKeys.size() / maxQueries))) { + for (size_t start : + sampledStarts(poseKeys.size() - 1, maxQueries, + max(1, poseKeys.size() / maxQueries))) { QueryCase query; query.family = "single_pose"; query.querySize = 1; @@ -571,7 +659,8 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, const GaussianFactorGraph& linearGraph, const GaussianBayesTree& bayesTree, const Ordering& fullOrdering, const Values& values, - const QueryCase& query, size_t queryIndex) { + const QueryCase& query, size_t queryIndex, + size_t repeatIndex) { const KeyVector orderedKeys = uniqueSortedKeys(query.keys); const SupportStats supportStats = analyzeSupport(bayesTree, orderedKeys); @@ -587,9 +676,8 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { recovered = information.inverse(); } else { - recovered = - information.selfadjointView().llt().solve( - Matrix::Identity(information.rows(), information.cols())); + recovered = information.selfadjointView().llt().solve( + Matrix::Identity(information.rows(), information.cols())); } const auto extractionEnd = chrono::steady_clock::now(); @@ -604,10 +692,12 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, result.variant = variantName(variant); result.querySize = query.querySize; result.queryIndex = queryIndex; + result.repeatIndex = repeatIndex; result.reductionMs = chrono::duration(reductionEnd - reductionStart).count(); result.extractionMs = - chrono::duration(extractionEnd - extractionStart).count(); + chrono::duration(extractionEnd - extractionStart) + .count(); result.totalMs = result.reductionMs + result.extractionMs; result.supportCliques = 1; result.compressedCliques = 1; @@ -619,8 +709,10 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, GaussianFactorGraph reducedGraph = orderedKeys.size() == 2 ? pairReducedFactorGraph(bayesTree, orderedKeys) - : ((variant == Variant::LegacyDense || variant == Variant::LegacySolve) - ? legacyReducedFactorGraph(linearGraph, fullOrdering, orderedKeys) + : ((variant == Variant::LegacyDense || + variant == Variant::LegacySolve) + ? legacyReducedFactorGraph(linearGraph, fullOrdering, + orderedKeys) : steinerReducedFactorGraph(bayesTree, orderedKeys)); const auto reductionEnd = chrono::steady_clock::now(); @@ -677,6 +769,7 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, result.variant = variantName(variant); result.querySize = query.querySize; result.queryIndex = queryIndex; + result.repeatIndex = repeatIndex; result.reductionMs = chrono::duration(reductionEnd - reductionStart).count(); result.extractionMs = @@ -693,6 +786,7 @@ void writeRawCsv(const filesystem::path& path, const vector& results) { ofstream os(path); os << "dataset,ordering,query_family,mode,variant,query_size,query_index," + "repeat_index," "total_ms,reduction_ms,extraction_ms,support_cliques,compressed_" "cliques," "reduced_state_dim\n"; @@ -700,21 +794,31 @@ void writeRawCsv(const filesystem::path& path, for (const auto& result : results) { os << result.dataset << ',' << result.ordering << ',' << result.family << ',' << result.mode << ',' << result.variant << ',' << result.querySize - << ',' << result.queryIndex << ',' << result.totalMs << ',' - << result.reductionMs << ',' << result.extractionMs << ',' - << result.supportCliques << ',' << result.compressedCliques << ',' - << result.reducedStateDim << '\n'; + << ',' << result.queryIndex << ',' << result.repeatIndex << ',' + << result.totalMs << ',' << result.reductionMs << ',' + << result.extractionMs << ',' << result.supportCliques << ',' + << result.compressedCliques << ',' << result.reducedStateDim << '\n'; } } -/// Write aggregated benchmark statistics to CSV. -void writeSummaryCsv(const filesystem::path& path, - const vector& results) { - unordered_map summary; +/// Aggregate repeated raw timings into one row per distinct query. +vector aggregatePerQueryResults( + const vector& results) { + struct PerQuerySamples { + vector totalMs; + vector reductionMs; + vector extractionMs; + size_t supportCliques = 0; + size_t compressedCliques = 0; + size_t reducedStateDim = 0; + }; + + unordered_map perQuery; for (const auto& result : results) { - const SummaryKey key{result.dataset, result.ordering, result.family, - result.mode, result.variant, result.querySize}; - auto& value = summary[key]; + const PerQueryKey key{result.dataset, result.ordering, result.family, + result.mode, result.variant, result.querySize, + result.queryIndex}; + auto& value = perQuery[key]; value.totalMs.push_back(result.totalMs); value.reductionMs.push_back(result.reductionMs); value.extractionMs.push_back(result.extractionMs); @@ -723,21 +827,94 @@ void writeSummaryCsv(const filesystem::path& path, value.reducedStateDim = result.reducedStateDim; } + vector aggregated; + aggregated.reserve(perQuery.size()); + for (const auto& [key, value] : perQuery) { + PerQueryResult result; + result.dataset = key.dataset; + result.ordering = key.ordering; + result.family = key.family; + result.mode = key.mode; + result.variant = key.variant; + result.querySize = key.querySize; + result.queryIndex = key.queryIndex; + result.repeats = value.totalMs.size(); + result.meanTotalMs = mean(value.totalMs); + result.meanReductionMs = mean(value.reductionMs); + result.meanExtractionMs = mean(value.extractionMs); + result.medianTotalMs = median(value.totalMs); + result.medianReductionMs = median(value.reductionMs); + result.medianExtractionMs = median(value.extractionMs); + result.stddevTotalMs = stddev(value.totalMs); + result.stddevReductionMs = stddev(value.reductionMs); + result.stddevExtractionMs = stddev(value.extractionMs); + result.supportCliques = value.supportCliques; + result.compressedCliques = value.compressedCliques; + result.reducedStateDim = value.reducedStateDim; + aggregated.push_back(result); + } + return aggregated; +} + +/// Write per-query aggregated timing results to CSV. +void writePerQueryCsv(const filesystem::path& path, + const vector& results) { ofstream os(path); - os << "dataset,ordering,query_family,mode,variant,query_size,queries," - "median_total_ms,total_total_ms,median_reduction_ms,median_extraction_" - "ms," + os << "dataset,ordering,query_family,mode,variant,query_size,query_index," + "repeats,mean_total_ms,mean_reduction_ms,mean_extraction_ms," + "median_total_ms,median_reduction_ms,median_extraction_ms," + "stddev_total_ms,stddev_reduction_ms,stddev_extraction_ms," "support_cliques,compressed_cliques,reduced_state_dim\n"; os << fixed << setprecision(6); + for (const auto& result : results) { + os << result.dataset << ',' << result.ordering << ',' << result.family + << ',' << result.mode << ',' << result.variant << ',' << result.querySize + << ',' << result.queryIndex << ',' << result.repeats << ',' + << result.meanTotalMs << ',' << result.meanReductionMs << ',' + << result.meanExtractionMs << ',' << result.medianTotalMs << ',' + << result.medianReductionMs << ',' << result.medianExtractionMs << ',' + << result.stddevTotalMs << ',' << result.stddevReductionMs << ',' + << result.stddevExtractionMs << ',' << result.supportCliques << ',' + << result.compressedCliques << ',' << result.reducedStateDim << '\n'; + } +} + +/// Write family-level summary statistics aggregated from per-query results. +void writeSummaryCsv(const filesystem::path& path, + const vector& results) { + unordered_map summary; + for (const auto& result : results) { + const SummaryKey key{result.dataset, result.ordering, result.family, + result.mode, result.variant, result.querySize}; + auto& value = summary[key]; + value.queryMeanTotalMs.push_back(result.meanTotalMs); + value.queryMeanReductionMs.push_back(result.meanReductionMs); + value.queryMeanExtractionMs.push_back(result.meanExtractionMs); + value.supportCliques.push_back(static_cast(result.supportCliques)); + value.compressedCliques.push_back( + static_cast(result.compressedCliques)); + value.reducedStateDim.push_back( + static_cast(result.reducedStateDim)); + value.repeats = result.repeats; + } + + ofstream os(path); + os << "dataset,ordering,query_family,mode,variant,query_size,queries,repeats," + "median_total_ms,sum_query_mean_total_ms,median_reduction_ms," + "median_extraction_ms,support_cliques,compressed_cliques," + "reduced_state_dim\n"; + os << fixed << setprecision(6); for (const auto& [key, value] : summary) { - const double totalTime = - accumulate(value.totalMs.begin(), value.totalMs.end(), 0.0); + const double totalTime = accumulate(value.queryMeanTotalMs.begin(), + value.queryMeanTotalMs.end(), 0.0); os << key.dataset << ',' << key.ordering << ',' << key.family << ',' << key.mode << ',' << key.variant << ',' << key.querySize << ',' - << value.totalMs.size() << ',' << median(value.totalMs) << ',' - << totalTime << ',' << median(value.reductionMs) << ',' - << median(value.extractionMs) << ',' << value.supportCliques << ',' - << value.compressedCliques << ',' << value.reducedStateDim << '\n'; + << value.queryMeanTotalMs.size() << ',' << value.repeats << ',' + << median(value.queryMeanTotalMs) << ',' << totalTime << ',' + << median(value.queryMeanReductionMs) << ',' + << median(value.queryMeanExtractionMs) << ',' + << median(value.supportCliques) << ',' << median(value.compressedCliques) + << ',' << median(value.reducedStateDim) << '\n'; } } @@ -752,6 +929,13 @@ string argumentOrDefault(char** begin, char** end, const string& flag, return defaultValue; } +/// Read an unsigned integer argument from argv or return a default value. +size_t sizeTArgumentOrDefault(char** begin, char** end, const string& flag, + size_t defaultValue) { + return static_cast( + stoull(argumentOrDefault(begin, end, flag, to_string(defaultValue)))); +} + /// Split a comma-separated argument into individual values. vector splitCommaSeparated(const string& input) { vector values; @@ -777,6 +961,8 @@ int main(int argc, char** argv) { .string()); const vector datasets = splitCommaSeparated(argumentOrDefault( argv, argv + argc, "--datasets", "w100.graph,w10000.graph,w20000.txt")); + const size_t repeats = + sizeTArgumentOrDefault(argv, argv + argc, "--repeats", 10); filesystem::create_directories(outputDir); @@ -826,9 +1012,14 @@ int main(int argc, char** argv) { {Variant::LegacyDense, Variant::SteinerDense, Variant::LegacySolve, Variant::SteinerSolve}) { try { - rawResults.push_back(benchmarkQuery( - datasetName, orderingName(orderingType), variant, linearGraph, - bayesTree, ordering, result, query, queryIndex)); + (void)benchmarkQuery(datasetName, orderingName(orderingType), + variant, linearGraph, bayesTree, ordering, + result, query, queryIndex, 0); + for (size_t repeatIndex = 0; repeatIndex < repeats; ++repeatIndex) { + rawResults.push_back(benchmarkQuery( + datasetName, orderingName(orderingType), variant, linearGraph, + bayesTree, ordering, result, query, queryIndex, repeatIndex)); + } } catch (const std::exception& error) { cerr << "Failure for dataset=" << datasetName << " ordering=" << orderingName(orderingType) @@ -844,7 +1035,10 @@ int main(int argc, char** argv) { } writeRawCsv(outputDir / "raw.csv", rawResults); - writeSummaryCsv(outputDir / "summary.csv", rawResults); + const vector perQueryResults = + aggregatePerQueryResults(rawResults); + writePerQueryCsv(outputDir / "per_query.csv", perQueryResults); + writeSummaryCsv(outputDir / "summary.csv", perQueryResults); cout << "Wrote benchmark results to " << outputDir << endl; return 0; } From 441899ada415753fd6b5b198cda9e2f2eb992980 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 23 Mar 2026 00:48:34 -0400 Subject: [PATCH 06/12] Paper --- doc/CovarianceRecovery.pdf | Bin 0 -> 459298 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 doc/CovarianceRecovery.pdf diff --git a/doc/CovarianceRecovery.pdf b/doc/CovarianceRecovery.pdf new file mode 100644 index 0000000000000000000000000000000000000000..bbb0265b99deeb1d7c8617f90bdc3c0cbffff607 GIT binary patch literal 459298 zcmb5WV~{RE*CpE4Y1_7K+qO>YX&a|)+qP}%v~AnAt$W@tW+raj`66a+{iw*5kx`jd z8JT6FnOY+3e!bDhv}N3n3$+oslIBFE0#(EWp;x*_@DtiHnQyzb+UC zaSLl_fFmJ;xV51(KonqXX99rX=ZA4}b_5vOz__gsY0JbOwjlkTsWm?=0xq$*BU55W zHdv{L8-YgjgdFXA_TQRHS5l{IeoB+@@je%-SnAg1PGst)*D>)naas*_!LSz6bVtc4pS zkneloUvqTh8GFcqjg#i=tD~+(koR%%wZpDs6TC2FT3J+9ba0hpHPb~ftk{|#n{B}{ z&wKv%><5?beTu#9`LT_#*IT&L`YSyId(eOC-!M*apg%M#Z_Cu74-Blbf6>5cx$67fbb60z&jZG*BqJt(6u8Kt7l#rg(H0EB$ak<^_N;{#$5X!3EQ+; z!*=h)KCv)En7(%KjP_?nxMOlv{-Rx-G?;s z;0uUWhf6G?+RO1Mxq2aTYLHb3qnTK%(cgo}Tf-RI@Q!zGF%}d}GE{>9sG}#_2M0rF zmQuO(dv*kIdHN99CfKw-*SisdX#lkl z1;Bcp^}j{+9I`76yM?CGvLwqqp|L*%r|$!`LnQd#I>#8c9q><58WM%;l{RjnQq*P5 z0#(cI(pRC9S zK^Hfs{>7KLPP66?->7C{{#dDAur7y4#R17=Lg}qD!TuymEg{(V+qvnq7#mZ^u?vK< zSq%`=YzV`nT^Ix&M%BeF?b*$>?HjYsP*WC9hQ%0(Y(2{4e+4ZFP-;9Sg9ZabEJAP_ zRwml^6AZH#H_I7;w3l4}CD|jFUkkltU_b@ak->DQ*z0x#CP~adNTK{^Pqd;zm>ZNi zvFe4!2f}O)U}VnSQPpjC{&PEj-gPzi66;}$i30K7X@&%W zp2g9HM)6+A&s)XK?I60fbVl!Dsh-<`>w~X*+#|Ay?hsyfPm%d<)=TW<&&jZl((G%a z6Pni<6noYoJ;IXF4fXGg`UFZ*&=a^WjSosV(xRj>n*>ffkh%*w(8D7af93`D&1v2v zqvv^E@X7LE1;PbFyIaIod|mG%miz-&L*K_j9ee;K`AQ};at9USh12s@gYWql`m`Zm z#R=*F26I&T7n^ZkERE)FP|znWv*KadG%}g7Uy^N_JjFCWCwzMqzMIK$&H`6L=t8?% zde*3oJGdet09Xo@oHwom8njCXIz8#F>ol3N(x}k@TmG-j+;7ZcX%ZN#+DZIiHv3^L z_xeUV%Tr_A=DeSL;|e=$>)v2Nuz8(`W)uk2X@R(-UaT?xCdg?_M*H~)H{;dS_<7=w z^4#?%3Nezzrs(Kf7z?s?p67((8ty(K!qa5%o4{yyf=gbAHpqZ#P!y=RI6P+IFb&X` z^CV7Yd*I@$^{cfjEDw9^6DXHRTVtY{?ns(A)Re|Dzc#^=aMFk{s9K5pGJN1bLW~w| zuDRxcT{WQTp20W+r%8SJ=p7Xb$e~sd>w7BB8vreZ<9mWf{T$@uE-1sFbDppU3H-Go zU4#wLC7im&KO;{N$S14|(-z0$Sp76)Eu{YbRk3!M*qx|S_Q|obIKn8;Uv2KeYu#y!$+#^5x#IGaPd_u#5t6c5sG?7bIk!+qOg_GFGgV9k0 z)SApEskFu=NT7^3Zz!0Ah{(|cCxw-OV!BODXYwP2$e_&hjH^;m^g{h+aBQ{Ow>{03Ie99D(A0uyHlb_Hk+h`}$UN>I(wxEm%uiMSktZ&pV#ZokSL0V)S}wO@IG!_ejKUiOduPP9F?DFTWi zX{d1aO4MW&HpcaqUMZg;pr&i9F#s8U^N@Y5LNjB&g~M2Qqc7uRJ$|F;|zM3V7B<>DXT$xHmuJ0zq1EKvpv1cFnlLiigOx4<`|(vd33(T#jPH zB%C2hCb?vLLXy_%0-t=Q7Mx>>Y5Fkn0aaPWGB{!}B6_2~uK`YR>c@KN^gH^-=$-#z zFvyScF&Ojag|^B}Mm3y(qL?a1)5D}(uCUJ2HB$$8Wr1?Lu>_yJBPs{;BG7K(Qqa-U z7p?j^S0EZnJ4#vlCOi^RP16|2lKgePrU7ZguDxT7Y*>tzAl#^n2}(v`13^J*n3rdiM-vvi@Ys7zImK?%%rBcjDR_t33bk*UQB@7B=Vp zp^7*Rytm6U8w{LSI8KEDkUjaMad`;@wL>f3(x80^UtjIsqn(q~gvgC#H1mFaJ%(j2 zvlQtvBOe;2$-VnXF~@u-Z#5%}##e7B>VkP2LbYb4i^?-|G?jH09WUirDRy5d=R0Lf zkMDhFtcn-V(i86Og&c3V;e7=i#s=q8Ho&1~JC}5glg<}XPGfU-!QyyuUf{t;uT!)`ii7azs8xl5>@`2uZAc z+*>9x2MMIvkae}DG0Im=DkwL0GoyOIeVZ)>)qfSIq@+!l#Q0?_hv5>i&e9o`zXb@q zRF!Z_OS(jZYjjc>ZhaDqtmV=0yVK9ZC$Lq4?$1Q=HAX{u#HxrubJx8>dSx80uphTg z9>RDOK=Z1$Le-UnK!TVZ*Nmo6_5`Wpl9+Ef-G`nz)SQ?rA8X8+)Ij@H8@%3CQ8JRy z&{AGh5C$!sp1sakt*e$zU5wD^(aR1)>m|t~zD=xipR%L->g2ACZfZme>Dc==GQJQ) zOXfO%({MTeMcuz7#dy~19h!+DU14JRM(OQZOsynW#Z;2)X4Q0I*9=Q6a1J}z1-i!0 z`2N)ZwowBEur>J~p2)w_f4mqb7WV($pJ8U@wPc%DQPUGg=A6Hy$lV}Orsov{G2IlM~;ZN@2UN$~le|sxF zWlQgKmoII74d|tBCrjZ`U`4HW`ilFq3>^P{@%=g%$@m>n&aGb2A)|RpK-;ibG|yQ( zPB@>j4R6{gcR`B{FMN4*XZ|c==83-n`8id%Kwe#N$LXw)*%gMp!e&U#=xB5qGYn}n z)w}p_dQrrjd4E?QLn@-!wWP}ze)M`ZO~sefpEiD8Om5rGBd3UF!^gU{E>Y7be%e+# zXPL1PM5E7Y54>O3Unu1+yK!c5X6NnT93L1eb?oKth#%;u2f>w{hICg_(?6O_{YSAKlJHCo#ac-0P{^GT~E;w?T=(~#}IZ#THBQ!qB+ws8qo8&`05%^C@^Z*oWn%=I>*Qi&a{ zzup*=1Svb8`|?I6u+ma;f7`Lgg#`18pdY>pv?&EYjzuOBp zXr*Xe`bz3zB7|1od9GYhmQX1H-CRzpm`V704UGm-R;!|Y4RH?S<}#&1NBduQmHA|O zK}f*;2#WJzzAjwNxttC7*p0;T#RNBl(0t`_ZQwuJ3Q6NgF>#xo+Mr=06plt*QZF6uVXV}n>I31^-I7*W$n*F^oSSy z+U1H|ay$wtn3PA#YV=lpvfOR!Ht)phRYxD&wF?a*a601x^ORtKo4FO~WgwV~`Y^Rz zt&K(ZF6zVln^1*si!-n<5Ab({ZETqo1?Jf^sx-~rw&`{EsQzA=#<5X8EtXZEqinUfpm( z28<0F=8u?i_eII1&!Iw2CeI8>{aU;oHcfk;D@2yvJ072FtXb=rVKLnzLct}9IudVa zg^(S58L%ZEVb7B|Yh=C!bVrsuqkPLD;Nk;*>X%QXtypQJMrqT?pL5^^?hs#@Mp?Rx z=LWH0IFOIcS-E1ig69Y8J!pUP=gcrkT=J62pn2N5lMs*}kEzrn>-()%ci5-VXiHzyhM zfZS$Pu$^`|tMOoH&tl@RtO6nt4fp{eTj1IGJ_*XhcK8$_fP8ZK>HSgmN00W zo}sSm@(B?v{#|M0ymwg#Zf1A7d8Khe?f5M%^C=lkz9Km(a9v(H8f|ETv<1p1@ zzl}5?eX9MPhlW^)KS947qbP_T{oA0vz(jVePoi{|H58nbLr9639eX#(HJUcw9+H+P zCLp2dV#U63v_Ly*tSuf{F};_LshllTU?6)RO}+%k`2Wo=2H|7jMg*nKV?^_lS}y8X2Lg?s^WE{#Va)a&? zpV5%>JH`P~KPKL^Sc_TUWQ7B#nmF3b@8!cAo%~o9i8Hi+cfcds`t09(QSa%=z=>Nn zC-x(3N=-=s85PH;7J<|?{O#|y%bWs+5TK)jDrDryi8~#=1B=!ju^X#z z(Y=8VXdicOnriS;V{@%_^}tEC$YP$bo{Vfzfy({M?(rn!`hxQbEt5&;!h-Vgws*aN zp;t3*lRolxzUQDeSlJZS$|UK_S@m80x2<$;O<&?7`zpQG>TTtA{Xla?_SIUk7y8F=TNQ45eDA{nYJ_#f z0kKa{Czrk$ex_k>jgN2T7GntRneaSjYrs=A!S>wLbGgC(G&0sZNgF0VB4J`2z^(BjA}y0f9bI){zDy3SU^7Ki?8 zSSo?^R5O$(F;kRqT)zPh^92?CW7VC=4QC!lKYLfO zH+Z!mB=;}snsn&~>6CGoOP+m#?SgP)Khx!+L&-P5YG5Cx%Z1E@<`DEMROZ)8Ta+~2 zhjCoWP*-jOD?OuD2R`fm7!pfVsGU{AXRz5R%IB30Tzv0?xm~EN(^9(6Q8}^2Y>Sq5gBc zSLYsi{)G)kKR+)u2fRMfevLN0ZMUJJ%MlBaJhkt23T|eLGHdjNlBO`MF`+Dojgxz| z1!LdHzShJywjir3qoUSLz@i%m_Xhj6C>_ahW%5q5Q@TkmG9lrYFM_Gxq@-&+v-ggY z3AKb5;;8HiuEDy0D3P&9T}V-10zs}0q84h1}MZi4o;OGDw7>jQq?T&NPe1%A<3J9k3o~NjhCv-Vp_R4JxDjlXZPvvegWv zQ3hf@@!-L|awXWjOLY)8ljiiUrkZ!an)1B)ktvk~D(B&ZfAJXWZWgtIAM7r89VROF z2!L1Zaq};carMxa9Hpr+ne00Rg!hjeD!ySHf@oz5x3K*3zuJ9>@^CNL%E%%b-DOZm zJa8ml-}i#FEHecMPA5SafD=X$K?AV{lg4n33_=i5c7v!cB`^{1HykdvK04C))8BYi86~oSj8&x7h3hhRBhc z4jIeCrLP)Wm{MXoP}e)~V+~(4I7ZM8{XkN`M%0r%lCGK8@zetRd;rC%s?3q7$>lTh z1vl*-BB`|US5r?~{Y`ef%@=eIFWj-G?!P6`RkurY6GxStM7t_F!zipsBL|tY#L|e= zr}xF8is?}kMm-;Gmm+Hv3qAWt?@X`q*Ldn|J(4*&Vb5wxPs7{~UD^&g@BE}R|JzxdF*Ygw_6hkew-v6`E2SbXjtE^sUu)aL^avLWd7hZ*D zE>e~m4sroBZu)qCsWY&_Gm~?WmFVITIv%`#C4}C2+{TqQID`i7{Tg~pq9qhJ31hUlFPrU9A6&=VQ zm6-{-Vs!>yE&*^uVGD#F-OmWEF%YAfFM_6Fdta65BxSj1P~W6*P9?*=XJ{xKB(KBcjkF`4b<1S8yyvXBF4Wo+42O1{0T>DI|&L~D>!L){TNv>wNmGaNf z@7rDzMa>A@Xy%SB0IZ)Gc|a?jGdgD-kYI~%G7FET>X~q0V~b)5M&gekUwF)ME=z$4 z5);YgNj{#d&5Y~`4~UGjM1jekjufhX+uYGeo%xxkWRmn!KLCY27#Vd6e-UYT;0YAd ze#1iWu3AYFU+N$w`JPe`*{^Vba!!O&f|s?%keph`9Tj_y7si`Koe5zW`l$*?<~u|t_dNURdqv6P>l z-JfYjRa&Z6ZYd2!KbtJ_u7ut3ty%=vA8@gmGO_=Lp|LRkzZjaTyFGxAK~urV5@75M z!=U0~6~2b?d=?$ z=}pZ%=U>KAEPIfMi#sDY6|Hvvt?5yn^RqPFo0sjT<%}nhb&5Q_j z7!(bi|A{MX8AJhpEQ|rl62f}_v=#re_CIa^Au%^+2^Hsm;*0-*#qDgJ{}ul!GFTW1 znK=H_zw&}H`fHR>EA;Ui@2qA+i zz|EQPKmGnM`3DmVC&&L;_%W3(7mLFI8*=lF#@!OCB<6k5A%>I3(fSvh%O;LCqD|20 zZ0DwO?$lWPew{}i5p>KWrGPTtL)5V=z}qySn0ol=`rd*hG7OFon6RQF{*Ur-X~k`S&T4%9fWx<|4q-w4ZhPbKC}zMbPd{xC z@_omH5)Mu;^j?qVw@z@iJ521s;ccC3*3(eoG$?}CEQ*rfKn8B2KMh)#=^+w`E;T5b zx&1}-EQe5SvNI|P5}2XuTVqVz{c8I|8BsG%F%pRK4$&d)R}hc0y-Dztg*gtP@(pSHslJQXP?$1rLV zVZiO`Dee|=@}MDx%a#K}_DUS5ZB^Y^=lcc==Y>m&f3ZcKX_nql8Q3rwFIps#K|}w5 zF7g9I+7cCPRn&^76q@7Fiwb|#=DIBTHajJeWrC5@0{X%;m%}_O{}7ngh}4i~oe^zoY)W2pkI6`*)Q;`zJux9_+8J7`3i7B8n+VZl*7u6U3VwOMto(#7pY zIlBptj^?ch)3Q-!9V^(C5?KBwHYaxs%ug%%4=k|Y8*I74lg*u!DNP=O|H`7w7WN>ua| zIWk|o=qVJO$oDVt8xmx=xJ;6WMH7ojm1`A-uGOs{UFl06Cqr+Gtu54c*WWLJWo{CY3J`r zoRV1suph`g9XiN(&@Br+Msk8yWQRQS zghLSnqUxm~-M7Q`5Z(}Pn4Yb(=86L&yIcR54&Z0w#VPE<81nRT$1_3>?Ul6Nq&ahvIscRnbfU^v)9 zSfyh{jb&ZHid$r3$;EPP`kUq3U0Bnvqx?4+%vuA`Ij3xq(M|RTlz+4Po+45QCh|$< ztq|{8Wcxx>2J#p+aF*7sOyEM*wA0HWe(AUzrSy0Fn-;$EXOCPAu*xM3=tt}ki)&Cs zel9D0Nc%Z=9zWAxyX*7Vy+fG<1HTda+{q@J9%bRyF0k<8czM5pDfr|>&ONvxVG#@= z9b1u3STXkHcZ(n>_F){f&aOt+YA9>vY%K5h=kR8|2O>5#1|Ou;`mj`29q8~?uasN} zR{E9JaFbRXi13pxg#ZLCK=o2x)nF*HzmBdCl!%y3nH=LssviH~Z>5Yxm)pd)wXp&@ zE_rfh>3wof?V@S7>+qh~=4AafkefNPn!DFk%Lv|;l11O_K*oB!M#rZS;Gk&i=jH$K z%=()0CA0R7t!T60MgLtvBa$jq>71YyyQ2SwhsS;Vc2b^@iIMR?d$*&LGa)B4=l|N%nc4qY+yA=$&pZ2&_J-reD3bSy z#^lDj+MU5QMrxy41Hi7UzENLhZENruR8$z*D8d9ty5-@C3oZdPz?CXOjcm%GSN!E{ z;*r&qFx?=UxV?N<(@V`Qs3Lm4(CXFSLAXaEQ>hz2rf@H>h! zLvPEHKnUmOHsws{sZhgbVMipV_SG zQb-4skF4v6_DxY-H*J`tjZnF55ga(TH=17C5!srM_)VV?A(2C97w7M7cI)~RY1T0w zEiv${rxZrsT}qfCH^Qt5C;_k(_l)pBTvh&_1T+pLXs*mE31?9BBV$o(J;k1(W-75v zpK}maJ}Pm)e1AWY_CAXJ9;Lp4xW8sxSS2OMSbz|cX%sJ>1!=zTB1jgTwUwl+DC+7i zm0)~32}s{AuPDH@u8r0fV$g}=S)uhWe`9hT498i z$29i5K!9$9gr1<0!1t2xy{vnn=Z7-LO>QbIgNhA}&DauRQCDR_p(o{RW$vI_c(Ehy zWf64|wtNg_fLQ9CGAi%;g|xu`-n|pIoBqUo|C`RCHnlyMe0az-fH%D`@SKe8cOvw8 zjTrWOB;cJxD$-}4TbKNmO{-NhZXA6cqPlh_VL$WJjbaI-r};bGx%}LDDMZr8fRh$< z8xh40rItFqw%OFG{&?H>n%YeyZgV-cr)VRZC`a)@2g55p#0=VXq<2R`>!F8cLv$>a z^iF=M~|D-f^ zuh-ezXr1cYDH>(%_nbOfVWgL4Ry#D(p*0h=01Pke5W8yjQ*G(Zy?wgbePcVzF4)#= z0L{dA_A~7+Gu5KQYax=@o74b2vQ#~160adxjSa*1Zbpi&YR zIxD6uYpC5yo91bIC($M7HTx6nMe?S)PW#GEwfhJSgeu$>as`neGs{EZU|X5$=duFZ zdS}|UpDd{Hn(UiGTKLR}?%&9neGoM|%3tGE^qm(2Q_{EBzv=KkYcK#?Bq? z>^&DXsDZW~`oD{xOG5t;&!mj;tzYX}g=|@O9l_mRuYJ2C&qM5;@D&^CLV9(=I`Som{2@LaIhx-Z|_uu;_l zReZ+36S}AM4G5VCr`}bb`^*O{W=0_fK(E}Wrn;LZhkNzF*2bRJP-z=Ej!vEaJYH&% z5b{`hC1soV`u=2m6X?m8Ccaywz(wpaGE`9YP?n~yn04Wr#rj*Lv~ig&*KNnBkyhOT zmD2qS*dXNmVFRtBF;M3%1L`1Y!It}S)V>9$BrD>c`B-pR3R?d1V~((@)lq~;MLyh5W<@glJe!x*e1XSz;O&WyLBC`r$Y`L&}lSvUy*UF&!v#X${NC$ zU-j@{LZdciX3dID1TP?jNI(wZDf>0#K(6Z|pmRdy?($#SFaI7HFjNZXY;WrjU?nFu z(Umo?V%>au6*MOWS&65UJ-{i++HDe$J57q&nByfl2B5k4YJPuow2g!x(V~yf?n6t4 zGxKBOL)%$E;&$A@+l$eI;gO!LIW|mbxht(GdyUOheoS%WG2-8l^YbF6<+U#{`Ooz` z*&qxSjQgtL(aJPW68yYUJS4bh5JZyXvK zFe*m+_Y2NI=8R5yAreZg2jhB}`uoMK9|}`ur&Xlm?oMy39ehgx=N4G=`V2KJ>|Z!H z1L;&#H0xASG`Ab`Nl}E#U6md;=jE&fXis}~7m{~*A4*T1c`X{=vCA>#b7f2NBt@)m zgqGVUiFu#v{(^~2xx4lk0*@V|MWMtaElqsv&il5bX+L0;?KhtN)n(}=z>69uQwe$q zBlVk7RQ@+Ip?$khabfY``4Rg*7Xw30Wx&hB*!-Struix7R~+kVu}DH;gYfE?v!+Pb zT1rz31tB-~O5`Wfsc}qOPV{w#Y?hV``E?CLsk7}4DIAB4x3i_d#Z}ku&6fwC9Ir{< zw^jH1`iDbfHI6sIzCM?pvem+|-Or}i1Lz9fzGM&B=nCQyFq2q&Po|*6*awR~d^`a) zkfY=jeNn3>FXBlA;ZLBB)`LF&gaztc*$CjtYy_*->#eg1fma&NJ6eKhsEIRx7R%=p z<5&2Xx+Vnl4Kb{twux`VOvhqpG893GJ7 z`FK<&fS*(td7KE_;Y35IiIN(}S_md)6S9AVjoJ+}RJkF-BkX|VSfMS*;eqkFYqRx=f{6TTbcfIa`OMpHDP1>|B-8=<@7JtM~J-2>pt+X{2fTD#U4@)voZ`%H!QiQ69f9n(?7OAQ8PsJq$+^RXqsrbtZ zs3SH(txqF!=SrpQneVR17O6kGExF1+}?2FCR$Fd`fKH`~W?0e)VKu zgj1LMx1}SB9mEOw7g4Lu0lIkhEnqelb5F+4fD$Y-c8Zma-wx|wre3cu#p9wpl?XVE z5H;{>V%FFGDXW=q$gb}OAAIpO3N3hDq-)9$oV^{0aAnE}tmlxf>v7a~NNQNl_gRuv zbhz^C{S*n<5QV0LMd{AXHO$cB{;5$Y)3_Q|oUR!9I~hI)m(3Iz{8^DRhSxR%nu@xr zP>uLcj#~vtNeS|ascsK-yLjJcadJ~@gR(j_@ovH4MWs|uzSdX6@K>OG3N+V~{v2zz z=~@djeVcbtoh^Y2*M?scW5401_2D6E)~A9MNe8NdJ8Z9fpA7Dl?}-&oF)q7!nD;`U zzgyyrUPhKL_gD%089kS5qs0&C#}7-aHe%F(^qa{-tQ@6!vdEPYmYr8EM;8BDjnyo# zbd;|2CSMDcMDI{IB29lLh3^YOf^^FBsZ6@^TYSJXX!r3{gpvm7%)jiabmAM=?@-7tK8W7@?d{p*Bufz+vEZ}CaZa!V8We;3;yUUxT1J231 zAH^!eO(FPGCE)gv_m39RZV9?~HVnU_`8VhF4$ax?Hd2OnTuODUHk~{IhAaoOd1dIY z(AAz*$RE^{#s+UE+(5F-HuqCk^I_VW8Pejxssr+f4gVlE-Wq)upB&)EPHzl!Zv`HQ zpFY_@GDnsHImsRlNP5AyY!&^IZuRum+!&BMdG2H1V{3{>2g=Op zk{hU9;reUZ&rT;<79`ydejOI0zoumhV_vM|(N6ZT>PG?B*MC=p_r={9^Sb@qB-Cgn z4a>%ktHzFI@K3vxYPQQ*>Tgc?1nOYN^UmiC3a6;J`LyUUMBLgA>6*WWgmii*XEr9Y z?0IE-1uWLf0kwF6RYu~<8DBEOROC?>rHcunIs02neOovps`eLT?uE*Z2v}b!_nUZU zD?YA;%FNzwOef#eflK-y85ETwF}GC0hHJ>(6KuL4bxBjz1!xF8?Nk~znAl&CvVn7@)eF*Mz*0(RT)At1>Y&gR7 zZrpwCco2@h#nv92cN0=5Q}D~Td)yd_v?ieNKpO{iA*zncmPxG=tur{XH6FQFCb;XH z8#($8!=9TVW@A$R@cG1pI?Bw*-7kH1lXklRN0&($aYKt=wLM4GAQ}9z;YWBBwWvJs zF<8{;6qLRWk9!ExMfTu5*pR!q1d*}N!zxh%}LuVPQzTA4ij zW*63mNmnzzwxc1pSzHm6edHdIzP1c-V?z19*E7M7Sd>dO!X}Fq?E`{Eb7s~d`X?Gv zI6fsPYCngVTFyCP1D-P-7J3yj-hZcAT^EF-SKM8HveL}r28C*Nl86+%m@}pu&b!7+ z1+{-k-_0rE@+JPch#Kf%(+T67v4AJ`d`K|;-CXo}1{eRifHOHTi{zUURx;+Gld*l# z+E=h^u@FFPA(;anSTp1loHz+bdkpUpIMLk=PWMI%Zo5^em@`9y$Nvsz|Gj*6FdYzF z^AhD)LWYi)vKv$${HWa7Y-=~wyfC;BdU{!_K^jIVOuA!i)Qhv~$J@lcwzUtH-H2L9 zOiUMublJO2maG{hDy%b9kt*#-99>jR)MLXVOyvud=LrQlotX$~Ix;Boy46PYVH3XE z7$X?1$uP+=IKhjbPHhI*H;(1_O9}0caUOXgMrs5;NTmr4CCm@ud=HFCShdfSUo~F0 z-bWgB!KVy9UydEnA;hy19US4nK=@*jfwXQ~8L5a0I0jD{8*UV_P3V;|Iq z59e<^17^<;np7vrDgSghmLorj-#|`;Ltw8y|qWF;8x1_NGok`0s$9vPHc_AeBAEddm6 zW%nqR1%<9d28wjKcS+l)g)paDeIuU~;>X>N6wo}Z+9+S+M{8CMQRCue3}I>(oz9E; z(u<@GCz;iZ4O6C8zO-A3)0p1EWyLb+cw!L#P%_XiQcjL04PoZ~aFtmmvE;vJ%(~Bw zWZk)_;c-|*TwSWc?<_ZFYwTr^KXIHDC@p;Bz_II*Z5MYml*D9+EX;9930I&Ez9Y#UMWfix2OdJlMJH#`u7esQZmpm!!V@)rGR=%Uqiw-G( zdx~*)ORMUQL4l~i*R=7uo3GWh`KEgnjE^O3aTxDXlnG*f^| zJb3S^TzoU#NktOcrV0!8D^rPWn6V2Arxyc7gJS%+k@NJ&Dl>rEiA`s?5F+dT-zU8! zd>L@v@RzLg*h~U8Ey1ntVj#@|x39IK-n^sCRjOz!oB$;ZycEq|igMmVf&+48f^G{R zQw_Ah@CQ{A9X(tqGf~SZXD)DhDw;0Du2_&pb;>r@C`oJW^DLOuZV?3%NLx`CJe%sB zToj^CaQ}rlVUnDz3is+Er!<@gvoqWF!j=Ss9|$Zew}vji$;ER!J1?*J)^0n__7$=B zA-GmlfgB0jz!8^lk#D@qd%6S5Q1N?$b@_9AEFDGb8;Ms95vFWL!4r$Mt6ZGciJF|1 zWKr2alhClX$?6Hv_I5td}|IOo-(Xy1LX zuKE@P4+1+JM><{#+f;Kr>hK2E!k!4E%9^~*L~@dI|~({52i)^Y{C|IQ;@pRRF<>(x(1E^(3f^>LcvFbo(R&Gge2t(Q-#& zxVtMykadREV%}e8p_pp}^LO*9kkD`R#<)|^{H5!Zmjg$iI+6l7UBZw=deZEeK*?4% z$e;B5f*IIY+|snH8w9v-h61R>;`S;bTp(9Xdmm~^)4tIP>px}9eme9Rd(V?f%E064 z4&MLr8>75MfN)&kX|Enkku*pu0}|B=ReT?V5~t#(HXEzdx@iS?+n|$=n_+pRv1S;U zSwFzdQilH6&Nraj_h*4dV(hM&Y0UVzhhRd#dJ<()qahB9Mq8-6*RKhD+?`w+{Yq5q z^#>V`+%T)f|7q=SQwK-Z07&{7o%w20^J*$NwSTjlQnu}daqNiE z7Rdv$6N6Q6BuB}Am2ZO|W4;bwd|O=#8pT(C(>M|%mY4aCgwvm~EIP-VL3^dBTSkd( zlr<))Js9Ftz71Es>eAvN&}0A0JVAGDYg#3)cJv+XsE`PpGA^|vOkk6V^hW9d-mN+T zNBgx#aYSFDyE>S}Y_cLRp3+mNvgXu01Aj$VnM*%YvC*%KZK%-epD|WLD$tU;sT&!j96dFQ!0*1RLMa~d} z7MMTe8p#-_M0NUJjke{*?d4^y0$Swa-0>=kaUk#}suu0?TYbcFC+hcW%tOFg!)7_L zS^B10Y2}MXmP1Z)1f{yM_9M>MpvF%2;5Eb6lE5wlEgs0iK>yR!)RM+Z*Jg6nq}boi z_6>`A756^Q*)3exAL*K_uf>&*Kt*n(+84;=h(nxD+5`?$hKNJxpYngC_+x$H`Ki4& zv}0(AsfvG*m2)6gzQeG}bK{BCj5j|2>*Q~sP&{s_Wl{Qd3{=JN-`r0swH5p;^Uh^f zP|!WMoGv!BoHxP2>XZGm(E5vuE1{7NyvsI7_nhaS_BWa|7}%k4T8ghbRjP)=nj1-s zh1tPS?-a6<*5ekT7)~}B6#@&8mbRUI{><&DvWlII8J*vIS@NKM^-{J|1Yk)EOvUGvI$;`#uu@-8{6I}X-j zohQaPdCbDAN3Do4+eDudZ|@6{MFY|F9hPM4JZ1`5i-h(qSGlLG<}w6A)a&Ds(D|Us zL>$7OIyd)8$rfYGZ~b_R%*A6ktX_;+>z*;oRceEw#YQxP8Pu2&N9_>DF;?h2>df@+ zc{c@rti^kfB^-7Oj2oz2Az#q7QOb=$E{6IGcQU`W1D-FhAqIA_FGa>1=6T*{aA`eI zlR*^SP?>+SooB)HhWN^1jp@BCW z|22_vtYxncMj-Xo9GD=9`=@VII5mL8iOBcJ@hQ)7ND3aASfhkjZsrvgPgntawwlQK zor+B<=3oY=%R9V(D7e3P-6D=vXYIXDLpKTcz#4Hu#?MVn`4mTyZt&qrpIC#2@uJ%V z`YELthHSai#*GI@S^(a(1KzhJNGz-N8o1sJ=xp|uG}=t*`4QUP9jCn;Syy}t9+NhR z)6|~g^_z6`TObowhwRs#gtE4IzC)m)Xjo6~K^tUVh(QO*hY{%oD>c4RVx#kPw-Hl@ zE;c+d=IkR8mbJ4nzfemhuLUUvgrN(z&&K^|8*Jms9MTj!tz$cfKLU(EhZ#&z2#6e7 z6&gWTudp+{$lc{sr(I7e@$T7JGHNkQsy#C3+3!HE57mzvUUYEJJt<(Q zUyy!1Bz{YK&~YD!Zggv4ddCPN`36QC1KQ?QyA>h4&>+y+im!oz9rct*m}gbpOzl;d$kfV>bCyd&I;`dR7iDLnnNIygykX#LR?NffAFY$>$cd~ezLJgg}|6RH&=_) zk7_Bq`cJSwP{%P&YyPnH`6Qo1$2MNls@RlI(WZ<=WCQ68%$s&*y7I)WVaxM4Fo9wj zKx@XAu>70^0)O`VF_ejZ)`ptzd^PS%rmmC7q=C)YS5Gk91KSEbeycx>KCz_Zi4CFL ze}Wh5RE!2k7~gUJtGKo=a$st&6K%c^b(z6^_dJDn-}wSWD}oFw51QKIKC(_IGr(qh zjRT6wu7f?W+B|G2TbErIM=00|MvsC!t5)x z-Ug44SkR&w{8vlPoF<x zOK^WkFH*C>+`@YG1?$CrZ0f$QXrm*^*rRr`~;tS?)NyG*c=oQ zA6txJxfYnp)eY;jdw@6t5%vlXa^BWemKjTe(ZH>paUa>gz8 zj%^P0W>6aA5NsNZz=={Z%i^!!GC%7UqmhacLX1PA6F2*i4n0&_#c6JQbU0;N!??RE zuhcHLwBbV_TJPBn&Ve9I2?(v-o%@3IvM>#9dFNe7ID&w$*;I=dHJJxH27=371N zel-R%O1q?dbXOyOZw~nM7KME!sNO(|7jL(d;e8gxRts{PMh-k)ral| zhGM)u22J^RSc?%@l3lzkmNj8Gt`0b?Tq>|y^Kd2*I$04+kI8(W#@rfy(QF6it8{zU zr|T4hYe#uPu1e#l#%M86mZqoE0P_!Lzk%N;q=IM&f1+jHIa$)M&gQP6W6fId3v{xi z^4(V$F|q7A6b)M$%C+3)GaQf|9LF?F$BgX68T0TV5us5MXglqfpTd7a=n=D2ZC@8D zO_a7^7vTS}Kbdfveq`NEp+DP|L>8OT`m3h8BL5 z9KfuidMtf6W7@LtpmE}5>Gm;~SkZBJ9}q3gf&&S}WFy%X1Y$Uj3y1W^mx^RGCu=mr z9XmfIMQGA!EYlnD&=-Ft!$6t+ArumZBkPyb;4KL|(|a1tcZ?nS_^(dq7Pe`Bl}i0c0rMGf=+S=9WG(T|4zAS3Dj zhBuke+qs%Jx>}gH{deF;7S{g?KeDnjZ~|C}SeUpNSOIMRgYY8@>wi#<|AZe|*qHy5 zcjO{sVf$YsB=g_Jf0B^QfWM3X+{3~|#KQg$lI9lkg`NFBe}L`p;-Ak+^lt)_ z9GtBG-&oC*rmWp22U7QS?QT6^*wIbq3fkX4)Y))rQz@7Yk})h>>et^4r6dWdrlu54 zFMmL12|;LK?mfjBxaCXw*&v@!zZ6ub88^HJ@G?A z*zab=W8bWcL?6F%%JLk7O~yG;gX97Hp>=8;Pw><5u&0^Eiq_pC0q$4 za$W9NJbG#jui`|vqt;mYH5^uFI{0k%g9{G;*dzwX=opby-rRbW)pW1^JWL(Oyx!%# zIzDdgj*PNQ^pt*E0|C*%SkZ6^L(${20=dcpYbKGiD1;`qVQNuPjOsS8uCIF~*gfyu z-3w%if-B?9TVs3#%VkKlq6?n5M0^rH+t2>6w;@j<09cdi^p6hBp;1jt&k@ zuIr4UxNv#VoA8}g2|}La{;WmFfpxc_mSeRzdj`;NNvU^s3O}(z`N?kS*PjkY4lU#A z^T>;#Q&4Kce$%JR_q$~suRXms><5cs#`F14Rbm)rF}NVL(cg#P&Sid zwptdbrx@k!VwMfLpW1p>g`93A%`RW<%Y}(@+<&TaU%06qlf^s#VsUxg8dbU1-02S4 z{O{pUPSzK;l%$avWSU9vC_?4_Fb#4r;GF?&l(#|C zFqri95%H(kfZrIR*tU-6?J{oL|kvsh3*ve_!%pW6^Ce!MqR8yNy&EU_XA!&PKn>Z?bbd1TOpxqjp{&U;#Su3sTP=Uo(^r(H%7m>9&7_NqIiE0l9p>7pU9v1W@T-+G zIhAXbZ{O;RLDy9Vo}_zg##XZRj}}QZ1-4LhQL^1nXi;e*+&|3`I0U&l~EWghLPL5P=x+xwxFZ zIlWOolOQ~Ccce<6pV#%uELt5HU$h6XW{q%?c1Y~SGEgmvU^gO( zAsHPSc6WMs2}7HOkPO`->%IE;?nM&1dEfdt-P3-+*QS8ZnDjktbY?Q@DmF3=N>E_B zZ3G*_=99%M(p_;xu8d9Gea&LDO6Nob{qpEUvHSMv<9lsk)ciU7PQS6tI!>$o^3DM|{**#t(o+%F zsDlL{b#d4^_Nni0KAuIT^-0;}OUhyV_`biQtV380Nuv{vc5)x{Xt2xtyhM3HyQCtd zek{ItPA-kpZEzn18JdV=WgVQN;6tIeq8VINs9n_wqsXw&*3kz zg}D7dZ_=rMIxHLlq3;|Zh~8|n=dZ6U^J5HD?xIh)ADN}Lq(B%b}$vn^k2(llQ#P3qY8i*xsDHr3?>mPjuAi^-eZ#@ zOEn|IBuiW)$qN82?^et9j((5|ec%W;S4S3s4dnR>8xzM?km-K~-upp9LDOjr*1}WJ zOj!Vo9O_*}pk@3!4E5sL1`!gFsvEeLJTeWT$?<>3-6P8vgzi|Fro5xNV8a<~Zw zYywJ>r*o-to*Sai6Sem(n5vYZ$>s;i7s4jxwFzx4wyy7iv^7s^T2+WPYG0T0{OXGu zIToM{KpH`gEJ^fza6IQ$>nr%~KnrN3s`V|kQdFWf7>$P`mjcc-2a541qT+nZx7HO{ z*?aAZNK8Q`~WMOkkFL#necB1JL`BmZ}Mx3y5}*p%-QmLP|Ao$t<~uF>c>E zsj#}V)j(26A-p;3E7ry{awU&7e_mcBdOlX?Fv9Es`zd``@lfmvRGhJZ1PdgWA)pe7 z3%BC{pep&Pnoc5-L>Dx6<8ooc8A$k_7$GNV_(?&EZyti6e2_T5%d)A!@UU}tMo6vm z8U4W@Jk@Vr*a#(Z74OPL63j6`GN>ieZvs)twa+X=($ z^a05H!8_doB^nMm7X$LM2;XxII7Sk4f`4JWwpO#t_2L}uR|$m)#ng!<#d=;QLq7|U z$JIsbv`;X|&ETXynoz*7g756AkBg>ABu>@gj}d{HvE=@Pv-%!7Rwm|urAb!yheg?i z%AL`U9cwxOQ7q5^{sR!rgT|XdYXEs5sq(NI>p$#jk7mIH^kDge;_jd=j1^L=7+c&o zULwDoVt+MxNA&#{=$;SoY@u~+7cgk<{`oipudzW+nhtS~ z6^k>g0gK?D8=tHd0aq)~$s7Q7_ncce6#=!x1X}Q$G}1U%jt@+wa9VR4V*&d9;qryS zMZnbU+8uIiO;gmeU63?LRuweWf0q@-p#(bqGu#gqPXjH7#l2|y{FUj+7vEv2*k7v| zX4RUH+6wg*d~Z!%c-4(LFImWNg5;jg#WKfb8pP7jZ%h#A)cTPNC7Z^=o*b>9Zy(u1 z5VI_aTWPsmF8?KvFV?vRZcYMwAIPRHH@V7w6G7KFBrPQLwG1OAqGB_-IrnnIL6Gml zq0oYLm~Swt2*_0$uW18Q*zQE5+CE5!oq<}N0RC%c3u9H^LQkaA)JWUm`}z`%Ow#_* zuYv|rB~y4u@G}e|3CKB~nM0PEv*dwKO>W705YF>cB zopGcEARNksQ1tW4IJsDO(~?Jp9YGuCe0xIbh5jTkzUTFx%%C~Gp| zk!BxeniD_cbdEo#=sHEb@NmC1f6`Ey{8UbL=xT-ONnMuhjP#{F#Gtp8>daCbC{^@} z_2Ken9K0g^SoYWcsCVw#M|B|dUJn0NKNm7OCPIMIU0BFe(YMo9NvioSAOEy9h3Lll z4YI#=>-sOMk-u$?|Cx(#O9kaImucI|7G> z?B6mFt?OOwW|d&@E;Dw8ejTXW=3FaIDZo@=5IjNp+cz|6R9v%R`H3WRsD}R4;$@Ur z{GLiHd`2kT4f1hP;XntPzG-1z6GeASe`sW3uM+4uo2oA`fg>LCI~;FXt%zeiv5&bd zEmrI!y+1(_iUE|e+C<_7bxaD?Cu%>){DB2Kv%p^0^2i58Z*Z?RQnEMyUUDoAC1ZE+ zfGphekakYegf8A*(6dqqBslA#`vs^8C0F2%aIg4ocol^U8YyO26t8=3+>nUkq`5@< zd%or;oI48QzCzf5(QB_Qi6cwId^#^?>1!kBJb6ce7ewK&DkNP?4-ZOeZuA|5k*Ve$ zqjJU?=kA-36%Q!|9PxGNLgR)cZ{)6JLGGs8QAG5(*e9AX9!!^XD5+@(g;;M<_pTffKhn@J?vDT2n79w;J)Zch-+n?R}(t)HLR z7(e>n@)?AyHk#CPUO*7b(|uf7f2_B9_*#=(7TT|kd5>X zfmEa&P~QGWSLg>Qfc~x-iv?jgDtKrsQQTOepoAFiWerl zEz3V2K0$j>kZATQeGaB#nDL&OYwga%OI``q6 z+MP6{bkSb%<8WdqqZbubhPJBdd}?cH7RqZ)aUTBDQsmC}8+@WoRuSUpydxgGtp)-< z_?P?E>>hez)Fs~QQpp^0VoJxxWtQuPuv%bCf%L?G@81wQng}tbBe&C-Ts9}UydnJ- zoxpDTCCkNIX`#ixUB{lg<+Z}%Sm1DoeM$)}ExhZ09nFLD(8Yn*S1tgopEk$g-$e># zXfaFfJY4}?boC0uSr!QcRrqwY!9q!*#}3crxRdEbw?UC+lqX*1BG(2;M$vFmRf5Z~ zltu;)y@603VQ?liS&o5^1p;zijD0}8x3?y5k&-y`?;zStD^&L0n>Qygc&vZl{OSi3 zxMO=p3oQ$5Npi1+3OVF!v*GxhrahNNr1g?X3e1V-B`Cz7+f~h`!r6J7di=_JXIT&5 z_zO+{?FAk1EuyYskx*%JPbH6LF*}KCE4z4Au~_`*A)wmAXq>>3Bd@ZfF7Lp>6SzMm z6rLIw{<~a~t>w&%Kc_%6nYNr%KDqKK`2%J~)pSu&Hwt1MB4(^2SCD&#;Q}q<|y*0*pbRA!tS2>#N&q(#1_2YZk z^&LCon}^cl_@w6>xZK$m{l6Z1f0G0L%c1wLdpZFu|GTG?_1_=Uu%xMAhs%lLyHdNW zg}VEjoQo`!7Ysb3tp_$^H(>qr=iZOgPaOPXj}kn8#ox(IS_w2Ele*;;O#96652%W1xu=Efg07ngjj5kbcm^cR=p@>vdMm51ZO=U;zn$^FK59_74t+h8k z4q4TwF~vj;;-2S_uOE5D+#F%|`bUrXoRrDz7>hX4<7Phul`T9Jb_)XFLS7Ivq&yn*<>%9@SjGAg!Ja zGO@0oA2RVqCRd~Wv|lii?gbxh@@}h2(J7Zs-; zU!U)^QAFIJtA1>QBJU9uMPNu8_Bzol8QluJsSsslk^wxV_yoji5V2N2q|5Q}#x9UX*PtM? z#w>Rl`9y@a)T!|)2thLSxc2Vd)WtlqKb&iB5h#v2A-Hi+bbKss~lw|my(E9@sSEZ^^c!R zh7Akfx+?Apy2{!6TR?<+LKew?#NarH8)ynY|3qXHbPo#96GoN|FJ{W){1&%U37n31d=<$uwU>Dl_tFxCbA$Z2u48`#(D7Osh5>^tOr;Gc-JK zITVKsM9YJ&H}nsQN-1-p0>nFu+=w5eZ%8oBGEeOi7ugIiSltq3wE3=O$2^}3gwbgx ztbw4#w;a#rQCYNb=1C}GDITlJ?~FQ%pnShT{B)LI-@9?QYAW(O?MfLRQ3|5$Z=5aQ zU5h$ttD#7S4z$&|LWVa)II9Ft3)>%vJ{UOqDZB`<$% zMJ<9MAI2`#B`lC0YC<*8h*zk7Ktyx`CX2^G`r7>Q;=tsi6vF^<5HGtWX%}1aTTmPo zCJUVA&?R!qMPIp}NMjZRoj82d-+;CvQLq*y192;o4=1K-Ddrv?2WI^c)c3i**EYv#iE^70D(rpnVs8Kf(0@4}F91_4E9Xe3K@p`s@ z@Z+BH+^_K!4{qG!_uRdJz9AS^PGEkCZ_7r17gkCjw~`y+<)CBzAO@x(cMC-B_wb!F z695<&FI0{&^AF}@r&(?I2WhU&G0%9T+~_HnMd0cIDT$${H66y1!zibImC+^mropT} zzu934IF38=@7oytC+}0IFm?c^1bT);hhr2m3kFI+58?!8^(wPl->Z{9wHaRboggzZ zFBN5Pp9q&_d*?>TA1(At0PMu)5nhbA2Gz57EQEMXRLV0ZN{RL{g>oT4TAg-D-I^|y zZY#W$zpbr?c8k8Yq^zq+OUwz3vd-bpv4X8vy+(mnXTEl^FqNxVMS8Wf;>Tgub?LyX z%*io<*2buoxxy%uVbqkIxH8)_s?oVuJN+Z{NVd%&6AiH@xixIATZflUhi$hDGHtH( zI;=q4SZUx>$TOh7t5I4B4hlBi2yh%En9=L+F=a?Zs5co{V;jC)V>{+Mw`4<0koa8F zsZyPz{rFb8)M+*v09fxRO{=bv3Icrui#-trY$Q#OOQ=*+;-iXtI zdw@e=g{<^NjXHbWRU#)a`Q=sN+e=fLnpmNntGQgJP{*&cRPoY3Kb#zjvCUjYxsaM_ zQcdC(v2rxOyAw!I#F1-`qZ8>@XgOaEsa8OZyK%xeF1Z9qm#tRu#d8_y?mrb8b4w=w zyoLbFX$vaCrq4U<%&*f46l%?Pzdw@q))hke4Ij4#{)I2_ffH8;G3djE#33z!LJwT; z2IBC=frPn*6L*7-qXDshiGs8a6tv>^!cO%5n1FQ^f-;GdA zMeA(1-ymn)>Z~@ z?w1-vriPSI&XSM@$%xOh9Hki|W0a3ilq$o-`U$6w9a=`Dc!V0A`)P-?r!Oc=3B88! z9h^o5yAs`U@)xYae|Seni6|myKW5xceXP!E_Fp|QuVA zaZqcbAH8FWu*Gfxxq>6M<3P9Ln7g(d{|JQM4&Cy|a>pipbBuaxv=)r*`o+Yj*m~n3 z{c{`Vs>Hfe1(`v`?R@7CK8&HKeErDz5CLJ;Dydxyx>qIH_w$f$NiE}3!j2Wr%-4Bj zHyUBaaH@aM->(!siIA}A{02ME!@E>h51YwyEWEE*d4k#n+hMt#}ajFvwncj>a`jD*LseX>Ho~= z_`k<$u`vH-KK|Vd4h?C$O#n*IyV`>Syhzkb3d)563ofE5lNXfXg-K)IIQ{x^f!3MC z8DLGXR}`aMt#KqL3KA3)gHUuiQ4f9X+O|elZ^2NQRnZuHYje|vZR50xDBVxD`BlwP zXD64tQ8u^$dgSN#tgS{4?^DY}!k&S2;<{VRR(bu_F~K{#GtGi^x?G57-9*nG#d8T? zT7IS5k?*%n=6#U$0$!OdfsEOertuic{ZI{aww_A5uUSTg^~I^5QLE0{h4nY^`(;4HI+n@eJgjy`e-K#+U9uUS3S1l zeDnTY%$yhrquTsCUmPOk627)^;;@_C)*VomofW^(FD{Qx`vtrbeb)leOw>|az4(EL zodw|!vdiW2QdaUrdFtp$+ecGf&2iPI`f)LTr^fDCX$gDT$%|}wRSmd@)(a&5jnlW{ z)dwtO8m%Sk>s`c%1+iX3%Z(iLaO5QO5Z0({7x20=ZX#J1vzW#<>V=1-<%)(&(c26F z5L@bHBWa&t8wP4h>rbd@o$PQxN#1{8QHg@CZr5B4yx{xpBxBvF{{Df_eQ@HY>qwnV z#*lO2Zsy9G9UyBLii=fG}yE$F9k!L4$rLK2lJb1 z1Uw7s2Hu3lYRBMkE&rEabS$C`=Y^cT zpWoxsdnPUJ)LMvbnSPLo^FT3$2Qg>oz|sk=6qQRD7@87l=?6Fe&D%-f>PL6?8_+KU z8hEdgM%kTLJS89^rXwY|6YwnGdKu;{vv7CN5dnKb&b%A6Jsa*fNEJxO^Pk;!rTEXt z#+-G?#-Y}yhHk(-Jy5 z!>7K7{9v{L;SI=&V0Qh!a=aJ0QxH}HolQ?v5k4%|7cl0EDtVLZ2v4*n0@`Qv{s`|T z*e7oY7=a%{s3uu`l5kX?wu86fWR&U3s8Qm61VyMp(g>jn$kknG3~-_p31i=vIFkk# z{$j@Z?-geblLpN;GLO)zqD)Q8+ws}ng{+VgRoy$a{erB9{+E}`H2JO--zW2YQKETM zxT0>tHTWN!7w4B>Hx$>UsG=8C72E1GdXUgJ;k>XGQwn2W!oTFwD?=~ zL>b4C^cphmo#dHz9)yf+L3r%m==;4wJlEm}3_-H6QeZ)r<6!X`J!N8Q9UF#=k`UVU%}j!)XO92AEg``|+NWV8iawbD8c>`e0fJqF)OQ$XW$Nf40)YH1$1~T5hAwoX zyTr$-KU{HdVg>G~m`iA7zPxLXJqXAtHl^h)F%<_$b7Nc<>I)~6DW4@P^`4CS_YM8V z{~~cN;Y~97aAWb#`3~=OqXyQZUjQ@aS3^6@*9A)Sp?9lkn2ij8p|nZnD_k~ON{CGd z$*3X9RLaiiuqog%+c zhB?%jL}V=IK8(p(wc$=wmNjMD(t?mi;}8#(yHYwrP&HMTb3EM|>vApKtise6_6ox} zq{A1qf{$y0Rs*S+1-|CdOu4+YEpr2M#+uF#42pzUILC+O!k(l)d~UE)9OBzQ4$Z9V zVbpI#+@>C|cPqp&6A6_w5$W!G2`W4Z0%|M&8$4v$Gyj~MQ9djeduao}`JT4h?h|FN zBw|7{Y=h5EYn%2XZJN=zH|x~f*gJ};Wq7uJi(jy;7UPjRy1MD^hdV8q%OT z=}Y%Ow5mj+M3v*c5cz5U$FGXto~ZPX!SqxQ+Kx1(p2A^xq8Wts&nE6$M?yv+NcmYv zH0daUk*pJ(`_ASI*bRLj&V)|-M9yHuL9U#P@9@|^+ZswLASG0vbmpcXOF@B#-4n;j z^RRz}i0cM`)DK{LOWnwG_fW3M`2en_`g^I`%{s<^PUW63*4W#1H?Hu!tVMx+cF#!Tc_=|@3zhj>5t`G3&fLrYB$ z2UVK6gF$6=6=2#5BsoD%E6gg%Fod;b<*Wp~XrAJ_Ri=iPi{TRzyixs%N8a!b4+y9f z^$oR;rh#+*m?;Cz^*SlSnJ&{T?*EA$YiWX9@}kolko6JF6Ct7u0yTCtL!9Qhd4d8u zEXl!AM#7OO^2ght@uHZ)TQC<(3nn?rw0;%vD@k43;WNkXLVQm=bVduWio|^eMv-aI z>$>%OFk4kXENAbNbF$$!UJVP*bjxaI%DSK;~_yv@w<7d8bjaB*_{5Be&s z%>T)X{`FN@ng09IEnkm?VJrlbzM z@h@=Ozx93-7x+_+#r`wF8BX@ER|L2 zg*hfQBj$}#y5k1#^9ry)j1qnu`?!}OrmAM@T71cN=a0zU?ce#G&?NOo!BLF$GWiyu zHKbT5EXpC)Bs;@TKNDJTLw7aUja2%6d(BM=sd@;iWxys{Jazg9iH?8`*zJyc*s2vAgufUk7I#Xcj__WS50N3R#6# zp8_F=Jt$0TRV&nwHRGH0YTkr;-_9#2oxorYKakM{N7GecFCv{%tXOFdMo|{zF3sd> zRL={9t~j)U73zx>BeDlWrfY}giZPPk?0_74-NbaoxFnhrVXlHVkhTgZW#@PSF1v>0 zRb8krRs)Z9inT2o5!P4p@LNg#2fI>ERif=(%_bj6Q}y(0J)85JOm(DsfDf)ivw9SA z^drDo!*XF#O#IMAz%IbbM^dvi zm#|_=-3VrDD|Jrh3ocn0Q|$nUIIZB88G&=Y)wW|YN|Y*juEKu?0!E!Vn9nR6ISjh{ zsD#1}89|G7prsXpht4C0fqroE7i;G>wjKpvpNia_DsV61s8S9zBlUhK`R5t(X|eb!Q}OAwEik`bm9N?9pR_ zTjMC?<7p&gY*|tI@M3Cz^4Yinbfi6H8qG%GoTQ!D4b%-Y1c4pD%@uILyb;*hi;$D( zU&$0DQABNJw0+pm5*d^s#4mJeL-@NYQH4P;jU&)={>=&Az^Xjhesr5|8jq%4P&O2l zyv4TTkOXjuR?!Rd`q(g9OYEn}(z>aqKXS=jCb&D1N=#VYO7 zS6xJ~z5||Hw8ZY|IjxE?0KrY1LX zIAUz<=Yi&)6uGL9_6~B_b?M0s)9@a*0}#{8ixJan#rq1MV|8zqK=@C_x;INiKG!mt zYDzwA^6FRiVxg~vf{NqZ?>lfb#gCMMY&;VHO11HCNIgez;ao~5%rC1~LJX+n(*Jro zva7&j_?*1lYu1j84wH=u9=xJa{&sj9ZV7T%}9oirYpp~S+Kj+*f-%D-9CE+mty+Y_6v^( z$4ni^-&uv8i>+UQ$mDLJHrZC@n%>ywUlr>?&}R^21$ zrj-rQ>JOarslYAJrKlOJ)HHsSQ-Q^s&GoHlbTm;}U?1KJhZN8x$x;7(wuCw#6PYW@ z@nGCC=Z@HUs!i$v-dwQIew1ajx3=$(pXtSELdiI(lm1Egk9Pc0qJ{3nQmBBpaHRc_ zS#!85)k>z2-9;3oX)G#}|Bb+HUP#p13y=A|Bp&>Y|M0AlaAqpqaN3cHF4ol9!v&Yqfjw+ zIWe&hKcf1BA4APN@dGhf$sw3>f8+mAxgf(U#;9WaV|kIiiwvJd5Sm8n!fg1g&s?>* zJiz*eNBH^^C2sEF@K)QZ-(U`eH+qtK@FS3Me>^_+G|Y!wGxexcdakthnPe=&AjoS4 z3{wVV?#ttDE34JDAh9nw%^n8k_Pf}0@Yz1g+xgTzK6lMht094A4sv{@qjwYEeYbtn zwe`kDMT%D$zc@brIZkfl#TR*G=(NGw%-O|rp5~$xmW79}VlqVu3VzN~D~QuY`ZC!< zv2H`Cr|IOFkYxRJ(8k1{~ zuvF>>hzqQ=m58wJr4`Uxn*JI~r%RJ#HdwfHeKgf3Geua&NgWzu0@GI?);H&`_&8Cy z=0}wGf@jjS(=l_y;xp6%qq%RgAi=6bNLeryHc`b8(RUnyDWI6zqrnxkXz6Q(EAdkz zRqEbFT+0??@>$g?0iF_;8sa~Kn@CJLBOvJ&M=WZrfC)@4$SqU_I1$|S!!aSC_(>kO zl>&dT{x$&l{#@wROtB>Zhg-oj4Uj6@BE@&krjPrw)+EmG^QQ( zt@r~PjDYv=yuXR-dnw{#Z|1b=N) zhS5DamIP^+xK8SodWkWKsN5S2OtbasH*6HBK9L?w`Qf(}BA<+8;X43�v*t}d|zkL}~ zkvRmuw`3ddneFvr>lx29aq9}b{GbDAH7GPsqt~m?Hy|KN1_frq`x|NiZ6c6eb$gM# zCtK|hcSr@WN7&7XFZHxaHAdH`p2VML{Kupqsk`r=Usn>NIvHcOdW5&Y%5sg`M`%by zrCH;m{ARQ8_8S3HXzFv`ziR;8Z5E5PNaf0F*u-(A-02BN29gd0KRvP&L2C3wj-C?6 zHQugydcCe(v|5FY+`ybg%*|kYI|Hb9t-zrd2}1kDY_>*eXA^ohI#a1_jFizQI}WV3 zDd5tj-d?(D-_9Y}f1DE&ji+(!KS5Q#IVk+G(D!Wu5jN8HOfD@M0t+f#`WYJ{{@^R` zFNE89j`KXy-JXcH;d@Y=kp-q72#a@14YU)-*F#i9#7mP*5RJ6pZgn7DKMLw_qoi6) ztq`6}w=bbdlDd#rI+Wn; zP_eMH`mKHq&s8Ni=Wkru{7c7}v2Tly(I?KyeLrc>=HnD#x!MhP067(Y`WO6KLedfH zWHLVc%1of%SNl!pW-xdGKi70GCJb!|ohaxpHTzPzz)ml7H!`H+8RNbO5BQh#gsl<( zTKBM4?{({lgqu>cshPSS<(3Adh+mRh9ueMa*XnMocG_;MwbeWu-oeUP*n#);J^}bE zGmZy)4x;mBBk(%rg*je6GfmI1f)iXO58~}>lgPgr!_s^|7w584xEm4`M_x(>DXj$8 z<|lFH?W<6PK9nlT=7-Hoek2k^bv!g`2kYgwMyPz|V{0!Ba=haNII@FbuON*tZH$vQ zVGSUh*Vp=Zg}G*atExBMCTWW2Ve^gYm=*58$27JxGzpS){himVDie%eoVqXML&3zd zrMb`|VT^j!)6N^EUSse>4}yp-E>?w4(Sa1Pm1p-BTvwO0vcu7BZ?liyS4vGmbh!DT zx!qm+fEq58@8(>+?^!zc@W5&1tvT3wR_Q@wp5k+;sXjWs-8XfcTK`ZzdtzxBz;v-D zc^;d;kJZGN1KrHmPX32l*s=FV)2N6Xx<5<~sRQj^zix5VR5-Tp&!c*HSchm8HLM?a zHMN3kI=zyr*amPEzBVpSQ96*s}dKcalRcCa>*> zD++gt)rQM>p-6f0SBsr(?9$^fVld?-o7@ z-<~`$%*^Yjf9rxtvEQ&b-(euzk0;`+2APp*bE#kW8ZK`DJ`pgRzflq3~H4Su)9`%_HCZR??#69kJvKK03~6Rn@}*}tXy zMVoe{2Om(e&JW3lsX7yy#lcJgt291h(a~2>2T2NCp&SiKce<__C*X%w&xWUJ_4qRg z2Zi?{vt_NbzdpJRhl!CmgBF#N1>gg0TC5Gs!-x%PID}wBC@fI%C~a|-k8v;v&7r8oQReHNJv zGMk92mqPx>9)e}wS_nSQ9^y{PEg6@~IEI?EK-Fu|@rn13u#rhJu!@w{i(@9mG7l%+ zT~Vl(b=d}KXyGpEQq6NrlEq1IR_AO{5olpm@6b4tC8 zMZzD6hNa~Q2BL>YW6(z|6Q=j^luk}QZa#xD1-wtAp9V^Gug4*>>#JFiC6-Jl_P3^< z@Rr^oqUsV3m}9NL9wW}jrv+rdEU^m9S24cc3r{`0kwkkWwIg-bk|lx*Aof%JI!9nN zbPE=zEwehL>T+(FQqV}0?p2)#*Id;1$ixsTB=FD^acq5{9h3rbd>~=>lN8~)X6lH|B_1124eQlLyaa3sB59SxIXPJ?; zUy#UC9Mu2fO7t%$Y5#*L{_j|rVkkZ5YB!_6zY*TI;Npa{bc{G}h(laPZL>hxg(cYl zhe3yf%U^HRXO@nm3eq^V8gyV2pH!+VojtapG((jSx0hC z!eo)mHX)1yzgxdI&kyakmb_llTN=Xua%S(xZ)Y2=T@o;=SOy8_8-o!dTw~5x3FkU@ zR&OmmJWop$sKL^YZkaOBnYugg!6ctdsxDfOO+0vZ!#yxOj{=bgBAPzbtp_6RfWFaU z9YWRri@0+NvaH{-ecHBd+jgaGo0Yb0+qP|0+L@KMZKD!5zjOLKwn5&swa_|2!Kl@>^#~VvZ6X{)qVlD|g=c z2kg^Epr?KfvCu|ofL&OB3s~g^VCe1gjhq1{Ef`fZvEffg_46mo#JtUN%VLU~M!h`z zQ;6_ti?gRVvm%nYguq)y%qJMCipA=cdHWkMDzq|D_qkM7sO`_UhRwbA9GA|0j)hK3 zt|FX)UGg6ySTrhtrHCv#R3;LXI}Kw+DW@_Vl9r-G`+NEP2}B(J17SM6NY#nvR@u}I ztiM^ZpEp~q&%Tn3Hk+GZV7Q}@bFM55FuDZ{8ga~+kOr8{U<5YJX$Ro6~FS0xX0(H}(}cIK_Tn*~Xl2)asgU%JmAD+zu}z%zTn z@n8Y<^^5|P4WBTRX3y8^vW2g2H^sp)&5;zplPt`+Rmh$!WBUh=SR{DOPwG6tPm9lU z^z0j+Vr2&_8h1X1#V=NEkW6INW>#g8zDK1YZ{Te2QsYIDPgWoDXS$L{8frnXyxq=? zN^zus%YQkvV^b`f3dHPeve;}INj_>ygb7z24AP57^o43FX%BsP+;Pc&1F2m%gZx0J zM0z@^{=f_s$fE2Sd{T9{1i`@zj!^xc&}nU=u)e9V8i9qQC{Iw=WPbK{dCLGuh5lrl zDr5g;Fyo!jFvUp}bVGe6YPlzp&HCkYVos@|tPW7hk|>2gK)f`n*;8jp91_^s&PY~e z3mhq$Y6*ev}e=H;*(cSb4Dj}T`U=?r(qYTUZ09lk^tx&e+KNK zTfpW>u9KqbE8LXEBT(gW@drZz5S3|;uOyAMVZ(kX&=&4&8d(=R>{~^D;a>&?t|D+pum9Q*2mt$O!U$f-`FqQTg=MSk*}cDMm;BlcsqSG!8v^SCX}{WG__gXV z+AL-nB3iI?Fbc#TG%%*6?rJB`T?m0@RR4BaKfl=xp_((V2Xs|&@H7X2jxKK%^?bZV zbiC&J1AL%=W=%(6-UYFiYa=F%`BO+6fC4(8sQ3dQidGe^C=Ibb5G7!ok8idp(zQc~ zA$`5E%d4n-zcID@!i2+15p(8iV|kzBhYDQ%FA$R+eI%(^zfr`uV4-6=N~gPDLTcJc zHA4-vkmtXzg-h+IBjvMqA~;cz-nX|l0mf+t-Alac@3Ft249kPnHToUYM?oGict-|} zZb^fttw9+35qk0f@|%`oFP($6VxL};DU{~kV!%czmQ&cr^P11%}(k*12jV@6D zZV_k^u38wV!E2=jK1F9FI+^;`nDq&a50ZVjDx$Rh&b z5mVwYhSQcQ5m~eSJ=e5JU2mHh*iz8m#y-EKNC;?xt~&;K@lhSJdCuqa>V=UcQX=D^ z!iu=%+4-#jl7#XXh-}LI zvIRg=CT@a|lrU=O>0J=;fFaGCQE4VF&q5Yrdd9b3C3RyKX`p|EePmg>zY7up&p`n+ z9=ip^%@}krZGvU7R557t1J*eBd~$T(_JR1F+w=45?Sz610L1hM3!C1bBhg(#)Y}4f zCqIlKfFdy8JR^mA+%~H9-uM12jF6O|WbgbMsS(vP7&xFSzQ;3f7}5&$J+yLZ+B^J3 z9zbqDkm|=1#PM7gVF-e0%r`vfG^vq8Q#Ni-bLyf7YTqTLa7IuY+pjK*k}@}8(}y*; zW+LaUDZd#pM82Y327SX1ldaXivdh8C?6G?43@2vOinJX|IB7UM1*@$7+{^d(Mh|+^t+lQ{sbLK?hct_uM%l`{0Y$Zu@n@9e4md*^LcR`4Qhdbswa;!@%$XiIv z5V}d`^m9w2C+}8nLD(FspT?k?_Cbb6M;fn^QnQ9GeD0YB&syWdehz3<BECr6fcO{;L#_h#XejA3(CBd*0^nWx7yMr5sBC2;$_c!9c394U z*E`XqS{2eC&^F^9pyMvT*GbW|8SRkQi}R#5jQi}vVWj)+IIJt8)OE9oiiFCAmz*d> zRJ_hs${cY^$-t1xWvF~Iqb#FFfGN1pBZFbw-Fh5qRi*1)7j6|<(JAI6CiY||Q1)H= zU4@Syc1(cCQtDzQ@Xm|U@G`p^KLoj{&%411)O>q&-o#p8PlU(|5qk{|CYK|B?;=xzA>8Yh++;;bGup zVf*ucB)+ozL+||0;wv)?D;>jk<_;4BBOL?F|K?H~Gt1w4>tEvQzw&&(F^9}7f63Z^ zDY4&tD`wWeGl0GmBbizM`JI1PmgW2&=6zEozj=(`KW6>STNE)dvNbmO3ykRay%}g= z1Ld~%7xR#W{F{0BLCrxHN|a_>gG@?&$hO)O{nS)>L9rH-)O~P$3>pE1Rl={9!6)t7 zJb_`I(;ySAua~Zm@3J?^zN^GwctFCAlBS@oHNc1O^2J2qt^dQ3ybWrr?n@nIg!>=N zL!02p?SC;3Uw)CmZ+SL*`vzp_>m{VbmY_Stx$V+w!PpZvCtTRYXC>_^hV=E+Z*p2R z1Kyr1;}7#UY~C05&<2@PhT@atp~0Ls_3RM*75qc6n6ejzzuokP8?U3k#Bqs1r!O|b z{o1(&8G=nX#!TEsW>wEScQk>f(En)~0!>^jnE*^&lQpQmCzc?u4z7v=WQcI>yM9Hl zvYX6XZx#N%@XL=9l_O>q` z4)6bb5JGW_8|EUTZT)2gcp9#Jqw9{z0BA3#+8LR)yruvZ1h1)~+H;PJarkT14YLil z@7&*zkmh-T4kkdr_`9S-W5Lb7q zoEa7Gaay5hh%1gn{sJvm7}BXRO4K+{TyYSg@op8#(X=%H!4bev@tBk_7lQA^pT}i0 zdA2heWT^?`X$}wMP`^1Lfkq4wNEXdZp5rIrK(OGsQLmO|ZCvi!+;P>U5*tQsKyIXv z#Qc?}=HRC8=_D4|P1As?0sV031skdQgNvM}PCXyB0Qa00lP`2?O;L-l;O_T_^O@Wy zUx9c4ZM$hP(TQlO_mG{2rRTEdKQ?+=Q^Z}hQ3GUs)Ajw?jwq5_o`?*yBD&;^%9@_b#0J4Q05QFpcvO zZAjoS6NbicdxuCHppvzX{LrfA4Onphuu}yqbWRAZDU3I|B`0zEd=+Z(xk2JRjQLTM zi7Osx3nL`1rUju%!u-*yZ320yF_#R#a7so|gZuByq7laM=|&qb4Lgl-V*g>7%N1S> zN&MIzC#-=2C*F`Vi~(XL-VmwV6J4b4NqqLW6*!&oPAp8|p=7aCI}W6g{U*6Zc+X%R z85x^#>hgIO_(8K&#(rnKq@hB$>u7`W7)Qn} zCCtl z?DpA|=PWys-APbza(o%3J8?d8Olc;6zOk{z_{Qi_&<^Dpz!lS0){)Rgc;-T$NX~9G zg%03`X6&VWtf!Lrqub*N+<}iiD_-SpJ~Eme*`l*gutxohlP~v9oRv`Jsp6 zV(B4&OK57cUVsInp4rwwp^$M@eW^Q*ITf{r_)iFRA+v4=b-J? z@7ebRR=s1j!gXgAi}Oim_Ll9_AK<(<(hnAGM7#XHa5o?%59Cm3`tr#W}oIm$1# zOE|~wsr`9vCtr*A8HI{3`42`lhF3W@uOs}PFW`28-|hd+oAq0k{l9P4zs=PQ%pCvj zWTF^jB4(fMZcA@>!&tux@dq#P1!1Cbz(E4cZvnV5JoCt_BN2Fb%F@!~bEP4w@q|Ks z_((8K<9c=YrS)q({H-4JDOqESL{`IRx2;9zwK4}a6Pb)d01MY%^4OWBYk0|VV-L1M zW?maK0nPXL@Qv4Swm|p%;M|Qz7M<*?y)A9?@4wGDJ8hZw9Y6FbCgaum!#I?DE&4mt zw3$BQo9q(1sY?PVLz+PsVZ1g$hhHyW<$783Kdu`0(S#mwL z5I2s|$hQNFqg>?|(!2CR)O;c?_@=X68o4b%I}q&{8pVzfi87-WwfIcd1PlU;-MA>Q zkesQxHwbos%l?hi4Kk0hn+?zTFu|`Mu1}E`@$c);4eD>Cq$6eBXe>z65L`-dL#Fsrg*0 z?GNxOtQ83tvwid8Yc`GHjSB)5sW<}#W8Q*lZpj5tyzLJs`<+@^19MVPyeFKT)L@=Es!S@e1>mepdorimssqi*)z3HT)=+C(+3HMGQq4c>vDrSLl~c zp;$rm`iaI~_vaC_>&_{g$L6*i*o_H|?)TApeJ=-aLG-{0nHKw2!ZZ>KOjc*V!wt}`#Q$YxO*zrR4kNC0E;CuwF8igO{VxB45T`! zrbK(R^z#c1g~EUwu7Fo_M)~ih{pk;^zPilMb*tD9mU3uixFz&5R4emrtC>q7aW2u^ zZle9c-(QTMV*SA215WG5p~^rfe*$z&x=phz)t=_8)VJIrmkR8I(ZDo>SO+pbR$cB` z#A>kgaYNst`@w=^2du~U42%M}b#E0?$~>e0W|KZ)>`W{ zrS}I9xm(qQ4*w@&;&`YeG7v%|z2{S$OFrZ5a~ZK?L6VayOSW$q^8h zq75+JoUn#CY^aLZ1kYM0zj`JO4ah>6{Dd+Liw7SaO9Lq+S4>>}0FYA59QHMo@s!z< zipb$Xh+`}((_iA*L9iB{XDk@t#Cc|9hj^jX4zBB2RgzF38r7@Vrj~zQ*R@H5hnI&X zIkT##n|o9*1@;A~7-y1gLzG|*2i{EP6?H?ZGklY1hAM&%09+0g^4gleR2R1sDkv~T zSlfmT!pu^CmO;7i*Eino(EY-#{RSHqXkp$ke#u@+lr5>-PGT$A%6!ut(UVLa4EBbQ z0%^9XUD78L^z;!#u0N~lON~<)xjtEk2X!^gUns&Ba+sd?x2zH<7`VBOlUY#hX1Zj% z24YwVR9?7UT>7q4-)6s?D>hD$4mZST4J;Rr*Vl`m3hjD$HVV=j^$Qyls^pdI$3Q7~ zys63jLQsSHJmI!+-#Y#uhv&_g8^F)KIYLEVn$ezp%sl_$A1V18nr0iHy{&R; z(!r8tMekTNplj~|R3Tt+`K6-3hyWKbIW8G|z=yk?2$0VM#5W$hKkKq_A(sv$>e@)< z_xLj5J|t9hDYrD&KvC_j}@nw3dTF(d;owysTu=tUZ-aPV13-RrCnb}O4Wuq*s3 zYz_+S#aLw1oT-gvf;k*Zu*QBI&IE2oslGTN;Vz6Y4ZUdX>F3UD!vUSEsFs@BZBLhB z)b)p8j)qIHkM(wa#9tlm-?4Z9Ye6%122SR*Mz%I~4knI{|I?&VR71{~tZM`ovEhc7(2LH3s%S0wGgo_f!OoahZmjIQWJd4G8LxL?olvr5sti zMrKRYQ$XPW7N)CO7p93rhK|iIL``n4vu0aCrD!A+WdgEx$}vNi`@3?0quh+UaGI-w zy6?mdoW6ylac2Imvy8pbFPwp>r3l(!J_ur@rY(;jhzzuRX396K&J5#V12kb(4LH%r zv1Zi?-M?kIiFP-+_b|=B^oda?$RdyzU9asI+Z- zH!T`6iq@l72DXlduq%jN-q99Pl`vXRMr%mxbO}=E#kAQ2Ea_&1bOiLu~nwc6YV8?f(Ior@j7oIO+Tn|1}~k#uI0^Q;i9C<;^* zkY`xZqqES7MUfDBiR4Cz#chAF6gS&b!#M=USk7lRij!h0`k;)$Y=AQQYqB-j6XLAPNpcR zo!=-Ek;j$Ou!cDHQxin^8kuK(2XHCxft$@Mvj08z_n%5LG_i7g)4$3S{hP7#m zB{+bj%rS()1Y?2~n1HpYNkh>|w7z3;u$B~FReqtbiS+6VKJymiOj*Q8B_c5;&^QU; zLOD3jJT`76ewbArony90!M-sX?FT$xG;}q;6(YuJ5olPe1li8QRiUyTl6vXJyc$v@ zS4Ufmc<7dTL#tmXSl>I;ig}0AGgZYx{<0K+dtY6AXV?>OZng=H>AKNO3z?K67~yY^ z(cKd6Wt26d!?at%x;!XlwWHlU4lCz?YG0&n?BsI6JwC1c`C?A zzzNAckydHX3+cF9{?mJvv!v1&hJ&0mk)|i3a!LryWoQL&V$!@6fxwQC#R8ID=4{ld z`|wD*dmzUp56^<=?R>JSqNI1vYE=na*;(UvK^M_HZ4GSQmm%iZI^AlWfAo-vN}j(E zo^~85DN6xWBY$i;jpPGmJ9Ia@cE*J&_LS$<5pyK_|Uz6Q-fWm1iC5FurTO z0D7|-k{QNrst$my7U9ED*-WcMbe{EIOK!WVj+7Z4my4Y&@|Nbycd+my{2`5hzv|q# zqO3(wn#-J6!Ex1^^(~JasZ$gCT8W&3sYH8f7NL6$?8j*yZT^u1@w1T%rm2aNDvObV z@ZkGMcgLOrS>6Hz2V-e&8=Fb7pXp>cvj>Pxm?WMx_W3R6$A;X=gXgKoQR|m4V7Etw zz<=|CO=Gzn#wi_7d_G)@s6j%dK~hkb6YQcz``po{sFE^HR7{dC|pY#Y+80 zUpxn~hcj(#HmPhn8+l67odHhSRx&FuaXUN-BTv=SZoZ7W)7}o4SN)bm4U^gmebuie#NM zttxTdGDykAuZ9f=coX%S;!tN!L2oH}rHWwvVLCB+_Qg)A(-afoCN%Ij+HLgnl$7N< zuBF9VQ7zno^?m0Zn!7(O)aTrqSCMZeTqvD=5jeSY%?3zq`%X`kqWK0`=FkZI_5(^` zEQx(K03Nvr;=@Huv5^Bzv=8byc6s`#)cYHGlZ@ifD`V;LSa#H=PA@PZiL+S@(in(i z(&xfJ2{Zx9WuV3KHK8c$=_bQ~T8hlHLn8i4y4suKJg8nyJ?{E z`RS2&e`-@{AqFH#{MPHPPr;DXh``C~nqJX?Tqga5IRI3fzJ&D!W7XCDU7>EEAwLZk z1}Dg>s8YtZ@($Dhg`x=j0F4^{FfDq46bWXc@nk?de$pV6v1}E3)}743eXOiS*_rfV z0#LKE?m}u{Vi03&0vrVA&a$l(AebkRt-awR-!(`BRNIv`yZq``4$gqA<1bG;^aqar zy^vZ&nFmL-@-hVMk<2;IQ?AAsZ!oRRrgV{)1SuCW*427XmyZDJ^$6fAp>HQ`MhB!# zIx2XtK)jCd0~tG>5V;g11vY=jL~%J?L9VXv;%gb`a1h9MZ=4Jyo{_vU9MOlR+Pe*N zrX5lhmMO^{VkpyzV!BEy$k34u#Wz=;I*1W!$o-11K=)CkS}CIsp4F$gz*F!pRWWDG zC_VP{-2ghR=yE2p9i)PaaZLNSh;<|?!XOh|Nxpzdg8t7|6P*$`CHb?Ho+UTcy3Awt zbE^_OOC`J*8_oku?UTc+FizX{5TSnlT36I0QIIA+JT}xNxd%ns*hlZYp6MGo=T)@D z{^htET{GxgaWKLQOuUBGb@TO}y9W9ZwZ}62VNdZq1 zzkR;e+Q1rU|GEvL%a%*3yo7E|9!|&*u1!s>jFev=6hV7&DA=GX8;FBeGeB=~C|km9 z1+5?s>m}Q!ikA3=$+$=I{v>Qx4t4qvvZN`T57CIIp$>qG^UM_?2002#z)aD}*mB>o zbL;xq$>#t@$fT3-2v1s1}bPX%v zGDMMPwy@145C&Mfih$ypI8(49=qvC+KPFukK(#<)=ad;3|DBLG|vUsA8@LuE2@#EvC%Jt&&{=BNu+H?3uA=)x>alKb|ZywXb8eR z7Bu-aewcYdOqV|Y{(kC%N9$BtXrmmiiE9zmElzIa1%k4TQg9&D+3%rZ%veIb?G7@0 znDDWNBfDY%wp(DJY#gAM?iZl*DyzvLBAQG+{l5DjB^@>y{3@oD%5;Xz7BKp2%iMd; z(Q58&F9eSkzyWyBHeFS}>##vsVC zh;*CRib1BPGH=q7)UUHAfCpUpgO^#gaAz`NkeCY#FkIc(8j zm0_?x$&ee~?wg85jP)opDTjY5EV`ffTxe*(y3-FM1EPjJe~+7?_3EXb$4ozmwTKG; z5mexFA1Gvx0n}@;j(sR7tF36ElMppE4uNQ_j@_JMGg0*RFW}4-0bIM?H?9I>poZwA z0U}V5C*^g&A4%}Mj@--B^a569QIUky2fdJk<2T1>4f#K4qOHiFR6oM zP-B$awYSYcVGmT{UJ#A+PYc<_O!4>BZ0--V=gmkpn>ebmnE1%0SHl#^_H}h$!L3r` z1ReoS%rB^_tfYf0g$+hTSKhPFbs6HqX@VpJpEzTHf}T4#s&Xq*MXcuw(PS+^!;@A2 zc0}gn)E0OSbZ}mU=-UX_wGiq|G6-I|t)n93STQXdaYPMYkGa4jl{tBPywfQFa{$QW z%WoLPfvJ5pSaf(}lFEZIg%*i!79!HP8X|pp2EuMqYYb9&Du6&=1q;EPQb_>!LT(Rd zLKKVt4*2L5ocvh`UY3+<;&$bkeA)BQ0TyvLt%0z zGQz<%3X*WYFvb}d>nL|9R`@G2wU&NMcLx_<58|ZCfkJ&q2oonXe8|K1c7MjJ-ai#V zBTaR6Zz=Ff;S+3ig;rO`%ky^c^TRM!%FNA#JqJsUv#*>%awXVcEA!zZImXkcC~dDD zoifJ+^&YSgSVOidfP5-0CH_sOVY#31ypVjW@KeSxC%WJ_hxoAv(c|mMiV!a__Vg1S zjY@=vzEWp-xOdJ^9MVAr-gIx%@YPa~pmxmW-=8t0fe8{37I#4I6+v}0D~ayEH=x&^ z>zjHwn8EQmjn|q`oZ^Z7Kf^ipqJTT8Z`|qdSUJZUHhjG9Wh{kEd#*20`x}c;bk+{= zQVV*qcnfjjnctC$Sc^hVQ17kKm(7|MyyqhbR1tQIyadSH;t4l|1l^$CUTMa{z!rvO zC+ABhkr$|@4!#gL9(iHfb0b1i`ikwex-y>5m}3`l@a{TGVx%8xSFtFw#>u1 zK24F$YHZRTP~@Fjux2CUUMdLVQSNE05*xosrY|Hs_od6$1xxF(O!@T1^XY)E1SB5m z=;YXN>MSU6-M2)~jkWLHNL~QgQCl=%G07k3Uda2&Xh_ziHjt`XED8Zi*$l*ulYRvc z+b={Y15Ggg3}%2o68Xvd@xT@g&u!k%L$7|Y#TwQeEgaH~9?!>Kqqc*?v)nkbzS<=v zz?a$xtv_S49zKy3%+w2b$J^c-MF%sS1RQwYR8@w5ockmKF=@Z9b_diG?I+aoI z6&C-nB2MSGsrFXSx&>Wb&rFuz@75a0QHbj9ZMXeymv)%0$~kIykJo-Gh*A=oJ-`fc zzWR86rmLRyy?3%8b$Bg1KutP7+n+(;3xD2MN%I=^ZB4fAjL0%ldo!K|8{NMU`v_uA zrP3xAam6vq?z!J)KkWgOBnbRUoxm6z4IMi1(F(2@Mm>W!tB9C8d{2aZxpxGsy8BU^ z_tNgGv+yEvo&44%cA{k+WCxffsd=;}M4_=Zdc!eFt<62KcC ztlnyN+JQ^?9!Kz@pT_ihz#l3JXDtOIm(~NCX3)p$%yH18H4FDoe2DeseIrBbN! ztku4xYg|=ao6+3kH`p#w<>1tW$V&1S&yjn%A3jqj99t}@mx!hITTcYuO)`)g-DJ4+r5GBO_* zdux0(s@<L7uA0wB?F^to&@8pR;y`;#10-0jdrkv$3}f6Ko2nSLU?w3h|D@wC~s9@ z83ivzk9aM+nwCM?SAGL)Kd_|O zq^aSE&3a}oyzXEH&TZu|r=Y4r5_o z;ZeY9WXRpCy9#BR9B4cEy8~)QK+#a$!*ft|u52ddO zLp5IPi4zt5G`;wn++BE(P7m$3^CRR2?%VE z_x0FN%(yWO9MKXk!@e;Us)FcGZ=j41ruChffs#nz=SG@5O;TTCKWI`~x_XAe>tncJ zF1WQ1rv7~?d)W(K-`z1lCU;-NF`ql7ej{`Mj`~$`nx%V!u zjpZI-(m&Ni$8!hh#d^EmYdqw5&X!(zu#I^dK!$=6=1F-F>+UrAG%ITJ_(7-03Uo)L zI3T?_FU3wpJLOwSzENQf@Y}aTNv^qIo zuOMu7pigR^mZClqQy17jNi7pHwh}j`!D@%?;kID+aSR=ZVN1sfiX&kNg_s{DSSc0B z=B2o>;HI9MG9D@NPo^=Hr7LXh){XHQC?zfks-fqPl(Z7N1Scnt0Zb zJ>kf>$z^7XAib_wl4t{Hxh&j?OK+W@q98o`hBilOCRA~(@|zA-x-AcXyj{YFT-sl3 znp`k_$%j+LMt(|RxBNEa?Y6JvEy;oP#I_qI)Qf<|2F84)tsdJZ(l11I>IfdX*5lMb z*H+k8{F9uR7?tFwG%lIxPgx1}krvL3PWyzp>$M}N)=bW@EUqxgpRm)M15Jax+X0N) zBosyXa6|HkSt4i_d)oU>04TP0bi}NhzyOeaPx8^wOD)9P=nt z$Vxj}u-BczLPtkUPes2H+AlY=#8LxG0~KRCLYP5oHsm~Ngc0&F5k_^k)9BLXar*m) zF9%{)TuQKMY`Wd2QuGDvw>DOpR7v&sK)d6a$N&Xk?CZRdL}yn?9WfR zKSGHF#noD0U4ozYdgsNO?al?c@>bejee(KTcbl=2;h&V-Pht_c z4s6Km7_aYn@Aw=YhmBOnzK(HW%%mMDU7w3qHFF@6o}MFVM-z3Bsl6ohQ%271aW_wm zpOv2Pmz-M@oZ>QaJ^$N44HA?@e5W))o-kODx!#YS+AG1=U{kUHOX-~arvOy~ zl7w9zScmFJK{t`3J){J$LqVl?2Z~VhGu<{M#M6*Zm~=qf4tnwjFBo(;Ec08#&EK<~ zr{SRuBRh$OQ^6rMf;5@%Cr<!{xe3B0Gl5G#@wW3uZi;N z-;werMov)lO5d;(cRQ1BqqD7p&A09O`|}_AHzO3iyt1e|-M0_gMApE@gn)ux#nHsU zk>1$E+Sne(@xP48%H?P5Y}_?`4+ zOl#ui6D?^1aCIGJR_ zKd4a*&pbXC31Jqx9H9vr4YI~{ikRUD2B|Jy2-J25esGtAIBwQ$XGs!WE8rdijZeLj z7=acW=J!oj5H1TL1dHnFLr?J0ePqbf1p+3?AH553>MU_5iyaU2W!*j#kIvnfUVp^j z2<2PYP=^xSKVkEgFJglr1r@Hn(`=!4@MQHtXR8#oF&gnS4}-~xfUD8gZtxLCEV7z+ zL zLZ54$F!CCE1EWVyJ)Qq_Z~t7#s%fmIjH0a;^Ldj96;PY~`XXM8aOKC?2dfER6p`4% z6K4wyQk#DJ`o)%Ez8N#BD&$eVcy8R-=8oADYU7l_J9q8`pU1c@2fw~8br&fk;{jTu zjxUrm*TeOYZKQ@00pvDZy8U^D3!UzYT!igLd!196&{Uiaa6iGyatSjx9o3Y$Xs-Zh zHhI6}a$yCRzFw}gIdX9rxBY{*V974sQ9*dPl2}wEph*@h0i_|N?WVzNzeXIE5^lz? zB_QCE#0j-{fB~z2?Pa&_M~k@*xYjenP_DjR4Yh#KFczsOMpU&a*F^voW3=%~aTYV5 zx|=1WJ-g4zdtYlst!{)QbS3Vga3zefP`I4Lxt$2DVHoIubWj*Y@Y3)fMA>2ZDGs%$ z!+2dhlROFvY|CRjau1sP=r~S)!*7Cc>6rBmse!{PvgBG3s9B71$(~iv-a^w4o0O6) ziALbZG?LPLGZC})Qn;|6mKAh9-eR2j#6cs8^?saRF1s?Rcb5UNWCe_4P@oAP-F%)sW8ljxL}jR)#{>}Chb%389VTL?@iO{R4Y8jKvq zd}elCyi5>*WQ)QL;!6uBV>g&%&KjqRO0UC7#wYVn4{2}-cdNE|zBV~NKYylF-nMe)Ve3>v;dyqmr57uc!3yS;0Sz zK;I{&lGFFmC`-V|@DCG;gQF7x2gf%B>F-$r%XjSGzd1{|)U>h1Zb$sA(d)NO1%TBH zJ*b0#Ya2X%^25m>6U$sWhHvPOS(G9bPH;T!y=K;)*h)5*(!~aaqd=%_JFw%xnVuL} z1vyVr>DM^)>Z?^FoZv1uXZA^yM7hmWF^%F>ZI|#>D2@?V5kS_KC%vQKD9sWL1xGeZ zROvynYe};Vbnu4|elZaOrxb4}i#8{*AUQm1cyVMLC#ef3jRrc=j={JiFvYwhI3j{Y zNChC|DeQ-fE~q2%2oNSN1n-6Ogz7IuEJmEA0F9d42QDP1(ic3enu2a#Fl#b9NaFMpMMRTI-V}u^|HmCrjawq*@3>;UUV3k21^7>77@7=s8HZsqJXq)o2MwF{%%x$RzC~5 z=+KbDXp|B9?n=dphzpJf$`BYF6_VTN+zqydRaXO_yH0}@BjK|bqfwAk2A zRKAOC8fpYfKw3(wO(lwGCnO7{KRlU)24p}3oK@lES>q=Mn&4Rk8>0^zDk!(H2E;NY6QtrDd1jLnAnu8|NIqID=VJ`X zlsRC&c91!S4MC3`e3(d;Ajpe)I0IqnI_|q74nuN~zys_3lgIOT&bJwr!pT3k$ELGNG{2d{FwejIF5p9njQEh z^O)+mYVaa*&H}HznBHIBI&U9dE*2~&9wy)1tUxPR zKb78JJ9!#eQ{>;F{Gox>AGX7hV#5fD+UxiG57sVx={~ARD8ey4Wa;Ebuw6E<6n33H-ZXxr zcH+*=WxvOQ-Uxqfd>!lJO}TF+N8+7MIm1|0W5xkR6h|K<7|rM1qYx^TrSrQ2e|&3Z z!cTskzc4SE^!Ko5eD&hBeOP^w+`yYIBpAP!2vmWFn@ujtE^^1gBUEzZ97lSN59#=g zQ?@T3KLKvS_pzV5f@IFaVu8!Z3D_2Ci$SaMF z0S@2=@@Km4D>U32kg@U?SAMU!mbYY*GX%U-4eb39g4w0!*D!QLmGMC)qI9*hZ*m@*Rc$$xmL+zk0P#7foXkD=y^UA~F zzA1jA%U9Xq{A4`zW4cEw)ELf$NSa{FZX=N`PVC7&ZDqXxvIZ46D$~WzrH(ohAsjLT zFb$8ybdUiswobh_kOex1)OZB<+_Q`daD?l+31D4ET51lB{L38r0$XQ!x{mnxCoRLo zqkg3gQ0)CB#Ey2|dX(psWvIHT1a=ChIl%=|)8~a9wB{yg>l;Zgc3bkbzZN50s1^&r zfpSnYuI&&Dj;(@M7lkrc!r%(x0Ukt#g>YOOp@dHt!G;Q?D{BL;|6W5U8AMIXd4LGF z0Kzir;3j0kg^OT;9y*DQ`VSafkd9wDt#t^`8h|;Sxz4JQgt3TWH0O2T8OCOx9r$F% zOyYkO6d4;Wj8b~1Chr`!06dA((xKa`G^BgdMem!_uSQN8<5>Bz^&iu%N+5v{l>}~L zxe}B))H{X#2n@EtAqsE6lRcaiS;jd{+mq`MloH?nxp4!`d-C`2maOV{{1`OwE%OSy)=x4!EJOFg(S^J51ZA=?8 zaPNi}Hv+v~nLsX(sSSoBdm=$Z-x_eR8=kePLljFVaS3sUd?oEQKfczg$MRF$>Ziq@ zQL7Gjv&nGh_m~D;^7G=pnqoE`ry2-AIMPFlN-IIFWzCK}AZ@TmfrOkWonaVx~1|Vz&n$4&|(RHKEZHnNC$_e6-Wg^ zUumZCG-?yKU5yBExhKV-i3?HUOKr1a@OS&lnm^Hba?UB0Hj~wB#yg|x2NcGWtyI^% ze>{lWpA6C4%7v-ogUV760<-+Hpv<9`ORKHicd@dQ;Jq&)5oh${A64oLDoKKU%K-$% z6(S-ONb*TC3TV27cxTiRG?oF3f`h&S??}~`XwB*$a2g2Y^yRNVbWx`eCf)dQKiG1; zdbF=J){Gsg5C^rd#qlq3aW-wm?2axR3XBOIpVErgDk{Cay2?Aan60d86JjUt+AAtx zD#51#2o@jb$u5%oQ@WHj(w_m#EpUrUcm*xb0>?psTiC9PBIzs&vW@*VGxtRDm^m`p=rGxweSmAl~kFvsoC9;50cRP{HE^dbdRz2gb>O1Qn%*{uJBD;V=*iS$#WpzXj2!xA)g*B1{(MZKw#PD0GvB zVx9yv%W5b{JKrc%H+2@xD+QHnW^a%1w0ufegKe#-o^?b)$TrOPFn(7LZ_DeWdzvk) zk!fP^Xt!<7uy8)1IKmbWE>kZtSNqYtg}b~l$hUFR#3Ezi!-D!7BHl6n*ix?PwfS^2 zlh|RIxlO(Nu=%tN@B4pvd&}^+mLywL%*@QpY%w!4Gs^;tnOPQC%*@OdGn2)(B+FuE zX1e9m-7|BiHFNyq-S=x}eU()^GIs9B6_G0=-X6X5?cB%48n^Ym+m<2{&CEh)39~zF zs1w|%HC*jqg~&lqps&77Hz%=z@^k4{qg<7h<4 zr@hrtBAeno+dL%{H_4F-bO_fmb^67UQmIJ3j@a_{wOD6E!U25wG*NkUEq$#?n6g+0 zU7MxIfbkNy+qglc%v`KIkhoR(K8BSyV;4v#Aheo`-(blGYijQVq31gJShpG8lD|@D ztK6`b%Fo@PYE~NLi=j+8mGh0askN1It4fmfR4y(9`n-T@lp``1mji-LVp@~s; zi`|q3@YyeJdM`k-dFi-(CFEsaA?@PQIE`T92yf}`$VK%4X)c%eKo=0}!UCcUAH)?R zr|ndZqJsi)Y^g6-;ToEl#zsl|7v)hMdw6e3c*2@ zI@y5P!4ST{Gj+H%x>y{Oseh+K4dlT9a#>xhFhOY%5YX+vjehq_`)*a&DC$WhSj-5t zYrp*#TY|wClBy@!u=_Z$ZwmGM(h%H5Zdt!d+QYa`z(!!kWQk7B1+64^QW-~it5JWcUpam>LN9;+cn8h&OErF zbmanOeqtdK2ber^xNKFB&r8Ma{&ztp#(fTSr`dOL29w|2j?rU72hhg6W= zTQSdU;BqJz?A@P?}=WFvldmt92~k*dvKc# z`+33(!n+yOG#oX^gV!WqA#$`>V4e<@ zKT=VsF;HEI+~~oegQSeSJ04I>PO#|8`C#o}!W)1U>C&E-TzD)gQ_YtZJm2!P|m z+$9hm$K`eEMxMPOKfP%Q=9Bn(&_TOhp@#E|QL9o7K<6F09SGapgJN)f|59sw__6or zJ`ocaTQ_bdj4wt0Ssn7ZWZIZ#n5Yo5W*D56TV^C0kNA^s@j*C`$L*$}W>V*HE> zA5t>M7cOlY3Pa~6zQhsA**ZOmfvc#Zoq@DBO|e8~kG$`g;jy}Az>e3m*I=x3P^bvd zMtuWCzCmG#t5J((J#*)9dtQAGF3x!xAqtGqv=hVfQGxRd-|?Z_^Qad6ixRZfY8pO` z?#Qt3)ke?>ABDgkEB8kF8C#L$k&bQ8(pkIQ(?u)ZDQ%BC8P{KTLYh8DZFivZ>haYi zqI*g|`iXCRvF)xYjpI*c!0`Sc-CFW7JQaebt8JXc%fz?y_nK;c6;_$m>DMZb+ydlhjtWM7kStyR+sh8~3!Z#yvTy=m-kVd~zLN(0-(d9wVDQcs#+=SDdCNyGeF8LayDVqpde% zJ*uU-lSle=L*&OBV~ft{Y+^0VCS6rMSW;oP>r3$YL;^-A(PVRUujI^jw%;f~vb>h9 ziRe7PZ&*tb6K!^*B360*1$qrn7I%ySIz9*#{{H8nkNK;~1&2E^#pxrb0Va(G_N8;> zLH<+^Wt~5b@V?$-Tm{Iki4zoNgQ9>@9(zFg0_nN^9f@AUwX%lyE?~!@iW=^#r-wDn zlR;u8u`Z)J7&Sv{ZxHEPnPWrbt7Q_rNKh2;e^g=E!_hpPij&h7Ae zSH0Hb^%)zWXv7sloTrr&4TElmdfX&&sq~|a<);kcH8cnG!LqhizF*HgRBn07+_3sS zyk~u);I5@Q%O|;P=@8nV>F!HhR9M?q{OtVhAHSB{sp6?Q6e;R>qkf#uvQodT(Mtn! z#VkI5SYenKGi-lB@RjF5Z)8$7grMpirtmUsMSj}OXyf~U5f=6u2fo?EHtbtEta7AT zdiET4nN+cy#Sm1+T%hqd%Z9X{1^*?8D@SwJP<*S>KqF1RN`_o1S-qng z5`9=_d;uqtNKToti7iP<*%Mf`p^6HabazxtDOJ7p{Is@+Ie_H2XrWA?qTzGAut#f~ z2yV29LNTYT7mJ#DFTc=B-1sM4i60^P_zw$g$e6yL8?c7PHZ-I(C}}A6lF|ywq=c~N z^Y?id5nTkhs`=I}U(N|Aqc|q>%O`#e4F$ZKSN1bD%8Jg3>f1{V(+p|#0Foj?*0`C$ z(1`s!b_hmYFpa!ur|YeQ6~_5^q*+a9c{tr?Kii_1gdi`@hx!?q3$75dhuAeSAg<g1*Fo80Rba#?Ur*B^4Y}d0i-@E#fNPUc{{!l?iA7*(Fb-;o<-4-;Hc>p zeJ`z$DaDS_*kr0Zln27=6C}@_He^n31QNa6iWaLo`;Krl_QTV~K#>A}kxwzOf;}51 z>m3iotm$9}$k%VADYx~%=z>HHaB&cp{nB~{HTMP|QlfJT%BC0QSK=zx5~fmn5)ovo zIW7adoC|D$fz66%P6`94h*bJZxq!@3!hpWPZ~1=Vhd)Aeam$6~Z^6`&@hnB;aK5#H z_z{=LeGgs?oZz>O(}uvN2)^EKb3C1Tl~$aS_>m7LqMkl)d}-*^p*mk5{3*|k;TH?; z?dk)%;hop8Q)*ifeqoLtUXPOryPxON-KVu@Y;ahCAQJbh!`qs(+Hgpe>z+z{EVeIK z>)*XU*WLjgRRg1}_-=<9bfClVPYpRdF}eJrS?`-E9G9FLunPw!g%SK{i0IoT>i}yG z)y))OQfho(G`Bz!UmF1tSo{Mg5XLxkY9)XNVqB>w=0@`lpMhO2VI3nb4CXx6<$NZt z!tSF^zu;iGDC_*fc}(@!+kUE#l7w>Gf|f<2Gpl2n3OXfg*l<3Op9~NpYC+ielJGK$ zPc;V^TuY%&DL&VqK?iQ18UwA3BGki@>A4?xJORmd28TS_;ZzZtB+7y6j5X!ufz!ZN zI*q%N+=UxAL?2As*boy1!y)b^!6W((NB1`pmIUlW{J>0BaDro46?j0Dr6sScgAu+& z^$s+L3^K^ra;TLE;*sAn?=_gFL1S=ff=el*DX7fcI-C-C?Lb!*DjnI)Z94;>${+(F z5l1GMs^{nx=+X9M)jy(QFt6@mfaC4aGa2=ug3GQQn?u1>CEBl$g)4Mig!p`xhigRG za^_z-`F;PB5=hx>4__p^VhSjs6$Aqzo#xc%$JcCJa&89`dKkWP5v@Vbg{pISCh_ym zw9JHrxJlp4<2dw%U-ePaN%ir~gsw=(C+B%hh{h-0Us*j8RRziY6U=BZY4W~Pum>7@ zFtZZ_%I|vnr+}7^3XzELoR$EJuGLFz^YlAIX9d7YFo8#+w0`xbkke>S&X8l(baF?# zSzo|0mku;XTe`DdcGC%$g#pSK>++Yxm*CDadV&P=K%pWqHIKC(M2Z+I1+lJiJ!l9w z*#9AhZMizk$3#1vA(>a!v;Mi4PzMU5WvThB%jYU^9I?dnR*P!Wy8%hj#uQ3~_EHiV zYw(LuGj?G+Iu5Mt4z8Vpy6NhJNgW~f>9m$O&CfnKV7Qq_9-#uE4|vH1Xn;CC{!dE| zs9|PaqCtjPBwIttrEGe-XuDO@o?f)CEnGt2k*OQ`y~j9Oj2Q|Iq(^5fk8*KA>tl*SweWJ+3kbsnwh(Jmu12XQY$e1_os z-K;1rxy)w5u-(JO-369FJH4Szz0-6FeH^!<1oVoUaXQmo=gebISOXC;;FLsHlc$V0 zsOQuQ~ibE(F$6vG#)9yW~i}fMvxjiAT%@h zYpfa(#zF-#ax$7-uR0qWjumIhCQrPC`RW1qcvpumxwzf_`V^?oM=~V>=d+v&&u%^6 z-um<#!O@T5aho{p9>+QRjjkLBjP6XWuB|*Znig+HyZA)>LenA!UJlW25ObL$lJ-K`Y431HpyBHIOQFS>&rVb&CdkN6?^;_RUex1sL6o z^pg$a0tS0u6r%S!q>&yxYkk}h z7ipdO-g=2CWT`7>a)sq{Ldq5$C~Ar)T7XStNcb#;8SSJDP0MO;WmMa4xegEa)Jh(r z(2AB@pR$lkLPR7ddSqq+kxZ-(3c_zDPvr7TV&8x!ae}vpnO0eLgEF;mtp)1gTPopyytw5K^$eW*-i9hv}%uOUoN=6A3KU;G(0{U=ilN$(oBkK@ zM(Awtow%lcafH4c=>v&$;htk!JWoLAvi08f^LOV*aF+OD;0O;!!2x7)YK%lMF!SaX z1LM;;9>Cs7m;#_;z+g;9HAJ#8|m7bsfE&aB}%4MP>>*3**s0XQkO2PCIEc8}dM zk0so#*ky1SGm)DW_qbARKk{zWts}&ON|^OpnoL-p0MAlSM>vd2(o+i|RbJ7|-UU~h zc=fOj=7p|Ad1}`3__qj&iw<5*oqUuZ3(7c}%mdln*`Hlh4-dIO%T)~^RPPH@Eu*K_M6VSYsG?fZF>ruA2Kxm03A=8u>ey=0}ay_kJ$;F<6O~a zQfy^=xb(De#W-R!bGeqrb7CNlZkReIlr2$K_)s!wT!U{Qxvu}>iu!}AB@ev(=2LE4 z%en-W?y=H~u)3ffuYNyH3frVdN-{W}ebW#en%*Y+q8iSQR2Q^sRMvB4?|RVVUXMPX zH6zf8ST79p36e7Oi2}ajV8y~YWpwH1i7%3A@a!UdR}mM-C_}Z;25h+w5e}usj{#yF zlqJ3KAq?3LXp!69%UEGgAq+VMRCh8_?rs5o{Y783&ra!4GtH_)8>HOdt{&zlmE{rh zVeI>dC|Q7{=p{zh#<(W@ubV|$AQ5j?DTAU1$Y=~s3nF;oO{kZA{j`?0N;rSyw3aZw z?vPw0hhLT64&Jxtmc^!wI z;E^jUG{}+F9>lq<+cQO*9COE~|4TC)`Wpn0HPB|JZk3r7xYfe;4zZMD>j|)5{@dKW z979o$^r%XUYNp!wG7Z&yV#FmF4K;>V#lr8SnG2NSU5AtXTvpFq|5-v z&H*Xf;yo%W0Thd(nX#$ZFtTbAHJ>z|V5@llJ6iP(2`aGZzMTS2o6o$Ki0-=2w63Jl zo6Hwho(Da-T_>dHZ-KL$*a&nH=ttH&@X2_^gf-87?rJc{>(~s?ss4m=tDmWJyw1m0 zp9LtcM|Tp0bzF@$O>HAY$vag-BHEt2Q>E*!Dm0o6UJz?Vo;Kcb(EiG%@!uRYKt7N^ zcF?jkWWFqOAa$M9oGU@lh!u(girR(cE|Ca1K^f;5+ z=AWGQ&QI9u<4t;-W}v+;71PD%8{;Y^LYv$aW1n`dl9R|({DQ7bjv0LB0FX27N;w3M z+P|C=YSw9B*En}At#r19nPts`Gjg=Q6mR3kX-H|QW$3j(@U@*GSQIolsH-X6c;dpw zNqj0)^ZDTUu^>$7OXI7jda+6}e-w`C9`=SC_oJRVg0IWZp^m7;C2Q7^Iwhm4JY3cK z=*Y&H(`GdStA-b+yVvi0n6z#Ufs|V6!v2%XQ-lHu(`vGnvh^KMECPW6`7u~aaVB0O zw%LF))vqDy7oxP3Rk4W8z%iCfNPAjo_Q{`&hvK!Ne!3e`Kd(&Z>_~mRXL|A|ivJ#g z)PRWj8c&mKijHV3;Qu8*+;nX#P{PZHqw%pxtnFaCWyfAUxm3=tDdCbt#f_8O{7n+f z?K60Xl=ZUkwJe)nM z21%Lwu9KFcsiv7nb^>DyCpNlUKZm)Z86Ar!Y|`zwB`mZ-NyioYLv#$X$Z)z6`7eq- zW?JIyxpMrPD>;;J-(CF*>72aasO~bf=GXhi?^`J6rRvJ8F~u6s8y9FPC7~z?m&60m z^Kc#~bBc*O8Hzukp!0Fd?1x5E7BFRKVdEzf%$qW0X`x3;<7m(H2KW!+qp;4PY;4O~ zapT9bp_sy76c^yt-1ZAA)ZaBl@#05(Z0|nD*~|aTe~=wdC?FV2fARfpbOd5fPKS`^ zd-JWjy{9v~#`cV$lx0#@xV^u)i4`;fP33vKSc=I)ZYQY&H)CE`P-pI;<3PGSVHzSh zJkdqR>Mt25`?~(0%EpNwr!>{|tE?Twx~L9z&|G`4cNZl(OZg6+)@FaEK=~MUuEFTF zp^lJ52yiv(n#^aip6fgraKr2;`Bd0_l^M!Ig}SY*bLhgLiRY~doKR@iHb{r!Xr_=K zQc%P<^(jlRsZKbyf$W*?Me4Ltt%-s&5<>IZq$=5GUWro&CjVWc7Lt~F=_Q9`KeY;mXP^8nJ zVeb?&mYauiV2||L`_Wr-NMJW)_Y%T;n`wnc(m6T2gF>XRVE4+bl$FZS>y)xl$6kIV zi7aZITQc|vZeD%vtdw$dNh&?U(lK4e8=Z2B`D&?Zqmw^}TWY-GKo0`})jtA#R&%cg zs4(u0@N4G0@={9|9)wYJkfILZ?SfM(X)!EqPN)Y{o2rGq7&v2%N~f&M5NV5xEuphv zi4kY;ijBQDH>Rc_As6nl&lM@C)DbZYB2q5mXPkUI9v(xPu+z>08PK2ot^Vt?h8tUs zg&vcO#)&^ssl}2M5%hTPI@M(7i3l9L(TpT(AlPQb=G%$xkWNGcr=6Y;$IRlziFVv6 z8k3|vU{*QNxUL_8DY2yn6^}(eRKpn?knoIoO>c092rX0xop(NAa#}BkFjx`-%fNSu z2o))&>}m4UMlaZhaGq44l;XC`lRToI0XeY}9!iOxu}`E&&G?|rNFcTe?W`=XMBVZI z3hRm&L=MFa9{IRyfOK^kf+_m432R(*wF?^v>?`l&@Deye9RJ9!|M*kyanBNCmE5c@ zSIZT3+%c}!INOj_l=y|fZ5uB}U-?4wF?dO|6z+%bc8n@+5SxMJ2Y4jP`V^4`K+d_I z0c_j?iUDSF3j(A-)tXyWsm$$CPZEMWo!dMUl-LOC?D_Rqbj?97P5b#1GGdv><8$Ch zO`IAKkuvmSCzKRB8+KxeQl9}Hu@Lu?yGw%L;8ndg?Er-{%FnzPb9J2xQzr&(>VxW8 zWD^!)zXTUcV3%&MNgS=Bno9W)&&k4M7!?);#^6*AWQpA1gX55{`ysp%37kCCkX~Ca za5eUUMEU4GEK*Y05c#H~=_-j_-g;loU}Jtb*HbxXzyT*c$x&lG3)Uf?x)%lWMhR2Q z1!nuXdECy<^SN*`SJEALp$BvH(=tte{SMH}u>HEX2jo8Ebp-rW9G~n?t0uwLNQ<*Q zsGTf35D2tEcC59idx&{qp@ABjeibyzBYiPBDiEp_u6o zO0FSQXb2+~7WJF(9OoJ4hjX}^dK~k7Am=?LeAGPbSNL&h+q!oaNsfOf_x=CCgSIfU zGjjwakv3%nu%caToSo>MY>jMe92o3P&8h#%vQ{**Fq3z&H3npy{ul9D%Fg_gsFjH` z5gX_4^NY&=l?Bbo!A8Ww$@y>mXYo&V&P2St05Uf-;AelakALUa`sW}4-vD^T%=DsW zAC1&qRE+GL=xwd+T$})1{~|X7@>?^CxjRd!I0K~ptFsXEUzdOIAphel7)B8xA^;Q8 z#0Vhl@BbHK`5(IhM)RNDSpUavObh@z<-a-t#85PH24vs1``sV#NyXC0)XL7{pPv*R zKbfeQITPs+F)E6R6EUg+$mK+gQnmmU3jgye^3SUjk=|bd{%fC~mF4fVh-H4$k#oXp zM(&)d>51b-68+GH$S;{(@R_z6ja1z++(%K#I<%Y|KQ3AA_09u}0TX@#u638@I^H;L zIr=m!>|g41y|B%V5*4akkq$}O8L`;6BkxT8-cR@ zeJ6pRll1+#jqjTUmM?+4fzdv`cn3bj*;nQn_Y#{Qt6ZWy&q<@6F^ElH8<{1(k!!%O zqz_%^%m)pdqaKT(WMmFmV^%p3(@HBz;Le{&zsRgm6^!zG!$SbCZkyWd4i(rjE-!qE z#tR+!i5setrD%vLnSqtS$eQ@IA%?^)`|EjZB==6HZfI-q#|hGPRu|4#YOs@_DPlP$ zmHMAMmbPcwGMHvHK4bhpjcb;0o_c$C4V?{DOEY?Qu>yMUrO+#jXxCqVs-B){QzYyL zf!cP?5wq^`0^5=T2g2vMRTYf~H4W|QPDhx|b|6~f)Ck~?^$rC421RB!(AOigTL(7v zdVL@-w~wPd>1gh40!!Y-1g@84PRwKe>G0WnjDLfMu0M-7r=;@NPXn+q5?dg09$ie7 zDW>waKr!#y)-A2CT~JYCB>tq-R%Z@MtaxP%InJ(epltjYeWbkJSU)Bv7mEp)`kg@EO9JK4d zi!B|-+7RH1_e&cI@Gi>?tW5xk#*3} zx1(HV>|i;{@a-u8;VzQnfzz4Rv-{UV+{@3kPbbNxu?Fw=6Zn3+uoNF%M-@*03_k!~W$F0yOdhzOS?R=pPTIJjR0S-qr1UChnDy}?Y-8X@D903#kJr z|AwADe)+Gwr*5R|#YL1&=bzi%E$UGG9u1H8uQ@quo!zZGtzB&o-X*Kg`IAHCaDp0? z14+tk{3-I$<~(&VsLEkpnUkFji5VN;f5J;Zmt-m(eLMen61tTc;UTSgy#2dv0zVta z>AV%viU^f@K0&R5tN6`F&=?^jvV_DwWi&^!OL)F(}5NH7H^>&>NfzjJx|Mw@{o3-yJbudJNWhVs*3OO3h-4#dZ zyxsbGHS=F27Tg2~#wnC6?V7-JH*cEIC&Qd%Tm4!) z^^s=|?~7>dvWQbe-f~J@xQ{VOXqZArUy&-(W1_|n^sEo^k?Pb6*|ImpnudJcTYM(C zJzQgoTbzKPGD-pFqXG|*IIF7%b+qu|ToKZSgTj!mdCZ|UDFcHmJ?mL zBw}-Z*t#UKvkzc}dlA4s!5V3i;FQeP8{TdI9L&3)-!Ni8A4shDwK z1E)^DGU+$_rnV85*ur|3lNP$aeloD`c90o2C%cATU4LBU7%#(j7UHAu>kX3LIc{L5 z#pEj`<_lbRMP%RNnC@r5cQ5DmjPY2{Luqp+%N(|Q-&HgxhT29{etbF!3-gTYGi)aH zCrU71)YB8I7Npw zcqddJ)|G1aNhR-WR^GU5_rAcs36IAMzjSWiNQk|Km?A`49)H`)YDpOqOPwFmThh7P zWtIh#bkPNKzHEVteQbf+2XjOwLU%--mf9xCof#1mWsDz3DvKYFm8VD{R;ElL&QfF$ z307tx)h^R5&rqhtMDEmFg~}JEPa*y?zB5@etAl^oi1w6IoC2sJ>*UC|IBhww&?&A< zc2g3v<2tWSmb2?AOei5|byO!vjw!MzN4SUW<884~r8MJ)aXS{K(m{}u<{%0k-CXHS zXJ)J`V^S`j&TPk@w+5(vrB~)rZTaM;U0ri?c= z_hj+K5u!4Kxkkqc{1=(W4_-~elCx%BRJZQxYCHAjNR_%P=&y_!EAl=4>v+kZaB^

E6$PUW~4v+@N9y(GdQX*Kg zNJAl0)|Ocy^eY(ecVy-IuSXyMc|R@yDE*t`beZf??eINJP@-PNEy(wr{&x}iXt%Gn z;q;il_zohjYz$4a!blspFzSo#Rb-XrOWoi;7Jb0y*(d+@!Zzy3fOC!LaD(2I0UEDF z78fR(GM;3yW8lpX_X*GVJsE!=ApDm;{{yPB|ACN7Qg%ShQ0;r@uYyIjlxJz>hj}k= zUqh7`K|vQ6$%S|FnS<@`mBts_i!4G6C3>b_NAB-0$Tw>0c;EeIEtsHdif?#V#uE^$ z6voBJvw`#(?saI zRSG-2?azSAsxJb4?5hRmIL8FSkabkfc4peJX_~y&nLHB(6MMe$%WiyFRmJm_9~_q! z__)XC74@~Bf+sB-UnmzC+nMzVL(sV1V=V*TnSYxioPRKl<-P%?F%cZtbT&0F$od<< zQXz)R+`&8-Y+llXqcu#gk#ELv;oD!;{9rQOAKB z;QZM%tq^3z5Huh(aDcj_;ML!|_dCTuIR50`?Ccu=D4 zIt#IJZh1Xq5A@~$|M)!-|7+mmUlxY>Pb`e0Of@Jo)bbu$mtc_~3e;X&xo5_z-xE`5 zB=V1S!i%F+PC!12dz5?i4ztQdCKc~tW%@!_!y`eL4c$T3ZI~GSaJl2gb={^`slsX^ z5fW+AWk-<|#YSpwa=%aMI&IX=lyd2Ib7MX8o+qq?~x zF@1*-Xq|s;%&8#X@bz2phs$&h-Igw;iMBD0#LlJ5K+CZ$&76&(P4a#yjGZJBQq~Q$ zHj8~ZNGSkCVPbBk6Li(c&m^}Rp6zCJpWP!g(p8OqPeEM&{(iBr|A~T>Wb8!$Qjo4; zq2N8)UfRcbF|RjU+u3Gl3__EHpX4eeJ4H=J$m`NrQs%bnE(z91F+}NGjPv>4qRwvwhZkj%MmplG*B~5RgXa&TF-$vq#5~2_ zd47&i;PtnBT7rClM^x&l=L&h{0XpXn{5XFyIp`X*5WME(7X*t{_h?#BdWdklmX_Y2 zbst1#)}a#~h3x{>-+Ak87nw3Hba+4Fg-vj91&IJissHbaWM_IW&oJ8`yp!z8JhK@> zP)FS=`ykm`tK%M-qlNcQZyX>z=ybKhAhRHlY3>ok`pywN$s?XlYD zs)d9t9JX68nhg{%$>MY&OT%4+Fs=HcWW^E4Kpnb&>`i$lP=~Ggv)RfM zl1m}xgSYGS$1uXONO~&w$7em)R)Yi3JG7ID92seedhzbVBCGBYstH+XIyl(@>RnkN zvel5uUL`pq3!cKw=3q_ph4wDo>M_rw8G$yut1TmbBip{F`Y{=&&~k- z!C9lgjGE1){K;?D>p6;L{iCd&jdFz-A+Nru+WtPIL2Zv^6JNtddRZWNgitR+9PLW20P3!VuF#&((|2yMQh=y`&wG^Ystk>R!7QH z%c0%*kRr?-bGITKhZUkZx?mM5vwO zz8@O&Pr_O!+hDj$KY|k!tWd}xs4p#-%AZy7E=}JNYA-kwzNh?m&=U*m-=~?#WCuXb z0VcTiC-mnYpdY6ll!Lipw{Hu|V`xx<Z#0l9 ze-lrhTR^#=S!vlSi4?L6s9^!~Zc{G=<7yJ)*alY8v6V^~7RRjo4CerNq{xR9t#^t{YxXE*|PZ z6xyPR?G)qHZwi2IpAhAVRgvG**gFV}h4oJin*vun7%|+qM+iTY8rHI4cS%VT$Kr!u zTYQ>)>^br194daAdm1Tet@-e>wkeVMx{B;z_iZC0YWdwd0ZC#ctWjv3{g28myX+Xu zH`k;oO~^Bj`_EeXNQ-^4KQu5b7?#0JtTG3WiP87&X*>ftg7S|&&OmS+h2Hd5?g_-&_sNNH zp)r0a8J}kE1RHd^Ium@QLU9sK7h*sq{&ql9jFhfe*-((HtYlxtU$S4Bn5mksN6HR&|hC3e@bHt%?<7cu87=18_=@Daw$UJZ^=7Xf*dg_A- zcEU9~R+prVC?|eAhlJOsTYrF9IKQLlI}0(xyOc7 zMWvJg2{wNisT!p>aKzlc2pCAI3mfA-k=_Bjtbek;iz)vDD0QpY2S{$D#9lR)|2En> z8M5EMtwS5yxR0w8n~v4Cl9Q4xBr5ojh*TCovpJHH6yHlhgS#eu8McV1Su~Yy{+DB9%1R+Q&+O>Eb$vL-uRnh0G-*2BMiBa z&a~Sx@){z3bs%k^QLQyY(1{t#{M%y~hVGfqo$)Y(KSt$VS1$rkX$fj0_z3pTQx0lN zAhotgslI|sPdnFqn*z0i2RtBF1SZFxaB>~|u9;P!WFNhKvFOh)w1P@ng3lx0U3*uV zM}5EIKma zDRUe=@ZRHj2k5i^!Hi+$Uwii76QwAw|@slfB1t{g_WflFkx%ifKfs*0Pw;b;xA{gt1O~bm;qA~ZeZ-UL)b{3 z85nNipGstlG)ROYT9+1qEsCEB95=o$4GKiQj4}F-K+NyJQMNz881D*{jHJ$hDN6@A z0Wy zIUa~X+(|vIGE;|wC>K>18hhEPq#LD`2Uo2`9|;6An8ivbJe&0~+kPxc@rQOnt?!#yi_|Oa0+GY+xLZ?gSk9i@J2rnn8O3n|n2Z zb$Gk@DRi>cFr__6_Uu96$JFC1C;_$k<9oV%2PiUg0QQUjE`}!-%Yy<+3@73xpGSI6 z3d%oa&O*&`_sL|@M!9EBlPIViHE{lCV8ni4SQGgQ_*oU0g~{^)haEf0HkgaQdf}F3 zqOwoxpjDFdg(Zg*Eo>DkzBz(tVgYt85;ywlN&dED@#*A)i2aShO}Ft1S4Kp@=omiK zw?ma*4;(!CZEd5kg~Pup7kp`t)r_pPWX7SJv)auCp?|4x{jA^jxJQsA>cZh307A^F(&J{!03C|Az1WHvGUa!Vq*4j{syUqFNg@M{Xp6lPE`m8Cm?zKwLc5%*oFz}cgO!rA@8ul>#5cGa z{cC1;95YJ%D}CwA$0SZfCRCM~B!`N)fJ9UX5eo?oHrS$(F;8LkzG$wzw9bBeL(uVt z;KHIRS%FquTeOXR4@907x)-UFz5r*>zqKEQ^9OnUE)?;YU8{3n4@_Ale`fbof( zr3b=-O;6SHDtyijbAGcXF9C;3Wg4Yi!U&3s5|K4LPBqyeS5>IuCnIfclj1@uQ~Us? zU?~g7npr5bo^;S<#@p=9RW%Qu6+5z`Wy>at{f#%YpyU``{*losp)?8G3}K{FWkr5u zED${vbKY@ns-?;?50#*awm+X|Fx)W%+v@)1tnh=L!7q2F@9z!p9q0ilF!lGZrJPcG z6~LcA;tRpx1i15E9t`g8gJy3Wg_&Swq9SNgqx~vvrej7v(&Caa42ZTkGB$0zAB0uH zJ_nXrM;s8Vy%0reVAXn4%Y{XQwmfw3P6bEX)(NCvZk<6f+b-N zRb=(I>Vt7=L16~Nj{0hWl}H08|9y%^}qcohge%pg!HQ#Gnn&{fHV;c=1a)V3ZsNIIP)$7ZBbI6h zPf(Q9y}sBlZRV3#QKmZVTj)<>6yU)Tb!AIkQ-+}vcQ6Z_!&mUKfgg_E8R=iCGymIW z7a+Ry_tS)4S;ldY2yWR4MlYB39&(%az`4!6^Q|d9K};OM@S1riG(y^2i>SHa$3S!R zgkZ=70SuQ5ZZmB(EUfrNMec%!LkJW~{Bz zYlW6(484qEprWLb?uq^Sba{HgU@|$RL0Lw(9OO^J9933HKaW4nmyXPW-d%P)+zkR0CQA^Y|F7L9@^a ziLsk5n#+=7#I*QTJ(blFN7utDhsKG2<Va;7; zZxUl}%j?_dWuL0yV8()-AjkL3wT|$ur>L5}y@zK|14Etg_mub!h69{e`Fk@U7b}Gz z0s!@QnSGe0!K^)dyxrw(mS^2nB9JZt&)Y=yyu8y6WDL%x`%y8p8F*Vg4MZlJGn{Xu zE&Kz_LM!?7nklZsOA{zgeJso%P2!_Vy!kzd!@5u?rYVG7JwzmWUmn!2v=XkTnt4{f zv^AO=@a6YJ977G(0&Docv<(Ny^gZa$ZKu$Xo1lhW1{{(obMWLLeN{bnEdSiFl0j>a ze*HWna(V*(m6Uhwy>Y*T4?q0DJ`?L#Hf4Z=&H;o{Y%UH{OtA~|ukBJZOH&y09eZr8 zbZSjaAZ!ZrT}9&5P&@_`6{lQaL9wA?L!5GfFxntmc%YHVRG8C!$17D#rnmQP(;(H>@!-IOQQd@x2 zd4WY1W=fSrFbSsTi&Us;e}VCTZni^QG5H#h(nP!$L1avYO(*oNObivnc8ao)y&K@- zt)`r;jHnb1C1V9Z0IPH2E$lCxC-Esz%s8X7%vZ3FV?m>ek?=mm6n{rO(q@}wL75*y zuKWnv!Sli-4+MnjFb-mxBc0f=J@BdSx&cDt@fA2nLN)o{6~qQe%l4nNhyR^v^#5Vv z@_#4ny8$x)(mS}AIa--H{V8pq9Z>%Izti@A*UDxCq%QwoiTmvTNDltriTiR)MC`1; z7iqvr06Atr`}eB)yUhY<|6Y=Qw^;%0-^vi*;T0sxyU|JjZGf9%G@zyUCzfS!Lf{yLAq@xOHD`bX!#PA>dEJ88ho z#LoH$Va64`@p!UfhmJdq>o{InTXAvzFaAWmQ4|C~eIuZ9kXS9=*ce2$fr2lczZyKv z+e%2So5ad#)eDgacGWFB#Dj-P4Q_TDn%{0xKCSvbJd_OkJ$&2vc9qlR;TOAQaM3M* z-+xhazcwYou9z^T`@B=Gc#GtY%xm~ zGqYqd%VK7hEM`WFnaLJ2Ggu67`#(83|EoC3e_z#2-n}_e)$G-Knx=P8_nI}mzQ%DH zlw>qP{;VT?ffJ+jMABH|2u0%&uB%jKZYNWcCk4^eXNT|!?_Ki;f&k$==Z_y1WTxX3!SF7&_4K9STC9Q^d3_HF*u@<}C@?4$1fS!Ek$iy7I8#e~6x z857^NuVmmSb%PgCkVEQ%H*Y(GOo}O_O55I-Fnzbs)siNzG^Rq4uGZ`J2!qw8S^L0b zjm&Z-lH1jZAE^ct^EN z=-y+`eousK(s56OH5EI?Lwp^LYWe)L)xs?X(03FrApc4&8&y|(5>{)55+2Y4|1w3)1*)0oyx7QabsURnK=mQvMlCVrIx(s)*+g}z&zbrm$D6i5*6*M&8CvV z4HwL=l`?@I1Qa`soXOA26*Ub$ex_j`BziqB7k4V+$vsY1!goS{9hxnKZzQ3gdX_w2 zHpsNDx)0GJme#8Kis!af20sa|UhH_&y^ywQ2&HhSKm%mF6pX-X&(OjHevnd*KAWCsBi ztRs!-U|}Izjlr(>SrFQrys<7{RfmixWI%}h!nEMILt7%$s`((yzHQI)Wa?p`wT1-1 zbwhJ;8aMU;%CA(@m6mUu-3L>oH*o=-gx5B+beUM}U;F0WkV4khCk{VnQlUMgG=_6h z(~5)qcrm$%&4p>5B|QnM-8`Q@(^+A;kp7JDY{xO*_Cfo=^5?i3m?GNqR{ayWOxPydl150Oc;5MRMUjV|eZXbdua7LVA4!$7 z7umlX={5~%+|wRplI_h96a>}uy*)s40h-1CMsN|nGC7j7XeQdZ^}J@v9%2$)v$^3o zrNTt$ZSk6>b=5PfJ@b3}9aiy;XMiDl^j*MZ%~UBDY$j~oWKAp4iAp(-EW@sWW2w|y zp5Kqz<8$MzvITa{JT=v}q_~1Wth4i=8ot4!#FAZ=r_^`h`H$_Z1o{R}LW`}Nc(E=r z<*FHlTomQN#Jjq-dNm8jeia#(KV{U!0+dd6j9m_0FcaDxu_z-@JBVU}7gg9VoEU?` zC!kf$0NraIx@kV4pUoMj6#R;mlae<}|3*$(zT0uFBgFaLaoQD~(#fjRSrB8-BG2_b ze39Os!JQ{56Ec6Y8+v-L_NY8L-y%hO+1i>vm8X$wNF~Z0caH+DO7&bo)BG8h)9qp+ zx0UD^4v;_|{9p^D3!4j3Hp{?iLIpGBveOw;-c~e2 z=w4(-HtB{Gn%88m*re^q}bKi&*6HWQ^&*=tEdGpX5 z-+5f@*Ai?r7|y}dg>LfZu(>XzUF;dB8%=--h2t%(1`BPy$uarvR)rH4N5D7R-4zzv^73kc zj`1s>&z0vsb+at=loFSwKXj;E0wx;e@iV{G!;g(fm=cgxaAPy_ zH_#l2JXwM_6-t=T87-B`(zd_CRO%c03T+ zfl;LoA??*csaQajB&kK{%&U<>xjwlj1oc}3x=JQTdF-9-zN~xohGVlJc2FP^GSPeI zcv(VYUz$m`PRrSx;@y3dCI|M_i@?PUc3vCfd35Z}f1aoGq`Nj6qLRsr#e(?J@#>yH zW}s&2!J4D%#P@bxp`&bge^Nkr zwnX0FvNd_JlPPj1wX6GcK=~=Fph#)!2@Rp$AmsIc0o&)X&L&Sr$+!>)x=oisZ?EM! zI8q26&D9FP3srj{p$UZs3lLS9+;8+?0u}yv? zeO74cY#U&-6FsL{uLNFnv_vYnvNx%+s)~{6p+KQy&~^Tl5F%P#fukW=x6wVJQ}*zJr)}9 zUGmaqAGe+*qK-sn3MfwQYVck;Vk3VIa>`amJ?bWM$bGrbQ0Fk9c?)7!`Lod|&PVja zuXaD`0WDL80MDr@jJTTK3fe>q7qqB>*)$#Pt_a^zv;8&=2bbx7BDqZ_ZF@i@Wk5ZY%fB+kpTbpe0bf!cC3$(zwpw*^NMf z4^FofrNh#r)09cs8}PeGjrHAi$dAbrcb*3EZGl*rD`@el(jT*^?8&x<+Ucaaf&}#~ zsDq0~k%+fvl`rmd(3^!`2rChf$XhtN(cRst;IS$V*~saMdgdY)Ssv%hgpw=BvjKaU zQ-<3?4+-#f?S(bxS~YYm8we-2H06K$i0Jt8cnSK39gPUwx!2I3*Fq12y}}Gws{m|) z|IB%TkmKXxeq$GQxAm| zzK{EB$lrV)PR~AldprC1?eVGo9`WMsdhO#yOpdqj%l72}{s2QjsArijL%;K)SN-Ov z3rFqSaV5tJa&zjA;$yX?<`}Wt%e!<1xWl5%>$2 zGF}6%mP=7+Wt9UfM>RjJz0#ZfgOkRk`aVz)9ec6`3-Z2pa?%W;g;pg07_@>_OCFawy zMl5}z+AsnM%ajFs*&Ag)^hrVf5PJ4-9gKX=^^@<01a@(At~OeZ0UdsEYV70pn?c06 zfQ1x>yl;m`>2Jd|W0wUbzRHyWJs64U?=gmJNAxHzrK=5VQ+r;Eo(Z{(pS8)om%fLT zi1B=XVWZf)cq0UFmN>F+t--**S)8i#vF(&w#O%y6_MS=EN=zy77{+O&7|dXyu`TpH zCs{tC=WSEk{(&=XRVDp_1VV7YkXX zKA&;LIkMM@DK$p=8uoEM0kt67&IfpGqi3_3ec^=3qgwqI`e20 z5k^vf=C+VRBaxKTRu*tM>SC#>2P-HXjJg1|5-Nk1eWcRVM4l*W6&eabJorF1!stvR zvC&90hATPx0jM_)d>AG>E} zlYK8ldKbOoW634#Mz&m1P=| z;&v7zMlev}hwsO?8|z&07U5%~!AHd0@|U0*3y2DB6oSCM%VY}E3+Y@OsqbKGqh={1 zCZwqg=kKa*8&kt24dU<(E(!yC%mtKafkVnM2h-{#LvPofF zFcA+~y)T-IZ~FzYygLV-;7gri-!jZ9TR%%CaR}@@FS8{sr+LvTBXyhrgojhe94GXY zg9Q~ff}=S_=wKAWfDaZwzc^RC?2fNS3R6q2(Xj*37O@GFgqr%QQfSsZ6KHfQgs;-p z=w^gSu$6^=iEQc|_~NoAQq^Q|PGcbiMNA(qEXmJsv#d#&U8cCcOl3p!_#Re&SRe#4 zq^2zM@k*k}2G!h-@^Y)admIV}U{_@AC|b0{S}41sAG|xY+&@al95ZVXXGgFdh7c5} zzsHk1wMIP&IS1hGYP|*}s&o=b!wWzX_;J%DbZrq81Y8;bg=fM^uOalpoOdg2R&IJ8 z3bpc(j=)_cLJ@t}bLV40rAU_zxkxLaxVA>2v$}*^i~^CW#}^CAs1}0cm(Nip!h0y4 zuOwz6yCTC_bu;|Vr{Cbd+C+s#b&K$L_2Gte;^Z>hQkyoby!$&9C4-c&XwdA@C(|ov zi?GOuEA9}OIQz9FADk+UBYrMiId<`2wYF4d|Bps59Zg7+c5vL78h-TFFnJ=TNq1l{ zs*$mnU$sNv69m5kt?UzAGwVO#+ov(u##<1z3L?*_3)A#N{_qeUzDffko7w}ToxyB2 zG<6}x>CvJFK}cmqU}E9*eD&ah+x2s zL!+%6Uu@+;tXajly-c`^IBw9SGdy?dv1r(67OvJ-b&Qp49+*)bJ@{-0Kk5C>paTj@ zzs11#H!OBb@|B%KYH{jmqdy8z^L@lVB~@p_Pe1#;nic!*W7b> z?SX%xW*JE@Y)>N;F2ap0a4V{m$Vf$Wh%Jip*l7Hb`!$s~gPUTFh%9oKIFbhW3L2p~ zl^HjSIANqBKtc^MB2hf>%#J_=G?Q|Gi9d!#PRE3y6qU=>hb+}+sJ37ecv=#1VX~PT^>%ZqRl+ja!)GmjmNc=8 zB^1s*SO-7&OX7lAKTxz5$i@WSVNQjgvauS#-3~BbhE3U~X7emNqCG&3w-Vkq!Dl2Hg6p6J(%2GFNPL@~hKn}~#dn6#v>!S2$Ozt}bj;xC zs!2Q9lys|z`lHT|#ogkZGK^HgHIbFsMENvKHV&&kwuvBw%#e)G07)*Gs?1+%?Xi_| z9Wjnod_x=l0(Q`kdIvvXCFZgItmQe;Hg|Kr?nTl7_X3L89r;la#TP=Rk#Wle0eqvr zKcdjwrd85A+s9)D#_45ebhJF$Zet(8s$xhT@$i}{xxu~FE9NPI^2hTIc_!2jW=`B1 zCO#bqH(EUNdTkRw+ zRl>^t{dY@q-Y6SA*{VLZDREn#kA~fY#=Q}Hu`Q&FL@slu{kLDO+@NTL-<+z+w21~D4qGe zMnf$59unaf)F9qRD22|!r*856)M?kXd!@Cu20Qt5M&YthmnSzLbI(*7O)OgNy*1SYH^KkSh0*!z2G=9%%V#O0Waiym3q+;yP42Bzux!Lx z+ft73eHW0l52nuuR*KqXKLuCdkGKzP%5}{MC)+7IXzv~BI`MusOwn46Ixw!|T)teo zQhcE7$m*tD70C>-1okTq*6F$FU4iC3=$I(IU!r8ZfW8>@uDBGY<4qg3$^T^lR5}OC z#@v_R^f0J`j;UV__6pN-FDpA`F=`^_V;s-wcAC)93oUoKZe9M6-+o6(`K{LoZq;o4 z(WF}^tH()L2R9pcdvepor{S|I1LE36Ev21It9;mpglw~I4n2+>)134!KuzCkd&fGV zV)CxdrKxq@XaY?yJCNK!reGZ?FWE56-BhbMRPehtxrxtZo3q2UG4)9Ko~2*bHZ|V@ zoyMHw$}~J2vijjb-PQI(jp?mFe7% z?*)4?#cw#$d=n0qA<$wui}IF|V2U z);;QF@@k8;A^QQfaN7Qw3|l>5Oz}x&1!2DCb?7M4s57Bv(BR(o8V=${yvBkyo3By;jmY9S+2TUsh*w#|Z z^@FYmY97pntg%T@E6T&!S!HTw_z7Xh%%RJ`Nocd;!w%(S6J+%RE6LAjF-<$}Z0*D4 zqXmabqALV*jZW_JT);6bh0mDm}&8@91Lq^_>ffK8<{J5=1BY`br zJ>B>eygI70yvhfm1HF0zh87n1@iBZ!RC_(P4}k~Tjq>M$b#&tsg0kN2tO5Wdob%% zrA>&*tdo(NQ~!i}>2>HDGTCVBjkmxlH$G)?j?F7D+PDQs6|=MYHR_T33Q)3WE35lk z(#h6vwS|$beDLHn_skjGxNgPmG{e~Ic0xOn6&vjLu^ciW|ul&oRx!_1P!kOQ4&hC8whihYy03$RSm z3Hj+q)rt&OTID5f?m9=4S04_tmBY**S@dKA?Ur&_wj7_9nRL!(+C#Q1alf;}0k%G* z!^&<7)XB4NG}y!m$zeA^4asql02~IW0S9zA)Q}7*TilTH@M$Y7pRZ$ZXg>QYaA;L9 z7gku&qpYwY8N5p&TP1=S-8YJPOG+TTl`<1@$HV7&*L*D0uwc2+r_9YnemZ@<)hLGq z^&S+FZlU8NrAVw_*h^QhvHB3KXenU)jB01B;$}uq78g)k+7ipY08y$YBNP{Wc=(_! zPRk>TfRTvrMbDj#|G)#90;89M-g+HtF3-Ds0FmW1&{PCa@q^XbL|`v~2fZY@4@R4yJq>%YOR+cT1?oUT_IIh+ zX=;m|Xg^#G0=$S)*chBWv<*>FMBKxdhQ)>0%xvV!hW z2GYsDD_L1cK#w-EFYPP}0j@&Tr&<}!Q=9|UQxI<*I4jr?9Ma#?T%w~S1ZkTUnDlZ;9>R%b+Fms#lZM&F?<8c+%e%eR0WJl5~Mv>mr-!#1Q-xppir~D7LfhLRcn>#(2;T(WgnJod z-W^_!)kA#&k^16N&bF$1Z@zimoQG`)c-`Gqe|oJlyqTEw?Hp4t+_;f62uSWt`=(vA!B4P7x!ciMRFV?!Y1^gyQ0>}E z?}bJW%PXY|_4RQSs@`1Z>*_@b699<#dXI(pXokud5Kc0DjJ zX_0}<1z;Gw{AFBx5R0=e-|tpwT4Q*5xPr?0kYAU30xQJVxX$pT&f_I^SpxGpD!-O2 zXy2wMl+q(-;K%cqm=D;njzwPFtM&UC;18ZDD z@CbXU46oH=_xQ>&jm7@1Sl8*lwQ|L;FI$ zQS?3AQ?8!pDD6^l$>FeQCea=xgWiladXJ?A^N$+5RP97@V1%dt-0n48w4 zMTcy+JKo8Nx3^k{eSbqKS_IFPtKzBeO$p^X1@F`{P`!um#>(+&jI35qE~4?bw_cGl z=aLvOW~Btiak2IDvFSf6dN;ZwQeusUG87+ogukTqBjVO zLHDtTN)8mxTgc`qF_-+b>LZ#6B{iE*Y{&NlvlGU~?MX2$i;MZLBNjv}iFP+k3WCP& zp@kGrvkS7IkPgokgx+0fr!rXcRVNI$Za?{fX~qbqR>=?j4$TABMDP-Jcuv+r!pDuG zz6^`;3lT}AjNDqTQ})krXB-z^`Q`n%?s2pn;>N|I%05XfuqU;Z68BV6NwgXNOru@B zQ+*aCO#4E?VFz+~^IFQV4Lr)dY4#wXKP+=u+zk0eOPuo}1+!Q7$kQpKb^1F7HnBn> ze3WqcDF)Rp*K~{`wqKa|c16Torzz4ohCk-sEeefPo!A*k2*z5LvxwLazXfFL&7+$t zl$GKDqknNW4`9G*La-I)Sf=yHJqeR!TSX&O^B17ywKpmVX+&?a2s7alfx|2@%EJC- zmouXLw{|(wA$jAO!V?ryJgKi&0u^%$ncbW}xneIh=u%0`X>CjUA zT7cTa;1||m@FGFUBPLi6i~GdM<8~swW928qKDhcxw=1uf;dX;E@kRoEXv|0g|2r4d!zO@ zvm6AEM2Cn9j;5#@ye_~jm&-kGcM0#F$zLwWb*WscEn+OWy+qJ*(O>ns+x)70mLo$AkoFHW;m~oKGibCjEMi8WW;k35e_7zBiL4=`?#mCG zEV`>?bApaDxgANdFjv5?*+?us$*?K#A8Sy&nGy4sBMVa$zxaVd;KwZq2e~Fjt_t@l zE7RJFF^tkH^UM{hnM&G2d$13M_$gyARSa>PRe;;NILA1ko#$8ZP3Tat=!)XBeI6WZBokcub&-dci4$8eMqe|HT%VT>LEJIpLGn*#xr726B%V3;UHvjtVj9w# zx>Kql_OA*7%uC5279u%u?d+vvlG_c2`=26l8spC#Zs91=k;MDQSwZ-;%HTgnqJd8f zaXr{-CtX5TXgVJ9#saWD21>JLI+D&6d7<6TmO`GhsTE6ie1>ql1Gzz-P~sdNc@y}; zLQRM~qP8_+fC2o=)es$q_{L!hxroslOqC1)B#(7Qv2*;f!uf~*YIrW`QrZ< ztK18SA}1`qCqEiV)~6F91bY-a;W+N2G-!%f5zQM$ircsYC%L^`CXwUsA-71+I8JMY zO*aG!bXY(V$syagFzR^%oDtfE81M`Jjsg&>pm<0{7;|ZnR0)sGeA(9c6+lM?S;WND z2PVgv-S}#=tqc_k-$j?H6g?2lun92yVSJFtQ>lCE1S1+guBXM^d4<^{y058@~?Gl37h;><8xP4vmxsMNrrzn3s1Y-Vj`16*2?| z8lt`oU-C@PQXGq9?W;uB;C}I{=@0#8DijWu8;Jv{>EB(FuNkJV0yA&37Tb3iSXg|C zw#XgLIC)UWb@G#!kUed`?ML<1j|WF~{j4`0UuPSS$IPXZF~U#$9*YAN-+hg>Dl$L5 z_jp8FFwZYhX(BIh0q1#WV59LE8Xdxk5)Gv=in%s*xia&?Vg|~0|6r-27E0Y>_+nT5 zDI&+q$E(1bJ!6KW1riNu7hdGj%<&eq`dt#d(6RBe%8965$Ek^|9d=g)v3X z=YA|HB<7v_ZJW{8{rU3kY@_S#>g3()8B);eVdef}gTVLU=q%>_bxP~&mLvjU$txjY zu@kH~oe|E@N4L<*jWv#ivID$})#ep;p`aQxcm5XjhmJ6>WzQGlD+MntO5M%XM^O2b z8XS*EY0sl9eTKgE2R=z;Eure^`vUb&_w@D?MXuRzPJaUj(5lg_HK{}zkE#0sR-O`#?||QOW9MGx+C^DrUgEO_wFZSv7^+`%cU4~ zK;BSf@^vYT^}9|CSk0GS?TI1qi{kv)!k)(fLds1#?W0Iv)9!QdAKo8K9#@l&`Upn#T~aS6V!vvI!4~avwA5|w>_{u8B^^>|5Cb^TjOP{5ujwq&QkE&KWavI!-`ziWPPa!(h+@)+GVQyfz?(^Xvsa3H! zNa*YD2h|{MPd>CmClnwT^sou{moWeI|6qseF^n)eua5M)7W%W-&0lOGK+_Nb{{P$x ze}QlUP+Sm#h~UKT`NSA6rDViRPG+rI(qy+^n?W4}W!KoIyLf#R-{LRji@G1kpk?Ii zcRlA~XWL{WvGy10sD^SC=@%zmxJss`?TwrxYSF&VFCMxVWE^p(4l6A2;G2XTV3{!T%ko6BQh<~B?{g-17+1Y-B(%@$K&&NohXd>{;qgnO)}WEEG#vhEi)3TT{qxM=R3Ml_-+!{h0Q_SIHUg z%pPH7V{wm5Zs+jR{q!p^qBH^QZ*F_G-*_?p6Dsy!1QlcZ^NjO%%H%(xV*deDjP1{} z)W5daUzl>)|A#`w*#10e{k_5d2^ITafr_#HdFK0T=){#uq;_Lq9qe$GkFif$-$7Z@|StAz24k!JB)rk-)rDow)j|tYRLAf zg$HdFvC~n6kPQyv&`Syxax{B46wgoYS->srB8y;+@NS_Sz=drj`$3KcfkaOeRVrhn z&B#!{p|6=4;^`mE)B#svtB59lJ{<}xoh*s$5bfvxDECB_EK9F8Xse9<=_N68-pd)B zrj+eE@p@Xdei~LI+ymu~`$h8MV9}a5gvWOAI((0ib$|tBQeTE!KQCoRVsk~)1-S~p zwPn)TpD=0BUbf-HXZYvGH|G_t36~B>sC>aaIibsTgevjc{(ctztSD;Fe7YK(^bT>> z9s?xg#rwWtP@GrC4kWf>E0P8cl8i<}(Wo!hPJEqUi?SC3+>3pvz1A05i+OddtTe;{ z%WWZ+CxWi^T{rekIRdPQ`8L0s_kQET`;AxIXzy?V6tPBTMh82PDdh4@xBrhQhjGxKnw^ zmwb6vD4MmMSKM?3X--{`guyLfta-pj-cl^BCHqOlsPb?wcnDgBy)9OTecM_yyiu#R z&*G*g6hZJY#=@&ueqlr>Aaz)Di5wiLESi&`XYeENTKeBhaTOy1XcHHqo%7ZD%f>hB z_ZM9`Md+_LOT4e1%+*r#gJ)!ZYPf$2=1(n6b3Kn2_S};DKr&7MQ^@jxp0@FG|FNzA zlfanLzNY_jUvU2ghjg*19^`H!C@=s|9~uT``6ERF0Eiid z#NwrYfN&lJ4%_4*P6(bvp@*&kDQ&c>5F^;RAO6wl9@c`W)UZ)O1)Z$ z;_;4PMiE=$F=Lc<4{P*H%KN)&{>EqczmV|8_8VRFzm@RD{u{OQzk=|_{yR;Rk z9JCj-!}RiG4MPz4h~Ua4^lh~@YK@li2UoIINN7i9%|m4bu`krk-Co#qOL1D6Cytsh z@3!6`I0nI7r}Yt{n;zYuvSe?@e%4d`+Na0IVjQj^Tu0M>5q=pHWWYkoT;=>N2G5r5 z`v+-Mlw914)%na_@bddIO6%&aLsPjz>kq8FW^U062Ux2=`vT`T`aJft%C||#Z{D#I)H||eI z3LBe@#~=c0#AIV=U8rwr2w|*A#7xxoi{6`>jtcs_Y4kU`-Cx=J)65VaFsmPvnyno)CBrfZ&jrKoRLoA92zR(L(;EPY&Q;2xtMZHm5H zVhXvL9tKPil}{s$5uIdy>h_SQ#9lhbUmdC$4Ywmu3MkO>0g|AIl}O=0aIoEwMF}*3 z?1z(u15~&pMYwNaNA?C~WntbepJv+FMuJSyG`^htA@IQHfK;xo)MIX1shaM?MIa3OeEa^}qUbskOscvRB0~=N< z>fJ5ebr=Z{=qoCQ9eQl4t==2Pk0H=NC(RS>W*O)|#7Uk!uQAp3Nw(;YaSzI*U8En< z09V3Y<2w6tpXWhe2NBkpmiz? zGo7m<;Vml_GwR_ouGp%OKY4sA_duKT?Z(4&ZSLETNX~COG)LN6nnttyxMzujbSy`n z8n@0ji$j61Y!~@22Mcg0Y$j3hgOHWW+#&gCifZo7A_?#l%tORC2-$tu(9%!5Xy0PU zQSlRpHxS_Sd_NHsL}qfVgY4%E*q}oqY}fbcwfdt=V_L=E1DDDk`X9YlUp01p|4xX1 z<~R7ee*7DyljWbNy#F;+9$>HMfAjk1e*!9x<2TCfU&7MKwITzsbO4^LM0bp22jY-o z(5v=o5L>c*4)Q3Z)h=+rRum)gLp~#RP$MiN&9kKQ4^enCbTZVwYP!p^OmrJ3a?~YF z*@AkZvD?ZsyFh|AfwgEnnBR5p-)WHl=VR$Oexok3{1Z#}hu!tpk`s2$-%QUO0JhuT z{{B--`m&3PoZSi&T<3xM0~Kh!)yQ?ID_#@Oij9Wt3PM@s4;<^#q)gMbYC`g53#A5T zBxSFUWIsjIDZqKzERH*DEqc=_Fl{oNZ_XW3)JJ_E>3uJAP&CS~%gmE%yr~>YKF|)f zjoHUOF1}DFa!qX^$SZAV0Qle`5O&K&EcszyAxRlVckw4Rc};G=|Cag%a(F#nq@H{y zh)s+6u*dvd8*`K5=Iy9^lEECe?{!);Dgo3L15v@kTJntGgnAfT;B~d3Fs+PD1GfE< z8MoY3W_7ygt8V70Jy^?TZBZU6xUoRwa>0$d5O=hS#v?Pwl?V7%K=OnZws_V|3!JV7 z9L#umI4u7-(y=&vAU=%5JoORhKKVmMGV)NtH*SR}$Tr(>moORm?VyyE!+^ZP4Chm3 zL4zr0i|n({3bxAdK~inNBh9GrV?zm!JhE3Dcn!m1#OA38gUcP;=x7=d9R_%`g)W=t zU3jkVz%C0qzgZ!}#`))mkNdqJg2cfwP63?O*09a{f{(0D!~4t?T-AD{=v* zNOsQugsRB-YZ_Jh9aWL@*F*!z@E28)^Vg96O9oIC|DaF)k^xl3KU(XT{Hvs2&q=>z zb|QAJU*-RjIRNr6)%usr36Ov3rN3k@fc!5Nmg5GRaQ zk>%fy#sJ_m|AW5x@8cZ*1Zn)=MpI{QhD z;J^-mTBx2Z%<=eh#LfY-!Im^c@DQEUOWU!0LMq0>Avp|H*dL@Yac_=@Vb0byPmKv8C{;9 zn)|k@L%)B@J)&%Qc(S+mh!p>D0$DzP$TB@SsAz)j!aK%aGj1i2u42sUj3IaIi#;je z!2DpZW~hv3Gfa_|TY!Ce!@R$>(|4J&b+Gjl^Q-d+oNoX&lZ9-b9VB~5g);&T1?009 z;seuui3n5Ujw+km;pN%Z#3k(fO2NQI`IDhJrDzqRW{<_Ka!6!{wo63Lrwq9}!v!sD&28dWPv+k#SY59XE5jCJVIk+@u9p(qQaxezX zGwdBNQrf418%v<$`RHNv+<(qu_&y@?r4fveS$Ai8hU-%rKhi{=%q3<~B zZ%3Cy&7qw4PTF!H4LFt81cVC|AgVqE_Y5U)1xNi6{LYn2KC+YGSq&i)F+M@}H8MLx zmvkK(Yfou!UhdC3#NA?pG?+@a5)!^&;PFG|zW+ zgfqR`C)N*k0n^xM1nzDd4D&FGXNiUo1TWSz1iH-z-K@ZlisE>11(WP@fznF4!D_&% zh6`YIh-3x;N!(leXqeg&gqsQ!7e$#N>fLXUYI=D>S7;{bmWOn=TnB3OZW{;Jr}R0;*rS zg}2!WG;RpZ1mO=UQ>lvxh^LW8VU+`>kKqPH=F1>X4_vPS!i$j4WxC?Z5T^mcWHAbd zRG-w3PZYI;of15wN(Vd>HBw&EPpRSn*_y9kt-g2SGf!I~on( z)B%*(+OtCxC2c`;SikR{qUmYYRv_Wjmno_5Wum_0tW?VUg!epV5=mblytqT(?+6hQ zH{Ndu`>Jz75D_ol57xfDJwJ!$2(UwYFF`GIi0O{M@9&8F_Jz<_f6IBcxbmrD>pXL< zw(#ivH2?TRR)4u*?9F=f=puxR$J!HOQnByeKCJ2BlSpgV6%C~cvSfPBi{@9@(D)R? z#`M)})`#T?L>#ZYUPu1Z@Pf%G-DmfX$N@H-E^Vgcnh;(SJd^8*JFeq!#3ALW%O_lR zub=m=wR5ETA7Qw+86}@Ew3cR!cD_vR)vWdtnOhkPonytfjARtuN-H~xrNuMQava^{ zeaF=`g{#Dvt4iKz=&j!Rc^Uft5;GO54mG#zSq$nkuvO34^?1yU(3@QUQTcqN*nz7! z=Wu*E(s6IID$%tqOOb&j-N2ya$0XGOiYqHwXls_@q&pml_)TJcS*b`qDdEP)Y~9#T zsrZd?5xrLhS0iK$`Z6pMFcka1Lt{=0 zAVMa%I3=RAd7ALpO?M68TT$4*@bN?L0uRM8(cXZVJs2||a#(dvYl+7ylEz7J#1tCm zHNsI8u<(nE}Pk@RKPaGuc8gUFh2>Z+GHCs6V+eT7sCnit%_f$bZ6rO6O*d=KxZGb~? z4QR-kCCr>H`=o<$g*_v$Tg9jCj)COVC+svQxmJWFyJharzlcQK+>%~UAq)w%cu643 zaD-`$TBs)3w43OCU(n6p=;M$1kppteN~&eDGQ8lT`}_m54@+7}ER$-aX{ou&3iCNY ziYqStG#rh5iQ>8HaCxY!P&_a!BOIN4iQ^eCyc!Z3UX?h*C7Ub8+tdL@Pw!KiAHry^ zsM}&vO%q)%y6rzw=&oNQu|=7)j5AK#^R0q|;V|06?iP)Tzn_=V?dsmCj)Ffh`Hn(z zD92*Xw<@r-f@|GGD+fJ`@2-x_R*G)au{6~eJ>47Jv9;BDZ3>AMdFfv!41XM1qEO zbZNK2B0;R{+oo~c)BxRqm$y1eDNdmdTZB%0`zU$q3E*RrytPtCshh@;fHHY!X3v%3 zC_|v@_1-RL@0291Kty7^VlvM$*esv1%61>ABh;6M58N|d1R;*d=s9PWC0%4Mj`5VQ z2xTjLJ}wopF>o}i+TnGSzE*(-{c zkBWz*$poXTe0-jkgk?6YgFMRNt{iQ_A!RX)8M-jW)N*6)-Hc3i6iyYmki3$PWFlA- zVrxiWCJZm!U#ew}Fe{G9{~A5<;D_h9$m#Bz-#GIE8OJtt@P=1HP6Pyx|1YA zs`(|8lTHPvzJ45oGu3eUiJVy6=5;0#^9rTDj`E}>(k3EjQC0UYkwKjjDhD}^VL)4F zPogoj-12qBnlP!~#&Myn3|-x09EA)>Ye(U8MDaF5!WZt>1P>kE<^koCGKSBiRJ%>m zMGDzvOwBDYA8rWhzZ_qif|jb-B~+`aRz8%i_HVUhqPkM}CRE=+tEud|am1dyH9c7B zE|`2ul3Bsxt3$xbu)SX3pZP)qVFp?nX8*T@FofH2DPjo)vz(8XIqm~fI9X13Ws%$ zHyXDKmGbUCQ^$E3+*^U&9k#)Y(5xT7iEo|0iEp6af21~k>Qs^JYIq+TQTPcSPqx7e z5;e*L7By&PgyiUy7VqV@ z7pJQa2JOB`q=!sF!q)E$F*kbmit7s!DlxBF*qq}G$DwLKwV%u~Tjg!9YFGX>< zkjJUgWEjaERT0%mi`_Vm1@cNSio~~o1~D&H5yS&#`IsfQpRr`gK;^YOZJv@SGJdqi zUh0Ta+XxB|E5Bl(Z1T;P{2}-mHOuSrk%fQo!<9QcCYD+So~HU++VPEw_FriQISQ_S z#Q^Uv5$^iql%LXb?ypmBe!UBSi(4RZX3S@tv4L-d^S{g}T05x;w;? z3`85&EZ+_Ofbhm+nlWI^@}m(M+t@^92{jS?O_P>r%3DN1>6nfETB}HzCde9U5w{pK z-3<)gQMw@WhC55@qC;Fk^M@^oBijXhGhnG#rx$o(s9tr}cij%j0j#+J*h0`bwdIfq zwEArBv9(dcslk#k1Kx$aDm1xo!gVOpqA-I$iuS!<3$FL#2NeP?N1sNH-1GWXf>qARiWpfU4Qodx~$Y`_O>0L^{e%`%noHbV_ z_#`<0vq>~F_>P68ds}1DgZLyd1xVMN>eR>e|6%Vez^dG~g-w@qcX#KaySqCTkVd+@ zOQgFSX^`&jM(J)zK?z0qm!7@v+2?NlbJ+LXed3<2&!bbnwOI3;-g3(b+R`+pdYVl_ywSM^~|7$;}}p6cLWB;_8vJM zvF5>(`c$0mRsY(uUvoN&BuQ2%JI|Zl*BjdGgKG3XUucAOBbOCW8JJNVCog~#Sl51Q zc(cjs&tPetEoHP$_F{V}%0t$PadKhEfQc@jR=nHr%!mT5Rg#V~zHfA7NJbd#>?uWj zF%=u9Y7N$0O>RKcYPSj{jbdnCMbLgNE32wfmcEURD1!rv;V6Rx0#R(FUeA1Oq+XxI zN7DJ~`nzY4>=4F~QXw^9xDhpA zr7PO1T+*u5>w25#gthY@7Z`5(%gnjStPKb?*n0Ld)znwoXw4*1Rn$Zo&SN}w+aoMX zhgs1|H4SrzY_gQZJbAI)Wl>HdSzfURMlsaau3;;S>NZIRO0n9sd2JWomBb3rDr=Rh zE+PlKRHP*8k4oXyk||dR$}{kO`-}v=PDMMJb~5H zi)09+v_qz^1ZW&bz+LI{GZ9#64(iV4El)17%Nq+*JbW%M>YsTwl~nT%EK+p!w5B1@ z_Z)xJX3JSLoKXH^zu29NXVPSsL3kl9D7zR+gCjpI5PaSXYE_1{W^ph1YV5GryU3Q3 z=1!<*L)zS9bG^tj=+arNQ`30m^=ISeu3h@8lorIu(lYI(-j-OQ4ea6%F9!446wA_4Iy|V3=H&VbYLzy&BdRmBp@u}2d zDcW0L$}4-;RXq~2)$uwByUl2Rvc|H8%`pGS5r-I&_3+DQjFX3R-D){vu@DO;8Cg+3=RdAPwp4y@R$E?e3~2M010dz}K^0BtbzhJsk!L9zKS2lzUZ! zeUYc&GNEqT+?~XXlXmnGX9@M}nHO`Kypc3BPqVd94WC%;svAMHvQ&G2{t{~VrAy-? zQnIrUoQ9<6tZ(dm=%$+Z8#6y;HF1Y1;`GNMV^>%}$u?afOBxCt=No=g@Dajnm3Q%8 z9#TldPiOCz+-`T?7q53Tw19d#-uRZ`(@8uK5BlLq{B1?4T*M4q#K7NwF1cg_{LKJD z2Ak5*7OT?v)(nRRNS+=eb0TaRO|e=eE*_3T(4 z)AIgbu^{v}v=aLN-~D6qBz}4}V9$($^%(VyA&Eye15|MI^c3_!tQw&n3M2joPyEkQ z<7Q-KX9WPO-5CCB^sB+2Md~pHGJh5+r74bSHdYo^HWsy^-2gTObO*l+J6ptL#t1bi ztYkDSkcLF~!iVJRm+3?QQ~CPcr2mJb{_owJ|F+WqBQ){%-u>?*{XZflzin#&CF=h| z(*GmK^V@FY*V^^>lm72vr@wc0|Gv`y%S@90v1WQi!_wcb`+r3Je%pijmz4frri}cL zSNQj`e0~H_f7>GedT;*wO8@`L_ww%|{XgQ@zwN>ND@s52FSYB>rGt-%SbuMz3PdA_ zc@{OH+;I6_hv%VReX|K;z*^xy48OECGRX`jd$WyMTV$syr=n2e3U67+Nx*wRG5(c( z*n<)GBa;0mjD~dZIA!wKP_g9EM6+E(F9G-$_|G1&&bWW61Am$$E88Q=emRt-Z9!OI zfEA+OgbJ&v&Qf2$&;5E|AEL|z4!*EJe%38PF3=ZqO0DTN@}7P4oL76Ne^O?1r#%d= zfVKzD0(#OxgAG0lFBL4A?SuAnfmBRhOeOg~dzT&dK;bY8J;~8S=2^Z2*k%E2d*fp5 z%4bqXt19gs^B38)Ba-h{=^GUm=VVs%%#Nk?TnrR#EDW)o(K#Vw5s7%)pl?a{=oxup zZLiX4LK6!}xETD1!gJLo5vx!reV&uMjbtgD<+Hb43D16N_Y{`2r8J>!RFa_0DrX;v z%KiM(oU-)n-aqS8d&f5rQF*oIhZgOZN2Z?^jRo+CqEP;rZWK{q=jtv#sI4*&24c7Z_1iFjZt9VdTN$yZXA*+~A*p7C((O zW?WZKQZG)dOnaF%-)=1Y)*_h$!Dh+-qT-cc564>mIqor`2y_j#ldY-FlTg=JTM?24kfa!!ZEd48VJIVA&~FF_OLZ@yB^Gqti95Cx-i!#s4izf|Hs-7VK6 z#8`eDD8|I_5K~z+d|(^*0?G-bi=8hKP;zUsov1R6Lg8%fwcy|I;#b_vsit@z5TeE@ zIj)Lnu~94q6&QXVW$sPU8fvKG)U0&qz+AzPd}wCB%vJhnW{*iDW~*ga2Np`a0YME( z+WU2(1iT-+mIb1mIHD$$CN4;46v9KtX6|3A&!0Z~A5LEZFh7uT$o+^kcmC+n?BX}SD(;>m}uOAYC`GLxU$EA%b$yR~`%SZOnJA?{_ zP+|5{Uwfpl`F>$8i9~s~LGvvffvu_&nw*|LLZveFwG9tz(VX}T>mja2e!wzDH$bE7eJWMSAcP_jz1 z_2xZ!C#5%;7g3!&kyt*1h;&XXo3pAYpZI&t1j1z72d+vMQ^i`ChGJ&ZWMSpm7pKpL z&?opf3t}dSg;n$dtW0CR9wz65qcXEJ(hIq0=4DV=49;}2xy|eoJ=Ift`OpGAP^-Yo z@hBB6Yb*9+f%J?Dgl@?9Q!VGjJ@0L7W*T8JiHzfyC{#&z3mXcPWSWPQqn-6w<$VTO ztxRy@==!Xst>dq!Dp0X!GqyI2^bX5Gv{S1^Cl7Hxi3QUS?!=9(2E2*q>waDiC1vY5 zVIAbtAWU{q7$u{*R!Sr{d3LAff^eM-Q;ebMSswp=)cGf&!3EjGp|)77btrq6 zpt-}Bm?rIA;vN!iyh}rr_`OXp7NKtukd)hMxr4v)f}HaNSk9eH^t(jQ2dz8$20p>A z`D~J3@*eSOJvFUP`zDawv`sfG3db3yxBbe?HZpls`2Ee0Cl2A^B{brO@ytUD`9N6# z+hg*sIaGLO(uHA;I#mzAvb5Jm-7|&@ZXE9cV7wUg)goXsV9=><;Uuq>D{m+inGLAU zUEBFyW)HT;=$xw+5H$g8w!doCQNkrj&<8ILb`VkQxLMxef$?Km^hC)?Ad-XIcfQ-7 z^oXYkUH4u4-bPFAc@w0FC}rZ<3Q zOkR=(Nq&fST^fL5F<`u3PJzUVulQ-JzpC+r&K}FB+Sft@fNp$iDz;5@afmIf1aeM$ zEO~61T0VY+vl-51l$d_yU0kJ8ZoskRyz-ZFE$>$m( zalFI8t!GPUVDVotwRyt?O`dDCRazwqCxP`nVUY`|cRAlsKF@)P z{6slf>f)^8a_SAfU8CWWi9+I_6XDoR#+!*iZj6@e?Qj6J{L7_-<7+evS|*j&-@t1o~ z>rS~IqpTwlR0hxmJgv533_LMqoxA@Wim7+zef?~Z(GRnHzoQ!wq@)<_4df8c(kXz( z97Me(Qo1Mq!o$`j&pKcI@D?A04UyTQD~v*ypksOsB*|OTIIS2`hOZK1oNw=Ugl zEW=WEn0rvs?RI?qsdlnl17JcC?OWI$=M)QjOq!KpY3H!cEhbEDJy}b8`@lxCt`#7N z1}41~W%(sZCx?6iS7zc45>a!JTs$OkIy2k>TQfO?I@@}jHCr}hHO-pqr$n0>OnO&G zShB}KeGeD`EDsz^{+Y}o0IgyxnwtF z-~yA+S!n>*FN_zgRk~)ihyz>E0_K(i!VdyM8z@#G&nh6yjPDKswj8KC5YB!Y1>5Ec zD&Ecg7Ku(D%mI#cPb$y|o+ElBm>2*C27_4o)V_kTDP2*C1y5&0-*8Q_f)vl25qGjyCph)_~& zxJU#EmJ~?e*lqyqo}V_95N;k9bR}gdT_7C-$mSb_l!rFm1NPYeNu~~f|MmufnK=oZa z93hL8Jp4-dN_LPhL5M^T>_^rIERDx}2mWo441o0^W8yI>BI2)P5g~xFk?V}S=&nJc zeS6l!V8{Ctzf4;+WBy<@|K@;PenuU`qa-Ui z^ydN6v>_x)ktw*b45qe?e#-!a+S)|b!szPAeCAhIZ>%v04fAwKo#O-p`)HX~wp$2> z3g5M^lY}Qyi=Sb!HBTT7+>q3>En1jbl9+H1h0TNLARU{soT6w2n>Rv1*RW zNUt8!EDzX3oR5h5u+_7x04D$dK`nYN0arx12S*d4CnOM-IBIHc0{0xK{#nu64ECAU$VxEedC|jM2 z&?ImRo&C~w#_Ox`1}a-ZyF4h-MgCO6pHdBo7Y{)-#J7~C$L{6ZOT|?ui%!bqA*k4* zKRM%+y^WTaWM! zUi4PY!Dp1#xaZze10pRH=6;^#sun9n_Go#LiabZ0aC1HEO zN_br4R+$?S=odJ?2Ihv4M=`l6=24G->l}}o)*$TG3we`3l6s*MUqZ60D&UdIn9;H_ zKW53kpY(>o(XXkYjj1B8EBtv_V7Em|6KEPAsObE3iLxjb;nZBADs}Y=gg`{2Ez+uS zy?=58$$mKTGin@q;qg*&G)$XGssfHqgGju!@%#Wa|0;lmf&r?Uzrs^K+x<*!A!Dc66$vPUetW7 zgVOx`4K!O)E$M-$_F&rqAR6(pz@J1d*;fSs)RH$>7+GndiH; zW=VYM2R=WUz$yO5PPgZs6+MzZri3@TJ(&AK{DZg{p?UD3jGB{0`dd%_l3iP~eMmKx77|BPCKOjXhD7OS`%JGFK`ug-Hm z_iG-=7&`}oO3gf`=DnLt+*E5PHr;H$k=wfl$S0IWT|PX9DTJQi?!n$wb<>|i31P^8 zeMMdJ9@KWG?fl>=uJ{Y^XC-(+bi}3|^p)G}Lo>HgWXlQsfePo>Tq*C4^~V%6?V~_# za_U_H-c}O!@Ys>gPCM$oYGh;&LE z$ejvx)?N1Drg-<(O!LKiK`-7%L8aR(R!x>k7;fk6u`^^b z{k2P6Rce9gx}9<2>yAsv{<(Zrq*qf}JUCP2P_Zem?i-QZPXGF zSoJr!(S7bC;dgY->h<)LNs64`5^cZIT?)kOrqd}#9+@$^7RR;vs{-0pBNCred}VJI z+Gt7k_yhxbeiI$pev-UPVvxZ9@q8I2S4Dj+@VZ?gzd+-{=OZgzcSj{T`*Vc+L;6U2 zgjakZDDpN4#E?|S$1U*d&;^EoktR5@dg&RyCxzFb?UjAt-fMK8MqeVzX2D0=%4yTC zK*B(}Vs+l-_02_n3SSovs_J+9uxO@oPQSZvkDoW$rSbGMROV76wW|AoHmd!VC}d&O z2x(42Ol^Y((v2w~lBp8Z8Y)!W zm9h;49=hDFvXM-6+tdg-C=g)}B-$uC*|>-$*BnDup|H@w4-TGkM^{?#lh|g)^6K*J zrPN1*y$v`Tp=#VvSg;ZuH>f8(8_avWm5!6BN8V~9d26LCV+$d03N6plJQ80?OB=Ts zeXyE+MK(&Y#{7Ze{X4BaqZpJDy_1@D-xg{QUQU-J@bar&Y%-aO$VDC8BP=o5{*UlE zc3mmNpG;WhrP|BGiZQ~VQ#(I@F476~6zYjJZpoAlNs8rkPFxNriR6vW*qtXj^ZmTT z=6yCrY506UsnLUQk48`@OG(w=4%hwMnuQ;59_esUVd}#~D9@mY>^?bVn<|1{J$?D{ zQ*X}>97XPwUnN@L(U7IE4LGwCU=w4eSeMXN+yGWa!a5`P=}?GD7#~1eY~dIQ}W%sXNrO>qW^EkSqQCMn|!! zQ@Q#XAYIzKC>y;{FKV~tmzRw)R27mg_RbB@i9(Lo6F%0B)9}tkGX`D(s~t&2DuqQ8Bs1zC41pl)x&IM7Sr80H>#EPo<$3#UkTvX z4H<8AB74xacHd$e%3q~f*dtkTkW6$xGw08&EU&oohinIF^lvq;hfOt`0&dRk^lAuf!Bf^{^Epmvjqi8OMntmd!0qQ^)2`t~BMvw@`E(%vh# zzqk{gczMhsmsgZpx`4D-_zyMv^?D~Y(1DeUT-my_MqRxCN4&sj4A;hS)c97 ztD&ywAadWm1>r6^yEeq!mX+0O`v?Jr7d+nhXSOMz62l$OdX-E^5mcSX*HY+1&?d}! zG*4I^hRjS}dVz%AGGj70Tq#`&3b60`vh%mQqQfyd6A54^3w^;7W@@TL*k(@LW=CEN zs|hY`t?d8=Ma{uCd`@Cf2Pw6S;iley=NCDQ<@_#(&%+7XI;wum{_TSFQ1Ps5RC-Ck zB`Th`#I_rrYT(W~sv2qs@^ z+i$3iSof>dHGOZeZ8W-V!Rr}^(ceUBG{?lsBarrwOWeuoMaJ(pl&g>#yrM&2gwsC6 zSCd1GOgw97c&8dOykAbXPCXu_*MYYd!L&TcNX9>ORv}A{E!it0QIz2@wwP{n8pBc= zpc;&0QdxMBDu7y?9Rl)BF1*vEmhw9F^$T;dikgAcG-JAW(Aicqu?rZJCWw4B^x*6d z7#qXXy2M?3A85=p!8W#&(-n!n-43=Q%{LBeV$J)mL?mbT>sG79U6}A$lpn`!rEn|v zb&R0*0$y`Dbv#8!kk_TE7gysk-G|lXhVp&U5a1+0a%Pc!4p}=V_D+?Ght8scO~EzX z_UejF)?0+IzSuZ(~yn5P@c0ayGq~I2MRM~Gu@sVN2`}1O=hX+NrC&P zyjJ^!0qn}qWvQNZE~m<}@olnWo@U3H?Qa&QR>#uoT?a)R1YFkQYa9o}~rbn11HaLr*Ro3*&{UC2(p^RK{VgP0ddV_ z+;sNKY=$;Ma-*MEc{w%4=GV{5^?~<(n8$JOb&vk)eo3mQ-=IBK{Tb-^3V1-j%$z%) z@kxL?)KH0}*Qw*&7(X!&j<-UI98ONE83?@*ksgsK+qIt>qcX71kr3M?NJpEo=Te$G zR2Wy2y^OQAb9q1CCY&Pj3m~w7a_HQvYf-%OI3TQL2u3HNjcr{_(FRtK+`^l88U`|F4 zqF!1Cy83iBErl6o>92ls5E~tbUaf-CpYlYZ_>6CH&P*Y&^{oqWJ z^AZjUh?vpeM>Zazwo1yieQh*X8HiI+{qw(U*{$Mrs$L zFrTlzF3a1H&N*PUI&Eur;(zT?fVMO(rKPm#CCN*OX3f1qxs<7uJw>{V&+O#q99ImY z#zNeUZ_UB+qMTr<>Au+(AyvxPh?mm}hFdO>C&0CwV*=%+zbi zj_Pn$GU~kB&cD&d&q8EgH|bk`KIVz1<_i#R*gV6`;3bXKG6NJaOkrw;D9B*sa+wV5tcEXQ-E%X`N_J(0>D6o**G zKbR6(^4ywHO63^a;MnUe+`TzYow|Q%M0o>kZ5{PfhDbasth@6~Ie$S5&jO>j~mYEa~U3ee;rq!6gS zl@Kbfq>w7Um5?ezXyB!Ss^EvUR1U-+&OQpk5eE=M+KI=+Nm2+09B>H3<>nCwJG~|j zMAnWGZeo-oQNu2XQNS@lCPiR{nTJ}`Am0LBe@`69?jA#uA}|CZMr;C8iL3&X2t!ja z3qunW5rjTd8U!z5A_BF^LlUf%8zaI~7$Y2}HbksPSAa~5sUlU3$qEzu1SjYy7+wTI z6lybqgkhn?M2fimIq>7yfgi^Kd>tO}b$F~WD2O;gbfM)pKwBG-5(&Wc{M5gamlmyqWmkt zXd*Vy4J1$FC|~F*G_GY6TFupPjvF5B#e@JBW~<=SwVCB0DFA3!U(j1O6wOfP7dN^T19mbY-iVXMw(Rz##NfrKiJ5w3we{65kBET`wMh1pcAw#7IO1-+W1{sA-?qqz zbg}I#D}*}0cH>Z%n&h!mb^s3e>rzC|ATcHsI@#VA%to>)|YBOy)e6=aMDCbBBnDw4Z(Wd;It zGTZtQc-M>Jp_f#vxp<#R*PnrszRPQ0slZD!;M6M-|2*!i#K21IZ|Y`Tc4e$&yRRdm zk1)WH!UVmIHLj>;Z={inP_=B*o|?|o%ne}kmSVftcpD^5xe8aHc8U;-$m&yX(a!UA zlSq&t+<5MtIhUJ8BfDeg-LLqV%FFAHSic_1o#8&cmh04U`{Co++0{%v0|H{ZkC|7lO6+n~)3khO zrL%1Zeug%?pfGHg8H8T7@XOD6j0kr8odV^)zD+>S2#(ooL zE}C^TN02}=BMaVYjGC1%U9yWo_jRB>q0PHo^seE)iyG<3Y63|5v!pR_b&91?6<^k~ z&$k4Xj^9km71?Pl0Z3}k7IC(3%2%HS*>V&0Dbz}4$+61sb-P>C711}q&}_>dZI_?4 z@?NcYBaXg(dF66LRMl?9|G<&%FFHm3^&{QSRFhv9UH@J{gg+gvep}`7KXP`zj1oO= z?fwPpqW^SG{d*Vr-?i@kPbc%g_wIkc4e)r6%Rgg#{xaX=-*^N3GUMWLxAAK&^Y6O> zewlaixVvXz1}4lgumjkLSvY}I1t5fq?avsi$8-eUW@TqqWd?Al5ACvY0>J7Vy6DLq z$%vnjM;Zy6umO`aFfQS|9{9F;s4W`zV+ybSaR>*%L%q)aKsfw$gaZI5O20~R|38ax z06f$y>|X-m0C=dI*Q2u1|9*r60PssS{7*wTJk(a}Uku>@cpz2nafv|xAqWS+19@|g zs`UGVJn)Yo4?NhI?Gf2^z`~9HZSnx;FOP6P*Mu^2{_Rq3{y14%a28;upFl7pa@Xg@ ztjhxG??s`@R1}91_=}k0mPsvg+Ny*x?D0Xqhv#-RnHRj)lh2=T=;S4b?k z`1Kdx8PB^Y)(uNJeQT96Pa-}8G4+E3XvuI=<7BM;ZDH6$nI3bUutZmJaN*O7HzS^~ zr^{=WL$%PQDHFUj&#RA|R2XfsLP-dRE=taK^B1f{CU2_gC_YLpgs?eKoth8q&HaPO z1Dp>fH2y&z_$%arA5GPMKCJ#Eu78jR4$8BAcMbIz9yl=kXeamI7wj>h-9N|!KbOt_ z1upw%nS0C<{y`r2uO)oIvVD|2@&|d~A3+}Y3+VVy68^aAKQ^E}!d#=q%nDFu2C#!Y zLkmV1Wz2yA7JopZje^z*y>@8I8F4fM{`I}`1QHvO^&uVgfI0t91t0wAocZ6B=05^_ z@E7p!pEV5!*WWhA#A9V0Ac%pridg|3@iL|?&G!I=2@`-za>>^q8L}c&`h9eF zX7AyPag&BaS8fenJVXc#igBq|hUe&%-t8mLBW7D0cSzf4qya|2oQWN|9C}%Zi zT06PP#81krw=UWV-jax>a0}&*_|_XEHoe$X66qDEh}Yr7id3qS{U^kW=g?Fyy%Wpm z>@uydre&ECA-;;BrR+os9l`q#jH`a!K|S8ycG>qgdf|>DwTL_vOM*=h;F76#zxD36 z{oX!=cd{O*68~(=HRYYlpy9JP3`fw&6`GQLD@L7p9GZ@uM~Ie_J>fj>iB;6}f@scks(!;e3ewoV6O(;zX&rELzkoFH1){xc|(9Mt|sfRR>x_O7rhbM0m zkTn=a&=fy>0Dh*TTjP8HdV;J@u3ralTvO3v$Nv<9qu&E#?-R3ec${Rmy6h1sB-+i) zt?#MrnTt25Q9rZ(Lt5+s!-?fF{z#5jqX@wJ6Fo}{cmgpsS<9ywkrV24Z$(iI37^6| zOtpv^7#k%jXLOumyh)*^SRp`8*4QG=ja;h43882%2hWyKAiI%x*kQ`o=*C?!2bmc& zw5n~xE`~GC7m{CmjG^$E$uYhp5yup9s9bebVQ3@(BL!>DVSTcx!XX!puz{{OkGDU} zAsxr!=IdDjr@rBe8}r+TZt$1Em!CBk`y*IC^2)6hK>x!Le=sH&(EZTi&gkaWZ+Z_X z$bcvn6GfLE?p19u8F}h0BOw*dh-8B+Yu&=fDWV!05m0Is{yw2BwP;M0UViFwO}lar zd&5(mb8h`(m;qRJ#daqs4NgTQT1ln3AFGE zZzpLrzc3Y>F3?uHF=vtr)~1;k8@AxP9nnCGEUYB9dXUJ&oW6uI9;4TDEv?N2!IyJN z4Uf`lLl~STfk!Y%gDSUs_cDdJ29K-|$p9K>w%S#k(76%&Lx=7_LhIW}Z)NX2{SzXX zZak_RPtXxOeS?Pl!VTemzRe{jb`Z6N;H;114*xVZ%Ody@41A&fQnymEIU&8#@%{*3~~%3%puv&Jf-!p$tP;llaRSHW&_ zs=^-HQ7y%0C6(v?b-o**dvqxprsrNP`O}E*Igx}!<3mRw%H{*yMQ_T!Y~u&(km=go z%NDTm(h+-0Vbp7!yFZsn6`Dc%)w6C>6YSXdj4>&43RXqi!twUmgJ9xdl3ggh|H zp^bqZzyBBAfL2c&w1cyT=uk4uiB3V ztf99%6i%`!h4~3vS?pYSJ)fqOM#a|8w_@V+Bp#PH+^%QLB+L#HK-+~)#+9pNm+wF6 z%Ct87B8gv&ml-p-UyyJm2@f~uh{2LAiUuXavd#BqLptW1zK3Z5=Xo=N%#=m%m_Kc? zvWJLQvb0d_=S|~S0<9D5ZkQ+#tpv=7mr5Zt*i!weAWC^+PO*@J^dLcXzD&SBvMCy$ z-Vpd9WJ8n`=T%35NZb~1!PU|3#tYcw(Y^#hCuS&5w?1*R_33QDtq|uDFAd*uRf)f{3j>M*4nmvZ}K`+ZPwUErJ z4v55BlUUygAUm%pHn`2AFv(;eaGBEAWz;V}2PAAM_~TwreGHbr}e{_%=o$ zz5}I~4|Dv1_9~2+;q92Q00y6l93QAR$!fub0|)VE=L}B?wgNU}e~bD?z&neQ*5N~& zRBvqONps5;`AvN|2&uK{UWdNa8mcpKl((4hUmX~Xj4$w4fvQVz-BLXeZm zgfUK2-Bbx-6|G-x5AccDIJEh_r$L?+vJ8o)LZ#k+nxNXm6ysRJd||7cnUAj3+w=r` z@3kbq@{F0tf#+1*5mSBQzAmL4pBRX-j6cAVGd%z!RYX+2%*BOpYG2| zvk&Ouc%wI$BYZyTy$$JoJ^O0??#L5m=`y(+0!kJM){{_jnTuH`iAp8sX*YG)b6ygm zhU;-gcI%NB8BDuaAxBpf{%OrL9bJYPhI4SO#~4oi%L8*Y@bCNqR?D|!H0J)E@z1(E zy)lW`TXy64uusUkx84+|@sXB{D)e#AiEc#q(|Fq`2qcF^z6$@UL0Y-77=NQddRY-< zkvmsYS0l(piG8?%7(4Ot1xl^ID%qD|Z|Ns2Z}hSikE3FGU6` z165m>&Adkp@WxMxWMh577_sYiC}9^Xb7Qp%;td6gT^NW-0`&psbfV5IQlDopWE*V1 zrk5AilE7twDz6;$bsnw!|`%Pgplec51m~*XVRYCH7={^kotTRMF#8W6?oEn))+5lhATsV2> zI4Yl2O^4oeKXJ0nNN)O3H>%4o0*LyK(d6uR5{3*JrZ+Anmpd!5RP-l)p zmRkBq@AHv5hRQB{2e9$D{qr!WYA&|7`Vz~6)1x58&v>zIwjlOeTl(yAB!WLbG0IiJ zlzi8#i{MrKvh2dOr&g|)ny%ySO^Mn!_J~nzPf4mP_Z?SM0)Y`cq=Cvn1$7@$(K#4( z=Xj|Vgc|{T=sOiLlB!G-1E}byOHy^9D`m#f36iwq=WT497bQwk*MVD9U(LnH?^pcQ z+{PCOzd(r9fGuH*U|?SMka@Ul07^g1@3pC zX8Z*XgGrd}2R!6Y4@%t4NmAA6sgo%jlc+H9FYp?_A2oydG3?}ionhM*3FP)my3g1| zEAPFz2kc3Sg%D*Rc93_FrHr*hFm=iLr8)$vq$A4rVk#_D*-&zVImXl8UoX_RO%Hz= zU!TWHH&k4&A@Z?O7$}RhAzP&KGGyr%*!)5le~iAa`LgS+&31mzS^8BY9H?*jx9h>8 z+o=q%SB1LeTsBdg6D(xzPECrE-Pu*PpXmxYu%MDxXEtj;eGFEHUeY2&h*x$%S?CS< zI&r!%d`;V)`b>~a2x1hxCwQCM#Hj~5kouxsd$tjzXCX$NRQ7Zj}OT7HIEhO zwEkwaPGh@XEx33)IsR&YTpRBls8To#1j=n}#k5MW%A z`GSLvG(qSpvML6nspjaAluh#`%rwl&xWLp+J|8n`LNIZF(zcI;DgnE=CZxI7#@Y>b zo~(6SR1~_TyJdol-fQy=f-6xu^{E7X2GRV4O%@)rM9!X*;BotlD7XkKq5`<>5a7E3 zz;|1>?TlzK*f3jGq0_&Lw|N7%LWA$ZoisMB7A(K`mKC7mVVf5%AXc}Z%A?RCe7fDO zYdjbzBGF{;r({>N zV>nuXq|j2X1s?nt;kIo^mXVdw(;Be>R#dl^7#?!+%90?)=a>1LB*9xl*b@DqD9>JZ zlV8r|#(C-tP;A}lm{p(*8TA*Rx;2^i=fe?ZLFq{Vmu61&mF%7c4i>s7J_XJjiA()1 zaUv9~0=SP>EH^00z#Dk-X>L2top$3HnPiMg9!^(Ml0SQgrg<0N;uL7xXE`6nS8TWO7OQ zC5?V;h=|O`qY10&S!!gmmr)FoS20>^o4{e*in?or+hfoJ%rj!y%1ou=VTv%wNz70~XNDS(IMV11 zd+X$o2mBIXQuvTj-#P6wv=KHNABi+)vV-QmjFjlDH7DeemOq8y*VpJRD1WMgnes-@ z;+67}4u7LZPl3c8;iYLpk9e)uZuqCygP?p{{+t>hbImjq51`y7 z7IW-7b8<7LTMBeCvaDwGGCi}JC>@xXi{77~s1XbtQ82i>HFrKe{g%|*VcT$AUFJpH zOI?&82l=EzxaH*>L*jfzmC8n>MybKaqP*qVctH@g`i-vq}k!Hr@2mjT84g z1%ryqn3a8C_a61}Ia5sv4t%yxmfUy93&h5KdV`cjJk}AFa0?LV!Ef_!K&yq_g$joX zte?I90$+GwiGx>$uUV%4LDUF*My}En?WcXEx8qSy?*n2z^~pXvaFtzQ*M z1cnbU$D&ymUW%BJR|dwVa8Yf5EeOJ8AW`YSou2Z#i>6fv3YwoZ?eOi$4M~?hz@TQ zYE-H@WTy9Nsx2q>)kZn;FcJ(RMx&?QYtsuH&B={~;0u%t44GTd?p!!mB!zknf$jG= z8MQhJUD_ncM92iRj@JijPxjaeFb%LML;@NHs-6x;Bn-UZt+2f2Dw%!JCkMAy~i&F^uC)itFn zTgbD{WL(muD%T~PGd;eI+z|>3`liaO_7;^so1KF_c+Qc&UY>*YtTad=tPq#yDd0%p zVB-b=H&{U=N1n)*t3^6I%GjlR zHQkvIiY@B}N#INR%Sge@@OW&#!LeYq489mY{zk5R8)TCgJ_~r=-SODxZQ)^SOuA(= zg0>Q94vlfVQS1|n&tiKiOqo`#Wmy0K}ξY`^P^e7mvGqn@SvcKOsF!Y8T0WcvtYWXN6<^ z&AlIwvCrGuSJw^O=~4SKbj?;B!{a{es#N*z#Q6lIF0i2Yt2Umf4)(rZZZ{F!-#;JGY5ExeKhdOTbNt7cCfdf;P8eQ2PlQ z{e;HC&^7-As2M5%Wg-S6JKhe~Ljkrb%8n9t#$`ti8U4eU8%lZaVgxeBgpSyd0u>7E zCv#NkZQQdWY{yicUYKIApe_;gC38*(TH$kQ)w-8(!IlW!HAci@nB`M?$-T?bO?oTm z5eQ=42})U_?j(7Zp%-}{$o7>D00a4L1zJMx!!>^MXmp-bQLOZCFhQ^RVDlH@h={8( z1VsEWs0Xm)C8E(G0{Vk^F|T+NEa+)nKwb63Lb+l3cqU-brb+k9nTIdQsLoNXB}L1h zR^=F2fy;%|zq9H9_l+?lfx$z40!#SJ)Fm5E`CPSPy3wB(24UDc#jbnRYJv9{r^$V% z#iv`5yb@E;EvjI09QvqRWlX;o%k>^L_p)T*Q;}wwHjn`q2y>izh1P{ zCUbF>m5Z)QPKg|6X*AoMqqt3CkuHkBZ|CN+wao$t)%GP?34fbWlK`0dUdF@#PF%kN!PcT+1y033Ujo#!emFH!?<>)DwvbV z=tH?bYwiDlG=LKBV;G)hp;i_1=TRjaFVf!|+ zD)l>%NPZ!qelIqZgQ?HyQ<2lO&Tx}jc@MS*Ff;32il4^YG7G3MG7V57WOs=wq+ifDP!X+#UFC+884HW7Af9$lT)D0&6M0~81SkQI(NDIb?m3^L|_;7kgj1@Vk z+3Xo}SiOlck~<+g*pLc*K97qx5_ovLaGIYbvsC03pYKINb|v4$ov>qj1ycRPVIr~q zMTd4rv3h6m`?z>ZA$7uJv6$_kCncFXTnA~+*)M>oSA9uw;^h6T@N(=>h3jme3!k?% zZ%amd<`&y1(qr*CHC-zA;&8K;$ZGcZUZ29P9q02WV8c#!D>OQ{p9iT|;E()k-g)+U zx-mPmF7<*sU<$!4+DKdAMj($hn=9qO`SN53tEkO3kdM;CzGFF)!QAlco!PiqG)tz8 zygD-b4WujZ^hN59_`2-L;5l(!FVB2H*CrR}&|gB#%*e>-=w_LMJQ#WmRW0XWb#SDS z;?8-%unE4OkfQ^Gjr6wtBpUmJ~Q3Iy8#VKD$pF>Kgcp)k3fg~=Whd`>2Gm-W;DRC zcIaaDUPm|kS-IW%AY|_+eYD5OCN+c780^}?$TUhTc+Vs>{Ss|?KEsu4b6wvPim~+M$I&*iIMW=93_R1W@#awC2z5AHx*36l+`=coAjZ{wgx`us zvj-UZM7KpwNnGe=Aeb(#W_|r&%#lNpE{nQtAo#>>NsSL%aJz;HX1ocFfyB*-q(~gV zbrk^6bBwesDwFHf!tjpW{Jlu^e6R*h%`D1g1=PU$Q;X>J*2}x`IBC=+W+FXyV6GLi zB4|q7r<6E!+%gGTZS(P~lOKq5OhMt%oq}3%?8tOJ{={B815~+e4BCU3_)|7oV?P$R zVC3OQ*)zE1!$w$%b-k&wPj79sPJS%r*Nw@KKz|pH$|D_25bRf%1$w@TZ0q$A&<2oX z_%tId?FIWlXR<2lEo%L)y$(;YqT>89U~vr?BI18tB*tRCoPPt zvwR#T`^(dU%cC3PPR_JWL|X=Wtb14ccFio>uEZ;u_tG@F7@Hkc>};8(@n%^#y-2m~ z5!=&~+9bOIucx`M z&M&iz4VP9N#^!T=xeRMLM8;p1zw6WrT>XrHS$L4~v|l9OkUdkfSE8yswPAeeCPdED zuk>ED$lZ*jIM&}9rh@sJlG}S%Ta%imw6f#tLfgu4vwP*lZNb1cs^qdO@$B(KBJyyW z0sDCOGIVy^C1h(C@6?cXzd^NnZ5#o({`J+$E5JCcPEuek8T=|6LX{WZe@EyMf`AYY zniNgA@hZ)WRx!>fUU4#9-Mz78CzXjKwZzg!xHI|ui&7Gv1NLp9dfw)QyW?qW^)>DJ zbK>PR;`sUybaN_F%%w46Yt1RG4W`t=%jF@Q^%tVXX#s~??@ z;lX0t_bs3>M$%v3Sknu*CRcY+gvoGsviv4;;Gw_X`;nc>dO^gGZUm{L#>Nt)uzLa3 z3HLXQZJJzi^eZm2+cFy46MmVW+#={#)Pk;?n{QdFP~1jvw9HcP?W<5cO~N>n?T2nv zeg-ovLv3wU<_c9W7g4`ttY~9Lksfk2jFw!<@2R5Y?x0nDfvrQY^;3sYziQX%$KG2* zCb}r65VfQCR2pLsRF86lu0y|sH7t7pp3Te}?(^4pVHuJ<*rjt0U!jm~oLU zbR`KQy$#k9y7=A>oZGrzX)EDsR(YWAn-l2#xWRa|$rRZef}f0Vg-iestoqs5eY;y| zaMLkj4BWk2n7BD?6BXNu2u8k%>)J6ASOBSV#DtMfpssCbe+8YD*g1NHnPp*83*2qN zQ)P7H6lZqCuavak%gvaaw`AkWTlRC7?Aq2yonhk0q?;CTe&RzW-1c+KhU1x4bp}@{ zd%*Ed?pW3qI5^x}HEOb>%OxJ0^@bR)7f;0GQ$8mkn2QL$2gUk}RHPNyuxQ2#|KgF-Ae6$xn*TocuI zH(R%zZ}KOph`?yrknm(f!FO0<(cvCWb@GOW$HSe~li;CpS!z7M1zkW}o1aGMBHY}J zZe|fCO@>9QW6-Rr^niiBFU&SqY0IvEH+gQ#8p+()wTjRlfEVk>_vHou?7=>Jst2

L0rUZ|E3oF3)m*_G~nTwey@&P7uw_S&s_?=!BH+fiK*-R+)!w@Df5rGI3jKa=<^ zdm!b`Ms4pdyvr1(%iO9~l1S$erm#?@z$T`pwo$ZYrF}F@Q{A9hy?uxV8|-^X7gNJL zTTpiF+(Y60*47v+8ruEN))p(8*e5RI)a>YD3Es2$YjdF$$78qQR_iN!q5M<1W`Bf1 z>=xP?CeF~q^>FHKDqu8KGtbVgR)LU$_cgNQ(9rYGIqVR zCeIfWfub!hlO+HTs@XeovLV3%1(T(0e&*zeg3(5v&;v^T;?YJKd_~Yn0Z!6-wU!Mr6l31)@wzzx5KID#jLXL40K=9sl3Ln{Cu=?) zoNB%y=2&m~JV{wEC%pGAH|@MPFE<&m6|aDj@OfUlKr`6?I_rSsibwv22WiSsJc*KdW{MOy(v+ZVAQ3(H{0viIwvq%l-3>>L7x)qqzhqkQ_^aZLH@gMT$UT?^W?~gOW$$Y%~atu|so*3Ir2YQt2Kh6UdGCWTB zJ~J<_dXTaJUQdbjUeLt2Zd;B44tWAxwLlnPIg<=)z;2(E%rP3R;F z4l%wuPkB!1Js<_;)@&gK>71O4;1TKLf;x;bpBL%jXAbSW)GVduUgbWY!@ofzd1I6Q z+v((=m+$}5y8OT1$@upPR{vGuN`Kz4_`m)2|F7s`f8Ij*zdpL(NGmYO4{tHbUjP{z z1#8pl7=hxCZU!h~Xlu)A16VeLL47oA{<>lJf8Mb9N5;PWc~|WpbJ%?375&Ge_pp8B z8f9ep4bvQp!k;zt`^eh*h5Qf1`)Qx&L_FWEt!J7cQSpotmq?TdcZ-^eQY2eOQe&L8 z8D)Hi7%h!45~%vEB&-ter>YRqXEV1p^tBHw0W{KTg(eR%ZiR!XhjtQ1R|6UoxqD12 z!NhGmC#(V*KMM}F1%yd03Ls>*)Qbz|rOxiuUE!`1p$gM{GtB3CkGiex+mj;(j(Zr^|bT`jfX&DlXk7JC=6$azK%ODo5Fa=jzqJw( zqHv7=airHb0d1LLh3Y2x1d3a*N-71by0}~_dtSx8ICYPwx#0AHvX<>5uPoyq?3RC@ z-NMHB*U$97G`TYU4!lr~BLRc}=DT|^FTD!-GJjV|NfYbON8i?jG}*Wdf{|GyoHVyI zBBEN;p=C{DeA5jj>4C1hMmVJM`wd*eq)2Fkka)ZK%59tM7_@hn?5MBQcD72kh}=*^%dW z%hWC$KCs8otkDE0`wx^J0jz=fC+_D!m<|H(I;#)3B5emG_*jsr^9qJ%nY%%H9WG9| zU&#?21=9s+kqE{QDU0FL*P_lPhjOQ zx@;f3x&Efr`7dv--zba!6k?aBXQl^F5Dno^i4PZyAV3ob=pWk+fZX%b0OQBZX9uq) z{j*?wv+>iHkN)=uFL%a2@EgB{-(dTjMxlScaQ`jw8*EG;R5yR%H~#MU4K`-_e+#Mj zolbZrCRQbS`C57)#Ny%*s6EjXD2fnme%`-e`^Kop{Hckc<5I9`g`kb-tqrXT^-T@I zj5Y8X@LT^0ir` z&$gCG9VpWD`r8zA8Z%Ozb0o_}eLGrs_at?KYq6*4V~PX!s13-IG&N$A2+cH5APPu4 z>S=T+gmaTO2b`sLk~#ir5Y5O~?ST>ifuA41af_Jn<@fmq+YA{MfdhztI$GF6ggcOi z`xdtU@>x|C=H2jUq|G~#6Vjc)%`3(* z;&;LtZk-QGx{q5#GS-jGSvv&OZkql>U8ToyLw52~g=xGeu5ToyLwzfPh3Wlr)t_%#{@2?t;Sh_*?p zn;_GYb)!_O(4F@Mh*5B`Pm%minp?S1Ir!9S?Yr?6=6&l-3<2w)p*~a#*6KU_%J>pS z@+^5SmmW8`KkdIjjwR05!kAXVy+l#091LtSV3;*8n9RYS=+y9}35--~_md!@N&he) zGK1wyW29|#fYz>DsMGE@2V04clLkT z!MEe)p0X#VbuvDPilNHD-tKO|H`N2!AhUnPK$N`;(9SUk$jwI|JoUV)TD?P=7E`46Og@#`&ky!uF8?iIMr&5dFPcs^K6sZrVN|qTeWF$ zLi561vTYurtzGU&vkF`!hB}$$PWNyTqFWJL&L&Me3b8;XlnY>7oS$#d(~Rw7wm$a1 zdvVD?^T)_Kw4`e2$~rwbLEbu{hVnt>ynEu-T3A;2vb5Ul`;!~N@e-aTtf zALXP-S^I87#wK~kHQ-T+m7wl&L1q|qw1AdoGmmyQDD0_3t5A~?rjxLUrxYykqZW+zrCe2f43_=45qyg?dfZ=Zhpt;PiUxJEJ0capSXVR zWg<9zZev{U*Z5*8BIpmYi6EvyQLh%qAbYium~nJncqYH+agDyRs;Xg^y(@b0O63i= zt+t3sfGK8xLa=9Y3`9qH*?CZxvL#%obTFH47t*n!O4?C>lb^h z61>K%TbUE$u3C1xf2qCg^K)1M0h`+J9rILrIY)=<`&8oIW?>NcqcampLZcs@W?nb+ zM3}riYS)qtfzQO&xmI{PGvyE6Mml@GnJ$B@MC~~2qNYz#oK~mW%ybu%c0&3PMD{cK8smOSz#yvMLUiYZ*ZiG zq7z$c=tMZV)nXTXAwFWooxRu?2a<|L4WX51VCUU9N`UAI1$?U z2~)g9@!^D7yMuzF zK-L7=Wxl}J^Be6*ss%aiD0~ZT0?}D82@RWxdNP9JjzKaBJjgep&3-z|M;Hm-^4i;E znHO#nsxurLL5H`PyzYiEX_su(B0<>d^3lkz9vd;D*?}*NRRKcRI|07%9a7)hq*4jl4L_RRVpeM*5QJM+!CV z*PVuUGkXF9WGU<^IvC-E^Q`^%Z;BgXyf_F*EJd_Wn5XXb_1gsnnBRrTzQ!;C(Ma7TdK>wQvVU8L)0gMPOj5fGjO5 z1JEwUsj|r4H3A%}mQ{YRB6{1ICht+arItY_4;R)R$I!qGCGUJUntABL_S<5Q{g!+2 zYNCOfqH=WwBu0g(+4l`g3j~(}vDoqxa~NDv8}>DoL0c zjyG^^Nkwzfq)Wz>Jk}uxMRDrcMwD@_0Kxw5sV_%IQ%$P(el0~xZVot7xf#R75x5o% zS`5?O1^zYdf>^n@{9uAL(u%Mh=OGv7T9-VOOi{`ZyVt2nyQ@@Xm2)MKkZukQws=ax z6WXN~qc#SCOBR;#sulQ|2ewWrG7x*K42l6H>yR|z`7b3bZQd@QPA^C#XO=64EhS`x zgSFCj7aBLYFaXa^A_m4c^1b? z0bEUQvqvpUy)!jxj+g0~>VjzNc@oV+v0p9&U=4zWZhAQaK8SkMtNDdd97L@8+cPR& zw(N>UU~j`oUSl9t=1`E-a|bcS?SUrbPO-_j`z3la+GY($c}C_Gn|)aS~n;gg+EH7Ht}z?RH&^!2=KbJ`5*NloCmfgaLUt z;-`^W6r<~BaAjp{WG|AeSx+YbA)*pNQyKqU2s^~eXFf8^7+$z3@|A0v#%U7F++0ad+VkLkMrr|BxGV0JKIfdJZcE zz4!+4;NOG=wM9?dui(|gA|7t7DMEmx6WMrLMhPV7A8mxHt$2eg-IAPg)$wu2!CrHb zjpuA_*yUDy_vn@#y?ReAJ>_zCz%?C!2t<{7rHOo%3Hf=30I zMN5x3ga@tI8s4Cu!e_exkoKSoPCORFK#R-=6Ho-vpa) zF+_XKRrTH9$S!vv^9)uj_;2c?$mQ|Ptz@Du@LpYM?|KefLJN37y|d?;OU#p1Byq9g zgc<#;OD&lIs$R0aCr|G5WQW)u855HLZ;=Bhj>H-;NC0{L970MF*=LMq$ysTBwnul* z_73U|m+kw(goysHmk0mXEv^4gnJz{SwvLX!&2#ya5AlDW=kg~<;fFkzKgs$2ndkB+ z6Wsp*J_`#6Fk+ZZ@?5z~(kBsAjSf?P(5cexLThQJQw^?MY?_XzJ z;f%sLE>}^m%8e38XwAZkEW$aebO*>i0E^VX@I`$LX-XnnQ_cCO(n+Hv1BUIexnokv z3$WWLJq4?(C+!~O0kK?F1?LHckm`WGH;mP0t`Rp1UawLd8HhwBq&k0z`)8FO5ha4k zJ(e=YnbAXT5gAsrz#JmU%+v$Es1pqItLe4H$GbUdIq#UZYwzbrfbDvg>|3M4K`ILX z$`9XI*mI|-&ZY+rnxY3}NlbGL$F`esgVvQta}2#Vx{jvAZrs{m=-u2xqbHWvtaV<* z&v|QUKePMeTPW`w#%4v(Tl|FeLcd2cC`b%U)qID3nFBRfNkK7ZS*r(ufE<``U@k-o zXPM$H$+7JMyNR=euNrNbuht5T$Y}?Q9&H7S9$cQs&;1cW`{Z}y6vMvJ3U+~AOd110 zTGEUx#7Z_cJ%Y)AU6zz3H3v&)&cis2lML${j=uqJ;W-NPT~9;gr{od`|S7RrrO9|aJu8j0MF zPG69Bo;^s3NPbfnz!!18_*OyWdGp|+vTv{X^a1J~2$w6eK&BX_^gZvCF8@}6E;34(cGv`3jHW5Ym^vL+?iW zB3YVvWglY$aumhy4(XlhN*=X6a|LeUnAwK~DWxJfasmncHCwnSwaRybA^xt44=a%^ z90JxRaGT1aeK7Je)c0-s@*#);e9raCE%mII_Cdk*AN!L?S_7N2MEV53e6=X<0QoPtHd}uC#Go`CSPP1?rv%NyuO(hO}2u231##lN{&XD*vQtGR zRA*Pl=D9#j%&^a%`st-}6Q;U%S_#84s!9wCFl(pWS%s=vQgt^oc64vXJ~jUuI@IwS z6iWh!hn_7Hs8f1{stS&aik*UpdXhAhld>kC+qT~t#_BgF*r(yO`@v0Ym9Htz?$WEM z?};^7Dam<;l(T&qGX~iUqamT|>F%5rzWiDAjr+HFy^13)=hQrDTzt8*noD*2TnU1*cHwu%tHp_f9#=6;@w_>Xn3brY9YS%fFw{>XXI5_Hrd*l|(3e2ORK3H}Iwc^cls8W{c z7Ve5Ty>e}Ynw^6+2iio1Qs*rBQL`RD*GiSOR-=8L$aYa7uNI_ii%f|RO_Z)5TVS5Z z18h-|H&8gZRVWjik8$yeweV9`{4U`koA zfqr|&YnKokyrv)W`k~xW$W7kb)5q~j)<=7OM&yH`5`kanW3Xzy(}QYhke7q-0=@(a zSX^Yd0`3{W5c#b?`xCnpAM6DRtPyH+~AgV&@!nPnHs;& zLPO*Q2WGgbXq?b%P8gjTwIny;LNilxUm_vaw(t>$3ndA&c@u`uvIhrqoXF~B9g9|N zYTrAc6t9Ek2NR0F(OmzpClvn;qm_SSk^Z0e>p$oN;P{QMIhLrlPu=to!k)$75FXh5 z?!)tu@7}D#XwX)84#Tgl^o_GZi5j<2>x=D_q!ndLU12^KvEgtXkc_`Fk9g2x-oV-4 zqBLayCnyldhYF{DPd3}t^WufE#Wwt4e12$-W%{k8n}iJj14P?C${T-CE!lZm`BC2M z`_~W!I$+?RKZ(zKM2UI(JuhHxzZ00f?eG*3vmrI6Y?c?L%&ue}jLLh8HYY7RfA`P6?dW_1 z5Ry@D`RJs5u;hfWc`g{{0lgy_N#-d5#Uz`m+0SgaG97} zz?$y*X`l}BgNb8g8UPgbq&w<+{Mo?z9R+^uqoep>tNI@-HTsd0_4oEq<)x~DfAyB_ zBX{x_@gqX)rjW0wfNwn-Blq%my!Aat4o37PL(M%?jZZkXDJ@-AXf#{br z0ZdAM_N#es{%P4m)>Tv&XC#`>5G<9`%I2&R!Yxmq8E=?W$KYM*Vw!L(-EiD&x)h`g z^WyaRF!BU9TVdP;zJQ{3fTc;?>tSjEFd{ueGc~`9T7D*p#n4O_liSQbo`JS<^at1Q zV|navJ#7An)tda(M)XJK*x!;>vnX=SWC%bUcPSkJWoxW`ch4Ltd~kec1>!=Xt`!8D z0Rm5R3nwU7sD2=kqt_+7aP8oZ&KYWp)4WhF#QVl-z5S}*Knj&2N*%m7)QLy3!r3DR23}` z($PqUn5aaxc<=EillCBz5piicDDffEeOUm4#h}rCB?%lOw%qO3KuzRVDya*v-Es=M3kG2*CYY!_9@;vNpzGm}J)0OJ}iQmfu=`0F*E zfcP(LU6C{aRH+;b#!q#4B3OrkTThu46b&dOFG9)Obz7M4IqT1l*Dr72QRF^EAC2=5 zS{wgJJrDoqq@F*L=>Cy<{#80X!^sjTBYZSmKd4g~|42Po=J@XFY14dk!anGT{jJFE zAF1cRv{JEuP(m|t{6;Cj^Q#Ykfd8LrCGFgqi;PKkMU~a|Uw!yOie;4T;S7WH-lK6X zyHYxc_Q4~~y470T#a^^pnrZG~ZIRI=yiF^qX9P_;PPBFGIAT}Oj9HYzrQ_w(c@Kgq z!QgSS7kSXV-W+e+bbdVxwV%Fi@-Pb267Nw64%#SSq$3I-80^QRlorb8X!NctoE_gY zf_}D*DuOn`zJY866|@%b2Rh;h5I#v#u8NB>BSz{%Sv51n*59A52du_W7EbXz844?# zD2-|t?&p=0c_L4drcoWVQNqxBNs5~Dass6+W4=ndno?<)f>sZAN4(>B5r5d9w;~AP zw3)vO-^F7ZU__kIm*UXROWhXRSk`bxsK#meHsR!tmppGL-FWOXd@J|nw5&Pq-0lF8 z&%Y}paM1=^En3&#&&ZnO44rvqeO`h0+6z7MI_>O5;cubzpCk|1EIHRSU#ze_{swOvyVAJakppSt3HsVDxX zEcsxj@DG^7X8&L+@mtlC$gi;{{HspyQnK?G-%O3WZY*#8vgWImA^l@~15)40?YmO3 z@n~%e2@&x^lAJf8P-XE8vjZ_<@q+{;s7rF}kfl^*^htava?aA_cHNC=@gj=m?b&qE zc)r5;=rG4Hd|oz6YrW?j?Ba!ows`A#(l`P3_jh@JYLit5C=vm!Dc2K(bvT^r0IC3k zT1(o%QxnFy_oq-)?Q`#Y!y#Hf)XM$N9$0|V5~N1ZVT`3SRtj?fmDWg!-hwL+8<%{m z0+qu@Yyc)$dWY^X5-pt0={0~9Z=C~?=!jP;egzHwm*F2SJ!=dj;&!NeU@;wb+yiNL zQtX33{1F{n=pGj&KlkX=s>9MRAe~!{>DqgHAmN>fe`xdZOZ zL>xq;<|5fS2@*7CI0Ck2a&a}cwb|;ntcmJc)Yi}NHZ$q8?~c)=PJ;SBdb)m)^{sziRB#sLa_*YlDr)(b40}(Lqq$wi>>%FbfPbL zrGW5*fY2tARnYS)5Hq8fLslCW#2pZ4Kh?r*^CU&@mH~@or%Q8IM=IzlBpg#%kE8;O zTzF2DwbT3^hvKt|Mt{MOcyx5A;7$^{>)6BPps z4XN*t%~@@x{E#b397`2Ee0WftcOP8!k7UM-zZ1y$AC#^B$dLSxlCA#G5Bx{A`ajNA zf9M2e{f$JTNE`>^uT>)u$BqCpaqWQn%I{x$p5DvA=f(05ftaydQDsIwkj;4y>qPTf zrz{VsB@={uP!n+EON_#}$i=0_jS|G0a07|b)f;raq$yK2C~h`d4D@y_YW^4&j<$<_ z2|ol=evv!UPP&i@tVv*aLRW6*3XGC?&=pzHWH@~jrmw@egR~VP1q}+XD_iWG)DIcE zhgx7Cy8a{`z;^u6E&fr>$MhS^rZkFD4g>fw%Z^Ywxl9k>JKTp(t!^FfO$mu2qOkfm z47(xWl3p74%?0!Q&Cz50!J9P|W5JW+%fp;u-{T^`CC~(W3RCYe^mF$IoL5}p;yzZ6 zjWmD{(k;5eQQgf2nGkFbU@RG+3>l#8sMk6ZlzX}<750@8|J;sz=N)jQ0ip2{o$}M$ z$*GCicuYXGxc_23TkTOR%~f7li)|(6s7tD+Y1YDtI|)8=SN#(~u?+}0xP@uLag%&j zRkRV+g;o5swv}zntGeV=u#L881W{a086kIW;m8;%)K=`@Kcf4Q3Hgsq?B633`;qba zKQR;gk(v2-UcvuyCYJppzw&?GOf37~^ojnFy8J&%U9!`EuuRJE-#>N9PX9sl{I~9M z7J7Ml`KhnUQ!I?ED)cNM^`FM2Q50cXHcqr5kce~oK$Rd3{0kl7DILH469U0e0WS96 zzJ}T9KUnT#`;C#4J zL}mYzpY)F)>eCxwj+k=F2e-?g9IOB81TiuET2uYaAZnI|l;g4}V&}fv0fcHey(yU7 zy7`bp;TL<=nWf#O6F|by9b)|M4Fsv_w}(?S{(yiEm5M<619$!6=i{@QP}?(KH|L^y zXp{$yxU$ISagltw1pMnj__cYo_bY9tjAQ1zrL0|1BQ=$liDNP!8Z*w@){d%GN;-9r zS8^-M`>C(hlzNkUd8+uLhk6a25WBm9T2(SabrM~lrgI>;y_;Wx=QCN^C$hf1Ru#VH$A<5gTs4p1RKCy1bbhYD zY`#5`JXR|Bf`7A(%qo@9zDq#bBK|@RX)b(pJlCzE{{?#&kNaq>)u*&KGEpJ*;&9B( zJjw^FUfO{e0dG*)oMiy7JfRlE+UxH%rxbWThxG_`MBgutlb_EH2l!4dI-zx z(9b~wO-Inn&A{@E&~^{!)w5xP&ohSwA1Yh59jPVAR?GHgPvb)t`YFXQuU~TTDL1Km znWvZXJ#d1cVfnKqAPY+-dlWM;#O@t}bqrWvGjBv*&&8`ujH$;K0K2WiEO99RQoIt} z_d3zK8sc%EEY3Lq`z+$Ml)>ZynwbAEwGd2K{^~ zTsLT83^P2hlO-EJv;L;3q&vNO-`w!U2A0$&Dzek@^|fraZN$ot72^s2`gT!Oldb;e zWQcJkt>iD#y+5^vIT3AxIryzov<3Gz$(AAVNhnZ2u$L!!nuggaen zB59%60n?M) zx%t>vzEE2(z+yu%B3W?Z`0JW2#RAR(J>B0@14(byE98>52$5IFmpsU>4-T&S5B`9t zAnzU%zX|kPrsLq;*Xji?IfX13+MtrWZ{xoKS}yvgfC6CardEbF@GwRXC6h@E`9h8Z z+uKMC({a2Dgf;lgEM=%$wTU~*wGwoCPCZkWd{Y-~FHe;)uqh7!2Vgx#K$=%!v~9-8 z%{54{K0~$%a-?A)$>}a22{1yJAp&8N%6jM07aD- zQh)m>N^vVEUA*Iv|9t^X1olN>?Ocdw8mZDf!jidOHDc}S+nY_D*SHbt%TIsJbPg^l z`ctvDBny7u?kez(_GXCeh}$!SDe!qU?1cWwGpzPz(3D-fhxfF@{w#RgG)xPH4HDH zXLc3c<73~%*v8{SVM+~6lQe@u`%G8|GV~ck(jveP`giuQPp#ebwr+jX9hvDh_dmkz zGztKKn#p@>5j^F$(S!c7>89Caj!cy`X4JDm?P#KxVcf}RrVzyp-PZfQBaB4Jnua%M zh8d&Kw}D)`y>Nsvk0L|YYQ4~C7{X72KHnX>kSufuFN#ZDnXle4Lz>%F>ly~(VC%I9 z51r$9s+fKL89WL3QIxVo^w8|EBVoUTN@`h+2%;>O#MQ2vC_ucX-{?5yCk2#WQnoUm zCMEaFeD`854=vcKoBl-2I00Vkx84lqGi5`6zqWJ9DD_dSDC{C39O7NX!jiO@_U77} zUE*ZG1``bzQ?}&%O_&TCiENb_ESt0im~&o55(T_6LTwftt-YM%2qVtt7;9=xO~-z~ z%elw$|U z9|i!YQ#Vf!$?ZXea289We5X}_cuAauBWmbZJ>W9zO^M1l@Br%_o}o0rdN$TNGZWtq zru4@V*^xX8y~1|1Ar4bv#i1Eg{A_CNPn@m4o>PTS8L!TlZ?ewh-R%jV9)AnP~6}dq(DFZbXH>K>RFOnE0thqBu2! zy8IFh1c>n02MA%FUdcZ?kBFyMcm!nXY>SVHc8?k40@M*q(3J_HC`Cah`M-qZ&UiAG z0JEgQ0-`2>rl z);^rB&{~$4P^3EX{d%=XnnPFLaADZ#=epj>v>^Jc9dhC6O9qL^8ndEg>q~|g{%9^P z*34zJZ#uSOzaOrVpUvrTG`oq{_m$pG8#LEM5RC$Xv6fAwe865HRZOhv_gtToKKhfZRUVObR6d~y2*@3I>ikKrs zfgS$VbI-FQ00G0RhbXg8ixMzh;6&-V*-qR&rX+sNl!P^2osUJ-87W4gSMKMBZ|6aJ z(vgpN9Hf#TcODghX1}Ybt;ov4d0|#q5?Qf4a%1e}OtRs?E*AFFU12MoIc3^h0s#t#~3ex<%r4*a$&kRo~w(r@pd-k zPj@jidiiU$oM@6E;(K~s5;N@BvIyS%f55>EfHH`(1+ zB4targ$kzaSMAHJ=7}9nz~C9a$dX$1+Yvb_LnG%)upf;Z5pbR!iD zsJ=Ir5=$%o~hutTFe`$el#V9$ZbgxKI8`Qg-$&mP|>2L(g8gsnexfogE~VqPkn*3+tSgkJAu}*NYXmgPYK1b z_4c7XUFUGdJO`V(9YoBu|0=uZRU2E4=40QdXvH4qO-lZ)UhgrB?ly>~x+U&eZk;9Q z$@Wq}a$9qVtSjVmX-`N1J%$gCFhdI%%!CPS603J+9e2L_(mBmME%z2za6VXobwE!T zSrOg|_cj-jsPf{49QddEDbo%2cJhLZ+JGY0AH}buF&1QXz@c*aiG&H4h`~PaISdks zFsZaPeH&jr27S}?jc4#mMslGF)F^?;B9bR3qkwI^KR_hpgavrlkh&vm$pQh|EP|_EhzT$$Ui7$#M zlbeRb&)GDtMV(P3fHn{_R#~=2pUN|9+)_Q+7N7^c(rd7;SuFs^aCo}ZUh{n)KwhOr zrIc`%FpxPuINlt?bU9l&kd{K?in1{hy`cID06yN3q~m;W{*W)uXDU6+NKuq+fAume zMv)1}hvIW`6JP0~18g>Hfe=$On;C5>6+1A_Uy&MulxPj_9v`P9e(a~s37Y{~XRqZVoIK zlTY)fDj+lvHRBM(FwBp$U#kwWh2u;U#?M=ZDeqy4)Rn#MFp9c6T#GBHN5)-_1CLS* z`eD0v?NRWP0=^EismqTn*0T8260dn^we$pI_93sht1S{dA`Wv)HB#S$YTj_kU6ev{ zKjhqJoZ5KpLkSajU~7YY+aPQKxX|?t-4nt;f+jDV_fvWDhpKEIJ9i&t@#=?6MwZPf zy+QI3(P$4S2v42WX@Fh@(Adg<=#POtxd_06&JHKs=7v-i+^3}5!QxEXiQUO``Pw`Q z(X8*AHV#&k63E3m$le+ff0!O;1iBDm4loP4W3HVc;kA5@iRO_?>-dem$Cw{n%L$$` z#KkX}C3~*e`XrDoalPq~=cf46q2R7UXFh6}cfopp*SWURVz;u?Q6T4qLferJEWN2G zI{2@f5nVLZlnsU!1VpMP+BeF0f;22}Oz7e@q!Q50dilw6J}JP4a4o%utP+`dT*%7w z(q}+G-dBF;(MD9LU@ESA==(-zKTRkZRCakEE^#3z0-+~LgfEd7YTKR3de9pXm!d;&izS?cX>ErIW%qqoS=K9Td1;B76;5P? z51s+nj4>IqI352S#1>Www8nmM2gwN?4%#73z6O9->%peHW-TV2wPhzd%L8jnf7iH` ze;VH)uj8XWZ~1&RUzvv)#EIOer4))|57ca|S7;{)WKC)U7^5g|55+OT;+_PQEOxy+ z?HdKnC-cE`=mS1213m*g!@r2r8SxpI7#Z3A;!*##cKer)_zcWUtbcZ@|A*v&rRY0Q z`Tvixa|qIe3Bq*SwvCy#ZQHiHr)^Bzwr$(CZQHi_?fkp3hmGCC)*&x>s7pmfWmZ1# ztFyTR4pRtyBj+a;*lA_&2EQW!8r^9{)Q=wkiFkuS*4FuNT^^2gpKjd(Dt9VtE_RGJ zaGa_cS8b(~$WQMF0qf~uoYL19Um=>=5uL?VN+`=+Kw#-^qs1SHELTpK{XM`Hxa zfgSC^HaG5msD+k*!JPj#h688sfE?S{05Q#|0b#HK!BW!0V$w4+`z5ERpYr>+AansS z=E1Ik5zRuy)i(okk|;!MY_xOxO;2U-th~>X`fa2^^bHISiUQ2J1lDklfY=~5fR6m- zPKYjB(WCv09x{CUe+EM#QGNT98dH2Fmvi6_ndAYWHP3`}}sWxvAcz`Th%$34Ajx?PoqDyb(XK z1Ac7>n~e6wZ7LIbpD+`947#s>YHDhD93E&LRKRxRM8=mU@5C1JV{!Z;^t~F=PM%wv z+wWW(m&mT}_t`aM|041k2nYu!M_?B(;QCEJsBZv-0T`DXI7-0G05{0DqBmWz#CN~- z(G92**g0+YXcWZY=kRftvYS0PeQiUd9f10Cip)GNC0QonTk_d?4B!$KvEByCfy2uJ zf>1*+1A>L6vu}uVfXn&I6>!Y<@a$5oDckEM+?5m zejEU_1c1^_O%GguyN)~tG;RT8-T|c#{1solFy8>C1pAhTk45=!^*%r>p#^-4BY^ur zwtYsc9fr{#|YagjyI~y{HYdSIueXS6&S|Ku9?;4s3w(Gx&sg z0LBph71#zWV+0V@;Q^u;29VgY0VQ7WhvD}Xz32}Of*XMR1nyK|eg78#nBVh^iQ~OQ zuzt`_^kXmvOy7_{{(XRl9z}*vOs_+OANseIwcfy84UKQup82{T$ewA~#OdBWT=-3Z z&`axDEBBZF4LgY|pl$bM>PB{~1#oeAJ=|vkpnnsa-q*j2&N%Gd(*`c}?Qh+7`oZ)f zy?OYT8F|*%ei&K$mVe`~U~qM{ckjdnWNosKe?bB~kOKv5iHw8Zv9*nR1R^W?PC8)> zh15f?k^LnnY^KR@AZ9&6cV`fP-J)7dEcR4!Z9!2!x#iK?L@4X~Y7u$7@K~355H4Yr zZatknn;;c3^=t<*u!k%%XL$b7*_H(Z_zPYy#;i7Wr-t;BJA;~3!kLzIGqXo1v7KaF zr50(sxXmBTwWiw~XFJMi4wV)_hd@2s>jJ)hPtX)T{o!eFlYf~=Y{nNsfC&P z*@Fqc(1yB-$WB@AqkL2xaDt*SL6Ue*v>Gn5n6zh=bE#WkAW#KT@Fpt{dHj;nB>ID+ zF1Dj@5cdOo+v%5{QwrH_b@7g4xo>Rr4tD_m7$ma?;^}^9^5m zk?P4G8mm#n3xy2h2}BAl@gl;J&R_+K+(qq}$RLbld4`y^SV1a7CFHQbiTP3Eu00UO zgM>i~U#)HOK6e{8k1Lg^9H$Y(e=apBFPWc#tteAnz0B88_bsby);^6&9a^%F-n`2s zSd@EG+9rTKrWlg;Hm;{vlfRY3m>f1}bS6gr^yFM{s%=!p@x~^<`jGoZKx8)|FH>&u z4_Z!sP)TMFb4V0D>_$wQsPmTGA=gARQ@!C~eEgA7TN@l7pTmwC)RbAVCgSM!a*fZP zrFe&5a0!u4;Z|;mJz5P*#>jb>vbUcFwf3>Adx*af5UR=%PtYm+efyIbX=>5CNH2De zs7Ekdy|KQh(nAQ7ED_N_CbNb3W@2uCXc4S50ITy)7b3u9nBQ^1Av>n$wew*<#tu^3 zfvAN3$`#faAw78m=#EYHPS^{fkx)Oc+%-673Pv-7NJ|P`Q+6d|xXs5ivolv!;$Mo_!sTt4i5D zxI3oO5O1amA!w47(JqhnSWe@vKUZADk`z(?cn&-$PXV}IG- zJvD~OIgT0zK(_=FBaXt5rRY8IjmWd?R^2C!P9MT0!2vwmvuIghT+Tli2l+?5y#vRM zXt8DS;+0s#IV;B#>=Ad)wSQLmw>|2-rvQ?yDShwEcTubk=eicugq(5sCZJKRpts!bm$K&c!uJy|ex1GJ%-`{c9PR)@|Z4 z#uIERgqAc5;9%IPn&N0Gw?%pcpZ~Nk>se=~WoGQKOi5!%9nK#7$M4)!Cg8GN^*;${KEf@(M*>WMEq)rTK<$_20di(g`fPsZ&I{(iI%1!Z5&5xpnmXfydACK!f}QS z8j0=*AG?4X|4DZ&>$0}6$yJ%(771c-5yLXMXP7T>X@S$Y#deCDey#a}cbG~;S@86o zr^Ii~H*96fL{Rj6&~jw8CneoLf0J`cImhdg#U&!MYMTR)R>Io+q~9%j?nc=av6jFz zlieua+}ihJmpk?*ybO+hE)IxV;pPyh96^TUZC+1_UkTwiY5W>XIJ7;IE7GNer4!+3 zv3)mvg^$hk=YF~r+Ax34btO=#OA_e|NYyqD^(YmOr0d5)S?m}%Nl9*zbTO^7viP&b zKz5s#U??a5XSewUDfpKJ>aWhD$2wsTmhOcP8vL;>dPLqTO#49fFM$agAX)oMj!@!^m@;az8ICs#1q>e3KS8fWRo`UeYIR z&reTH?@YASvV^O6Np=92B;6@be+6DXsHsn}LHzu-10^k=jAN0-TQ0r@lY1thNSr_F zrZ7}Ck}QvgRrnZ|J<3g)$Y_)4z!i#(}6mBfm4aw={0eUSo&r-c)_*8S{2HXOrfuO(?!*b zU`*}x2NtV~)RBfMJa^%s6`6Qi*D`CD5xh!^mhzaLJ+%_jui+n0Z?(ygt6ef4EnEQB|2z& zC2Zg#bH?3RLWI&dq`H|*ZlWYb;sR3DV)hu*@bdC_@2|df^}&1yid$BFXoT%T z=qJykBazwOyD`Ee{rRZO7||?g1qX+Xhf#G>Xd$0@Mci9-@V)lIu*-p&aU29jN(u9a z&A-pem<*Kgi)eMtlu#6D_p;8aKYw=^RJSOvK#?}ELwf>zK(8~brM!Sgi?F)yYb$YY z>y+j2Gus`R0xPxqRDF%2mp8p6F^o<>#l9cEYDZZPfyQB(HUGC>Z)Im^DwwD zey+D9qEEn@@mLdS4z!yMsxN;UCXJsvFv00aKLzowOC`ngMZxZL@5=B+q7`35YCyff z5F_jzPBYj5-LSgzeVvY+^VKCm$Q>XBqPAtfs%{Bywg<7cMJP`^naX;aDlp01XD_Af zP{Fw4iV%6=_9oJhNs3#mA8%+Pp!bo{5P*z!l}q)I@>-dF_(=}J=9C1POtie-bobtK zM(d(H;c;21tP8CKL4>2EZYJYW`=4NqeI?DRVDAiMUAW_8rL!H!5)l6?BS?x2-3^U1 zt>Wr+8RIsu$g^umfw!Bd$&kG7X~0&Kj9HC)KP|1BYh!PBtu-tM>mGia*iw+a@P$;F z9ZGP$dI)yeLE@T`9g%)Kol<_cV}%$8dsyC*k=PBLbBs)4$=d&OUUDOeQvh0ECDK0= zX7ry`$Y5jfgx)(UdQkzk(U^<211}~d-lgQ2PW!EFY1fn%!{HdFH1xMO#@`AK`ZUxM z=JNcJedE#g{!LHY)2L@<@4Q5@1pjGFYz8zNgp9K(9hGHM|2pW|QUX)jK3Efl_+B*t zWZL4?Y0KOtA8nqWNv376Y%E=J#OC%OJIlqAA~`gaV0hV6l7G(y@gkv0gxjbiqE~Mx zIcb*AfepiIMvTa3P~{{P!8|Qe<4-A-$UE#6E0*i+5qLhRTcq)julyJ}y?riQ zfAHlRznQZ1ohe+kZP!?GvNyQRi&Z9c;(T~oEQ0L&w~)BzR8$~-k3d4XE$gOXw@fzo%%bPwKD~j{9D&NN-v(7SmD5sEUeP?^qBmY zVLSJjzO5e5mU&f)g1yH2NutSV^urSh(h=di_dvxCxL@i z*W1@wa%<^oq(90l*@T>cOZn081a!IrA=)B%8p z14{1K@Bu45nMM{)>xT$Q$^4J(9}N&(+QzHr6oAj_qmn#t^edTj`czLB_Bt5&DCldu zV5DY!8EK^jEoQg%Uxz9u;SgadMAieWt{EqgOus93v?!s4YEf9lIno=&4l-G{hT@X2| zY)1jEV35E-GYeg~r6_4OaYcno&(bO!6w?J5YWOKzwPYx5)Foku&m3-?1Zc`gDX3$rAz)?(CF4s#o> zahUL7AJZ9S(d*J1ns@!C zD1uS9VDFn1C@wlcwZbpy*!;cXIHZDaQtLndGR9|YaFIPD;v{rXI%s+)icVy(HAG@A zGl;F<6u?o@(|r=H{uwv_YF`Q^M6>#*HwvRk>qM`%f|~VG)v>VawTd!`n@SX-9qTwA zzz@7`(SgK-OpM<4V$xP2X;8AF*#^^UZeqn_G5mg~b_*GDKL>B~8$X=!Q#GjUmxKNG zrbA$46AS7w>j`z2C~WAhWC-NqwAL$(Z28%z^QoB}{py=bdPmF`hE-ETy>u{#v5mMq z*D5)@p4t~vu36RWL6|L7W(-=DL^T!;mboHM~fHv z)Aqsp>q@}I*RC)ugsk}%#~oJPT$)Q?ISsH_+dZw~4>NObn4E1CWW6}&fJ|G-L z<7);k&KYy*5f=ZA#hD;|st_U}F@wzvnhN;~tQ~)o=l(&Tcb#v6g|(r`TI-awrk4?k z_$bM)m66A8Gcij{;65sdeT26I&i;J>dqDDohYD_8F}ILF)#&{oL@(p`*df$1daL|%KB7Nz zc-tUh!WtiNPO)cHW{5N6U*6M(&%S)+{h7c$e-dGh!0YN9N{bO%fyUHs4MA0dfWBZ2 zy)%>Sz^+8WcLh%9TOkPwjU!{ed?6Nl_ciL>fw+~swVkYrm<>56e<JKNYk ztrzTPDoHAZpFKEYBs)-X3XXRtLfsrhSDgWh62jueD!Y}6$!VfcSULJilZudzIC_hu zikms5nre#MLSo@#IQW75In9TL97MLH_06Q^#zR`=ejmhhl>Ab~SOikG(JdoStSV?m zIh^FJ$2b{^arCB0pjjt%BZtuJui;tE}xAI=!GAee{7%>DqYmI@7K_p zFSkUHVQATbSmAku(j;!kEnA4ipaz|UlA;Y(GCtM`Z;c>-4*VuV)jRlYa?*L{(m z4xHt$XG8J0I@bUSF%DdP&K-Nf%OzQ>(MF>jr~%3AFrGH7n)hv_Rix?M!}`^vSKTE$ zV?~k$>k_Pit~|XQkfq4jaqF{IH9m6QCG~r^z@#D$Nufkp7~bW3Sl8FC{;7F~W^}`x zcDPO|lhw=4n`Vs~&UMO3T4RJmQS+D%b9`qc=r6bn<23Jk!Ow`A^_oJpgcu8q*|`$c zm@s&o^D?(&(UZz^7Bg-vntCky`pIxM#V9ys!pUDoiUhZq9W<~S{mro`M z!zDx}QtS&$SC%Nj%yO#^5IogAWemi$| z37+`^kw_rcI@DAi?ud(-YBzrV3`NtK$rG+F3c0jKRSZ(ZIyc|E)lB{gfp%&t`%c9{ z*}ajxGRCj?Md;d^vavf3H<&|?`cD71vjtu*y3E_+IO*i*%FA-( zacNomXk2(=^pN(y`iP-rH=mQyHO=t`1#jBKrNS6~n)uml&epu$<|D@JSAcmT{3U*x zbF_`Pu!=|MnBmZu9XQ|k4wPM^nZXiZ>!UtaCBle8oXoVEBUeQy=}*uAXenCuy3pOv zDrvZlxZMDUkPtvP)o*|B z=R^LQSoZ7@vYVGSr=iF!;%pZF`inZ_{d`_EI9FH+IYE`~wAh&z7N5LNZr){2o*(Mm zsyTWqAh};=;}k4z@Noy>t%9$0G_5oW`tYAi!2~-ff*F5LOp@J=c$qkT-rZ={uEs6L zz>^^=VhFn8p8PUz70QCt7gP7exApHn8@4vx*WbE0f0G&)g?Y#l7v$QtQOt$l!ha$n zCf@v{e!Kdn4n8)5niD@Uim&q&&&FK7yPSdL4hvzT3_%=7-7bneR1Yi;GvgR1w#yqP zAb-Hb^ue`K7wG9+XkLAXR ztLyNYrl(L%v>*bz8XK5JVCRK77#;TsUZAaWO?95flEn?~Y--fYhR_0&%`uh6@aaUe zB~+8dYTF9%J2`-D53?e{oe5GW;f2s;vCX)9C@XLvWak8O* zb;h_)`Vr%eL@Dt*yD-Yo`MMu%kObFNd~A@uAG+qlm!9#xb=XYUz1~1^C$Z~xNe7B8 z;E%bQ{*ddfbVkxa%qq^4bEsW?PZTbka*fkgR9pCoPSPyE0~-1>px*t%CC6Kb<<$E> z8k*$e|7?mAS5XE(0|u?kV@tOgfH%2QfTB#tzAa4^Y30D z`wVLzum0j1Wc+z9v1Ks5;2Zt1=rx)R`3Od-2IXo^ZsLBlK zr8?Ctui_zj&G@0(Kdl2s&vE1ISQWLR*|GDTvd#5z00hYPLbg)x)gpRGoe0{&beD8` zQ}D59=cp%l6IVPXh8ZTqU>|@lL#r>|fx`{^AaXFY^9OGX(7mQfUl2|RXGYv|XBtJ@ ze2bb(scnsjhXGH0%C$j;4_BL)H!vO81{>L&d0_atnvHVt0?hO&AX8 zyc1x((0;D<4BaRh&rLO%TdxQ9+ovEC-uH`Nf)hmnS!2o&fnL%ddg{HoVg*GT*C_lD z>etY@idtmWq3;Gt?D9KJt#ZPZud|_oi7w(;xR~CYlzn~5lMR97Bf7wUCY(mcJrkYp zW~lk>5HE*aBcr0bNX_GeL|avDxn%ELUb8xU#r}DZ+z$HHzfGGQ&dfSOal3S}#&i?x zBgiB@W+5`qn?1e*>q=O=9uE8L7(zro)kd5ayLQKS z+3BgZ*VI#Qyt{m%R&{9UYg97o?`klyLex(>!r_$t%we@*vXl&+tAyIvs@5I0%*lF! zzYA=-Oc=W$8`a1_Hd|noO1J_>SHW6GN~-U1n{McFPim{~Hei8H-f;ITFO+fXK6Hrv zUU1Z}w`xMufnstj)xpeUgORnMK+;f|ybEKK%1Nj@hCB?hyP@DNhmh;wLipO}BurMg z^>AXcA1OF-6203*u(wUNk*=id!gDIXaM)%jonHv+~%*P z{k-u2eb){lCZ)|_r%QbcIGd7MSi+2mJj?D-+;w%%GnO*TX%U$Y-^e7>IzhD@$nO0P z0IyD#>B(AMWA93hCJr<^5O)<;@4VC?evUTKzjRR_zQsIqnR2!6aF zL%pk|RZR8`B{K!pU;Y58Q~EilmJJv6`ucetT`^IGb~_c>v`6?9bS5dp(zX`_v?c8kq~JDP7*wkNA4R& zrpowuAK)B)e?!KX^J%VpZ;a8oNwNN$VC)5wOHR@MZdD6iX8c&FRun^bOZPLmV14TQr`Gh<+%6s@Tm11e8PR2`jZ^{TmnWsS)t&=LzCXvh*$8 zRj1;h=eYQ;F_n`;5_>1YbCu(n*S~z1g0|5hFZMW7)8{Z@vy9hcLB1UiVF}wP{4vxZldozfH*PlK(NlHrrI~etmlKd{{2*)NL-VOQ^pIGS%1a(L_fBgV74H7*lZPM-#oOCH2qM@}s>dXrOcKg?y|)A7l?vDZpO zAAk2SYG;(4&J@>)#dBT3Bzn?wLl|w+Fw~27&44)c^M#*HECG{ncfCbAcZpFd2s;qN z0Nf4&nXlHJw6U8x9H4S>k3+J|sTx$WI2JSAzzi=lrmYaR-&Ag=>fvpeZAy~oIZ1;M zc^|2#OOT=jBTrK>5)2Nz&UFgaCq@pX6v^d77~s2ndrEF9n_F6Xkic9K=hB#dF1MCX zhTuoUS4q*<-Qlz&M!L3f3V#;bYl%}6J=<+@=OqH`qr0?FAUty#vEL8}p(iZ;ULGgRCcJ21U+RDK{#jdtkvG_b~+cBDDbN#w(H_G$t& zSO4K7ZG#da@krD3j;Q0JZLr)Ye4q#bpO5|?sh7oMc8IC^YiZ`IGUFBu_eNtDD(Za_ z9`n;ixHHMu#A!}XghbB3Gv4oZz(8tXNLJD3sO*K|5G*cd{Gx8`z#_$_BIZ{jFBr`I z<1tTO{FUg4=!a7-x>kqwqPka|S9SLMX{(IuV{h_!eDvWsE5R}B$ zc%b)IErVX9Pw$m0lJTM<>}N_Pe{yj!VJ! z??@^@yythnq&p*t10D0%)C>Dh`9z1`?qoYh3O0_a`sNs6(QFM}>$H5@qge^v!Gy2n zcAFs7u$`$uCd-J(L4U%+3yL1uyGrd=I+<66IO|-H?U z^maA;e0I-!Bi?&WI7Eo|#M1OKjo3h2eL-)Q7z8MWi>eGGlt#iI&9V?Tq!kA%{|`;N zG%i-%vCmIi)cWL2^bJ&UJ?f=frQewp3sU0Y=LNUB$EQ>?@tpO*&`!-~0 zRk7@2Q7)A;bngxa7!mA^PeCzQJ5H=|-!G~sG?_q+*D;XA*0Yd8~9@nhSqEIg9H5?Wr$@pHoqa>RaJ z!z4`HB-S<@MnYbiaCMF*EySe9hGIqMAa$r7Hq;GW9YLZfQ*$Z*S=CxS;-r}3r~i(j zR^=46rQETe&ixPEKf#k>mU*i3DKl9D9}y~yTF7|+GHX)KZ!OK2D`L4#Sz;LpOkF^(o@^A zvYhVxQyLC~?h|_FNO;~xrz1>BHsIRs3sWbnj3}JqJ-_4=pD4w!=6o#~9JV$lCAXnz zVZntMCD?>4^qg2YmTVVcj}yRSMJ|4J2wj@@4kqP0n|SK+`*gs{LAE5jN=ZG4zS|6d zEe;Ak4a71-knwS)72akAdIPPv=i48ax*S8s{8ywPv9*9g$luuUSNE>{^-70yokEV- zy~Xn$JilBcP1#b-1+sQo-avl0j5RRq`&*Li0!N-sTqQCk8qz5(g56?KfZgpPC?8)z_Kt6hCCJP3!bV(tP3PlG_RysICIn1$VteN+<#YF%{ZXvq*10=e`Z#i2n`yngqMrrErjOo~stp{> zt4Cs>J7&HUM0=UK*xm{JL~p4*GD6-lFp~`3M_*J8WMGi?B>8m6yo2=(iiYb=_neFA zmjp{*yh57EsOV=Us6i^UC>9LuokGwS%S#to1;^x)>NCHMihk)@VLR*3EEhm6pGO(l zppi3MJ5`6eJe^Xh{>%k|jmm~ICLQFUaW3fN@(q+4WyPY`aGc}nrP=Iyg_ja87UsE} za;LpK+(@f_r}ZWANBVC$A&oc)Iqf<)kvD40i(~e0t5_Ei*I%sZU^F`UFMJNkPx=r_px2r3XPOV`}(?oCqDLsVeUCqYjHEmbX8W?(BghC%Ssc4nM zC_~?06W4H7u&4VP4CvX>Opd6GLAwpXuz_PAq<`tZP$+0%>Wh@u*J2K}kf40nkdyH|<-dA)BH%MOF~M&iyjTNp3hd<{DQyhhJZ7q_ML| zUjuvMDD}T4u7J3$Nj9yoNIfiGnmQ#@d#e6@u)T?2g?{iG_Z%AZRnOY)N@YaO9*+K< zc5e=Fxb2ia4}Ys-vo6kPVTZrn_0h!>Zm<%KSBLgfRA}F)EKVT}J2#Iw`Cg&YL6hXD z5~`e?YJ>Kz4MaXr+bRdArW-OO8)@GNRxi`IVzwcTWHa?z{E!Sq=bTsdKXwbyL^6~q zVq(B_3EhmR{IImheJWm|jWmw^bdVH%qS4hILisz_H4-wVjFWii{Q4(eGvK4dnJDYs z>T;M%9qU6@l&vISgLiXkj5$S>NU)y!217m<#-2!=U$&Pb!j`vTM=Lh*;+!ewBS;d2 zWI?K^J{SEM>?xBa;YwA)l|_6-&`Y^|nrriLASCBwq8IEL)C>)U-kl+c`%i2=d;@f_ zxIi&RecHCG*xYpbSuw8bi*%|M)L24`S^~)W#8t39hhAU0irBE@7~{X4 zF%PF9`?YnYkLY?i{xN9UVc#MY@r8_CrK(7Zmfv)y#TY!fe12wME8ppYlq+H?nbgB+ zK^y6>3(GtCX)t?{rgQR3mp0Jwol|= zS5+%cGl$2}!GZ_T>>6tyy>g{Mti@;A!Q1X$$~%l&YW9(-bwjW+5bonKhs1>U&J|VA z-m$mM=Z|z#ZdnfHJk**vhbD`jYYD9pm?BlN1PzMW#a>#Wz=0eU@pql#^rAnre~dSyG?FEfpNR(1}u= zLZv6A1C3nq_iI+qAVbT9nbbUaC$&wU%djo<-1vf>^LAhAfAR`?ek(t|P$C!=Qe}TZ zBd=yCXR3FRH*O)J6#yB$WKR&`xtP#6`pob zL#tFm?UX#npo0rpRf*c6XRxd!sMkOA$cwAGlHDDdX;Magulnv7b5D*-7>^c(&*tCa zq-9ZJ8v1_YfU?LNg{J^x#4@C&KYpyo7XC zV0|X6)gQpI1Pk$2^I?ZB;>RplvuumY%p3mt0EP;2i3e;k@>Ke%{+9dZ_!1@%s*812 zCH@&iDxt-_s_A0===n?=8w)OsRW|hP^i6XXE9vbGB^b)anvPj7*KOK~traJTDBzkU*z%#F3ig0MLOLtbw%YdE(FQ76@S+b*Ao}s(S#5s+n4p|DCh*+ru$TkuAfHR?HDG$$RBLe zil}Y_aqt~hqOPSDDAPVA$uiDBD1c{r5n+@GYHMuB_`e8g(GHPAMdWD>UpRrviGQqFa~ZLz#@19{){{-=Ek;-B+0o7>tT3~0iyrHI=){K=OE zbG|=Y{7_c;LxxYhRFF zfBk;L)$-rgi*Ao*s2cOzAm;?X8MH+RR4#}yUYx@dA8bLo;|z{Zj_AC8c_lS7scx`v zrEIeNrfn(xld3RFPM@CYqId43zW7Lr8zoF>CoxI=WSw4v`3WQe*RkByT;8^LhRTsG z`K8nvn?A!n;Z#_H%R}dHC}&+q#pJHlS$n~0q_uPoL8nx5c*71)&LEX3Ovn zAE)jrMW2MZqa%K0JXu3B>A5m9s%CIg=p{H5=H1YW$gUU=WYpJ{IT8&{TVc&}v9 zDIuzNE=zX8N*2HIsi*`od;Hw89iF{9^I3&?^cQ~BY#wsCth%1Xb@cB=ZacX3{9hx` z-~blv{EfRpdo=kAZrYlCQc`}Iwsqg-OZCX{vg9tg0l~^tFhP=fBrh~;f=Qlj=3h8O z(NpvRo=CMP1Ea69i|lacSBpGvzsTjjzAX`FOLakEJo!C!3S>p=Z0|v< zy@D&?Y5fBd4{iI2B@S=?TP$<#_HM5Rf`QFifYD4jBX6zQe11D40Q}lk03*6BF&l_z*AG!QBzY@P-tiuM3~xpzE@Ca z83L5%ae=(I{3JtJeiU@KY!0ZYuL9tZo_Hz;$97Xg1L86%Z@7 zhhGBe+|RASdoSo2Fn|va2$poxck-M2vsQ@c)0aFmEuC|XGh@v&;EEO)gGif5KvF4Z zet0mLz`)4vAGs1<-8ksk6P^h@wleg@yQg2B2}CBU0z`2O1E`)|pMpL*JD56yYxtHX zUDP+-iPap~(V6O>L9n4A8Ug)VU#=fa;<`GZDM2$jAmu#rF@k;hXE)}#1G_ID zfE*E`AHn12TRl)3;N$(4GVm3e*{!bi`3v=@mfB27*^{4JvBOvTr&d{IsULK2y00I? zz~I;bxUR159;l5Y4Y&uOExr!+bjz0pIGR|~<^Xd4v3>o{`dMt)>^1lM*o74WecRQF zK)6kW1ycZEJA0cUm^HrY(*SZuzx96u03~0wRDjyRA7AbS=jP_`)ZC9-KLBBGIR4nm z<1X@T;^oCd4>%0MZKnaiSGd{Fx3;D%u=*YFJl>YpbsG@YU3~2ui+n@_{Q#6f9jNn< zQ6xz1y~gpS&7d74D7)H&`?&lA{O@ct0|<9NUDMaQ_z7ojncwL#@4P*JQk4dFrux5X zX^oHfz|uH4)7?oJdSg+jAtC!RkG=7y{RsdW|8a@kfs>vvd%9WleFOc_`?a{oM?n90 zMAHvk2aq%o01+Kf;u_%)ya5Uz&>cty_6%7MoM!SvlNWU$DO<2i~P!+`|vMO`T$uElBNR4b8~IxKg-trM*M5O`W3jd-ux5k zz7s!A__Pyw{$E)4MIP;(o$7!21_2nqUlOEG0f2WuL4U%1&A&Z^e!#j~t?w!Kx=mr@ zHu;%;9J$-LzDf6ahaL#;bW@gni9bJ+wLG}AfC20Co$ybHZ#6R~|1tsB{Ck~zo&0gf zy3@Hzc(>&*w}tPBfKHxJ{;S(@1i+!s?aqDdr*8M*=LYxJp_j(aCLoj}X?U{7@g!EG1`+;oe zF$V-jJ$HAV{@a+Vmj7ah+56;q^0vnuJ9# z^CDhpCcf_Njr4LhU;8Fzkgl&x78~5_zFOM<2m{F!QqD$yT0EB{GcCfju@MjWP;(D{ z8~$u7CSdDgl`Os3o&;Sb|TgjtQl`s<={hnjq#&on{!a96E!ZaQRw%dsLLfyQSWZ>yoW3`23q80GTOK z5raAbj}Pl`u~us^Q1#4?EntsO+PIYXsA|;8XTsGZzw7z84=)=mh8E+|t|yXMz?#li zQO_k#gNa@VWLC^%-AVFweJD<%X9S6{>Lj2h)r%*N)-r;QMK2$S;0Q@+QdQT;=z*4% zDHo=fbL*kxO)ov}Rs7reTn6kQ-=n$AqhPj4W_?MstSR3!2*gtLoh(j9=PQf6GfS4b zJdZoU!Rw+!It4k?sopXsj$amE-tZ`>NswU(Iu)l@h|vP-(u!)ql|i$_AhE_}He2;a z0#r9+q|) zZ!wJFgzT$nShhnBhGh=9Hmq(*CLzT~l!p#9{vpI|Qfnw`4|N9@?c5k_n^yA3G~_f~ zBtT=v>RK@;l8xqN*v66~VNg2I)hIcv+GzLIR=i^lpK{GgJs8u-2dpI; z%hb>+fYAeIa;mTyuCovRRT`VmMGT3nm(CaMR0$$<>q18i|BWVl^%1f>hR4i4!`7EF zJEG{<&amYaa-)~Mwc^nN4;}XOdmrXm@U~8MYl@62=urqwj*o@zwu}%rAv0cR-2Y(g z9GZmDf^1v1ZQHhO+jf0r+qP}nwr$(C-8WuD&wB8N=O5(B+-vRo%;5e60!*JS2GM#3 z{;%ibq8;VpE*%~-pKf$$k760}@)FSU8&M1sX-TXjE|`_d zUX_by&1%O=xY(5mvyWNWPv6VBchK}`$+1@&^?d5_JRnH#874}O4SvwOVX>S#Sr=IT zCFm9<*wjnO!;D+T*alyGq3px9%>EWGMj$>=##^B+^hWS$_e&(kZG`0)at&S(9<@<# zM0FbUIo?EL*=|rKp)K+Meu!R+`#-1Lvxh3A_o<%{8 z-xFsfV345khy_oItn@i1>`L5H0_UZ@EHNl!EbF`MuO)ASxAg=dU^%!nx0TPqd9vW$ zCB6fn7kyPjPloof0#|(T=h?q4^4;x~N*pm5Vua4g&IS#8>wo{r*G~c5@P3b*0XkJm zQu20SA}rJLWA7nkMrZBss;z>yaZC6UHUURc@5z`ai`cjNerJF8D<6{?kS^F3%krLQ zAe6py!=`3}_qpSbWg7?Z`w3_Dz;wm{2a)^&Novy|pLT&HTbPg&tE zoup4NH@Q;&7L6@1+<)7?t;xtPJymZEbb(A+uvqWYrkSVYw89o`e+T4HdO1{enfR!2 z9AVpD;tHqFTTc;XNZhHB>H03gUl%~?B@~49EDv!d*L$O^)aaXlG|wY^A#vR3VHEnp z?NP~S#)DJD*xv$@mWejWf5S?=u1=ivM^jh1nF0Lr%wx)mJiur|A5PbWWO=-Ul;@(D za#g<&Ej`%5l(<;G8fS+BHP`Abfs9uL3^}oAA=o4(s?yDm{twvXP7Fhkh4e!SM%TH@ z9MezM3MnI778`qm_N2&7J+iw)q>PJo8}tcoyI#$H92w%su_RO z9bdfIBK#&Giy!ei9LBwA85j!Ju7^G*3{eyT!ibuCK6lXpfUD-%=@C_!c?V^y-1cT3 zQ%o5chVmPnnHT%uh@$c3Y>3A$?y4{$gshIHl~Zc+duOXZ5=XnTdk$cm_P@6d;yVun zxe{~*N@o4Eq?wUJBTxsgKOc{|FIM#e5P#^20+FCDS_$oVDDt?d^kzxU z+cQ_=QTj=C5O0*4Vm+j)TmBX9U-lckyWX(SMf(+{kq`^dJ8DG0QpBB@>S+I6UQ^xW zP&K5?uTDz7s?s^5Av)gp@!eXft9SV)Pb$#-wxT-7o~OfZj8&*7_P_uH)Y^U0gTncU z!ZRHR{Qm3;z?OcPbJmEK^ z;ASFJKXGbsIQf@|nuHN?1HTN2ck-YG!9TXS0{N8ZK`H{@+k9BJ|YPkfCIAC$wIyN+p zm1tOMatx4|fZlI(u!B!6D8_kRHCF= zH3k28?1*tDvwJI9j1^Ng<<~pSn`cxrfZOmAitA@76>G%}IIW+UOmQnJ7ogS^@|%*Z zp)4_R8uQ6@jg6kD&+AUTI;Br0%?~dtP%xYf*40ZO!Z){?EfshZ8^6ROz;X|_ zBppXu<57RV(-PYtl&o#f*=)_n(Lu?-ONb*bKa;LKKFk+^6Opx`bvk8`>|qne=aPyL zB%XzA&Ud)+bSl!aP4K&RWh82gK!{w&Lm6}R5X6jL z@4T7wOz2HB?-F>9%?`~|WQ+TKnqCS6;S>4IVJVE|)Dhg@>Sffo`XXnJYG^;f&Ft(X zOlrPEk?Txxr<-d(aO~SOj``GYQ?76oVVW+u5`Pu&+SNR@+v|X3@3o)M#0s8YulmOw zd}3gWO{&Laj}L=i_)Y;@HY|*$TyFCs-;{htnG>WRD{7608td~?BbrGo_0_@Li1Egj zuNUW+DTF32KyWy7f1y8{@7^S1DM$S1$Oa*#j$+P4fh&I+EZTE|OPVlquFe(Yglai`q83IG z&KlMvkda|+u1BuqdKI?TDk5|vEy*aZvs=wbn^7_b7*gezc&UBH8O+{%>0bF>a?t7$ zf=wKUfhD4!gvV5vFM5Kc!D8^F+>|YDBLq4259qGDFe|eToWfkY5(BfE5AfAd@REXp zsqC~aX#@u7X(QB9U=WzFf;qj=^j29r%`h?^hGm8ri-QkZ3W(0{X*=XNQ6D$S<01BY z;ojfhMz7gw_HA-@?3hvQ4JQynlbsG`fVu0m++ghdr?i@QV|_a#@JtO$AqDm8%QzOu zQA0I*Y~@fx?0TkU$G-{vj}d;--gKzs{!d6_V&^rHA=hpj)u2FUZ@~q7u9RNFTwEwG z%z4COq_y(cs+EbsiEkL0Jr-;$3%$7ZU35UM@bdVo!-!{AIVE8fmF_A3rZEisZofGpZvvZ)lQfp&fa%8rrB zD$QQ-1K>K#RV#4OHMc%SQnv;h$xhF^`mrT-9ZZUwK9y5?W!JT*Wi+7sNK(gB_j>7S zM^8D|Q@5k~eC}Lig8anKN<80U14*2Fx4yCT*Q{2bRv$0eC`_Z6LR7u#Us=5-SaEtg z^In4ysjT#0raTO7b#UZPxiaPPjbrDRe7>Us&vzEm^yQuJ_kveAHRv1EO z8|djGn39N|$UTS?4(oc<=w;Gxd4CGVmFyqQcr zJU4y#MO)|Yu3&=?JN9riVY@`xwz05EOy~UzFR~aJO6uvjuk9~nDL1&Imea`?R)?OU z`o7!8LQ&*~;fLEZlRxD?CWJ5kpj!QdN1x-AO&LKoc4q8^8jIT|Jn|y-bFLvhdV?|| zmozlA@Kp5-r7zSG0}B$l*m$3M(k>5xPF{9h`Cy2EZc7%BazK~(_i&$w6yKQU7`IY) zZZz(LTYY<*WJNElK5~Z-VdjSg+{$opHi!~cit!>{;snjYPG-V7IF5ZPs1r)^*@8JT zBxEwH>tZdDZ%hli(Hkn$6Se8WPq>-D1@~^`J$}@K!Az#kTT)3)k z>rUdXwCS^ko2FL?4+MtFbKpSh7zk)*9v`G1`)KU&2ujqiuUOn*MBAZLNr0O|)fkt` z$^jne$y^w~`gozF>-fJx!h z&0QH?)Am)-)odkqD^vFr&`{f0VoQ*y|D?8@iQ>mBFH1d1%&?DG=}-=kqTZHDnKz}c zR7jIPNeegbj1WkB4P&=8<$?P8|4Z&-pMN5Iu3U{iqtCwOH{apMP31V3%12qD7WJO7 zDCx)_X$}VH!X8;$C~L`z*ptyvy4>pX|C_b^F{okG8TiQoh&?1#_4$MWpgf)ZrttH4 zXg+69@*>tn^EPT`=^a8pN!}E9$K*qkCG^B&TjP_q=K{Qca}t!0ukKVqBM$om8``U*~^S+t$)!Vu2EH+21~Cr#^eh1`B;-KCVoDLM~wb zSTsZucj3TT9n*<-09yd<==?epQ8r!a;piS`-__r1915g38|P;`O>DchvLupltuz7? z<~8{nz@s`>PEp?0__D%Fqa<7>KH&ZL{2$%-<1$pphvZs0kmKf)V*?YixGzwULZ8$c z@$_`_)LI~P7k!qL>@iitBgjZDNeh~=9eQ+X{uzzyHHK$Htp$ zfC&}q*{U%Eh#XPiL)KT%T@Y>v_34xGs@CFQAij-nZ2e*_~E(x>RlQ^AEg`d#cvqef2o!jMFEC3=YGH$ zVN8mnyiL=0VI_o7Es73yf|z7|rc_KNq8)s}Y`RaTwzyg``VofIuGI`?G_|iK`Vn@X zojdkb=|}o8x+p>1Rz4lhLsaf>>Bf_DdJMP{>(!y_^f!-uDC^*GXcdeedaA(CY~;?V7;|Mm}QQKdI|PO=RVDX(gvvN2rU7R67H3?_N8#bz(wn3 zl4O2^>^&t16Rb#y0^+4~(cNL;z#8!L+1z8u!@%S-j6tMizrr->l5olgVgpwr#TwI` zcPncPLOvrO!l>?S0ygf~^aP4j_Zn9e5*KF;Tv`Sr!8|=(HjN$(8G z$Q>P|IMR=ITTkLh1YN5X?=`Bu2UZ@P;h*uA%`$uZVD1on9yZ6C_aN}KuYOQad2yS! zKVoXrHDcBt&e;ys8D_mih8E!oa9ANiFjjFj?1>j=^uGdP`@3609YY*fHQ#Y67llib zmY+c;4lS`#TK`g5FuoJ4%K#;bj+KZ#XK?_ix2qlb^i5)w^d&%p1Vp3qRi>X=mSuNd z+(sQ%y-&`lTioZE57oo30WF5-u+;`W?jq3-lmQx~yHkB+kpc}pgmS7f?VVg^c8syO zT2`}Obh0k>w2BH>jOZHuB4!TyO=Db2hGCujXrls6vS3dnyL%fO^!~%OICnO`ie^*L zV?5{fMk1;Se(Pp+l1DxVR(<sG2T(xs1L`8Vq3j(gSLB%oG7FhLYTZbe|)KiF(g<|Fp4woEW0+4Q5Bb|o8VW$(`pRxkkf>(Fvv zU<1mt2g3uFFS=jk!?j3Xtge<0dE-T(;+7Tsw>>6W@<)`FAd1Av$!Y|t`#W#zMxLm> z`*#ibK*&rqh$`${F2la`e~o20`0Q!&EHWnP(0Z}wBMbdsLL`z#M9V|Lft-#?egC#tt)uap5~2@gl-_BHEW@~Cg$ zdwHqv*FteY**MtKc63$Wy7ulMo=>cHE#A1!DyaoDY;wJeQyzlF&g}0 z;TnV9^1x2vu8eoB*2NfK606olnpMRw27<|$WBy^sR5!9~;%#u{0xQ61r<*6ri(&*A zosVs}e8CayTCefgJf!Nj$R(?96$O&?A(h>^ZJkKP63P@h)FFyD}7~11i@t3D=vEzNpqT5I~P~yA}o5rg$WXb#_J+E#d z7v#(Hd|-`(L8P9|O_|R)p>6LX0z4BQB)8CD@hi*PRh!<%Yv41o8?WhQ_1ZfaS}2&h z8De$@A!jvd)FoFn@H}sYiW#kWdiqDD1}NfMeW1yg(s)yco2KtnN#fU8xCE5fY-4?# zc7`QX|NEe;7h-j0ia6504Cv#Fv^2eVZ(&jwK8*+~4HyOTfr_h}*GTQ|{KY)K+Mpbv z4d2f^p{p|0k6+C`{>u+!e_g|7Q<_lYhV;GdCoy$&vK+Tf2q6x-Q*mWMqfv=Gd04KDovWy9Ka!oeQP*#v`5F4E^YOLz zb2(=`CluE5h{!+ymef8Gl_^fqC-n@|ZAH_yy&z|ei-L&HJiVncsG{S(A9xy6@ zG~xjiYc|(dN)m?aLwv90HOA!9JKGqVEKXnqilnM7_W010q%Z?4X~DwAw2y$}W^*|> zHp47R#>L}kyu12fA8owwx9lR_5;&f`=N|4s3)3Ht7$WowUmf%&hR_D&mX zlxA&G?&f!SG(mAJ*suwaTkc`IwCUcE@mfLDaZPD5gd`I(HCaVro%COVDP>$c@+%?b z!8rmDLNE7j$4h8*p*xDYTck*&=hQ7&$<4c#PSA0AeEv?I>vk-oTxX#*cL3P+G-M&+ zxMa?SI@tsj9vvS`|EQpECMhervVz>2{HN@&VF|@3$(@?DBg_1J&+m3|YhIpvOXPFb zMf+=r!z-{2y2id-2=&h^boalHg_Nvhl8jp8-~|5>CCuCWeMnwY8rs#AX~UuGN?QsO z#cjKPR>ppD9`qHO!HOUBj!;Q^*Qu$E0=c4+XOh=YfvbmB#y19;rKwY>M6xs``(Nho zTFQ^P*$aV$$b~*)V{Kh%4o-ZEr?X#a=O+qXf>!|MiKrH8vlLq3w;2JI{X#3g6VJx= zRyoGhHh<@PZu;{jwc0d)Pwo26b@={r{hli)Dom8XzvIm*8kdxsKEVF=GuA? zuksjgoz3v)GOO69Gy#5$>!$SMU{5Bc!=^E6S|lu!SU=-tbZPPRVdpn1gc>X(`+RTW zC|IKR=n0IRnJq5+iL|-WGthnlrskJnU}qkzN-}lb+s8-D>+x-PvgH&zbJAKFMg9x{z3+mj7q zX4r+}?2;~16++RRi%>Ot!Ld0LMmp*6c^i;ZhzR9e@fud-5R@pnW4HLlN#_hD3bg>f zA}-uSmtOMPyYEp`0MUYO%ycZASrllpafyyok2c`uQHEOdOx7etF`zXTyYTrSXw1ut zdJHH*a;v01-r55MmpOgW^zLXPpNw5pLu2A@R{*5=VOqD^>Emc-l9uoh&4@jCC`#+wZR-YG81f=r879&C)mH z=tVAcNPJ9WT_%FIA-3PsBg+!i+}Es*<`&P>u3QfKfOhm6hG=TfKuizxzoZTv7(DLn zBLvFX4Z7jx@&2RD-&ITR)v)|J7aOgUJI>{4@A??V;z#&0(C~PE_VvOPeoFCHw&-Fz zAJAkeiWw(qYKr9o$*bwnJ>3AC%Jpf)LCu*`dW7M~K2jsQhFvfqFS-j+7RQJZ6Ynr_ z-FlSUgm6*f_mTTwFOXq;=jF|0nXdzWGM(F{&ZRlO-HAE)Q&tImA~L|Y;Hy9kV!Yx4 z&U;chhcl!}ZkpIluF_@cHd_Ob^k-yba#GKz+esNHiKKU5Gce!NrG`E+^|``(GG6;q zHU7Rge>+{#T_mv)!N-s}s!N+92sIl068sPj$IPkb^fLU0wsQTKYFg`-u z=`B4f%6M(yN1)et%93WP;fuVRR5+}BMP=NMKEJ>TYp?iocUqKBp*8cmgmL#COIHWm z>ch{u6oq&aS&8sOkVTG)A+pO=gsU&N3$EpFXt|tmQgtoi#_2u{^_9 zvybciexP85o!Ks^;mZYN*O|J<_#5%JX?u>JIC^N+18q5Xpvo>17Yz;H7FtJd_yKF? zgOk0%nJK97qN3CY=_l-G@7@#UeFG8`SO(_ z_4Cx}M#-9Kx?d%~BYJ9R>%Z5*m6^|6u!c+jlD+LHZo*Tc1aV|O?A-%LG`dcaUWv`WEgM9!sTZwhfWL5XD)t97I?pZF9|%XYaCsn7S6WVlvsHdg{c#CBqXy> z-F1SOYR*%l&79}x^gd-$GxT+?-8-m!WF5*uoEq0N53r5u9JclE4AvL!AS}pA&aApn zW_XSCWLY`ICin?+n3?C3rjjwAC#trvBMA@C^LaBL1JZRuGF^GFa;RY#ElkMaisC8f zcNM`(^91sc4?zt8;VcBh+CJVukKNSR;J$a_bNa!YIU@CF{2IbwIP(|Lg^P!XwdYr~NqorXivu(4 z8unvv8sjz;ng`j#^HZ2nde9r1t93D9UgvCodXg9VQ>3N0{toM(D-`qly3j9HR=%O* z4B1A`LCa4g65yP+Vj(~fs!Exp#%1NIyX0GMIeSLwT&r94N1$Xb8C~co2;O?o9!KfO zi}bh1^~Px$hF~DqH@?Lzr{{IOJ|SMHHvm>4nHEquwfMXNG|+)BGKPa&L6L+E`FI-& z_|qF|q7~UA3X{~Ke#vO{Ou$P5^0KCBv|#<*nucKN*JbU(VK7faq0>b&OXxmY=+lXk zqXKK>WrYmuid>ZyMdJAzEgBRn$`n)ps&v9ZvsV0k0$8_8p zxo9naO4CuMN?bg9jcIJ*+@36`P!a)56f9zdAaZEO!dqM2G8ck6wQQ;90- zJtBIn;f}yeFQLoWdV=Qxp-Qv@)KMU!7kDLl15K}fEp}`DNX!s+fXZXhpW8qsyN601 z?o{rRd|H9JtpmtPeiKf^{zZ2&7bpTIFtN7uh@_Aj@tO;E?g}iY0^nE|nu~nfA~?tx z+56VpBG@_%7FMAnKMAk4dDC|6MO^oqU+eFmV>r)5tcggY8?J@!8#U2;96X;4ef^kG zAI<87HwkSz{I?PSF_R#Ku9J2|snG<)bf4Muny+XL)OZSA*5_%Ym=p!)B_G>q?17W3 zZ{qYhbXISPTXJ9|EL6#-Sd60cueuslXXY5hKmg?Ozi5(~Qq)a+v zALgC`)_`i$9nOx+$wjYB#V=zlL3e6dcnxySkPpTcd4zzU?TJ}6J&N~W)P<1M-rA`9 zlGQ98Ym1Hf90g*CiHB38ykWn~J;Ozt(b^LV>`RAYYS0Z;A2%#WZbBWTVB4f^xviyP zCt77(-xQTB>UDgPsNH6*~z${23R8N)i`LKNNf*I{5qL#X$*vR|LRrFj-CqOF>@ux_hYW>5 z66p2eE>VIjp_l4|RCIv38|??bulb$-1bO2qW<5%3%R>~sRj0Q7@P*{tu4>e9qW|ILr9YGjwOO&-~oTx zMr-c_kp`@Xd#k#W|#Vju`} z+538@Z+?)^R=8(+zK~}RhH&RgJLs^qpYZvuBr8_kb*dA@3L&oD57NF!t=TQ%1iT!f zzL$8KZqIDjH6YWZhFhy%_Z$Ydbp1FIhL9jGP7|R|o`ZMU8Y~ggFNDmFd}tXB*s`n) zu^Uj?A8*UI0Y!CkEoT}GIn=2PaydA)wC#37PJ5XRx7vU}m0shK%tXuQNy!RBbGeu@ zU!v|I#K0WwxaFDgozL(y!#`2_RuIZh!a;rXl_yVBLy6LDLw1|q>6m%XB3FRCO&r#T zX`$uewtHYW>e}mpfchKMQbFl2lqUyuvCWjIZr-4b<@(9{Wd{v~$w8z4z@tGI#_5J8 zxuJsu6w$p-O_I$=g$~PUN#oY>oRdno?rx*Rfc~aYbCw~IQQ8w&Uoga1P{aQSVG7~} z-aJQWjlc)PQUovZ4Z+gK0L)B6AxXs9+^e&Al%pzciet`d3#?AQsc?|^mnc_sO#Qxv z>mq3#iBvht4wI#V=xIwShBLcuZL5%xo`*!)v~Cj78L@gx^OCy9Ula11KD+jtEB+CO zpfI4R!a0OgNaI zk0|N-oBes^s$Z`o6=j+zn(L}c+l71F(d`TCZEWEaocLfCf3dy+jAOZJ#(d)M`6_nd z_nAKe^4Vk3B)$Z#Q)|uT)lB_D8W~9S1ep$TXv8o_Jtd^y0)I_Oe)N!_M#9BbZ%yQf zO6aP2`;v>9oG|Pc%jBWOQ+K8wbR`w7D5p_4*t--1KF7&sPQ?f@#qV|ywWz78K;tn@ zgwqc%gQAaiSwBuqU&h`UaUXj?glz3!9u%r4&K^-7&?O6|q)~K*tSG>X$flT>aL79> zoz9H>C>+UJfwQc-I@cfuIz1eO5lBPfFeRDMH|6@UWs^;y)6n-|b^(@oKHJ&LO5;xZ znhL{Xrz|BP=;=_7*zGvBZ3?FvCOd7mPdt4IS3?k}Kj5`~ z^`Fm!Drtn5DiNljg15Ge`mxZ--EVt|jv#dMg$Kvcn z?+>R!P>gL36AG88`-<5>Cln%_38dXcIDqvup!B6DB&SH)-Mo)3^eiF`rq+6)a8kgG z%Xn5s=$F`T|G+@Q5~SE43l3(~Jew{k;w{It%K>a}>@`-I*QnQZtkG+HK*SoB#a5FH z+Yr#D%E-@}BHnOYa7Yp#dD!}gy^sIMd`dK{C`uIlfTg4VHcO_EBo4>m;wk0ZHTG)U{ z=8fWRP)+2s$a~LCP2#e)WX~+`H8o0AAR#j-ZVFPI|9Lp+GfjnAF8v&ajIY>l%*NCm zSv>V*;Ic;$#15b`J!l|!wM}Jd)Wq2w1!9(A)}cD_8NEG~D(&(?Sf+seZ8RdfLkTjW zBJJvcE>$IdNwZ;*db`f)^+my|;|^HZhn#W0Y_`L9>93dTo(dxtY$t%sW{NVl|#ZvMeE+1uSy#j8N|n|HFwP_s~^IiF%pO= zI118pW#;sPYv;4wPr@rtBGD(elVp2!GjrO!)a*DjTX_;Q32z4FtvQTg&v%aYc0ll@kyIdr8h3UXbeO-@YT@G8(~x-Bcma2) zNtel?FC{xMk7G(KrXnVN6a-%gnx6IY8xOraeEF`_dIjSJqAiAY0$0QzdZ-c|cg;$mrf5qAwEVPyN zLTTkv(d;;wXE3IfKWlFsc_;m%X8$HHH+7|&z2_eea-pKohws_!Fq=z5R52ZEiqO1!ISpGA;$P^D^QatS40FTJVE~+*7 zLv!0w`w?995BLZvpV-J(=9TfN$qB~py&VZxn>Q4+dd_A`nZeiM`%cC|)(rl-Fg|V% zZ0j;7_=6^+xZ6spyDK|^B$JIU#?DIJU3X7zQ%sW3`dN}lO^*(^o@!t5csXdh42dSn zC$b33O&+{6L^ZjjY?i6NcJSafY`3*Fe1O~5p>nCG4Hr3qmRW>ce{*iJYs=vLJ384% z&QEE?220`zg8~gpJQ#p&pqdFNu;&Q>U1ND_H4!4{g+`IONH^eo-*8k=O@&S;p?resVQZfFQg?qELM&pOvRCO4s5L+7YfsXaU2&EkSO_5#U}? zCZVi7o4jN@epls)K}!BP(li~m#K2dUj161_YJ79L1|6czp3fSMWT0*Dz_#6zB^$DQRuckLe&X*ays0R2@_;1ql+=AEB}^8mdkB}bi1k% z45{w0TiCKQ_l>ZOifXX6dU#iSmAN}+7}GFz`U~&O-~z<0n=0WgQ*Fmd5)^>aElv$11;NtE6`otX_r*+Mda&xk2Kh6 zU?{pdtH%a4{LWIP>Bas>5aQKU?3BsYSPg05&Q*@pq$X+G8aDVra906BArYb!r=%2x zNtmBe7v9zRIA~vQ?O)n>DbkJ;>>%3}RWdkgK7PFM5GT}va;C{;NM;*|)e`@UrAbX1 z7{@e;QP0K$adNqilr3BEgv~XwK|>g>_xO)XK#S}-Y74!85nH}nyPh^%xSC`JZ9}RQ zQR2uy8gsvwx+Du&2;}x&0AbzFM@G2CHVs)2c(`Ov4DEL!ZkOvUk1Lv13PYS5$rAR5 zY(#mD_x7Xgw-IR#Ov<-FKpZvcvTM z{nJ1epg1`0i$%p90#I@WBzgk1Mt5PP__4GQh2c<>KL$~MIpET?@_E^{3?YB>WjrG1jY5KX)={n3|v>gbQ(_| zU!|5Z!=!!R^qK0u9}IL4E$ktQIOc6XN|LlKh zY66hV+eCeO9%wH|YN&+j6p4wt*2%r$Ycqa?-L2H@oJXO+a7paYfU`QBk;{xpK2kro z0G{?XR85bpo79^xe;s-r;%88DtR|!|#*LZabD38^!c%D5cwo?hBVzLofGD&!`DcQy z_P1`FKxdxQ)x|@?D1a z{j2lVI=jfHrb;hs=$+b7;!P4c%d{2L!#Sl|YX#)#TxaqN?Q_V&0MHld7JAV^lymrsc6I>n8x{AuNubMj*yDg_dys zF}Z}@nSZi9?Z5O6W$DoGa$^X-YWvEqPgVO{`);ACxFs#O5(JoF0BnmZk6V2leoVZt z>-<%8<;u;AW7{7EC?k^?IQU|u@OI#2tDx$dI^t7s@@3Zour8|eSz}MQ&nJn4A>0t* zOFj?tZ=KM>ugt~`;|Dg{ zKtH_jI4Q0)ki9=D3yWQP+Q-}UjMCmKQxFarY7MOM@`^VC$Nrs0c3a;cGN%50qqnD}FI-a;G!{$O(UdHJ7_;DD*a(z!_nu$V}d zT}Y;(OSeO{vAdmB3Z?CTY8ORzy0A_VZ6F~0s3Ng>;p(>K0mtBw z@hhLOKT11Lgh?8Dt^{1dMV(wUWz@Z+8%s9MvFv#M;^SYxP6Z{G4KTJ zjIqiQZhGsZ^j$HW?Det#7eEKs?45EWt$SK(8;LOM!^6hr>(Tv|EZES3^TbZ!^)Lf7DNI>{H}7_naa%0 z%(Ra-l^w8dG%E{mY_$aq4+ATGo#F2IMrXmwz-BQQ_lFb=A8PQJ{w2`-k$PILFeH_w zRqrR6dJM`mS&)QOEJ`1bBNS-GUJIOmXc(PekeuQnDf$IO#OTrsiTj8isY|UM&{=!u zK-HXqj1r&8fx(1?&i(9%Vcd&Xlyz*_fZKlH0`)}h-Bg4YG|TmQyQ&th-{Ie3BA7rI zROBKx2BWY-hRlsXX}?xgYjAQb;}*a~AaU?eIm#>-&g%~|bi>G&-nwWYGmWmOkx)!! zIg+o5a+*ake^ct>*-?}vZN+h&TctK(T3y7~8OG?dutZPR+!=l;iAU@;P(kKV64(uh zY*5uYA**Y-;bJ43hwXlF!dB4tN4a9b_Czm}_EG!#}WZ)%S?&#o&b?#84I#8ezn*bMlD(xrX`G0HzK=k zO+Svz0JS)C{f69b%b~rVmCQq=X^?VB&|lbN{#4R3C0U@#oc$v9JD=y^%dL3quRG%Z zSd0K-TM8cYH*mtBEMN>cwLHfbdm)T-&NogDa8m|&2(4pYGH-BhDxv|s=ym3RsdVORh|80%AD_DsXb0Z}pOSyeOglnS zK|h{7{LCcVzfuv0=}%KUuU>CLyGs|C0I!VCHrc{u=$feOoKGOiV(-h)@Z$UFwt3iv z0j;+jd=e6&9z-AxKmLya&2govwm#=!+Lt@QTzw71tWNqTNKAHg8ixQ0X>CPuyU_V& zKxNS~G**ehPCkv|nX9lH6|^_q`C1mcKZKy#1V*lnN^q`c`g4pz6D0+rYiVdd3UXOtlEFSYNu}@4fg@+*9E07s(hlbb!>k*4BGO|{2coJDUKZ!XYyj2 z87P4AIX|R^XT@Kg@6l-r1XTA9M$;n$$Jb8v%or9gn9*5Ic#2w66RQC4dK3VAfN$zT zj)m||`t2wt+q_B#9Bpi~fju-FK18fPEq45A;rE(Ns)uTx7ODCr+>A}YCSXU^vd^=?Sm)A7{v=P4h--J4GbFG(GIY!qa);pXlQTf&oYi`1gUTUKrxtaV2&e3 znO+2rV`LlDKKHby56}b(4M0Ic(*GL9EiecO6Q<#x4}gj=2zG6sw*X`UKOd+m&<_#! z7i@smB1nJ}!pXU_z0Dy2H;cp2{sN80=8p|x2s{tM9duA@Al+Y=3Rp=1et);hVUGd0 z$%b&o4@jGiItU8_4txvyiU7^9{INR%Y6TezeA@)vjFJp!6>D&wXL7<1Y2&|_1`OZ` z@CWy{^`%Y#@eFSs9|Af(fC%#9FHi%hhTz2@Agh)Ed=P5@?4O_77f#@1zTU$>jtbHM zp0S7gOMwd#pE3{Nf6M*7lh*`_a~N)aY9G4(cbV{{p8jQ>8lWXLfP>So5X?MV_gPG6 zUqABG<7NMgSBr~s3ik4OWda(YrS)Sqv^bKW3=ZYs_#Zp*cewD)dcYzpxdqQ27(_!_tYXzy>|oij*h003kg^!n(< zZoiKlhXBCX+N;Mu(A4gE!ZrnXPC|JzGg1K=;F1ga~I4x|4&ZZW3gy`AQ^&;M`E^Kao@bJE` z905vB60bILM7y*sVkLpyuYqn0eDNJDClEHkuZVj{_?)dN%|Jrwe z=D%1e!kL%mFJQpk+gTr_X+9dmlz!Cc%osetzySe#_7~$`-aCL^|5r>iNY@{s2>>}b zN@%+q;C9;?aDCu_gYQgo7IeQQ9JuCsz@5Gzbuj1f<|q1rJj^@$>ln@-Fcc&Zhphkv zdpPMk{+3U@7j8h!0fCovcvBJY_>tW;o@2M4U4CEFw=Fo-FZw(9!PyUc;QQ9>mmPfY z5r2Yj)?eidzQDO(yx+`-$pLYpo=WZ}Fuh1^9PCd2a zl4y+VNG)yefzQ!#4YonprvG;7c>2*XQFvXhxZ~|A<(b}+D$g6Kv!kwYQK0_CfXf4h zSF~KSL;sh-1?)}(UxcJIgfQ(%zC@GR%dlUNXRuo#l2g^R$MKbi(xl({CF8IYBHaM z!YvB{_*08MtI6&^-4L5;S_e^;J26@RT!gOp?S;L4SON^=*lpT2b1P9E#1*2JaLGU$ z7ygUJ7>>CkVF6Y2sltpXA-)8WM~YHbn>fTLkjzHBv3?KPfx>D%#aUUr--Yj=DPE`~ zm2$eR_Y+J=RfVXU1&$1#7mpabaH*i0j{Pk`);>%9;fR9cPwdkt+VM&4Dwx;P04`!z zn+~AVx!<$71-(O`IL+5(9NQg(%d(afk3f5xC`M17{C!U{d?l5O2NKphNF3a@*9RDI z^OUZed;)nc!qbWEfypR>IrKO-Er^g=6>(;r4RinYQ~D+yYwI&<{vtaih1ZE%_rl6= zH4gJzzL&%6*`-`rRjIKzlWV|TJ1=wDMhE_w%oc{iZtXo)@o+EBO5^Q0?Psy395jgyJgg_Iw*V?G(#Eott!{kO1*Dmuy69oO z58dazkK#{XRD~Sl3nTIDdX)6kaSDd4S@LoWL>jbzLmVtT~!3cwD zcqO1$Gg#qM2dgeb?;}S`&?}+w?-j?+hl}pb=5qh~Eoox|CwNxd&1!cc_!m-|-pF3` zb($v0aT#Fe;C4@+4@%YN^?2<_*xC2GN1Cgk&dP49BAMeR8mK)m zMHsbNIwMQoQIuU^0v_&dE z9sfxP)(QQWsAmn@;gOnjMT@Z=Sw?wcOFw{ zJVE`bl_UBlU1MKMqRkaQH6Nn&MP()wnT100sPkRbPxRavgg=(W^koucmMa@dK~Q$f z6yMSp(QtSs?IYP;AO>ib3SOX2cxxi{U6)jwv&qe32Pb)r9)h20+;_$7yovwz4ma`p zp+wt*)E^aS@W#i9=eT`j45tMK3!`fBqnC-@P=eu6cixl&Qc<%%c> ze%L%s5Bdu}jc>;=&NvnB@bJ??!^6UqTr@_~3MF1Qm+4Lpv#0-goAzPY@GOig0dUz>~Qb||7QH>c@rnqdWQ#vx^@i0gq z)|Wpe6?$p#eA$EP^e+6n-GitdHc9{4?x}kb{V870t82!K2wI|31`b>N$OQFU6R-Z! zXqTXg6yYSn56t@Geq7FU<3dBiTI9;yuqur7Q-mt-?CsteI3r^3i-^Hzr-=K%u@xxI zsF`D0y_$~1Mf3XD{6$-hy3so)_q10u|CJ0qA|GdagH*j&g2O-0@4m09D@14$EI%0Jx=tkC^1h6Koiv~XoOZfvLn4^gY ziGo#5o$)L#7BJJIB!4u)J!2`I*m^2NeM$ctuAdr~$JP7N!Pme_lNQN&?L}d@xVU&^ z-rQJf8@{^x^Ih_12@;~XwlbJnSt+9#r*ndS;<~F#s-b-;ioiGd;za{pTDCQ)-;Y{* z9A1Jj^4+TFVrF`=vEG{|i!aF*+tTQ*g|oiH0#e<7s!{w)%Na&dImht&$iCD4TeDH7 zXg72_zUvV%$f+43(+eIIAWzH?VI`rdeTmpR?Jvft!FVPt}BpM27MD6e|pki^YBU6`VZdU4zl3 z{ug{hr%~RpES1z>L{obAPkl!7#+g7 zST{ZI5!biam;at~;JgX;n&g)eEz^bcR0t}8xdQc-o1tzcu3-j5l_rI`5|%AOj%(8!U9*{ftB0-gc_*RkFr5cAzSrU|!=l@3iq)BjC;J zbGHX1Q$?&1lP?kwd`%R@XMY(e!Q5NVWo4y++Rble^ZyJ)vIn)sDfAW|Q8ZniJ0Zbd zXhcuU*;F?2%m-5*JC-1mUco#XDIc}`z)cV;ch%#F_!XhZrxLKL@%BL2f8(nJU$@00 z?-!Xx7J;y8Tvv^+me7$vt><2oR&=4XTYakwf!WJVK;>@KpVix`iY)m(#3i%0&19NS z@#QZDBAR*soW<8HkxI`jEgojl=ECf*TG%{|g=4I6*-~YM9IuCgb;s5ox`g5Q<2Kgn z)xn$+hm7#*c#|QkaO3EZBl8IA7WcJcN(f&KkEV;{D;Kly8`$kfX~)T07mHD*uhEN_ zW6+3~)ELngJU={jIalhe?*eNeZODc*x$2N(9T|9DtNXvYYc|lnVqB5z0wmZ%QZ|OH zGLHL46|f-DFXox@2}=^L;{E)KAlFFwmlAJMnm%m`P@`S~Jv0a+vojOVB$;CWHb=|A zY-)IxhKiFKK-jcqAgkVcKD9I4j-DU8bRe8ad#n@WE(5~vKi!FAh-d1qgqBp?BvNY% z(CzXPzhv16?MRZ6_dv=6E@|0SVNxwCQ=43Y^M<8Bfu5*Idz9omp5AzvovI z))Y?74F8l)7j~at%Ho87ohV@9=u1cY)O_vg$ag8dpSFhu0^T*nu1R<#j?e_k${7Dx zF?L;*e5_)+Z7PUFo-U}L7n;aktORVSRcWL~or*t@Jjo ztZ#5J#Vd03$tbdT6jB$+Z35%{wDWjuT-083>2`8fJiO1>X=#H=1E?gz z6)D2b59VB^3~2rO9Ho9R81v>WR##|F_=1H-43*&>_eKBE_-GB%Hb$k(J{Mjf+A|jm zO!8z?mz-#0xSX;x_4M`=G`eW*LTlysEuq+FLwRGhYI-=Esss1)aTZRLR`~2m#nJIJ zpz)zAHj5RSE4c!fb+)gh^#eg@nZndK^zv4sEY{1EPrh$;epP1w&9oNB(jl>aIMokJ z31Vo?JsNkY>2qGySa9!ASPQB`TofhazVOsN%Ta3A||V^4qPtvfGnUs!I0Ye+}o zmzQ(8&i5G+>($L8L=Dc&^+MoS<26zcU$HWcwMQ%>Va8poTxBzXrI%)LlDN!s-@3FW zNZd9VSvsV7D`7hB6Jjd96yRO*B-#PqW;*QL949E8EXxHlA#TyJ|Fd&(g%2wcRB$*a zk{7X3V>_QSJmP%qX_8gGHO!}ygF}f4n&{*Bc=z55$WG9}S6-_UQL}RWF^c(5zWWLD z?7hTq?|EKJ`HF7)pQO>m0;tR&*Zuf3z|%iv3W2+@ULEGXlehaOHQ_;!?pESQBp(L7 zQ7*}KTs4Emi3QV8w;@lxz2CPqL&BTZQpIcRA{nuHpmOkx%>U}Z{?n`5)8%ZG8uq^4 z)$rsIH90Iw(h+WY=szSb7H^7;q`&) zOK+TW&V=nta@Z=9cWFs^W}FZ=dxfxFr0^5bQ1yV8RYeeMD6-ld?pg46K0vjrcM6$j zJF}8yME^6g(|m75MtFVJ8{szVcyW=6A^vr%)yFY5hKx4f*d8~}43Nrua?_e1or zMEZm?Jly-I7EOy@2?arwM;e{u>kWwq?%a^v(Z{`&rYihV9|ka0BnL$O1IQE`wYAoq zfkONAD&*_qL{n5q!>0qyq0M6HRIqG52YEvZZ3;Vw-Dqsg8kNrJf-PwsBw**+iiDR7 zA+=BGXraR8Pkpl?v_9sWl$E2e=#|s4dCAVlkL-3c{IWJgP1XGL{{Y6vn2oQnPCadq zImK8TXq$fsD|noUUmE&JA`T*w2PnZFy<}qihtON*rbY&BT=0?XTqJ~xb9u5_7!#o_ z%tcOPHk6=w?Mw}5?CWdR5_@ZWs}@qe zS z$kgwJOe|CGSCT;SR|(#mZkT#V`l_FmUH(R#aGzRXjFB^h)Xin?;22H0HCzR&wLAyj zX^X|#$cPqsJ>xYQ29evH1kEs)9VyR4BW4ml&gZxD_=*x0A*WCV(H9AyH7CEOL$n;7 zVNVF{Yl#P2sT+?{RFt&rHIxLF3FOQ-iX1t$?$w65$aw?6Xaf$wDPI#gaKmN(u`Pdx z$)K(&Zk)L!Gs@sLKpFQ(b_fovrS8--|H}so`&~wcJH%slpTw_TA_;LZMBO8X?*VLfyF|VRFcM%jMF=9?FKoHg>gLUB8%b=^O|xIAnf(&Wpez3IoV9l7RPexacVka02JTo!-IU@D(ltAzb&L@mymst$t%WhhfLIMT*C3u zOdBXA->_0;#cS z@KV?;o0@(;3usL~8vMr8{uC}&oDudM&BY;!=)~a_Kyu2}%{!NEQ{vnlIgws7Co;kl z>Y}(zA8VYlCr*1I8+dQJ7nKa&dE!W0tJ%C_qbOahLN)__3p-1VtO>$05g?*Q?I?P% zq*ZG1UbhhGa7r#{W5)VGftVv=Ss(;D>iu#vLV|q}H>&7_RhZlL3ES{zu$h`l+RWx} zC%@rcBGwXkvwBB~L|)naC%1=UK8*giwZsAZ0X>UHm5J23HNItszH!iVxZ-x42eRTP z)*P%$1CL@9N_w=eNRpd5<|WDHf4DA|r@st+W$~6cr}Mo3N@|nK;i1p=?U`%*ILO%B z@(cIjlFr=F#2b@^^_YlD;Y#x2StqPUHrX;}US5lR{6_V;5A2^u_b@+8$@ZaE6A*`2 zX!7&w8yzt8a1q@W>vDW}72s~%i=cm&cof|E3?UdlQJHZEZrDX0mSHH1_b^i(&Tu5) z6i)@gH5*QwNP0rc(m-fmO>@#&QIBek?u9UXu-l0a$z0$OR0lPan(1`s^kA%^2sA`%Of>H(uO`ysh- z&sEJv#f?({#MOlF5m0RJIOa$2x)HP(i{USt^XJ->myda~!$7YA9Kl%ib|iY6x$!Ka zET2}35tcf-yI{y`ivg*0Af{AOJ%X)xHIF+IVQ<=ra{tu6z=)jHw2?wOoY=%QhdF)y z0}JT?OC*oO^yTFUz3T}}t3Ku8zg`Gn-}G2B`L=8-wcmt32UL7=`Tl(Z`7)O4#_jJT zda(L+ea^$mUf^pWd;Bn)$?U8N6Wn<$L){Nn8fp-&5^a6if1B@sDatjXe~i$}$0Y}u z2MsmYt5G%4n=1acAda7M6wYtz+-rpD4OuQUf=sOZY><@~w-C4u<79w*^zg(fkRAI5q3$)+ph z&=AAFw#fWoT>AKnD0JJOE&s!{6ca<-L>fEL30Xu!^64g`=5e|Ncu9B{Qx6?ce4D`$ zE@jKBCsDdal(!peQO^4Pv1@#@EbeVH`#OrQMfL_coCSphY7 zy@YEf60ug!8gy$w{;*m5c?^Za0dg|gB*$s>&yVI;v0yKfN=}-MlRlfPdKP_;;Pc{U z^1eXV!b}84Q#mPzj{{vil;_)n`x}~ju#9-S^l;IlWs2BsSf*y(IKc#Yj&s&VYdar2 zd8Ab|o$}V^gr@bbwP*#5hK9ib) zucP47p}NScy=SLcEt1)Iv;8;7vu~5@6V#q|LR>oq^ikstfc||SNfVW}MrEGlxCTp) z-ipz!4SDi|sg@}6Ci5;q;8U@>2_;mMcS9yZ?@=Q*&h3OdoZ|wmW;?w0d4pYU%@+_i zsMSgt+`B|ji8nY#rC2t(U!7{P$TKqK8!$Slcuz?+i4{9;EmL7_8B)^&2~SfWv5N%I zU4}L%MjKM<#OS+y1H3v=u>^8)Stm^%#^KDkkwPBC2tUo{()IOPHBv+b_9<5@KV+E` zT_KOi==dPv1pmmb&_lgMh&3;_sq-Nfj8uF@ze$W`j(L`RfuD0ssw|0O{ggTxMQWd! zB(jltd_IjokFL$cR$7h}Jx{<>xfMSTP2a%d#EJ#YlQhZO#@m)n8>hJmH|TV7k_ra0 zJBIEKQJ;xTS;HBPtrzo>Gya9*)vWgtotTfvD~vH7LkXL1+I|LKt!pi0!vyy=;Y zkJLHTz{`V?Cb^Ju3jAmgV5bK)a(ly*tEM93%lTFic(_#7gxXTUz+aOfu~A^!Lcgl} zOZhdSIf7oZLOvVFxGjf-$>OzW;l;v^7m_k+Z-u(y9pBK0=kg>?Ctu~v?`gRZ#7&F` zdMHT=^o0HH$ESxJH$8+>r;F~hOdOA4{c2w+U;5&Lb=t%i!_StB3r3`n-dsYpb6z|} zmy`P37ft_BXEeYtduwQCyfhnFnp5I6D~Xp_RoIP?SFg@{7b5$>mjoL3k(===#wLOu z)rh;4D1m{GaXCK_$aD3KFGbC67`un!H5B9opTgkrS|`xmih-Am*prG$;x~=klv{v) zW*yC{)@mle;M4kx-Zw!pk*7|TXIrg$4&ww5{)){`*KKV3{)Qf-2e|oy8czNu-VG^q zZN^Dsr6U67K0rb>3cVh~%4b_5c=M)mZW@@Bu3oXHubkSk$&<*HJ@wiDB@^5$`2dbs-%c4rJOK}E+azHY&J9*ZE@btT~E1l*ALFssA4HNZ*D zTH97wXd4{VMA2zTFMzi+s@bP>Gu6U~N-SS?`nJqm0mbKfz%wdcpt?A+Q*;yWT8gPh zOVu!G2!Qc>ql@uHI55G_1^+tgBdm4;2D4x+BBkk8gA8_R{C&@b+`9fFiET*t+g2er z8_KWyv_%!&V5v;|U#UE*?mmj%TMT7-wZvJv7}&D0b#<)$$G}6Wg6>KrwVOG*2=MpO ztxUI!xK0)W*3-JJyL5MFMX|Eu}7|AuHU7jC40BBGPu9FCq)nO@H_Bg9^tKc4c^5mxDGz(?OE^#iQ`W^*mk|SYs zY1H2m4_Ky-D-!rI7cx-jO(J@fp?s@tUqgww3#K=NOWS`jrhE@$;vL3(!C+(7)h zlSXxJvs()Z?QJDvPm|WtQTS7ZEq?AzTyXq=@9<`t9@RDT24yJW?JM2>3M)I%taMb6 zJ6Tjm$*II?481TT3o&n^gmB%xYy%g;ri|1Ju0G^|-%BYr?K`je&H^Bp9R@U7OcLtZ zj8A@CDuoVoFwy*s7=c#&u(TMMwt4SA*MHC6>Fh|CWFmmxo;WzCcnkuCq1z{gxey3* zm1B@jlPu--rIX?D6r6MDqaOL#YC*2Xccj*H6G-nXw{kbyQiY<49v-yjN5&)q2U(oI z%S#YRX*WBT^&ZH!gJb;$*UocEeF%Q?9)Pg15&JF_Y>n@ zhV`7Bqz6ldt5*-fNLh6uc;&jsoCoLT7fl<@aE@94g#8wX_O$OzqNtpR7;K2kr9-A< z4W8ZTk4d{01*BOYmYSO=+MqV76f(&jk;FHug6aqR#IX=VMVBjes4JA^R6}1$IPt*l zq8kO$@;UfY6(X}rgREII+7Wd>hh|h7?*>rmxXmHWo*aBohs~giP$scm;#sj)2@=*# zO{^w@5JFM6RqfM9iEiH-lL2*bI_Bxjzc@apU0!k0Zl-6E%$M{x0Yd*l8Q`tRH-3BN zXg{~5L>FkjBNU&cd0>*x^yMYq*vTzh&)!uE1q*O-(xnC)gYAK@$eHO6R>`p4=5xfW z;q1gahn^SCq%#&(!0t9H=iYB|r}B29YHNBpW``fwkkIV-(f~7WYsTDS?S17cj|M)N zB!x8J&Gs?4jpS(5weY*Z`HeIFD5z9_BaRUcpdW`==N;RW^HXH!ay{AXoeKpNPCi4FVH3$u&9J0dKH4`BoSr%T&3d`VPT|o`>3l~3Bqmg+n zd2Cj@Fn+8oz7XrcoyA4h?H6WG!lJFqriU!}K=bL=iq_#}$O}JR03)sHL{%#YZ5Ny& z^By;hO=zgvYrJ*gT((q?J0?T>bj~iEKUYgjf)mEk_Ld9}BXg;J>^+LhCRtE$8K=CL z*pn*e6Md=U#emiEGj=Iy;AJyn2-~ZnTI^)lTLx5ox4Wx?{gMi*ujdj{Tl!gQb{ks+ zzbe2c+MOKK3N$r~xQT2@qF(+0jDt-o|0iLF?SB$xnAsWrUtxxogNgC~IsJbJXxP}< z82{J8j0>oW%H3yefD08YR2GtgQFuXDf*C|fSOy?i7$ycrXGw9f2p3Ac+C^$|JesHw z2qGn*AlGr6)L$mst((m-pUT&7E)V%#a}jqDrXoH6j*9b69>jf&`etigF(@ zXn=r`5J5ZzCVU*^BJjU=YqBFoVS}9njOOV-pmHNbg*fOetmPx1vM@p5Hb)8p5g3Go zc*KNcz(4>+1c^_50T?wfgwWj zIBvuzYvFwz3wm31Y-p8{jt+taynCbmPX%EE#QI3f7sTJjH80C3^v&Dbet^gjt{*Jm zSO-*AVS*h;Nb9El_`is2em3zCZ~!pLC@HCMUQPjOb_^iI02cwB?}U#IVP3=laI`Rp`>(xN|J-pA5daRPQ^0j%oCJ%;Ka)NNVw~S> z`qVg4FW}UC=-UW@eEmNEK2803=vcubpI_j=9(_Y#Rbp7x7j1vC-!^$s&?DG)$Ve%m zpu$B11_B_oGyoD((SQK|Q^pXYzgNId`FgfZKwybK%eTYa-<8HQeX#oj;WU1? zC4DAg!UYK7Xzs@~cTfZrz`)-r_X67Wo+$gUFHmy-E(G+&4|7RZ78u~a5=O;(5P%V* z0zQ*`XsQUk>P`7$p=gJYH+wYTK_QFiF;NHyMm>Q2fPuuH&GKdxf@_eMd!a$ZJ{*%j z3AiD{26UjWp5Lg+KdwJDW}t(ZfCSl|v3`@G?5aU6IDLvHFGxDrs7U4B-H2UM#=pYZ z>kb=~N-Fnf;cLrj@RQewI!5s)^)=C`xvRS!Lx7#8kK;T%;vojrC82YJK8k&QFV$a< z9bI(tPt~&(YG`gomhA+?s)6=7YxN6S{-S`b*Tt@CRoM<~*c5P7Iql(Y*S!#m`>-RU z@QmW(VT$`9t&}D$YE?a|z8s6CQ@1@utX+xT+6J%W-6t`W?~fOk3IIGO!W>uIm_=1{ zc57Ke+Y;p<(J?y|kEy2;<(y=jUYRYpB35#7UFR%STKY#4>xM6zIKI_B(qJ>k80l-t z+&ac93+}}*nKWgcWyPP5RBH!ywfi#PDVxcrtogB>cIn=e-NUvzg>l~K4<`x3jRCrY z7&Mh_*1puJ8#WfC37P8;&FY*eDF)%_7lnyX_r#q-m!^XF-H@Fjj1f0*nGJan5C*eBjhMsD3 zaoz`CZp`gN zRev49z^t;RM{6WwH1LtpZ2YZV!vz$cb;HP|q94 z3U(=hK7}pbS#i4EG&oe^?Gzw58prB*o@3y*yy&Y`(=c8)XIsa!84_4>Qx+^bPe8yb zU8weOQPYf|I*3g>P(3U2?^ctLLYqD*8};i@T4r4Z(=eu%J)B5InpzrnbxtKTyBpRq zE)AB)9C52J$i+JjH_6aYV*QU$#WIuvDh}e#k{iDxS z`N2p7J@C?)Q~Oyp!Z zV3CeMGWzcSi5QXpZHRdRumAGa0-90!FCiK3sPd*^!d7|z~)7svClK>Xcm8mCR6n$CeH);6PE1&o> zw5*W$QmK7!APo}-wZ>jES{^4e!S^kw%V}H0_sOZrF(MjOOHr3Kc+394&FVC=sxqJ357V8~M;) z3!zqN4)iKpYFb#Wh@G%p+H^SibL6I~`sF%vXs1heT`rB<=xNGvp=C)Wf#6+g%e;_* z552w@&*sM@M{x`0W3c`)q6&SSTFn>tc=5pDXY}uu@A3Q;m?-R7*OG|o#!ozoz~XQG zy3G1f%e7i@4re#}hR?{aaClq5RPDG86%EPB=L2}9|Elc3jDVDxd_5?VRY8a&UV!P} zTXtb2l784u`8EUTr^B9v5s&ACSQTlHS@`CKFJbo=us-v|*f)J2ZTy2Udu+SYSB9gd zA$acj4RsQg&)`3-A#Z8=g zA&f;ja+}zQQ2fISlkY`f1hC4c8cgxi#{-Ky&FtE4UrC>58>PD89O1zJ(5dW%+iQj` zT>7Y!Zt4h2SNE*?j}2Vr69|}?-)6t*BOc>H+7)uv3~WwJfmnzd_-4nyNAW;+XXv<% zu?^_;ayT14==7Mwml4d!(<{WM%0*o^nr0>fw26f7s^e!=DdmMK%KO|V(=1z_Zu_x! zk15@QW$(QxK?qvEwu11Ho;NBd>(Z15dj@y(rAPmm_2iQVQlayk?EJMo!lu z#Tt>`oDog=pDf;pKv+KI=;amypvjc=if6+e?m+hTK*F`SV3?U18g(6-3vVRaYw7Fp z82yh+ZOzFYHx3ylStRRNl zlR=iorB?o+Ow5wl7o4x$4%FXcbq}=%wTO|kMh@q2%<&>dEgBprm9QU+qK|WzCFO?y zN}nE~8GEF~=vNF$h4DgQB#*G4`lsHx5jTQ|?HgxPHEU6jm>I8NO^#@3r+R!>b!v9D z$&R@;2A{zPDkeB0L@_-jB<%(xfch+&ORv!wGsD8~)hLo9dV2iLt{|p3JH!Jo8mB_H zCmGx6EOSJ$5-+Lcb!ES2vGjW2F@q4cyGrNQ5K)`5LRx)&hN8SSTw}#%>8#4iX7#Bj zDKdmz86Bt|&c9Z~b`uBD6S+`Fp zPgMp~PR{wmO{OZDA4#VJYi%Y{z}5IjJ4b!s&-vE**AlA-i-45^-iy;Us6h8^74>#~VDbOqC+01RD#f$oFWE)TGuYwp#T* z=W){1G@R&V{&>zXL)fzx1&QSF6fo(=9Gf}fG2-OAz0y$}?ig5i3ZK0e46nlFP=(vp zC+bCay9k5X?uzq+Z_k^wao~lRG|pNaA63Pw27qia$y`o<>%xO9NThDpl6lTIZnbi1 z@cp?eTNl@#2QiK_j6_Z1%o-HDRT}Zd@e{<=ov;V|W(JiKIl#yk4iYU;(WDqNGyxrA z;VV`uwX{2e1b6o%U+iSW5%ej`Lmbb{I9_p`GI-KFJBJ5D%^{InlD}zNUqdSn1scvu z>_5UZ;RSfiI^w*K(tx0;@ID{KzDOl$%u0{DoF?rU{PSbCOd{Tf^*zQuADpxrqI|mU z;!=!c@S_jpx@MV4)OR)i01{R&6vF1M?X=rD$2=Q4cy@_Cls$vLv6_I}O7fN~0FPSv zOpmP{EB#~>x!F;PM`TcelMcOBBz+3CaAlii#mS<49?o#(ZFcYX0o}8}*+A6(2iCs2oKKGz;Zjh(du7G`BM9lYN_Jg@FMuk^iHe~mf)gCOu{25uJ<*it3*(#@Joz}m4!9DI$>o< zcE4}K1YTgH13VO8+hj+w=Yow!^Vn_F%$K}xQfJGiPni1sqj}I08(sZYt<5K~e!m`A zo1BYx{EoluvcFNgd$sK0A$y95wcjBjNPc3AX&cIHSt`Nr6I6J_ehSs1N7(4|kl4qxvk_oM21ofi$@f5za(UDgQy0mP$=ci#q{j%9dR|q??1cxBkHe|H$&Ax}X>vl-fD9em5%tZVI_@ILd+zG4ue^5)}eCj9o|o|a^Tcqzhn z8=iI!1N1fUl^CJNX&j5}c@y=9o0$<6ROY(fxno^xya-8k2rw;tstRCxjV>x~^BTv$ zDp*dnszW?|0GDT=&JRd-QFS~!udGzM>)p-0u{V6I(UPTZ8NDKXmLY$T`On^GvMeG_ zq{5rfbdVee&UrC9IdBAd)HjFMr zH>YjmTPs~kq+~VtX=u?rrI0b83C8xOhUJSVr8#F*=bQNs54 zod~i-YEWsuoZvkF$_b6sM^yDXZN)rTV^&?BrGrATn<3gyE8ZQH7mD35SzxgJf7N4x&uq~$8 z_?%+}@voxlsX35H6(b`bT%gN3 z4Uy3>#dK>FTW4;z=UJLH%)EMNE1-te1ko}xlmM%IBK3w8Eo1O>{jht59)tABw#eE* zb%vxdA0M0BXG|uV$Q`3MOmAz_C(F9jLb)3KTB;o)R)jtpc9(76n~1&>qXpy3xFT*| z4sT>1ZkXr$lOzM}R+UfTyLIPcndioUMyb0rAJfV8L)*BS#r52m<&4ohsy)J*-KEo( z)HvVsi`uWH1+~}~BA(b0T(6Fbd)ivLb*ThaP&ev|h6q291TIWFNZ8c*fcaTCxX_Dg zUW&ElOz7E~WQR{u_YZ6U)iKqB6NB$oWk{}IoTVCD4q`HwuMI89Q}EB-{t(8voJE}-h!9E zOD_!GmYZpc?vieZe#P8#g-dTsQx9hoO|7&_hU0K&$CY%N!OK;xAykuSdYNhYQgoG<#>6--VY6TPKHkU?tSb#m7v@&2Gz}(bC@0g#U znqTm*7d@}gRd+lK=Joli&>ngx#;8Nczd0@?i-IW@*PaZZy=jD|)F%Dd^rIQ-@aHvg z-AeelWu2+r=#gyqFPO6=GurKUC8smB|04tK-x9D!X5SAnYWKCl-<+p@ZmCpCL=)45 zk?801$r12<;8VyD2P=fiQ^-tmd}uOGMB>??*W6C-tBt(x)bZQvCZVr^xr$OEPMaP%Mb|CzJc+Y_?dV&hyp7UYdEfmDJEZ2iHy`1uhsC;hbA|Z zpgyuQM;cpJCG@zov9~J*_1%|vv0m-e?!=XuheJ&KA--2l=|*}HrA_&qX1-L}2%6wN zlNHo_+`}Dy;N0GciFgN6Azj|Neo>}^s#+06^Cb$$r)|a~uyLv1QBrl6{(^wx%PHc_NS6Aq8^RbQ zGz-}d{mExZAx|;KGxE~rnA(P)sL!=txlVHz&=4Uz(y{5o(8Y2{!3 zyG+$;~8UVI*Pj|4}suTFYjX|(>P|9|#j{Tb>zl%fIg8(kz`uQ=>tFb6kS|tZ>DTt&91!n z8Q2DTF9C|g2SkEsr zs^Zi+=%ORlNm+-hV93=3;#p@XqrcJU(^yVOwH(K+g@DY~-KvNJM$3G1YCmPf*jf-g z@|WmtIuh2b?6YHpZr{>#t~y7vU#2kc5~Ws+htd!M!mKcUsfkM0>6naT-6L5|!OoUs z%ewJt;-+rY=op=tA{^EwJi2zd^IX=2i`-3zYSf7yduiu?_otimW?}z%B+~-cDS0{9 z)i_J^ko9d8Z*ch9IqOWDRTr7nwx-lHVRikfOmWJOk`Jt1cgu5m@SYwQH2SCh5P$nC zA9{8V4N$^uy%7p+z16DKFN$MIj58z}-8bEXf6j4FXpF-(Pw7c^c|RZ-$u{8X+lL%c+49H8iGU6t_-%u z$?HkgF9Ivl#{XD#Eq{ty>txQ>1nzd=!t?O?dxhkYqISyj(D)8+@v&o6eV;hJlhr_) zS)#M?j;z8tT`b_WWRDEd8`}tEcX)Ks{b_zRdr^xqdQ5jG1Y}=@gF$7)*ptnAe|^Tz z`~k$5zN!Bwz{Tc_uT~N#GCWp8ZZCa3+x&#u(6;h#Ufs5 zsE7fGXh^^!fT^ykGbI251r-QL5JgA3%sz(tx;``MnlA z+>$5}fL3lT0HR{RxUMB4q$L3Y01!~gFQ`aiF(B1`m;;4?Iz;|Ik^cE)okM4P44sYP!Z;M5drSk&i3Tt@1KK+5Np@}`u+Fn>PtI9LpvXG z_>up%%8Emt!QP>Qh5>^JC>Z zQt^LH0q*o&?*V@^q~RmVXkq%l@Kd#cM*LB!@71IAN;0pPNAOXV%5`aI4{~vQy{Owev zlnkgx#yA2E8}#F(_)EY!j1W2ief|1;NcnU9tue!x#s(|M#t;=U5z3|(&V-vn)$9T3 zdkY%2;Je}5=rU<7pZs>%V9?NfJr6stDt8=t8;O8&2L z))l!T_$MeppTB1NflF%)xw&{}(a4fKGJuQ8W)0KT>xL5Mff34Mzc>L^P4zmB2z$#nJ9<_6y@#A=Gsg*)y#C6ElRr;}pR z28hG?VZe`NPuLB(1TyMYFtwz6$BI?%wv3UGkDORuAE(tPn@!4e!qdIBrj<2aiUgT)W-fnBvx1yb4qIQvI`s18f-fXBzxwLYR*Al)W&L0^@f5O_htBV;Li1 z>E@HEV>gz`bY*%d6c%sZU#G?RbN`$!D_@^(Hv%f%E@G0PF*kj-(f0l*Zx$@~zsX>aYqo3&1(#TAZ6W4a|Fm3=Lz7XK@|0L## z;_i9H^MaVE+9c;U(Fd4q=}rSkdt|q`N<@4F!?OrYfJ(U2^@bXPST!ZnO~a_@hl7`a znpzl=;jYieF84{(lfBrK`HqpB|`Ea$rV4WokE5v58 zGVjS6fiD|O(%F+nO!M?%B`SEUfO535Kvk&Seu`MzncuDRtjff_{$@zk+m-(BRn%k* zEBhrd>e{#jy0Gzkn<-SmxwI45C4pi>mQW??mi6GpU&GcH1nIH&ydu>R{`AnYiau?N z6N+6$moQHb72Eu>Z0@kxKuQ&x}p zbzgoHqfNZ=Hm6vixH%UIpL%K5{h5+zxiu{Vn_V#L$EZWY8AV{lyZeOAV7j%3~(_Y4wSAsp}3`u}0< z9-=f^m;eozZQE9tjV{}^ZQHi}m2KO$ZQFMB+%v0L{EJ!UK2I(pGTuj^mm45q(EWE~ zC&BKPI#>FkG6{=!T{kaHL&oyz#WO|nwrGq&m8=huw2&WgpgHUvY%_sxq%{Dd$1QzcG1GW(2!bQ|3P+Tfd82f+35!nA=$X30}5| zcJ_{CiqrubH0^#|WU-b%s>OeRcUs2uyn{m3Utjg%Y~w#W)irl1sc6sj1AE5M$UAaptQsfCT9yL~UqE{}Go@Caa?2xWx z_^TO!^Pyyb1sj2ju0y;_Y<(e4mm&IRg>;~Wbn|2iE>%D30h{_cuD-L!=5hja`2Db( zvV5PLFUMl7W;_G@HU1X;>BL`uO;+n6bEk*@^g~Tw7scth0UjTDZg1sU-f5L(AVTg=3Y)4p z<(My7&e=4e^~7o;hXu7nH^KWm~E;H6ucMnC?G?!KpcLLA+-SHwKJ}$;9 zu?5(ZEEpMPQGN`oNxStDQaWrj1%*EzJ-P!l;xG`Ac1_$=0F)b zx6>+f&F4H+6Ri;MC(7t7fJGf@jV?r#)vdXDiL($N>v%t%9xZdzO{4jT_i0v-!-B9( zTwrRJ*0*H5mi2nmr_ngQ@1t{I414Uua>Hi3jR{ijh??x6@V5ORElp!t+u3~w65b}d zsKV46g}V3k>BDW@yj2%{wC7juI-%)Shroc@#>dPZww5Ql>o#v8*6NY!%#)FT(CdT5 z6QdXamLKMsOvl<7b*vdF(EJYYGha!d-X#k7|nS$WgpGZ%%DQ9eaR^ zE0nO>q;jIm2y9^;2q`{;lwL3JNbfrA_Sgi-KvfQxLKvq0hg$`AD;8!opmzY4XjeS0 zV$l0ng^6f+KBc~-^^+!fj3=5ErlFQ*oom!BT)d{dkzhieJVp~_`TLMbnSF*Lg806l zT$EHy$T0?ZrPPW~t@-PLi9( z%u81Uq5FnT{=h4#>VZB>o8eCT)cIJ-P~|DyuMcid$Cb0Ry-}Sbv1+aSn;lCl>(up7 zlrB6l?g8@#!=9QlAL&o#{VGK3dumb?!+>td4^&{OzMSOsn%1puqroyynl>0^Z||Vo z^Yd|Wpl44dG}>VVj4Sq=n#LclV0NaIM$gtonR&&Zc)_`B*zskLMqq`62RyYv>(M{_ zW$W->+OX*iA7{@;Z5fpjasR~mUd7kSmW2Hw!*8TE^}w-*%FSRhAS)l&GyOd;w2OJC z;OgsOcH;Fev%9B>-TbOEy)y1nZ^Wg!lbpDC#6`yQb&+KU5G=6+ekfEe*`+CAdC_0j z2)qz8Jv6q;?XuU`<>w=dEDOn8lM32qLvqtFo{m#-+o=P1PEfdxsW@D7$vG>Jn~xFNeUsM}zCPgDUcD7#XpwC& zP&q7-1v0_t=?%15)X~cyldB`GE5=yoZ?m26c>Hl_Bi3)X z)V)Qe?gmz^Bd?}(l?KwcJoH9|Ma(hB6g4VBncX(%fRb-`xcXsifoE3uW3&=P6&ESG z?QT=qvJ72q4rq0pIez~zZ(YFBQJ9!BXXZF+?#u=84cfA?7<SbkQ%KUPo zp+s$eNe$4fOoP`M%a>QzVwJM&poR_AOgW`tD&KSA;fw=v&CIf&y4N3_6^;-!upJEV zwMw9@Zb<6nr!|UKXWPB~F#Ju(u;ZCftSRMX)Vy9r=;;Q%wIr{B7hUg$tfUSbj_1(h zyI}i&`0D5$(yqWe>h;(q!f$?$!N_^3JvIv8Y|m(BES zOO7E6AJ1^bL-L{|`P=m9#j^AYI=w&Eqelh( z5+lby(saEmPj(k=+%DrSOIW?b_QVYD6eRc!Bg8sB!eMDnEtW$u@!i<9p=q z;iWJ5)|LM9g+5k07MV7>CaezGxkKNxwMH$fIu`o!BZpXRqL(q^;%$n5gT|a{OsX6+ zh81vyyNbOiIh2Nn=z>?1Yr7K~bXSM46>$blNl&pc(G#^`BU^09Q%u)$O$LzCYf$4% z&=058g=3_9o`;mbfpK+8!Dg7Xiw>foMEM@3=yBgz6E^)hJjx-dYUJ{yxY*gG!JC z9TifaBZm_C-PaL5$RTsxPQjsL!d0}lZxVTANaF8l0VX5O-nMI#FqgwZ2Zc`5!3ZZ> zHmE6*2E!_pd<7+qSLLk0nQGCZM zD=yiWIp@BD+Nw)VHM?pu%=ingzz5)3E5}pb4<^#}W^Pjy%?=uh)0tPMO`u1>l$1H1 z_jW^}#U+5xqtSBZlnYhjABHpusJe*J`%fgs$c0!Y@*q-oLq4K-C zbY4qfMJ|7@+v&PJj~yxK0s=ocXCVXS2hzLD-eH}=4(3qN`CW}}1e0ILA|T3g8|`iW z=08%pCm{t9AT*ZtmRw*~rgHfwBE-mxNek95gcez|r1~Y@&hdWdF0=jpzwr6PdBl1r z_C&2OH{mhzZ~X9ltnq-#@aZ`Whua2Q$A?33vQKKkM8h@FgU?H`K9}rfyH*v8wt^~H#6gTPDfG-0kUC!%D*b|bkVsMSsF0sRdTG|{lSh#YbD+33q1%Qkg&n8giUpS?%+?i@ zSTq_tyh^=S(|N2qKwn@9Fs8#*jH3Q?+PU0hgwp@rVQo~OS9xTVE~i>4bS3qPlyk2t z%41&Xrtzt5KiO953?A1qnQZHmcIGD#rslEPO3z1^#?gm=|NhN*m-)4i_wy1pKDSOj z&dBGRsxwo#?dyj`Mekl$cRvYb?Csm*q3i&x6#0DegtDm}5?eN{8~nJ^sY7r7O(8AQ zc4l}YPh1rLXrtP(6Sz5XqCSCU0Gp_C=1;c~ zv=;L%&=P<;@I4b4Eqt-#ZY9m+z&Dm;)Y)v@#Vsvlt0||)5=`vk%yFWxwN*|z);(v) zCa_?YAYe%<^IWb zLd>ao*Kk%6{sy`5S*4zU(QTy~OKz5b-M>~3G>iWzbqaL~GLa&d_lEKg(Fx((DEr-( zrEeVH9cibxE za(?jf%d^Q@u;KSZv9|uw3fa77YttM^#ii_Kx&%OQW3`EM=$yKkS$MGNA)?r=%Xg4- zPCTMT#M=F+1j^Y#!7F}X0xWfWOov3@rpsq}$_TEe3_+Iakz@J?<(Dvh+>&-Y2{NhA z&w9;Iwt0*|*120+HMek|wGSK?v!&9>gMupgBFhND{6KMCd}xk6R5`Oop0M7Q>Zj#eOnbtW6%BhL#i~vxd_eCx$uK$nf@f)}T zU~3Tq1{DhI4GAC^+||{^Ghpg~W#ZuO?jH2t0~i#TtOKQn!RU#K}oXCI(1M48u!I%*?~dNfox9?Owpi z!^t&2xCnea?W>PY1TP?LUp=#&_On6UL+f3eS@ zTpS>>fc(*%wNm_r?6-Ca zh)SXRJAh#E)z)ym2hkkhj{w;(GWYyvM_{)vlFsIz6FVzA#Kt=IW~b(Q7O)I`bs!M9 zqo!9qZ3c#ch4tgs{QM^J^QHZ{jfJ7D#k1AD`ehi9BQbfvfpzG=Zu%j3zc@;Ei=4+kv?Iz9-Zc2Oylj+%DW9fti*@@Q!t_Z^%ro^{k9vhN0n! zIKi3K!Ch!7^8aM&DyZN1X*ei|dL}2QdWS~ffLEaWss^s1JD^HCxBk8qnZA)aHV@DB zz-yq=I#Zw?I+?&afqR0uu-U&r>jTi|Cl7m3|3vR)WPng%jT!r)EX)jH|Aqgk!m<9~ z_Py>645H`HymR}>0FCbD`RBRlQ%-}KSl_&keb-^I{HHLCS4}K@D?j#085$ zV*eeR9)&V6GC2Wr=;rtM`4eAQFe2djonDtxLk)GGeeK>`2l^Rr<)bbFet+P(vy|fRT3;z{|6hAp zkiJeJJ?mGHj3B&ye~zpi{C=Wu?Prcd5XOj~Xig0vI3<51+5o{%#6uv)@gG3|5X6T+ zG9^oZ;0K}+C}a7LU|m|4|GYJCjX&~Q)$BQ<*9!K(XpIcL#Ey}^jGMOC7c<6h^~Wz( zY?TkVoKK$G7yHzKe zN4J3MV?<;=g>J5fy>72T9&|3)%G?j-m+VWyR~Ol=ht_?UQ21^VBAwmin7N-${dyB-{HrSz3&(-&m6x9@}NnonUT=7Zipn5 zNCeUXDc3)2qY#QW@?@<0FCGjNW*Ws2;UXX5qc%4yNk)^-hvB72*3_YDA>tBYi~MyA zAe)^LP$Q93kM`k$g1uYI^X`#uwfu6hkZ9Tr9Q0pY)zbW5j&h>`V;0sNR4>(4m(|M& z@9`MG=xoTv1(6gQZa_GB;E}EJc#HeP`RV3KSl4KBm;k{!SY%0}l=O`Ugtg05=0GKU z`+LVBx#Sv&r2N$IHw0Jw<(Cz9qIYFd7KHX9fe5>8WaGEuMVvAdjrwMy;IEWchez*O z)D3B!*yAjf`I5nSYdqV8#g-APMy3j+UMaAru*s_C)LM#Q6VCJ|pyCw2@>_IDC(yPx z%Yu$hViu!9)oL6rRv>&2-AdQHy@~%!*TofDnQl{Ed|j+Syt8iYk9R4iPp^QX(fgtS zKn<7r@Yblw@kaBevw)Vz29)Nx(&et+@T=t)pPn0K7@la7f$tmvF=nvT9+tF1XA=ji zhom|nhAogPagM&P?|JBx8|*T`AkdxRA-Y?@#h*Jw26B98i>+Naox1l-G4Gb$m~a+X zB;Z&--1%reWqWEAh=yl`U3YD?@)XbY;*VKXyDdRq-igz2qt zNTV=D>~Ty52YNj|KJpq#tIuX8GC!+gB>N|HU2*Wg3D=zJC(F})(g+;l8%Z)^rbL%? z-uZtdbn(Am6)gQ8gB!nb|7+c)4hZOlKX~IerPVRLu0v10^OTO_p`4Zd!yu2SsHabA z=@K8Wlh~5Kw2F0A%IhW7?SeIA$8q}bEi!3&l_1kn35K1SF`Zg0B~x&G@SW2|QL#Sd zUb@X7axpE`SoEm!SFFUG+jcYiOiDA3Dp|pgRQbN$^EbH{rHC?TFF;|4PoMX}9;?;2 zmtUCPt&^BnJ7AxR|3%cjtR&p$j@!xLVL#1k9V^cdn&A!%QqS4M(r;FV3WfsDx9~sLT)PEJ1 z?vh^KHbpusjn;b7E+$D2cHvkNp|-X(AOoINmeH+eZQW;1Ji0ok05NouMlac>0?8DI z6#4|HtKB{;LMhdK%Ct9 zHLxe+KK2>*N-E`Om_2=-hWbaEXW*lAr!e%N8I^AE?ifR%cfV7$FOVsCd?k=Kmp}z7 zGe=t3w3_|=owwUZ|Lli1wD06+eHnwfR9`3YHx0lO3S|J>@CBN4hQnHKk@nw>j5>M0 zuLNDAXW)YD>Ml>iT96*x^R+=j)@JW|zvSP^kt?l$Irpk6<}S!MeFe;BU#$1rWESVI zH6YK2N$mz>6{W3UG~W&g;Ep6{E9%l1fog3T0*LDFKW*Bc2ae0axiDz`IlbO__%Ig= zl?C$`OQ0WtmIDhyBUe*)I}O~6fU5Be!C?{oa`NsCs*r&14+0(DA7PNKqKcJ9J^a-P z34W9QJxmqRSVYwY;1Cv_Os)552i}2H;6uP^W^ID?8YbH3*kfd)JW*oUU00iRBkR#e zQX`gbVH&$q18}I^qmOu+nvHc=$e;fK@Vna^qx&abwmlRoFvxad2r?v0=2#_^cobd zOQ!Xhfn&x#FWEFuZxZj)MzNzdyt~H+vF2(*j)cQ=YvMn257pTaJvhi)3a!F+JGqP8 zjXXZ=qL&g)6HKrSQIy#`wIgY$aRWUs!xP`=VYMI{tC3ny9BVac%?&i}78%wq)Ai{> z%UR&2ONCP=t*-W|qWvCYK31rRE0DpX*0FDV(T_WBFa!5NZj~dfmBsqc_#k#hcG00_ z48*zqhWwMdu~_P>hVcq#x2*)KYWReAsv;{JzKC-?p?P@MpV!?m3fd)gi#1BuS@c`#cuPJA=kTVFUkj96veJ^7=V*( zV9dw|ib*zipR$}CEa~_r(pbo#-$Dq-oS?9}C%d70v*rxFzrBB@({1%bPL6$9F>#k3 zlT?jTN!Vhw^S5>{i>@k8S?B3Wg60h z<4=5c>FQ@;nGZ*5q22=f$U$(5@R(6%0m&UFZHdK!APKF$;NprvIE#D>ZYod#*6nuJgs7&DjXiKm`KDz>CAx32Z^uq4J1vU=`YaCzTy zxFwd5K%=zFc>+xtLrj??;K~-s%SQPn8#^54+}qwIOl|72+-TW-ckr}9iZ8)SAJtn} zx@f-2r^Q|Tu1#0n*g0o92>IELIk#2>V5!nIw~g((xiN39*M(NCGu7*mR- z$;u^(aS}hU_=>>UZ_fx-^=t|um`0l=E(+-KGveyw-oWI3w>c9$ObDv;RFGFoCZU6- zP>l(22Mq!p+93_KKu=YB)IQ|*jb)S>fOTwFeE9GEqd&>KOIs*Z)(slYt5MW%@}XC` z=kwLvo7zp`Ni{GW41}AeP*pZ0YGCRwup#`nes>?s>`TE2($b}HAx)X+D`Ax}mywN6 z1Uxm|@WKHLI&w%}ht0@N`t6^YAFIXEx#1=}Gq|{BG`+=Bb~Q)bC%&+85hBQq_Ceom zfUNUCHhF@8=`LfpWrBj1>MI|#6GM5Me+V;}w8m8kKGyNw4IKOI)+J3BJE z(T6yKYbvp%4M9z{&sVscuIJ!j3pyz^`bwDMDYK?*LUZ68tI%NMvN&%oTg@~>46>CB@SdDzze(Omd4D3~t znB!WtVR;hE?OvTPffvg2&7SIR(=sss-^z1goaBAnd0LKtj(<&6a~78Cl|HbAn=0(_xn0w;KEM0AZTP7` z1tDf1aBUGN2(Q87D9o!WS!B;dD0YXI(`MVO{_1am&*^Cl9D~cmK%JlzC^4K*+8+6c z3kM31bnC^fJXHa*lqD)#^fJFsN5lO!3(saLFfPK6A{q2~%Jt)>yFgE`Vjh%2xUD6omD zWB(VtINa6!K~C>{6N{z%FLn##PDus4Tx-?bu{hJJyR-eXJ^@%C(f1=evYK1eZ~qk~ z)R9rhY#{uaah5vb@uV{T<=m^)02sJxll(w8?RE5a`jq&km3^L$ z-M`HR>apWwez};(I^hbT-o`=1iRm?LB*M!7#L)+3d_u?J!zEB}Xdf2r1X95~82O%1 zuZ|&CopPf|LZHmD+&9jp@jAL(!XG@yGOL2PufVFia4%z+7TWTN(O~TvA_MC`q#<1lO3w-5 z+Tn&A#kvP1p{L~45aDVy@v#X|uo#}{Mdszhbmy)yZXwmqa>J&njOyLaT9Kt4Da>^iNVxHG5XreE2|=0G-{1z=3GZtFaG zYim`sHGdR?y`4UdqE4RV%oNuQJF5}aAZ1o{y-TJ?-orqngkfEeT=9V_AO4Fy+Kwsx zBK9$7s5?|jB*F;qmhut8Sq-fe_s@;s^6+)ER8oIw)(DUE_9n8%g&m~&zg!_8JYUbN z0A^J0@QSzH^>euE9~^FDZqp%^&tmdQaEpW@N>}2JMoG_~0&2|EFPIwgn)5P1q&=x7r=^}UmI?^ zK)HSICo#qV63w|04!2^%dhir`QNq_Lf{$Egr7gbX!vwY@38d&YPZ$4p`r*h0_y*5apW@)#wdIz-GbAe0`IESo7pb zV~7}%rEi%-e+8b8T~2`LKnPgGB@UScW1B5F5LBRR$sr~A#ZS^WXlYSxNX)N6nHk}X zchV`gb@Rb$+A?uqQ`;9x#x(rOo&H6{c3lBlbduYS9ls{yVY+2VU#PyOreiX82?+uG zM)~nqRQ=Q&T^I&0{fW#{nXIL(diZKk0IhYfQGSj-B`>bGEllEsc?WxgN z42{qppr`Z;-F~%i2osy$F;TuP4!+=!n5o zndo^-5zF`LNLlubh77(C&E~wRrXZS>KH*98Db!AQP;me(`{C#}baeiCu*It30LCfg z(oMCIm%8;Dq6Z<#L5)rojO%YI?Z{>gp9{cuhr&VOMu-Vv8n9%OvPf)$9I|#vPsv>R zgz%$<VA1z#l66V^Q?>$D$C@ymS zI~TqzU34is$OZv%CvLT@~2QGRwjEtn2Mypr|PhOhEK#;DUMgkZv-XRT|vMdUI} zvKUYDvm@A>4z^60m2znbUYlb;T<3T_#|?#R=S9`*Q~R0Nb7D1r!^CHuw}EaTOc#pT z#t9w-2I7AkA=D-=IDB9&uHP9+!Qj%@v_Q2;8OssH=p*^+QXrJftRY@;-NwlJ%!=o9 zU0jqttJFejh>eU=yzYv6{T|BO!OW zNAsX(#KOfx^WF+k-dmyHm}M-@wBXV$pB7UK&)Be7f3)7%!Rzvl z&o2-(>)oH&J%Vta#!!=*_qoKLLXNA}g}vk7w+<{R#d=ddp*nkhg^nbb&Cw&gY?Zq_ zBJDIZeK2lv;?t_y=lM-oC#o z-kPcx&|ny9XJ@TA@)rzwFmH&UJWDS?b=q1b!oVD|)><#87P!ia3JdH=KCf|+wmqq1 zwCh)dC%SjVW?-TQi{&UKv42^>teWyQ8&bCu(-I627q97nIAq~659pIkthhV(1E~96 zJvJ>b@Qbt*PHpGy7(VRlum=Wd3)A}KlhPy9o2seJQ&|rZVq<_%KQVwx-Uph>ooR^X zWLN;qvc#7*uW|yb-VlUGJB_H|D_VlL-ZdybmFF7dnog8!LsD`##mwfRW0j>)C z&2X|_$yWf;V28E>4Xm3ybRw6y`stl>J~Go@fOPvWA!?n_sxXJ7Ya=W}MS%`p+$#b?-8;+vp!Lk=71mFqC2 z0mUWfL7Hh}zR>wqXlIjK6KyNo(EO^|?H}6Jf~Z1vi3jG|s{QDo{%?pbDme*`|eMCUhVX7rdN18DG4+9vYCeQLxN<-4)z^-eep}dt&UwkTdZPKhV6HRNXP4RjOFY`4}&>n(KhD7_fLe;Y#Fa!xlymtsM0fT5WJ{Kc5*B;y1!`{DWI2X zX+bfEcr04`GD>}1%cwS>dJ4HL6J`=psrtY?cPd*}AvAI57=YUPAA5cmyxYih1TU0L z!5-IhzUJ%VS@GX+@hxF^$hwOsG+bS`{RYU>hgKQPsB)N}KE3) zSIDEBCJgWI#?(mrkCfa=Aj&m_y&3UGVc385khx`QVv*?eyV>7*t`1pyJ!%>M)b=gk zKEN&5CXRmifMDTS2{SBpuJ8jME}@tasP400VYt4Rhc!sq1}txv#540bwrb$sI-wQf z5LSX7&KRHlo)N_&N7twj;`q6{kUBn{#9sQhu1mz;Kd9t@f0!HYeO{|WyUZHsZp3+< zrGWR{-a_BQI)*5wJQ7JT6`D@eaSmShcF|- z6Gxge#$*x^igpY`g)AzXIL>Hzm(^6Sd-doucQdG-nb2~n^U_M|9$F^Sm%u~Nb}4(v ziQv$<^#rEy%BAS9LZpvER_eLi`)!UnP3G2eF|c3!wc#7u0zB{z3adFY!#wPZV;5b( zl(DF05S-#{bed%qeJ)CfEx&rpZ9nZQ@Oxgf6E;7h1N6P0D-S5?*yFe6(Ic3QDd*w3 zodxG-``uVrM=W5vY}46t)`*?VZkBGss**~l=XtV3Z~}NoZ_C%jRj4a&=6;zhlkwi$@1$0K+Ex4wCPhGVN)j%Ugeh88^R{j$L_llg zG4#tPmHU4Ceex+ju@e+>yhNs<>hPySY3Yc5V)mNX@jeFv8f4-o`1h)5|MuS&8LNxJ zUv(RPqzBymjX;AZsU0!gyW6Ev~lr?=ly<$CiHOMjlQ zSyu#yKSINaElvvOpX?*MwjBk`=WmR0&&L<3S z0Vb7|CPhlTyWmQUxSBf0S9s3tx0>N0x1C1GuxQbdhN}i6=+1#i`kt;FF0&$^7py;C zZ0r|BE&+M0MIwMQi$r19MRlQ>gT?jY=#>41Hf&PN$Af!MW|iE5mC#JU8f5G>p0vu? z7%Y_o>nw=mTr^Egp&L=Q+`=5^8`aP&s`r zk!O5)#$U;^7)?g668+`pU~O9wG*6EnZ26gF-(iBDBeN+6yM5Z-R@&D-MO0^@1^t>s z+SLvCNkJ5CfgJHP4ywwXpsWwMgSl;Vyyo`zM)Q^amUDYxLRI5JfTpnYJ64a~0X$#A z{OtDEy);N}2XZGCulz^&_+c(K06B&D0_@4u%g(7v*Sv}#zDQ?K8UKqhmi65u{r5p_ z3VrImg`mHWKD{$(|AFf$L`A=E2^o-m{BK?&W~WtJPBri+1P(9r+#D8`T?bkz;v>^q zwd`kny^)_?4e6T{26$Fd#p&;yGNe2NUUkOav)|KW0ln8!{$^^rTy|*`Odhx&{rVa8 zg81C4vKumb)p z$DpoaTA|TPj6%$_G)Ci#C3tVQ-hy1Ip_Nzuny4bFu7vn0bn$K+(*&v~MFBm2f_DFa z4D|4@?{nla5U0Y_yn^hP_IFMII0Dgx(+-*}t#=SCO4E0xJJ#@s-J*Io+#gMR3GRH= zjvnEpcCsH71s}sQ2^7uBkQO-=58PB;PU?*MozyVhwfB+5?_NCbyNcELbLogrDJRGQ zWcSXNou*EWW=Y|^4?&nO4XJ+FlL;;Y{Ra1=L^`%MaEP>Du#E)t^ z$O*Jw?hqIWh43GTBF(fU<%Jx{(5j%7oL#9A!KlavosB-dOuf!6>`LJ_1OCCdjyzw0}xS@@L_8F4Sir{#yj;~ z-?fAyb()L^^k9k%x*-$Y+CuqwmE;pi#xZ0>uNm8Q|9B{m=5LE4=oC_Q=P1tfY=;c7>ClbE@HV_vQY z?Bx@G41~7qjpmNqy^^lugSqOG-OPZzE?O~!|87ld^R1q#GUyJ-5F&pJh|bu$3fTNV zu=D(Nks2Cqycp@wub7!G?&T&5z)xkD3d^sBjf4Vu;z_1Ly2+eV<0tF@;j|WveH5nK0gU6 zta70&ka#&nS;!sF-C;kT69n<3oHJ+NlFyuWifYQ5&v0#!pLfyhBB9l@5r?EFKye-U zHBKD-i=J5zR;evR6p>Lp^8676KLvHIJ`^~K2<50<<&f{6^8frqcfpbcw@a@jZ9?LY zbEvC+T|Jxc%MBd%w7qx5$9yW-GohC63azavHkJU{kY%&0U9z}&R3Dd%uX3mJ{zq)hXUYTWAcdN zT^o*2Zp=-_j2HcvXNNmzq(%2IOY5(E8m~ysQiD&5GxgVP=i!t7P?K_FjZR|fLHB@a zqm9=uA3FSmep9RzNE_uhMLcH4mf|x&GYza+&H>f0H`Tj*WqhiLA(`lC&VQ$0LJth7rpiCZQO_{D`VPC@TG zotEF?BFr%fDqzx-?pbf6DFhX^*A!_)b5tpk?afDuP^pA(oGpb-s1vc5b15mAR{hU; zmN_I!^@M*Y`t*mwGon@!zSu6=9N&7VE9Cwvq=5MRSO``@lnemg;fMs#ngfyYJMZ?hwNNy8Q-` z!@`I7exV3G)3+!54Xk`T31MLMIiF=+)uEIw`m>UgY&J2$GV*SF+>L!v_<|@T6CD2{ z%xIljP4GD|HH!?+&AnkrDzbyn0nz@{ph|XCqR%r9_YhwD(sRDe6AlP&#(MN1foYJi zXM&U3Sjb~_+Mdm6=LRVd0x=!M9}}>x8B1Af@ttDrS{Sq=)=&P6C&3ukoU>=GAg-Gj zRYcesDZ7+ry|fpGN?ajtd4=l6E{`Q>sMkEupXkSOKv%<4|9W$;JmoFN1)3!~Y{aX9Lg!D;s{jK=!2|AbL(%J`ZRLlj&aqe+?CFCX$gVvG*jlL``K zIplY^nYIcByq~mX!2N-Rr>7rrP5{g$KiGOhya^TLWEg zMUIQt%4|r<@afeQB@05eDj(<$CC4a!4%2bBIZ1f2_V$r#$ zPk-Tk(-9uTid^P_o(?7QM~@ESFsNUbdNYCi-!|_^S6B9qYZx>JyWX0~x_=zKjrz9}EGMdJ*N?gVBUPRCo)Z__RO})wdtnzqyL^@aEj_R@y%S(}U<@VN zF}`tLTXRaceH8Smnd^RfRs!2Ka=QI>%OL|#*P^Ix`XnyBuvafSvW{}P>jJx3$*`uK zK&2gu^Jy*TeP|WIz=XHKxkspaYMpoBXUQK{KRY)Dt0;I(u+Bh~63TbILdmtk`#Qz^ z%=?=U|Dt+jdpGk2!8}$iVPriD`IBUeDLc_tFmaaKVqM~pHbO+wt$o}YGtp3TJen&r zYuJe!94fl{kv4SAMlx8*U@_3lTeXyt14(MBFb?Gc6mD0b7jbTR;fN&JYbL~GY|0*q z(vk2S&Rfen_sCz0O&&*g*J**Z)czSM;|KDom*DL?d%_WQxqQztodVOY-=*9lqw$6q zc~a0BC(8I^I{E{@#d{|iaV;t zpe|UwXEtJq7%32KH)21rzvWN49RBn;E6_eOL$M5Sj@;dnMWYG-jA8y3SjFD0}+8%E6j%rEi(jHMT5O~}dIUxi0 z)zN2>kEA_>I_fDe$1#$I%?&el znl~ixdQ(ltAKOWkiBGTC&L(Ggcm^hwr} zAb7b^szq%PYB&36zbZN^I+=_90mCxapMAUOUA-OR|2#$YgP2K#lY3#A5I+4X1x$u|gBGKYQx=v3;dj z6(n%7#PE$U%R`(j3T!CI{=QV#FCsF3R_bG@>Z)F-$Z+^@9+qIl>Bm}?c zVQQOI?Z&<1fUdsP;zo#!D<%L0;7>|f*cT=rOMhWZkursPLHCS=Rju5>AGiGs0s(!L zf-Wgo$6|#P62OMP_&To@zpz8yIJx$XP0Uoe=ZA?>llni5ol|sXVYg;u+qRvG@x``n z+qO}$ZCe%Fs@S$|Ctck=y2m+V{1@kPzqk8pt@S)}ZutZXJ=jokaQgDE`fApO>(4R6 zP_40~|@U&&lf#ScI)q0CoM;ZqeRiDG+X)8C&9Jivn$# zbhV)o-*mJt8r9M=WJF!YsZ-JE6fiiQ4F^?(=JnPOXH6_U%2vyz0YA&|zs@AA;=`k; z(zG`Ehrd_jZ>bOo5a|`QCl)EcB4-iWtv3)!(A=_7^dn&HFcRn@v=uGHDgA1P4YIUr ztj@QJ)x|_QgBA{!`!Gq}5)E=$D+o)?G(Qj9t&a7)-NWK@QTZJM5V!SXuIEIHu*`=i z;`koCi=r5g?c6N&gP@E;|7@FR;>uvI^cdmskSm>3qkP{9pTHN)vpIj_hUmBxcZBpG zSIB{7tWpT2gMq`|@~jXmexH8Z&&Q6sxNNqqV*+pECp4BAQjO*%iW@HGLu3{Kd_Q6w z!FtuF6mScx^N{@l)7oyjFo%w!4#{5~z&5R(RN!f&dbIS!0m%%P$F2s|UFjj)lDm#o ztHo6)oMM5zY;nk5Sfo}_O5A#XkpV+KNiBQi+V|hanRg#5?lX0!{ix$Ru3(eJTdC-9 zi7J0kcH7S0+^w(7J^9{1i#^<5-<9WY(2=68FzaM0Hcxs!ioDO>Sgc}ez3RZ0A;y}b zdlhCPp7Aq0PxXfXbaHw6t2%$zU;FJ?)C5(4c4H4QeIkSFwk&v1UQF8Vs0w**9LyxH z(eqQHPPpP1dD*2?tzuddzc0IDl@DWOi&J7J`^aE%)n_16>hT9KmLl0cZN95_C3Z@G zPLb_vgt{f)HP0RlFcxN)q#DQ*J-0C273;*@hj#4&&F{z3?1o^R_`sPqeIAnRvyNGWeBD>K#uvIzI3#T&q3oq*vgtIz`geDWC5y_IO{p zYCQ6QwzmXL%W*R7mvpJqQU4Bh_UWD1uoB1h zeKkUH!=(RDR zYrYas|M8d?4?9Kt(_^bRuJQ9B{)3CjSBfK@T;nLzUd6F*(ZO8xefa%j5v=CVLwX$r zua6qvDEBA1ET#mVkGO(v(j`AQG4jJ7NJuD|r~lAPR@wqA(-2ep^~<1Tt;rzS5!0T}=$BM-a2wu?^&hQJEMHnKn}?!-m5L_#YTR>6@x zi@#<7hY);?bG-Tbxqhj6^0i*(c7EQT*}mDn@yi_)sjC^KHU@1Cq8c!Sk|SV9(p$h52%bRz9U-`Fk7c|+r(3tc?HOv3`JcH+qh<|= z02!G$cIPZ08g&TW3O)=N#~=hS1npYLwu(F(tSw9ob>p9GfZi%jlr7rc4gdh!`{e9& z9MpLv*%A6sf7e605ZfWCBSygAS{n$UUV^=`U}N&3=G!B>ejKa>Z;BYE2`p64t*H0zuxs*Z~nRj=vRC*KxA4(wh0CK-()wciBlkh#Q^_N=O(vM zZqm)R&HUJ2vBPgw2-is%CS0zzBvi04hryqvJl;igqnHji`)mFz*MNS2VUIt&Hr3ye z=M^OO>*-Ahrt&Br5z%i(u%m&WxEX{XATWUeA)f&vpnVX5uIj6H|CE&%x3Euy`%kAL zihpRgFdopBa$=%y1#PHv#GMuROJHE6+G`~Loge(yve219&{csN!V8UcVnd7V)`B2n6THZ^X|RzxJbM6%)cL-glO}UgO3_2gbfM zd8pk(bfALM2}Tg80=>^4O;KF9uMO~1{t6l_XYa%%9W(qTkoCvAu)Uy$3(ySeIa~kKeEY z3Cs9_C;o2 z-)rF@e{t*{q}{tff`C?+&@W@+v;Y$*Kt7%dAkBduUuNumQ{cg*3e-SWX8wH`*S~+P zr+9fkfm$yZ3BUQzwK_XH3K70#Ar}jN8vUbiLGFSy4rXKqYKDb!)xx{P)y5UPooW#y zjS0<&2p^mf(6x3+I?%-O=qS&Qy3$p>Yd9Cii!AOQi%P3u?~eu+Id+(8f z>3O)TLdLUL9`8(coN>Y=_r?D37O`q-&7rI?uwFsVk>%YM+gx@$rbm2fRPvN20Wxk< zXkaSBdR9JfD=HsDxw&E@_O^dB6pmM_`|IxVkV{|xR`$8IiqFB%6^+ zEXnQJ=9-^|w4Iw#1q3a}5rh#-pbvRj9=*p6KUn8cFb49A=`-Pm9oOfTH|N z9uxJWU4%goGGaLdH&*7-UB3q(S{z@xn(ix-K<8G%9u8nzNrZ*=af1FN*J|dxOCC7> zvX**-p@o&pOAssR3^5ds2^D^B;n>;jm`;tW<0inCti}OcB}&lj@`JGCZLLK%!|c*a zQlE?YMbg}ymM2NNmY98Xk-2!Dah%(jkx`tKH9tZeKES6xR4?~ejAZ34${ND6bJHa6 z=TvFM#6|@4EFJPtL^^R_Md6Td&R$P4r+U&C8o32v$EQBB1l~ilQyi=*EHp`X1tn=P zm<8R((u@(9ilsS>c7Je!?_}}*?xW#uE)>3|7zR(JW`Q2*kB4QkP=8Ola}O<`A&*WXD6yy+KN#xx zwzBM*RUIXc{6s>98J3yI$v)u{7HnYCoOvfp4-Uif)L2tGy@3aiCBYaK?zEcIITN@K+W zwY7-2V#-$Vy(c9UaYX)^kDMY2XS*M4X&rcVdCrQ{)#vqZ3 zB*N5$NIQL#Q$<=(;2O=vDq7|{v#Yn_F)Y*}jy0Ea?CmJELpD>D1$)VKGHeO)o_C7DV7p2O z_jh^iG*16*N+iGPsRZp>st&|I1pEJVCbYw*SrK*UGA9+B{lWqGf_dHWl;S!0I&b)~ zGVy6kB8{KB&QSp)!nGcLCGT_8cbTSeYL0cwZ!Th0cZ;L5{Fbm{L(Ep`LFNjoKijpw zD4&J6Py4p_zl?Iq-{|>Joc>{<%G%S@sJOkFu#|!QwE_6Uo_*FFq($1gm^Ra#2=U^g z=Z3Lz?GiXEhbz;WaVRrH66f|i4tEd$Y9H#Q!Au3WYMQ5*}EW@<;W;M9xetU}~`+&D0V35$4yAwx`0i)tJWKG9>f?FWs25Xf12 zW(+V#klin=Ey2v)7WXqfAt96Jbh;e;q`b$P(PMeWxq>C0spYWZjjapQNXY0NdU@~dUN5ql5@XYwrUeq<{OTh-p#!(ArQ3EQM2?zM*$V- z0dv!VZ!r8fN_P_n>v6w27gs20pwu$2pV3GJ0_XjUre*qL%mVEZdk5g9HCU0K>vOAH z_>eAQN1w=eM=P2!z3|SS>YzqVg`dw&uYoxqZ#_ngs)=M?O(oc3j5WRlGJ+f=S!r3( zyi??yoNd%#wey|#!d?NoYqF=f11UIsxH*GH;RlD;>Z|?jzIsGFtSNdv1SUd9&5#r* zsg^qC_CKyS1PgSlY^e7h*sQZUqpey^;~Zw$gQ2XLR3`t#30u88#AwuU^H74RyOr@Y zJhLKOc8(bt1ee2?1YS&aR+>;Hm?XXIMuwnq(0o`!^UPd$(85vJP_;ITtOc)>)G?IG zuq^($JBQ%4^EYr#wN1-yO(bq6bvTX+u-8Erbz6BJxuEltPHx+Bt2o@;=w+$Hpdg9( zs_0qZYnve&*3JF%{X6b?aopZXb{?CntJwj<`cX`+&G3=Ku+%D!^~w&p9AS-UU6}l$W-|+V{$ZVaq}y)((+W@ z&tXN)PVbKc%uWLy-Xvk)cR6Wht0-$m*3CwSqQw(lRSaX5hgKjCB&Jks3W&SS;}g{_=V(Qz=b2%{a>--LYgPi)E*WaV!u9iE@L zwoE~`RHa0>+Gk6iobA8E&k0Xih{i`5vODQld8CHhq$R?H}KOv?$7WX})p$SIyC` zBUwLxEi;LucO1wt;cRcyEKN>mFBPVHrQkVud0ben`;S?&w0~^@kB5Pj+GSC)tf4{( zfr7vsm?oXKME>F2(%al93f$n@2Nemt3ZEl1r<;4osC(IxK(xL9HCcl58QAK2kokD* zj&%%!0|XB#7oSx?gnnbjQ~SdW;jmHHHw-?+P{(&4{*Zn;}E=`0pz+* zlL>DUi*UYlX~=D#3k#?GKsK8>413(!26xEUt!QF|5bC@*a;Z!Y-y5u7E;*^>^3$O9 z9!D(0=%lCmmnD$0;oTYgIei8Fev*LE%;Jxlw;e=6mP(OshznPjLn)7}wCm;- z0Z2F96>BF;dlcAmK7j+59CDKqEu=@Ti2tCUziqXK<4I6P&=k?LoP>)cQ51bI2k-V0 zw)W%06HPq!E#0&FNK{o@&fSq4mDu6tP) zhpb9Rr57fKsSIMN^%n>l=o|Pz8eRH)DRsP^DIA=Qjf%3#-F4m#|@thaG6kL$~fiYqIL4=nT;A# zY=Hs)qV;~d>_cAiyaP4#xBgpVlzjherFPIm8L+^@*N_OrBj51F`GbaQmZq`RtC(qfrE-IeVV zzi1g`84BY7&kL&s=uy=RqE}Cln^|=;ZH%aL1rnV<;`|K^bU8*4uKCCZ_DdO9} z&DD!I#|w4YP2#wub<(4!g|jj;=0i@ZVJBn|VFYV?hMKu|jk9f7%`Jo(Eu>DA)wLQ| zYyI-B;^%-z%x)YZ5&ahaC;c_@I7Ib+D|uGg73G7)G0|k~NH4zKnWrnZRc`r)LO$;z z5kTKh^ur?@r|qaVy6TUFwpAl4L!Qb$1<#B-l;6Fqmc@MI-nF?7V;LBP%{h^-+1Dr? z_$8_8F;dKXjH1Jp8acrZF8BT(K|tz6oEF8yY9s02;2vK8Z;$fre6zST&og{sZW~IL zZE^MEF)LkH6Gx{!%`@lJP3cct-(Qy^H%z^r)cejk_Al4_zLY|=*OrKT+C0jh{LI>P z2XE<6oh(m%t^T{?;wUjv{To*d?t?_7e=&_|7WN?7E@4MHeuWL8N>-x5yy?i#_4XJv zbE-*fbQ6z!LR9I|oIx#kecyM{sD$UnD2ry`UR3nwS52}VBdaThbWi<#BoKClBfXw% z^*P4G>W1dBs+An@Xx=T0fRL3#-QvGUW&e-l)nfv2x<(Czso7@@G{wd^gHbOTsI6>7wP-?Lmt)q@CVI z0J@ABf;Mg5;6+2RmEr9>gR#riH`4Z{Q>&$^_Q}nFxdKyh@ZVBK^ zQMWb=jgW^r9y>^QWly=<8@u{<>vksHyD_#;9MoKmI4vpmjuZKZW7TYF;PaM?eg@Xg z;zuk^Np5ge!&MdPYv^Zi#&V3t3`Z?@9-da?DRYCKSp6e@4kzAy4mJiQQzoGc3&N?% z7nGKPei+A*7qYx;6EX&hiFPFc%yPq5aWeW^b{|BqP<`yk*&;R-&Vlk(G)Hz9Z5*?# zfyGB)I}JKx&KFZc<=p|(rS};Qc2k?W-66eXntWu)Rl3yg@j!U>Kb?CA!pb|aeHU}P zGb-vw;AZKVda`L9V)%z*kQ3|YAZFU*EBg>#5q24MITl*SrF)DW&!cju10dP4k2jnf z^dXAJC|D5hkudG36SI{t)L1Sl~-(+NGb#H^b@LQ zQX`d_2EoS)d@mf<-mxejkMRGtLf|Y56D(Npn}?M-gFcwLACQuuN_9GYeqizFu@lR!u zLxwqN*II6If=_oto?3iz8Mc92RkF&udH&tI=@v~Nj71nOSVEIs{y_s_L9kCfdJfHk zVi^vMUWIL@*03*??I&o1>}pu?*_t2PFB8)U_TlmXjQziFpfc(nGNm)+ueZ74$jxaY zy~iSV-QV8R^|&jEZE8#?#SK!ZROIn4kv$C`UlRxALngn#wWs?kZHv1XlukBjntuPz zcYE+vrQNK}@j7vzR>GSmjEq&|cTi6u19Z*d;kc9|$2xYP9}Alh&ymSZ)s#=SmG%#I za>c@;viNb3lr&ZycGP2Wl$nl8_fsw17RY8VQ7}}U25vL!8f!V&y>GlheZPqAt755a zxGZd7=!~gTdlZ(1$u76AE6$rVsy;t*a7~iKtZ3@`24gsqc}2dM)Q!DAzHV0V)w(E0 z51&lk0Xn{GI}mc3N+q`!@=PdT8RP);5-<Zge7kE7Pi5$Gg#63eU^_%xp`RS!4QrQq*@**#lT)54!c405VG# zqu^93RNBFs_=!14z&W1EsF7@3M^_7kAmQ(w(Zx~OK)I!txhuN7WZoRB)!%n(f8tnT zWmYJX9s0n;s?XVcu7 zVb>5t=;PFBbisI=XId_(%o^Z-$_f?PmVm?wrwkj=FB*UGA>?Kk`OxlsO>c}vwEmVn zrgx1S3lnwSuK~F{1;1zen^ozK*x*IKgTON1k{*%64KHKkRJSzKWLqLgeI<=y62Q?) z6I~4Fh6!%@RBl|E^&hvs1YV>pz=U;aItum7mD(}C4ZIMB}9kL=Jg(R5VC);2LTnv zH^1;^MzF=@uWI0SZ)D^e$OpM+7wnc$tmhb8>zmccorzT1l?7yLKQYBMv+YWR`Cu(x!qM%Wt(QBjZu=@7lZG{CJ zLmeXEI7NTG(Rj~u)135*VrL2HyN#?p)leV`#;z=NPzon>Pvu0iS}p2*IzH7Fo#dNq zsw?p0E&#Jf@08@=Q%UCCiYB#uwFoww_ztAnx1-^+(=)K}(8R;}O7nEDgl?oy^`OB! zpnss!c?(IUAu~X|*HYljJgkiYlMe$TkPA_|(B72wm=l*&Y(*F$=8X*WcHGChg8lP1 zk4>idCCKrmvTf$1;aQ^oL4S&PWMwe!j=Z!UPR)b?342n-=l(7?XfI%sd;h#ZW~F*aJ!37tt;I@PRI& zeVk)T)SH<6BQ=>mi|*neHvxrsRE*OKaf8e_CGUk!Y-(%Emo2B(A$=1l%oQ4|uo;Q3 zafFc(%S^fYQ}T99_2HC^^KD~5{-A`i|3gh@6dFMVG3r<6z8>qf%?Tt6`jqyZA9`|k zhpV!*AGDD-OBWy8MABl7FB@CX=F8d*aX9l%Sx>M|_zub85PsPbYL7N|g(Xg(tk_0p z`v4_3)JrARFbSX3y zP3Q0#Q5oI4Z+u4dizV`?WEU2cq!43ec?iRSCn?l+5pV_ThU%$!w5p$jM7YV8=i2M@ zCfs43y-+Dw7oXrTeHGBF4@Su~Dh|k6=>8|cvKsCtA?I_C@S$S{af-fsUeI3HRC+P&E7s0Qq@I>&<-~nkYzclPC;x3oYc;u8*J>hf zs0L$&SM-j+TvEBVp!Ca7#EYw1uCAlpr}V_;zfr7R-%pQ)mZ_sM3VQb)M=#iME>^N)n4kDW}-;3{bA zIP5ai^imwc!7gPI?yZkZa7;sRaKf-slJ3EO79}J}$zxcdprBBs(&nMYIL_N&vYmhY zYi_igmjC)~uirGiJX{-^F0$<=GzG5(r5GxJ#Q`z)k_iY(OUt75%`gs4&M-!dPFO(+ zwgvqBI%vQN-XlQ5Qn@DthH+p*3T&hXK`!T{$3n}$J_A8Q0)dKD%<#LxL0sv&#CR1I8ng3kV1a!FsuI3CO0!LI4IX z0HP-vK)(FFjtu4kjMXQA#5C}tPtIA4j|{~j$;W4JZ?BhM1<43^O*A+Te;Y=G2mJo; zg0=~31Nkb7l@IR%{$n^2H44Mz65{dMfZKP8ye+_q74WM~K)|3Jl4cOq3Nj2-Aqy04 zkrkNR&fql9V2U4jGoW`Gf~b%7cE`!z^oIs4@LLWdNPtP5gJ=;G#1&{&Sf>vN-&9sF z1ThE~C}jN$2CT!QPvK2~k!T3qA`0epiwh~At_%{W5b9fW1{5s3jhNR1K*Z2Xb^k>Z z%xy|uo&)lC2^~(<}i z8tB#E_q(%EWPB02dYQvlFUo}J?8V_t0cHww_G{$M}!t2?tTmQ=F=(C7|H>n`RV zWI+$ucV5Xi&(V+kUT@{+j>vZ}JhgX6+ozlJ=kt&Mrhs}x)Qvtc)tncJ0%$(Ca18LH zzp!kdf0)|8|9a>0rC)~w5`hE8RSqikmltH9>vO>W5(&{X0&!IiGYE+5JK-;3=Uknl zbD%(f2NU90T`PFX@XQZC-=a@ow&G1Vq*R)}jsW6fJ+Ytu0VAAP%tG&nLQs%_Tko-) zf(RN=$Y5ZPM|qVvF>*4B0;m<_^IMG#5FsO4m_P}TLN@3>r4{FPopmY_=q<2+#y628 zP~O#!1V|s`JLCHjecl#-K2QMSCn6QpZqpAW8u%^O7d&_fu+Oc(z+!D~?_Td%0Pmgy z+Qtr!2=f=>_g7&+Kc4~8_9q=28Tz>j?z)>IsrbQE6CZ`|3Dd!VO1$}H3OYieyyb)! z+c?q5Q4oZZXOFtT+C+u2_VyRa%fqPgPn|2=Q_p}oFWiJS0$dApQ>*#u!ua>eADJeR zDGP84%lpT~l3PAj-Hy|b8wbJ-u1D;86o6^nRfhDl87aLohBBh{!nKFG^0QJ>w%UM) zy)5CJ5syV1gOkvBZtF1);XU~X$uC`=C`sXt0~E&b&iC($zS-UVV7-poQzF;8-6wlG zMkK`KVhBt0(1xlQOxPRUlN7HjGvtqr%6O`HTnlujbLD+_8nn_scuHD2EXG;f-O(;G zBO4`TR*Zkw>D)p9^1Wy%X9&phGg)RZ?h*H`NqS1l{@Zi+%sv*s_kF&nCuY?#KiyGl z@E9}lxYd&J0kC+fED>%K6g*|2DM}byWD@?_^+AN}x5r>FX9RKxh)&!p7f$>2gFv!e5vQX|2`f znezF)gd~uWi$a9}vOOg4YZ-;t0c-E$qTIA>lwiTAKA@%SAb#!j`_|u~d;JPgp%(0X zyj)8!DfiEusoWrAPMQaY0|jqv=|DnG$sLtjVhzvt)|bSzimTjOP!_kV^Mw(6bhG`A zt(kuj;vSSvP+uYxh->t$-kwu_37T{@yO`c>l#m2T`3Qt5t=I4>aNA}y-UStrJCThH zHjd_D6pXinc|7@k9mvivn$x@SWDa+WizYU7ZNJhPs%77BM$CVaaE`Zaml}*5l*cTg zGMR5N&n2PzK%o*f9BJ(w=7WeUtOtU z$tPl(+rR+1R<3pCtV;x5%2N-0eS@CF2&v3IaWr*lIPHNtYIpnE7v$W)y~4hvq2$GK=yQ$8>RgpOZ`9 zIY1%0HWNhH5%({i#lhONl&&H!ft6!~A!-bQtnfQ7ljsI zuFRRQCocF61wo%&n3QO$BRzBt^)A(kxKbAmsN@gU%CUSIf_SQ2K(7!r04Q=X*!Ozu-2|O z9N!FcoIzT#J?MnVTHDP@oCUy`=lHBc)ki?YYw~kYzQHX zk`BBnuCA1P4YSCt?;5KbcCDg9ggB>Re8s&^zoJK(w4@oLsxNvhv88gX{Zr~$*@-79 z&L5L_=(hC5-6RjTy9$J38U4~A`|y<%*f7C0It(wIG9p|&Zbv+^`9}+<`d}4{6lU8r zBeq2&H~EAuf(H!WKirPg=65EjY9#^iUMSD0&g)ziOKV%ltLIh!Z8FKs?vxXkt zwK9g>DOOMCVpEJmk72DU67BRt?6ESE*Y6{i&Q=7H_QkUGT!j^#Z(tNL8lkLRyuo&GchrS_lpHqA%U6NtA$JA) zTtG^nc}ER*BlYTcfo{q5_M5xcA&CVnye}q~ua;VGGOq$RB+Vh$ zUn@Mg@_JfGlGPnXvw(gvPhM*CNnF+}v}v8lBDgLt)TMuJOGRi=oM>hCu8|qNiy&6D zIv>B)4+xe)$AT^Q5S{|rpY%iP!IdSWbtTA7M9E^u#jw0$Gp(bJFZzV83@geqWBp0l z^Yk8-nbl{>b>%L0-~6Q|dAC9`=N#TTTYR$qG=jAmi7++U%-SZU@$uve*MJYa_59pi zc27D{Wh#b#+m=jeEY*ftF%dB;brizt^jjJ+FTFyKiJQz)`{A(Fa zO7E0rHH>pYnaYP$b|&K$+NwT27xB6 zysz3`29{p}27Fnjzp~prU#R52w06B%6Q*MZI4y$vF(1t=i7>_YSSN0rno^AdGv5av z{TxvToqI;x-O6}Z24a}~a@(7O>9R6OX~H+%i%}8UNn$1@_;&v`m_=Z<@%`|j5pChi zl?EgF`{Cz0jmJ-}Nsn!B8{U`tnG)(~@5}kIq#26)oGmQW_-fHtGRvCEyOsw{RyRW; z$k5ySDh2k^^Dl`W^WK@1gK!LU-83}4$kF()ceG-9hdo-=PgI0RCL4(cOJEC4yuVKE zlODdowZ_nFn-$JLc<@`brnAgARBJX#vEkCChy&L27*{a0I~u|nFVP4D<7`6?WDfPS zH+I?mOTkR+6VCS;%Ph!vWf9PwqN5Tt|3}3g=zXkjf%0*fSrli%(YFXH9=k7E`J4=w!htTP@>t$ zaPp-Z*dmfHtOq6>cD9e{K|p-AR0&XKj$gOkKffOHiWG^ZUE6=rT{l=^^uSoF5%_)f zl75r5^%n2Xoq;=?TM=vMg*`RSZ>VEe^zz1lQgE@1>)M@8a)7{PNBOjlW}U*fddqYDT*cd9inG%d-sU~D6P#6oaPlYm*--T zm5YrHq7~B#p}g%>`otnY|kf=@@7$nuPM@TVyw{9 zELKHi8J*7jBh)K>H=NR+4~pW@%#Rg1US$&QW9u#V^*7BS6B5!xg#$K za5Y&;lm^6vu|dcC5H}(v7ON0T7D)udrJ4$DW2&2IJ)ppcFK7OBSw+qhwJSTf`JI!R zb-wX+2#QxN6OyZV8C&s+k*6(9tPasmWa?ub=V&sX><{(GzZew94|j|P?TP=ZMoYLd z4l&RR(sL!eYc6rv*7e#H+15mBJN`cHucG(rF2wM-%?}qEMt|p+qXzv%tS%w*^}5@~ zMDr_IyJ+0{-^z$yn!oM+f#=!=6$&ybTgunX`;;fdV2h(s)=Lbm?3eGv^Amtu8SvvW9(unX(Nc-o69M+Qr7qp%6Z|0 zOFDK2`;Zc6jb$`Lmwcl9odD>H*-A2!pyk+3w=-x=AnL6{y( zk^Xu{;fMZIW<7MM&x89MV`-b0&mqN`Y$4r*tU{*nZY&=c06G2E+;M4jHzRR`mD!6@ zFV|r0rLh=Qu6S{^gtSJyiq{QeI9S7l_S&Xr6uX~eZdl?#ZbF=i^j-UGh_ zhD{ILU9DZ4R%p>QDXeYK`71aZ?Ht+yrBf>LsJ8=SGv#X{^ai(FE8R6kvue+?j(K}1 zN(Z-i5=GE3ieUtUOG(ZpT2PJl5&Vq%T@Z0qQ_}|L&tf+lcH+!px@^wX0Vp0`pC7x- zDP>H7fOB70vwZ(Lw&ZTH?!WZ)DqNg28oDlnswY6mTsBr#k`d>F8OwUs_>7XJsM7;K zOKQ;iF*>WNg2&buR5!C`I4iN=I%9e+;5mFG_K!ZCo)zBTCvw;$aD6?YtYq)x1DogN zkS#Y;tqu2a`Z!L@n*H_1)I*Y}iQLo^fBmuC?>XMx@@UNJ0bc{dt#wtt*T~<6(-kVo zoiAwZdUica;q}zbvW>qy=o8`|{^)$8Uc<7>tKa8(xiREcMEND~L?Xs!uUf+6Q^86v zH{)eN4qQT!^z3#oXU)xIm@G4PsZH+nyjIw7_vNY=(}n(gL)B@!oOn0->Re?8N7bnq z`^-p1uOIYFIMqnRX$*ldo`$4L%ap5t(W_3))L6tiGpEqF_-S0q#n%{*MsW3ub88*> z)uyr-JwKecP^OMYUJZGbiJ^lQCO{)Z#pqJ%VxF#9cDvg=F=xT3_(2rM1>Dg$9+pFa zQ<&L+-xCjpJX(`d>j~mG@jpmge@f$Do&h4KGrf%&rTkOTI@>eu&(y|(O^%t6 zVjqEz*4g7mgvb4j&16#sb2J#O+V}y1AA5pCDlZhi3a~Nqyd`Zp`pb%b4Pa2{$Ls&kngLgiF{EkqcHz z4~zE*iG!~0eCoGu*h|}3YGO3ragmw^WF%r^q4TIW*ywk9OkH%i;*(RE^Wy^PZ7G~l zbo5#g-ak#f7i;kO=KQJg+&T2Qi7|J$ zqDxV86mhxbwrQe!kOM9c;w@V??*aB%yNOzcgcEUe{&jYyQH^(#uQCc z*xA4xEUZ7azT?0iW3fl0)PN)NldWSD2dZ=e zf#Qq=BpYQSFVDLvnlC1Km#ykk+^8w1VVGSW@p$p6#O-Y8JiT?$RDTDd;Q$<7?l8ha z%ZjNLW$|8fca4~i$9VQ2xj{a3?Yh4@2A1mT{5K=DLhFU_KBVPWDiTNey+U|IO)pY0 zuBJ;$y!Z%99`w*b42`?IW-)DzPNE;CYsc(7(}pRG(ehZF|Br-Z?5TzxB@{K-%Gu5! z)g=~llH&6Ork)NyZp+Jc3Ol?tN9gN-=ir{khr?UKboJ@hei?0?Wu{JyOci{;rw#D( z-v)g&QVw&ILwpQ9^dq}T>O*U5*j8|;u9N{sm4pEtt0A1KH0OU*OwG#`?gJ#O!6;ZQ zZ_$}hnsQ2S50e`{mx%q!Paga6+fgS`VXq^aB@JJxeFh`DCPwN} zr2)V!xZT=dIV7l45FRvOK`=Qom~*EdJ0WucOw`04gU$snNM~nQ4G}16ZUI`7&R0hC zd8>Jr>L^uf9^MQXOvtCxLbdKBz#4<15n9=!?)P0=6EkRiC_JK`&KTa*T)*6IMO4jXDlgZ2 zgy@s6tLk~E85?`>V~!+zN|Xwdc8Geo$fS!oL_lamO)oLtGVEKz+C$qGWC0PS8?vEm zwDL=p*yRsuZ9CpHP)jB#{}#_DM)MozRQy-T6Z3npAc}ByG_->SqK&V7M%f zQ{bj!sUj${OgvOX@QAO>`{VX2Gha&SQM$t>#B?(6^?C&&3wV&Z?nU;E{EaUho_^#d zzxNClr58eh8+NnVEo32pDDz2&D~3P6G};hrIQK0%>k5+a8wD3l@vx-qg7kMcgHCed zo$DzB2Bf*CK*@qS7PH^&DHDj{Jkd#^_H@eqJku&$B$xCRX)v?z<(IN17qN1NC%}a4 z>TTXE)C=h3Kt9bp5h#F1@BHIT!lYUbSwq`(OR!^qt{!y2b@U8#wOht>J78zK@mmlu-?swDaW zcJjxJcnfV7?eTk6xm~*c0gb^K94%zlya>t%g5`c2{7IXgtq-}eeMf&Vi5_iZp5N9G zy}>Motu_!T{O$eQEYRgY)rDM4jC=|;HPvmXl(=UlyA3_}=~BX;JIyOI(Xa4Je_EoW zGCA9kb`YQ@c)>ReB|N+Ygbh(;G^UUjuw>@FQHb@P#w2f&fS<42*%)oSDcJ{vj60el z+cYO*E7raB9gm0%qn69?#R;%O)}w}fuAD^jB6t`YNR8}_a{q7;HAT0?IuzwfP*5cK zJi5&VD7c5b?dr*RFcJpJR6Q5eKvSr zA%&FYrfrgz&R@E*=-wTQMvkt-qc3JpH1K(1%BQotFLSj*9Ps=;`*d-@%IkPJJxzg1 z=!w_aF(lsKo6Nuysn*o9F|CqYZI{XvIF5VLXBrnia67ph@~q_Vb_CINp}-!6>MqvmMoJ9g9t4f+LPRl2i5bSx*8ScU zUmdWkCKbEKHQ>YlI961BRx2rac(pEL8K3AxZ1Hp8V*xs0JK%*2fMmfVZ@mm0 z+25r=_2pV-kRxiw!G9HNoiLPD`#5!c=jl^a@@hmWiw`LgPQlSW4~~}BBBz_1#u(K$ zq?f(x%H%MrYtK!(x08Tvfz#WTDD3Gjj(7CX*^h?48${l3T2$zb76X7q{ zapIQ8E~cK(%+GQ*mwWe^V61&%dK*IPH1i`+I+if*=2y{|*2-54J$i5>Ok<5Lk6skM z`~~56H<4z*7FD{6vm7gjIj4;kokmb`sIE{uP6hPLfjY@_Sas996A8}&2c|fk`I{dZ zv2}0vhSoo98(2wU)QADwOOr=^)F>cv9BjU~mmDm@VePLr)fyciI!ERt`LqUiDqTzyKGS)j<5f*AY!gmmMsQD8&$JXqHVh7{(_5CP&>q9i zQoa>S%)|2CiJ~*cEVoHQwD)CN(__zgZ?$K3ap+g+y4u(HK&e)$I4iv^(^@{P%x9T9 z+|}stlB8|&3s}c=o^kYbY_7g)lvt8d*%E7)a8-7Wo`-x+x|e5N9f`qNaZKo*ghKDj z7g1vG4R3?3rjKS>OTwWDplN`=y-ZJ3ffDgbI+k4Lr=RkNkq6&z-2R5-lp=b#C+pK= z2`04r+5f=`!EW6f;I+l!%Wu~aSHg4Yj*#2JILoMY z2*X#p@7gApON)UO%Z`iN^Rm3&I5K2t!_tqi=%($cGXn(e=};L7XYw+Qv|j}KzZg4* zU{QcBNnhJ|*S2ljwryMQ+O}=mwr$(CHE$-Or+e`)dU^I0QKu?1zwBmOn3;~WMO#PS zWCWz|bU(E>2W14lEw*+%^u07}Np*0g^(3BAn~u^>_FC$7{92ZCdj->vY}W zh4*wl^t?WXH?<0O3$p+ul%UOTtIH6;Lq|aJ#xf=F`%to zXrI3R_XPhI43Ho$3kbshX)$OJz!Fy$0G|(loEQw{&*3rX-Tgzv&m`gvDVRKfhoB8W z#ufkzJIq1MAThk#y+h!}I#Jx_mldQwXd|FsLBT*)?;v2q3hD7Qomv;70`}fDIbNRczx3 z-oFwxJu_ecN8sP=o7ywI@VvU+etdfLn=7DzcYXs`0If1)ki6=m{^&bVdmw)LOuZO< zGBUPXDTSxLzu7z$9ZAKz!ps-{w;|*T4?^t@iDF*bAC0HO)+)nt}+)S6C{%(CAU%>yD+g3wn#iivAp)ach7gpJ)Ln97;WHSR7 z008k233?ZK13*v%7{aoieWdF4kA*&JMSP1Cbw$`a1#$yiBh2&z;kO|e;PrU_u21~mqYz7Cp`}z3xdPbq3 z!(yKrKec<^eVsHatIaEU3_6q>{cRZ^@9zfm(dGw0%f+VyfItBQ3W|^P^EI6Z6!@(O zc)gWZNu$9AIQmwic}V+FsXx^N(*L$%Ujz7+E&=@)BK~zx}3s+{XRN z?DsZ&=@I_U1|)H3W%*=k_-_7&VjRJ^JiJc=QfR`1I07*5k1_atmsT4hIUX1bQ7?0%7d)^#2WwHh4hL}LqY|f^=;?(?)))E zp}X~6i+coh74E^i5!d-)@ZX9b40-d8?xhFeko~O^LIexh{L0|s6(IO`9$=3G1G_wl zkwD%6$bbh4_TjVUVn{i`>Mk*K6@bz}ZX%y1f?LTzx#JLwsvkdYvY8rAbI81uYM3 zG;{8%q#9eq&4*!LSDzDTR)NE^g2+**JFa9M=K6XY;3iij3)IridxR&RsXXhu=$qSz zm&LaHYpb1RGCquBz!oSX=M^u+_fs)xN)ofrR=R4>yq}xZOjnl;p0-Y)DJM1{YTR{4 zBcd;`9P?muT_n=$A{#S!y>>~tI-T>>BoIucrrM5w#oE2JlnqE-l0Cl(`PYAV+dQiF zfH%?Q)1+o!wJ;;4biAY{3P7)27{AmT05~kmbThl~j`=XmLz|0JF|dwqk&nYqvqglY z$*I4?=3)Ifadq98rrTLGyPTLBJYVkGDQ637Jyv`Pyhc%QRD;8p48te^Dl-NjI4Igi zX!6L+a;ga}e4{av&~z6TaiMQ|$uhssiL-vPYM;Hq4NK6b=hLW|Z@wnyy=cZE@H6$o zr1L`inLNlLF?=lb#ilS@rKy3V*D?9mXn01PUd7@|bpv7jyj6$tdB)qarU+lG$@cv( zw@T_Us*;@lF!a{_LI`R$P2n_Iv0DD9V1sf}-ozj%!GIX50BZa~LHwB!mY25c7MpEoK1)jaK}8eFEXE)M3olCNrykH-*H zzF<=~JpfA|+#g2vTizXbnoYRsu0z+AfVeLMg)5mSD^@EbJ6M zBIPOb*382kX0%oA6p6p)K71B$XaSP1p?qv2!N?AcPnskHB7~y%xwmfH>5UTD-X7@J zzbU`!fI`yx(`RNbwP=S0RxPqITy5oMUR+!S?4c6%MN=`No4=iOxtnI1+v(48j@^4y zolO$stKn`*jC#{}BkLLfHzVdKptABwA{4CejDO_Sa3_5<*(*cKO7bAE3Ope<7Ga#w zH7%;;zo~g79+{B>_|_6DyT?H7ilc*HLFsONW+SCJYx zijHM3TI@!3Q)N9^jE{IjnuLeLRt=^p&f_4;mn;p3IjQ&<+L4!^g&Q5Zw~bef-r=#(Qy{fpg0i=;$Fj*n^pnnrhv|=+X6F6GX0dvSwb?PB7|`l}t43 zc@*k>GweN(%h#=#X0)$OpnZFG?uup>xVja%YWEj|8MnyKp^=?chgL6G!iV_Xz1Zu2 zDBt_?@hS(|TRU>jBk^=ri(qi~cN4WddwM7(gU_R7X1gM;7X6q#Z(U{Vj<*a$Pk8A| z3UBrnFZy*XT}eBE->P}oj-56!926FO)l9UaLS1v%h9%{-RS3;#5J+cMG5g$wg=FW2 zf&yvfE+j=Q@5iA`Fc-^qHWREUK#WM1hr4|9?`TRcUg!oO0BLX4HZFd) zlzA*E%cTp?1-IZ%4JhTKTG>L|6=hv_)9p^XDS4M?tI`3^+j5!LZ|n#)Q!U8@Ii&bYO8P^W2{>VLj>7v(Vm59m1T?tkq<;c8D{`9*JgW= zxLUY10bazxrWl%w@J|6IW771-xJJBKarm%XynNyqS*>!x2>{*Bn)8MjKi()d5L0bz znXg1oD>%m5FiUuGEiIePJK?QfPHShJ^6YUUZ<9=-l)_Sp;LHsZJXu19FX=m$CA=9% z@}5WK9Y|-QmU1LP&&Oj^D&nRi#U1OAMjWVlC)kQd@p=<&5qW~}HLzC*Vm<}yaon=` zd?Q|GLvUBK0fQ!<+OGNz3(>`3vzmx3Q+!9LLk?Id(Ov6VH|0SlElKm};7*3XwPFU=zf=|NiTE?rxb1&g-l6AV}tp(29hEh2ZB0*6r zF6oOKOT`9KK*=Yuz8T=1-+x=H_hXB)*pk&Ii|~`@iI!8iD(D zYQ7aOlUQ~R``*d)83G)B_+>Mp$A1Z%ICEg6;q)jxi>%CsQB2vnt`sx7e>O5|#?HAH zH#kg4VOQ{)<8uoazhMJSjTlCFtwl^}LcVflt9U1h#3eVG8+dW3>h^(mJ=4g%Q8u>S zvD~4s=@8zImp1h*z{fy@$qk8_d?J+>s{}nF=6oAxU2Xfik1uvGp?y8MG6cdSf>k^yo+RMV6;UB9!^iU^%gNP)PIKrW1rsIrpBc6s~yx-0>B7@pRFoNN5mza0NW2s%Okgy zvQ1qDAWQs$dEAB%nekiD zofb8d8copr*>oEbvd8sz4@tu}iX2%8)1Ul8>8&)*_{bvkzsbq6>v0_WQ(vXabL--S zK4BCu0k3ysAELyu@Wt1QLRmQF(8_9&u$4oHdzBlwC|XNa1FX>xXJj4U_mSL%~m&nCm;e2;(&+1OUFm2#B|Tijl7nLC)ZP(s(ey#BoKS0c`a@sXx)p+J@S{(gSn%=-mP9+&BGn$#4QzdZl>!l zvWa@b-<3ZEVb=i_U`WH!aOZ+sz*Ky_JAkj?ks;cTDVP#+`Z9ANP7e6%L<&r3yZVo0 zAQ#-?cNKADPI2~*NE(yxPKO3=eWT&fj^$hJYtbBSz>6{X@Z;*`-g|hTq4@nI++h

Oa zO?hn@i2q5|6Iv;S0~R6x{=0gDyp&l(WUbRDgNo1@>Z;i@3++-`+oUyF*pq3J$v@@L zgR|$mgD3`z3ccpFgn2y*fzVGjlBOZs=}Xgz?D;KAy(t1Ah<zPmZWBpSsT z8v(Hcwqf~R80?WyDQ|ErioyD;)e$9viN*jcWlvJNyA3@3Z;mGXE*Axj8RkMgbM5Dw z9o)YyJr{BIQAuxcC5^IwSN)mW#bGpjBv#VYlJC22zq8D5mm&yL;ja8kXk+K1lFa;e z>f2Jw4Yf_XiBEh;rYR)Y8&3SUOxB65Y|=VRt&W#n+%*=w)4+gI^W=Rh9Gc=Ir`oJldg-FPgKOT3+Hd-+53>r35^!F9 zB<5UQ5!E^vzN>`y#kxvJ>p;x(fP%z=W*K=^Nmz?FE22^?wQ^CE?~@O%0#p<+D(5v< zU#Hs2iN=9HJ^O|LR{-%o%Bk6?)!?<9!g0KWod}pU){;cEc4}l5!`mF(@sA{j;hH)! zL${8{vTqf*-Rm~B%#{zMuzlU?Qa{E}U00%~#uy|KB{+le+#q zh7zxo*TD=G^S}6tp19T=Cvk4UkIwaj<{P>RRCGbl8;*Sk*U+2{RJ{u41zhd4gSqOB z>Qn92Wv{F$va=<&x3iHIPwkiwIC_pYg#b$ZA_CW}p-|Cnph*u{w@;p?ZTsyF!S5;KWSDSoT0ybYc~^B2(Me)(!V zX=k*@`HJn-W%ciw9Q0#EI$n-qQc90G!hPhd@h|oYmQ8?OrjBsJhh-uZ`apZZijy{G zxp%Reo)6Nd@|y09mhh9pRa%JOfqGQlBWz!V{$~zw1>*1OmZ;Jx5g2?(iaBg$F{#ax z;d-lLDFOrbhJwZ@S2Y3P!}o|{wL*hXgsNCw%fCwSk23_s3qw=Z<=|}L^q~hfIw*%M z4HBs-5D@K5Ae~(92lS1-<@zHJ4!tg_ZvNZ&r3So}H3fXy#{yh=7FM3tbmVL#5j&cp z3RE{VeWM{5p28o&;h`B~b`@$Pz5bR|aXB#2fXXke#EG-uzh9qec+;Etp4az_Kq zEhuM752sf5-0i>|L8qY~Me=B;?~X9e2;nl{c6qgl{ukxgvN!N#fmgTa>hGTe&;ZW^ z3O;K$pbnoV!%%mWm7D2>2I2=%-jZwJogW0-iB#1)PQGdcm=-3p=KsC_EtaA1s?Ep0-brqld9^2c5R%!}Cjdbv9g}^RR|1>1M zE92B2c;&z9C>D*(NV1eQ3dv8a)s%ytp;DT_lK*;oL{YW6XT2 zHQ4FEPzS=+)Dn#Lh}J40PYw6eRIdiMY=@bHeo(WIvtlIFXx`<7{W3RJ_lV;dt=3QL z$RaEU2Sr$BLlQqG#t0%o)~zt{tPH!t}m`QNCow>{=FnJh~Fsy zS`mvv7cP=>*!(gKdN;e)S0qA@tDZJ(79c+0fuwyNI(^K^T)*vH$Tjnr4&Y%OS6St z+q9H2U&cyFAHi<%|)F`v>B%a3KKC!f}cJS}g(TaRn ze4OJfULUcP960b!e;3hV$ay0Fns0>%5m=GIOC?cD(26hS4-&uW?7{sS4+}o;tAd94jDvi?Qh-*#Tx$A=C#?LV?Z#ODF;^Pn-0k@ z`a!aNan9}ev}ePwCun;mDOs~!1N`L0kO+jQ`>|E)du`hO_G&GLlH-Vvzt&SzqCpvc zVab+x3bp`~mxoEGvIt`fh+vw34Z^%yrSr7TB@@z?H=Nx`@xM?^M zkz7@-D9fF1H)6|0U0s*Yo&*?hw_is&@=nPXKP z2E|ZPSFApA`Mzd1aW;^<`p%hKP6BP_Qu{s#p$IM`Slw7tuXfv^`T45XWGR1BcCU#E z!H_^JKFW=pO@Y-zo+a-@bu}>>%3FeUk!@*_i&6g@{g0+BBwttvDI!1?eU@(s-I+bg z0wwCdB(PdO`X@}dhC}N8q9MwXC-`Bq3pFat(IX~99gs{Fm3Tl5mcVEm?@O97WO55K z`4OQG?S9q`Zwa~Uz#J1^^KbYu;oRfTI$N(NHsbKfQn6u8WMMkN2WH;#owc!w)0A{EmS-DTyxM5ibGzpGRn*=aN$;g^de0Z|G)sq4M8n^ z>p;Bba@UVsRwmdj@~>l{s{*Wsi*&MJWiX)Oth%EbTzvgE^1A%Plz2G-y)SJ&gYd`_ zef!7Cd{e%~F1rP6YU5v^V!rlUL&zAkvcx>sZMV`NI0Ei^&p)!3o8#N=TMm+zX9u=T zYiBVt>4k___72Zkh|_TlaBO#xC89+x@NEP4c%RRLu3NP*Qu0UoCp)l3^RAPJoZ0QnN2fkbLS z-P}SrIG6qqkRVCy1vA&wIZ<=53K!huH-t|gq{J+*&nM;gc%5o(WD^+pz887bc4s$Q ze%}@a1_44lsM`2FE+4fcb+aaV{nZ!PJT#VB!MUif!K~RX=l(r6cQ^%{U||!|&LR;l zWtv^hO=hv#Q0Q(b{)`m1_=H@Si7Bqqn6k3RyuSq%fAGsk3T|wc^A_6FHs&VA&kcu6 z!g9k_cPM6rXJKt3{Q%MyFIvz=epNk=H>zVV=z>S}S?bwWrw7`ITlMf&TTl*RnaU=t zZp%vi;Ilfm6`< znv;6z>Gy79H}I+gDq#`FE#^szcjdKO!|J5RmB;J$vm>WDBtuXmT4M>u z5-24=aBu30+WHH?0TdKN7XS;33>pgyoRg)w19j`qS1LxfCh`?TV}Rh>FDm{G1ZxQ2 z8gbMbO2gadnrFkbTC(EuuMQ7SQvTc7U19XD9~)o zJllUfc_X#Jj6t0!oPIy>!0KcQbRe%W`+zim96)$@@UrnS;H0bmIKKV|U!XJq-)peG znSmd-_TC0x)P{gBSyon-;Ei=Gp{*+XKLActTJ-!9k~yF^P-Z~rLQ_7Vn41H6@b4ot zBdRSUr0{^fTx?+C;S~T;cwk>v+-c>7$voI2K#dLGEQFV}jPP11L22Pa*H?WA>@eSI zzDTMu`ir5>o%KKM8dwlZpa=J8^sNDD>A#o*Q{y=*z=p?rASv;0R7d?mKe5w5FyMY` z?jGzO9Dw@Z|LE6C3D0UCE^JcItTSV{!UkE+1bde*JY# z<-@8s`SyEnQ&rRyMOAfT?q`R5KZl0$Y5?F(;b;Mvz{6nsW@cu<_B`0#zuhoQj4FFK z^gqeezzpF)xrcsjUk&7bE!N-Zz~;V-;XM0%(UgLC=l;OteTE);TH~`WhSI(Kn$`Tu zzW)~fU$Qt`%CDV};=k**ciXx5`xmdZK0CR3Qx6cn$|Zo0oFDKb4|wc1#M1w_Ocl`D z^w{{dR~Mu0J`hQm;19gDsp+Yq!QqEdYk-7Cd%$#3^~KK#(vA!7(n8SKv|rmw+WV9w9K)L$6I(pBmm`#;Nqk(ihf z+f!(zFF(E?_-CNtbYD$xIjsIaKKVX8gA#__S+-6oz^$Wdw(|F|90~SJiS? zmCGTgkq=8dXX1;DCA&jSf4N)*Q+ zTD0>bfgpo0!1pq>&WZSqvir%v^@4G~#xiuc^oMfbyy zODK-y%HeZf!%l~MI0)z401D03i-XjMb8caEe5WNpK~r?Z=5RTTx>=;*kmk_308>#@4L%BH4`_ zg;@nlgsGub0ZwhnkrKJ)nxb*MdaxW6{Y3DYnj|Ns@mVF=NX1l8``J`4W%4kw_csGs z{5&*7z9X+lAtXg3fOILVEeVE#yU-iifQO?zz#hxkc3J3hkJH+)1jGLUhU`!_c)mq}v3;*iaTm(ZB> z-fpdQHcBBMB}fR0)G?-qX(LyZSd>`e*9MW$>5b1kTiCXAe_Fa$dz{s771!qlnqV$)r!0)K{hqlS(fC&YA-f%Em9Df@Y4{9rM*&+z)3&Db z(9aq}qmo06Ux#e72h-|skN>g`)sW|KRcdAO)3jlQ94{@*g%5NMx_@!s^=@w?j6vdl zjUp`IYb+9!`zDye_f1v`jXFcPt^)Xnn%Ka|=o9=;vsurr#L3xc(m2w^XQ_oGdlG6V zZ3gYKbpwSPhNm3NDJ4l}s>H?1bSzM3eX_%Ri{Ce;eQ1j(nSm0kXob%r^-s41?H+z9 zWnu9vQL9*1Ud6*EDlJ@l->VB?vzhDVCbZ@aHF5i&OOzFbf>^yH_ZWDt-eW1CLta;Q zEcG+jM9;%HhRE&h_#ksDoS+_;7Tq9()E)s$89Sa7MF=6J7McoT3fZGF+WI$!j412c zo_Wd#VgKbrnZ)rP?9Kw!lWQ}^1gby__MTc{L=C*C(_k^98hB9}Xbe=NGyMc(^-5r~wgv-$fHMnidln(?U$!*ajNPm)rU1524!A}t+vn#TrQZkTcb2?C z0l;k>U*qUhZ+a})eAQ>iMeTY=PTgP#yN$ubZ!4*b5{SS)W$t4GP%9STWaVnEO8U ze}5QnNr!yi68zg@{VG@S{`hx9;$uo~>@~JS(QW0qM#9_qeBF&aXw_I~dPED~HkY#E z(l@uV2^@^XZPLIaSgT!Pos&Elu{~TjBW&-gw zVr{AF%O1+6B_~`Ucr1Vo>3}6c?PQ(pnIeiGkRL-wFe>rX_=s(`BCN+07KzFKT_+?Z z`f;D$EnQe7NpNcyC9>(F`DE8qDUu8lp`NUKa}XeQv-Qj66Z6gS%u{q&#R=zg_}*9g zj#if$#+_%uOb-`;Q+YYO#E2?u2aP{qT>`A9Hk>%uxmOqZbry`g0wufm!>v}gnOxP` z$2-z^Q7v1R!ReMT=(ZbDGEoK(zZkUov?y&do9b~)T_nZCh7`je$r>)BZRW6$?F5Ql z2;ROT#4KGfPm!0^!BS{|BRq)TEl$kkc9?`~X|J+s&#iOt<{25ZK(A*)W__RcqY+#E z&EBAY7Cg`{mrr1cpc2=T5+mesLrx}qY7&T>xkchOc@O5Iq`oaQ@pj#AQr~WdxNtg% zyMl!)zUEy%bw<$=cAQ10Jf#}j-63Tg8ti?-`r^;-=iDkp$5z!M{*9uac zEydUk6y%(dM?W_Fb_Vk8J22Fz^=D^5%AoDtk*z+AE~})s--O%q)r`~ltT8}nEdLb4 z0>U?cJAFUR8Z%4JoJN^Ip&4vZxU$AoyuP#1yuSXLN-M#049iY{5?|~xn!LPQEcci1 zzzU*9ok?Zw7)CcA&yTd&}bZ0nI<=c6?r{zEJqGKVURsD?#~C@i|1)IaSxg}?p9g2CeT_UVF+Dc=CD7mUv4W%BQo-u3wpQZLD=~c8M1W}pd)?atJ+?MezS20IC3uL)>OE^u1DHaM|0>MXTR!DOd>u6$ zT^ovx&KR&<)88rd-p*tcv=#HcH0qvsz4Cy?uGzGs-Q|{m$ncH-ieql!mIoe`0lWQC zu$FKZz-EkKkhn7y`>XSD-kg_#dDkoz!{i44!4GfgVnpM|a}+&D}uelz*_#FDvCndpbCFFq&6{d6gIH+kG2 z7)?@`k-q8lK=pTRvxCqnrEUREd90@RJk_D3=3$@SWXUipj)Eb_7VB%Nx#@LkN>`N%hO7c64+tD$Qy zpC=}dnJYg2-Ut3W%4bmy5uo3za>L%*9j(iyWL+WEq%^c1!C^p$-nsX^?S59MIU5k# zeY+QmcZx-TgTGuIcV9+EFJd^w(3J`UP?85Hh6dQe>q2y@;wT`ah{x~I=h(0aPx#Q7 z@_Dto{$%&No3Zh zB>%mSt&Ujr2`hR*m~!0-UVD84gt1$`;eJiBgUp}^CbP#m*BBrEJR1|{n{Js$=8JBy zz8%}z(>O|CM}9Q?sN0+CF?L(R#^UIQi#~6$7L0pJGzA!Qh04=YmdW0mq7nTeB`1$C zy(E04e2i6NrQFHcI+0AbdNjAO-L2xa{lKS?Zo~`IOxes=%VR?q1g`_x1)QD8E?u{a zGi7Gd4T{>yq!|@xuDt;-k_{uxkP!yJ-f2LPkm^>#`j5l5_F55p$NHnvUa8dTeHB_H z6j3FO12rJfvqRL5IqSb(UeudQ$!xv)ULU6#LoE}w-lc5g6if!?e_|-aWnwCD*qf4t zbDp?wLb3XoGQTBP>_*?zC?%mbC8tY)&6lN`0m6Ng0Yn^s_;u8ncFTHLre2up&uVYG=eH$1`}q_`-!*CXZFV>#saoplfRM|B%cUAJgHm!xY0xKWV?3A##CjHVMCVt zoKoykYbm&k=>mgG)nYXaAAmCqFah`aunyqyHR2i7Dh?@DnqjIweUU^m20Q~+tVZ}i z5+{puEA|K8bl$62zGf}0TOosjpp|T878Cohx9_;H<*$*|Vd!%@soSQ=&z2n52bf#>A9|k42IZ9Q)632b8?! z;q#%#IAOPEsB~DmQvC$aY{_y8U@sPf+u5=|^xtooEH%t4m`DTb=B26*OVt@hv?CBn zV`i2eJ#c*2(V~;#k3Jv4o03U%!?DG64h)qYQ%dzDce@AE)^6N*oxpINzt-?(gb68l z3BC_QpwFh%WGXZIk`71L-r?g0K;Md1PbHF!%=viA-VGJ|iT#JY^`5az2ov@XQ7g3iEQ?P&ZX&?7EvIn`=$YD7y&1wC~@=MBTg zfHPC4lWzFLz+jg(>3M^ zSb74Di`%8bZ#9B(K-6n?m|8=R8yy0w-NLi_XSC5UC+h>HorH-tD=3 z9t@cJaBn6qZ;(E|P>7Y3voL`?9G4aLdrVaHWdn!KqD76@WvZdaeHnJm?!g76r0!Cr35`$$$`qg`Q7gT^7J_n7=4%Kr`Eba)*KJ3IuDs;VRinBJaAG z$Cvm(S_YX?jUc`m)uD9>rIT17Wk+`4TU>Bd8u-w>Y5^KEjtW|nE~gRIt_7O% zMH;c6)2O@M-y*Opn?v9QKiDbW2&EKR!6D+f3^VQ}?a8GNzi-chN%nE_;b+OHAcMb{ zmHGSfYMzK1#mRVQtkCf)mQX zOssP00Z^@xZ+LNWh1M}fxOuB{MRIKD?Sv!@_A%)(eIplxzIohExtJE26TT?@Rr@dfAg=JHLZC~Nng|dSG^c0J5fKKu= z#UC``wpUBU)aHC2iD@sqJ%k`aF1iR{7k| zsaea=-Ab+y>H9&oP=W$!hUr5qUS@sKOzqex zxOlRG1SWS$&C&lcY1AlXS3IBuzPbrU;O(0Nk}fRjIAkeON*7y623QC|khdP+?iTo~ zBhkn33?GAN^ZV|bFzC&8?MvJWbWOq!uN(BXrNp5XHbG^9D4Ycw6knPdSnSor6!yfjPG?n0~lIvWm4 z?pAs)x<~ijQsOs19$e>LsiYdRuP*zqsRpFBeqKrz^x{+tVolS)jl!3Sj{RrJ0~o$S z%o1UqUf#n?pl4cy{l*xG$5RH+jQKCm?>{D`*4^O8w`u_Qj7H1$bWe26^5Jx>Yhra? z1|#9TKo7Fv>01AAVRLS^Ae+ZyJiaWX@qyYrDKAXdSHrpYj`^OIpTzEwKdW~Bt0{<$+;z`nBe9BHeO~*Ht6@gv)-m> z30QQzdZSs>1v><_=%Yl?j^T}L2Wb?ZNG%;&A0`T%&Tf1r<=0>KMQZ8}bp?kRR!`y* zN#py7N=C0sMY;!FUB?htr*{H}ou2C>wWE-+6M-bs|3EbeV&BH3?wh3JkxSZKaX6f~ zlMT0dQHRrX&EB|JJ6E=}pANqxgLvx}+KCqxdk*MAi_d;{3Q2=YmR_Y0%=Lha;ia_&AZjAF-sNg?I%OJh`l z$-N2e%?8KR5{nZUrd;iA&f@)i6&TEWPjbr}2CMj>8cg^@ND%G)pw~!p#DeL|wV1Xw z4&@>ZU{I25Cf~h7a88+^UQdiEff|hn6?QT;Ym()J=CrAg|Di9$wnx6~OFI*ls#bd$ zHnlStWwL9mq0SA1d>(pkdF)9xo<=bDl+yexlDN<(n?%%z_j;+n60L;FK)6J=#r)G1 zW)PWJ3dVG<<0zb!K*Ll(<3Ph5x+77PE4cseZa zoHge#$?e*yct8}lb2Ca}c)97TiLBms*y73QkfCT<|C16ooJh9~Ppq@-+HHn*;_Lsb;E9 z^9araIpJk9t4XRmIX`b^0=G=3>H9asRuyd0{`EcMA=qY!tXB!jD1xqb)J(z|tWL`@ z)76CyB+u?e%V57X>;u=fh45t9>Y)2i`0-gOM_4|pRh)e9PF*Y|{pjAhKmysIJ68?C zCgb@`GCR@b5v&3omDC6i9!)r2@sRg~;5lav$K!ryWUW}5W7DC@4^Ye5XDv_hm$bng zIvEq=wu9Tj_FyziYz?AK-KmIRh#!UJ7DxQg-h;$A8jt#(euN`7(y3Pq<(2%qYI3mM z5pcH0vMxgX=)(f{DBr+Wgk_krtT0FQt~CV!6 zvk8sG5@gvQ`U;>vMhh9&5PkQ|FIHR_;mHFeQs)Vrhnc5v6qC3u<^_$w>zZa`>gAg5 z{!ME2V9TM;XG-n4-6NHhDJ!pJhiakO9F8NbhCu^E8Euwc_Eu1_{MHJ* z6Pk$*kq1nyXKu&nci%F0NMB%-1)NV}jHhA~j!3(4laM=YsEHbC6`#2YJlh2!ThM7Q zRoHg8Znc$cS&lv3_7k-Tt7Vu+ab62za;qg85b)g-^StIrWMe`C--9qge+lyD)p}Ro zEU*KltGfey#OA4W3&m1#p_oIc@GJx_Gb`0|tj&F#S;(0w-YpS28v8LN=T=(Zy4Ihf0j1UEHmW3LjXyZyPwe3PS|21Q7#*zp|)))BTf85pwE#5ZBs@smV^f;UHdFT{mohiU#Vd4BJzjCS_A+87Xe2m9p zYocoXETh8y{vXE9DMplNZLn?Iwr$(C?e5dIZQHhO+dgeur)^{UW|DvYhx;&<)Jwfo zD%q**J2BGx<$*CCaCoR{Vw~rS9J!%&cfIxk~&d zi0_i+>33_%#bJO-CWaO&Q|xSY4Co#6(oC9&JEP^C8&^(n%AsqAjGg*h)=RADwV3r* ztU1y;3FItI_DR?o0^zes+NoN8>O3>{NRVQ>=){*2JX%)={tku=>ld! zLS+aGf+kThpJ9ji%(Mjb{QDYZ1#S{Uagk`qnZ5y%gFO-YhYLS}WU33jXJ ztQ@yE#W9W{i<`WnkQFTkks{lD%5OQJ+if@YS+Y~mLDIRfuQWBCWX?3{0WC%q$5N=5AF-hE6=(zW# zy$yNHJ4M0mmCk)!ZHN}`w(<+2@$RvYY-VjLafr-uX!`H}VhC9OJ*eZD0v}DAytqM` zYY3)#rM+w=;s214AweH%4|S%9>gxuY%e%yt+q>GAQTC!Q%Z?Xqavb*)j4f}CcDDiB zXwR@dwW@rI?gS6su5v&!ka_mz*BHlkQMox?!t)pMfuj>6qdcsHeC%%d2m?)6s( z90{<1Kc{kZgAXV(;y^HBW%RKk7jYYMlS*x6Ks{9aE7`7gwo;)dLLzB zQ}tsD@4oH&y>Gcc)y8r5lnIOcwpe&+*Z)==dAymIh29U$zG$A`EL)3XC{}x$+dL{& zk$M^7_F>nq)1%0zRdVG*mEk)(+jE?4A!q-0Co>v)F++?)X00H+*kF*M^KNB=i4&N^ zh*;OGdJww9OfsA3g0XO1elngx6MiUnsPsi2LGUAX9hcF5>9p4}PaAK_J88afF**jF zCx6BuRcks;cDALHpWL1Wb_2TQZx(evc0k2V554F5ev5b5-JO&92!pn1=6LhL;b|Vu zP#2DA!!BCO^Yg-G?v#g!KnwIU)*rn^H?=LAemhOVyVdJq#Y8uXvs^YFD8N>@sb(Av z9Kknwq1Xov6Yq79b013v9A$OGh04VT{DM+^hdH9w*dO@ph_UMbhJ~^HH!O^W=p& zgiyb!8j5WQ31W#c0!j#}Rs5&km+zYoA1j~T%obm#+@8Fixt&v<5BvHv?0d?!0UN?f zdyGW+aD4@&{Nkb_LO=u*loNCmkOL=s48a7t_`c~^95RGpa1^+tPkj(l5Rl;R7RsRb zHXd9KnEZdgu^J>W2;O)Uq$Cs+5CBk6(r@8lViLef0{U`XfiV1h$S^^kTh8P?+g^zB zAmV%1|HNu^3~c@5e`7T_H}?L4)F6PMK?VT02n&b@o?XNkM?eh0K?MlKH+@R>lH5cI zwuwMMJ3Bj{1nTg<9D{O%m!@zh81=AW-P0L0?uWB6T! zTX_Fqg#-ZFz|bi$fF9aoZiCka5&So207J1h0C?FUF5xvl-~-TaSJwf8Uqim-Ueq7! zL=@I;3=lA2++2VMybBn>{dt!_f##K$PsHB|JOByOx9N$-M}U2?;qQS2bp=}6f_GDb z04kxt0OoD}<0}Ca6WET&`@~a7)2D^{lydT#q+;MEZLgvR34QGUQO#pQ0R-H|>#FPj z^_7GU^cep7O1vnhXTQ~vU2|=LMj6Vx$VG(T=qGC+fAF(_K_C%OQP7dm&;bRu01@!( zi~8#x#d>YycjXH7Pd4FzKDYL40X{a#2mlql#;@>u^T5ZUfdq(n2myV6Ht+0$=}AE9 zg8~x(w8Mc>LVx6+wV8*%;d^_$L6*P`DBY`g3H|r#c6Y19+wL2KhIG7t3VwR^0d0U; zjd_W4`Eh@)lvRR106t&+kpTGe%LxP|6l72cT)QA%-LQNR9_yGuej=9r*N5zgzmvVZ zi?#(S-2wWB9SAU)@2?X1c@&TOM zRhjeRA^P&i@wu0TQO|)J7Q=`JV*OYi#%w>WR&??i!uhs<-!B|GVvtZi>36UE19I%} z5#qEBza0X2Y|CKZ{sV-KU-5i(!J%Sc*uGfZ`WM0j5P$$3MfrI>wMn4tkvnt$dgt?Y z7r-EHhxW!d5&CWB00F!>fPPk4`P~5!6n=rQpkV+YsUHGJfB(r{2^w`yl zeid4$oVsyF{HF6#;3k{F(=6l136nl#u$4KI7>l>kib$D6I|N>f_vpXHSMH9kaJ->7 zB;PNVoo0zWoRm?jBP>H%F4~(_kxeZXm?Sc;>i9&vo6p!aQQyTqX>I3N_?>9RPdu{h zNvhJFPcZxwU5U;ecKLp})maV1TpEkiCSTki%p@6+D*Qo><2h1EZ|cKo9(LWXOcP($ z%M?d$m!6ZU?aK02&hWU3Vcc;V*IjO>Z1b*%*Jzeiq`WiJao7@xKgk+T#DCA7JV2}y z7Q`*uWoJ40$IB9J$0?|;FE#fC+6(Jb6_}-N3nMdq%#WoFcEuxZd|srCxwClm!zq9ntMi&wY znfsfH4y4-ZK@ae|2ll^8$rmg)0q15Dpy#bg?z2VU%n{E15xkbNUG_3&H)K3$I)m{} zshl4sLVSo8^>DIY=#xNwIDrRtO!f)?Sl7r#-TflP?Bt8(cypI==n(`ZlN&$aXN4N1 zPf3bSmNHcJCvI_xI`t0#V6nEcJtAMq^eP`kij&kvl1OL-`F0v6Rbgbpy91)@ybzrJ zmRGvzBX8MxSH`E4`k-AQM@hvpR^>g=Ml4kh8$^0GR4d5!k@l^($bYY-9qp`h>k@H# zz~M%{aAI<*JVpt}fn-LQQ3uYy$8iF)T3o79gHDq_F_V+D>)Jmzu{j^H{re<533@?$ z%S*K$J8BH<3j%K+4;mNv%gUbT)^QO?qdIoY+c{p<8K+t zXCxZ*Tie%p#BsXWu(?`d6?8Fd3JLB3rbcVT_}0o~CYwku$=W#lbvN8opMX2-8y0D~ z_>eI}wN)P}^yXf(*b1WSh{IX~?!Ay0Uu3>Z&YFX$15z2)eAIVgpGBNK{40=21iRf1 z;!|T;AW1sPagv`yn{_t&qd-Laqhh&~A}`x-``HC|G17j6&MBrWj-TcoL4H=R%4c8k zn7mEXS&EU@c5fYOPTuTdAO0TNrE}Q0{G!!3-Ac?l0Xy_W9-Y}1)Shb9d)kNsFnQrCqFy?_09gVcaA^Y_LD9zVG$QY+9^`Po9BJF0@`L8zoOO^ zuK;!{rIHu&+ESaGFOly6y|Jt_9s{;Qeu={u*&JD0tG~*xXu3HNQY^ zfb>RXjNHipnzZ(sty~9gz)!J2S4jX}xld7Is zYqBO*wb&(UaN^!nNjsbLfAAh%-Lg6pvBy+Pby+-t7uR53cO*?g^W3PF)>}oMlW6M7 z%SE5}d^Z1ZAf!R4Mb#(^%_N8TrqrXI*~r;+DMKVvkaj5doF1pRVQnv)#)`3MM!Eeg zUjzww%wvkA?LD;FD4fSwS}<~syV#C<<1$);?5^1%@B9a4znAa2&B+DR!F2XbJ|DY~ zvR}ckJ=|d(kKFa=g@jvi9M@>nCss+b`Zk?tg2wsuL&(TvsbjJX#1nt12&03)^LN3u zh8+*!CG?S0=tX9zLoGOBZ&HktrAkf;xVo)$vryh|k8Ifl(zD3$IwTNi8Cbjt+@HcG z(fHF|oDtuV2_{)PZh|8)B44+T4Tdktu@TiGy?-yn18O;nW~LqvFU<4u_!_?UA?FZy zkohX&k8UE9s1lYakYGx;pVi@%b6Sp@?%>@wbLuTB#@`Gt55Gp2!2WWvj;3g+j&Y&$ z{Uf06-Vv)Gw~ESN+3UW|5Dja|)Jlw4SOrtGkQX6vJEwW@z($|(#=_~|ti;IG%L2S8 z_1^_uV=hO1lYqdx$K+7RyPR?HxY`d9aTmM4HuiJ87#Zf31lc+pm5Zod5Y9`(D!&NG zL0a|AT{x9%Q^DJ&9EImk_z?h3z8!#o74?6&TqJEupD2$JT61u9rt9T}JDRq=TjiJY zV|Vt9B%SgXW%qp};ed-hJ-FL8{ZQ<~-k0|{dJP>Gmc+Blt?h#Ja3fLwjMri+SxvI~ zi|QVf&GsH=R+3Vl($*TVtVp}^d{+Imt3GeP=)(oUeD9Gz0#xM~AmsoJMGa)NlKUos z-J|R2z#DCq%N5g>dXqPAF5>`v7nu4!(gQR0Rgx8+QH(BreTlgpLtSV!kPXssxC%M( zjgvKZ;!Ask*bou#z`HI5SwPY)d8GNTJ(OjbmBNFpJwXCVljmo2V*BYEdKozPpB+CR z&br0%6%zQmbe}UFf-cZF$uiFu#lu9Rz6L{$2~7KTef%q;oVHemEvzD)8-Xpf8W_fu ztG_f5{5n~6#cO#jPwa#{6sY|>3$!tP3tRm;-$~_ayM*+j+GTp`N%~R@>p5Yy;b6AE;zq2EAe*NuYkSYV<{t7n5zDC$ej^vK^{bp*7zA&qT(c(-mO|d>V_> zb%F|v>OuwVm}OEqToCTI>lZUi`fK=sjFIx6N7MWU(Q#Gz>&w;PXP zV;AqqvQL%J(KvOqQ6ky;Fl@Y=5+T-~lMHmvsdr+b)3<`>xo`xJrgjEv^1}p(n7hv< z3GLdU(9lbep`nun+Z0&hSE@)V>i9at-xFG$1&7C)y;MPO!V6h3>Nq8!-#AE7nyVqp zE$+)2#A2cia(}d!9dc-3DyZi~n9OB@tBvJuff@+y+pa*mNK=NZX}NU*;3rF3zkMZD zoTHqeOAnTwaw`?_;7_W8!yH=f^qaWmqJcPm17TTNSj0`ZWo6Jle1}(~+2A$qNg(Q* z)yU#I#Wk#+x1f_Az%`%|beywhJ3>h3+Dn)6eX17F)cQ0bn%J1zZF*+xDCzMj2E1m( z%jwVJw0HTKBJwGnxxs@f*4?_0rLHXSK8^2R45^-c-Ms#^ z9>@$-+JKeF%eemi9QEo!dj(@1xOjfg!ZP5ME(I4q-YsS z@62Ul1=Cf^XbGJyO{;J;k~P_&s>P4zNKWMEg)3D6Oz4!qC6Zkd^pH*-0G-`ZPNPbL z)enkI&Qjh%g`(ETPDM#sf2z3t#{-#KPkdeM2TBQ_VB(wRumQMIJ=f1xTF)V7TH4+C zK+Q&Ay)ht_{2|bR?T9KE8kz8FBB}kQTizJ_NzJ-@h;MJJp&iOVnz}Y@J}>9Erq&JcXK3-r@RhPO_|@!!U~o9Je9#$ zWNBKiGB2j^Jv@IiZ1j|s5?xKDpgl7`Q)xv56pqMzV!)t6(=Py zT)gJmOfISvqnBD(T0=2o5&5}Q%7Pf9)9hs7Zc!oWg9h9jFrSw(;;;O!7nszb=<9+8 zS?r&QEn@uK7ny-PV4Vmt$ZW6S^S8haaFB-O82-{^9q1RiHs477&U}-&kknFlXG3hr zTgEky=4|7CWv$z^lfmRJG%P3x@9n0SeVjjnib`!Cnn>-bRVs2q!HoU}SMDR}b}X(t zE@ql5=nqIJxU%f|uBbW!JK0+vPaZl%kTErfn$En?hqh3V`lOM^|4fv379Su#@K7z(XBzvd;!RpuN2^c;0^Tjdai zY`nBWaI*Ao>H|1_43v?-VMF`aQ+FM&g;4^AhdApM0rV0-RndZt&HHZvtydUA(e@ag zj3}}~okGB%rH)EyF5UJAQuLIQ#(9$5w3iymJtr)^$=?ubi0nK%LeEM- z05H7X_t)uJd}uL>!c8p?!7nOPtbr;tf(*qHzXWL0{OW01{|xYONRkFk8L95R7l7+; zV&sN+obD|l@T%?Y%~t|V^cG`8{l~vX83ut$u4D>UL_Aq9xW*iReNYm#d+Lyh&?xZN z@=m4d@oG$)Q6mQONCNYh6i<8sxSs|Va{u8D1CTuQ}t*t$BL(tJU2K+!K9V@9A(GNB}L|eGb0N`^65vx60ubJy0W0)1| z_StJ_g2LzJ?Id}}-t`_m`CmpLjfslu)tR(#mjzpkA>p-c13p+cC0qR;wu5N>E&jGg69FDUU?6;H+K{zI0p% z-&|yxdphCz9yL3zlKeg&LlSj$aL_wPdz9TO>q%lj$h*f-J!yIJvyk|~ z%i6F-*T5wbfgnn83LpC3=u_G1>@!>Q4&3~?fQ{x~bUy~LVKP=a?Wnd^H;c$=7M?nC z8IDo@resvVr~?uJVWFU$Y_PC+ohvgV{VB%n{`Uq**D`(X1ueRr8b6No0w7qz&K|ZP z#VT|E3gr_!B{!~^@Ejwvhm2jjPt3MSiQ*+zN}tEM1cy_GR=dQR!(}69$bF-rb z)fu0`@<>JQm7t*2a;NIts$FSav@gQl;n$}%_i2JRXthl$uXFX%k(2HSDw~1FjZBddYxP5w(9~V zl4~Dy9L!-=9YQX0Y)s^Fo-ewT{JUFOL=)CK$$njQZN_3{=#tSGmYk97PmwGc+*G{M zHDdR3Wt`Qli$N>=<^gB0CRae(g7r!@RgneW$6`c`oMPUSu`Q!ch(M34lJTsQ+76bJ zlM~lgFRKFno7{|fQ%24QH+1Mn)6Cnp0IYHB&$1G<{@el`7^R~gK~GUFW}nGg_}o|K zaJ~K+n~LP*F_l>rsMKQd*qgL5QQmpKKiDai)!QErJLA9N9Mj6r+MUsD=$j4?skZXS zlGfDKk7F2MiqGQCch^YOT<%r9a=P-gb`F3xdfC=+Eol9)i??Onpb>UplcGAL1JYi2 zP0froSTkLd6g}moxa3<&<|I{d^FDvbDm4D`!q-^v^QYY*xlz_-{WDxK{)p#~&r2%Z??Xx?;rAdXPg;`5 zoj%i5wldF#)Mg$T8ZsupK3Ym8KU`=_XPS#R-Ika<(#qflt-z09Qy$(7Tij*Ga&=h$ z8f@j#KiWv5<2C3xcYnzFq+%lO zjdFqTX7D~2`AHY59!M#)9jZioVQGTusMU6oGlQ3Lk_84@k9b_oIEb~TR66&2&BQPCtUd>(7pRtA#7onEn@Ky&kFNz|}U zCB+S1vWQ_`ygn1jZlI?j-r|;-ws$Ot#Y)-oHo|##{dh9^k<_yan&%3++`oniJH}R- z5lf7alNNQdh)EqAcvpdz4g%#gBrAiHk~ba%?(ft5QKBn5R3bHQi&^dpy*QN-@Hr>g z+wVl&qzf$yFiD$Ec3zQhy035Qq5eq3(E4b@$Hfm&VQj;pp!Oq)-;q1Nc|gW5p4W&mCQ!Q3;lnpF^yj;@v46P5_SaB| zUCbGKbi*6=+`N#KvDvCL{sl9eHcilsw%X#=mH^<%;Djo}ex0Te%`9lZf#dT9Hl*@X(=qG|!>0b5f z&6l048u?k+I;0A(VbH|hib(#=Z?n6c1HMiuyS<;PM36ZJMAc7+M~gUG1P^a*({|(> zhGK&|3d@*3;_b8bM!qNR^wt;~7Kjd?g@?uTAHd;J=2a>fr&nY_7H4jUf<4&OYa&Nz zxje@LFTpDqhu8Q!b%%tech#I#<}p%>GcvLzTa4g#V88`1&9#F~KFvvt8>5?f%jF9D z4mYTDJ7{?h956X_{yK5zA<@+eG%w zt$iag0i)Pvj+2->TgMs4wwjt&rf~;9+f15kF3={p@~=t}w?`P9neL*%ieVK)c;>}} zpp;>*6Uj%iv=zIF%!JYkgDT`kOz;|(UWzS;_HeM{`|*$FaQdpYpr%l4VoJqqRL50u z**%p2F8Fz!VC}$bd5#7<7oyEr=8&=)gA>V1;R6(tSXFs9Q0r6DRKXHIw+`x_hYNSts+mD7!fAOPj0ZCvP624P zhXaENPBO)b@Ac^y=!>!t7igOy2tBPmEOw)_uFgduLajlM$;%g*yarZO-y!fLDqAq$ zAkz-@Wz90fL^srm{0$BKyW zDr~NY^zdCM;_ok*WdEAf+-X$n1l+W>6T%W`ef4;1iWAC$IYS6D#R59bo!OYp)zEC@ zu^tz#>IuqSFy;Q{u0&?)-WasHre7!p`%^5xB}0Yj&;7 zOSfC5Ln)PG+j3ueS5jm1Wqixa*=op@e&{-7*xqEd16XY0J&Hvnqq(>{(L)_F^(b7XVWq6lR_!|qcf=s<|0$gJh$4(cS}>5w!52L?R?`f ztumIBwG7?MV>zBkWxXUQd9DSTCofs=CVm=*F}{pTEAwq*O7@wDtxht(A14BH+KSSK z)CbQ}Bh{_twaOPTWKQ&WD+8pY0bHhMKi1br5Aa)yN%@1Z5+KmNE((W;!_oYgud8r$CV~c z7s}VPbo;{aX$)r;10JEK@2>PBiNdGT9Y63#2>n$58_~i3Ux*GSw*RO0VIp8+W@7yx z@6Z26I+$44+5c~V28v$nkF~R@BLTgbwV|`Ah^euii76BxAC!}`qp6_{l>0_>E2x4F zWHW7~mHo@;Hf{TFe+T@g# ztgIfTFuJyYN_KX(H#IRe+6N7%EN^TC(9l@R_`MM*D3@z=ul#?)5h+*$X6aU9;kx}W z!a0Fubp)9lkk#XJ0*inJR%YP(C*cf^4@{3wObr3+8|rUA;|hwH=>@iiw>NO|`$6Je zoB=us6e2mfJUF$rwK@V9KIhZ{VlZj_Q^LZs_UYaH!+Gb|H>QUH^9>FxL7Tx%S(qDu z%Q-VOfpvSnkpn|_CzqEa(lXYEhJq%BcS0uqt}Df-0`3`JS%NBnb^_#V2b}opg94+- zUIzH7j|K}sDzr7azG>H9S3gSf7k34o)=hh+tE&SL^d!6_sqfKzY+;(oKG z{%raK-pbnnRLfNVgno>Ds1sO)^<~RWPvczW$l!EWQ0Rh3Z#_YV(z zrWHiwL=lhg4sQ={%nqZN+@d=n`xl2p^@FJF@gH}jb82&UbTV{kY<^KCys2X-q>5Ha!aWYzQX!JP&Plo>( z10fN9rfLG|0%p_D&}{Ks0_<@E%r8zyzNx#r(39`!OReY|DS-O&$;HY6Kr0{$@LNF> zoZ$z?MMZEU?44hNJwCiC-{}YUPeL)Yu{nXJ1JTytBKV4fM+Bhx8PDJ5)bIj&(&TR& zgVuk(f4pP?TJ%ig;$C+9X8o}0n{hHan5xpg_fdbVlT)3aLEai382~agI{dB=KUz%o zv#4FaA&M-GAK^oIeN1p@ae%p9YeAcL{L$+l8h{!8F+u28I~q~(`4u2QmcBHdypW_3 zn8$(lpYC(Nj?W*P*E))yHqxKnV3O_2%WtK{&yt^?a@ot8tL|?`0NR=?>N5Zo96|HF z+dkPAe?R;hp!uzhnQuQUQyp1>FoFYvKQDIJHM%4Qj`q%=9RLEyZ-6v7If%Zp$x+DtH22bv><2&$QQu-)0A>xl zXSDvBpX>*K4AP%b?V147iG7IF{+j3PM!*cxKVp{vW*NKT!2L8I*a7Y1Ut$Dw_di7O zS=|vm6&(|Hyx}>6b|6M&uh;==lwVOhfoqgMVg!7ZeTWqG8#k2#{TmD4Zi#IKf#-dQ z;rXL>AdM@ZF#^ubzQhQCIev)n;r`dZ&pvYkP)+_A{gQ#Zo(hzueTWiv&-4c%|9)4m zz~((a5?ri4(g#1sj~21n13!TUPG3<_Yw+6*?)R!cEDDf?o$Z0qQy9z=`h4RT<>5Q( zX%6<8h+i1k)4~Be2&Tp-Ag8b31;0_?t=;&aYEKE$2$8Lj9ieHqhL z=d=Bs3_?0O0&ZykxXE(*tpjZTq{ER@ghQXkJo zteGm{>+<6K*aM8%e*g!HoqvOaFh0B*;|lKN{(g^p9X~<2?oQuC0Fei9&X3$v9(a95 z7PEy(tzQq3Aov6SYaKq1KtB0AjG^!7-)Q=!6EBOYZFWQ;_|YrG0Le+48Wb(DJdaa+ zTln$%JPYc@AoUzO5xyt4d^#Jcc^zo_c%Ba&ww3-+cG5}~{&zmik*ZibcH-$6!2XPQNIB#n2E5WeF0>kmH8t7}Hr zWj$$AOY1rtcNDkI4iN-(f5S#AyhUCTO&!d9BJa~YPk6B39wZy%G5F{i3z@DON>sI~ z#5kAS)H>j2+8S+5{eXg%kRJ`KN!3tSjj=eBC=FHFutg2q)fzT|BA&HqMbflwS^Tut zyvcO-GRl2HWeERi;DWJzK6+Gpv~BUv54nGQJ1y$^ef6Kn^VbL!*b)j!!>e&YQumCP zi0-fy&drn74k27=31G^ogo3`v+vVlU4!-&X&WYmRYO>#JXgKc*xdp-_=GvQmGAx*1%lNI*WU zYjLtAxi_Fkcn^Y|Zh6p)@`XjKoIYEN`W5@ur_J!n(=A4rb%;6PnAbx6TTw(gyw$T& z$g_~pK%a|w+ZmPpQ&CR1(pz-$rP(1KY~eTE$>nA-8>Y70U+s!sqC%NK5gxcX^H0uQ z`QF$?(M{>&T?2*IB_M2O|2dExJ`@SlLF)X|BgD4D=i7eQBZ%|vQ?A=CU~mn;_5ygl z_eY_#2+%7jwi8D_==L715)lZ|s-?s~nW2CZOA$Szi9}{R{8Ey^H9O?zFcLRnKSj`a)m zh(?`-N*VkJ;St?vf8vRc%Xi%xDH~)geQWm;6-)E$y|(-)tPEs^H5aYMc(Z}vUc|Sb z4uC*k%>nA$ntsgoOA_C4#`NsGFIoLBB|zq~xeNGUxipMxWQ;}v=M(XhEA zFj;%wdgn_M_mtwo20WHHt11xkw<$h)nILjgFSh(Ef&>Q6j+UBfOQ(@j#~}}W)yDo~ z5XxTyse%GUeJ4QqYA~oW{m%Yg+q5+KMHg`nuvP%yWe{y<-YIH2Ddj+TCVDOvi3@-; z1XXEg+j;{JdZV*7Kc_NIX8)|eSGrx#>fMLaRr zViu+gKY0?#nzMU2lc?FU@P3;6lXQ(d8-vs+gQ%mb4b#;dl`rTjoaIQ?X=5HPkpa@g zUeSQkpuo;Y*2~UYZ8c@M#K|C7$>mIeKtu&>~>T-kIN#AsGy;%Or`dVhbH_&?`6w`7mF6t z@7QR&_NX_xT3D?f2!geY603?->a49w5*xgwc%{uEW-Q(bt69mtGBS4CKj)`N^WK== zWCH#ernCqDUg0nx*G&PmUCfhsBNNerqbE(BYCT2be6nu!nsEIEq8~66q$~~e6X6t~ zYB(%Zg#GfNecr;@lN;Z=T|0mBN+vs@9uy9pyZ5oOG2)}0J$IBL^>16X;WXa1lA2Lx zV$CnUmeK(A*i$MOaP#J!Djm8PG^x7Q@WR6ScH*cNN=%lJFi)MFp3Jmbjj6TMOPfOo z$9e9JZuUTnq&MMw|Cs;% z{(HV942pWTjnGeka&DA+<}-A#z*`_Ns^IEQ9sMDl1>EH3HP62OxTDLXn>qMCW5*qg z(ZZZ`Hay`?Us`Ajbws-erMTUL!sMt%zZ^;Qga&d2_p-gaf5>#-m^8(b{`GjT4L&98 zA=yYo#2$QWmmI8GX3eK$qvqEjo?BCpix0S{^*a|Uu>6@sA^~?F7MqcKccu$MU$;O0BiK?-E-WOCVBew;5A zCC#8YgOA6VR!ws5Z&F3iTou3+`p0WrOKzs#Y74Z*A*Kn~(av{!9(2wYy)Tg|LQkB0 zPsRnEkt5piZxiWwKA%{PZuEWrSj&h`##j3h&3amm(VI%@8r%JuMBnyfK&4PO{s`f1PhN1gY{oWPAsR^{?HLH~TdP8Ygc0(P zVdkq&&5HlMi=sgVNu1;XH^tA{Cb}pDL?LCBT$zwZ9MV<)881bHLJ6^(yGdeP62)Ji$7TY1rC{p$U<*;kaQDZIv zDej-uHCu*~Alhhuy&8EAN#_8QQ$T~dWU~~iw}@Y2?_?PqkYr~fsg=v+L!4J=q(8P( zkq+o#eD{lG^7(S4tm9Tgiv43{1+%#4?AsrCAFkDHj4`eoe_vWvr(nDLBHL5v!4&*j z1Tm5UR+3&k-CmJA*~yS*`63B%WxqO9kX2PgJi&wveW#M?ZBJP_yH)DK|IUD)&*b0{nJFjf-Wy{^$UIynkQnf{G z82_H0sT|=6HQC?k&UG0Pa-Y5anzQK z@letLZQ;JOl61$`r)38Gcxa%BSibe-6rD}`Y7+5CI)-vnPJQY56q_jBW*skwB^gDi zBKL$FL~)zS#|r$bx2D+z)~G4N>J_Ct_}wt#!Z5l1rJjA8D$D6|`Qy_#p~Rccy>gVW zWXvo#!kvpmF34uPZua+dN(*{#g&Td8NfY;ri=?4VPU@RPkQ7vM^MnvXIQxCMwi90RE6_HB)KErZgy4hjvp8)iJ%F z)ZPPrFU>e{ftU+9#i^IdNm7idjm1d~PO=ihv?CE}N`pthXOQk9A6&0$c_Xj#m| zSc5MZWs4ryqspqTXFzzLh&}OcOa+Q`oUy(s9;Y0Gt$l)tek{4t$<}6!NS341 zU$n`tKC=HP-(OwXZrSuu1qrGE#309&S$T7I25^<<0;L0HFKNgTW_#I{zi3K1f9a9UUQdD)1%GmK23T|&oC?Q$Tgpz7$_}*qG!fm z$)NpQQ%_oi1BdoxpD2z@`a9`XL5rd@YFH-G+`^Lkm1}Exf$iLB$&W<@CO4zB0rQe5 z)s`zpDcLvp1V0v!vArsKcNOA?-vJT68*gJjC-{wLQZEuKzzDA$*eF43Mv5|=F^OLp z`XRIA&GUM7+F@_RX$$s=p46BrAU3U%0MIo4^5Gh*wZ{s@g5JO|Yw#3u6gApp49CUC z7Bza=>xytKf;uX@#N@g@2WX{QyvZuhxtcVI3oOnjsc%R^r7Q<3mM!xPgBWyD4VPj~ z7{h!nzrdDrjklBB=klOcXx}TL*ZX-CYOrtqT$_~pP?pC3@1b$Pc@%g+_XDvJOqkQX z%8KnOmbLCt)U`@UW0goY1W|#~B2Pl8>FIbI1E$p=V{=Cfy$Ho__}wGTO~Ongv$>Yf zw0gARLx&rKaUuPsl<;~Z|4f{IQb6=6CX~w+a0}{ch_wLCOJ+To+j>;;d0w07Vn*}N zen~q))ZcjXO)%Bcq2>#7xAT5IFEZzI!iD^Wn;=uB#U- z*bAzXEsmJt1%n&QQ%z_*MV*YIG6ekhI=>Iol#Rv1|X3CS>B_jMqB!*J|PGMx``tONi868Dw^)hPKwwz3g#k z{P}1Bq&tS`k|*)`9?JfF7|6+3ZOM1UM4&i~dNo66EQte5b|sc1DXHg|v^+`?x1&<9 zNu9kxM;E69q(`BZ)~VAF!8Vc_X6k2@qZGaa7Hp0((6tkl zq{XjKec&4DZg&R@6Z1EgBhD-*?vX!t%GpC)&aF%Ap>t7llg{!A=p^6@q-Sr`)@=~s zwO7GZoJ50J8qteY-xCJC9YQXhxn~qVMt0V59{N3==!r_4NHK<7D~yE6iJRxvPY6E) z0l9nPZl|F)o*i;T@TCd!wRMyJGab9*Y87`cqS2{R6&yCJ^9tb_DQWOPAnYKQo26?`v( zcY;)Bn5P6h5s4~CF}#nYuB6P%h%>#$J%nK0((W9lrGlppk!dqJ*s>}K(Md(#=Ux}`kJw=nulEPRC%Rc1@?<;<6&M^fkbT`JUWcW zto}U}_l$l6vWX}fG+E*+4RTp{ZjfW*S{G%tJ$eSkJ&@uUr1}i~LJR*UrL~eb zl+&0GP1T>8beAq56}okKw)(01;j+KdP}XtXcyUrrVvF2$FGzPX!Iz8k%#+x~D+Ik} z7Ll?QN^Hc(cP3dkiQ1YWd6Ve&bmeV4x(fQH`+lg|S0N%n7&Mw z+^~tfP%ZiJpb6m;4(XXoo=fT`3=RHD6tM|!8y-cua!+U+P-VkQ)wCxN|Mx_aGp^}G zS`Iw7xTj4l6Gd<}`e$WMD@dR#+Dk%iOiiU{JDX9GPX$c0lE@O~;y~hyN;D;p34K9% zNZpv^O6a_MY|tsOjH4^EF1+4ygFj8P@^#80t7fIy%plO$UV}v{a#eeTj%h}_FljyTs%B69cFs;UBhWO^(7QHXapebRlEVBxz8&d?Hq7moxF}@MhhgM~J`l9J>9& zY3x5?Uuy=|wRn^w{cTR={hJapHZZY>r8YDDxqG}2c|V*amzpw@$F zBw|N|i*1yf%nn!&U*lsWwP4iCF1_K;M>KSCl2NgJ5D-oY%Ih`RMo0aW2K!%;YM71x zbx2#3okqRBZQ7@E43?M)pIyG_M6-{yVHm{6pUdeCEF$eR0KLy>y%vuzor5In&Tl1F zHV4lA{{t~V&c6k=+0g=S;L|;dFU+88s}1XTPnyWC^GhUFMf-Tg3*L~ddk2FYi7z<( zMNQb~C(V_(xO9Y+r!zwIIueRJ%-)~voGBhpL>V|_^r1?%q0f_d1DZAUF#fpqh+zd0sR3vpS@6_?m z=g)snh2#90PsChCjKG*VBFGPc(FOp{<*h$xcY!kW9GNc1floIaB*%z1yR4P3wyhjB zTp>~-MIF+G-L>?9Q$02@Byq|%Hzuvj{S&8>_*iF4tDo_^WIwuuLj0`3mp;)C8(9?S zU91uhE)C6uH8Vr+sL?lQ{Y27hz{mk09lo(0krpL4on%2E@t3+sl;Ddg zA?{0sQv5t2*@D%6wPo&jcW>1#KIa84Rxi!2;;^xeFci4OFobNShb=~h1Yg&k1!kS) z`|@%L+^=z64f#OM!5Bqe5wT8O8L?3^Bl^+kBwe;SF-UBWC^?#fP}=77>)A=|^w9VX z%H%>POfo@~`lhf=Lms2Col3OwTdg)C7?EE0==u~0-DrLroCd#=s-kmx=ZZv znC)|Wu0Dc(*`DrtC7`apsS)(c?5YR;i2l)4zDqT;!#bCXZYIZ4tWERP<}ItqG)jk5dB5Jbc-&PLGz~zA_QULk7Bzu?HMbD= zlAKaAARFKjGF-_OvF&E=VprgyhCNRoB%0JRAU*14Iz5x#oOgk3yjH9mN|YBBJB*hI zOd|16imrmZc(08F`9M`rX6GNre(?F02y=3(;iE+XzEoBIha}q#%(93!%t7%E)HZQU zLT6gyW^8P~-7j^Aq!0FbNCPDiPKFQ%>trE7j4yN&qeV4U2KqW$E&8^22`&+$oeak^ zDoEc)bdOkN)|Qi0s0mUX)iY~2LQT+HjN!-DKOSiY-$=sq+g;uUSW4INy|Gv0OeLdy zkTx0;v(pKwA)727CG%2EsC_S5Je%Q=AO1|2gjr$2)`8Nl9;&KY!bftrim=_UU-!m4FjYP@FmrD83^>y>w!W zT@QT;@cAA?CAt*PLV1;J0fw0Aj4um_l-I(k9wxCj0u-S9JfTH(b5HI(XJ`9g|;KoO0B@sP#qu@XTwxh!iD?x|b@( zXz7_#6)~d{1*qUh>u_t1=j!E=A48v^L#LVV^}ze6#u`)m{wQ&6GNdo1@-mqHR8Y$e z8Q2j&bz!{Cl)}8=oB6cl*z&R>^I9YYRMJ$$KTu%mSj9G_Blj5`i^(s;16*x>I`p<) zTDQ6NTGSVc_dBN8Kr_JpzU42_ry9}7SI7A>bu`a~$TTy3_!yL@lS={d-Noz<3OCmY zI58)XPM4hQJKlTSnE|EiSjKQa<8=P=a-y5Y8NVz~8;XNBDo-8%5D+lymdmD)U9Uo=A!sp~X4ah{1dGNRQf547{(dBvn^1{70tFt%MGr zbSrVH0*nfTk+6mF8E9>!>}@>dP7Yda4(>Jv$jTtQ5;y1N255U+zs~PK*}p~wmE$s< z7lXZGe)nZYSGWf{ZGnP}$meZXC-lJYX=W%yU4*kj_;JP|GebPYl zy$KS$c$a*rsZUkmLuVT5$u@PfA|nMHE+3;As!GyNH zafnu}Zt?5*WXlr<&4p^D6pO z3_ZqtpJp5rjIhOjDOEShqDmbj(63^GyylR#lm-~$!XO|Y**xHuS`ws?hmRXJppupF zMf8hA1cZ;H+8Uvi!N68XjP8EpGF=-!cwb_ETqwH4DBS+Dvsg4fF*DDc?F2PMBZ=DT z(dKkPiJR(6nb}vy?B2P*ZW$4x!&~dwqe+ zwyB-Rl==&1BOx>XM~*53ozJ1=#RM$l?i@?GZa`H>yeasPd~q^s>S_$fDejj0vJ17_ zhLxqtabtwIAv!u+XVdbE;pD;))t%j%;Pf<%9uxhg4$JA3_8V|D~rPWe=$gxt5-f}-8(fM8f2@&= znDWRtp9`&C$7cVeNKJ+Z!#i{s8wbNcnRT)T3%1GfVRZE3ntYQy)A`VPuc}b(BM_}Hf`$Ak=5t22Z<8oV6 zhb3u#L0>wGS4jari%&j^#&r^1b2YC}9tW(uRqFH{RU*xK5Y zU+B(`(o`(n6XfoDgJ3QTEEAE72)rxbfEx&Q1{R1o->F*fHd1V+fI>2I80!#JQ0k~U0bkA zP@}OF0!`1k-8JppJvkrQeKkU?Hd_HarYxUv1B3GDG^VgUs?{nhy0B9(cd%2xn(+wB zIwhMkRq){zU-&pI5b;cV_0u+=+9;Wv`Z0`OMch6Nwws10UV zBIjh&t_A||=#2otC^E5g3QI^QlPNV$N?wzcGpRI8aV85U9NS0VmPIK;9v7uJE zMjP!P5$aAmKB_kDlEib4e=uZ>tzvY2t?$(ID|unzK{!hIQVkvL;aX!+ zH22$h%8QnChl#RRaks;qSIuXK#<0Xp+@xaI9=DG0xEL(GSK-fTBIvG^iqd{4OQh4d z195sITH1Z-a?*G0SQm^t{S*R)3BCK`EXAb+tqfL*rZuqgbDcX`y3g9ow01^`g)8+7 zaMj>BiGerV;3tc!ul0yQO)PBK!|XOkNACSJKcykonA6h2UCI5uGaov4%Hz6m;2QCM zw)5rb54EObQS!&N5X0op&d+H{KSu?%+O&^*&7q@wqUSG`%9bm3KCPqwTEuEU1`OwN%C#wPm*mRu;BEwgN-E zzWp**`izv@oH3h)k%RBx_ogamFRq|(1RH5XKVAUiyU**jm&ZKqQhNUwoXCYQwt&H4 z7*uZfO~xlo{&kWt8_TeSn`C{r>E|zs^_Ep!nRja@`Ieb=3rw6G0UX^6dd?QZhR8ys z$aOj^)i8GCGe?&%-14TEvZ-Oi?T2^wqFbS-?O2|a=XIg$yg>(-SupC;aXYvq<^g@3 z7U-bp1D6l|KI~|LFSHUYFj~Lv8B%E;)H`WO(zc^lA;B@3>{ODrR+Mz zy%4<`yr$LZPq`gv{D5$LNh#0vY6!}o^yx~WWt7Y^tSgXnP@@(=+7Rt}JovtcU7MY3 z^2YlR*YT6ot91EI_d~!N>wrBMtKhwdiMQXrhKvRTY54^Th3U&li=h3C1C#eaMQ>;K06-Cz~$xE-HEWa5|T z7e+!8@J|nHJ5^BzET2zAu->qJW?h?yU(S5Z0FUTsHmx6WZH{%e5~b4gtSKL>SCP46 z66Ds_8pbi1k@Xm3e@M>3T;=9~7So0QN$Gn>&^-&J!aM|P_ZxOsX*wwvqXjc!OlEm& z0xt13>D}CEB_Hf7Ypl2>f`PqO%a(QzMha!Cnn7z7I(O5_cV#{;%IDWws~8#wnsa?@ zrV;5MmaQ#2>oh~_VMi2Cq}GU)4@T{))TWJVeqrCJ(M}jpjhgGA=@;2x%MxsuxBXu> zFS?;MQRZd^+u%o}{4Ll-M?Kcc7Mo)vHrWMYq##$Q;DVV4h#<;7rphgf484J!P}5kS zOie~474uUvqpjR8NaAqXklgLnRV%Fk7rmRwVTk$0Ojxaky9=OL>EDO@0IByQR!s%7 zLv-UJaQD2Wh{Hi1pE707ljE*VRYFKSRu+w}yIE~vTL|c`B_gMj4N(sMSZi=0)80|pE zn^Q~*Ipdq2D85(hYQ2_qR86RsN@$^JScGv5m>j}6DfpjT~BIhVB^tt-izyZ}9A zQnDTAxNtmw_xFfdl&A~jdjuBn}HDW4}kfxXv}m7;t5wb>*GZG5m^uS;M2cok_( z0HUg^4sV)Joxa9@Uz^ag(yCxejL?|;hUv@BV*Et~y$1(sO0NC(kkm$J5N2cy%OtX} zTg*2ee68FRC~KEOsO7px+o~7|55XjBA~FE2JQK$&ucS5wb2P5Qq7e*H7pq_vQU7>d&9lvekWC1pr>+F*(z@rqLBv z_>CQb{8N&2DjF3WYygT&gDf1pcW{t`DO)@&rCVrxp$)~#t{@lUS4l`j-r)UC8)vjF zsdmO4jz)yiKz=QK8+9D90SM;V`C1LLDL5QCG(y@?vlo{o@Gs=vk9`tIwnI)F)}lzZd~T=!V^ z{JgCu1Ul@;Q;Tg10573raQvQp>=C(>&BDP*H?<$UupFXS-b$SMs2j>WIM%O=-vZCS@gRqd@aXXEFgCHNFHR46D^Nu2?yewA$}c>}QZ z%O7?w!BJYoMMZHgtV^1dQ6IiNN)i*V9@qJmpHOYGj!=)hxqxI*6@YAX(d^gDwKt0# zsInb`PP)cay>Qpd`#$V>FgaLp+oRUL_y(buU>RjDT8ORpl12S`s}QPh!t`xdD9olHc<>3Vd8ao zS6lyN=Ap7{?@;VhyA+gTX0LVRklTh_qyyy&pP(H|Ft7{cTg;jKD>dSZ7;`e@>uzRo#~_!oW<#T~Gdz(HY^-CAAWvb2?!C^* zIop{g=?@4ZZeW8kdN7GTsU9J#ldk;ltmrkAWXtr;@>iedxVOQndk-ttOC_mTi^&ED z+*R1g(1&5@Y?Jll$|gq8GaRn3@oSH7?^>NFb{E~?T_lwcj}*2t2Zgd71xey?5nhIPL6fve6ypKD?#lJyma@`_yttbE$HD^=!= z_l%uJ(r)|IsP03K$J)~GkWv((8cSSndUv*N_H%0eKPas~)MvgP&5$6#Z!}fDhdkSS zmh+{d}nZjOIG9c{Bg%0Lv9=ZMn`CVHvKXn3ft}zgKS9M4xXL$sb|> zZVvv-SG`Rb97k+kk)7S9aBL}t%d=ZP0b71i)L>KclZD%~3~oMlzpB+<6#A5%8uZ)6 ztI_7|gYA;7}mBi|+ud=<48BUohhj9@fajy-z*uEavj*Wm* zx=Nb}5QG~*G3yH`>V8%#Ho_&+pi_7c&(xr1COttP&TAD|3%j#v~!ViH}=QBm_cm~JjABM@rdt?)D)EKN*qpnVYg6qDU`v$$y7?0UY$ zFJ5VdnQxNWP%|w~uvh(rKNRA-+G+i%H192BbCyCn)-lIRGXfLo=Ea0-6VQ};uRNWz zB;C>5-fB(eMEi7eubuIWVND=}(LkH4d|J|gT1)k}88KDMyg3}DsS-fx%4f7X^ERyI z57}MV1E|}1&K1phNzZuM|Cse*0Z;vw{Yp=o;e6Z zaMM3`NjvoB%^KY?4tn07W-`WFcgU>ikp!2csNT972zW*kDxqg@fASeX-lS^W%+b`} zVG0K_A5qJS%0y|eFMM23WnlW;CC<tm)pS>fC|T-T9{_UM&WXim9r5CNJghHwQqx-e~v>!coIZB7M2){NGpa44_6 z?!(_s0LLyowZU@UQh)OF*z zf@HcRBTSUSbA!JResg<+@k&_>e^#2xPq!L1 z{oJmI)k(A3;85)VR5;^;&MaGuxP#@`Rq}%bSC4#CJlU0jG0H84ZXRo2W9&H0X9h*s zS7LojCdTtxI?#9E9AmOJ;F$1UG5@+Wn4bMNLfxVAZ zROrK3??^}xlWRpLf6hYW;b_FF% zEtjJTl{SB~yK2bQGVgH`)L=d5+GI%UA4x0iVqvJsyTA$u7Y3 zQbCP04G-mTTklaXODDe3YitS2M7Z@Fe6?WNUV6A*UuoR-I!QjzB!V(p&vzN`w;1>jD00;ZDEopV>X{i@DF zun^um5Qg)^5*zP_^Da^f2}^L)nX0Hg+7lMv^KC*BMkhr2rPG3dWH8~X+^>$QADX?P*N1{atNe`YB=AWtU#@iK{omQp4UQM65U$)&kw=F5KWf zHSCYm!J2WNqI3UIuV(SUs;d!iYQOb>}KT-9aXv+%C345GM zkkPQIW3h@lxLY!5^t;A65^lz$w954T4p<#b?F^|?@@jnGUGu;oJ3_$qxY&FX@0z9oSXNI!|3~ggWpY%v>9p%FWzt0lBqMR(U^G zh<3A)=N|vjKhu=kj@CI%xNOiU(7VIdvgvNIDT+6;<@;AmL$%4Z1**|iNQi~vRFcvR zHEz?3)OPcx_8P){xO{wG!W(R!jzH^u$eLni*X$DS3>ZRH4jF}4V% zq}e4$!6avl2QFKW&ae`KSe}BrP;b{ag7iiStyJJ_aZ#}w4<+27osh#>H#WQD61J<} zksyE(OD||@c7lCf%1$QVF40XKJTeZ;)U($L%dI0Kl-2j-p)U`D-8x{OL);t?>*KXZ z!(&H{jxM&u--8!ZJXJML-7?R@Jg*1~aTmSc3h5>JCX%npmFYQH%RT=kMGL-41~K-- z())BR2|x)vq&Ah`On6}HS5^sFNy&*6pB?uNe3~pZXQs|!dH%^fByxa?Q_Ur@mMva4 zw70pz2f_Ix`5Udezt=6q^~LNp1of8MP$(0G~y(vl7JSrjH)2^Dad0h{SM6rO8mzQ zY(&nEQk*YhFd-km&UoeZQ^AL=QWZ6MhGWrZTk$im#d7zMP$E`rz^=bMeaMU6$oe3O z(-2=6rj!Sn`StZhXF*TM(7aofsGhY6sGaWCoN0RF*p5WK@g7Bpxe8hO>M?=d=Q91Z zt3awM0+Y1mo#)RjQX{^nV%}`e;lygQfzF&4k4ifc#%rD--Y8-w5$mC-*W!UBS;h~( z`13otZnIK|w(I>Tifgfh8M@RGv6Y{coo}47FhIFysXvYK_(_ z*EA%n#=>oKPNjjAD;pnaX-K;7ffsjdj>Z zXGyGEsFDTJcQiC)Oym7F;m~#8U1Ypt&mgRO(_DSbD4=brA}lz$D>|Yl`_X1yTX^+EXC@JmWF zrs`+)5=%h?$aL@ig7)lz=6X`jv*(_00yi8smbk{L-nGv<;rSz8{CfiD!L6Ne712$1h`g%kiJ9p=^XTadewYi6A9hBC z3>AG-!5p~VoED!8a`-Xqk!vbze$8pR*uqcjn0tnU8q5u!$p?*uA@#^?dy6slii^fP zy$0q1gV5QC@5tTi?y8T5EfNxRN-NTT4Ld2K+*UKkSL1oZ%sA_PT90TWqDO&l_v5D4 zhB}j$0eePg*ib2d;q^c=Ui-Rc?IcbD46dy6>=W^Rmd9 zaZI*NYYczr-qQAgNZMp#QLU55Msw6-kZIn2mr@MXH*@9cE!u*XTl#p5 z;4*lQjh&$iSv!8kDgx1N!kCF1`O}gFp>nTnYiR=5oFI71u|H)Yjv(>1>Gy8cj8kaU zBgwY+uL>m;;FBj^Sy|8J`S4e3BgvR4jb+UdeKVHFQ%8n|$DfKjnpk|!|RBq<#kE1H6ljPah-Ff_uaO3zD`~XWWg^XYMuf+^+_bWYFk9~gC z<>wjlD{mY}&lSxY)oex7M4x}ErTKve?j&JiA{&^x{}vUDsg*avRsGKIRg;VQpT7cbi+#pl_F(T9Df@f2ey)*e>+XzTk3A4 z@jxW9C1JGrhANM^D3bt)!FWdE4)r+ap(Yo(kev5cK!d^A$&oN&0A6D7^YsTh)Wgi! z2}vl!JDW5A#Du>-g%b-XlEQsZQ^YTljIruA;+jzS-%~*L{qiOuZK-UY@;t5TPk?0BVTL;J@3=dDd99wy$70GetPk7 znA7LN92a?dQ3fE&FwARyT}n3YsL(nc77Kxe ze~BKg4ql(Kh0H@hRj$wC153MoK&};8S8Ge&?^5iLZ1!cQ7QsK4)PDU&0Gp9+lWLWq z6=w+hs}5$kD@ALcphtkD{2x44EB1m4#H@Hj97fY9qkop?B6ZW*hvfc2 z9@EZ6i^D|Q?jMTp>l}+bda{$$k2?U%j%p;T$aYE^BB?>%RO3dN0v4Y&WFjg|>?6rs!7F7NB`BEZp6;QYfBTyY>3BmfFu9f${*?aga{!!H2iz-@fllhC-aoGuUdv`-oh-8APUw%a2duEP6gih& z#t~wC0diBCQd3q&;Y24HKSU=wWI^l;Z1b?`x#J2dYv%1@=cX{ zwE>|2?8v9k)q;^V?StGgB$M-hKg3Gv+DX#Z--=r-hz59&~ zV?4E8q#wMbk)56-*DLX`%WvgzUDHeejGi*=y}n-=PBR zCU}%9o-n3$&nSpn-onW2X>sb`1Xxp#&I12lsdsD}D(OHm_*^@@`g$D+R{HfxZ;(fX zxO2aiO zRF0{ee#YdX3M(0Z2l=BPh=3IZNz1>rFvi*Gw4H$NCg(1-9(F822_PaD0T5{%6Gv>w zZSDM&i9jE^Ki(5h@m`)ab?cny?ii|rk>x0(jT;7KNtjBEshF;#sqYM{OgA|E;>?MU z&?11J^TuCi;}WCI@wDc?;TmmN#MESVftNYsd8U~?_3jf%{L^W2;p#Li*&EiVeY9B#&-=q3mhVPGn@51Xw?ui`ypm%GwIj-61>hDGSx z?s!b*xS6?mFkBUg6G7hClWjr#A$;zA1VF9}i?>O`^DYG?gS$vbf???GxC-i7O>D-F z$^xfUt#KmHE&~RZTr86v9~dmCb`~y&u9ouWP-czOVppSAZ;`yb2eK_|T)e#8i5;xQ z;*?wXcOGZr;iP8++2%~>v~&OcYKAW-meBYs3isL5ejV#6vWJj2AUm(Y@x*tk-!mDC zI7c!IF+LY(az{NfS&Ooe9O@iu*OyyLErNe!^tKE!?e2hZs<8KDbS?uyDnPte(<(M6 zOXJL5J#fK6<9P_(9>x7b+V;IXA3G73H#4sRU4kvSk1czEAY zl8-wC37vdOK8QI2(BZ9TL6k^d7XEd@X-aOS7v0?^;u^!H7MB?!D}#4*%ftv$YoIAKR7PSW(bvt4^YTSM&o2zEqc3!iK3sMF7&?2cOGCJ2Z9tUnrPC(j410Zu*g`RL#U4PDYs*paDMr$=x@*GD= z?|ilb>SR=Xe11)7!FdscPP*so2I0X)2Zj5HK68fNNB1!HCxj&x=q8IO_sF0M7%lRF z#kKk3RRt7Ts`A=%Z3t1Rp+JS3I`fDwxxvELx4BDGvi?e3#S)wM>`t+MHT ztt48tE+3wk&-94KNp?!mzLf0ylu2-<)opE-QCZ!AjSakuX~d5 zBc(&jT^HvpByN$ywx$5ADm2)CnZMGuO1lU`b_B5??IA!-cL)bZu!IoG&Llqv<0L^a z&Gn;`(`_{z$+T2b|GcA z2J^i0AP^di#7-Qgzl6|A1xx7;dA}itV8vnYZM$POelIZ@F`mF?2Ru#Hcv%i^D!Im} z>Vm$cMBs!lV?*c3ReY0cczWvN94daz+I7ISZs!s`PW0PT6MbZXqr4rGWmZD`l5B=% zUP&OmQy~l75{c8QrVqFR3l)V;jjVpov=GAdNEIu9j;kco5_T(vC(GkFgaeXzO^Ntf z?VgU?@g(2;p3jyK0fMG4nnTVww};{fGy`roin%&Mld_F(1oq}U;49|+EJNwyfL#?f z=-{7|6&^r9!*QSqXy0a)n6yJ^%t99Y<0u&ajLOM^C{sL!2`X;Jd_Lik$PK+VA%OF> zGN{#NY{396;p@8cSleTW#~9vI+$A8C%hAtJf5OPJwKa~Y4`1?46NslNCQMz`6>ovG zlSe94n&GoszY^`GE{P1O=@$~B(~%sK*+M-90bgNYT8AO6`PXp>4F|UnZK?cG=SZQZ zB|mk!Z3$HpK3rXsrTnZqgB2e}fM<=r*phjMw;Z#r!zfmFbj|5voC_90OglRh+0RGr zXGyIGVHJ)5LAO;kZ$mkvND!6+(dx?-klMNqxVZ0%43K+9jEkg#UFI;%D}y7%55Snp z%DzvB;vJdC^&^!;s} zQaN>1@5zoCE`qHr)Z=&*I5tcEMPFX}meO}%oiQPBN4Vc~CVZyAQ49l%bn7Rh`ePzcjut{p9uYN28S zIP2LGV9xpB-<1upJ%JtNOt3POuk6$GhnDpt7Y;bKbJ8Zc^)DQkUrSaz>hIT_;0F!M zJxqEu7{y|-0`=6mNeK8CkLXN3=%RMKie3)kxA_9dv#s}2dfa=W+Y}p1mXLhtopair zYgRKDAzp<7JqvSL;7#u}*RQ1$wN&--;ajrC!FzGZZInUR>xuqJ{NxbJ!_c$8;91Pn zn)rC{DTf8}j&=_J&1n71?=+H-Enl$pJ!s?Y%B<5grC)E%4V>3%dGW=s4+SEUv}2BP z4GEHMj#eOqlGDP2nUaG8#{sbc5^F5yD#IeQe{O9CeQo5eW|_sj?WV)9JY$Ft%7@Cn zQRQR$@>Q)d>A~m|Lml&U5`s4Y-l*Y*6k6Cg53E8M!CRE|2(y&A7V83r|ezj)v86Ye8))(GqK$& zrC_xheRWYz=P7`4W+vY{Oaq`n6566JOi80=-b`npk=0-ecyBKvQ>hUVVSxCN2wlgl zurtmjL*(j&yFN&F>GmJXE@7Z!s6&}?FHbnV03B5NYkBGL!LRwB4t4*t;SpJ3xL=fB zObz~8yQ^|7Gb(W(qN#khxI+2^OTbepF_O(!}NA#X9@4xuNYQdoAY*?)2#y5m_v&I-HgBz%78vOxXG8!eh(lKA7$Xt$inrv8iIy_2r zt;>oku3UneWbujHlb_}DuO_y%12*I$gQLW1QNmrF&$}(!gv(RME6HkL&$WHCwrKV5 zYTO*eDA}S~--m=w21#=_&M6T$A1Y9j`Aj8+#JwP@yp#+=>)V^!q*6nq1}(gM2|oSm!CbHa1smh;lFoZquq$BJ9*CP8nD` zVKWGP!AiMDh{HA`l1P%UObM}{^;&78vvXB!^Im^#<~K>7X;n5dACV0q=O( zZXBCJC*hw9NU-poH{m>L?z>?f@~MvuK~Uo1%2T; zS2rz4u;--#r)U;OGxJCsQazF?zb|K`@FjbAz+R)g2UTs`5= z%S>+345l5r0&aJOF`zT;?ip*Pbd_XQ8H!0olBm#_f=fy+O94*GFL+5hZ&L-L-BKa= zDY0kMnKombAtWioeEHR>;$THyBE&H={cr^9t*x{RVn({ZafA8)1HtDZK)FOuZ)KthM#|T=baW$ zL!za2I;`yu_&6Ig?W%z|6|l#cY#Ox*X=&jL9ai6HteF5@_&*OopyQTKbx&;>#AqJv zEl4EaKC{r2DN2zs`@uLIvhu2S43haZA+62c(-q!EDkyOEE-iMr8@|%GNGr?9JR{%~ zr?+muFNdg7DD(w_;oJajgd@ge83i>?aeYzuB$ZQ0r4?hQv{;6bDxA?1{1bF@UF>cI zWuGQHzYks8+NwGN#e?dP#&%ivajDQbAUXY~f++ugSTll|XANzC>+oFe@h>>520YE@ zNNly-9!+HM;vkU8k1v}I=Cs?B8*vT$%9Ccx(x+u){(Y{(vA=EDcot0BaE2x3WadIY z%t5YLV;M%=fsgw`rEtPYp$&A3pM}_`WMPuXoDPRo&yzP3!hOvnZE5kN4az zcrv>6xArtMb}t*zu;m9?_U#AhKh>>G^rDC}z!eCAyPI+6`>2DubybF4;9RkPZ7z*l zYwgNT)8}5j6Z0rw|JS8qB*qE$#pjjhsJ5LP=DwIe6C`+x8+0emjnS-Pf`PsmG>4a3uAP~keq zWr=DVI1ejvr5w#I0Po|JY^XP|UXwJ__=tQN6PH}`?TRywFPq_{x8o9K7JW!=D>EJO zGV$Z>*t7_6VbVD+p~H)kSyW~S%-<^Rrv)%Vl_~4dkoE|)5!0j{w_XpTG)RlIKSxTq zGkv^Gz1;%k>bZWkSbqrJ>1z~k+iJh!PPZ2NCy3cbg?`j(=ms_W*-=KRhAP<%F`fj- z)sV)!XB*cxMo1Gmd{%<<7s`24S=25G;y-s7SHlePw4UROP|;iI?jPHg?2Bf6a_IIA zY*E@~DJ*aN18(?8ix9$ zG4>AK*-4@)mwxt1Fv}K+=Ps-g6uCbG#hl*+HF4)oli}0!WiE}nE*HU^l5k5$I&|&J z@6r+@P&bl5_^vdko}*P!tafV>EIiF{cpD6VXmeh(xoStCyHdmnEX1|f5pt3K{Ubnkh`(?uW; z*cTab75CH$!K0qrncn%&NFM;Nsv(*`I6Tl7s@n+r09#_yF*DK&Ar`rte3zl^O4Sf; ztGW1Ri(4dT)a!|Ia94W|_t<5=y)HlM+ zE^rH11|eI^);0WY;+8+FfAv-8T%hCFpSp#m=AL!cnIC3k>R4BLAdR0OQGWn64yy&J z1TDuO7n%OMc7sDagXB@Fz4$62$`)FV^1T!1gB=42{07Eb@rK6=78bfvW-+T>Bcm1x zxBvm8PzaH3>pKa+XXivp9BX?@MT60CGFko&F2WYCv+E zGT=05-m%3}=>&XP6mkF9AnLfsP5DS`3D}{m9J~(T-U#YzvR6=F-X&NoqZrRNhv5%TB(j=bsnDn8NYGfBRaF7;o zw-VF1i>+2u^&L<-y5pL!ez3uJSKrf4HbB^o>R^53ulTmHsb`u=YTI>y0sKD>nf|uj2W+;)*C=q>E6l$0)API z-5dx_1E3&l4;R%jG(HZ)`^Kv>Z40`jbEtv%vQ^YC7`!}{wc+_rQV;#XksEQJ1RI6U zO~w44ttGBl5yYNvb<@t?PEPwnp4&@CI7TQX(KH!sjs4H@Bk~T}wh|>hJMo9y7K@}c89h;qcR=QSAdubT zTcnYs!6S#)@mA4(&Z%zKCq}y#M_?K+IN_o)5l`o+4SRPFGSkX4?xlUN4h2^N^9;7$ zT5P7)IR35>sSAb=KJem~!R$HP;5um5Y4rNs$os!20N3%6HXoe06PcFCc_ z4GTO8vH|(_O|l(Ql5Rd{*5K}Fc?P8bmmS72^ED0d)GgHlq~1x})BS@!zPM546yr2Q za+35f<7_yt*3vNMuY7?m?Pb3CJ;_mX2x8{QJTl&s`50eqV$hC=N z9-8zw2Dk~00296TE{sEKnL+rqUe%F^qi9Z7Qg9=HJ1pS97 z$U;_p{4(*tL#aP0u|lbfF3l{%aAlU&0HUq0UuD7)zZl}@SvE{PTvu)X>pE3k7e=Xn zcVPGFv(jdRmpvhN^vTnOb_%4sL%;Cbt#O#X7Z2|@&fm4?^j{SB5DI%<3&Da?+Z96A zV!2?e0?eq#M(AZOU}9=!0*UYryF!D)ac&Y|N?LKyKxm4f%D3iuvV;KzCv6sbP%XH1d?5Gj91zq?HP4ZKJINDk z#9(=M?nUd3xcUaW9&1PWfG|5OW$rAafo^3+DXAk@Rxv$(XU#*^M?wRZLO*qQ;=O() zGsuvE-`fni5enkQjb-USPCw<(I#7rL11UVy?u%IZOiQOm1@-Sb84`|{z}u3;7~T#& zf)!#RiEE_%;AK=(7|bGxz#MGfC?HiE?YMQk1MSnPp#|k!J|J85<*^>D zw!8tVsy1;*xsyP*^T3+Ak7J>%*owl$CoLO!mkL5j4Y7js7Pe6bayLnj^o)=E;%{_U zMs?-x9<#pLUkd@+NfCo#zqsJlrpfTF_WY4?Qg9 z;4E|20Zegc+E3?O{x@|3=YLTrFmZCRz%a;~*;}|;G6R^HnVA0f^#4>RFtIRmF#-NF z{@?0^n1AX7y!95k$WE}A*?-~$8%Ga^{Dk4Hesv!$Pv;H-WCEM8ssI5CRIyhlddi&5jJs&CDbU3+I8_*MWbS zNR+IAbMyoe48H@wB{@Om^bG70OKWPKA`uJ&|7PI_#(?$?Pt6Pu%#6brT9_Sup7E@vb34v&lsylQX@P7<8LF?0M! zfS^|$^jwQSC3gjMj&KafuUrZE_xIf7?&fxAVRUzUYslX0VdU=Ef>LS%<{7A44Qwrl zncv7W3v%mY7?@bWcY8CIo=^^ivkXY-=lp7DN{~9k_A~ zj}E| zNSMCq9X}OT2?g=UdN zkz*YmLL?`BQXDS*dK@tacLjH>Z)mu`bpi>L2g)yNXPdaW$I*}N{g(sSGgXWF`o_u4 z2|{b|8|XcVHmEir-d9(4D+ox#f+Ig~rU(BgCVq7l2m|1v5r{nt11A2i^0frl^oiS} z-_0_Lnm_aYhmRfT;wJCMm)SQZEfjQh`a+*u?3(@E$;5zR)Zz~`4(}Rxe zx5gX@a8m%Qeed{?_4j+!)sNO$K*{G1^ruJ4PuB1c2ay#APiN0&Q^4DgfW3-Oe9nph zaBZfWi{DaD;lKq(;EzW+`|VAR8klzA=H*YT#`Myo8{%NEy8928czhJ=D5_-vh%;O3 zw+?N<23r6_20j#=s*@w|m%kd2tZh}*&%{fI)^STM!|#bo;vZ*V1I&{i9qFJcd|H18 zEFMgb-o>@GMc9ZZHOWg|T_D1i6}2WH@9z>LAXt{wz9%;DTkc%K-uXW4vzHiW7hugn z|EzCuULcGJfpE-T;y1#<0T{!C?~qj>TIK*G$Uw1cf$$gfiXWkDAdHwFK=%qlX~3)v zWTQYhVz2Qx;ow{5%X{GJPsFz$KP|>ja4lY7!0NZSynQXqJ8Cb2Vf`nj?~&OP!|QtQ zyF%wmNZqq@lfU2Px9Hz>!GEVW?S8-w#(p~2XnZ~d;;&LJdZfE*c%ugL%xmjwcc6Zp zdzjrm503rCYCHFCYmL_Q*SLRRyOmwuFny;SzYu-VVWTR45AcjfV+R?GO>vm#O-*gw}px#nqSu2_*mFFAFow-NCt)kjV;7b^j zv}o?p8Q<+UjGsZphhl?6E<|cRkF@pR=X}2e(-3+cc$rj2?dp6Wrb0E`@r0FlXNyzw zPae=+SJ|O4@`dnLe-5jXZC)j$_{OW2ptY^x>&&S^jsoUAsiN@sR(ZiS8JvNs{6-2v z+LPymXU6Z1dwJ(!(4`?@S=af9s)%yBmn3LlBtNbE5q?uPaX|O3nq1AJVD39~m9gHW zVAi-%_Oz|0-08;8$x&FExmQNkYY{Y@8Wo{;lPuT5Kp_)$Fv+8rVDOU6b8^P$Vx%e$ z(M7p&$Ldr;^l*i+iOK49GqAAFdOj;ru60n%mJkftPAmz4%`BfImT|8ZCp@@ah7+IC zpir;ZS$~_AEtcf=25GHw#^nn}P-hz**5DmEJf1o1>JjZAv|ZRR%G1w0;f#K~l55vo zMa2>-RcdYmgS}euC`FefWO&b;Dn2sDba!kj2gKpvvR@MrEgUUg zdBFPsw!{$#?M*bS)Vso$meB5xjgyJT`zZ!@nuWw{<=gkheYX$ObO)kWljEWTO5qv0 zXKUU(nU;KZm${Q7Pq^cy8zlhxT1l~^n$x3 z95v2I>j;f{aG^Ax^S5?GcOyD20Jmyy$(~Fs?<5JEZ~I_df-PkVF`_XxrR# zBf3vY$f0(y-m`V+9bkG`R8k#jO~c1MV`iz?*6NTRKIb`~)N;d5xf5Q7(<*UNN`Fa9 zV1MX2w=q5@zNE~ix#NZ7WhRzT83Bcv|BkijIQWywSF&CJ%65Iguulmarp?pQ44*P(FXdHZ``w6Kk)b z8{G2t9G(INWT0{dZ!7#2!5$SB7~R!+qb$snipd&)W-I1kRY<$j9T&thtK}9A85-$& zlZ%C{Sxxpx6KBS>PR&;R-F#?U$oCPu=QwPA*2C@dyJ@bWg+f*%# z6?vK%k@zvS_@cEt!l2f|DyoFu3_|=})TmRDvA2cmd;6pJ;OKM@<;Z5Qui5VHbCtXv zq~r5!@*L`mNVKg6adnL}Qz=APp-!K|=~Y*QGq$4apXex)Ja+WELda?EFYeUdE(%=$^HK;byNG5KOfY|8e_6QZdU%FXq zzw-9abTob`(_m6?z|J{S5{e+jJg^>lP@R5yjak@~Nt0Ptl7SZ)!)+fPx>SWg$~TA` zm3&y+kKfsFqJ#YX=kA8&)I8=x#ro5}U(+2-=Ud=Vzxj6QEo!735kaY6yYySWX{yFT%p%R(@6X$P5IFKM5^(D2-X@q~0KxD0RvI4P9xXv3oAU#W%d!J^*h z2-7Sh4%0fhPH|bff~T#a(BjLdTrGtb=fg>Noy92b;^K};{u9-*^1g*RjTgOXY@%~v zH775(p?2MK1d(&oRL85n7u1|hJa54*fAwzNK&;ewiyCOD$n3JQttT2@^>n+~T!I{7 zJ2UAxqoU^ryHy@(i0TVwH3D-F zGwQ2%L^&PZVJlbA)xacL+vRMs6eExdEAJC^y+<826TtXkT}gD3`OA0aJE zto&YXk7hmuB4M0 z>H7O-^p87STMotKNOQ!Fi9D}Fy@TC#cgUuyIDa397_?Kx(+$IPbI8=7I}!HJt7V$U z&tUy)2E;ior7!->c!;MAzYO(~+za<-Q9*?xRVVs^u#0mbBQf+ZKB;MGN)e#yq&h)kkdyLX`8nJ72c&WE>V*N&! zOexPCETfEm9R4i3#0v{K)=xk;>b)3Gq~ZcX+^BOp1G5+W?*94=bGK;on~bi`wg(=C zJWFYL$0jExOar^U)a6~v1vqKhG=(_lx2etHI9AHWZo3uxI25}D<7H%){FK8%M>q*dl;= zI*KwWdS-icPMWC)qIGsv@Wh4YHun!DqJN_Un_8K03d#ZWtD)0s+V+hWC&RO;KWjGE z9G8mfXSq$iG_LeaUcd#Cg%OIDE^Vo2tuY1;?lc&^TqI|?OQ;lku_aX$PJLq`K^~~O z>0Drdi%?r8#4BS(DoFntTMOsp=lgm!e68GVmpm! ziO=<}s{4HOq^e6zR;F`ndZYQbX2&Qt3jcDZy419bkQ%Hj#wj6Z(kx$gW_%bUeD(9} zSujn}aVCEMg+=Hh&h`B3>-eziB&HJ-soEW$twQcFj3{s;k_WbGtZU?d7+4pw#&A7_ zEiFg~V!n-~A&_83Q-yg=AZ+wqF4Q2+^pk842TJB%JMc9!8GgKXV4|uQ@-;1(vhjqT z-;dSezotVDvE^!%;dVOemXg)-CnRh~yiHsG3~6lNbyvHw0kXGk1@lRW(_GvJNBc)A zpQeAM7IWD*VsHD=+iJE73hjNK4v!IZtO3a5K((tfbGx0+MonY!f6CDbNYUaah+iaZ z5i~q`QEO;}7nK%_REHioL^|>x47rdq>r!}kx0+6+K&wa#+(!55SW-8hk7%T0ax(Mu zbT5ai)Zt>scDj&O!(MM%mL^B{W|1(ddwT$K?Y1HbBPe2KC2$d}NF17+THx09+_xRu zV18&ZcF0AyyQeE}#PO%ZzQ2T4Zo@$1luu`rT#;fWF8x*=Seek8WJ29BCd#`%$UXzX z4@T|o^T-pAI@}=KKhGBIGo5pb5B2y-q@2~?O)S<_ROP{d1oa1wS4-H|RZ5f{7V$<; zPn--{@ia=Kb8ED%l|4i$1Sh|&{&KxA<1!`dcDK>6D#~6A7UXv-0xX^aA;WdWsFGK> z-(HaOSV-ndEQ4?gEvI6z-6O7#+nLh1w(5{RXMAKBhEz1oN8{2x>zS- zEVGn*otkkOQ19A(^)}EjY~u=)1W$msdyYlSE*?&ncb{J}&+|9ri+(zlv#km`iwKOW zTU~bVeHW8a!P7o7`LM+U_CMmL@k-mOiX;Y19q3vUC0>j=3zu9fnw@-`!Z85Wd)>G_ z`RWCBa4D^IrlwX|B;W@{&q*oG> z(nP_9!cCYv1fyUtp8I+7mI9{^E}5BG(SR%YDmD;6jJL;o%p3e);28V6C&|weeMeVd zbv!B6!{8eNazZv=`x(ad%n}yFcXOM3>sEob80h?7^pePSpUFZ(_$86(+B_7z@~UG9 z+7TbL?G)@xA^L}~w%SIeH`Ni#qAwCkbPc=q<(RTH=qHPn>Xx)|rBmAXG`YBAP5xu4%eqxtbQ&(ReC!QaV2o?y>%o{aUXXbp?TF+PYCl!=7 zM`|T}4zU>Qf`aQ!kok$u;Q1BpYzD*$Ho`Dl5aF8!J8Li;mpfpi>2i!r45vQ*{>Hi= zWiaO=Qr!O~Y!3rw-~OtJAj4!}F|d~T{_&LJq3hhKs(bYVC6@%j&kRtq+Urp$U6@fX zv6{h=>L$Wd=|Oa9^Hf481UoIp+gP`!Iyj`6JJ+a^ZN|$q@;7fiRsyv0H*|7E0|L57jC8>ln|41xL zY2ON@t*EwfbgxUS1!YyiNUe$V@h$ZeFeMb6j)GZuO$6)ym}G0n7uF-t@z}A>)JzKx zT{Vh+fRxY?YoYF=0*HlZN9e>&2DafZI;-^6@0%@<5?;IHrD;M#PSKPBllQg$?lWV~ zQ15T6A7c)%KBVm>6CUNbyF$~`WYe%x5=R6hyf^wH=NO|V*;E>(@SVo;qm6RYcb86o zR%y&~pV7@|b%-4{eP~I|-gnO-`|_5ee38I=m3km-o)8blZnxG|xt1kpe(a1q-9aI~ zp`Tw1ZjRh33M3YFj|@2)q8osLzK@k$+!pBz@pU()%H*m}uo?isMpT7;btZWFWMJ%L zA`W<$)`>Y-efb~n3W#6rSs(UW0cgw*!~QI?f@NiMPD@~9c#gdDE*u_;dl!o4>@u2C zkofhZev+Mbq)(P5cd;_I+fz`;D7T#_a!|VNgNWAVZD#)J>qMY5OUkSHQyiyLbyKN2 zJ7bL-=~BSa+JW+Q?BHN?rccz@$;}jrjuRU>Uba_Gk!kn~nVAbjk3bu0-^sSp+(8aj zU9H@H--_1lQo?Sa8R<)?%$)Pqn69D9f$*48_->(*G$aLi*hFEluk(zz%nn@0enL)4 z7bEAG!gRrkce^gt9bKL_1L1|2QK#%8n5=i^XxWCE;UoRIlaNqn(FxJ!Cw4;F{19m~ z2G@3Rn`}GIJ8cdHTeVg)M430j#VcI6191N2?=wV6O`Lw!KgR!R3yM|W9W;}4!W)Z1 z2qS|w&NOj2#G_eT!&KwE_<19JY0w5Pyl;cFrPgvY;X9F^fwFUxAXW7XpI9 z?cREKMcX-KyVn}Y7&?Lp)6cFW`K2vJ5@WHB(`sNy!_ZV;5uiHTr@Sf00I_T_LeI;H zwx<+J(Qp$K-AFz3@OR5dUN#(_3_%=z3i}x}#N32OB+KYbg#23D+5sFI@uklDpq^9E(fk?$izEJfg$m zE=Fkxe{PS)=je3jj$iz&H`%H)I;K~ABK*T|OvIK}`m>?s z{^~VyBPsAwrxfa^rf+st>gK&GlY{UmjR+ zPPRf2pkCwh041JhXCKLwsg?z5;g7xgUR#8w_(X#L~=dyQ@2ZDhxh|sYj=r;~Qr2TL^ zi#SZIPjdTkaWiX`aJe%#VG< zFSVV|JMl+ji8!a=Hn^ILxCO)f!q8Om_itzMrvVxVtA8;~EEHktIf-|if5#t-CwE9M z3mAzrWaciYD8r%Fiq+<-LT&{9sk1K9T36d?EKpu zslHp)cRUn;@$)WYkk-`2^8|AT3Y|1YB5td#YCXTEilU{(mE>@gl9^h_!choL7AChT z*DOI7UzguVex05gx%TVr9dD^w0DKJW$Cehr9Prb@1w7ee11|{aGvg2W=g1CBIq>Gv zqi!Ynq98Y||BjE}o3e9`CT6>EP1rM2;>4`WGG!9+)-V3+bWmr8U!Oaq&qoI)~A7X|m2q2+R&z>KU zlr%F!$r`f1L4U?i)pszMiN|-@IWAT~B7S(W-(~d}?-d5IrLKNntJE_}=FU3Ux~g7Y zM9agYP0`bGB_orqcte(-TY(yv)W|a_nA2k*%Z~pZ*X8B5Ojvsb(f~0St>v+%u*BA<3*Lc)IFOdAY=PK9TMLBU1eY=p$*Wr~MC3 zO!`Wam`+vG!7~+o@oknvWL+DPo*$k`XNRpvec3aZF z4tzE9GD|u5_IWtqbYv=FlAszN*y9~!oG_O z5IY}=X00^){!DQq;4L5}L=>$?xbqQi`4I|-6XDl4Q^rW&cJsW`KS^)Y){0UGO5&Y; zZJ0?Q*NZW!OjGU`pX>(h5zeVW!sI&o=ID&N z+UfZCd=&fVnpq@|{uz^Trvs@+b zgI#2QRy37LI9_JM$`^)ta{QePht|`gp&-n{elo9CGs81t0XClv~6yUD&G9F zoV2wrht&)J1A)7by_23et^{=h0Zx|;QKVo}gVH4q{=^ZB6>R$&BK-92kmdgR@7_o` z;v)qkDPgqJYJsIX0a;T3K7a`Vt%=Hyjh@HnXJ`hpp_w6^RoHB6XW|i5wbS|0_n3<2 zbfB*GSg*YNws1M30D16tjC|k*De8xW&Bu+xm4OveCm9Jwb^(A;X4d$cE`%{IRszy| z*wV8W#3s+L`CtO@1*xFN9)L9xiQw4OE5Oe8377{51*zO$Oecm$srHE#d*r{L6g4p$4^Rnmq`D21eI1Wx=q6sf7-;BU(g=8H=4ThnoJNGC_JFmyLnRtulh7HZ`{f>c z2dCll+GNr}Yo*xEo$4F&P#~*MsI<*ns08z(zUvr+NaZ{bNdy$dX8#lN5Wd zQ>o@h5bk|!32?2z)fe0gT{9LoVhl2x&o$r}&7)%bb~is|%6xLf^HW++Qm!;o^Bzgr zAz%;TC6tIh{D+AbIfw+Me^Rb8CJALd#-IMG2d|&$XBqdTN*AAu#j1?APKcrw?S|p* z8`x>fpMdtYvOs#i^gGZyeVi23i{S2f6OE4(p{8-Grbi9?g{7TWIND9PWwS0y(}z<- zXv2MlNsAvVpFupxtr;{E((CszZfZ_>c<*Te)!;Q3 zX^8et zYRZk53z!Q8il*gw9=bOE#=Vfo+dF^UZdOY7l1aBPa&KNy7yV(LhMECO>3EJu7EDs( zKH8lyG6WqPgaKx*8-ABf0gCC8r7*VksQo-kS_lQQU{|C@UvI#rZ+JDY6YtdC2%K^P#*um&t+AM9!=BJtFyi#fS^0g_x(9ctn*XwiMYmKgsK1V57L{*Q^K*x7S zo%vEND4!i870O^!UYR=|C#AMMwwR_6U>ggDCW;D8r#&)IC&Ma7Q;yF11LDEfeBu z04D&poZzgm!!a~_vx>N6Vj3?QllEBD?fxn!fkh@D+f2#1Lc6}~u7z9b%fFvUz4d*s zO6&%>GGi1T@*|BoV92m}rXG3QhDhPI-Ycb91by5f-}N8mIJBzu+rRuR&x`X>G?NcT zq43ZXUXM7zn^leEx6+}%85GQe0J1NR{rmhwsHxIw|5n6T;&N63&>F92hXxJKiC)6f z^#T1{DWPVqUe3t$fI+nHQzNl3J!Csj8w4?smHZ1(g>kn*wAw|I$U!ey-{BuRe5e%I21RFMn#)9hv+tfl&@1D#7O|=Qp{x2=B??4gu@0 zK5x~%;wJRSH9piB0-aUQ8!rvI7}e#7O$uC%u`czLO?a)%&>4DBO=RY59&DI^AYV@N zpJ&;Bx6GL%OYx^{4p%M5lVlItdlvY(bEtQH(pe~#!Vs(eqxD;)fW0V7ZWiS-Jdsb_ z)SMqeo@!^Iy)aY;!qR0_dA@x|Lsz1_YBTqGZuE-zfJrA0e*-D0cNDa z5wQ864OJuj9N&>2lw@gFOfIvEfc0I#z;I;#Y*)A3WnCtTO_njSa^{&J;_10wc+!3R zkYf5#np1AlV_ZJ#;APp#=cJr|PZXx)f3`M%-a9RHgR+59} z_EIS4-f}k+-Qkt>F@*)r-6L)lX{wV%^P8s^N!VIiF$5wan={>KqGSuJK(eVQcsCPG zpuVgD6!3{0mK6dx8K8u|zMwqKXKGrtS^2f8tnq-lr%ua9#)*$gUtcQg&ee6(-iqv! zz?B%M+(f=&xXu@j6EQi5x!LxEl_)TC!?8PRChnT*`-+jy7eK5tNbi@1PkeUETNbi$ zHoLyD$FdE*aakm>F>X;s%ui)l2VrF9{q+C`qr~H}NMD`I;7+5lH4}ki)bb$mn+I~m zoa)>|Rv;=$+A*n`T_dk1py~BX7z?*Wg>H<3GsU4dV|v709x?HpkJ}b8BdW+A3N1y7 zjE}FondPEZ{5O8lIMaiG>F1nYBjX1$wNRD+U%fr^_EF^DLTUE2&3(pY;ZK?Vv+w*- zElOlF0zrRrAn`qIp-G)0~QyLU?vg4)Jp^=f|QYI$KZmA-=+tPuaG{dN08;PE=4g z^Cy9lf8AC@M4M`bIJ0}0q0WSAC6AJjw@z0;Pz#iW(9*W72K?S=Im7s;W#~dlqAaya zoJYjN2lgV?&-<0fBF9>lD$;cHDNgIxrD>EKGC>|=a*yN!qu3v%N@-4rwzB@8_c79Lpfc4oTYR3o|fQoIZQdGS3OlzZRv9 z!(d}HSPvw$=;N0cy6nv-9rPh25dv$+&q`o^+m>on05xEnY8Ai7E`JF*F_0zepts3h z+|e?mlbtY;z>iGceAr)#?Lv(REwzOHmzg)hxwJyOjD4W7-#QXBM=INfb>)@Mh8ofB zTekHvr8tbT{yvq}0wh98;e8t-27vT;<$juK1y=uBZ5^>PNaL?omLs_!Q!N`D0c5cI zrtmRtB0J~Zw8utXz-@@BC$Q*YN+^_~?_D2S64An}Za2v!u}-A};-C{E7zx%S+}djl zbdec}3%-$5&4L*F#85jGOo`Ub z$iyJOQS^Ip6v4kd$y|&;za`4|H`w}K7PioSkY9o<%G4dXpLHkv9&LGbd#w#u_Ryf_ zEt33Pf1Q!4ZY4aj%5+GxD6G$QQ5hh&ZD3OW+cHpsS2w#=o$SF~P43$f&m4}I1<(77 z5_JlH(@GDXn9O2)6NyJ?)f@w?ZK$Xq2+RluD~HETr)J^?iW1W#ieV2|P+g2&lj7!h zb0WTb+-_|nI-uukOo;!_DoL(2Inev}B<2dn`XP>=41!)TOo6ryqjHvdecR1y2m9Y` zC_0{{;;Pxw1z*LbbPkwgsc%;vdp3jl>Azk}>B9&nrL{Y^QcZ$i5NwTxX_|yWjX>S* zEYFfBfv@&2fssR^ywjqqeiHKHWOMZ`vr~55G+`DBFO(4E*#o&8F0jbkvkS)-CRxuF zUPf{z&3fe|YHl(por~KI3jgZIqeM1_@}j7|dJotk{u$oU?w!|`x-{oh#|?uA$(^z~*ChycyT7xZq7IbAVFVKzUukLftQ@2dALpK3Z+@eJhqb_lBt# zSb%<-+RHJVEY(W_RC|DwVQ_t8hvrm(8@$MGJ9zw8eQs{&GSOHaPlb?-Eq}!P`;k5EMhAh8!_gEURwRN=E9RcN9j4RJRNTB( zc!;W~KVJNXPZF{5oUa2t~N!koNj)%c{+8q2CJb6ref z9r*<_JLp$l>bI4VrUA%LFw}xpranAj+j#`SC#AUdynXpdqZUsZJXToJ(5TZVV+6eC zV*<}bz8<-=e#8qQ0JPrf%cEbv{&sJb|CdB|n2rujOuU|v)eR$TohNtEfc4Av@VQ{n1-Yfm;B&fXAlKd!xZOc)d*~9}fu-oUtb-Ip`h6)S7Lh8*yR*W2f269e>6IT5rhPFvzQR0e@~d=`TY!yZJZS*ItkDak_k; z_{=dWqEfp$2}43$R3S2F%>LDWpF4hu;4e_2=-idUh0XW&1wk%OGM)x*M2F7cgxC4~ zHi%fK|5|Ln+m|WDsy1QWyEt~e__LJ0|7&lQCm)5pSGQV(S9glJ4gpqrV~UGNq?vxJ>(=d zYGWhsDi-r7{kquJ02x{Iy1YuEurtoA9Pc*L5U<1^! z@*M8FQ~t$>JOZ9!- zQpdKQJE42yjMjgZvvOvBa7rXUXPoPsewNMxJ;C&wHl`^AXt?Eeio)D%k z=`oP3WNwt1J)=xdxdn>N6(6*aNB9Qc;Gnzgc2l|vbt zGKdvZOQcG$H1yf;(a*Qu`faY858dv_SYs@GqW)>L+kLeLV|)sa?EYS$qVXGYvl08mJd{c_$) z@pnPxsH`jrrtX29)3g(ZR?h<#>+m%=x=4`+;9Sv2qc0iVR+lkdHSvBq+xBTYj0&?o zme4&Pf3*9FSiik;G*R0f{Lih+Ld4|oov~J2{szNpzn=##jbObHGe6tY%88wx3&@Bp^t1=zr z=St9xTJF$sOvn|M{5~g^uh&zNR}7Fn*6NJ^ z;oj-%l);!{_tH?grlF6P1+xO90e>@y>zbl!GNzL<$d#{jjd+%E^U+UJdtyl04#f*x z<^nkOVL5)s>O$VYM+I~I@q}y_W7mh?l#ot?>ggst5TV|hk6>EnSgpm6Q?cvJ_aep6 zWpfg|Fq|{ZMG01SklFQ6$iJ)pYgAwTR&x8-4eox1SsB+^AI0}avbV^KMsDe39k2PO zi4g#Klvsf}agy`<`_#t_k|j95sS#T%qN-tslnpX??;+;ee2e!AHgR7`h9*x2N|^EL z>9fjQkouKvuw~DuFUOM$H+N7$DWm3bEPK+6&UN%7k?1S|-o@*)UjlZvfdAL&aXq#S zRGqs=(W5StDsx2_{bz3P+#NF`J$GNXdM{ln?e#2Gi41Bdk-D4Np3c_YExldLg zRL8EeNo_Nwy9h0=>IL=LRm#DLnev0q{!p5C#mHg?4p^3*{1Z%`JAtnDHvoY+2Et1Q zR#G?zmi5cs*Kv@{0Yx?N6Cs;#%1g}LHgNKk^Y4~_-Q1pW+pZBx=TJ_;U&^9WxXanl zU{Erb`a0=6^<%!XOc?xSTYW3h^k19+X_j2W5*{L96n*u%IA0A+?_~=!A{YB=cx@9s zv)J0ah*f*0Ju?A^hW+e?jxC(Jsbe;;ck+Rh6-VxBdOGzxN}>tKg?fAa!bbCuGd@mr_I6 z?d&1am^7UB_KzYrrvHWv2(U&N>tTrqnMgD$!g9Ev^$ybKri`uaM^5T12Drn3_Qij)%! zioTDn?H_t16O78*N05=h!}9VSu;jC(wzad~Fui?J<#%oaf#XK!4lR?;rHKLIW_EH2 z1PxNG%F6Wy1VG||gc=O(>&=IEYKHtV8#bH;=jjwQRP6gl8gYe8>E_wao7X5fQ8Q8s z&P@^Yj=}HxQjLyLK!E_a2?BzC!1}Ynf#=Pykz@j4AO(>jz&i~YCHww?Mnuc(H3}1- zC&;~~eQ>*INV_HA&oB_3*)i z1Q8Jt5m+EG5z-r*DOqrPLHDgeXTdrHbGG_Y19#v-Rj2TJ1Kfv$`haFzg4#ZGfDx3$l@wAnfKw%vnhMzSGIQwudp6l)m zyLl8gkfC0Je%~PKNaZC^5~YftX+*chI*Wz4AbH zWufr599=DGB(I1RCk_uPkpBF!j1qxMDyW76;pnetkOLz_llX9sZtkETZ=V}?J5V7> zsD{w>j^ODb)kKQX0jqhFhLr+$3wt~wyujl56jx3lf;|EO0@wm$6DSbPFYgqeaS!0* z6Xm04mUZ82cRT!2Qt1@EzjLy1d#8tBL7;ALL0&zS*UbGXQ^P1)u$aUjqH%YNR%l3C|k%@kZC3$~_hY zv9|kpVHeglCCW9FaSN{uoys$QTc~;P8NDP@tmB>pzyDANu5$?%{5kN+q=oG)%NjV6 zN(gA{RS0?5kr@}HGfeHFh>m(8>z!O%n}h{@BqgQS*AGNIS)kMo=KGmt1R4bnZRalm z%3Xf|)$Ge=^3OY+NCV10bXdp>M+8cK$Gvj`4TK3G@uvq;d?0*0TzH4P0}5OZAPJ(t zXbeCS0J8i>L;(V#`xfuvfzbYjbp{FC?b%CG3}V-hWmkBa5kOX8AMM#iZT}L8e~7p? z=u>ck`1J+LuXgsy@G5$A&+yuWTJsaEAlLS9k?!yt@zC4&`5p9o#Y(e{i$`EfB4Bc2 zLFo(f$LTGoFV_$@y2L9zRI%Jn?(`&!8rm80dCMsQJ4~-j)!h9b3B=xNz*&BiE?@>x z%VQw*7x#QvXD!vJ1I?hc`-RK0MkK~kYTmNzsmmv)oU3^wvYu0FQQ+=Qu&^Z#B_~)< z$9LvsdrX646rmowTO?sGBnej_)|;R&Mxr*`!p`6FQ!X@A%*cqx@_&h)z|>1rLcZC&wGDbUw>-%M3z^XhP=V}6@SS$g{ zTESXUIKneRfcvRm;(o(NY#%&tzaQ%_c`S0xU!Nh`g8|BDF)ks1RS)w!vYID3@Fbq4g78n7ki0F z6|pl>qzA!ECB+YIm&dG=X{ujXvcVl;YbDVBw)VN&QG}iA3e^v$?}gbuuNP$Sx!Ajx zwUsmBT}e9AAA!F=#rR@s@jcjzY#78AS&!M)<7TRhU!8K_``sdZXWJHUsi z@1e3>d0*VW#$s8;-!-Q_{F?q3IguZl*b@uR;8Lg$U*&Sg1H)fMIa zy6H5qy_mW(xCis=G``zx$oT#{jjE(jv3s|T?DJaf*uwhrSpnQif5-9i7*sLt15O>= zS;w<__|Lx^Qy*!o0J^dD{w)}#?_)cPo%KH$JBKY%v?V~6ZQHhO+qP}nwr$(CZQHh8 zb@~o^(1SPVuh?s6Mn<^Z;@Y%qVDRT3)cd_ynrQGJf>Unrn!OFXhMg+2pm0gcBa%TQ9_ zJElTW>QA;ind3lycTI&CCd)3%aA75Dxn4q?pF3+la`P!A@{I{&CKR@Pu|SW})|$2B zxN{&Nou`zet0s$z^sJk;(Ao9if%W2V>d~Pu;FJ$&ef27&CUcaNE4sbH0B2|HH>h~k zZ4^(;3v_$e@}F=!Xr!Kn-`{l17F1I~YpeVg1=R7yrr&DE(c|G}7lMRkEXIKusnjBW(ppX7%&yBcB*gQX$MvrWN*yR}tXOaRQLjnulq!>DiMy;ZV=YN&fiagY{ zR&tW7pGN=hZHoO6BJ2hE)hoZvoWLQSw4Pst9=U{t2)8a*Eljf;hl-uksjr9^-6^Tb z*gbfteSvv8Py1sb@jcesivsowiV+Ze@T#@N>--nkDTD~Xzk_^!rmkQN>IaE&iMXe# zibfJ_bIfH&pMD<2#Ps$WsL?I#M0&yrExA4-C!r|Hi`k`_TPIx%aPPXF2QbPl3`#o` z|LT^bt)#+FBin$T8uG@i=r!Y!gN8!B;6K~MSo2?ZXr%8Ay$V^B1NttqCOB$EqR;Wd z6~TVL-GULc((PC$o!p%}DRid5C`mQXkylZm@(x3_b5chd{ReXxpWY@X5;AZx8YL4V|Vrvj@Vpt-|xeCDH5vI%ruO%VoO_H zpw$OiJ4r>lEiiXBs84J_6*$AOwCdfVR1Kbx4-nMk^wRXl|IT1PXVo|DX1|V!vKpQ> zmx)&Dtu<4-_|GSxWG*2CiuPd7e55zuW7_mlB@{P`E(p6D?0MRiw|8%GrkRU%@H0nW zsh%)ZU8mZHF+#$M=hOGY8iPbkGNd&#R+ZCYo@zyJt~JhD)eh(U;XHiiSUjX(*7St! z*P>7HW?&`)j)Qib%qWPzvhygZ_xh}YKczRRHgRgd%3Dq3$Za?fxZ$SfD)lp}-pFZG zB?(f&d5w8bU{WT=JI9~WFWlh+f!|~+N>~7wBw}O(5Jhw(iFW%>9I>+UhO4Ed1R(~Q^qI1 zQ5h*gIB`TzTSj~eaK2HrcOxg#F0mShXtU29(y8Gs;fFy z+Zeb>A}7MqzF4j-12z^y9^_>c@)xP}$7JY42g+yFXI=3QiuT;k@phEA@Y!71I!_=H z%z(teQ2UgsId!o@dbF!F7-5Hd5Qj3Q+R3M7j;TF9v!q2u;y*%_0DA9FfQY@XHYJgw5xjFZrVuCx1RCNmO6E%EX^e#-8uVfWLl>Sj5(7AR3L? zs^!KYOYR$45c>t7`8F2aj`y#8P$QGTMelK?Y_i}^6x@_WynG&d2xazBAvWEuz}YoS z1UfJ6FPlbleU=tQ(m-t3q(NMe7@ha)8tyM9RLxGnlzCv}F8U8g$v#Vs`E=r6cI?L< zv-O~?D;-7BU!{eNYn0E1f#diu<8;_=4{#&)(d(L2%CkEa2wV`cu5)zH0~Iryl91Hl zzZj{2J_OIFMJV_A8E`q;xE&h6ZY^4t%`YCd)H0|U5{QA4(>~H5nOdBFff0ER>@?Dl zQ;aTO?n^weRE`G!RR^I*Cuaq7cc(PFM9{uXu?@dIF9_XY-^uiVG`&TEr)i~5*-K2~ zYQC?>_E`czmtjUOE(&8MgNR(cJQ~$ZpUhk|i;@?W-$;t3rLzZoR z{H3Za3GXG|=8(Mb{#K^>C@XIBx6kInj&uYV$ayJ4L3>d3CQA4=|8z9EGw#!um0h22 z^mXpVh3~{A)8F(~O-$~zQHVKT@nAv2^cu}EdTYsjva9g#^msWpERDK^>S;1I@ZxTx z@~&tm8I=nJrqiP)Wm30WckCCJ*oScm@`igMSB?`b=TwIIB62Wk6ZLzQ(KoPg44P3& zJtB6@*-oRsmWKs&tmk&zr8t{Fjpj*2MZ9nxyI=5FOM!@x7GHkZmg>byBsLqEA~EcN zaMGhzht?im@8`+J*2aZKzfvBXbylK8tBNB*5KC!G?BDta5xmlAKpxJUyo>{2OcJ%VecoUb z%<*3L;_P$hPAAptNiz{#+0Tu68m|$WNLiO}K5ZXL?71fDR~(^h#r&{c%#$_j-E)%b z&q+~)33SO+6j%zh2umc_;$9~T%9Q}69@)*K`8#5JLV zI94b5Iv?EV8q0b{5`_4^ayOuH%j?!(9W>F1 zb%bOXQ`w%9nns5{spIo@>AkrOpKZG#wR7*0g>>|7(Rg3MMNu*RV)(|DEY9R`^LoD8 zX$jv8(&jn&vn5OOX0VD2@f}0aig-mt{vjjn%6|DDkqc*;Cg_l{t!tPCMSeVyHk|}J zaMS3NekE~z&+AW+Kt(WGkj^}8wRbU4cq&l3>i`JH^J;2At+)`sLIA&cad$?v+S(2P z8k(rV2ANaMT7Jl1*0{^fWW>A9{u9k|l=H&?ZaXj4o*&`>Te!KhKD_iD>Z?@^Gh0s} z0TsXT_JB3T;1F&zbfUtgSiK(1m2lT`gEv|jDnUUGlS@1KBU!nk&xzFHZxXBn`K~6n z>_4x$=FiwP_6Gm(y<&P%vO1Qm1q0-9J-E7m2W0fLqyE!macpPT+gWhCQl$vRoVd7! z(@L-DITzcrpNl1T`s`uYo=J+8+qjmyDH#fdYd zSe0dfXR24|7QVPhqHE)@>`>Myu6gQNlTNZG;v-e9}H!W}+Om01>2Y7)*_u8^EIlb6?Sw}tP zUH+eiH>O0RG%8mm?!CzuuI^6!)S|T$t!BTxRltwuIj}uh&+R#j&<9aY&r=DQ{W&HU z)ixeILDRo^7m3=QtN?nLi&$Jm?Dce_Emc>2d9RCmtI&E%2_mR`dOLG`pjs>+SD8ur zC-FO@&T9(u*YfKMF=+Sdew*8mo>pSquKXt9=jU0k8Qq>(A)`RYlKr)Blkwmo)d_v8 zl!na)V7DSoXD^cc_wic&1hca5{(X;>x8V*5CN>u9%3CdSlEcGQ8;`!(HkavT`K2y0 zQI1D35q`SiDn%%Cq zAopV%pG(Lj8HRrGjY?P)QQ_vl0* z;fbdoh5c70xk>GC3U?|`kW%KXaHzA7W6RXCEzD+Djb1jjelkJpFczumDJmgUIYzHV8gR`06r+5L^*VhVdYR}K> zA+e{SA6l2G1Fxxs1RiM0+E<&=6Y!LzL5+u^K!uUuuzZ%=j7a&4EjTY$?@BEf6KGid15sF+9##G={RTP1Ef}xH@K# zd{6U#CnCjWqaE^)@vf{>U=GTTwMaXIV{4AZEZv5e}Ov+zciH(!Ok5s1898h%SqGgDs0@*ZLQDj{y zPL?F*3(;p=d(f_QFK5--;1e9Hoy<1=C<6+HMM7VhIyy0R!8tArw=nyr^~^+L5q-dw z=qxW-0u4iv{}U;yQK1@t?rx`Q5r2=+iUN@%;m1jOtx{qhy(~jR#)ld1S%oB(T1*&n zcKeRSz5)Q+Es{l`C1*s(8S&i`&(8`rcI$<&agk-}pjd|!gH~}Q!*DiET!wK!9LgFK zRbzQN5~qto#x+*zRmWYqmEZx@$4lCA@}HXN(xsA7q@APZFIR)|AK-xG$MV+>!`zc% zLE8F79E$#Z6Y^Ynon}#pwP>0Hz`tYkji0X82nV-C9k9ZyNb#T8duG$iA1YR;^?|=s3bJTAW6&AD)6@S4pSfR{aunHEO}paqLT%wfHTHj+8?VjypYo-?-|+ky+Z{ z$=Fg(^bKYAk~>DDoR4NFb_+=qOmSv;KH#06JbppOcVW{tN+6yhOnx+*c{{VdagjFX zTJPI)tDVV)R^;vJw23mb-lJ~DfzwJx_OxpUzj}G=D#Ic!>zToW{X?<-K??0Fl0q51 z)Fd&DaU4GrckQ{S8gR2|1-PRZejG13&4j3$k3La3+=Qv6nT2-TO7)^=)&1SWu#O) z$9widDUs%5!ilG^dU95dTWY^u&1XeDD16|xYgEN}ZTh*=BfnHJ0@pRgt<#2Rq||$o zDW}E7(TdnYO@?$%>bpZQHuP}58mj_2JDFY(F%YOB=|6MA6>-&@5~#l8F1mgZ%`XrSSP$%>0c%eNrb_Dr`jlDV=S^ z{Fu5DosjNk#=HkT-YD}CQLP2U2T{Vu5W+A*v{%B*&dtPA4k8>r=K59mi1bAY7q)nc5 ziQ^iFb*-A3QO%h+J9}?g0G_IpM zx@TtW`CVhV5_g~=_ujeu-@iVlAxC3F9Yv9tsOY_y2TBCBrCwl3nwjnx7wzG9YAKF~ zNO|d;J|eI;$k_h5ZnGCaydUYK-ho4COEg30ex?O#4zepwsm~v)v(sOfYr7i0 z^QreXrCM9*eH0#kxNld#bX*lkPcMd2aR98nGEqBiua>krD z>#9oqjysGw2o?~WeX$S-E_w1xEcB$r3pO7fk3US79ZIzsI={tI{~Hf3lSi-ISW>Z=B62xc4ad|cR??S)Hjp49Q=BdaBr+t@gy1kfp( zhw0~M|xM@gLkro$_l<~8Foz(Y@>cL7(Fu5z++MpV3N zQ$UxlIZY`#;=8WN`ea!bcyamULRQ&5B!q^lE*e5mF5vxxZ!6N zZPqGUw!JGnj?liKp-Xg!$Z?|TFd91m={%qZ0pusb_9zwyR201!F8%`76|e1AFUhpIKGHt5Rsl12rZEbB8zrl%9AQyzRN; zm@sW?GAy?t%ttqmL(7mqP4_-kuiaSb2gnosx769kCY_h28HdSbSaNNaPL5haO!)RP_Mc0-Js zuwYIMM`^q?uw6S!eN_ReQNCDac*qj!^Ti-o_jT!`^p46KXs|dSf;Ro!g#GX^MU?*X z9LESLRtV3tK$ZH6*KINWnYu~&^@jh4I?rPO8jDMYx?NoQK6eT0n_+$eXl8c~^EQEQ z70JNW95QZ9x5v_So(5kYgxd!s#yGfGlo&P;<0G=280(z>XdqeF8}%c$EC^UWV3R6V z3+!9nf`+DNg*aC19I~2`dt0A|9)`q&OxVO!GZoPogw%mDwK`Lk95)lzD33@D-Dkg# z!PwhZk^Vw#gBLD*2j20P$|@Z}%yo_v?S_f)E>sM|BPy*y*CCvik4ceg3&n{lC2Xsk z%9^PYC9v8U?RBKp9TyRsq`xJ#bbFHB&P1aGjtre;7GJtV@y5RZFA7%N`t9({zAP2wPzgD;y^UJ0VV zCz-#|K-;FvzG%j0N2ffI-zypPX5L5s{e%*NA#F`TWJavKuvYxLoCkeE<4@~DT*qYZ z!8TS1huvM-5;u6=O(!V}9R(dMM?R+XDzDwf`Qd3cT z(v+^drY`SXy-TknbmE;QmVut79ge!t7c6wBr?HAIf2V_x3T?%6O88BW#!91+jW^-L zSfRGHmbXce#=(R}q`l!?kb+K~gfB-LURuiZK3Is%a;U8#X9^cL3;FtpHzEXNp4V&wu)?LzQ5>6{%Oa&&|8~5SZ#W3gX zu5SIr8r02)Z$cJ*#5uKjvF45?FyV595+VEA?^SQpbf?kSx8ksfi~Cz3oDb)Z>*N#8 zILEK-QyYf>ifZ`BVv-50n&h-*jpilhsIF3AVYuw-zo((8D$o zK565mj`XaI&!Yes9(S?^H;7T%n}neaZ18ua;tuc3E0}ZlVO;pzAU=sJVomW4cHF9Y zK9+e|5tt`a47()?3RonYbm+qSju|JSlqY}6_Zl4GE+);*Ex z17THSFQ)_%S3B1m<3=q~bs2g_F?#+UO^AzWjvZBQI8KJ7b8q)}Ao^3oM;`t}+mt=< zz`72XC7Ah~9LDA?<20@9aE0V3$FcR9bdDArd03inRLYm_fBKPVWi#>yRsZ^p)!(vz zG&rHy8L;JXTEcQFcy#a!Gl$;H19DOi^Yy6tDu)CC{9nvn#C0AGSCb%;6CRo(=;&U1 zESoDjx3dSQu+_05H5FEyeE)D_0`5xcd3ubV{3w8Ho&hxvycuOme}<%k7R0Q$TFOU! z$5VJ2XHY}{u21@PQ1!HU`2|0>)u4`xUQ^9(6bg{Df#?0@1k%*u8YP1m>@ZdPW*tP( zb{jf*>b_l%PTu&EoVC9aOhSrbB0>0~@I-<_k{y>d?AaSk?<^490;8>F9?`AUBfR{j z{fw*g4wKtw_&@xgNMQ6ZQD6655iXkqZzTD6_*T5n@Ot7Q56z@Vm!&|_1rE`xBLS3t zx|`0uG;S(6F#uG8e=|B^KlW&XH$lr|zqi0}u0fui!DZ$OZnq^cR?wvH(8t@}Sfod< zyukiv_W<3kmYQwONO8my;Q8^A8n-7BCkdl?pq?aaY$}cpD}yvY1Zp$7^3ram%$N*He~{X1t6nkCX}UcafcGs$_CY7w$zL{9;=+6GtHbjJqh$13y&06UY> zYv_8pkNV~OL?eZ1CwN#yh0?~@y_C16zBL>^t7by4pC3}a|0_U-R1>2g~8f95B z_0A*|dS0LRh7CPM)p^|(lWj}47v-%JzGdyIQ^&J5UqAivD6FoHz?(uCorB@yS$d}n z`f{?B{^73rG|)LrnUzzg1vP9P9X@bNes@cCcqr!NY7!1lQ3WpOnoNj7d=C(an9c_y zOO#z-I63S1UXxCZgJZ9=q=-)at@)hl2dCMg^-q-EWm=u`^AwZNjp4aQ^CQBxgSo*U zP@eCPgp}b<)}H|xzZl)6x7$FvT0%2FCr*W-5I_`BTz`DLLza=Wa)hV|AotQZL#Gq^ zR?M(kn+FrMvt4dKoRc;BWRDjNzK%n=PSE^|q_u96bnZWIwYc^gJZ0T8X*xQA7iMS+_ZZ~)+oMbF)`WrRSQgbnWk{@85*xC_IWJ-R##!FyU3|V#=GQYTogl; z%G_Vt$Is=t+w1ky%Za|6(c3+G!;u7W?X!!@q*;kG-lNS6@h(>E9>n^NsAoFwzg9eC zAt8?oFY3&Dzu5Z42d%KpT_z>avV0zxYgc&i`wG|Nl|IyMd~xYOk{qQZ5C(6bfDeED;bAlEzA`1Hw7NKP~i=%c2l%P@ra0zPWK3O;yXKq2zuf0;iZfChm=W*;b!St(2i zfLcNvp#NV%mS&Eg2o3}YBtW3?ABK?O5r8MOdIPIKE_wk_Xu!cojeNlz9z#PdE>P>V ze;NQBwH!cyMh3*Yy?a0nG6Yy#QvkpUErJ^X`AVD`S{wjw1u90!!-qNqoFq5MkY-N& z{OoM(`VizCbm%7E*$G%jAfg+9EdmaRGpHu8Un;bR*&)c6E(SdxwZJ+Y%s=330b2w+ zGzJ6!P>!Hl0R)aIK*&b0L4b;0K&~k(09bQ`llaChd|M;Ab>0=s~(7V5Ox8eBVXx-p~N^*Pwft^0Nh#{MKFHkc7O^g zt3VnBSKrlK9jGujF#*p*gK_;-C*P=Gt`krQ*W?Q1uiMm)8Ai6w)FIa-%=vgBHb5bj(*8{Yfgb(~-V8zjAS6JbAfkc-=mZeBQ*-m_ z54!f^2==4?^dGGF@$JbeoCCmCfh53hfQ5J+d=Jv@2m*k>Ksq^o?MMBW_VD=$xMn~N zGJs?P9d_^!85cCz=5L~6Zg}7hfS4f4;|JiN{`@`_GD>?*A)Pq1KUgsG!@b6Q0mWDl0M0*z9SjPP7NOpcfBlw!+o%7=?(`M^@In6F`=BJo#r3!1 z^soF2UmJqFxp+*+8&xL(8ufLhumU3ZXZwZoVy?3)xMonY>~Eclh*p7_5W2zj=Nn5tyNFYmr^K&f(SbzocLyv1!RfD6D4u&&2zE6cK7QI0DuDNjr~CaW+1$)t^)ed{sa+9Q1R716MrDQAvo|a z9UdXHL(qTvpVU4SWN=~FJA1D}>#z8quX2FE9Rc;vCuT*eNQ1Ad!?b8AO)U2OS;mU^ z+U$8{4v*e*gW3ryp&XLAsM!J3jSQP*L$rsbaNx0uS>WNAb^Rl+oP=_a+H>nWd^5*w zde_%+NeWS?*1uqPa>D1Sl}qKjeU(XS$+c{u?L02z7k)%xfWM1H^i6MkNGfEjyfNF z--hB%P zX&w=t?VwFm0$Pa)UUyaNh@WkL@|}|a25(q=P4bbeq^>4s4P>z1sk3H@CJ(HxspZ^4LEDmV}=d*5i$c-t2Sq-qSkHf5OHCxCkYmP2O;jdL0^(6mtU*pHe z*NyA)#5sCqcrl+hGOjjjRez2SJ-Y*ow+`_GNxYgVdo@o@GJ#pP~U@`)j4S4-y*Z5C6>#+$!<^(#b0Acr&W$=docT33B``ouF|fPd#6$_d`E z4a>tw;7YkkRz9nYoe23_9tZM~4~>B};+?>oEvXM%bfcl}_H8`vCSg&IeXO)MTaE;JkwY~HiZDVh0_G)0&?i(AQTN828vA~t( z5sle-%uIE~>r{PI$TkzZNY#qx7>Xzr`8hxLRdDi2yyCpSI#VrTV5rs9n@R?<-8UoR z^BM{cy(s3Rn1L!Sax#&E-m@De%k+6O@9`xpd)xz~KU+n?je}OU$2MuLn3K~Rg`dI} z;nnHM=%~)yq9k!}!BT>qbgPfijIWkHwf8kv+V&dL%`y^kT;c{yxT3xjD(lp-or>gK#pX~ z9n(9h*AIe)8#jINg zfshYHu87HZsyUu@Y%qpvr{3{WnM@o|_QX=!+Fv5Y5;+`Yt#93MTz{`frKa*XlH?j?Pz z%kQ#(FX%utK2R=97@{VNtKV^!;euLxT+9R>=-#;BE4C$^9$M&cwt`Vh%k&VS)T^jNo`!WWS&)l&;u4tlhRgLNV@U|7^sF2(PspS!{J@3)ycoM zx9Fw3sF(DlEliWdxoF+gOGrbFJAY|EMJG*TviT57bOmQqY3r2KmZ~+M92uVxPN@;O zGbeN!k7w9n&=Ng)96LCmste0648ek%<9+r$X6_#QVtO}H6LnkgSBmsmZ|lrGi(hth zHmcTcbaSvDs7VDJR0Gbkq{nexwQu~A}H=dJ#}%d4PiQd^Y7d|p%@v8!AK^7;2_e5I@aZ%gL*uh5MVmMuj+h*|NA(e1l%|_&i*G+e1x< zP{Yabr~@yr(Kag^{{}(^6CZQW`OZeZgkhu1A$lm}>m{5i=MpzZjM5o`-yedAvEECP z=N6e)NSb5Mx&Zt&YU@(5jV}uU9c`G0jTiy_%}?gw->DJ;eX+Na9;sHb{^n4Bv^$4T zk-jJ=`fP<$W6r?!*Rh+c=~T23EklFzo|J2nybqodELX;BwpZQF1%tD35?54<_5;&S z-iolWA10pwDl{=y#a_95sCcU?%Lf&I*Z#9p%2EfwZAr;CaV`)FwHwJzyTNTm-7E>GyhkMPGUjX0*QJlEE=E1@fLaovlw zz0J@iF8G)*Gz}pb`D10#YbtEUaR#e$bgvTfYF!n-_ z{h@Vv3z6d)yJ%1Ece=?~X-IeVFZ@^1gl6m8_$TgH|L*e}M4$iQx5nVQp_dhwf40AJ z{-AuK6Y))X7XGM1t2~&Too~2rcgmH3&okgW5PfkT-{W~=F?OG6HD-J@{|!+tcn3{w zq}9nd^*o$dafnf|_(>Xry6WTXggZZgB~|h6-W{rN=Svs*scj_E7|0FFAy98R`FVZC zGu3!L65k!T>BONh;5-?RZsv{(mMX4D_z@;9r%YC4`2}TYgvy63+|vMLcrredSh|<< zH@;nMGrmV!FUZH=aUbYqNN!Q}_#b(e^T($v7A@VowtBmd zt_=%Dq?zZT-_WMO4 zlpqmN7WL-0TMIJzZf}`=gq7?w)x`Ma9b5|q(8m1$usmJ}+ z?fI?I$-;u`$f#x+V>y*$DeBXl{_gRiwEwB`SAO1Fd)xEMZiAU)3qGA z$d|h3qI=lp)!?UVOSGW!27BSh%geExp>(y%@fC{5^IP5O$<;F9x@zNZtNJR+t<(Sz z%x|ao3{Se+w$j}07f}5XFYw!D`AIU%eOd3--2^yP(ympMk_h}t+l%rg*3wEgW9qFZ zTHDQs%3B_gcS{6gdt29m#Yef8m$$bRsrozwwtt`p&m7(Q&Z%|7OL^k$K<9rVJ_>Zhu1 zOJKBAgF<+-fv6+*<$O!eef3nyJ{meS5FF>eeciaucJD@&v6<%YX|4S1qyneXNBPGG zQ+zgbL%Zl|((?(Mazf*_mKihd?PS)gPJ!$96V+wf;By~nwc@3!iH3&j`X{pxXMlDcz+ZKXm1@$u2*xx_T1&pPCeJL+l=3wVfx}ot}dRtCn$=)8Rz##Hab9B4B zIu;m>g6LDOUkiR zWS7CPJkOXy`{ZDQD);tn6LA4I*AHVM&X>uC#|iS-k+TB@oOpd|@Q`-$USC?@n?t0n z&Y`~m;6viV#uUz*oKE-~fbx0=xv`h!g%v{ zV5jA2mHp)0954?4G$(^7`$W24D4?aRo|n921=eXkHr&4W;v{ii({qQqCzrqhOSTb3WJJn_Zz@g(IgH_$xa>e|@-XSW4${kHgbW_7Ps5up5&1Rw?^8$Z|Y$ zuUnNkt^5(Fic&W?ZXqg3+io_Ps+EYuTx__C-Zh6Cy75_bJlGI}otjfUC%!Bv^Y_aA zvNoCeq1&GeR3Fk zT?x*TjKusQ#@1cE)QczAYd;Ea_>-2dX=Uq|sZymqsI*BuAm-+1Juyw7Jxr9e~`c_oMy4CR|1EzI1Rb~?&tHI$^n2Kcj=$t3rY;5db`o$wS0-#Rg zp15}i=qsmGD>>}DioV$LQLre2l(Z~AGV-_Nw&rxx(R%tHjWZ3j;43UfZ81`-gO-e) z_7q<$8b{5jlvp)jIL0A2-t!~vBCs4+msRn%Uxr8qT0b2c-dT{8-(EFsrPPPP*&3JX z83$c)F%5x{)HqmnRrG@!&BEcsNtvYJBnNFRP8pgW#lz zPRS_2SD&WA9E@_%K$0n~0P4$zh`afb_`44*Ux`2z*%TC>_vi)bwGjLrMQ)7_m;C~3Q8>kUrJ_RA{#sowuRdSY1ps!Blh}t95X{X6&NAbA*WO(%XRf}&mKII_G zukkHio*bkim0muo0xv>+f>^U~@Icm6(NUd}z;)JhdMrrH68ZEr=yk7uCFQJ{;=TCK zCQ{0qsT$huomP%^J-f@t<~n}1Q-u#tvM{4@q!)aN+wX+Lt}vDcHqXr9p{+_Wi{8Am z%vQK#);_8{HP>U?d!0$qJPucDp`5d{wmXY=jR=f$ zw%Q@uRqm?NT6)!HxvJA9TY}JhxQQP6-H&al>wHGX4-39?o+Q_t%|C4D_F`oC$^ef~9O+nwD3%Q+K5d22WO-Wx=I14}eS z-weaA=)Qx%l4aS;B~R-5)uA9_j0!Tj+#2dbl*`3=|4abOc+LC7RZn^+nl~mZJ#Zg? ze^+o{l&JCeC&HD9I^`IwET1#&)FJs~Mu+$Y1yGt$i+)E&j>^Qyk(xgQhn*4UwEjz> zm-UiW+6jk|=B&p=C(A~G00u$Y@?vAj=BvcSI|F|y$~G?fSulD3S{MM6m6L>=#*0ha zad29x-L+&C?0fZVJ%@Iam{dI+FxX{Rv|}c1_?HshA@FlMnTij$MD{uw*q$j)HGIf8 zQ}+qhwdd-U#3cMkjM`H%15gfinY(eH)Hvqo9(IalsP<);(M`9Qt1 zd6id67SS>48eSq4wblxn*|(2WSWJCt5Jcj%{28Ppgc6$4{PZqa77J0s6NJ*@NM-(! zd0f-PACeB;HT7v_Zd!6sKI$u9oQqR9U1|a5yxH;~QfRQ*zR{VSa{ES~1ZpewqB1Kz zY|^!-o5)y8gFt!jzLJ8Oht{Q-_@CBrhjUrGgX&cLYVb}@P<++&O%Rjj!;kQ`6Rupe zM)`trS@!x1w7X+ER za7j4^T(pkb5kxgX;8`(7uI9Yxzbb(70gH~j(*!!sqWz?lNtjUtI|t8vi2YC z0&*hnUtU{QxITL*m@GA1s+fN`cKz0SYKv{#Q&N!?M@l)KG43ig2+fG1C zGf{IRd-84ASDkHsp?;i<3)co=^Vlerp@ORu*yn2SZ+@>k3--dWmR!TNvsbirY4MYx z-TDIqo-_erG4)MibWio-?#DrbwI(fXw}=wv*T1?meO0Q4_1n&Z9k zph-Yvb!X_%mBzyF2*TwnZQHhO+vc=w+t`VX*q4pF5&IL)+jlA}vzpM^<~UW2 zA|a7iS|eKaE5X^(OX=lU8_vbtbtgc@6-|BV&(fdB`R4ODW)&jkwbfTeFRIc%sX=-D+(b9tWO4sc|8Ocfg zh-}J_)MvAqll^`;aUe~|JJ;~U9g?uIO79@!7mTPx_^0#R9{Ql!wJ>IDsodP zs9On!%VHx9lyMB)-SH{#uH8qk-GMG(@451#ev%+gWL%qU0%`tggd~qCG)Fl{zCOKF z-x~Ul59X+^c(F{ekr)%^2Q#C4u^Oy&OFkoMS?$w0``9KHJn7G zopm3%W^xL^#)id8ceZCy&eflw<%q<1X?+z?N&?NcdNWNTz+X5y7$8wGy`hs1ueTs_vgH5fd8H-Upw?dWB*JI+ivG#49UDrwFgRcg6 z+fK@Ko+-s0TFB7o^<;BCYJER2tPfdY`KpPOp$xti%^#=&TmIhr0m#nfSNtbj|1Xe4 zU}tCv#l!PINS={^@qgiZ_WuLdv$6blP3ixG>)k*Vuq~Ht3phZf95l`C!}e}&;Qs9h z0Tl}X5&pa2uGB5zK&wjerx~T~Pjeu5$iZFN_51AmoZIbmPg2Iww%PIa_Un2MBydbB zU05^gG*UG{5D`Z^X8;j^h6^qr0K)hbB*?=a1H+jh0^A-y1zZpy#tl$_py*GUE*cyd zVSG9cL;#CY*uMl)EgXQYEmC5P{^+lL{JpKk$^3Nl|L7`0O-G((jLS3 zU^dS_f)+Q(L+URM;It|YfUSXn;LGj}fQ2{%jv;6u(6S%|cRlfg7P+#v=X^SRjW# zO#)aSGB_YgaSI@Uv5%k1sUc_>2cb5H4guUhRR4hrwr=cE-a<3IfCwYnzV|gL4+jLU zMc8#S@%*WAUBKX0{+ibW3u0;WSOsFGMo#BLF}#jiP4k)tiZu8R-ULbv@FhT?pdf(( z;0or?TYc5;3;Orb8R%El@i#Ex{nL|sARB;f9I3w-0h{3gd~6f+2n>v1uU230_P6G( zEqG`Kwmwvy5Fk}w3j*ad?@R*2`cYi0mj~wnkO7b=Vhk4G=i|$VN!W1;3(V#2YwYXw z(2){j@{H2F{+sU2E+raf8hCGJ02svn?hY7mYiqC@K=5ebbyu-jAil2=;ODRkrX>I{ z_?IN=YS9nL_4D#M;};7Ct-sI6qCY|N$+fGUNF3&*)TuWFR_gAYb8i3GD z0L$|7&JCH64hjLjz6A}$z~nWI%Fq5=5BLNiAh1QBE?y5Bw0{5=}M9bzYl;!h;D0k?|SE29fSMh``@zk#x}nRes)j{Yrxha%>2+zNU$D?_=~=} z)Zc44MmEackp?piK_Nq4csu)^5pfxlf0A&Ufqp4-xRxL7@3VLwE0#~o*mt;VV$%0* zCN}KqylZEWUC35<4!p6*ukooj5^T?k27Lz$$Xjll4zG+5%>DXMOO!$gch^-Q^s3^| zwtCbSiVEty_l?%BGG9Dn{HbnS-buu(eWNY(&sl^6OlDy?X~6=6prW1^3cv@R&gUw` zJ&fGsRgl*0z1@sFqIzP~JPzngyHly2-L*R@&M2cNDsJ-lJ~#%>Xqz%hh1gENJKaHl z7=1#UjgF#>pxTDWn*L^n&T@KRzHt%{r9&`-a{l!(JU&ZLVJjgS`;$om)0;gcnt}>{ zY&4)MjqW-_GM-Z!q|d8)tPDBRNqV2;vv|r)eTf`XgtPg8^wwPhp(r|y(ZH%0Mx5}v zb~=*TSpg5-ch+br)r)RBhp(0K+nDM5=ab@==j41CId;?jsfsDu$<4ovwqu@`6`gq4 zI_lrkpy^Kya=nBh2acaUtXa~whl>|sC2L4OX8~I@M%QA(y!x!nov>C_DQ{Ted*Zp; zwn3q${K%D3%T`iWa&AC?Wgvn@dhDni-GBzL1o{YR>@EedW_ioTd@eso@^5s}l(Kk!Jao;R4grC4zg5cn9F zI|FX?F_Sb@DVaAt@{E=nhX|_R_*9%bNK)XG+5QoAel#S*J{n^HO7%BX+GuMc+Qh{!`x@n{bVFj==`DW}`cXF4z;W1p;Dku77v$%Cd>8F!zNL!5BqZOogQ}2D zxneV#E?9V?kC=B}Wds-Dmj8Ti@Y)M9xSGWAL~HEw(UJ##81a->V}SOxk*;7%CFt^r z`SD6Qf@`V94dZo@%)seHx6MP%snRic*Uy6T;L~eYbXa%>;FA{>fSa3}a1+j_Yj zb`dzW>}TPjgq4ka31;L?8S7-Lw#bnQCd_Op^c)GaaQZCx zcINe-u|~ePcIX>sdm_g7GzCoI?dz+`>L4**b6{TcK54nt-v0 z^jly-Z(qI_OFX|jTiiqY!hZZc+S)jOQ2}v9z3hqe&Ru?UtH*%X#HC4`ZV`|ABrA@E zbmkTRKGPiram{HJRI40tD!kw0IUg)`DdfgP53Sz1n|JtQ z_{ckE!C4TH3h}0Ttq`Qs+*MHJ@!EzNfQP(TN^(z@%@G9HL@tI(%aaIm&7orBvq__< zUCBjR^TVfq{~dz(^zaFqkV zmC%@bTPtk$^2tatQ$veFGPB==WHDj0ucGpLfS1omXj5>svG!y@cna{9e_X6h8=rnvt^V?@b37I2goqQp*D@3(HL{QAEy!e?2rf{ z&eHIo?VJrI;yHB@CoiGuVLV|PMoe^1q{m>Ld`8feRN30TWAH6G*=ZQ1Oj&)M67l1h zyU`6Hvq8QH{<(E%Ml3q;+(@-^-rY9tcgjzt%TDWC7==Wz`iWKbhKRJLkYp#7v1%Fl zMmN?x-P7byS<<(UixQi>1R5Pg$Wxw#EaM%lR-qguK8kUBz&XX>llI&5U}#9Xh2^-_ zK_s0-%?VmWO875hDAvg4+*~(&D&8hsoPpvb3w;dI0y&gU2x_Si?-^+e*>&EIR$ASD zB^gOc6bZy`pYa^JQekfFDP!Q8gT0AW;3gLM>b^v_t5?V)RBmR&Ia!;|_@-`$y4WXt z=sif#9n35GS;l2dHM9LlB}LU8D)>-1lr_Cc-CJCU6);Ij^Upt8p;Rd8`8LSk6ptSR zN6B;Ln+|a*eF?dp`$|~PRbCE)1kgE73eTdle5OEn{t=a5nOLs zQlI%`8RFE@V;`IBvU3C~VS31{JFDs)v95#g+jx{^S(p@kx)pHDE8DweDzR0g>TW}? zb4~-J5{_(+lcN|*OkIbs9bLD;f4^`dko*lzT1bIO-Vv)T_n6cAkVoBGVUj_6>_0Rc z51B|vw)@`M$bEo+H^*PHx`2q4`C_*#a9c)OV!&aES$o3D5w?O#d_aS^>_UCxKI4uT zX7H6wnlz)UEPDU$eg`ne7j9^jycvW~j*RtfDITl91M`pkkzHI9jA&`bPQVz6TDfo& zd_KboHSh2uq6WD-AYl^QOlgY+J+8v+(%0nR2kMK=?_|(7ziq5*#=D-V1^KM}><(+> z+(X&gLt2-4J3j0d&xAYBH85&m<7mX)mV1KhHxSCGF&9o@!VDa=R_yn57=EtN>Dbx) zj)zYyfGq6kyo}*xAf42*F}XY8Fr#j7E=SP(AR_(P*=XsCs(c?#v#;RES6%ku0II2h_|RKDjA5)GE0J>Mo+v%IO4cR3me>yI)a&URkom zL0&$$wRg4`YKzwWU~e^3lbMe@y;TLp3C_vqy?LcXG@p6$=uFLEz^KEJug>1FUa&Iy z*R(sL4lx&GH=Q<+x3e2$uo(;WnPp|lHB9dW{^7{F- zWN8(z`w*u9-HI~FBxu~0%cOU>#6zU;K9l=<7tf46fm}p(X)wgb1m^pIF;k4SB?isT z_>u)HMfr{QLANCN@D*m#RjhR9e~Yk@A5%~@PeDmR8h1!b$=*5bM4k#x9$)gD4PC=Y3#O<3O~6_IP(Xb zxU`Iu%mss-BdV++A$)m41?hf9-RGIOJR+KNfZvAK)rqr?Rh!aIuw)3R?@k0kxpioVEGltlcLl`q2|MNS35K58kZSZTW5&LqWy z{EpMpbw0^`mPba*MxzHReyaM#Ut_#Odb_*BKiNi#zbf#3OC^cz5Pcp2c zDvP_%vssz=@M&K2Y|lCBrg!i68N5Sz7FzP2Zel5f+O*Z=tBg6X`z04I-)aRx9)rbX zlRKE2X-EUf17B}kwW`t6pU1`gW&Tmeww%Gw;_n`XVLMvg?0DwAb~Bh9y9F920kDs+ zkWY5B#trPvbJebpnxu}g<)1qLNNuX@B?^Q1{sDthR}$cEY5 z#}t%3gqDJRZSLstLVgrtWoee}n%xZ6>6V zC{8VKIY#Bw2hxhN>t}a=mOe??wGmAJY&|{|#A5K$O^m;m09?`YxDn8dPUO)Rdj#YS zN12p8`r$46E?|rxlc8D{QrG=nycX#3emt>wDc03WH!6-s9l6Vy85XnlDP*(5kKUW@l*LDLHgt@e6;%1;}XRBFq_ zjq$pH$)rn;WKS#6wWJkR4e?Q*U}SoFFn6TSxsrv@mZL5R<7qEhVa}ol#J~l{p^**S z9ATD5u~1STWLF7UCkC(dWzdSfUO=hI8VElskTKSeIgC{!b8;%$ z4NbdcrypYX(y=qSi>uk+x73hUseE_d%~u~~yX4#7q};I&La+>ja`NMD-9M_4y>l|~ zMf0-Ofr}f4XzyA2QUf z#DtnMv>x`$eKsPYAP?uzEIL}&w{Ef}Y%`bfQ~;aHjX`V?w+y$iCL*3LA?K*3{dZj% zmbs}hgJbeNdA<9plvLcfF2_kX*n~ekdBYee>krb*1KPq^g@bzF{t{~q>+Ra@=F$l2 zzGjmYIfZPM-hFNfrO2G~?3$4{Bs|<>$UP0uRMr_Tn1fC`t_#TI{l;ZkZo0GVY=dIs zt@83*Zy6c68GdhENkrG!SUr+loLup+^R^m!l;HSt`F$%T7vi?YU*>++vmjHF&&`{n4uj;o(j~fXIAM=f(&v@3kz9lzg$WN zVUSJQN~Z3Q!;7P?QU>crPOvA4yxXNy4EoRK+cp^%^Ph_M>QOu2KQ&Q{>+7_YP`2~; z;j80xtf*i*EBAXHQ+$zi5z@suo*QPSth1!c3YZo~%ly*Jd*-arjy=)){K zD2kksq=(ykuC4idE~e}GU~1G6_qPhlB7!1s>OIt4Yn3%ngF%HAch;l;V%Vvj6rBTtE(8h9YB{-%hSkuFKS zNiq0=;I-i9`h^P$d?bQ?o>X9GtHn{t*-d&K*9N7DJZ=xp2*!FSS!b`!nvW-M(P6uu z<4!i>PB57m^U|{}gb@%m&|4wQUJJXCN+oPmD1Nxo;BlVxpJXB3M^=7EQd+90o5b?^ z%^8!*f*?Eq#fL z8`0;%0jWs~|!#R`6`({Qwj^GsfqA0AeQv3y!6C$k z!4fj6bEw00lTMyS^IOH(UUGEmbswl!^rwzwT?qEA$gF(K70<7-ma0D?0ut5y^Uew0 z^yz1Oz3_err1!^J( zAlAA;RxX)J{{rg2nSdhRrO=|~S*!+3^*^a`yNxJR4u^V0J5wDR9LW+`rWZrawV|HP zR>kD=f_NvJS<>`<)|nO%wY1I!$Tq)Md~Z%9h@c^5Z%vV5^j-3^hZFR6ZLy6CkPI?C z#{8DJPV=zOLC^e3i(LD`Q{|;0d-+$^>;k#*>{0HRB0{=NULyvokBCs28W8Q}%^}TQ z&k_`27T!y@_3hs>njtcldQgjt^2 zdr$U`wHSyQD-a_d;x|^33-gSp=?;&@J@^;rl@2}0BTgHpf_8aF-UPR+WLE=o&P8Y- zIXt70YFrk+2bo2}lA;}YeFt+_`@SyFmH8{Et*a^t+`MSMca;Hr5%My-EznsIq&StU z5uglTFECjyq`V=mPwr zlHzuOgI+7pk^?sTFMG}Q9x!dChqtI-1@g=`J5Ny4I-L3RV6ewTiK3OS%qJCRs?2(k zg<{e1sz6Tj#He7C3tdp`5~pwT-NLZ4f`J>9@Kli7G=OsU&&&+m4T zrn-DsKX%LSeedZZr}jFuu_Dst%xz<%G)?Aq3cR-POJ%0Tug&ccKK67RdUXw&U@{1b zZr01~9*V1#UoJj_;C_2rmsWliqS*^3#9EzYswetyRzly9p*I52<1#lMS`nB7fEkW3 zSC3eqwrs3t@)sML&+N5CDYE+6hqTME-UE=juskb=x@hlJc%ex_i6OERPxq6I0U@%$ zkDD%Nj!Z~=(`|G<^@sSfOvj(;Ckdk6c4B36m2I4!kCx>Z@Tcr;x??Yxyc~cS6z>*JlecaAT4u>!MA9>EfjK z2aFJ}+>iGp;JWM0su+s`{7p^NtXDus08Y@wDnlnaezG`nt)zkOm3jyHESn)emWDAb zZTUGP=In#(Ke_%L#-M0$gFaye?NLW}o4~Zg@WQB&W-3jd>f>68?WHTqkuu&!J4zfX z{ED18^(F6Q|JypHp_Is6fQXC)esELC#5wO`+Tm6p8*VtsVYSoyysmAnBVM!QpISG) z|7d@ppSb45d`kr{jFvio2i=63MfG}cpB$}L7%i{;RUN&tv(_p@{^F{4OGIPMHpXpn z&DDvM)rzhq24!2LT-Y1)D9r`{wW0-qpU0>b=7*k{k9F(Co40_!4Nn9o$ME4XGDvNZ zB>_qD7WnP%Ztn7%Acb1bEhH5*t!f;|grJLL&79kj_ha%#Za%i3(68|%WmZ72 zeXSxNus-*f8#@_ZFs0mK&bXf#2r+|(z%*YbSFlA~O zJLhoaDn+_vVuQK^L)ImZ!KKM{g>PInAJ@dQF46lur)d9y9~EAG^FJ|pmjA@$S=m_r zhtM+-uyg$96Gt2z9PIyZCf^FGjADsSCnE`iyEv(^I1K|U73S;)&%na$3`>yjEFBgs zK}pJr=QjJ^`>S`k!)i72Z^_1OtZA2Z`sqSbJ5dz^Ivoe-W)^fG zEDE4Rg#|P~pMjnoV;WfBboHOF82p_8ltq#(~toe#yXfCw1Y0hnHbILlY-%GP@0*7kJ@ zVccR2Ec8!I<@D^PyoHKg?8%fT0pvhSQb*>7})app$54`)^c+*L;SZS zFcpP;aWooZ--2j#2;#Zku?fU#V9TH;pN@K`)*+x$j(p{2umxb6-&&KiiQj-WxUmg= z0R_ARiE~Y3VBf|K4&RPCjq2{kt{^RlS$+Z&^vkIFW7H4%RmCa*!G3gW@8|IgWeom% z4b##r!oexL&*y57o!^o}3{y^4Hhq0_JqsB;SmTQ+gu9L4_M;$Qo%KO$|Ps|6w=sR}26G#N5Q} z9In}aeQf~nSELVlsQP!WYocqz130GNZ8!*EppVZlPv)lGB*dTlm=ae9 zHFg*Dwz6x{Yx$;*rvINr-(Q0$u+KlSX2<2Si`1~yH-meUO$9__UcftDq)>YtL&2?7xS6}gD|EN{%!S!qcO18%w?#ebh zB{e;UYE*1?Xl?xb)95>9>p-2FgNBw7ZC(5DPzcaLV1Dqow^cQ`ws^5@-MqhQ0=H>r z{PZZH+eFmAH~xJKAi?qq>IHB+_C4+aI1!~EEPDqgMIYy0oX zy$27dqQITi34+S@qe@^BTU zHGVoaBenPePQ9^o8M7Wt4>OytG(woMen(GG-$=?{F&Fq89|S2Sbx?&bSFi=on=+q1 zseup!BBP&{3k%65ynZm$xQg|S?DxGGk! z!#uf?UULGJ2>AYC?7sP;#;FpK6J2WDK)|AcnH@q*(qH-uuqz7%bwPi{!Xe&*vk%uw zYGnRmsjD@kr{lU{4~L8AKxUgB0bUBf^Aw`RXDksMm4^l=e-=XCXhL2pBeIatstC_7 zKtCMea3-@JF2lC_?{DLiumaf`r%W_3E^CmFBv(7?eR>hziq=A>ZWC-Fu|Ch9S8!WT z(PY7v+!)%4+p1!jpt;L^;qUkuSz4OC+=a%jUnXLCY*|;It_&aU?uqqjyn>yrAA>`? z=}xM~CY@I4P-y?ouWFTBxD|bgCGHB}U)5jj9(it0tfq!L=;i2h{j4)u-@LGBRE;wh zyK1l(i%OJ~g4C8caQq!r*9Nz-KL&>n2WBgerLmDCKXP8IPavDW9F+%U+_?ryhIG~PIQQ$(!V z$|&`)Jnmgg)RxqoS{)ob;gmwllNfRJ=}*?$1i(X@(RJsskdH44+z*}j{>Y!LH#zE+ zeMt|Zu1bBaVu(6CRZW2+zFB^m1A$k;GA)wouu~v!XI-r%Q_AI-qv%sF4spYNsN0gp zCTz5}VE1ROD@ye%Z3=xKFC|@OF)sJ^bLaU9lbs1rmw1phrZn*Bi{69>L9LBTj1bSx zvOz4W?F2IQJDlszY6Hz?NYo$qW_)tB zU;64}uW?4Q?`sDHGvO=S%J=FSmgwoyUQ*!qRq0HcSC+NiTZYzl>peaMOA~*aF&^Ij zUUi4ZO`%#0fF0uKlY~*dj=0$9x2;LIb3~cj&WGWFj!19F`L|5yr?UiQG4r%DrIBL< z1|9Vvr1WIA)U62~a$~Y9U!MZzcXKO3>Ayl*qVx&!lKC~Y%%%TH!j2@=mim6fPzWOQ zh@%zW4g*kQ*!r!qs7V5k+45a=hMyBP*8SsA;^v$~m@iu5A<3rY>CN4ho3jS`^+G^=vlP73OC+JbjfIV4J zl*qViVU~>?a?z&Rade{NPGc|LMvl+u6wy*PTMM`L~y%lN8jt&Y6Ow!^F$Cb_7sC-$JHImZ4p=nqw9qropGGftz*pkmK z@QE{UC_q9R78?A4?TQ8MX|C7O*YURT0pFp@*z}*Ctd%J{w3Z4BCT2E~A9Cv;XYI*R zelN$uMPpZ=Q0SIm#>Vj&pgI*PIjiAx!k!v!q)1R+srBEaZO#>+&R&GW#y z5FN%VSmOjh)o=!8mG*fRylk%NLD45k(jCody#3J#;E4I-TJ3@F0>C~)+CkE% zSz|q?w77P&FprCkQy#}sCsHA~f~%@zl8x+h{d#H)E5Zhn47E_>F8!uOVmgw;!6__I z`%i{+4sO7o00Jy;qswa-c+sh_iWv|o&dV^&R!PR(9Wps{$uD=WtSgw>Pcuq<%_4kk zXxuw5kgGcEhM)aEmFNZVD}7KLZ5^9wV45-0Rd_P(S`yL-2s@<$5> zi1C@ag67;B8@wF--rdiy>9iY?ql(EyvHo`R>W}__>2Tu7jRvNMR;RcDaYC7w!q z<|)t^HKNZbikFDZs*xxnWc2?1#;Yxe!Wuv$Uql0+oH>C{36_~@QEag!U>4rAjcVYb zkAvWq(*Ecdz_&H^T9%Kh8esg;D~PKcDlf6v+>~71!zW4O1BFHAyrY>#;sp_V40 z3r>2CHEA>J?J4{;-+nh=H7K%B)#EIUy$wx~snC>Kq9l=!UBTs{6NN}~?H9X|W!elr z-LRv-BE#-doWaCT;&tQ@{is^p-DYQWxfm5&j;N;aPozo@M_=+qZ_mZvG7I5fMbE>d zWA5H7i8^cyk&(F_%6xNir3T|*p@f3V^SF|U6 z6zfDE{>tXDIbz7fxKABznA#y2DYY59K62y}#2aKTbiH}M4LO3$+3iU4wnnS}c(mL5 zQpmrY9E3PbY_TOYPb>1@xMqwaFFwDk+aKiAZPy^V2sS>iPeBh5r20n+#q~-1@!xcE zB zY;l_X531JqT+-87BVRAdmp$$b7?;@g&h_hnPYNQtv#>wLj@^zVQ6?5g6Jg*K? z7U)BcMcEV+%?u;s8y&i$^2{Hk!w0;+Y~6;%kb-)7KDa5?zA)t}@dC@RLvz*^@cfQ( zZkKYiQw}ih_ldKo#kCC<7syO}<@7v$wAyoC@wPHu^fnGzD*PQS($uBfK`gvY;SDbgEmjJSjdKDV4!i&O_BX1wrVTh}3 zj%{)PZ|uw<-(JkbSqT0?MCfIET4 zm-x-b6IpN6k4Y=Wc$Ej=N|s zEv-dn<{C*$k2(4%1=XNZ_OD_^g!~y4&k^coCmvL)9|o_+XzLn$hu>scv`DfO7dni& zwV>0dYnI3dvB5BO(AB|tCcPCQp*ijx+4+wd?@Ke!#>}aE1t{rNt)Y7UDpU1=5t-A) zf2YifbF0Hs*RLol5CsI#=S@F&KkDyARGmfw+LV+Bw+whQ-+@Q?5NN!r2XABVl#eg+ zPW~}f;-i3)fn+;!;7}>vOd{0XO|OY)1)*SguN0YQkQ6&b4XeIpu5mla4p;u7wG=SX zq*wh+gRo>9Kiv}Y5i4IrsD|@qMsVLZ!~1XD9C0YQ?c>N=RH3ecYME5ZW(t(I43TvO zPxA2t>;a?&du<+4EySWRSQUbibh)*qVkRdm7tFXzOm?nMO z?tJ*^-L>dQ@Fd9?K8>>8mn6E5^Y27PB}G4;)hqh^DTT83gUaAItB*P(-6mprPNlaf z0Vi7N0YU6#mPnf3kIzU+0-FDv^QMubes!zc8i!j5rmya-#4zN>^tx{e#YcgSL&RBD z39`@zq*bQuGj{v)UxoXJk(Wsf^aE6r(z=cM0N2RoiO_9#__KqhHtBq%6bl=JbTG1J zwT}WFJSMD1#*2q6B&2He6Hx=NI6$No&&5Yzeq17Vn4`4t#DhGhYl>OtoM`gW%9Th; z2ax?G$MKo(y-^d@kIvT*S1G&Hczstd!MQs;-NrD|8nA`SDaaZ1#=$q)Yxel74fcMI z2H?Lnr)3$GUI`0v$71+=IW!-$j@u6c#g$zoyB9xn9lmS-o)Pa}{1GpO@ zG(xgIvlDha0k#vO1jz*Zbc!+)Rxk!v4ylqB(836*_WQCRUx-P%H3EXpp8t9Mmaib>a5_uMc4h{5xOf*MPNRio+)u2HOsGN3;PF3#J$1c_Sdl)UTz z#H}i$Scs;??F8jO%n8$F*Z08}pKG&Vae+d*4$H@)z0o5mv%P9&%7Gz_efXQ~d8DZh zBK+#}G)m;-I{ICp#fb)(l%BZ1SrF%QS-a5-YoYIof)O>qbun9K9p%wLS|9VS$drUq_Bn#82(WAgJ)vSTLpk=^$tVhxQm zN5^y`x?<)>0FT_Pm%6O7cp;2ngu__l1F>qmoJ{t1eFPJTZ#`(d`$VW$(@P- zM`DeVicNWdy(B$bUP@$DsVsA9oUJGlE;XIx>X9)WJ0)WA@FpzHK7G)UcE-O?#uA%vtKDh?2KlORdwvb@~eALdznR09(;SZ%W zqJ>WIy`1xOx~%M|OHEN&E0QguIUHXI37 z$x)vc0g4^3-vOX45GX}`uVG@RFwl_a-WAtY;CF+pm9T&)))Kpi zSuNGD)|ytm#$10$Vz4z8`wd2gN@CkYy(BSNUUznQ^lbV&i7(fEcScd6dVwVi$Am3|=bY8i()$=@> z%1UCj^2Q&}6;Xx-VqZjqu;OEw{Cdi4a{_8M?wDa`*62+0FKo7do^AfXykV*v0c=8P z0a2=mRN1CWLb#08GEDaD%QYz&xGsQ@e=u7S7pEJ>5Y~HNlsm|H02t{6%U!|EJGx}R zrfBvbP?pzm;2b`jlmhu!9ai0n4~yedPL|la{6spe(NSfr^++0@avEn4_rd}@s~8Et zG<S;EZ2y_q8e*9@|eciaUA&QsokN;nSL`{c>{0YQMnXZR`ab?>D{-q8PO z1uyId!1Ol284MOurrahnbGRE)6a`*k56!A|&?miBFu1{$DpBZZA=kzHJAH?Q^=R!H zpgEtO+W+v)K+i$3slH?RcglcE*kS93K`qYBG<1Gg+M%$Gd8sJ!z z+?k48%pACx@D*aed?*?;f6fp zM&lI&*PiX#GC{)Z=?=?hu+36%*kdkYyKnj3Mm*dSsBz+hLye6=dr*_rZ6cH)?lYhR zRoLy?32E}cQEe;5<-o#{{jV6GZ>2eHtsHJ69}yJuElhKX)}tV&Sm4O>s{0Xx)E071 zh+z&8`x>)rr{b_z$?Tj{NHyF^N&xyTKL=>OT4Z(&AGq7DleWkx87=%hlzm77S87a@ z5(w@r4|{~*P?o@T?fX3i6V5}Cfkc3oH0icFE#S+K{~#oKg0gH+YukwXlZhNN`}w+P z1asTMM(?bb*e8IPkV8CR6-4L6(J&GJ(#T(k(SUDPilqJwQWLFSY_*NkZLL+&O4*WG zHKPvtg}TSxx)Bl#LVV2UQoeT6AvJG3tRyx`a}@yrbAq+}eo6Zy3>*kl{(YLkg4FZ2 z2=1J5X?QQ!)!JC@hzTc;K$9O1fEPCCGQ@NNe^pkovR$;X=}@9o!Mp1c3-pa-ibrl_ z)VUYbC#|x^jr#6J{F0&2HlR_;R8q66Xqc0;XO#v!-5wl7f}pOW(bl9zUQL;XM0PT? z?mPj$&AeHYw;>5zi%w5*W2J}}#>`3alPpo~(^eDNR0&$~u|ktf=@u8VEXoCf--bWJ zF6(M}l`{<_v{+S~n?U(njHxudu!Zzk_AGI|x+A&%8nLqB=5n>&QJAe2tH7u!3*yW!8f0fx@ECRD6|6Zo3|xA{?{jwYjF_KwS~Zhh z5sUZCBiV{Qr)<8unrp`VZPTp6^(j!-EikyGL=9}qYIipDpZ4Id>@2Wkjyv3e+MLtq z^kCqQ06$v>Z$jz>cq#Zau6tvUMSZ0l0}vtOgV?$5yX06lv_)`jo>Rw| z(SUWqwn4IIKd&>iFT};0(aEZWiM`zO7x9;S zvE0yH;sH6kDD+Btdf-yCAn|CcROT(=Qs@uuUpKqgcNWSHJvt)OV)ItNsu;!xMFE0N z%?@d1ddz_YN6dGr9}`Eeq!io=BkN`@@h^WJ+R9h34AMvpZBLg6j2tn&jw-%Px9Dha zG+j3wT5Zv%(uzrjE#aNM-t@v2dNMsZ)V*qdSot9e7l^+4WEQK>WNSvXpvxN|DyXkY~3m@d!~a50D)9Oe2>a79w^=zVTK|U(sc^ zD9d`mEL75BA>E~~eEivDE-8i^e0*AGf3x$E{?;3T~-D<68V6&LC|C^+!prGIj zbGoFSg;n!zP}*~;fP2ca`ZYUpJX5P06d;Q?9`Qrq#;YDg5j;A~ca!zbk#+8dx17%h zYbX1Y&-CKxR2qUXTcJoyY_Bq9d+0rSFCKX1TO^eI{!?0a_)p|izDWJJSu9REQp}OA ztW!=Ayd9ShznKWL(n-JHmrFEape*qt<9`>URC(53nOedCp6`C(rEmzI)^+P(Qg@IZ z;%O547wUIt82D6fJdY2*TTQil;?Mth)J45}a&EaRC9M3=c(bwlCXqwWDh&9* zzTEepzqZNF^Nd{I)reP80#Em9I*S>|hn${7$x`Y7{$9&|KkIhSjl-e=g~fD-P55@e z*K6drs0`WZE1)&YogPv_QSlY&?(TnYHAMF1*S@7#g}IHPZ@znQeBjzrN`jG?!x4)s z##5NHX>@`t^Bb$uFq>!`5nGQ+3|b**gKeeJMaTB;ChJe;RdaZO+CAa%$7~nK-Ir>| zJwtnF=Aktq?%+%gAOZ9i&?0bV9j-LT)|@%&xNi?&W!>9sKL@utnQO{pZ=%!CK5D@& z7seuAKIE@??fWmr-Z{pT=-u}IwtL#PZQHi3Y1_7KYudJLOxw0?+wc5ta^8EBb8m7g zRmrY@Ywx6z^{ll%jTu?FWbrt$TeWnB^URm^DBr285lfFpfBIES#(OxtrWnuJ>Et*L zN2M*^R{sJn%BnzgPMzpunI)a%$?7(`8YExC7kD?TY!hMcxsbvAYtRaOGW+b@b1?=x zCmTr9(;JId&1@BV~9ix&a)>lvb$BX@`w6>d`i*CCcDqOBx``FCH~X)rfpZ(i%}A`q!idAj4f&G8MmPrr_W!z>oJ? z@h3-9p#NtNL<}04a@ru!+|<3;0rK$|F_lMxKlr1;+HH#AYJrx@$E+ZSaG8Csi{^w| zZD0kwW}>S^b|}=**;L&TLh`5m&XZL}yOtZ*crLIt>KqKUwiVNLK(msnHB`VEMbj%f z_^v3WSB3E&J=?ucUNmk9Uj#CSG z-j=_o;G+x4h})i&dul33)J98$4T?S+P=^O+a6q4;3DDBrp$z+XnUER5=`D3y?UKCv z48$mZL(zQ8b8AMYk~5!#eWN%K+tIVn24HCkE1LIOUm!cs!BvqZT9iuORo2NIlZNHznGkEgz$3brTp4@ymNA?-bHy!VRstj3;|m0&sKAzzk+=Fdl=^xYMerR(v!*S-koI0PTB9?-VFsHqDfai-jIzxo%6{8jFU^-H?KO-aq+a7$-zYlSK zGzWR`_4JZem2rk8Neo`t7K^Ehz*qNZx9rnWqGjVFrBwIqtmo$Vo)E#D5!=EjAw z16Im~D-4|9pWj~~W0u@XAY|qYM__0c4VLc^Ye4-ztucj-77T$nJ3IsfT-9G1`#U3D zF-UCL9jT;oI-xFGmVyY}K{J22bDBDLw*IE8-=5LGPWM3Vv}?jRHX9xVxcdWx5tQp` zO<+H-BacJG{x<^@>$bnYB?4u7QA=XT_}>aae}2J*U4?8G4c-oEEFPfeITmP_S@2eK zI2(Ivt{saEx&nqn$z^LyWPw3{?K;BZxvH^v5$w}^ln)02g2YMxKvCqB$z4^)Dr8Ef3)P&T|?E;z&#_T1C($Ln^a zwSz%>?m&fL@N3bF9wTc4euPSJulN+3jCGN4m~bXI9}|cTefzum@V~t0D7PhxoYx%} z*&Y9I$nw=>fbxUTAIjd6!uHSMYZn2cu*|`zgzrhN|GGec1T`f0Im9TUou|6gY43P9 zF7>`1SkFIkmy$nRjlF$ad$RFo+l)QE92jl3zZ|YLUa9|V=6rJby417tagIzC-tBRs zsTp*--8>q-lynxNe(uIXBM_N-<~8?PKe^4kkdr^qWp*t&0dzO}J-5$q;%4yVO2TeV zve(b`;1938y;-(;y&TH})LfW7a#)qjN@x9TaC1x3T+}kOQIAy?w$<7eSVe&|qkBkwNCRj@vc4$#MPnN8F{ z0Rc&)ZxR+4XqfGRugGTFdD%nGsAzi=o~kNpQcedC&^sH^cdTk%FTpvEP6Wj&c<-JQ zwoFTU7x1F-)pHE0SIFz|QKZe9ui)*YM?NU|>}C)f5u^9c`W|V#4(?O*DEREp6FPOb z?cngGX%4-mnHsfwIXZHQqx8CSr(KLJB>h-Fy~vqCB&}hKA$>{z)a_i|^coN-t}^Dx zKc8%2TRo0~lmon?A?>0fkvCCXk8g->@B+cnob)+4uH)?tkxpS zO@7|bHuNkwUF*GQq9|$Xz8Sc;b~5{_e*X+S%dPaLduO@zR!uL$9}N6LKp6z&01H66 zWcu-OLin%cW=S^?s>+i=EYu6IM2@9kw+qb;MQgygci)a3<{GJ(iY13cC~|%{!aZFI z^Nx7RJ!Mhr)sHA0el(6@OoNdpXn4SEbe;gcD&z)V~ zTGjvUANn?KURvw#yuNb(;ZI5mS|3)`Inv^IglDCZlwz_8Dkm>o(LHbyj1JO6YxV~O9F|U zDLL#vS8CV?hoVUi>v5!8tA@PYHU4?j_jFu^&7iB;-CS_HAxn4i9Kp_efkOOEGpl%u zlV3p~WCw-vET>Qc@6&(MZ$ulmx-+5`k?$u1$oVK0fau#9GmQAB|7H>BXWisZldawX zhMlfoK0y3!51qdVA2=$1+M%(Jg*Rho22L(4c~hstCJ*-Q5w;i7-LFK2 zIe^NmVA-X(WLU2n1;+secPEPFpIvXMvMZ|O*ne}+R&x2pI>ZLP_2JQhw}ho8O)Sw5 zKe`w;2b2`N!Mo9vKQZ5|`wZmMa0x4fPg2q1fMYUX>Jvo?cA4dAYezms-wuB4oq`K< z<8ukk)cIA8aS6w7EQ^W*fI=*co)CtIwZK}FHvRbaqrPLoLhVP`N$V-AS_}=_T``S! z5zyfid5A#`&ZH^lJJb#==Q}AMI`5~JUm|=SuEV0AZ>+6*{sq_$T8i7Rm7`N{((+ys zad|Dh>A5$uYbVFYeqf9I8FHH5aq-y_@!`YFw=C>C*l;(~L%=rso{MD6XK2-Q9Aq@x z{*q<#rC1eOPvU{;me!!Wh9R-;B^z;1!A3Z`Sta|0IP_OeuD zS4-rx*|adiGP;Kemwl!WJM92+*(*rL2vp-1+}=~fJ}$9&6~Q4y^?Je#vrk86#h>=o z)mbHtssS~I36y|=3^K2IJXMCUF~Ag}IdhaQJ|tj?oP8f1%)iaMni6=m&o&^(fBzNB z&)6ygPxdUGyaG1`hR|g17hC>DGI9}}iCD%MacFRUyv%(M+IG5_ge-6YuKARMNSTB} zAB2K`$|qJJyF!TVEN7yw{2$i7iEw;u3aLzD>_%=C5=9W(aBQ`DlH>8_N5h@xnqqFX zj?J&chUc|pld9Cx#ecCzLFsH(vjlku3)IzNY&prMDpbBqv4WrQ@u@bz#|f4^54~`8HN5YNbj8C%8PJm6kUqzc)ggy*K)1l+Evm z)UD9ZW=@ZyHK}o2=eR(}2U~%?PX=>><1PkYuWyX5fS^ftIY&rxsg=#`Os0P4vr{%h zAxRglov>|}U3hBwmEw9mO-n5-b?jouNqGnpCnbWSmq$veB`2>jz9uIkDipZVLW?6( zgofKntyL(9$x#qWyXr^=%&|nQcn#Y5_LCy^5xG){|Adu35Hk$@QJ$|=MJfOp`X^S3 zIC{2sDepeV*PkMgDFmI#M&}YTl!4-lum>xO;Ygt(ioA*Dh-8XwRGL`v^CdH^Bwr13 zh@dD>?0a2p&Bx8&Dv*1wC{1M0A9Xk&rO=va+nJExBUyMSODIcSH#J9xQ+A|ok8UZk z`LvMoms!A9XCa>?Do!i7 zx`EB45wgj=Nz$-vml1FtXcQpJ0>suu&sYI*+>_NtG4TiHSL88NG<0@VpHE;H2^?b9 zt%H8`+gwe&%a4QuCF_Vq^_-=M-{^dKm)vgqE|1y8_d&61e($2xy@F*!Op4Ji?MpU# ztpN1vSRd(2WC+x6>EiH3qI!emQXDxgOb^G&-^srCB$dB%+=3A4;RUZPHNzxliHs{V z|4?iCcjzQ@C=~V=vkT^Ot+zO=4G4Hl@Kj!cWp$OcTS`Uev16>cvhJ)&sU&63I*xZ& zEvUFEzJl!=(tL2K>(Fpc#`^2-{X1osiuW1wMd zqdC$WDV!*?CPf?E{RxyKREn!8pb;b1weNsPFQj;MA=VI+G=%QQkO~=1HJMBiJ5A`1 zvH8JKsIlXz405Cz$>@Vt-Xm;-mZpxzsk^2!ZDz|+R#s}dRJta4bXu|Bo2$IVe{-z# zK?ZbyDM)H^h%Av!whArBXLCx5WI5yhA<=vWvvzA@-U7wf)F$e@1ha;ql_tatARjbwMovXV$}dFUXu!a(MoN@x}E$? zdX0G1IkbJcR54aFiz>=SW{0SRIfNEd8=-gU7hivsy`qWf08a~#mx0OvsTYb_mRhO0 z!cIr>f_3+8-Djh21btEIVcwA#kJ5Z-An>dBDPQsz<8Ea@>0Hu=^6~^Fh0A=)vo2B~ z_#}+~4o%og)E``wZW&gx_~~f<0{>P&`S!ggTIaQinTnXO^k~^t+Y|?qIjmr?#RRZe0r;p;1XA@ zd=myP8m4e3nEDJk_tx@M!oSWJ2oRp^YhmG$&Es{zzET|9*MNTWm01^%gt z0;xH&9$CcB`^BP|a_ztI|HPU{d4D%;Aa-8sQguZ7^)Y2b9J@p<665qP*opR z%=>CSd%RH}HqO3&z(;eRw{zBe<@Ry&I^^@iOYbdlzVbkpA>Fh~_mNY$R zi%)j1+L~VbnT4wMDc^iBhGN=fER&(+Yc?+5XrS`ePQl++bNn@0dw(Q+rplc;Q~wY& z0`KenjeGg2U%i6~!F>W4amwK*Vh_sC?s)w5JwGm3{Q zx-c*>^c3BtbmzAdy{imfw>~Q9&VYaXteTC=QLj~_ zJDCE@9IG`rjtZccD=8&^GIT-PJemBv@G;|h%^$BRVMRvhh}88-l>;Qjp0vyFhqV7L zS;nTjWct=D-uv;sH(>W7ve=biOATAIG8JVjAT7ryZ;JziUhU|}`3VeavwU{KSFZG) z^~>|o@#Z5xy0T%OtIb4V0n6;SA&G$ zrZk*yWW-1$SNI#xib*)0^IATRJnVq5<)0XG{%sxU?=$D8(=4qk_w>B5lTcN|34*HE?9B>hJ3+Q#o?V1~$YQ=&Bme1+>lh#l8XwpIGNGbqN% zPPK66U2<&(-nG~3PQqD&{ZhLiSgp00U|}8X4G>jN*WdB!dvvWUG6MIrarCBbi|}<| zw$tPNE~K(XQ&hv!ru)(bDRw`Qw~^kr6fec{2uLtPbfTkVzeJC_w)?sL6d!%Z32-V@ z*kEf@<0KfX$a*iJXxO9`(uIG*lS=miZF_O|{(RQ&67d=I_F52@d4e9)GwjWM&#gBf z`9Ob=3<5^KuImd-Iso||b#hda>-`-a7Y_f%esvTlad(PU_j-ZV)+WFTtE4&nRv6{f zwrz)=^w0i>K6vKsc>64|ijH0!qJ!E%Fmqs`sNa`&bW)B@Ja^xCD2x7Bnd^3A>qr04 z1AeQm4)BxHYwCwvxL&C_?%W3gJBO!KU`}yauK{~l*?sjes#eWA<%bUA@xDFWNShgy zup(-0HgPZ>(epTpi8)-s7~5EuICq3ut!|&G)1;kpASuB>`m5SKz=V65+uiZu9>+QQ zFr_ax;rDgj42huDuKf$af>Z#e9p|K7at>|6P<76raQp3UI||p~Zi+!-!p|pNkD}tp zuW&1{;29dF8HDKVZF@pJcw&YflmzzY{ZSl+^;iuhhMKwK_IJ(h!Uf3r{oHWH^u+H^ zKOp#Mije;v{vR^7jESw8v-y9Tm^qmKOSJwEIGOGL)x`WiR-fGjf-VAMD#BzB463s7*tc>u^&a8MUv&Ng8iL3_Ztt$$AjxWEP& z=)W@NyAgkg+m!`?zjxnH@c$}f{ud`{Oo@S=TpNNq2Mb*Xx$Hwg5YW~Pf)5b61ytp= z^ukmV*fJ#dri7tl7@EW|y=J$e3TVoq>xWd_)Shoz@9LumW9MRH+*b;H>lrA-Re?6E z`g3vzb+40?h#-wR(jq2*j6H=9RGTHb7}z*wz=|6(Z9IPS{OaLk%@^2qxfFS|xzycE35Z`+Juw6O=y(zs0D&M|*bPVYJxD}xB_^WWi@5Hwb zjrRZ`1besm+?gM>Pi-OqFi?v=HfSG~F?=Y}=YP1#m;Z~K+%Mr@4v2IY@b9bL@sl&9 zuwDC`hfwP`>BpX?CnvZqp&j<&*8ih8HZc$nz}F>I1k~n*0{|2RWB>$V+|O@Z(GjRm zbu{3g*9yTaeL%!NaI)^%O)&5GIp2t0Q2(!2HyT=u$a(_62tTMF83B=g&^zG2fs>QB z2;+COV)f2{gsqNXLfyZL#qXAI1NM8!U|4}>f7pD0-rI)I9YFMt~( zYge70bP({V)|&-n1yFt6_{+%|Bn>n7&kL>n~^5f6+-}k=Hnfv2*QU zo7?tc#yVuxdsfgQJdLnrL372+JH(-S$CjKKcNZS8Ms44>+upIjI1SkH{8Y@QoLtb! zm&eHYUoKSymz`6l;X`HZPHoj9`Ffmwb4_DgVLZ^3xhFoQxJ;wKGQ$O?0mVgK0wkF{ z9JvIa9S>6#c@zGPz}eMKo8!hJ^*4u-Ukuv=^0cw9K(vstz$cL#`We~q->T8i7n%7; zYt#0EERpO?*@}hf9L6hL|9)b5 zX}c`#EDOf`4P@cW(Zhw$_*<#G$-0U1Vn=Nh7Bx4kE2)<0{CmEC(qcDWgT=5$Kq_$1 zU2q`(Wr#YZbSfrE+l5o>Jc@apoX+x3ZJbJ@cKQH>X0u^t(coHj-0`i7{iu;Fm(oUJ zwU@Pe_+)=4Jk>coRvdEQOVxFtobu-VIaiumPzonuqVJ0xb;xoq5{V%)qq%36QEFX< zId0Rmv*JTEdh_jvcC1(qquG^Vh0%`eEE)<@t~B5PVCX)zsFJf$)w&u{Ef0k5>(xJJ2|4>OMlbtj?9TnK086O{S}_ArD|^QvdM0c?tfVOU zkx1Xg=3ri2SeYo@SiW#nM(Yd&|1yUTNHno0D!=xXeRkLO&tZYVZ0{dw+%;+<%0pHd zRcm~w)P4l4nk^sXzp<@eg4lCfvvq1hw$5(B+IFdQ0!PE7E7A!Wx-NqtX9q|UriFqb zDSqIO*4yuk9UOA5wMk4!y}BOS$`d)l_`H^|2z1P25zQME#7i`ll6)F<l+s&QUwlk2-nrbqnwO%CL)RttTOpZ*CDPGpEx{=Q5y3V^^0pmW85-JbYXXV z-t1dFt_DzY+Zi`HAKw_>L06HogEtC=3ZepHOO^+RVFRTcM%3)Inj_w9LRi!^76x53 zbxPP&vaS_oa*jfh4IiR_IyUDz10!(GH~T@vdm4?d+^N>ahP0Kv)^;e=vPh0AN`ok4 z1$5tDB%*HZxZ)UY6?x;d91|PZ7cbC|K2#d!HtPV{L(<#&BBoi`FK=Wqo6uc5tPI($8(k3 zExXh~+3%D5XsQK!K>b=YcW-(P+r1)9t&QJX(NB&%!qAq{TJ2hdXu8g3X)B`#p_n{^LuuuKf3dIjlT4|$n8MB{k`(Nd`+2OY{<+D-TvwWTQZ@&>_M$7>O8`q<$^4Nu zd78TBJ)>wXOrc%AGXP0W90WqW)93wjM`_oSBr_S;bMpsT(z{Zrg)d9FlFt1eZqa@7 z?~(T1b?B>GTg5~RgBmG)c9Nbnud%+1*LQ40+U}E9?(0Gop)ESwp7IFHxXU_x>H6_h zpIa@g4v!(K@YDhl1sAsirV-OgL~H{5{LYQThG6VUf@DNfE!)sKb@7UMzXqofaK=tg%Dt+O=v_UK?k6(*5-G-i@PbuV%QW>H5@kz@!4^ znYS_9oF#UcY5isekn_jx~`5hIwz?jc}CYNo5O2a{Br z-(G#q#W}vxEzGLt#)3>;ho=n%$+yg|G({-q_`p&qPH!xha--2O$^|ZjVew;=f&W^C zXIi}XYJ4ykO>7byVpRQm&A{1nYsa9ym6<)bN}(anx21-aO-YKT$7;ZK)!B&??8OjJiDa1>BBBE`@Y z#r-JnDp)j5vApi(WkR0T!klQQ*nK&15(kDnt%9LoB4e$R2T8*<9)Bfi9J8t>EQj06 zb;;vMVxw!*#{_ec7%{eLRbPbpgZ)x;=GkGDd`WMHGYGjgEZI?PLw422e zcHVhS=o0&dZw!aPxR|lnaolcF%r&=s6=vlmhl`P<8O~K++Z_lUoS+*!0xG7`zzhWzo_H!)9nGWH=5LTj$jRMbq$k}a%?`o8L!Fm2MT95Zi&wsLRxTD)oYZsYo+ zkRJ{jzUE#rr5})q<(!+_{k=Y#2YctKkw)WBYdxC)A_pt5N(2s6%7NunuQi^gjp{kb^dp2_KWc)17XIf9hS0H^2+j_aK-^uqK+~mKB-_ZXUwC`WgAd7 zXlcjb16ZC9Lk086@QdeLBU#7vM}bT zw{53cSS0jgir4@P>l#Z#I{NSKj#vd?}H(Y-RVy5gs4^QlUib@}^dD72%w&mv#% zDMpPz<-K{m=PX?Irr=Aq<5=iFUOwXi7K};4z4{F~m+MzL%$ew-JLx63U(!Y<4^^ffXfrIE?8L-$rFY;C0Y8xzh&pjk!F;7Z$^DBr{BlJ8C(13Pz8VbdB~D=$jzgQjaUuTcnQn)> z=no%m4VG)lRuy*)aOdHVfaXBqI|DVsDHY!Sw~t}t!36`dr`lLMnbRQh;Y(o~?ps(= zve(|%9-V;`3j&Hd52XeBY@2J zg7u5EJT<9^wJozh*k6>>mrsiP%jt7jTM*Alm$HMC+qz503PV@A_?!W7dP$lcABae# zat#Qasg=6xnIpE8I}+m3-=orS!yxw9vdJgep5xHf{hlw)i!&mnFR;(@w@5|Ov)H0j zKw_9@{LuI+2ZK22^WDZ3G0~Y;pZ*=wM#&xxoa(n(HF>c6Gf#n9dwlHBLQ$(IDb6z_ zy&1sCAIGW8DiNq&%@gcA|DRYi6dqTyL6zXR`hILkZlQ4yuuV z4BB(Y1S1zzxUOIK6NFT-;-&NH8;vz%Xvl%${$e?R!MhFCNqX(CdxkCmnj%S((>!`=o%K6~9O-Q{$;tI?$ z%!2IZO}*Z>ZeV;L;?29`DKWflSQC}n+#}RV3)XFU%+#f0W8f?j$3ZEX6v7G(`SRLe zFO$pXr5?tY$)0ziO;Ci~a)=E{R<_wD?Dgzldb^nTdn=770()UYkGjkyM_Y@JKq)Em zadP1rVqCf|U?>yHY{#zj3~6N8!@q5_`B+Gx~55a^LHW4|-CEr+0KM6pT(kIes!@Fq5xs^i|O0 zUf8GhWu^-DLx$0sHJaif;I$rWVE&C7kFuQ6Ee*}_XA^N z$Jb*D6B@wnsem3TO!TQ>8X`4}D4bE@lk~08ovQ>Mzj8Xm50Cxe0(?hl-cop+n23$5 z8hWY8i+W5Pos*wC04E#taPaycIRy1#FBh(zSt>Up8hT21)`Mef4sNWLBi3|zhl>?G z+UFAUn$d%hytsvhkNS(S=l~B~qIl4*#0ihz-F3xM=U@mD`;Uy_Er32y!Rd=E6TXy) z7k?J6{(*E|dqN|{FFt74A~ahzwE3z2Z&OKuiL}>6a=U1Nq2Q_-lzQ;I+uF`3txDc$K$g zy|9hj{e>%TGClv=ijI+(dUDzPMH?l*xzixhSRL^zOZ-h4g4N)w)zsxqNH0iX`9ld+ zA^-QdmA$MgffN|xop)>8A~69=@v2!2?(eIi1us{{QFmG zpj=UCXzp35Fdp?->Pw^2fivnkll*=SJ?>RK7A0PH1WjD5)now-_Kx-Kx>002QXZ9S z)1lXZMq0;!1EFGfovTgMj7k;}0V@7a;0{VR^ZO}c6t(pf+cb^%haz@t6Fa@xn#~%7 zcIX4q2RVYCIYG{_3hQ?q{rH_!#ewF`C*h@Y>)-*QBnS#@C4UdR9Z8#>4w{6 zaQi26`aA3VSWant*Eus#k#S1br$WJ=Zucu57o1?=I_Vw{heBK=!F=^g+l+C~3KF(lX7h9)q16-}G@eYY=86?UK37PHonwZ0Nbi zj2CAuHs}|fzzGRKqC9%70j@rXB~&xoQ}Nc(!sSIka`X$>qRBPVtG{Zy50bMN=$I#| zh~Uw(V7a`-a=48FAY8HqNDG`DH|mL7?#9GT8`oQD-bXAM^1_*Nhy4PKlnX4{Yujs7R zb*YxPf!F}nh7GtS({Oj@TGO>$LG;!w>PMnjWwO0DRdD6w&{l26dAc7?9bqN{_C_nJ6ek^|xp6Lli-y{RDW)&|w76K@UpQWfGvI@sEHB5% znnDT93cN^7>TGl7(p*&oes8=Fdy9O9ZypI+Y)xet2kWzx<4?v^_#^e;E<<#*Hwr#= zD4Ua06flNedC3r}$%c;D%94vJf(km+jY^mdSpISUH6wns(iUSD?mTl>_sY%hxMvD)n?&|}i`(EPZ^Z7xvaq?7A+ zxZU{6ju|SWjHtGGrotD~rO=DN@k=F$Pe&fEYS|thVj_*wI83S@54-$NNe@|~ClFYheHH=JaO$4H89uZ5CLFtN!tAv)ufJx`&jd=7MstbP4!!{l~b4us^hc4L!iU2m2f{~{7unjxZQcf@bEfR{g*vCTAB zC9IHJ>P9pnszY&j2^C4mt*TxtjOkO&hYp2XnubuBWsN-wW1AjP#8x&s_k#JDilaDR zq;e%Pd9U1CNrOG^(g6o%?#X0W3HK^7-=*`Er^_>7`_-^v)XJie#5#9Ol8J#-cVM^UO-mk8tcd(%MJf3h?Z3#`TKcWapWN>? zc*MUD;w{?sAanK5Q?_*dSOhas%jc-(qLJI>(S_0k!*0C?u^}ewcfJY&#oO;mFlA@F zAFx#Yn3BleupKAd&Vlba$ZhT?5G^du5IC#|#mP_waX8mn`S9B`I9S35oeA!5d@ct; zMhJ_BC%3lzgLpdjcd6A;%d6Ze^N3~M5q>f9J?pb2etxaIA%RGs`bfI=9T$m6(Z(7q zoY(|h%Fy`*J%^KjG0KRie>F!BA}sxjz5il8zt*4}nE;+|h71bT7)6H1qYqm@Z|IR0 zs?FXTv1win4caaHBD7j-q**9g(&?T>wSMEOIaRwIV{OdLyFqwYrm0Ac_|+Y0`4GAg z@89^k*H}p%frJc^7I8QDu9UScr9{@@s%z^z1Fyxi5sAbdDtCO7F-{O z*AQ2S4}Hxha%j4$3S*pJfzn}{hI2mstLPMz=}CPSPL7$L2paahOok(IG6j0x zO8%*#05}+TcwGs20z`jr7>3;vN||1^nrASa?PH`>(p5;040RFn=~H2Pd)>Fvq~tXG zM``IouHb5Z_JO3^LF{Z?$3+`z1O3a(Kb z5C&8EMybI#(!urgly@#sjyIe|3_sku7Nl=IptqvWSEa~6-T^mBT+$zNE+7i0)Ru(L z;_>P#>np+=X@YalirGwzy7<$ed<{H0{nsY{W_&fZv3DA^k5U?{`8E61%NLdpHs@B* z&o{OCA6RM@X-s~OjvT+=PQY5YPp5eHe8e3v<+CL8BQ(!^1-d$wMHL*HJEWu=PSK{r zZwt`tz~G6*%8yd(`pgd1zoZk$&G4#pD{dUX4xaE%Jz;3caMik*?pUE!L)BI8R0Cxf z5^k*0YT{s2A$e(V8wE}>5^^1M$_VbJay=m|(G8~?yj;?;x2W$>b(U}p z(Zf@jFaPuy7hTHH7Al}2bT8H;@^5rR5)cbMgj}E)&qfEi7Fv5-OjoSX$O7HF)?d{q z7F_h3*x~uyGrz4iZKYPVW=apS-=OGjiwT9iv29`Fy#+fi@IYstYNUi#C+_&Bn%tcV zR_OXw*Ju0YRnkYpO?EE9TWc%i)&!Gbz&34?OE{T+;0uZ;sQ=&Q@*MxyxjZ}j|DMaU zb8;~M*V{jy@_#J}I5;`}=Y-@YFqLF0bhauMiGLUD7K5{dn;WDA3p_UljcKU$I2%;w6q&yCfNjPtsu4ilR_bsZ5-=;8hm zcqGsvi?b+@00BQc!f4pQU=h41SKv?LJ_BYTVvPca%q9P$BP0W)2YnI*;ms7wE`xtX zCb54Sejhc-Ff|Q0DDbPlz?>iEUqnNIM?Ci;cwRrOLdZa04Tp@Qy%{|yieXsS%zZ7f z|565QA2k)#~|TXFx*! zKrg`JWvm#-o;SPTjX=bJmv$ges&fFX8N(&L(NixB2aum0tbbbOORl}2*AEC`MHkeyJoS)(wrgM0r8=j1mA#emJ(mV}HE>OA!JJC_FqsHLaZg+7Ph$i=^( zSD()>+a{j@dt--owT<%uqc4xnRv-1Pm-bqe<0nBq*)BO zstE)u8UWBG=tU5C{oef#Bw28_w-WHZp$=vW4H5pWdih2BRjL2d zTRQXpVps?C&7Dg2nNzP1xaj@$4NL*q)bn%u&A;#&H}Qkt=_mfyi}2}pq3G=7{8?!7 zRsH>AE-0rUUfcWh;_V{5?W70d+Y40p!^#T$(_Dk4k6o6z@MEbOpZ9?qA0UYH(=Jk0 zNwkP;T?i|xwecmI(t8Nri#~}61!6VuJHHnn1%OVE@XFuuQQhF$=EtIQ^Y$tZ)}xp4 zBUcV+4BhzLrsESN1V9D=JoYx@Uh#ebd%NGP%z|IOh4lmQY%y>=Zh+hDX5jUq#dkk* zN)i0U;h`LWzf!*u!=XUjzd<4Z?p5D{T`!LZKtB+NAh)aE*xN}N5Z~}92;Jg!KXu2b zfLnrZknK{j?|`4B_-1Tihu&#FNVlD<-rL+(5SV9B?E{+0zty=R>nouxdTJ92p7u6z zQZkG-*xjZF_nHFEZC`^UG6t37FuJ1NX_APov>!US&s)A{Q)w+@mbkW(|R6bZ(^cq4dOv8CkEtHOLWlL5xuXx_od@>NoP8G z8fFIe8aKGORfR0$d{bl{hcE|wAgOXp#~a5p2unu<92Je~k+a>AWc2?1T*fgw3sq$g z`|h}-59l8mH4mbCGwyWhR!*F*3iOK@2usDf39xeXpA)_kE2P*?l$F{Z9kv@qyW-g( z;+SnBE*M|Xd!nhzY+xVo-I_O3X)vh{4otW4zao}DdG~2P7HsyeR^<$Rp9A~L&YNLRhA{J z*XnI3VSEvFDtdU1UhUGcvsfF~(`X>8!@OA=J0_Su{=P{2NyN;?>OK*W|M6Y~{d=Y0 z(!ro6Xw74-nAjET8p9aW zDODtiso{RG}W1C ze<(Fa)HCc>@e;<0qsAS)@Ebg z8*|=&9ixG4)X?YFc~_Ow&Mz^~(2``&<5{|cL@IQxRt_8c+~lfC>;B;80`(SGvamS+ zDf)CWGynhCI;Un)xLC_>+qP}nwr$(CZQHiawr$(CZS;4mtGez(|AqCCT1iI6+~}sc z3V}jpE^}cwoSi)#N2}FGS^KnR%(tb_1do}KGfKA@P^8KKjw*|ayqVFz-g{}4vg_Qv z4pIgu@V(kScgc~4o#LtAmdmPW$BSa?{2)aQLdI6PRy;>$IQ0*L|Izu%$8qP`^Tt)#Cdg_vf(RIl1eu#V7*F? zi2tIdUN*xS<}o7Q0`u%LW>7F>8@N^D8CTyvP-+wjAUi9jl2Q0}Ik!EacNQD|)3j2) ziyjsUq*@PkG6x+(w#a|eiBg@s*Rn!XB8h1t@n9N6#w#1O?1~Jw2<%b~DORS}KW@{T>am!&%!U7Ke=4HDZ*Ogcy;kD`x}nc)&es%Qb-HO;eg z?Jw=FsY!xK`PaEt_?o$y{u*gmVndXz)b%xr_}VneK>=G0oW~(kEOzMAxeRneJA|Q@ zq?5Mv3Zy#DYgJGodMn_^H~cUaQ)R=P4ZZqaN!z)feU^5yvadnm6$_!JErAGTiWH> z6|DHUGy6l;4t%cBkq=yV?*)1;RksCA1{ySPE!kfOv}Kka)3p~TS?>`K0<#fk6>?Yx zKjJ6J8*;41c-x7=sz2+4Ny<(9b#;xaq)Z!pDa|u{xTB=x^JhbG*Gy=|Hj0Tj)~1QX zEi*rtn9Cp*>6pG9Zv=1UHEadF^{A!0X@QyqY&V3x^{fOa^B^I6Wv*w@iiXY|&ddzo zkkbp*^OhYFSR6<4Xah_?{eN#xY@h5?ySK)(9XH0ljpB3KkCS8yZ0zu}vmTVF68Pjq z|E<7&8Tej*qBdz0b47hy7M_!)W+mQ`sueHzSbhwjlml^G)PE}c1V z?m;g*+AF>=VtKAYVspZmJ}c@Y995)UcTn;i3EW^x%Jx{GF-PEk#!a{xyxB^0dti2O+{G(d z%tcox>rRZ^y^)>J-X!tCMdo3rV{&4BK_-^Mn+pR}8yt3&sda%EzRvHUG{q!sE%+oCUYsjfa51q}p$ z1{B0*8k?=&iVxL{Zu6L+ljVl>GBV-}G9eH60hwmR26C)bd(*aCujt*-4(F49)Msp* zvV)#ow7}#n`GV(OKB`#XP4PFZdXm0vi0Lf*z--kVOw24wPop-WCSvwY9Q|-NyYoYF z=|E-exD+{)8KWccyj~iY-!$qltx%&XEfyAE&=sSvq=(`9)_500gTvg3bg#nXM?q8k z!&G>y_?AJkbg96XI>%k;>Am-L;K zqk!~a9T=%agw}SDS2-J=B+4?ykif-WUAq5A^uZ{sRpMEy=*GwjLv`1lr@Xa8AOP7Z zq)p4Ul&B|e+nwA={0xEs22+FkTycB15R>dRHW$mpV*4W4Q4|jxs_Z-l z^hXf0mR`ZlHQmxm_RgH3?e9?PuZ!_1(slH$Eo4$PM0faVOXgxhZcKHPW^;>q*##=i z>0E?(9xxLsjE;w%o~B;I=}#saXV$=}Q+NS9;95Cr{3I%W0R6iUN6Fl)kooWm!zfcN z4@#Fhht_0|Gt~Fu()qT8B_<|fPrALFUUS4Nxr_TjWg*VQ8k#m`@$K=jFJVtBVF^bH zvR~zX^QV&6-jGBdBG_U{sa8D4oLn65nOik2#-G4Vzd(0o+$|jVro3$$zl#>9le2(= zsY#XE&^Eag2xOgr0i5RC1TzRt^q|!-hqsLyxY?gj`nm#(@}L;zUY>)&|C9w4 z)-PF)7Nu=nx214hEK$%kV-|`kw#JpZqlcC&gksgvjZa&WPw}PU1$M(Hch6Hj+8D4b zr1xCOLRcJU$!v9KOaz+imFd*4!tWC(uB&3f1Ni-^U>`5soKQ>bg5D=z8JdO8tv=Fb z?b-(auTsUNUyA>pMB^}js<1$QKRzmD7_Z-Wro_w-G-V{HjdyXkfvZtE>s5~`(yy|f z@7G|)mb50I7a{CW{h>GLKTBG*(7<#=)nB_0KyRID26<~KDosJ)4@nbODO{Ii zlyL|jW_8<9{egz~!OBuClEbS$KN+o$g)!Zs*Quaz*u{c>4g zKaqYIcN=nWGT+aE#n8236a$(M=j8@jWIv2$etcxF+jmDy{3$-|!_2d_^{w5grx^L2 zZ;&k;3}_cA^YP7APi7hVkFPD$N6|>xbeMe^^@Pc;VvsjAr#y@a1AQzggLGHXPA{{Pw_}c3Y z5k_;%P|3mfdLR&cj1m!)BEG1R1=STD$=B|dig1q3wK>oR2mY%&{?AN|mK56V;>Z(F z-jtET0{UU`Uyx^&Xal;{q=_-%d}Sv`z@hl%&mja3;1R zpuF53=Zf{@T&osovs5GV%YlCV3`%}Z9|9i7&K!;3F}UR9!lz6BN%F5wf}O+XNcsGU z)8ks?;!0~_uzgc#2u_Ip$8^|En=?RE&K;&rjdm;Z6!Zd9XrfUZ^jbL(=TB179u>eo zLSz!ibB9E3ROU?e>?1%vxiZ-U3oePtxv;c5MRDOuY7nz z`ClZXx3woX1}@V9i+3nl>6&zzN2%zC#sRR5N0t4_ya6lUCV}Ukn<1xvoi1R$!S++x zU}Zz?neY2y^GLSCv(X2T?mXbi_6b$Y;Sj}F%rGg`q*&^g)g;xP?4sdcdP{T>=P}>Q zI30#FIasytONV_>wyy$@fWtGZce1?GCgtKk%YgpNiR*Al@e~uYp$#Db-F&$Pz3WQ% z8_Y@)+%0VRrRg^6si5g>-L_?VjFJbzk%aV$K8#2Zam*VA;nBRAMJ`Y*kF=(b-ixhO zTBp_#Gj=r`DMd1}Tc;8KNz@?WDZK8lUiqLW)M9|nw*j_Z;fmBD$kZ;ClB(Vyc88Y^ zP?2~)QU4C*gCCd2h#RJv`p>md%lL|CiFjI3X8dy6Rn+z(gVBA?JzcHnH(#pE^rU=< zEI#(?&dY?dmNg5U6fq;{MUD{G3ct~OksRFBbtDA*3ga4qJ&%$=Vd2J{WM)2)5v znd;Esw;vCxNasH$I!M5b7{BA%Z5l(+QXXP?k@7{-LxxVJ(aXi9?Eb7bx)N=;bZN6vE^&i3Mxjm~_n! z$H<^}%>0MPbL5s+u+r){xPc;1_0%Ga(Zc8axtO1o6 zggU!fyZ@M7}D9y(yGNKBT*tCG0>3Uq3Tt-|5RU8?6iqwwyV_?qBf9$41W zMmsaUxOhK&FpI|ITuZ)rUcyz`GdMd_5NhwIXNQHVO}hFO!U?_gUo`DGMK|_^f5+&A zo~-7AU2LTJVU7Q=7Cm%`^q!tx>Un`~%(5T!x^l;=4peXlAOX(V05dQ9i<%jAQkja5 z5d)080g25ATg@3oMy;o35GEPiTE$77$oq9j=~qpPN4^`R6?MYb1~~@{>u-zOZHC29 zSvy8VV5JYY+;s^1Z*HnUpvIY}rZ~#O#P<)b7kgVY}5%BaO= z;qIuyE>M_D6S49uXk@}ue z%3GX3OD?}FezjM0M`|7q>fwnxk!dX`rXEsnVO3AbyzjM#T+b!}#`8IEm5n_O(A6B| zFs3G$4p0pf2zxxa@AW8@Qx)t(ozB0K=)7!qsB^xm)b&E%o<5yNWL4~|Wv|7%pkYhR z*2JIP6XxFz4}fg*eM5r9g6V%25;#w z{w!9Z9!jj7RHuwSuWyvFiWY%v9P{~|P7}Pfx7%dMpeLMXpcSp%i;bFR`=%+HGAql^ z4hw(`H&yp5RXZI|yStvNa79E-NVvizGgZs)ir9~3E&mcV#hq&Bcv{|bbQ_#*P^8(| zXp#38tyCV$s7e)$djeo$U3mASOQkO*FFTgyRDZ9Jo#ga#$QWUChs@!z)&~UDqsD!2z{)JR_*?o+6V)!%t zE0?fr=wVIM6~P%6#}C!>3GOAw=R&S=U5y^`coVFvV_Or2A;(Zv`EMu~Ygop8azv{h zjI}^@Qo2&bKGieSST<+yA)VU8m(f$A1kK1q{u+^9-Kq=uoT2y7p~_9Rcg0653g_5Q z*5Ve#EZN7G{Q#_{&~T881ve8sn8lV{64`ywZhbL6e)6Veq}ie!f%Wu`%NR?fxW=@- z)sO>;excy@QIbDePm2dG6Und8n3Tc|nvFNsCJ~RG%?PTD4hy2hQ~^0QZzg;9_svvb zou6^hPo7NJF(ZR&q}TNwDzxS;G?>OT}Jz<3^^jvhn8Wt2+An$+AvbAB3@TksfJY9LXXon)64R-Z_>PK}drw2IS3= zU-wf52>*;_Z3MTG>0#^f?=LL;Mrw?)q#qXoLgvqjw=YnP`xcx4z*F8k%<7C5v`K(2 zr)^@5g=+COT}ZOGi?>BbqxGx)Ave!`bKI<#v-!K*XRt+wQ(LqI>z=^?2H~IO?|GZO zGaxhO*$3gapw|Tk4zS7MGzjiOB)u2;bZ1jdjM~%rBda=8E_z;oS6rZEE96Za{ zcj@*tQ*8{JCM_{h^IwMEopnqVu>f}iG5PN>2oIaT4A|c0FC~72dT!pEY>?>+PKXq4 zU!!^}TkC>?dITJX`0M09&}JC}BA3G|p~CJ#kaFF9l9$e0l}t){F9#gf3My1-8Koq>^I~x=wzYt^|M8qT`1ai#7 zN43tan8)^C7u@wKz(Td;*=u}H;lGhSA5>Wxy1y0Ahl#mfc7)en?C4IuZW{c~68i2t zjU;@g4)#}h=@Jzg4~o(9c+$r|s#)^AI+^c_7|Wz#6-qQ##`GaXLwFMF!O)3i-r$r0 z+GOU)2LNHzjZ*j?l`Da1PkW~x1`%5~>llPwGXdF1DU?X6HP6MulW%*kj&S`ha`#-d zzB$AZ@H!ntn9*MiyTdoI!`_)KYXq3B!<`{+fR8zp_EDn);Re#%ngH!S}J!iYh7gyNVPZXN!mZ|3?n9+VB z8c{L*ZI2xYFxu-peZ}byMGJ79(F0gq#8dA;>ms1@Jx_rH)!-O?mu`4SQz0**Lp@%T zQ9-CVg~#~wNwxx_2CFbIc)4JOliWmaNaE-Tz%)E)v68J5MHr5~WhLI;k)y;3YkN?u zl8n0|mi+R>zRCjs>0V?!HCA>#T2n8bFOTYk(n}j}t*Xc*;%ft6zevV^K`gMm$sI(*l`T4)bJdqNK8DjI?PxKjBOb=cGgY`|H5~sFMg@FEn>ymwbfT8AZQS7|dHJ!F@p(k!clecHq zqfVSPg7cmY-Q$&vMXcwhSD=wj<4sN$V~ti4uPFC{bM=t*OuYor9o=%52_c7QtH-m} zE!L2}q&QZfC(-SAzESeb~&P69KNO+G4?XgXwzVTOGM`>2P271W>v$7G8?4}PYt!N zv7h4*PY`ChelBA1BTmsTO-n|nI2BdIXIS z*ji{F4Gh6t2i+bI0jm)U9i6GhLuT6#*Kv~f%}gOkWylWd^BbF@uIkHT|Gm!w;Vim* zj9`m0wiO+&3%ftjlsnXJPKhNVq$^&%rzyd)|8eWE(c3?ywk3L%V~%BhWqZI1q1^hy zG^ajHw#o4xa!O^dONv@*fk#S0mK+z@<9>IcQ?e93uW%d2ybok%lzTyy_XKCg zd6cHgBk6597bK=4G21#UOo6S0HKcWx(Lo$EyT`M&V(Ea@^(4nKx{9^mRiMrvJZgYj zPPn14v$0(B@NR5oy}B)Wo9%9cC_p?nX(N1Pg~M2(VZ`y2h?~RI>SDC6=?_`dWX^J) ziJyEQ3w66Ce3?DlJ%sccBsSSQmRMrUBCu!qEQ@e`6b;n<#Er9BpPr4bI4<w{?sf=Q$8S$r!$eh7 zE?rNz8H|8}9J&@FzI7`f8pN?oiKPalAEYsZmBMxVyc|Vl?pqq4N+n~UEtK7V&oTCL zI%9;BeFae$2vvyd>ApM&3M3`rx;X1ktj3fXr#K16QN*I*w6DbtmoJM;Q{lcOLgu%P z@$)U>^*k%0GdLIfmTZ08z|8A83Ct2|PCAmncCPHOlb(0yXT@whf?5Ls=pxt+Q&7$H znH;7oZuhEI;9}}PoV@BP6X%=GE|@VwVidjYGiCamQ0dHTIywW7cx}nB@ZL9@kLrIJ z*B%vjyLom}%LYxylH;)_*@%pflZuj*7MQab2?4+Wd*AB}=ECSL!@5OzY??I~^<|~k%hqtPEP0#eE4tRkG{bsQ7wAe|uu>k?lsNXk@-CeX&tImBw9?Hx*h>NPBJhiS4(4sujeu zW+UV^p*3r+NxPTolBALwa+=HyE#qATkjrfJK@M+vE9rYjDNQ11HzVexS8)+J?pfjO zqrNI_Eehdb)l@|{VMwd=jfzU+JOFbPf5N+Y@+*4kZE^jiX{kM8&24u-?;y;k zjmOA*>OaIOL=mj4Eu@sS;WUgKtyM82FzUSGlF;y7S07>9or4(Iukm>?a$mJkV4ea0 zQub17xl+Xfi;Eznj`I(Rha}Z~hF3QX`|VFJ^~h<8(*z~T5t3&2y!bNx5gOU-m85c8 z8NKzSD;pE%aA%WmfTC-}##a?A5|zMNmcW@IYZOglEft;IWWab!J4RQ>%`E2RdXQ&h z59W9iW&)ekS57yVz)_*Fx1kh1TY@g)8gJdZA3w5L{s?2w{cge`~UGc z|6BL`|2!G&oc}8wos*N{|5-EsH;==}$iVi0ft>$wLfg2QIuX!|*%-Q*ikKSPo0vlJ z@j*GeIGGySLV0Y)wu35U@1W7iI8xM&0FUhK;%-#$r<{~7Sag;Y%;TBOAAygq_vatoor8om*LnckU)!Z`l3&WA!=*DKyC;J2M-VL<_xax zRuSF8flS>$gk}aj57HH+yFHK=uty5KJdNA$pE?>R2R`50==!5v2-*_lnb8#hC=W1< z2IA)8>*VO%4AKRVCkJjpSqZS5+aKqTRsC(*5A|Nn2|(vo=Rf#!^241_dxSrGN`SCD zFtNQbwYq?1U)3gAfz8}OkV z>c4UZ<<#gJ)X~(nDde{{{=hx0oPB~rYgzyYXCR(I{dxCoVyoLqoolf&VHW1G9vFV*C~!6SJ7XS8a75fHB&k)IzA4d4bAz$?gx(+5BQ z>IC#x_zmn=H83{@c?r_sMFo6qZVl@9De&gV>JAQU@E_L0pZ}-w-4-%C0@~0FIskxX zV683w>|e}3U{K9}QvT7k?gbRXk$*l0y8r$2c{cGLX_%%U9K~IKtgS6CC>(WC zpY*3FB`wSg$Y--H1i(hr=}1vpMSyka&eck z^LGevqz^p^@_wgbHBWvT1Q_#&^utPyPkw$8d-a!j>)-zU*ZA$8@<+Y!$4>0Y4si_6 zdz26Mhu_l?OgnrG?Not9xS0JCG)zjWK>Izxo|{^}Wj;QA>;g;o9=!JH+GZ==2+ZYdInCD&H1y zh0OY=5SZ_F-Zz)(3?fMDPmj%x&)>g2GO`W*W4S7igx?>2Wl2ptkmsL(**|a#5z5;E zkZ1J_tRbj7?+>4r58qGtg8iv{2<{;9M-2(UVe*>@!U2f$_$Lvh0{|E6Pl^W+zS@U$ zhfMyL3Id4p`6nSHuL$#(*q--3X=n)7g+Jdd+W;*SF6P`Of~kED%RNwZ}fz*D9|#Fl*O(dy3F-glzvO`AGS=q{Nf>b7A+v zo7IOZ&xm7#yQA|5meeV$zHoA%G~BxoSd0O9ix2ZaR5>W#Ab zrcNtrI{0P_{rDv|Zk!|d7lIGt=i3_}8#M(cl+xUid1?}!xUxTVv0;K!pXoHYi*ask zM^n(6GOB}tqvMzMg1NQ3@GgC4)j&#`qVlC(!0H(7*0LK6v^5j42vN9bcl!rB5HD{h zo*NV%x2`KpC>#J>U;!4+6$qs4G_b?|?DZ{?3V$JB3X59(nD$p{{OMYEWa7zBhdb6zXwP~!A6?!?Mj zIO4)e=LlkbVFqLkug+Y5&eq=m@!CBtSu*p^u73+)ZCVt2IT~_vo1h&RZe_3TaMS3r zkcn(HE0xWQE~;q`>_e92syqqXdLl$p08X}JkMt{+7LF6Ofl%K{!Yon#5b+bU!_nOT z+%X??wnrz75C#J4@k>4e5v0lyse4Mj7fb;7C~^4|AO&ML?S^cRNvXeH!u__Ke5*vp zs(Z=?S`YH>nJI1{K@U_Ea{RnU4fh0nijnqaVCv}p;qcdpdE#wa{ugM1%#B-+nH>ya zbEAO3n1Z5}Q4qOuGBCR|n!Bd95h|@L%#7eijLH!k9BS{cB=z7}8RY-mqv4RO(PThS z{`WY%!K@iutdWyddxpikmnd^cqch9Vt|*)0%nf5Z9kqg?H{fw(gAI3d`&I&57BmZT zy6RMl?+PUIApNa>rq%O>>D=S3>Yr6juZnF55h-(-1GUcd!yvU__s$u{Q)_)#(Uwc- zxu)FsI|h4***nq@bPphFL0HmFm{u=p_QGsf61QOPoZ4DVrjnkgSRGbCQ-d|% zMu;>iE%FgA)@+|$6iO83T46qeMbJtHKnQ8TJr6 zo=OIog~~l@3TL>*!Q47hIB9w*tjxG9HCN0p>;KvDb*P2>wt&J`OP;jL>6OQ}Pd4%1 z1T)H`6~q6dbLN{Cf4BP55|+<7$Nqr?A>=exT0m|DiYYaKLL;asUsY1>q+F8bCFyQ^ zh^Sm<0eZ(sJ@fLOrb0|4uOyVw^ zc^oPn%3T2IqiNeYW(4M!Sh|={)W%DE zo<=_WWR7FHtT3Or+5o3exjHHCS@RrCeSsa5Ob@1N>p6xae!J6nB<4B8k4}-Ta=!dT z0>6YRJc#rlvK9ctSkD(j1KvJ1*W_1LTim!nsg~Ma#hbD&;bN2rjp{I#MUJKo=G5_N zOKCtZg;qg&pPBPOB5vhhjoNGl37p_%i4q#lQq3H?YN+M_C37dUVAvxFt=doVo>*}4 z1Nis2XthV~GYF!-YIY*!!o5e%>#NM=d2BFyC%$$zf}?In4VEcg-!fyh6d1pRPZ}$j z5){cAR{}H(LrB6smqL8&d9yMS5syDbdgcNENlJ~ds!E`8dxP~5$NMeA#heCE#T>MN z#QL~!6F=G*+HH1V#0TN%+cJf%KqcJS`MRJ%Yt#c95(yn zz45CF2TVU zjG^i5->gO<2W=1pz*DyB&?$NqN8DxWcF<>gg+^J!DzkC*-F?$5Kxq{N`j>Kc7@s^rlUYsqG9rO2Cc-uE`&8%QH&v)0j--Wf+PvWOyu_dcbR` z-wTzt@3FRW$UQ%9`ooc8fY?h!r7YU$P$uema@j-}PI-eh!WnMrhiS5(y8Tz$!odE7 z$<i>!C6! zUGz{J+Q7szM~%J5&geFg3w4(=!e2*_-b621hlj%aWQj;9`0{kXBYpx4xNTJ+zSLfCwUEF^cuILit8I+W5tTUHNE{d~;nmc^>UomOlsp0nS#Vb`%0z`yR zYb9DDzSnb}VC6;osuVaHQW)h%DyxU0FuL|x$ksu2lRBJfRN87d=Pg~d#<<+Vq5O(@ zWTwY{eS?+jFfI?HP!g`imrYj!#y&u;Kx_%dCV`e!+LD~vxnYnHpUF5B&O^*`ODMm} zu;LrRHXw1{@n&deX&tYs0G=K4qx=Rv$t6Nh2C$N>p`Gc9++8xzl8Xu*E9iXG(}moU zTo6;Sa`{~UMJxuGn?rvt@1$|k);)1y@u}k1UkJp-lNgmc8&8Kr|G2uae6tns% z!zKKO*1rJ$WFL7a4=qd;ro@0>4khaEhMBMGl?~ofy~wH7JMh*#Wo;;KEc)v-W;CG6 z`*wj-tWJqcRP9t{7}1aHvISt`9HQ5v+sqsxhtXV59J~?N&T-pNZ}o5ScHAy&-#A#I}4Z$V8j<@DI@MMET?ROwx(tEsaU*_#uMPO zRe4p$ALfJsI>HK=Hy5qTPl6Wcb2%km_JsTBbJK0yUW6@8ce3sC_4v3z(X|rr=%d0U zE@ywp6dI3$tumV!+ZcXY>V@^?vRk-Bujgx}H&0J6b9WF(>FN0D>SG|Dh;T~PMC^NT6{q_U*a~BK zN^ebtqIR#pi}(sfI-gCx9@(Jqj?n59R?H|%BT1_9rbf+-4{|~M)=z)M#^6DZr57iq zNW)mjnYSIoU!S{TCp~y08?UW~sXgZ9>fzOBPh_qAXrSUkc1@MlvpBpX>?_w$hWtCk zj!bt#`smKLGcQ~%nOgyDZji8d^OI7)UVk1_zQ@e#bJ^Rkcg(v6Q}|>wiP3jsA31%F zLbEET6j-xTvt!ij_TT%oGYJm>Wv>0hfGqznO|BC9m;>nc&?7**_rSvwH z|0Xj*#}8UDCl}*W+Za;dL$5U+Tq%{34S&wI@H_Iw#hli@)#Y>7?KDwEl5#6+V zAEHgwOI?fPu2%}hm`hXS)w2{_C1*AM@Jl5)Zqk3Kb&@dx5lxRi zi*hGZl(+jv5cBKszXypTJ$FqjyNpvw3h+?Uo1bgZeE9=IE7wq8M1)&;4%t^FsnG+O z;VSoaKv=C0?mieLG~6r6;5|a(^0C>)bcXC<1(;#x?O>9F26p}JC3d)vsJi$U^pagS z1-T?V^`jpy4H{!fAVXC!wusXYZ$=KBj;OM$Yj8+T#ca2Jbn9kXU3+GfN>i%kTswl& zNaKOGbf1eR=DH#0?&Ae?|I{auQpRgPMw2rtScbmDY=&nA1N+zJ9L)jMQX zw?$$^S~e*N&K$b@75!fFH942tgnSec7T=uILD_Q`p5e6&!H?9t0-Ph^J6a;Ht;}GY zV~0jl6KV!7ITiPemxG+Z%<}5-bLE#;0EW#aYYq?S&m5AIm_ zW_}C)NW=s`*u1$Uj)s(DK*j@%rQBm~x1_Q=^wWrO4Zn2>VJs&{ zEAq-yq6Y8r)G^YLix_|&$I<{&d}@YmyUA`jOGhK28k0^zziFn@$^IGhs!UUx-$YG~ zKONN;(4Jm4l%9CAm zA3jBfZPFav#jSu;729u*zF>hxp`h!AKWEfN0Q1S>698qAgC}5+Xw;tHnjcA-DWjUA z(K}0!cR)zY5IFy5;vKophY*F*fno)GTMdSr!r+gB8<&^wL2N?W!ENv`@12 zg?98H?@hq>ah7%4?QvZ6Kq=_2K1?d*>K`Pg$9kz%dl-J{YQ%|z0XyMGu-1Z|Y~FCRXHf%J9NRSKjF zsARUKYp7y8smF!D3WxSU{^735lbt9fgBx13U(rkT_W8ViUb+#wN9d43{4$WhXGqWk z1RDB{vMqgc8a7j4v|el!-P<}4oV@;SNr(;n$lFMLpyq!J6}h3SX) zWGVZgWBx{&ifS5jr6h-#d35?HT{E0-yZYa73?qL|dKmY{cr730>HDVc+}X+zTsx2i zz`xPxyE~UOrR4zRCt~9>nDpveXR706=K?iYGf@gTDj#u68tzzCp7>*EXUja-%J@|}09myOq z9{It(EB2t#3trN}8bKypnI!gO98yOWghS|F zumg{fQAkJ4hLVq_^qR#rne5opQ|&5 z_;3|c5KRt}T_dhg{<74!(o_JoG;6!%jvWp_qK`@VONx2rF+m#7%eRuC7$qWCa4K(! ziOIIbpgmu(_eQu`%$`D!d;Wglke9pig*D74E$1HB0{UPy2~N%sr-Cm-{#o(oa_QE= zXV4PR1Nt)Vnu8CcZFX0bOkB6hrNm9f;a%y2F}*L?faOxfwp#DdtjEhnC9(L`{FGd$)sSrtFjWI-gUd&ZYuCV{$CJxC2$ ze`PcjeS*3lCp2uVmCWFvX(#ufS9Lyy4CVOrjcQz{_BvicMrxP7r?LS#kllV_)p-~k zz@GGJJzh@^MtS*KMqRnp$sL}~JA;SCK$NQ%**F~-!`wqyXQCDO0KJA>#YfU#04bm# z>kT!kdBlC_b*OcC;h|HVMody4+1ZBE6ZmqrQu^)MjPpMn!sY;9ZI;BMW#cpFyiopf97R@jB<>O}^z!sx%la_q2)TUEBAWxN0 z@Q)KXc&M0jBNU|6!&uME`z^mqa#9vMrTSy;i5zF12EMiwM;ylbENPJ;@s{z+p10~0 zy{9wmfgv)BT>HVi<-546NULs&jTLa394#3z_@KlJRl!y6biFtoE7VsoXLOy_G-Q{G z@g!y!rc(}(+e&8*H^HOPbnRRkjzT9;&DFzvc_wPpVs*sgD*{l~P$zj|^OHzsvYSyT*-{ zt=oV=l(fQ(;BhxA@cdMMhiM9-FnR*ID(k)Ma+>ra7Yt+`?=hBO#RibRxAM> zwbQ%LRhq;-V6YQ(^(1c)RhcyGkQuQ7vaI^k7z~nIL`(N|1c^8U#4W>c6t6k z%Vg27125*>RL$+rzfjy|7fWy{D)xdteSJ+0jInrLE(C6rerYC;L_K$Bb`Q6Hs*y8} znr1ru)agW0M}Dl--at#6+ey9h(Fb7LbX8Q4-^}Ym_3Sy$m!=61k4Br!>wjm*%jGFT-_gq7g`Z9gPBuesH~9Wdd&A%F1}#KMpLfjkcNeH zOh5R!@WI8;W90xNegt{hwBh~Y$viPnUAt4p1zeugpoBEQVoE+#UTZyDOpP1*}&rrKeEylEn;8Qx_9rXQnUwV!h!ekv@EK&)sGO z!NZ1dHx2|r9|>7Uv0X1Sy53b9Av2pT-Ywd3y8YfFfSp~mVd{F9B- zM0uFUYnx4*e^{a^it9?$X15SOWW*mB+wUzAV10-%F&qBgH-3|%t(QPim@$i2nnY&{ z5*J;o_x%PU19wfVl`Eh^+R2n^#8?H!Ge#hPE{kf~r9np%S<{6sIH9bl_ zVE4zl3`yrm2w^SBE*V6hcOc>}Y4zd=p8Ur8m$=Q1GZu>9UeeKE!f{A(F}XT>hLfJk zOz6#u1b>1i3_|j{4p@pS*8FgE%gsm0#H7LS*II@! zqI_jM9YVug-vJEcwIMQc3BTaHAM&8byOV+RRj{PZ;&EP_4~-xM>*DCqUkXbL+9|f% z{|?k52YzfTEznqZzX*pEQo$e=xc&UX~X}g#v=JiwCMi& zC&ymQrp7XWXB9^J;jW8r@Y0U7*e`ruVHBzx%;#%7DRsPcgrJ`zAqWa16=mcT_*s?et<)FDH^YdA-wbrJ4gE4^Fo)r{uIF#OKmi4GU z75vbR(=4@ALt?cqOFZSbJ^|E*xrY3UIsz5J#l7;dS|?EK)|@0UkMk?4f%;BB2GgL< z5#@`QS-KemGOt8ayVhs^fMMC*>CUgA+VGv+Tnn&6%>%fQTUzvCdpQoQ{JoA-#E~S; z782-f8?BQf@H&i35;g}rt32I^m(vCOJPmdG(&)!_l-mFXrUVv5pvyvELH7g%_;oJh z#P%1oRE>ptDds6x9`nW8_5*#Nvtp_kY9HoBWf8S4ma<52XtdopXZ zf@=)t5BY)K6VK`;Hmps07%@}K0Vw1F)>^lEsm_-}{F7N5>}0-o=FGs2Pz<-~?piom z$b<@j;%=&A3T+C(gqvv8f8QqRVjeF&@;&wop|R^OovjvX=QJapua4;sexLsf0HDbyo*>$rM=1iE2MH`7qoTCyVB{}g*8>EXh(12}JntF^7 z*S@^Brn&FCx7tXUxqD+nw^KL$YU3xIvDg!XG;plO!ely!-6W1 ze+d}_mV7MK3Vly*b+qHCho=&dO1k^{_0hm~0G8eko+p)n5%e|fpFFTuK`Zx_1YEBf z`tI#S9?Trz^*eQ8q#uF9%g3mE>k3Uzv0O-Oby3#UIL2o7Qn zCc-d2HdX!;7I?pmTq&PKa|JW9yRfNo{oYz8FjW!T9Ra_tHyCEgNlk{u5#Az6y|(d@ zpbec?+-7?(G0$9yobgzQ%~;MXZes?Wbi|8`Bzl!6^l4+d8lEd41 z;uI?AH_~HUx3_o*?~q-SI}=&kn7d+0i;@Zja+ifh!8RathVyh6hrU5yxOJ2N3J4Le zO|$rG@~j-aD>y7`-VacZ;M&V|zr&Mjj-VSy<7$}};fBtme0+u_oIe@t~HKapx z0uj^nCRj7|CohN7_E(E4*>A#Cc#e|vh!SL9AGW!vmXEn}1x`8Pwq9|(78~BwPDEBI z-k`Jpt4X4>g?g(<@f(;1DlR}Y#Bct|e$*ZuI)K9#DSrU8)Xg!qAgyj=zU z$>XJawo@xP(}av9GygYN7&(imL?mYS5pAwqr@fGZbnz0^N6`Jn|2f=y1hX`S#3AVi z_j?h|Tp=c$EPIRvN$M^~n2eOrImovyHx%pZc{h!xnl+;JsDS-{n^K8L6HSmFw~`yal< zkFUbz8;98U>9BS7{)mzR#GL=oQdYIg+iGCi)JT5GQb<`w;@)9qMTUIO9ye8nnFB+N zUrUr{?d2OS|1?WOB{(u``N|4(@dX>|9=Hjiw0F}&eUgEI1eJ=*!cxvUk8ZUD>9M75 zGypjTTP(-0mBA9drDubspVGqH$wWlR6FWncz>Vc`>IPTik^~Q4@Bm7Bh zW%Y~fE{;?wX=~uG94+|K+HF0ETr~_M; zzpW1^7yQlE^?Ym*>nm14D)-%oNC-U|1GivA%`rpT!Q^2}PX=D*+yQrAYoxnxu0Ke< zt-|GvX3#s4rHAs9NeSKzH|+Q_cy^v5?BsgJo_S9RwbUGX)sb8;;R2h%^A7OHuR)a+GSI!-GB?2(@;lsK_f5EanzXO4f!}e8Ch)r53+a5dKDQzZ#u#t+=1@2J&+eAEIdM7b z%GJE%%qQ?Dq{qN{kGRz?eS=%G_>sMcIY~Ix-tu^fVQcFZrOcG+L<}^J&-at6U@8A#( zZd25m)!BabsEkTPD^jTH>slBwNxWJV26ox!reyR_$iRXDz8Q8D)%O`!yJ9%Pss8Ue zo~6#Fc#BZ|UJjgdYgcshY2_@D?mkd_7Um#^L|3k7szk>X0Eu{<9<9+x2=wA|-01VB z7o6am3YdrvD6Cs5Y~$`aDKI|J2+|shoHZ0bSqI zinzJKWf)Ykosb<@%kGF;6-0WIh*UwsG z?pGNMqfCpO@ zE8y7C!hhkwkt-Cr`(oRmNE#z}IAexmXw3-7~TPQ{5w%U;LknGSIYM}B{qZQ-g6|mp4heotc z$OK+Dw_?vi=tpwBhM_lB6ID+dv6OUBm|3>)V98w2U7Bsxy08X#&TSF`Ip7!vE*7>$ zMiLWcopvSxM7xz{7JA~~)O~x)cn`+nf5dh+5|Es*_7%z&37zotJ7zeWuVkn@(BrO{ zI}61!KRWlOm?w|HQ&ThdX2iSNtX**(a~;!kbon@8gPu4s45>i9rE$`o1$JF%p@?>d z`x61ne2M&JU>&_E8N=3^X&+8YOnxYaj|MvjQ))I@#a)OlRG>}achW^_SiYyKE#bV{ zX32NR)Mj$TnUwz9HMA(5ADj?qQ}x5kDFo~?aC~YkI$q(NB2-GB9$N%Yy>``&*dzx1=?l~USGuttswC&Wke{f zBP&7M$nA~HF)I9k{C%f!gKglU7g9xrLtu%7SS;`l*j7``niEc$yS(N4*RRhm`GZzc z$~u~V(|p6>#Y-ZAj((ap0=444ds!9rlAi;K@DB#`bf{g#RQHJ(d*BMSbp+#?JSS_B zD-Q6j6q*_1ce+W`so7{a&8VfxNlsKeYC6B4?&42wtL@pHbSE?QV6DG$Pnc^ZYxbw6 zjnU7L7g<%;lPTIcC0BbZRwOixf{RE?btB=|i%<8JoAc zmn}OuV+hvvg=AGu)h9mKYoZl8d`EtEomQ=xI|E?DYBA?qAV8|E~@(;*!_?FTp7JUZ)t z=#{O1GvfWl}-X;yu0y#Avu-Gch zc7&5_AsroXloS9X6GViQSSV9inIB$&lSHZ$c{vl=!Zh#2&hF2v>x{-}mAd7Lcg<(V zWqa+X_TaFM9#s(t|GMC^oLCfs7zP=%+zN9`5(t35!2n+#86FJjVmz8(ykBA{U%mo^Gg-Z3D!-w*(vxO!X?6#@hTD3I|FNx_yeAcdYR21p(y z%$xvzz8MmYaZ+V0=hQf6p!DM_q2H=MJU~KxJkr-SoSXpPwmzI55g&S#eF#Av=AS-0 zKl%wku;I5aN|4$vMzBK)N`iyqV`3PQykPkonFy}{09uR@Og#``!ENq*gudDkKo32T zCt1@0A}s)9Q;ZLIn<$4NH~;N?04jh`cD{JCs!(twAZKvBMBpf9XMm3yxg*?$8QcK8 zz1mJdzaai!$k)`@T0XiXThqEgV5og4k&nJO830iX9H=?fMZ^&|Ll8hcq9b%f7}3JI zA3a$*7`T>EBp+2curhK?puRP*Ukmu_JvhhVyx@7dw^}q|pWyzT1`4EtC;_}YF_?@a zRc{J9*D~Oj4R4_zsTI)h2Z4`oXS*PL{FvShKex7sGy;8_zjD&ay<}=(N4Qgv5rAR< z#ze%!#Q<`w085+w>PM<>$hfL!wuEQsQP+5Vv#7^Vc0(+Huzu_U^}IwrW_6?}e)g|^ zU~k{HgT1mucnAPMj(q@E`7(4w!%VatCZ0KT5zXBWMzy70(| zwoY+BZr>v?%q_9i$RNMY-*{U*U*&cHc=7H1;-cD^RB8$s0Lab7`TBYbG5qv>l>xs- zm66ZGfX2Sa(L5!6(XZZDzubQ}V0rp_4bSuI3W9;$e&^d@<$%uozJb1dDZg7Mf2H?& z3%+`pes)32-TU@?r@MNue?u{&{QA9r2=tgQ{rfL;(Sx^vj(ioT^L<@Z(4qX@@qRWd z!T}9m`5@1OmKzYnv@pniz(ezw^>*aK0AUXIzC`JL?G|-2!9wx#!N{1dRx3d-K|y{} zVLNr;Xx3K2u_z~ZNyuD0f3j6k&;0_vG#KR}#R1l~|6B|VZ58M!fTzqSe z0U+uVK?OPk>UqKduoY~H`$Q{afgsR-fqwIZhXV@L(aY)hioCK$Eysjaa>96u_Qv@h zyWZKkj@Inkrt3w1etvnL=F8cZ0gpd{Oz_{F4@Q*2jvh-)=?F{$gFHq`Big6@*+;^- z8Q0=9{WEZSL1^=Og;yNqT@I#LD;P@pmHys~3-7VnWWtjpIX~9FSLWi?-Ab6W>e#S) z0n!c1zwPuvl#F$s{2|(fPg$JJ+`}we@IK@orj)sMv6+mHE`6pN&X0F+C`>__PRWgF^LkrX$F-7(T0dx%RZPzJ4<`6QfkW z?R6b%oKT$4B-PZTakcIZsV(JnpRTcNhI8YI6gp9xc*vFpg_ytP=oS`1j{rS+z2-uK z2P8N2P$vtC=0n}DO{luRvNG5T1^aOS9Tu+o*)x85DX4zuz7ZD7c#f|EhaRls^J@N7 z{c4{I_%uQ7S{1$!f=Q+SWMQ1e8|y6ztPQVV#}L9M+m(Qn&!NcWGYUlMD&Lw*+p zR`&h?>G><|p^sV(GPIFiInxq37;2*W$>q#w0}?a2g{f2f)*XM#N~dydOKM}Zbmisd zPdWY`MpE2g#^wrYU)7VgG(eCAzCtV;Q&IDH+mJqZNUXyOJRQRc&D){VREor1W?$xs z$v`8V<~}MRuqI-&J3+SahE@$iiF<|oDuo(%Codt`Vd#S5PHtK zTFlIR*T@`3VLOgky}ke7Y76($uH2MeGd|l91dqiM6HPAda-KKVr^K}x#qfg1=|=5G znaC>C5l2-X?q(nzPkJPP_cfG77eQgK>S9-3d&R5>I{Yf-GU}a$J+8^nu?-V&MmNS| z=t#eobo`P9);hCNU_BYcW#|U4_C!?{C=#QedCR9^7bU53u>C5~ZEKV%X4wdNap8$r zzk7#u3lg~)Ua#Cy29ZL?T3grB&+4*`_-&01+}TM9%V27*Rg8Ww($4O!;`aUk{qoV{ ze_%T~{YJ=<31*vI*7(6v>9}T00|d{2#U{etlAwhvf6sl=&M#2F1aJJl-dtGeLCq}{ z1%^J0Z$l!Z>8ukzp&i{~UKQY1@DzCAz5!(BSnHFMD%J6nRFV0jV3Kd!mfvL-04_A3 z@OF$QHgvl4kc!8vX(~4M{_R>!QnO0nz0iStl{g!X_Rb!>jLcltBOeN!oMU^ihqS1+ z$+38+V|ey$=Ja>}LUgc4(4<1Rw!uWa$%}cYa(`!dYKyMI8%s}=QeU1TbBFwnt}9+z zs^RI`Ib$OiN}Fa-R&)BCd&f3XbC2U!%^5qykZCI%&2qQ4-lCIx3GbD+QM8L|9FkiU z4+Z$arK3UY7->;p)57FvK1A{vmjaJMon3a_k~WlmJZzGYAQ?-t?a?Rz{&}L5RbZW% zK@r*N#{AAQs0L~_B3nVU#Xf#tt2^A`<4(bs(v3?}XLHByBVAqOTebyu5ZG3GFY$D@ z!skdq+VoN`rN6WM1>U0tEYM_K{8ET2Q)Tjab^G0b`2kOYmQwt9hy;oyl5l#Ambb*L zfj~faXvYx#%|7T=34h)HnHo2e(Qzs;i5Pg9?G8Bx zh{-YpOs5I>y<(6v6-;UubF;#KYGt-3NhZurO8mKr^>G`%3$Q0(167h6oGl7|pO)_Kx*h0s6XfYF=@E%>iX9x1?Fac4g3TYXSxK&M8eS(Bb5WAz5$m1F@aVgDVE< zet?n>*Vo%wm5)`(7RTTx4Y8v;Ww;qXLm{6pTy3|zI*jNN)2ZXXxOAh|ZWzZQj!kFw z2%0yD;dKnW7&TlijkDg$3nX{XQhTb@QW9 z#HUQ@>DVhC4PNg^Zp+>AmR`UI)}hN06VD2>LmPw^0ZcgBoH9@#CYj~Lr51Fx&WI)w z{XuY{fDXaN|Piz#RLej5$IA4b!4m73YHx$%jGvae;W0Dd1fP zxME9+WL2j?g@cJ1mk5dKVSy31+HxV@dpnA7XW6mkFjJ$=)BF}!?5~qFcmGOYnayh- zujqK3;d#9(7GQ-)C<4)v)^u9=@SnydFV8!0=%|&mjnTfYWo6iG`q}!7!Med3I7VTU z%#y%oI)olrgx(}AA)g^p!%1C-p0gTVj}>9hCN1j0mu6yKW(OM{3l6+GRWad%m%x~a zlqdTid7tX-P3D$`e;utX(bgfga7%q*e5F6lPgRkSB;yruhegE!%lR*>6WG&U3J==a zA#aQzeG0^2(WsiMC>LzgA$Azya05waZD(L7Rt_5GY6n8;rynyV>MuwB!LQ!(K(Lvj zr^w6E%zcCL%&|F?>X(xXUzb$O%J&)29lJ8mH~Zbxo~dGw_kt5u9r~KLAFo}dsL%T; z$a;?zcC5bF;qVHfmli_ASLl79kkyRc#b2kdjBXmb`ugr`g zBu(sQvX~VtXt&M?^+_w>`;$}XPa(>)i*gPQqd4yI>sQb3V0lJQuEnz+)oSw=5$hJX zhDW`hzT-CGZ6;iX_rhL}4ph%uU7^DBziqY?hGf^3>o)^n`AzH>6x%`nba&Gl>lXa!JOfH_#YHaYWUmNEC8XoXB!{|*43uzO>p8)n`sa3vIZS$VUwUt~)jDliEF|YGlrq3e$QR9L#Zaz11#o^j&@={;W zEfw1aIvaqGpPgo7Jk;gYEjyTxRi}OxOVJbtpAI%J0eN>rwt5B1pmCuy%)6);ATcKX zflWa2xLqp(omQYU`nRUdgQItf+NCpl6eQ2-e)Hz@ovn?pw_M%?*KIwW+4X!vpFXqP zW92z6TqZr##B2i%3ET@e(tC*hTmM@-4UlZan4<+7aWsJKf9DVkgRVy(p>vY?!y<{I%xaIy9slMGI zu^%rkD+P00M`l>Jr^))0p6}|UEF6`=;@u_PblVnRSS~I0E~w+A!_>e!d4Y7;|<@ii@@CV6+sWnRh)t9(bb9RJ;x3eV6W==C%#1M}ER?z0rI~ zO<8->*A=f66DP#}#;fc}lhQA}F1LC|!|-kyq>zao`v_T_-n`-^5d@ekN<dk6~@$>gs!Vy&3`+=MjtGk%m$RX8qfgTf+Kh1R-HBU zv~<$bv^($`biK%RVtpfO%swKTuOj?D!^#;DYanpmSLPRHBr}!N%7Jo3s zMG5BJN@>teSeOX)7>$-a?bXYJ`2`oOlQ^Px;{Y0Zm|oe5F!7l!xxCB!UH(YmqR#0t(f-NOQn zy&MLAdD>EwXKHHh(a818Z+U6p-TYcAiC3>3o1{|a>)}UT;URViOnzIvN(4g^ag?A< zz#@oFgCtoa79S)axDT#~n5}$Cl?3`5lA|dpR7Xpkz}!XlmP7esPdLfx5zR62P;kUH ztG@VeakYB(p(aYJvN# z&CbJtMK-htBaP^Q{rZiB)u0jV~WVoHP={k9vr1BtGTJP$g-8ZB-}bpB0fI`_aEeb>z$yMtY)?~ zb_U6o)XB6c=Gv!up(Jj(W9yRE{YC+dSX=z#(JE$_ipfBMJ(G+YTauv;=>ID9BuFVud5-qxJL+@#$mjkKaU$hVg&yX>j2EV8*y zeDhSHw3%c(f%!bjD+aLC6S+F8Kh_IuRN+@`io!F(7y>xwo~dgub8VNIg@5l(^R@fY z3DVbFk#~tKvyFhFlo^dNEUSSK-*a}oBFJOG;CxKfr6rR5aTkw438YPBqilqeP$urN zXnNO{`9dYqM&=}4pW`2Gn>LQedA1K};-nnT>!2DazPaR7Q+89jP`@6g1sxFZQRcVl zMVCH5{AK0;d1R79CK-&e!YKCrRKC1grktbx=?e~MobaC%TM@mJu zXE~o^XoF6rX|$#`>7+#9#0#|=zYdmYE7~&CNehMwWrNjwSc@u?)60(e-LZYmJkw-^ zmKJuCN8;Jo;u9csQn$l2l4+M2rO6*5y(&`Un>h3@9Ak@8Z@$tT1Jy{L`%T$4sexK2 zJU-}N&VkZ-Tzdh_M{1hYG^bBxX#k}N?n&be$P361^LtwO;?&v4!l3CxGRZ({TrG(l z4q+K&Jh5XZFYv#ZaZ*3h$D^M{QEO4lP(-U^Ff~@$gLUnU_Tr@oO1tKXq)k_7E zC{lN=1(O{&1Qumv&!5PFloM6ym>Hp3pu7WGnTsOedMLx~w~EIe8WXh#`lFb_&{`d! zuDgTc7{LFT|KTmeZx$BGO0YqexVWs~%{6PuZHb1GT_j$m1hs7*>*JS+Dmw04d3;vO z85kl+Mc70Kla(jMTdK*ft~OgA?p1mTc(@1?fwnV%8afWvfE|2U7GQ}uadXjDO2oG& z(>5Vf59+fPBqt+F&)}c(0U5l+Cq|A-eW1l)kk$~y(;z*?_35E4R~OUVl!0eB@zJ71 zaf~Vfu_mCUD$E-+wWj18Id9^^v91khLzPirx5KN+v=qK%9rnZ>Gs zkW-sJQl`(D{B1VNMt$D#kD}p^x90E(MqaKkJ-@MJg-j5xF?joqp1>68_Tu4n`}AFb z&6Lxrof~o(jkR4uQ$&{o0sGU?! z9!=lK0jay}l5lm6MuGp#C8`Rf@u zV0;9#B#5<19mY#L~aHb9(lay_H zDuiHoiCvEjbRHCt|1i7i4`)j8k5NRatbL9~u+N`vfKHiD%*L2NmOv4rbU1>M(p~A) zf(tYZyFJagP-d+#u5x)@?Kb0b z+7)6oA59)8i=W`5@)CJnP>(K```RrgmYB(}Su+1-d@5|RDDR|_>^8dinii1eH%NAf zUNb_SX>TFLX-o0ik(qLi6=E9c@~^;ATO@(Cbd7<9$1Y;4CZvq6;t(apqt?3fIx2pG zTcYk3_h#l7n`2^M_0efI@Z<$=R9@Z%uLC^nGaFwHtImmEmDL~kR_odO~-2j(gulg7yI#gMD*)8R+{ zvY&S`q`9~ZyP_lh?yuPPxN-3U=?L$UBao6Vef85JTjCoA!8`iZUk%aVmMf>*%U1YF zmG)D$ZxVe_Sdk}lbIa@g3b(yRp_`|eZS< z=Fs{K=3?cYy}KW;xlRJ>YgrzJ{LFd0Kaa*PX8R;^qd;yk5eozq4CXD$V5d7bTbn

sF?`Fd#^sm;nRti2-VxsXjYSUdJEzRB%T4{G?r#X8;AiX+;tUU%Sn@8##r zzB(R5vFEe6z>YIf#ZL?9euP@-JJJuoSxtGK!R}Psm^gjLX{A?Bdv#7lQphUl_(&Hl zaB-(<3w;NWV*Ct$FeJL3yuC;Q=SiLUhl#k(6WGZ`$Gd6y8LEFLw;#{0gQm|>(It9` zR1yqfzP^1&YoU}f|BaBf3CFAbePIBXle9sPtA*E5+2O*4IP0dyXL#B8G-li1gp6Jr zvYAj`uZa3O2~kp0>CFXzZ3*vN(^2^Cdn2Fo%;!4=Vuct2K%U8==zak_K*L@g2Dk9L z!HDk$0X|GxT#+p9RGr9GRt^rP#OMJn20Z=Ck2um<6>bc9?`Yy1u>OWV8ouu^_|uBG zN!@86o@0uTymkKrsgT}C*snZI0jgl1qFwzzTRDw0bARPVxj0v;dz;E0ihvT;1CHoY zmZ_V6XZWiGgpzD*$0Vs7@5htljyp3P2QBNrRB>-_TB0hp8Y3FLUC*sd8f_R{C8viw zzw*SKrSI)JiwSI5w9=cLeG`8o5X1HgA$02K%6w1g2o!$P@G$?X_qGYqU$Y)iU;lbl zJb+pTqaH832>AY{^q-H%PeF#br~8(&9``c~BcsglMP^Np%53UvRCLaDHDaHful}8H zMJ_-dDn&s7Q7{Ix(oc2+N@Avsgmjjcf$_33>wLp^sZ=gv>0#*+ll+r;Y@JeeeiNFB-gFyN5@EK@mxIsq#{-Bc_E`%0lBa#&j z{Su7j@5{lUC59T*aXJ5sGcOF_0ic2V3Xt^ZArT<(K!CPC(Gi1F0LBEh5mNx1`TZ!M zAYDlg69m~k@(@>8Fs@jBJwWgJ+yM7HUx#jfWWdMR`sN`pP$1<(4XpOy*8b?rdHT^n zh4>kA{m2K1E`SBvCjkI$Z*76(!_5ScH8nHcYWraW83NDwa}Lhe*h%))`U7IgfxqRB zgN(NUc(6d6^0v`TKplb!4+5(7{RIpp%&y0z5tC%Y^4rGAt1JMUa|$B-ja&XfxB>df zfd!y~_;GFTUGIg$kLyj$r^A@&M~ryl!>a~Vf$(JGQV5syYllLbqvWzjKMJFHx2r(MfC5T(34dMG$#*ru=69NpE2tF zNEFT6r@N~61o+*m`h#>F^7PSJCxAy??E|ZSegNSWCB)X=r+oCQP=~PYOJ~Uj1^~E? zjEaf~-j@wv=b8q4r|QlPFZyIVr?$xR3FboqMQN~-3rUJ&>4 z_c#ByM>nq|X2nq2`G*(zmy?7t(gEBJ(hncN-xGljfGWs4EF2op>qlJ#I^t~;?2Naa zLW~k+ZztELe)Op}M*A1a@3fZP4e+nSDM-Hm%f@~3u*u0ZdV=^ z2E`Htvxr$`3P=x;KW+>cXTK`UE>zP3pN=k*H{m^y_s5vo69lOy*g@p$qeZWgFYh-( z{~NS%(1$mxzT@jpfZ_GytT$>LUD7daE+oGYpd1s{1wYupgg68cpqqbvNK;VfuL=VI zS(uQ19XY^N6b}F;O2*Y{b3`B@-?i@CEh+{P6o3Zb{4bbLFaVz?*~x0QL0!Tx=&zw? z8Z=gP^S*7ep6BQ4N9*anohw_El?N1PC$5zy=GI%aR>-ilo_Cm;eLFkBOc^Ck!2ZwM zz@$hto3{Cu_)EF*d9*)DwQQ}xXi1m)8(a@;XJ(5r7!?uash%B5hl+75h{NX$Z>##? zI<@@N3ZVfxV&zik{f5 z;&xXgy75qdd(=5ALvchge`Zm~Svl9=_i*&!Fz!U_sDC$$8gsbxWp3{6^wo_7B9Hrf z*MKvQ_E7eiuR%KC}rW7b#{ucBbTymnGiptEI3`rbt zUf8k=9~fdxrr%0e4Tr+^92*PS&^G1x{orEY8EER#T=PHaUIGaU{03zR*|ER1C(83E zt1T0*D4B9Ct&fz$pO@WWEPE5-ix-@2j5XWS_(^rTC&`3y|t4R%}OQAz$H|nb1 z7uCLMqSfL{l&YRlu|3g6Uic_{mr723NL8#vqaN+XY*?mrG356pIit(;>dyya@*3faK3CXdQ>LhJnD0=gxdQMd2QN^0rGF1~yd@EcZp(_| zuC%vTNu5PGMq1ot2kX<1dHK<`l^R)W;0_!&!A9(^)A^zUwigrGg>9E-q#dCX#?jzw zord8AsY=+Y>QB%zwT~39%HEvL0VMTBJZ8hTy}$8KCRSSc)_-)4Cl%oC!W$8vq4W%gaNm_+fM@qKaA)vp?EQjnm6I-XDsm zw}%(vnh;~(Y-%piXlF0CQ+lH{`o4m{#*FAj!0pZVv1A0cZu+O7A z_TTVeIihl}cQOW!)2Sv(H_ja*^e1Y%ou<+OsjB@s9k_0)j4B`eJeRYO*^ew)B)G-E zibr`ZUK}Qgs07SfH4^S$s&#`hRLB*?9e8mDGmS5ZVaZ*HPOswPmi;Tlb76{KnrYIp z2gAxyD=!R4m@V@GUapaY8-gTc3lpD(1K|Uv`KL9j8@^;pLasQmILEG&P~nwkuV0n| z_Z?Xes})z+uC_kON5Vm2e`4-Zxn2X5SG+B?b=;G#>kw$J^PrZ!q`N`xZRW|@jZEG^ z$0C_QsK`;oC^8of;ZT`}Ir|_?4jAPPs-f6>{M$q~p+@irLPgCdsf2tWQEh*T zU+WvZ$I^gECe|;z*6=0~7tu)ZaR_=YI09O7FG4~BD3Eh;BihC!_tz?+%!sILBUvQI-Wh_(Jw&@Ltm$OV20HUI1gSL1phOhofcZ8cB zbIbH|Rv`*k{fqVd*-X3_&)~FM33wvqss-Nd(Wm@&VgAr=ZI=60a5LfeO4zm~Z1qqa zqojmCA!{hkdB|M9-dz=sa`Br}k>H9!34j*iBYxKjw(V zb3vvP7?SmtzsiDfIj#mf5F+%>?s>;&{9(>>g;jE0c@QL!P#Hg;{NtIkV*FCZHP8Sz z70VT5Hq)rg$85o8NC+!?x-^C0$A!4af*|%BpX?tCmiqH~JXOV9?`qp_Fs#^p?A$p> zv|&0fP_BN635#pkF&HCZE4qVYG<&h>(t75BWrT7U_av>$f^?kB&E7xP4aV*GZ4(w& z2~mGIbx}+%ihwMExEt@;^OemfslWT~fyNsCbRF&V%r7{v5X=vE;dV@mkYH`2j`7RN zuVQ+KKl=%C5@DC^iJ~zw+!0AJZ^*EJ1Ohwp6xyY)^VfBBg<{cmN_(@WJyl~Rt}laL z{>#GaQdsX|1#w2Gs&|JA*t*;iuAdt_3E5JmfamFD!j6S4PArCs{R{1jv z?j}m;+;P_!HqLg_vnFxVO~(akumo@lmAfv`=G!1Ii;ky`={OYzuz+dV2cLxw3vF z@PmQH_V@W!8}&U+9qN%uuoWHO5UIazvxTXIw&1=caP`F41|VKf?5#nT%UlnpRnWXr z7$@0>tkQFlQ?k){$t+R@CUB~}pIA7rvI=yEP?{1ha>>Etr}!B3B`5jEpsGFm)P1V# z@%Mqj_28=xP>bI|d0gy6p&tT_(O5(X=I^u?yHuFqS_{lW0uV%A?H)Pqky;Y*X8^oZ zSTuJI2R7wiV(N%^qV!m#YwsrZgDUbz1>O73B*Z7c)B{oSdIFD&dt;%gFIrV~E~ zn+#{69Wo((FWPgI!;VCMvAs!V{uI_q*cf)wfd3IX@uF8nv%FFc2{N`RR$vg3S>Tnv zojj3tg;h`Kfz)7|j zwxX7}<(;Y9LLIPVqN3)QsJ9ere;Ly3-QB08&le5{UsDph@Yqrr&vY5hdy_w5h3}Qx zUW*eBmLO-^aa!tyOg~Jhq!Y6}$LMyEDt?8+)cH=I4HpnA;*aL+C*_4L;DvY_4+p;i zGp?dUJZM<-rQc-Ek?QGG(LO>vby!KOdwjF(FUl(L>i1Y{2210vac%oIve~k+^w%?q zx|2_NG)Xh^spMo))3sy3mOV%EIBs;Vre@jG&7mu8Y`8e?MsHhS-Me`)a1tgR3I~U$ zB;1(j;j*xIUx1o4!y;Zuz1Qn;&Zq7f>de$H_W5+ zPwC4jxvGFAC}I1jGj+C%b2rnzZDCRb@M2O1zEV&E!*gjTuJVo<8`T?@QVm!S6Kse7 zO8YQLqNYpxeNaOF&=a^r4?l#=biemPr!aDl=0C*FA|lTA?fjSh!fnqoWECXCk?`cm z8`H8{5f$WW&6tVJjvJ5(}G)TLZ8{nLHX!u^Y>ql!~DXYw~N*FMyz^1!aK4ArFV@HJEJH|43jTrH!L&2)m zfajW!$lIB8yOuOf5(Bi5f|+#e7Zib~F7Kh>qhin5yFK@}Q?}fc+Xi!BF7ADQ0!aqn zNdZP2?c*@w?5`E}(Cdj!IST|lv}o;!jVQcG{0F#p5KB8bMjwNkV&+Xw)0*290}Gfq z<6YdN8U}3?Xq!ntk+SXn&puE+@+)r%7FF?Bm~1 zZGX`WT-M*C>u7~08NygLJ0NMS?GtMv$0{@M=_4}4F15L9?Zui3Zy7nGkhZHfjo7Zk z<4&;k7m!N=s4KA{L!@s1p>i}dKBN(g< zgY)N`ugFcGi70U{n9q}&e(B>-yVVP$|G#t>BwyFM?K8JT}7 zcSUq6eev{OZN2o(eiADbjH?>>7U{bI7BZlzOJI_>k1u|lYTrC}68{*+fPTm_z5>?p ze(M-1A}4`!MIh-fIN-HljA9$_Wl&!|5F8j2I@idk+gGUi=y*inCVTRZy|iDhMf21K zHg*fwu2cKdarzibR|pO~4CjIg2CK%CW&|Qh2*8B?onJ7PA?6Btgcf~G6AptIU3a_6 zfHdaS70OsHa2n~op@qo+@TOEd{t7xFr;u&Adu_iGTeb{H=`ygy3FO(|(u1XW-)n_* zhj6WoHu1KbS#e9DuRhmSb@!#tV{dOJbs876cd-TcddheZ1AdD?9x9oeW3gM^8KI6> zm+dwwZrP5?p{A_ftvY=S2gZ?o7q+C>L8DoZ53gQ;(gw529boO6RSt)l{+s~ z-bR><-(U1lo7`VOvR7)H-Q?Y*KbE)y$w_;?IhB=}y*Pff~$3ODR5GqnT@T#BpKk=!F?UBa&_0B ztU$*o7vn*V)|Y5|ja%=q+{h+`{VtrjJedu_;uGP%BalIrXikdcBbBWfAp zpf;N@na2pXg(gFwfWB@IzjO|p{t{DQf#J=fzq+`~!bA}fNcq}K+cJE-TiSTaURdl{ zo`Yq}m@7cH)}Yyy@x( z^}QRf2WrGbKAL}ks*zA6UKw^|Z*j{%zbwpO#I+FC`KFU5{(B`5URqRakIb5Mapt7F z_LNe3M&q&AT6p&l;+YQxyx})#i&h3iJDywXk$p2X&*S!%HV!Y-Xf)GY-f9txK%?)Z zZ+$zG`|i``a4#=^EXYi1Grgt&uI=s&3FIud_~Zebbn(c=4ekEj3D&&JqKI!el-%D$ zd5gK&GU4VmT%k!+lgjhXvak7gI}J#upvR17=@zP%8hx0udfr!!b=H_nX4RGV#k^2l-e&0m7<J!wwauz1w?VtJt{{TT-a)#dKZK+0L1JTxD)%ivs& zmwl$uP)YezjCizhj(eHlG75IWh-5_bkF#oR_yn z=8&ByX_LF8Y8CnT;^N9Z$u}Mx>NedV_lm=bq1(*}WKiyYj)9>e{?$_)#9+8&R@8N= z@VIs??klb6E)Bmy{dnM&XuDs?;rN@-_}~lX)w7~rKVVf!o(D+IPCB$)E2m_kGi@PZ zvEE4~5pneB$@JOHNITUuY9n3e^_%37KFzaRCxPB_5#8fu@(^S}_Pp20;;JT&G79r# zT&s^+!t~g5z6O&06Q)d>x1&{L(jjS@wM9uAe|SQcN;l0Fh-Vl#ORz2qxbE|_*B=wy zRJnY*+lk1?3%vIIk3s@jmaK^Ee$0itZuZ^j;bkWvz3K`%q@q7dyk1-)=Nh~8C-NwH z)zB*PN9#43R&A4%O{!=sJL~vfoeH-UD9iAO!TD)5+CGt)-&*?9oT0RWDX492xT&GP zT$EZxMTEkB)$l=_ZvC2Kg^W?7P4q!Hl%{(vxHkNK&M?MsH&B!`)62CN$hxAU$%-|jdnJbfJic{o(%YV~v|0a40i4PeC4>@KnZa1+^`0PR zG;S^&qbrYH_@29GLaT$AhWuFp4ZLekC9xoXi`31a zdBUH+?>bzkfVJxGw79QGL(QvTfC6h)38WD3J6=b)jNhwAB6i_oap{zf`GK*0Xw#78 z+{mUOSG>lxyIx8#*6ZO%(c8?e8FLhjZ4nK$>Jn7z?fGHQV3K5J6B0n zbr#>&J+F1Mr7CoPank*o7!5hgyGxkqU%eW1L;9dm{fc8s{xUSz^O*V=W|VQP0=3g6 zi91wh{uq}k9_F|jDfB&CBUshWyxc-DbqcJWgy-;#K4&Ls;>8sH{T#;CTKs`??6StxNV5D z6s-hU)i5skd^)aQ1shO_oGuqMY=F;QIG4Sx>E@+Zclf4?a0e&#mE9K6#{-PtPQ!FH zuEe&Jy*IUWt;wEBUq$hLQgclc!Xd#^@YBP4fAZn?JKL-bR5C?ofLA$pvdS`r153mE zEC(-xCL=2hB<8!N8irlNM4LewDrc!vpDvf=SeV$zu_y5zhH4dMp-k6Aw2W5}aIIMp zEu0YiDJ%I{CvGv0`DWIJB8vA#hXj?;ECad48H{nn+5{pKW8nK-BNPXEH@TiBL*|51 zLXU@?ioH9XULHrAhXus108a{+48rxWYeVFfODXOv7nzH-v`H1ljvM*HCH*H@A*>ch zyMwRCoB`>B6|yZy=j`%%{JVt8WqVPd!g-Z;w(4Gp?~b>x|F+E6fT{{3yJ$TadlX!D zY4>p8^0E{`p_nv}jkbl0MZ%jKtxkD+19M_h$!S*6wZleWg7e#IcApAuK%hpg6yHcI z-||WUqh&6z>%cHMGfu(MaBo{g}<7Owi5eUbcZCLt&BI-k=Qrc)RguBz7Nj}SYA7hm` zD}|s_Q0s4(!At{$(E-eJ?_??!Y~5Ix*2}5U5)UnAd8TAUpuZ8b9ilQa+ZX5H zQTjT!DcX@syWB*OT3_WGF86LOO<7CYfmDUv*Uxr0JQhkJyRF@Jgtcya<7diw+S}Wu zFJvm8TwSkd@3Ku_H>lLA&C2@dw*`J4v& zZR5>J>=Z^NBCdKHB@dLPwC5{{ODe3n=w?6Y15k9V9DgDpZ)($Ttw|5P&C}?O&3e%p zH?9ymNCYyb%>9W6AkA3RgM_V}p?To)Fi{uq=3CPB=pOnWtK3Vp&6=Yy)(-EVwo@VM zzY(&X@R>klk8Sva6F;b4(D-04@$&3u{TvCH8yBHqVO0gsi5`M)Mn{(BC|#!S!fzlJKEL6s6?Us4z#@D_{7G>#fQaX4=Wz)9C`2IVGrvo=U%tJs+^62NGwV5@?cTSiJe`9U zdQ^EZ{5$~`c!(H)i2VBMc@;VJ#Y}Q)YEu6Wirr}pB+MbuH#FE5ePF>H9nt?`>>Q#i zYXfZ?+fD@)+cqnQOYXZN01jm zitr81DZXLCCrm|!0^ioxrwH-maz8deNJ+@XDX+eTL2(x|^39~`b2Q-R+p0|fNgxR@ z_;d18g9zuKl@$g-d_Yea#vW$?^f$8eAFyY37f5D(96ur$(04N!Ct=ch01-0E6yy_( z^$c{IWW7u5Z*Xo#=uJ0@XpG3YOs?Nq-FKbNeFmQz%YIuPF`?bbWu?o0?Gwc zu-6}g5Wf)4d$$mPdgNDNJ;B>&2Z`RFmo3-n$Tl&8=ioWHzFyRZJV02Q$C zaFBl)9n>4l1&AmJASN~>|Ha?*>OqN#F|U~^#hXNE-yqjN$EN-%kO-Aw2bclesf~a4 zg@-3)?GYpZ7OE%-dx82w4h8=KV?jd`LPfQN&HMWoVGbxbh!bGwpG^E!Tgx#(2>bV4 zh2BlpU*qZ?8?+6`gG9LJKhhC5)PMzd1V}yN7(g2^yhJq*CD%})h!f&{d$=70+3hcF8U zPniNEIS3p$@OQw`20wue!Rcc%92NZg9+U~-VaLV+vkLe%=+~`Nr#~za z2$^`k>p%|Y%=(|GNdzRs8@N-@5W_;`D-ziUFr~;BtoeRM8X}{CJ%3D_=EW0%Mf7)o z)boFUUnfxY)iz5@gNCU33-^*+qUOc#_a<^FjvX0D{h%_vk0Yai!Wb|Y^#W);?AC>c zGbx^-!dykWf#wqcLqf>?`^)@6YEdD{~yBun9c)u{oFS;vp zR8*hiT1)tmTAPuH>tZ{KW)qCtm(u$m$!rdj*l(ms!)}#ed|AG4+Yq(_v7$RWML9cI z#51H$lk&)@Jx8m~aw)`Bw-=wq9)kM#&kJWpz&Mhad`No|RE+3}Pd>pjz5Q#`>)RPO7zj>B_k2!j2FwaJi9GUHbXs`9~Fmbo2`SqRA@+5g@Lm(_r@8 zz#XXo!}0?+9bBF-d$Xf;L{H*L4|a|O_jHxACiUlPQ!A03{m7GQzD9C%8e5p~&7x3{ zhDm3VQey)+nX*&>f8MW_rrIxOU2}}2IH%KuFpXzWR4q(3kLZE~$R)Bamejzc`g_vf zG|e_8%jI4HIcFuUTYr-GzI|&ulp`@3Ve~vTIJp)<*I3<}(XAx+reEkQ9-9-y+3>!D&$XZuR+CemriLoKJ%iS zmII~%c+~FR!9B5!TFVbd6f(Lc3oQOt1FyG5jd;3}STKrT`>YGxzNAm<3=^eJzLSWr zf8tR*)N`7QF4F7)YIN&+;K*~uiDpv+lu7{h#nwN;*~>eiNCXpqL+DYrXntwEG7Bi& z=?l{HP2HjrLVozbPcL6M;CGSs545*0qN`$|$l+Y25p7fxF?Lf2YcO~*z3gYNO!6-S zE*O20HLYS-aI6PftW;HhzQX-08L8s z{$|cKpen%l;}(Z*ocL2yV}Y|(xhSmc-L%CUge5b^Kciu71&Wkv>aD$OTF94sfS5Nn z;(gn=#VID1JqJ4Vo-Tg*gp%?OA%ZG*K++BymtY-jRAG$-*6Q0*$=?f-tk;RwM<6uFe-4;so?cL;h+9unNc0oaUd|ZOh05M9pZ#oxz_6hmqiONHtaCkdDht=^4rQd3 z=WKEwL9i@VZIV7wMxQp|q*_O>r6rBsh0rfH|1;wD(HlTM8~*cDF=d+1f?nH^UJrJe zmN=1#z~yvQDLl~iK${mLorW7pQV7!a2NsBetGojOd<>ZqXO)0NWA5uq?dMZghRaRk zgv6cK;zot+Y1ci^B{oBYq1}M{VVxB&pZPe{E&41L*7C`yKmAKv4Q3kg0AAc`PQZsB zD)Y|?%rDH{8Z9TMwJ!fM_VfqJ@)&ZT(FMu-WOoy&N(x0VCrZi$V^NEjz4;@xec^3u zYae>Pbz-^DjZvY^M~1Gx6_6|^y^msSB3UX95apd+A z8!DhXZoA)K2i*PKfCCcyuhv^Krd20BSB$(#NoJ36`f>0@zJ_nIbEt{86Q$5`LT|}K z46}8q#yjN)kiig9zv`UpSKgjhf->#M1v-N{e*{L*2;afkB9>XN&D~Ekjcc=e48c=t ziItr6_=B>wbJWmWI}Nu!D-jTr>>1qhhXdMyQDyUQbo6a%nsI%Jp?(uz2rsLG#6npM znRkR8wXvtxhIJ#+D%5%m8>=WGZW^x78+~zTY_q{m1!XgD@>*)U13{eN)nX=8Gc~%Sn9<;E(45k}EZ_3Y)Ny&*3#?%Vnoc zom?J7j*@k8jtvdnLUUsTa<1xddeNp)Q`wRe4skd*(;<@v>T zsQlt&TzD*jD#`(5e9SM!Sg`>wN$XUV+g_VM!Iz(uM0m!G^M{$lfRLQdvOsdJ*j1xw z=T5xfdBqEet9o!MFX>hVo6Vz7j(S}`&$Ol6mO+~Dj@V%s)`l_mt5a1MeYHM_HA?4^ z)P}{Z@FDFNwK^qY>xb?w-+e+pjXFt&w|42&bfg|!Yl?a)&(Q`MNsYAQOfV-~zR1Qj z$y83kF3-YWwQ;?;-PljKKaec7Q&kDlPvxuXczC`mXjuV55rI1ka{Fc=-5S{aw)s~_ z%Ui17vkO|uiTKfFR6*wPoCfW>Y&jN<0`F zMW!)B-dl$+Y29N5I(fr-|B6jX%u}h@I&}nK05=>;q=f=?^DyM1fEHA4HU#LA6SC;t z+|PH>E?OIy47w_{*K3@lcRwRiiuz~b=SZvoB7kCz)7!q9x~Enf4_D4JU2@meq>2=H z#~g%jtUcKcWrkySIJX{;S$)_@IbGP^1P#kj>BfI4bS>^ z7Co{~b`9`n*Lvr9=vaP!xUryQ!iVK3l*Sc_y>WW= z;Gmy>aVpe6@ckch3gT7C#L1{40yKs@(?8ITq%y8awUA3EMNSGMQ1=xUE^T%VfHa>r zyfv?a)E`ET%DI#=y70aOL`#0_rnR1XT+M4}>5AF5IBDn-(zpsj&hP7#2K!yWX~i;i zYh!UhK08U;nHFh}ryOIyjpvR@Q^lTUhjQ|{rAl)S>vEq&Pb!kP0SQvJRSE%uqpIVD zE~-y)WIQ*(U-9wmz^JV zkoi3Jumb1FbW#M)osv>t!AO)2^jecGoh~`md(-P`o2a`Gt!w>|F+aFP+0gu zq|GlwMJx&^4#p9roK<~3xLio1w!hfr3RMWOP;X~J4K8QZk$cKAzy9uCymEC`K7cWI z$I(1lfbWGc;*FvAW-0)^{vOxh@T|6ung}`n-t5)Bqk6OzV?D4wa_`uzJs3f9!0nZF zbx*xo%qVM%wFmhX6#v_vlp5BHJ#rqL!1sJHl2`EAhVXf+mc#eLZhy8+FtldJ(Dju{ ztn@8KF+WaI*_g(hj^1k{>YXhW-0=aQ3V&HS>}F}1%6gAX0Nw0!jMAqwmgiD@QmRbE z3$VmoKR=Pkmwu|b2rtMHr;lF4TRk zpk_;t$inMo*e*gz%CqIxrw>E>Ri)Ub`=vh=xbGAh!v!=1Yi+L44c)gdaM#KtyEQ}* zi*%JN$ZNO{GkeflWk1=b$cgMsO2c_Aa?v`)y^elO0ocmthZi~9*9_Ap@U>2plFDuT!@Cu-6<@YIJ|ceT%TkJD{p zAY+#|zo-55fhcSj%_1crA=;tU79mL=ExYraDuUVw3YxC`dlCyIWTc;%+IDtHpXg|R z7uK%Zn-$wKy4#t|3ZN8U^y4ml?W+V9;-aibcfO3GtNJKmQ^(p?yJv$kMT(s1Fwq$c z>E~2NFP(OV6Ref-y^gm#K^L;YShY6MiMe@Z4VhIiy?Xz^89dA|02nYh%n5sZF(RU5Zl&-TKK%0V4SGRQks!-ZaY6mONO{a{E z3C*e!+;Kv3@{?5=$sijNZ{tYth^9q5pO8eu^REB-?9(}Wg>=IpM!jcRar~zTXMUmo zZyi?chRT6`$mdT8@^PQFh&lN#(#EQ-+tIH{6Y$Kn=8PG>gTPmxuR|JG>e0uFrX0#l z#2W*sn!PL(;|_a&oMUX$W9Rf4mLI-AT&i#kmINeOy(p$Go*VQnEMrYn1ES#FDo<%0PQ&X4>W8})7&<%adS;_j3A5>i~=KN!D5wPU8o`Yor>()ru{Vfvs>KMlP9 zk8~tf#eTf9Tb7GTK!g8t)^fq++)jBVci>xizh)Uv#;_r{+&o-8tl*U5Sv7XD>k?Kk z4Hux}NmYn|Hk$vFe`Gcj>E*S@+uX0!rav2S@kx#9e1kDO4$?U&y+TJ|QTgfYl2FXS z!_q^#7XcBu>5-%dV>2LI)S)Tx8EV#cd-KPI*De_lG^Q$38}EqB6G0X$lK9OQ(CJh( z_nt8zq~s0>16c^Uemm@^~rQqJ9e41ob+auPu`{`x6 za$oZj)?%01c@kRhK z+-@ZYnT(7)fxVosSo_iQYQlQ_6UZcZj))jVruV0o2V|Ph%oA6=)j6o0_K1+{xDzVz zhY>Y=kFhi~*HDNcvt|u(TSODuqc)MA!qK&dwMv?-)^6$J-L9(4>;?b3bJE+aQ9Q}( z*<<9)pze2T;axAz!ZT0qU%|z9x1W`Qd`kUF2k}{Kg82S;A19j+NYbJ+7oAlJJYw99 z(7%e_Q6|?aez06#hsV6|J6~E;_00IW?iF zz?6GAMIAy3hL&NNu5KB3Je~`*_36cAjm$y5z6i6nYK_?$ZaaXiS_D~;2~+0(DAev~ z0$6}^Ody!v6mP-~Jvea~ZGxqr3h>20Naohl95~5I6EfB+tSgwvRr9`Ec9{f}`J|HmbcX`x($7ERp*B#3VuN9unC=^FF0RRSPhi7-Vn@OgYL>?T!W&+5X1n639F;%U82m9 zx&^e354g#Nv<)hugl(5d8r24ODzU1Zp{%ZWDvIH7&()JK+#`{o^s%U@oP@Rglq z0br+0^}}^lnGw_Ahu_Ps+RCW6JLw*Hg|x*#aymV7`t@5acXS#Z`SLM;C%Ah^yvQkd zimxkYiyIG4l;2Keb}s_jKa^;AbmfZ|Mmz7I{h;227gMKMytq~yQH_Kn*p!+9fn>38 zNOyWV^?1@-8VNg3W!RP23TIVL2FC+~9>2CXuI99m{^<*07cLG~AsAT9RmTglyTK~# zN_Lg&)@nWSfCn+rh4Y8UJDighB&#@1hZ2Tkj2| zjM(Q`RX9wu_Wg@Dqw!B-2}HWY<@iN9+@ORjt$${JCFAuRn$A$(MkZYkcG_braEMP|mc~i#^^V7$iL?DNH*8i=fPVh5{<>u(vVw1=ch?@cZkq z2-`B^(;nI(zfEi-W5f^r`sbYsBQs~BXOFm98t*ZTMY~g^B6`-ktdL|G3Ir_=CdAlj zcH0G!j=f896m`5j4xt6}!fB+foMD#524(0pzDYEMQ>hH}URItH!L%O34!eG7;LIy( zVEUowiWH)3L_WXUZ585sTl*8&HcWP7sit3d=3B%K>kNBE9uqWD#+3FaSd`}SpZ5Mp zDDS2zo2AE)v|n^?&4G#BU$g6Pp{3U%p{ecs_P`1bYMdR8rDN&lT=tl*_R#iZZ_fI5R7+Xth<&NO$Yt&X1uebv zhfS&%www}5%?4z)fq26xRK+Cf=&Cif+s0*5b@0|O;XeCYOGG z$AFF^J9hN2xHJv;*`bIT*3IuX6eElJbRuaQuYa%pn9VqTHbZ>(e2VbRO-ALbO~1&4 z>sG{m4(MTO_#bTJ^h=oQhuoO%`_(ElR_QI2CZD$WF?<$Y( zs(q#$tpBF|W{UB8ZcM$4NlsAPkINa4YcbP(uu*^roU&E2Paw9D;*)PCC7hJI5TM2) z>ug@F_{{UUBzESc_#zm``yPoL^xofwWY*@F&szHR`qMmO2asnVJjs+(!ueFB5H4vs zM(u_C!?G>)Fz=d~in9E|bg+2@lq(tB#_ZP@hP|p&Mfn#zsvf7Wvoq5qV@d--A0#EQQvnEmvoYB6IwXJX&<=5ZTUz_G zr>K1(aaoX;rz%v z-nxo_o{W{T!b9vT;bwd=^D5#=`sJ~eg(ID)0LP)F^u3K?68jU%zJmLT;_8KKwNTbj zy@Tt-p2U+I4|HH&En6bq!?1D`u=qQM?oYc!;WJ6L zcfz5Zwxr6(g7f>99!Uk5Wl-8C*6a-J&4r#{NLwKYUwCQiL%OW}(uh_*K8CjE$OvNKZ`cyjwDXVJz;r`}6kG zKN=`8!o}@f)4rl_eanq37?)ok4~KCKvnWLDC{i#$#GRM%uf0Ks0)d7N^=Am=>x;qx zAM6Dh>MpaNNs|kX`gIq^3I_)#Y;>ugi%$VL1j5RjB%t6xNQs(T$&wodh6)O791s;g zFb2BZukS#msDM)zBQj72;>V7$fer5N*1zBSzDlbI;sj1bLrY8lMoUn3fHc@gY)Gbv z9PRw4{m?x)09D8Y0|IIA9Z(n?5D1SHmV%CY|MG$b)oBu;capW+oy+p*~_JGOXPFh~NPxp|2Am6MDTo z&>x{+ax33*C=dW{yu7lyv);+?aex*~>{l{EsF32#Z>9z8SQjXsepIHsKcO{DGtiVU z5TyBn5rz<0A+yllfA(SONOSHgotYFxhhbnwkl!r$=peu)4(kRqxeiXlNdzbN6y7<| zDngyy!-yR<`(^=4`#3ld{#QLDz4j}J5f9=YKrOER1jW)^Q6c_$k`l?bFiKgOZ)8Yh zP{2r*5mz3Wq`I^;8bq)sh>-vac0%s4oX>onf$)4TlV6~aKN}pP%K$Pcd@yhSoj-^_ z-5Na9kP)BJ9{`a5ZWdEW6$2(j)ImrhjTImEt&@i^l>1x%kntz@E2wtR-3B^jpdSG6 zZ61}1jS=$e4Il?}?IroqG2->{!~Z+yZI@Y1?Jx42fut-J6&WoxI0j~NJeahM3^+JY zYXk)WxCnK2t4m*m4oCIbsq@ABU1?G)2!`@z5{uX8zp@~)uLche_eJl77f%Kg=pPQ~ zEe6mY`>VXo(g6R}I2wr&6(9~YH1{;V{Db>%9D;9ug6TKqaCLz`DSF@$0h6qdK5e!6 zaWHPq0l7-__&D|um_@AmQz8Xu14I$KT=}HAXqF99Jovzx7V??5gS>0C-bQLi&AH!X=kHEIw3Q#Fy zg4iRTpG_ZMEsPfQ4rrGrLr$;PFlpBj^LXpt;!`M-39u^@w|j&!Y{v&V!|>{w@?#1| zHA}rSey7J~p^FV3#;WR=Xe#(%R~@oI_4s&xzp2@0yy^GIyT_=iae-fA3fkse^%n`K zj|`1&Olt;OS0sj6nNh=PXhm%e*2&Jvn5o{I;DDo%^_Zd?V()#0B+n=_B|WheW)$1{p@ zQoe*53Rel=h1C%4j|FK_Cf*Nby@%qW-Z>_>>Q+AXZ;j)(_YBGVD(l!e9v^iRw)199 zD=l;k&xR){bDL%83I6r@{Lm}=oH&KSifKb!9zOZ?XZzWOL(pFWD%q~S!TUnZ7h7N%#3#|O=(c&$o#e-a%<5pvNMTcrx!o6#E zPMuq-7lM7xI^Fo6)-Kwu;PNM=j;?9WHb?8@i6!>-qlD0)DiYpf#&*Js)VhMuwzuvs z4(uVErTuA?)@;6=OZk8Iw8fj^(K25_3LgVzZ?>Y5MmcjqX5;_p#a>~g#LTO`oQ*Fm zrR(j`;trYc(9MIL8W#U)c&y;~z(z_3tcOv2uCY zCvTxnd4j#+;N0KE6Lb(^*Tz@|TygOLi4%scL~5RZb!wrO8F3VN+Qtzw(bWbxjoSawjd@AV!(nZvy+j^-}#W?YDoi8J1%#(!!Ra1z@ z(MQF(Jrxb~$No0xj*5dnsV$tP`WXX{@jEh|zGZ3mSK@72N~8HGxizxeXkC-P zaT&e<x4HQ=3V_lL;+jd=U{issTXK+TiF}3%p;_BYY#mfl!KO&1O)o7oa`=~iDkW!Il6>#vz}Vz>ZMu;9_{hT2$wb?=*|^V;9m@cR#& z<2Hrn$1E4*SnSfmy)EIHgMpcyuw+73ecLw7NjB zww`b9yzsci|299l$lQ-VR}m^KzxiEFu45mS<3*;RpWvD^643c-_6bsMc|JF1H9XDf z{o1UdZUC)jr==O3pKxU=A=GF>JyW~kUI(Ju@ zDQHFV9KacaB~f_xTF>xP&h_)BTv$%=&s58?0WftQ8PEvcl~Yx$B#EuDT$+{3MZ z(B}G*lN;IKuVUR9dc1NMAOK@!Rrc(MWA|(rMp_)^jx(cTnaT=GY>&uB7+7Q%)CnP%inVIo zjz87W$R4B-B){bmm3VX+{_C-vphT6YhJ7u_@}^=RIvZA-aRRyutH>s8p0)qPsHkvtSaHG?iNd-{p)D%{z$ zC9EZat;=~~u)B%yld$12!PxO~8&WeLwZ*FPNSONEK%%&dyu)XDJxLz>M^HI7w&NJ~ zI_|i`;7?c28<-?~rr%9<@hB%>Tz~Z3QAd6pAGn4-vp!GCF?(^Xoq@Z>!1uUbMbfhC zcx3=qwuOArRtl8y zx~TJl7P0jWO~uIQa^cFpmQpUutIi#@8rDr?*i7b$mRV4 zNx!!K61I3LIOQBlWq&O9yk&;`{V6}?IlXB|ZjJcwVM-*z183;_61SuHs$TM$p1|igD_JZK~#h7;IZF+30$UU)KQV2T(Q7_G}gU zA~N9!B@2eWn15b7`usAE$~WoQOk9m=gns`U+y;8Q-yFFo#@jg90t%0`FUHhZa^h7i z!Vv0^%R*#O%)hi_UcU-aqQ%e7-IT)Apj@MMEH}}ud3LoiqZy-L*m=D*n_8;oA5F7U z_Jr4eRgmWsb8g=OPk5q{iH&}u#Vm?jjpMm6{R1(OL92$HiAmNGJ3FgcO=VMUzG(82 z|I{I(-O4o&x9v)lJ!K@8LD^zzX(oQ2goK%P-}$piKv+@=`mBZr=h7(sFKLXi-Etni zL2*W7zX&SbJJwd|qOp2V-H1gLpC+FV}Pqbc2G*$EOyggoC%lQWG#|;TW0N7mGX`|kn@Y$X14e$IAqz~l4 zzyeRt;qK_ztQ+(!yl8a=iXA?#N_;7TmunJE-~8}HGz|aP436KjIN|*Rk&&H*5Gul0 z1ed4BfnI!(tn!f0LM)ZU3HMXY-=_VY(&!ttPAvw(PJjUXB0cU)JIBII$ZHc{j8XIM z&td%IO@g!}|1s6x*B7$Z85ElP(x#1H{1xT@{AVv_(G&FM-!oyd9tvzuQM3cl^Dpd) z$HT`1j7RRRqcN9WSz0A8XmwIli!LG5JWA8l@_LY?>o1nL2h)Z%_VXW-FLCWU+*7950}U_QdUhwDX-w34<|I@5)!DDh=aSCaQ~)x$cpXGh?o(; z`5#i1<#%$BEW54WrboiICPkP*vFF6Iww6 zi+|KI7kuKa|7LSE*w<98EdA?ZTNo9tWIWL)zZQ+=*veAS!*j?A+o*s3W*#OHsQnA| z+pH|8o_yM+JtTCXJvP??7lwx?DK)62Ns{0A^b}K&D}BF=xW_?7hZIDUh^&nC?e%De zck^>7CCdWa!D<8Qkb4EYRs4#`Er__^xzv=_cC4FT&e5z3#nf&#awLm%yFl3 zI5jTeWhzzR9IWs$;TNx9Q}qie!P(JcsF+E-yYuKGywD=pMR=ivOb~H7jYQ zr>fiZ&yQ?hCpDWJ*L@3@o!3-*h@!tafHks&<}%oyM*BNi#c-qI^cWLq3f8pI`;o{g zso48N4_PPuCim&b4~3gKurqu2Yh<5%`^a{VgTE+dLgG}tL|}$-|HhRXw^ z*|EZdSHvvACOifNQ7@pIAz>fDkea;rVzlcUl#*Bau|sqeol?8nFXV#rNeK_kD=29m zjWhYkdsH77F3uRts4?_+5uKLHq-K4MTnw#03~Yu*e=dSA}L zr3SQ=yc)RqM>!{duIM&m7iv~c26gV({a!6Y` z`g_Z+m*S3c896K)EUYM;cUt-d77h+`4-@=(b&oxSs`=$n1Dz9MHhjuQ!&>(JBU|WI zSzg8GzP3{ZN6i^sL`R{uv0jq0-WH0&Lcqkz-#S&n-nGA&!o}mrV(0W>J+|rMx36Vzz=TFaMDstre57`h zoce4coSk$onIH(BHf2&aATOXf#4RLq#&dFH0l zzmQu~We7Phn=@=>g)rDDvb$derN#Oj5>`Z>nLpvU?i`C{V?o}Hs%&NeVo(JS%}S)} z%TmSM6(eW1sd`YBz3i3qd&!a+yJZ4!HKcj|QW2^bfoBOq4Cq2FK25io*F?DvOGb@Z z1>;Sj3qE7nY(a+!bfIpsW$_kQ!uZ zVySCj+a~{c%^2$%xW_4vE(0s5YDp0hpO6L^cMSBv|$O^jYFd5(xH!2?xrygU5P## zupsuvh4ye?J>hk-SA&R<8g@ zx^o{&y1ZJgkXO6(1E5{PdNkSg^j(yo{(HI^jTrAea{b4d_^-?0BpP3O}vo@8-OyN2?caHJ|TqDbP96Ny?HLG1))6wT+5x^Cc{l z!rY^;lc^yOe64OT-`>Y#`+P?}I-s537EP(ENulG05wOjK5<1meVm?#zxgyV7H=Ni$ z#vI)}SsL07kI|_f%w(AY2I=>#^2FxUCwHhtG~&zO%bcxVbl0WZlPcdobGB#o?9x(i zO+Ip{IHwjr(-iw`6E#JX)zdfnua~}R)2U(I(IN_|?f)T`ut(}W!NIP_8_=mc6q|%2 zN+I92Xt^ITL}mr&p}&qkQ3*@DXY$;rIciU~IFBvHrpai#ju_f|=T z`d5-#ASTrJUDnM=xFYS`zHKP(5z%?c55%3oZw3^J0Pho{YBK8c)J`P->e)@qn{?!( z#``lCADVfl7>wY?FEJqR3;*;v7Ovt%&f3WoQ(F_HtbxU+oLN(IRpX-r>*hq+a>e)mqB7$FFMvVnk%Uv z0GLdR_AFQ*s`P#yEgUcDA|WaN-xO&2y$_N!ON7pa4@A1D4r~=Li=K!NTxYuKBdT`Y z5l741m_nSbyEw!@Th5d^mNhkcB}ny0*_BeSAWMY=POcIi<*uJ6r2X03?Altq&2l$> zI4LjWG34i0dh!)gK0i_DW$2}JH`?~&o~PBLydk>wqN+*bjgqZh7E{4EbD|!*o6)|A zJg}Bs6LMRRIb+Nf_=ltplE`qaUQ}@)e4K0H^j~(D5H3LKp7cc{zU8Ms*5%VwkDrSk zB(E1%ATu#C)_a-vATsj&8SIH#?s-i{yKUX=LBaXAq$4KfnRDR{Q@?SX^V>brfMwn8 zsovSBS0wq2ND6gV@JW+%>xBkfWLv@~Xfr5KcD{j61T;V>vbb~{-cz!W2mysc|1deP8qJ3PDwa)O^+D?&KwA7 z_F(h=Ul|<7e`IhhO#h#jW+7tcU}s|ee<=0;gr}J~IoY}Xmqyy?7jT!N&6WVf(U$B; z+fDH>0$$9`mPN+}DV`Qvmo?$htF@MD#?LJ0*_~Ga5NDUuD!Sq|UE8^a{nRTe@RwAw z@X*o@4wa?-=|JDW*c3d9iei$H5fl?^BQpzY3&9I=2&nO=NduZV9Jo2r;&? z37Wl6HFQP5mrXZKuPdK_{h`~BHo5Rrf= zw7fHfc6RXIE28+Q)7Hjy$HLs+*~$82oriUUHywUq4t$GVj}C-J$RaNZZw}*5V;n?` zRA)D45owwZ^ za}2ZU?)XDCG<~KvCPYMZR|h3zmlkJp_f0K8!Mu@B&z>FZiy$*K zuzpX@jg71W7I(*{#}-D$-WK-^%JD$S#QuVc=VAg%1uW1hWuUPw#4Thpd#y}AXs1p& zWY*Fn*Ecu7u648a0TT*a3$VW*+HZ4Yf!w;*yx#7-w?JZ68D5pf-U%jGS3~92Mi&>z ziE!ZPi3-GP>lFSO*q))e`HA^46bJ#R5HdP^NiUY-qYDT?X8a-btr5z=9@-l^VBG>& z$Uug5?-V(!wJ`w?W$)k!?&%p&df<DmYodiZc05{HnoTO43c$xm^2@TNSR_9iq{>>~5;<<}N#uk9}c?7zv=&37UiVlyAwik$8 zGM%0*9blUsm{JL3x93Q46C(GvnC!JnQ(!bd0TzDZv!Gwj>I}U%vIC33{AT8W`Wgc> zLpx8kMkdF55IEf2xSj*PInR`iAYEDlr3)Bm_qFCwOw1eWojx5P0@hEEY3scG->!98 z_#hMsy}y7I3?NBsyF-YEXuwPl5Lq-JIfFS!($Ve^m|@~a<{F4Bi$6MVfYgiq0R+=H zP%ih9`YW|f(1hk&t_p-Ax%Zs4+}!&%*^>8_!+?EANZN5>p$=_QMZ5K zXQJ+ZBkO0P9{<44L_Pn3pNV??3;$R1o47hTeZC3)bxVCt#{clYUOPab2hap=>5sh$ zUx-zGNatg%2);YR-UKT<;^1}EEsVyl1g_hGa*!DR(+yie^rA@5+;EiL<;b>%Lrfx3(dhovAt2MXSoN`>pUS4K}^w z)!uyOkrY2=YxP5w#RW7~^C=?&*hEY;G!8d68vG;RThz@eMna6@@hkcxQa)wiYS&H3037nUB>Y&@skU(l< z=P^|wGQKRC-KlHo>)jX`74ufEiyl~ixM7g(lE zU`L~aonkHNMSl|R_^SkiWXC{TE!Y^W1x>otsTX$kBTK_mkRV50y%3#{1$`|f@Zp?1 zACuy-%)?9_dtvINVrm;kOJq6$sXNCV>NkDPwg1C%Gx$qmG}=Ha;@2OzzR2u4BLp{j zQU@b&)#vXFr6oA|<_FE;zAo1tTf*MBlqqFXTC;aqhLJLG!9FYb&ZyItX0vZ?I|QTQ zdLJPT{9q9{UaxhhmLD14ZL%&kQa?fo)$7L05~AQMd?)i9WAshvLxn3-ydxS$Is5!B zHiV*NRlDoUe>J$>kta9YS~if9U)6v42ABVXIOpq1d87(*l-!Cb4JSY?lG+btFYVwJrc}+Jw zT8(ecF(*n8?@M;ouojx{>U?-bi~~l*T$)2O9AMsl&?k-OiJ^29vJPKPoQwN7) zW++k09;7Dx-;$O${1h#!q9~Xz441>jtM)eO!ebrJua@l)_!5||?lqfoOEVQf+CdQ9 zwM}a+*)ICNMyKzS(veeh%p>_QCaXN0#~Ln5=~Q5POfC{A@HkU84{_l*Qozs(EHvLz zB)#Pz!+0eY$g)X_P@D+ITj$2k5O3bhm@)-`Rp@1#-~0*;VjaC7D(2UHiKN&_vYXVP z4#wbcmBHGeoLM(5kbx~U)2QuqsnAP((u3?eW@9D312eupD$9oaiUig)t?C!><*ux{ z3Gt9J+3@YiVpG#uN`$mwhvEP^VQ@T^blT#)ga4x`_A3_`TD1jPZVDNGI<(s4WK^CD z0))I6D3N*AT)T?O8(aR0uY!rMVc+%lgu=JLbg8l$T_%fZJ14zA9t}KXpjnpKR=x>S z1LRLRyT9NOhq~`g%cj0==~XwE6=;UMNg)F`4)_Rfu)5p$tQL1YxqULA)>!>>M57h*gUPg{{Q#y=&Xi>+Y)7MyuBb=pPk(aQ7cV@nRm;` zVzqq;{Dp|1BLLKn#NoWa*RrGgn~kG1RbirF6d3FC9n$x1nEGXrFOxP&A*>aEnnJRq zXD9@n4*by{&OOBT`3SHe?Jwdk*Dps#yK;m96aJ~ZzDp=Sd6*QI^vupWpfs0k%&rR< zo+T%I76JWQ0C*9WYn(9U!4%|LCf0XufGXzEkG+nvVZVj%R_wnqX&FLOnbUA!jFcbo>edEXAm?Z$J4yW{Non&0@YKya^;>|N zWF0mdHJN*rS8v$kPNtCyN9b|G=U3*a95hSZD&00-X;?J=0$CjY>7^%$f+@3@*X^~^ zaJVl&;X^7WQS0t2x}Q1lv*@UrxtfjA;l?eLU76Q)NG{F&=PjL`*qonR_x&Fidywpg zAl_7?26{x#AYxr;TrC{#^Plnn=e_#g%gM{jl*uOEKO$AA`RwiOk zcsdj!lK7!gTk!!(Y=cvtb$?IJZa!k2FqMs1g#Rt+&N^4+?AkP(6*HU z`spjM z&~Kdee66GAtIT7qTRl6z9b;I0^y8|+9?(O%3miXosw$yWPFY~q>B^WEQP9gao7dbI zYWC10ineTfOy9q>Qx|-`2+Uul7-@Z@p6*c-O27?HA7{isG-8p5U~F`69m!*VE#8M=7R$e-O^(;g`Y0G z1aX1pJsX3Ahmv%*LB~$XY=5xo%V;rNTr}nIT~)y4iE|#-18;|5D3O7xRvySHg5X zD?lw0YbPX@4naUn^je|chN4Z7nqUYA7&UXFVF|VyJ9%#L(ooGzN z`s9DvW-DzK$>Qty)=^=g#ERv!X2gA3^xH3Dbj-S5Y3rWd{;AmDzPNqdJF9o53v7F?{bd&Cx9oO2Bqx>v<%I_v5XVWiAHA zxCIPRyqM<=+jmsbFdY0(cNO!4$wAAmUB1d{aF5J=ghQjJrK-@F7l$J-sX^7$@%jUJ zYZ>){sGKGHl{0p$FkR5z<&}ey_3G**AFH!PTVs;^y<0(q12>5*Z+hm z|D52;*qF#)jt(;;gVk}p!psa+IVd&+rPmM=f)vi~5JMh$!Ja89jLJRc03N1NpH>4s zKiR0hv?wzo(!TlXC2EThDJ2=%=A0FmrjZhe{)`z+x7Zl^&}IH!kP!j@_7QU2MN)6x zh!{X+)-UAP;NB7GvXCj4uRZ_b@^D89ISrOe&rb&OMzgJzM(>sOG~g9I)g1!~yh~*^LXB~D zBeL>OA4#&VP=Yrn*kQWFX%K+=gM4!zZ=k0RLX_Lwo8om$oP?luK~Mg*Y?=qvYW#df zd!y+#?gNGJ!ylbvyKAGR#3f{YRM~N?`fMqEM#|b`;(qJgyD$sZr$nXw3G7WC6b1ee zdr%LPPj%$WFoKAikWh4La_&aQ zJlIZK!dGi&0UI~t^~nNIFz(+z^~3$TKMg3nFK0>{1Su)K2xOo!Gw*7VG@ifyRDHHo z7m2y}T0pl3GMh*~Ebg0#(0M0y_j;HG6fl$bK^_FqozZOCqeN%vOBmj_l(!tM%D5$> z?c$$vT?Ck+%5^r-Id|lVd*!k^UkyN(zBeDU)Ab(tcXdVX@d}FA`8zzTG5uL;rPTb0 zo%>z1mbao7OE0Vz9Lncj0ssC`Hiw&YUR&-p+&Npai8Xob1)P6?0bjFDG!gI`y1X;m zeUdhuHzddYe$W03^%)s%GI|qDdPzz@lZna&M&m={ZF=POV8WGvgVuNe92$q`RdM?_ zcuXVZT#fH?3t1K|%qrX;uIDg;gK#FF=O(ctP1ekSxls+Q9ujwv)Kh%x;onqh3jD&V z(?KCI)jzG3xXo}Y+609v4sWVL#{he3Aglp$Oifz{-E!T!h=Lo0G32RpOTVKQ7SHPB zRTU9A`XmL`X(9(n$QHOkfj++%$CKvF>r$W$6s!LzgSDdHt@7gKm1dPdW+tuZs*AjK z$3mL&3magMG_F-&!fkyG;Zw+6pWyIvc?VOlz4+c_Ir#olHezA1PVdCs(zf@oUw*VC z?|#dqSfOP)*IF=9TBZsBUgAt(P*Z2{a;$X;!c>T{Dt$>IJqcqLnWX1$fQCRCx&``& zBc6^&VrmABRqYq_SnKeD-j72UumG>eLeZS4;cj)uZ7of7TJlDwu`clWWD8OL_ zBu{Uu2st6~PuHV#|LKdr2*uH9E4#}#b`#WIAx(*(ty(wx)AW8D+S%NR!I%>j`@={g z?x&cVR~Zz`C)UQk<*SYQ(Ah{%KS`rRwF8oTD3M-A+20T~%e(Y;5BRa21$k$<6lpi|(I9RxXvQe_F2}Es%x>zZ9 z5VoWD^zS2J|ARH|Tmm}6JK&+1(UgUK6fCD{#7g!I2NMhK>f%n_{JIE8=L#P{uW#HL zD>_`*MiT58TnHi^vF)eCG_?`M(`B7T|*Ev_KBYA!l{BsY3WGktJ_K8LbvWsN-o^Z`j9(OWx4*D zwkvDI)8w_L(c@e&nmlPLUJD7MDgBI=scX8Dm1x!FPs8T1N@4d#Wdi`|!t|H>Qu175 ztAe4sCd1)iiTTBkLvYGmSZjr2H-!#wx{v2=yLF)@iTQV91B5lVFw$#e&2NOz`&xP= z$L}J)`;u0{#7`pIj@T7N%Uxlvdv-iskf*%#94gy}OOi>8V!tyA^^GM?*UT}k+N|o> ztWjnjVBn!es`$lexQmh$+$KJ}*y#;&)5&nSYw1b5p|95eew`6ExkkGN_3KW+TRZDioiom!PM%_XP2jEe5s*#U(ctzw7}eFc!qK@lsHc=( zdAnA!Mo6Vg%GM|oviot>auaVaTgVf^^Yz3y*kj5}9a}y=P6Ji>p->n(OnsGsvl_T^ zwA9v4Cxg{6nBsCtqG5*XK6u_@E222o86dxPyVC~#raiAUEx+>Rs<`mMQ?^n$iH4v@ z2^5?agq&Y9YUvQ?^v}x0S_iN)Z7)Y54Wbf9kg{ErPMzAuuvjCtUsMPA=KLHb zc}#}M9*ZkXOj2>%|D<=B$`2J9GY@_r?M99Mv2HP-y>MBt5{w~RG6WE$os%kumyBD& z-SOrVqXOE_)_bj%ccR2rKF4~s)lzDUL&J8Xzu`An=U zaS_fmH2UbJs}T2=_hsMLqcd4BRR$LC0MwH>1K$U$hX~>lS`UfM*@>s?*=?A52Q*c{ z>85;S%#1_4^DHJ1B=RDH^f-cb?C3Lmxb=u?#B%AeJ4NR~zy2nrRSYW9o@*KUoob$3 zvrcQ+DD=7#51mz{6c!~0FBZ~~eSJeCKQAG^jMBF{bAhL-Issyj=kmok61H6T2eg_1 z)6&cBOMvt6^uXOf4{`K;vrC1LSaE}rnIv|}{f|-DRYs$;@6=)>iyNTg#=Uni1Y;Rc z5@jBEOI8$Ttzxu0i$tY-`rF(DqDtV7D#B8P0ahsdi#5*eU@%wC(K9DA< zUm)kiy?-s&;RfR9PlN1c`=bgXNzWcjcA5NIRusn+yIlVRW=VYHoHTv86VjZ5Qy&2~ zS)+}{Ey9_cET^qtf&blB;z7zmGkY%geka#}uLEz_l@OcB#elLKzO%kscPA({H%l<{ zqYEb^>D{c{9p6|_(8uuOmEgzNZ%O9^sfT9q<+&{HU9YKJtWJK1xOsfuOMedRX?qiW zJcn;TiC3fVx0^7n6cO$Wjkg^LKOhFJqJpp3H1>N`upwRqZ{HNmk_P+I|GEA z(C1X4MdD5k%e`nik_kLX)O%;iMFUSmJ??SPXhV&8 z6_~i_sI>QrvYl0*AbaqBLR<`UI>X!PGtP%n*bkWDOK0$R755zHOvR;f!xH&%mMcMX zL;&9SLj`mbbzb~_0E{HZ(i{1@aP7x}@Zp3iFC=vjdO>%TvZ~)RLoED_ixi!%cN07) zsFTS@Nr-IGWaVD=a`J2k1#t#8^%gy;Hn0vOls~VVK&?KGBcZoeds09$g-#}}kcYw~ z<3bJsZ^4NYtI>Vz{fq42^T=Ho>dYG!8I7~FAPfC+uT8F5g-qe2pw_7u-Yw%%=v|l8 zy4Kr430wD!PD2vomqg5b2ZaWI(oHKjJfkamNL<1PjbFB1N-}cd zIbe0zwHe=dWEFi>jGLvK)=?B27NiZ2G>TH)tTKZWWOvcDnf%?QU&`VVG{_(As@=UhG`9+4o<3^rIw*4}%n&!*OlS3K|CkTpTF=C-IR|AO>FsiaFAs#k_H|d>D-f!zA_M8kVeK~ z@o-s%@e~?&U-*nC`x4u{9~RJ4#tgo@_h9WfINdyHLtsd0iIbkY=w05ch^m3jmL}xz zJZff|Mzui47^ZIMo)3b{kf*kfDl}md$>F||2uJ7H3UZH9Om(!OI;OwOaB;*(x|6wa zd2!gDT3w;QQKzs!kpva(b>-J?w%9l?*i#GnQd(59`1EAYYwnka9f+_agrJ1p0lJyd z=}tZKGJZ##HW<8Ht41bX{LVxQO6_{FWfN50EsokbH7hJ8wZg|SDewlKI}+I3e4Gd5BZ^$XMuY|@aPgqwwr9%UhS6d{$7P!0aBL$?=$s0D$|jV?QC~d#5oeRzJ|(Z&8{3$ zvp$8T#Iyv4kZBv`!^tP>_r_`cR42TZ{Lbx!*+z|We>W&f;s4xE2Ue%*OhCK<@qh!8 z)vnnsMuhQTT>gk1j#Goz@aWjwAK#VK^P76FQu9~4jd}7;CDeS@EC|*iZr;rhHHAi zDXH7t_6Eg8uJe*+=7xP=DT11*;?9aOp-~X5$;~0(sD!L}%X-2365rCiUi1s60Q8$u z9zwHtc&H45x;j$ihq0R~DKdtt;P1EPb2CQ^f6{o13hA{TcV{eUv3G8Yp{EU6NuQBjK6jBZ94Y%9$QdCgv&F z829v==#C3d`*ZELobC;ZKkn&{?a>ryg@j5=vEyjJiPCHM6P+}dcbn?o0u&B(==)!b z;nR&4W7eymoDN#lXh^c2=M}<+V#{Y8pQ)K(>P9%LhV)vBY6Y!lg@6x4OKN!hOSdk}~$Dr6d zQ;iYrsUA`*AJyaXr+bO;1!{rwmkPHC5#(ufbLQN#N>&+~_E!t^Aus(zgrbVmqBja8 z=&av>1Ffg%VKed-powW#;gi2jSE3=X2m8bKbzq0$`mz+kZX$VvYvPJK3wZ|>mKgER zfG=APWpDO=TPKX&6Ml?uo2++;11KW)Q}vf9Z&R5f%~D72%n;xrGgL+lECTi7KETJO z!j?p$wR_2f;sx=LL=U>n@nl*ve3in;6p`?EBw|I}1lqTI9dw?StQ|;b%^zVm+ zf`gc)TVW5&upaO0V0B-1pMJm*jx6>!XCAavdVP+?FxJy24aVFHj)?G^6o(?T=tVVXtGizi0S_st)&T=OZ4C{#2i3#qQtbe8&~$>DNA-Fud;Elr1Gb0U|e z{vFEqa*|)MLT-9@=2YUQYTJpm87Am?)%b0^=PEM>EOZncT+}#t-|w3TVI6n&f!uA_ zuHs&ya^AzBkn&6e?fKR;?|wBNNe62O0|b|Qw3uNV@;0wp%Qx-FdS{)-07uGSZ4=mtA%k2BsX+Ij_D`vtr{z1F)WZWbY(eS2q};uh*Mjw z0AwjpZUz1aC_k|3J{e{1qWRdJwg>+3W9;F;_=ejL*3RBlUD~3GeGoqvoI%Q zyPWUeGzcznhT4Ak##;q-vnCc7V86LZb)nfz&bn@!C3icb@vx^!O^qs4^0d1UDouv} zFa{2!yyzB-%35_ts1w7L^DKsjK*hBc%BKnIBAp~>|5hPz7QneaNJtzxqH-mHxFPR} z4+RHc@gmoGoYgdSLUcvLZbs*t&CCA^+HN4jvA$_7V1JtiJVS*qpm<8nns7La<0c1^ zcL(ak*GIQ-7--E#%9-{;^=m5;fFXk$>TtI- zABl*0{-Pr0MQe{M{WxG|;A1L#kN?J!@Q2I^#0IfUc|BG-_h%B+TIUGHT*8#|SZ%YM zhnsT@O3AwxY~~y`!I#1(H+<;9LB4hvq;qJ#ccaB2IQr~F8XYNUan@Yvmes9_PQp#1l+gKxjpy`G2ePxtb2I18LTLUExyOI3KKR46L&Qdgu z1fdTpOY!H5-A`({>2Q49XN(;IM6g7quJCE8?P5;+%;BM@IxJ~e;p7ErN+?po(!XlN ziIlQDe(fiOv%JG|6I5A)KBk|R5UYAl@%Q!NT1Jyc5+pG3U$5?$yG{3AnMAV_;GriQ zJ87}JeS1@u%fV#U9PDuS<0Or)epxQ_&EM?z^($3_TiI5*1?Qcqtn!tu81JDZx{^HXbCWlK+$Tqp-N0GL(d9BTSCyPlQJ#L_cUfMI<$?3x;>YWqt} zOSffbp(=RT?+lg`3`E77&vMqdqBOr)i7N^ugt4c7#ymBQt(d;_<9m79O|;j}~33V{sx7& z-m8&Fg0vd&WhR;14nYhw4DW?9>??#-COSbp4)I`+BXp_JpWG5GEYy7ZV zMg3{0($|sOui^Em2OA^&TiSNJm-0;<2KeR8!61q`aR~!NEbltda5;gg^M~H%3nr3b z1$0z{K>?9}nkyH5lTkI!<=Vnpy*OKF7W;D{>>Z4*_XB)V8AY!DGGpu&NH>zE3kqty zF#~d^_5>pah+0U?JA3uvzAJP2Cbt`oT$eXUlkIx}C9ZU%O@d?;olf(0FlK0T;14UJ z$JQ-u`Iyv;7nI!z(YcNRJ6g8fUp*n~Zn-SjWr@unoNwF* zXZhH)y;iH1`1AokLo*C00BWiiRN&tPD1#u<8zr?s<|TNyx1Y}Eh^+83qY zBf0R}9Blmd5jDZ(Bl~Bk(Vknld`uIFU3DA-Ik9xh05Yj(DM5VO&jN{w%i+?*K;o)q z%@^O2R;|5JpjpiRF%iHy%)d^T2~9*sdFDz#npg~Qr3$w0tw|zxxNvkLKNr3XZ$=qv z3`*P6CV?s0u-w5ryO+P4e!-|Uq?_T^&+9*ZozE>4Xcqxqt3KC{(a=wxDQRnXQFhssF zFH~SAoL<`L5O*n+5pn)29HqVMEv3ww__dB4Xqks5#LqF)LJ(V{KNQVjv^3f3Iww@O zjw*4pn`zSy7p`8=sU3h?!@f-Y9dM6 z9GDvZfn$c_k~qHqZA~D{t?f$*hql3V3@lF;Q+pTv7wX#_Fs`DfzE^U(0Yv3OMV4F( z0+LstV*^uL_9Co=4568q_Gzh)`}CJ@hlbu7%{t6X10zMDn-HsYh?7*$ZTWVFEGg8i@uF~e6vACLgV^m$s* zh2AO!Qip-F=s@n-m5d<1W_Y&1`yk0oCr(GH9T%vtmp?dke?G5CaHV0ZiR+!J-`Q=_hEC0i+I15)nC+el6;j-0b8iHwp%}g@CmMva zq#I7)B*3%Vl$XHB-t4 zy{PYd=IoHbRN>YIIlS9bl8*1-ETmvb*=8h{9u#0|2;Rtn!%=`=2-@fIk_K5yTKP5p z&GyJP=w%L4`!ED5*a0lfEu0jd^2Rx=BHaoU{iOjmV>8w_P}_4fyk8g;RIZDv*E#f@ zlkpA7%Q9{kxdUFz7H9PIW+zb;VM17COW|OkKXpmFqQU23YQTGiu1A(P!B8Ej_m-YD zkX-d-he?XvVicC6ZoAl1}C7a`{I!TY-$Cl+R4QBWPi&D zMkSd40mXL{L{t9)IqeoLYwUe%tj-e$AnI8aPqpcp~XKBP2M&1WXH+^T6;7SZiTNSKfU4~Ts4ARTVlSBew79^sQmrqtb41VDF(As z#eXB0a{LgZeQ`Z;Mh~okS*9dKR>@=#6_J%eJ0p)(U>$yCY~*)q1;d3%7%S`v*Gmy8 zFB3<*YkjF!5k8OW>9Xz_Ph6~%fek2ul>DVf1x4_B!- z@%ZfoUg23@)VSU>ad=~nO$)1i)`>9>CdLt7(I;TAj9>bUUb!BnAWPXpG za0GU0Bx<{z;HqPnM)o&klBMm4hl;k*e}GT@!3Xwa$yH{;%?rSCvi8BB-b!auCcGl0 zA@T$~2z9`%S8kt$3)glI%flM;uMY4L0w-l7b?K#4 zoA*H-O=fB^vy#WW1*4!90ww23u_Z5pi@w(ec;fRxlmMI5AL2Tt{j!`-Av(m9-$7Fr zE%>?2k$aJWiO4N(Al!S5*zc3cxauUMS%>a_%FcKj=U!ev$Q)f3*;N9-h?XrpE zAlw-qZ+j&W?YCVJ^ThG8P7CB(9F71-ZNVynDSjfuN53Fi39)lz!Q{N`Iaa^ZJz7r! z*4v5AmyF2Fn9Qtq%RnjqWec;qX4*5~zBOxgEHA?V$6@G%@?5sseQ$@9>e?Z9SVDu{ zWpN2uKC!~hCuwwiT!&gJymX6{-AulOwWbQ8oFIw19C!NtX0j3!XxZ-vuV*l9D`$LB zf%J;9kiQy=sx6M9g3!gGX+0Xd9PpfJN#`R%J&d+>a%ZSl-{_WqmS8_ajBD+6%SA4PG*bA3MozbU#*C#Ih-q=(BY`*V>bF|qRtBFSD$ zAr7+n|Fj$z_3m0|81Obl1x}}I9S1Fh?I*$HOYODtddh8YOOSNIofip<(WQ?2Tf*zO z)ECOB4g;;Hpx7flD3ue5ou?4%TuQ0xT+P{lvzTI_Ezb&_6CVz zF>9+x2icsZ0tnz`<-+5$4TSKuZumjWQl4;UmjYG4iJqYw7!YPGAwa904e#it?uS~& zU&3}yh9!7U1T$l*GZ9j8uqNRo@0cjr4r<*wI?!%vQCWF*dB*8q<0S#LI=YR)_{^u{?YrKvX7>(fBYGybqR4 zx*VgUzzURm%HDbtFyynpV#+YdH}l~-QTchY=?=H2Q4#JOg;PomnChbT$oHyX5_xZ0 z1?4645lJU_lOFAy+*##{oYs8}?xRF7GyFl{5>V>n18x-U<^+`s>@pu;LeeB{uz?7D z-bx#Y0GWxeU~iRDRUNd%1n!3Z&M4|CrCIx-%gK{bF_Ntj_K*pHri{iC=)kwIBOapY z?Cz0Uk{J;t9uMpcz%*R9Rg189u8vtEV%R)Zmo9kBskK_-i2_^RzQ&W(0$=LQK4w~s@>4%vg1WaX;SZ<(@5JAhoq zkNl5wM%V`L% z8iryhcTMPxVq{D_plTlcaVYiYv!_%7hYUQ;B8kXr-ZwCmZ>Z+*H)P0=-I6u=0kjT9 zgywSJVEB%8sY^kV{UAe&$%ba5J?|OvHIAbFS1luu7SacpOt0v+s2#W9!1BuuKP`A<{(sJW4NQ`>WZb^ zu}?van@p^RWHm#;5ffxyiR?%X7yl-rGdOg)m`ZIC(4MfTfy zZ^9qMxugbma$mjIs5%Nhzikc?hxZgBfB6@zc}7{3>Nh8iRhzoMr?SHLc5j2l%taE4h8yTELDrvCqrSeTKuecy7MpWK+;2w4jH|`r{N$CYL+CXTEyo$-*=KWNe=skh`1a_;vqUYb04pmo zms}TC7n1tPhV#;6``>dX*!vWPxmJ+LTv|N7ED(dM9-5cS7op2Lj4B5I5b|!vkM&cq`sh!mw? zc=)_F%62A*53qCbZo;IDN)L{ci?LF_uAlK8i|yc#fn4BgBj^hO55(K#_hsG(vcj(l zd~ulc-D1Mutw2+T;kKCSEO2ShOIh%4Qp|x|$5X(YGVE`iT-d$q!4aC1#=HcPTj>ur zse;)`kwYoH!@{*p;6eJnTIu!Z=??@rJggaWVX$Lj*@!+>koR&H`r2L>v?kQ*_)a7H z265GXGQw{R6*vzm&M;9}+HzmFMyAf-t*s{taU#JqtG3>%$50lhg0gLuw%4m7 zH@;C$W|69Sm8b+`Ri6yDoG?6^cJRQtA-J7VgWhRbc-}{>w9~={+vd&|+$6~#UR6~S z+k_EOpZB9htop~PfG!=tyWL7u_6gV~2>(KX>GGaV8NOf@OLE@CQb=<#_FD~_eEwcc z19&Q%L!--hmJDxnCDu~BEw0&B>*tfgN&yl@O&3w{Yi zjm^#DUzmjgSbIRcR8c!|qFFB8`~cI-P7^M%r^vNPS@)!kaXhD`5cUuZ@A8q2wCT7H ziy~+QqL}yx*#)S%451htfyP;1+1mW*e)#P4>o*E8{kzwA@>? zvb1|zb+T#I0m6OOiLV(tu!m3mbMg)#S8V*QnCc9-2R9#-sMEpjNv<1S_mlDoB1j`A zZ||Whd+Hj1^y;c%r^yiLEY7%RAF73Nx((H0Z{hIt$rRSr;XX$EiYO#ntiKiBM5%MN zw!R;_6|s}HJ{Sp=5{++ju045Altj$B_w|{58IS3Vc!oPuXW8Xd9KGWX0w{Pc=oFyw zc+&ej%6Wy!V8v=r7iJ4quJ2yqO+G$}mJtn#@h*PcTzDG$N1Q)vq>H<(B?wdc?K3o{ zIeKM3RCn;sh33R+YklcM)UYv!v17S@LFgiKrS*bf>8;D67nL*z>46~jzP4&vyBm;( z`Odv091*gcZ5_~Pm!v!Sr{K;o>b$ ze?B8Fd}d@GQG^*vb}^f7xlrfJhLP4Tq4+wXWiGU^uX{TS)6gYi>;wxp$J!S37>>%~ z&m*NemZS${Vk%n6KtmR2cYpQ8ewlhAy@5u!F>Y-LIw^!6p3o> z?#1K4@>2AuHUtJAQ9xr-nmzjxY1ybJkKG_H6`bVy3}LxDQhdKxe-lh=Ttr#yFkiUK z?%boSwKkeYnaxm@hlGa9V3Rw4nn2(%3zL4pb3KH-=Xy%hi(-RX6@rckVjT%9HaI;= zy$BrIQ| zk_G1=YY=#79aPlqeSRZBb$oW${$r{d;h-gAVXAw%y|7G{lLfSOY!aFiF6=~iURLwYo<*mrYfADI!MNEQ+Hf_J>`;YyK7JYSH)vD zp`4_H@A}F{bk?94e>uu8D}qMUA8vyE94k4g1o&uRl$inb4h@^-L37OXJ{2q5$6~QP z_}y|7h41LlG>NY)q_5(cD%!HDuFSXp&hHcgotQGl&lT7;SY~wR$R5HV2i-6Q7c6}9 z)~e}N3THyI*|97QSFdQ%&H~l<^P2#-&9Id<#-2J=Tf+c#yCZuZWDLlW0xnBg(Cbop&?Mycl_^!W$zzK7`8IL@@FikiXo125IGx4 zowjRwFkW}6s&qiEy?xY=m<+KR zydW*m^LpjGGFzwt!HLAbDs~LMxf_GCoLc4#@0;4Z3BUh80qg@4{BA|vF&NS1r6X#HAyw)|mM+F9 z*U(pu5I9fj+EI;ZPs{CL>yx2FagvTGz`~hnX!7C0sS^bTv0{AZjR3H zIm-4nbWG3QG#S60VVkNh{UeUGOW~Yy8Jvl*W?bD+htU>8KprkaQ41Topdzrc=E&K6 zQ#0Q8lPFvWfu;fsl_EmwdSh%hSXxz$h+vTx8WtRJm#atyzo!@^%yJC1rT>>xk=y$8 zKO5X?NG$ePyZ3<+Ax!lE>?+!2ei{yrWDywI#<$!TXn165 zT+e1O&+$4yDG5Gt+=t~8|6NxK&UBP&>yNM==*$7n;RG}wf580e8HI?_l=QLhy1psq z!IO(ghtfBkvvZjo$bp-c+_sMqfdUCd*M;POW(u#95h`#jB*#K%psJyEOYL!g zyh4~gxh*{MPhvy7fDAvBg5SNUc*~Tu*TWjZIpKDFH9rp2_oGP%T%8(UQyf-Cd!zEo ziBx2w{T0&zgFNh!CB)0)7i9nhOauMc z+p!z7I~(y`%;ot98F@0F+?{IKAjeXgA2tg;v0c77Q$&PzbsQ7(SU(#gVe|r3<@?}w zL^RlC*Ia#!aN~ix$w{z}P`cvhOy1hex43Kc?je9?DKR|YO-RACH)Fk6x%3fy^b>+2 zN)7-VR)RsL5PU0an*MOzHL<+gonQ;IeWDLISD0bTqCCms>)x}Df`A4~m|Yzd4@~Tx zT4uoKdK8OJ0tV|km?fK3a+5Dfk78VCg=c# z((ULDb$tz%P6W@2055xRO|VJ)+rb_2`Wh(+HOBzDe=pJaW%I*-*}J9M>xRj9hV8hj zj9gvS9D@ZkJD{ZhS;5Q=gWWG6BqEX7i0hn`j_4S(_Oym_fNf48UB>)9h zkiZ7fNw_Qxh^JkohL*N)*7N%tY%X&FboK4kBjeivGGZ-|NUcoJI{*dA3cAsI#sa1p zydqe(R#4&P2S$j(0y>oYwyCkRv$GNCDo3La3D(eyJfIqV38etS2}DRo&@5nw4m2gu ztpK29EK~+zp`pd~RjB}(EutHUgtV(^U~LN1=MU6?7?bczoj7J-!Ao$Q!RYu`L5) zV-DFE&Q1LDM}7eYgxNQ*i|0Z=+}aq?t>xttH&c5pJM+hGaB3}3b#Z%Q9-EBfEq%HP z>P>(d7749ydSql|avT_l3q;VaEUgBBYSGRU@U77JgCX#;dvyln29zPt27KSj49N#b z;L8o5Cjvs-hr56NY}*GQGxPBDO--P|Fam38tdaguyf`PIJ!7=~z%5Kju1~<5lv#nZwR{HS`bV+(-(=RN^8H4? zGV$YWRx3_Uw?c&9g@=H<$V@1mU}x@i$Lt%?m`_XhMEM zHV7=nqdzi?K^wHZVje=&Ykk4qgJ{_PfabrAS^Y4);=z0(9`1XKKmWi?&wv|*e!}vH zyS+p5%Lk#K!+fW|uWdaE^yi^^2N3z6|5&S(%^;0E_})Qg=byZCd>=T01a1nJjp<|b zm4OJYvid|J&6xv4DMSFzvL{XUNyJK?WDAhh!QCRh0&6>~ilJTPTqU_tVK<0c18y}lV zfC?V;!PU=;6!FPn({$SU&r4m^>$;4AUe8V0UqW(?w3W|^eUILcu_r!v8HQB#y_vz~ z)b{=@cE?7AxDBwb$fn;L2E<7(SFl7*Vx9N1e1=0Qm{7WD|KK{vFXTQ<6=jc-_>0+BE80$kj<{7(Rq(ag zkAKS&m*TVe0>%sa?N%*wF$;D{?O@fOdhf0yv~MnRA@t}qny~m}L{DhrCz9A|)^Egd z3G@)#N8o0u*`}G>*VtwcuFloUc4MFk>k1kK-SpB&xih>QCEYxG(CIcN`NvQgIZbNM z>mRdnj5_F*P`w-2b!r(Q?b9tkCLKb>y@wG6oLuLUo2hOt`{g?09iEzF$g25ElPx^? zZ8KQZwE86w7)k;p(By+9Y{bsw#L)SI#C8X*Y*H?vid7@zrX_%H)?Y8;IlETAI=R!8 zqGwD^uJYR%!|#p$*Ch#o06r%kT!F*wo8P5Uu_gX|JLdDkTH6$X0t6SuA?`y@rX^fZmU0d_<(!i$u*%8 z&V_R{*p%dc-NvUl!OoT1;#2oN;%2=G+l@~cnhebBdG6^pbPO}OmWy2H7A$jR!cgJYnoCakTv2vf zuNA-l;ie2uQ@=m+amli%jx%;Dvi_U>DAhS2@6(ILi@SyM^3}2z-FKaW+B0ASmQu_h z-z?dHPJCKVowvA9x!2P-4R=NS({&*Ue7!v7qsr6JK|F$2JB%E^oG5>XUFKm@XdlA` z&o-CXq^g@>2~}O))`d8E0QYBUiCO9w44EF5nxnw2;y2ny?>HqhrJra^8}n~}N*w)3 zebI8+u1PRLmaYavoW^F+>89QEDF3zy_8 zbHA&`U#L_vTL#>aoSuWg&FKCCmaJx-l? zcA}>IC9hznPc(zLvm|-GVW{$)lvc?YF(8c!LR|44XvUs;2IdCC`e=CbwCL08v^5^x z##95>>-3=-(Zw!BfMg7HWS^zB~yplHbi3@bno5${0PsZL@ChDhY7 zeJzh%>JnDe3!?(Bq11SD-x!Mu6xS#2AX48tRzLMtFM;{G;JDgv2Dq^>1D+s;Uw|Lo zqL{y2{SliZ1pZqhda!TdU<-v|-z&+Dx}mtl=;!1aF^^^^*4hyzY)S_;vKu3K&g3wk zS0kJG#nh7Lu_9;y&{sl7C42ZFeq!$vfju{f2m1k(9Zxpabgfx>S|7ITT`DI3h2!nK zV`dV{!g$Il3!3B4V0bhAYqR7947=*tCV1D~`ke1hGS!S>YFx#Rd(`oc4%Qwk7#fdf zL=*I$!xv$0t2N1ZDY%Du`fUtjQmoTuMl&aTXlu$;rsP^vrv>~vXt7U5x9%2p2;J5O z4Tl%`Z7PwL_BzwR7O{K6Vm@K`#}bYIc%GM??-u{YR+Kil z&^Blgy2V~?Btt6OAYN*RW=Rj1(p!}F`@W!H0j zPVF*&Wf5ISagV7n6hZBbN$QcBW7(VR8EJM09?f>)0hLtys(lR!+z+JV*9}r;#LzXg zvdk`dKR-O_xf^(Xo(cVKIH3iaR>a?pUXQO|S@I7;?+U$AAt2g2{RNPwZ$}Y>A*M@8 z?lYq5K6joG6qj$g8pc?r;t-tfDpDs@^~O{7&?}=C z<1xlREEX_Q#1(lEgLM9Tkx>;zs$ZNYuI1>ylx>1y`iqSi{tRtcf&1|cr)GJSK;>Co+xUvdGhyWCw*amyI98$FO!2!C*p zY+QZu4eCT4!^cfY)Cb?T_}fGMpM+00vrB}k{F*cDw0%una$?Y z9mOMag*XPX3#fwnT+R-{pU`<&)#t`bzI;g5I^D`dqKS}TYeIhmT4jftC@8|NF+F?K zdM9N3bhP<=8Rn>?qih7~BMl~yTlJ2_%UA*fk_YAJ2LORxk;_Tl!I6-qWLH~#sD*Z! zy;6-(Q3^L;XWk{|!6Sx2J;0G^UVjKyR@^u?Y5 zjZW1Z_!?|sKEq{!E?3CKg_HP%BnG2ML$qyJ(8k1X#SPVjRoOkC&<|!3>E~pt8T^3q zeW%WwX_B8wsP5z$GFs3SYc`u;D$5Qjc-*!oIBVGC_(o{6-?T2DV_VwgrkO*uipmaD zOK%8qxupW3cRrJ$@QA#d8EJg*2cxp^MA+K){i(9V@O0@NBGyL=YhbbHk>TTFf=N+* zDF#pEUu$H)8Bp6 z-WlwzrI=gb4wJ7jAM{VG{$RieTqKgmQxg#lhNP|VGC8~!JmIhIr8WfX32Sd+jSB~u4%WQplS+DKCj336$`a2}PA^g)G)!T#=!XFL~ zQHNXSNgkNtX3G%(yT)C>3m%i3p6|jaJSmAa<-4Ts+`t+>hBM*R;)5T75g}3$t^A6^ zD;Ae$;&TG2uA#DCw9?Cck;rf-%Mpv=(fd8UF<%jTgoEEirKqJI&99{1M{c$^i5Cc? z%Fm8JD{mGM_Fs;e-Y=j**rnYhJb7c*rSHUvf6>0M$;FIsI_D$hd9D3(|5i}WEwMa*8nj_S6 z-RXMY$oUV&>2nOc7M<3}Wq(~qY^%89RF2iQ-6EODGOcoRvt*wf!f(}`B5t~A$(zF*By>&US zg_`L&w1o&l%8*y_D%GUeCRGG+6nv(#nivq0{kxCkNmHZxHgwb3J?b7OR3E4xGH6UK zJL0LF2dfxW{(AI;0ymo!Ok!QVDpS$t7g9}@r&dfFm#R8UZ|OU$8%eQ}iM=R8DYljf zU7U92I;)KhZSdHqf`U+Cz$ZiS)x2TkyU>!(K-G4?qXyxHc#+VzfJR}Vbbqc_h7C5! zy0|o>I7IkNKwjBp$!%gV*z$E|7YtHq4yz9qbrquWno;-UyGaD$wUCMgIAVgS(xAT* zzUAIlBJ2Lfrc41FMf$D0g^1Bs^Okb74Uoa#jcd)(A2#sIM{<0SOgekVogb1amT;8xE#f(UsQ19+WB3spP4ms?(3{aZvbA?@DZEM}MIy$=nZOXzU z!NfqJ;Jo>qbfCmf=y5$lLVpCcdmqf;Hme&_l3!LC9Ya#JtpTfRW;1X{xi_9?kBb>B zK&3Xks{%c1HD&^^@?vi{Sr)`3D%`7ox{-{YHez_%ZeNF=8~Zs!kiW=O>vvdFU&Z1db*Ma7|E-s; zw^?rUhkR|%v6E(}x)lAx7TZWTfLk*?pM0?d!J9)0zxL#71Cu(Ow?mc*Oj6sj+I^b1 z8?|DPeLuqeLUlT%QuLR|aafkXqcFk!DrLL4x*4(Y>Y}>-iSkjISAfB3d3_7JM8Hl@ zp?5VdEmxMH<5te^P*S7qA(5=coZjo$Wt2LWcld6?)=|%V$*$oFWVrkNj>mDguH)qE z2z@~;Ng%R4PSW_?GIA|jQq2LP2P%;UsNeg+Zy@VAwKDFxBY^Rb4wCG1Pd2xM?vf;| zg?#dsC=IY&@S-UNo&L>bI~O=8Bqy)PVb9<8=T2V>;yOwcY50<pF#m{l+`F%d6n;Xd%?V|Xc>n~==A21vOx!qhv zP`o>l^Ia$tgu=+K?EJf0j@%NJhRy?)CY(;AnI4Jncv~Z|1P+_7cSso#o{;}4C&(C- z=Tnv4TV2M(C7~?G6xlgEKXB?hnuO{y>oC#YGuFtzAf;WY22&nc%S>6|q(A_Yi< z?QsD2PFE66@2In7ATV5YuVW{Ot@VSnG!+iJ(hHK^VV)<9m?oiRM6QXB?0o%7Nzbsq z2ICE=+NVPoMOlS%8Ci&a15eMHI~0${-=TAPjfNHE%0x>ycY)*PJ1FvjQ+){Sy}bM@ z+B$WJtGH6s7&>yrmQ}oQrNdq_6nus0G^$(KveUP!=%K5rkJ`i`nCB<%bo9%J^ldb@ z-3**B= zi1&DibfRFqEHq2WT)p?9V6}8&y6sP43mEr{M!bkEgR|Y&sE-*&Z>L#Ue>NkQ+D^9W zoUtUYx|Ib+r$6&9BN4}tV&C-I<-et#;n?55?CisS$U*WT{Cv7$<{NN+k%pHzFqB!# z;5w?@z+fMQa8T;5%NE^LZc2{{G@PgzL4Xp&@UWdlmrXc zq$7iX;>!H!N=>bsikNq8n&Co@K~05J0>mfV2ZQa@^}LuRv}^XS@(7y*JM((|W>Lr4 zf*^r{T+_t7zJU^>tMRk}UcVW%^1(k;2cZUwgCUYQ|1N&v1us6jLOhh3Pk`F-P#tBN z>Z!|=GEjkxUHbZOg@sg{GH5s3Tv}e*hXXYr)XoDWxwC>W=HgPJ&WapDa2~U~{1+Oz z9Ijg2fQ)a5*E1IunjjOUVs;)i9($8m8Rd%}1 zG+w~JtwVFe04~TzCm&FO@(|IQ0GQ(l*w6xoZH3$nsCFgP8lomnPdFxod6#VYO*Jnd6&l8@ z9Z$cOweBF+llBu1y;}@BoJ*b{>%AFfkOM+U!+UX8KG6~d$W{hdveZc+gIafNnHvJj zf&y@+nURV5-P}11@q>J^kS@cf&)X}R9VjYqg;N-}kH`yjHS^FW{mh<@r}_dQCv?SwOPU2H(^ zM(J*eY+h(@6-t_>ORc*Th=x&xja!hxSsSGm=#xG|Gj$lu@KQ~q$-S0J0`+ud(NZdr zbklQH9f8a8Ms1!3+gS^7lZ;V(Plm(IOb>_+A@G$Q7I0E55%W24ElvjwzVT%pe8;N* zdlUCy%Ml0+r-%ugy5$3L>T&9@g%T4nBOI3H5D@QBu7vwoX)m(oT z1Xbcrw_fAbr{ZB<@$t24|Vt;RI#a0mt4_a>uV6Ow9gtJO{%N=ZRGGe_5|`S~iPPPm=Ca0_rcyvh#wH7}C%3MXXOHL(1A zIbka1tz<3w9@3jn%o%dt;W7Pa5GS*65GfDR6QqUJN1PrF)B76h`oIz}7~ZG4$X{05 zKbH=_Q9CcoPf=ZjK3Gc(yGiUn(Dtm02hOcm8T=+td7%DR{yNnYwCGqi9TQQ0>80sPjX1*YDFS7y@K|cV3TuO? zASnojbgUW^43W=;sOKnF=Z^DwfRze1lLwrDI!&>xT-w1^XH=;WC%b)VTx1#Gpwep* zOETHbutHk%;uqYlYu27*=O_B-nQHsJQz?A5boxpJ0zO>I?{!5zCn;~bM$|J%?76a~ z=6F`g_>#*+>(Dp>5AS7VOF z#rW-+Yx5i1{+IBw2Tl`D)BW*pWV-_ABKLT-`j26GT&phO^%qBAX_R9MQP2A+i(=y$ z<%Btt^$O%n89IyTk+t%W_BSzu_8Bg-!8g!+j^$AfzU0;p)`hI_dw5xdj;PAFOZjy- zJr^?Ar+-VQ`&UU(4)qmm>cD;iPFgPz)SjEO2N2nCbF(4(II}UB0AS zu+la8gSK*D^s1OEGxT}Pb(7O40Uaxp9kMaWh?d8EsM4qG3^wZEZHN6}`4LEHxQ$cIYefrR&%%tUAH7@CXC6oWW)#5k$ zRYA~VPgrV{GZGr&!i&Ib^fuh1erVh82H7(^h}d5G^%lvcX+(fMKq4aYtmnB%jr{Yx zuuGVp#|gsyj#@bBobO(NUK$%MBW_M&inCGb;{II6MiUS_LSgtC*2w9x;nB4iSfeT0 z2$Vc1SsoE`ZW=(@9va3bfqYlzEkcJ)p2P7}vDG#o z_h&v8;}MD11ue%YOVcJIX>H^$&|(U*02K})2w8uJ!cM^brLU8LLh)YVk7{fEc3i3X zc8r+m!{EQ6xx9kGWq>Oo!+HTLk{-lts1~8PhmXO}S85v-IfnN*Ch9yeN$rO>WGx&@ z3l=#v7K&#x<3O&#Aaz#q_e&N>i6_^M>LflpE#Z+&$oxNcrU&w7DpCZSkJ0T;2?Q0< zU;I*E$aRni$ly_+gz(R~4>U#JSn7ww-1sB(fy)54VhuJ_1RMlGE`llaWv{Gj)#Zq_8oAjxksAa#O=e97*G7roORAoR%^b zG+AE>Wk9S$$l(^vj>^M(+%jWyt%OT`cp>$V@!I>}X4jufp9*$rNBbBFa>H zIx9WCXo)t#V0?75tt49*^^h$6hwzs8fp=ps!x#{g_?)#TL6o=&+`$xw{*XYZx}37p ziA@;Ky)@hq9(!T&&gpAl#+XFdF1R*W2(!bMfF8z;Y+A%>XG_gWI!#11SFr>3vX8}P7%^pSP6ah81oPtwP(H*W~Exb=rK#E>i|y8%|( zY)j?)5gUiK!^yx4Or&B0zATqh%AD4E|Io*dNHs#*2J?@pgQ6!KX13>%87hgeCkEi;cxwG+lZq{h?LBUDO_+w3%U;#28AlSaCTZ)Q*V|e~L&Hs%Ie1PE z!>R+bfbzzZ!)BGqYH~5u8-jxH2D_;9wvDSRwCJJ*LxoTzjG`|1;n?"yEZ77#(Iz9w8g&wqh4Kz4$Z>3luJ|#NMDojs(gOpdb>Y&^JZ97gV9#h5b5T^tZJmzRT0!rav?H zN@VHUSBTs+ER#m`LHg0WL?%Lur@#T@4tdI11Y$AumMY`WZx5*44!&hS*I%BjcWpV< zI4!97$g1V}uk0o%unTd9S=~(%?jf)B9>`iGZactDEir|T>xLSY-io!%+#zvYhfnLu z#yi$lqDm7Ct9?p+TCFkB`#5j(A0OdnnLMs$u9`(1nR`PJl@qNGL10* zV#UYf5LFl1>eqVd>tCMvV`xeXaz-tXAP`@a(D_{FXf6$4{UJ{v1s>Eiefw5 zV1*jXOCs|_>k;H&HO1ZW0JMJ$SlsMKPoTPaYyK%VksvLr;sU2FB-m(E6@`@AJ)Umj ze#AA09hlbYfbrbT?p{aE{rb5;&sV+ePoqEh*yS!uugV|&Qw?&ev5t#aU=bG_THw}i zdcuhzY-DtGDk{t6?IdmHK$JLEA}1HZIF{W>s;FS*cL_J$%+nG zNiCLZc@BP-luWbQxF@yQF1@k+2I2=j9f=AXgK}bdYLExk9lAi=)%J#IOEx{F;jvleCFY?(1Bd%?0mFUzwmV)%lv-f8BC`oXH&{ zoAuY4b?GrRKI2!nV|@oLQ(iV91#L2a*zN9@pAq=*oyDnq{MY=43F$l#hZuLZ>+W4o zX-3Nl*j$@ts~@}bQ{BoWlL)f|;CEPG9RYs%0n?S2?uuA9t?Tqgy`xAb96|3iobj9>nc3oyzi%&YjEwp-#F4|YEzS?7iC;G(58zcpy7$Rtpsd$qZX4Vw zpMX-3Vw03I{=j7Ke_JR?s`8n_g?zKYy53X1AS($-!Zim3>h*r;I^fsj2;aAtmpKK9S9evDsO~WDjm@Bi7iZHZglu)_IWN|2hKQxfBO#YSO zQr-ID()-E0ShOYhFC`osnVdyF%y0qkPBMv&7 zIZ@D&yO=gbJ_8KE&x2yfZc#9AsB>jNi78;=w_$?h0o&q+4&g9!v+hoC1>I8y&pYa1 zA291@vxsDE?~25aE)L{gsro0$Mnejp%&4t^MMN&H@*GHBA7m~U(Go-JEPGA*Cli69 zK~^OXX8>vzF+`z$^8NPC#x;vM@iFGqN+eOTy7rSFn?pC*m}Pw3x7NEDRT<%Mn`+@N zk;WVlnP|p$2?<%dl*-7D>Bszu->Jqzb)A|6E%%mTl_`~6-W`T)$6hzF9>#435mtkW z4L+LZCp&9h#16e3|&k`O^xkMOkw!>VVqr@Obu;e zJl12Cp;b^VQPk$qLG=n~i-W%pkia3GP!1z_2axSTzz_w^ERql`lU>3~Kt&ON6BUs} z6%!6R{!oDI2f~n&1hGU!ZBkdjkwip67I6|#+Cbjs_}af5^~~t&`>Ogc>+2`_-|l5Q zhiE`e4J&Ns$Q7;uG4uvw=0aGol81^LCybd0fTa%*I-+=@*C>!+Sv`OcDguje2673t zheZ_j>HY$DAurHgpG#kxvj`9>*7PScg2CMd3ndla6$8G;f}xQ#k&yYLMpS6D3E{&H zf*MFwpsmfof(s9chg~BGh6K}1qysk@feW61cFP0|a&TU!lu0Am8TDjj&?f?&j#CJs4 z5U<`srn3bdw9gPI4lSZG3-)u#$zw_KZ=Wb4lcJLhf~Y920~|?Eq<~Ti3QRcgABBD< zMSbqx*55ANNF*S5A$^5VQtvsr0fzG#vQzqjqCtWMN^uz26p{KE)&fLAlCax53U4+P}p?`(Ha~oA%UjGM<_Rs z4Tram@EI`-5mc|-=^Wyem=NUop}lD%MbHt5Uq5Ld7GwU(9psZgXzy+4j;cy$6+0#| zw;TdwA|>ZcVNFsnG`+uS!bUMxU@=Ij*V^ZZGVUo0tA=F0HC z9CMocg}i-vg$+MuVU7o{S9|9GVEuQqcgOrbk~#!RW1S0IIF7D#dq!hE6P3nsK(h`{ zW==2BaD$(fPs$>MJEx0qpV9!{HIFJxUVPLvph1}xj7tT87-^5cDb%RzlJ}*Q$}lxGnJvjk^qlS}qj1!mw3P?DkqOM_CwZ2b_V{hH zAIH@GPIc$%J{yvSR6anRednezW8JLX%b?YyCqaK~LFlIPl?`W#T@s@QJ<~RssOG5t z^*wD($^G82+wzk;-JRhU@fBnkJSsx(y?egjl6T;X6DW_FMzl$!*v8U^HG9n@W&0X$ z`L)WI7VH+OyG{_xpnaL`ocj<8RZ@1`<3hsaW|5BL_cO}%m;m=w*!Qa>Pj=G4!ZVl9 zUSsaXG1Jz@-(T)*dVZwL>m8HtZ*JFvaXeCrCk~&ybkZiiN#+6CS|wJI*4~>` zPig1r=n|bXdRG5@tC1j7>2_CjM6&%d9xwHw&h7J0Yu9>=IA8a@>Ge;(g%zS2ZWGh) z^ru~+$#;s60jslyk9BdB_OR}$fjFVlp_Lu0ldEZdmOdP6FO@RiEEL@OTh)ax_4)9x zKb#}WE_fcj0n57QNTJU?(e;IJwGCU-4|RVlaiXmEvA_+&sm-vOw8$-*)-ow}+U=%c zcW^UR^G4uMjUhGB_owy>;*!1P{o(qfK94?kr)aoF!4O?4B}02i?H>bj)Jyey&S1Jc7Z)G4M%85j$yH)}371A0 z?@_)R0Q+MX!_JF8>BBEx00HkjNURaRVd>UsO*857IVqp1E|*h7^~4zV%KB=0Vc#!3 zP$5FD#pBi7|I9F z{AA1Pc_4>3`M=r-`bkU}&S_;$_n-yzc)m|hy}FIXZBaT(4~8Mbu2?7lpV{FMW@Y2i zFm%s)NE99C_>$0@tu*Pr6m-PRWKntQ*{dGX^Nu4dBPY7_BAhm=Spx17+aFWfU!7ye z)$Z)_t`YivN5h}#j&ATm*Es=H8$ALRJ^YyfMJJWcR`U~<^73y1^?M#dSI^e@?1{6) zbHQ9hRi5=;hKTE&V~!;klKP^H-lh)6U9sz#FIYqwkBf`h-njyV@pM{0O%L_%{lMz% zJI8Ir%xElAF}g54fV+*))D)M4hKe1gvheYl&ctS7Z}lb7S-T7FLO1pE&cwK?CbYno zb;i|nt&J~i*V#z6&9%;jXm(N#F390I#jRVskx-^y3Z<@B~Z`Nrd zniZF{<-r0uHO=6-YNmJbN27w(Mi9wE%&R1s6>26K)h7yWn=Wzzp*QOTuLXAby@viV zZOeV`=kTL-%te+jKPGJy-{*v(yU1G|bvI+Go$>p^;g*h1#BZqwk)zrp@MTy_4Q3xDeIsx|w&{KmwuCadJ=E{w2aH+K9E zzCzQ*YY^MN9l;2AnRTGfGo85Z#*I0TuEbqbb@DE4n>t!37Oez>Vd5b;NGxUHKKGNN%8N9eY4!ys>&EK4RvMleml=;}3r!My%bEk7|X^WaY3ZigU zXICBD`%fwB`LykK-!Jk?AV-?#et@QWMjQT<&}04&LXU%)>Hq0Gb}mM)|GNIW&f{R^ z`ako`{{x+8>+Y(uWWB@|s|2!e1hlZVwZP^w3dhpd#|Sz|6q|yAg2L<~6;(o{8x-Oa z%nI{cN)qbc^Tzka_ixuqo8M1P(=7kRnz?{EpY<1~23rDDb0vU6MO08!K?B2}$gqZi zgq9Q-2?LFEe^)_7NXP;UPlgLogPf|&11kr7j!HDDw1 z#2(220aD0-fDx?^4_bmhl&b^eFrVMI>T_vB0_muj^0j;%3wPlP<8-W@DsgT@I!Lz zKku)avLld4lo$a81mY|V+NXet74-X*VW$~+=6ArM0OQc;!_ESs(6;|0aQlzP7-)cC z?oYk%t^;TSBwAl>*yHV^kcc9XFBw>rFi=b)0nreEHUSdu`se593sD3Y{{0{rX5c8^ zdEiHo(H=g75Dg@x@JHhcF6gJ>)P57>eYWRRgqV>q-v7PO|MS(k7>Nwz`bR+G8~fk} zH1shxHqflo=ZCIu$J8|h6$M139Y|)*zZoY>%o63C674cZFpr4O#SYM4eGZD_%zT%bcD4J^imIc|`^_Jkj ze(%0Ts&VP)4M0sLY!G)E61v&d(jYi~W1Bcv3F?wGbM4gJ4PQA(IRQy|ZT$Agg`(bC zvX}y8N6Fiqv!F0H_nRnBF`<<0l|H&X9`wtDtw~7iW!@EJefuLlvw^QgO$&M&^k`)E zA?apSc85G8l*!$K+LepUK_Yqi2Qas2imv_$RIIks|i|Hbo5!&ZE3t0D_Zmz*}R)tdHs;{aYtd* z?$yIzOp|LeDH<0Xk`nkN+&?Srk?%vH#;)(7?@m#Dbu!jt*(SVAp5QO#P635dnR7M> zC3}E#zqv&X>uoei3PzH-)9sKKdW^_H^?FmJLUkmYg*DJ&QTt+@?Em~ zmQS-`la?ATzXbYt;&0ow?%>8+j3Z1GYQnC4sS|%T4Tax`4hcC+SC;|_zkgi`Z}{p@ z?GV%?g1+|_i`N>#0&Kbg?+7i5L>_i++XTbG@r}J~96TI9jTtM(garca(+1);B!tB> zOUuZg=$Q-nbG24Jb`X<#FvVQ{wAY4eP05{WX@fb~T{7E-l0=>Ae^H&L}rE0cy#!9=gFD z)3xA_RZl^@PI;s@SBrr24kSvZh%(!F&MfRpmnX}!zlT#po#HLacl`huV`(;A93}oq z-2ln}2M^a8Tu!|u9kHf|BD3vFb_u$=idwoN!~75-%;_xH$5&YJ#{ zJO+2bzZwIG@r`IJ%$nZpOQ&WhM0FH3|Fr-}ncu^k=zBYo5VZR4Jzr%hN*>vf4gnF# z9f7Af$M25>zJ@eis)S~LzAW!xK`AE+kE1wXynn`XPsWc2I zNka7J`Z$oB+R7bB28wuNbcMy#vs4?Wy4*BB`sQ;)UlMYlLo~3W9!)9P5Sq1DW}DBg z-3Z(Lv&}Dl$sI_XU5j-7WYuHccc=1KUgZwTeR;~UfJ44lIfMgJ`mqo*T2y!0FfpV! z25x}wck!eJ8cEasoky@Tb~NcP`=lp7nyh+KJQ^kLx%L;s;A{8`mFUlV-URwg8wi$G zeIGS%)O>$$*1XiSG zLtfeIzlPfAVUSR?wU@p%FAZn5NzI4(BYIGtx7zCy^oR<76jhEDY_ri~Pxa9nLdxvN z<>G=roJON9NJ@zaSxf!(El0)?MMeFT7GPw)ueNCiBu}JFCaM2+h7sA&?)&J2=<@ie zd@QP0bxptz=C-Q+dUNjDbSmL$#?u~pPvA~?GjxI4Nor9XPcf7?07lb++2!$CqNFXz zy`i#uultjr;=h-?E;CIvckf6$eK`K7V zCz}*q@uZzd=$Xrrz~esoO|VtdDy6357RB(p)Y@q0M4SvwFW{z_i-j0{b&mb^m*f6= zv1G4Enb~OY(xn<3scee73>)cX>isEiXSc~@j@QXycgFR;U_p5?Cv{Y!SL{gkZxL6O zwvlVS&5gzmLW2PMlwU<|4%>O1_>mI4wWIp1%u6a!pRWK_E5vK7=`h=EKk3+IsKH&ieHGoi zh@8uPrh4{{KT1kD&{d9f{1(Xm!#4NM)#3nS=RH68B|mwg@h0Aetj0>j$^)+|>eOpr zdzr=80B4Df`IA)XP($#bFm1Glr+q<-ZUi76RVMokE>(|ze|ghCMt(pD3jw>6uzZ@Hp#I$Rs>t(q%7j{#~(8(<7X3L}IBz=A#dJUOV$*w-NN+ zvV~a;qhL%0Un6IM#9N7RwsX0BbwxeEydlZVG>zHjx67rOTTTFlKPBV;CVVVjSdG)l z77(s{Uc$&>dj^nl=SGHRdntSjf$LUrLlORl2W^{fmn5~vB`~0OYKbK;#b_SaS@RRS zci9Ob+`no~6mr=RnKm&r;pQ;^LEm2!>@2-9??d1@5vcI`yk#caulzYnZYg`6E9(d; z-jokz^%H5Ow**LaL9V7a4NLNViVMIwqvXpe*6v>0%32tAE@G0Sc800Dcjv9g^eEY!yVgvMSIxdIp)r~R#uN_l3`I|Y)a%I)>qM%u&McQ?MB z-q$+rP^tQ*%AFDvX~YqVEKG=g8tOAuwJZ3`?l=!9RUq%Lj&%f9fKYI?_aT_63FB3H zmkZpAWuk)Oe9k;rr_Ky)brm=&paFHEJdi_{IhbwnS1zhG<&sSOExA%?5bv#knozq zV=Sew{c5+eI9mH{0R`sIyEWK`hySawuYjo|=>EmsDQ*`iZujEuRxa-DTHM{;DaGAg zio3fzg;Lzzq4?u_mY4ir@?Nr;otZsnWHZ_9vEQNk(=_Y;RG!l$tFOS#UE4B+>hW-^ zNHp1UyN$$gp`@FX zhogo9rFm{>^rE2(a8q-4j-=b1rWK7H>faTYBK@`Gt*;_#$(!;$f^M$`;tD$8ZozrT zP(%|8Olrqj3|`N^=35zgY217*G~vz#vL89Mnrew~t-!J$x66slAijxiISmN zZ^ipH^Abb8OGI>ca~G1FEeER;h!5UA$ksIbHWe9~xI^T!DnapZAE7$!%dCZ#xW}tvlxHkWp|8#yTt@5mR$i*D8~4d zty&;{GsbTbt7y98wyNObTb(4qLX`OV14pw;)up26_7x>rmUZw( z@YthBph@h?HuF*4GXu?TFX@)Gxx9$uU}~IKgbV(d6vwA#nTmr$xXVLe`fPCU&=h_o zc24>r>NE3;;Y^)d-z16X;_{tH&En;R?~RGGy(*lm6TBdJYR>iqQwwD%VYW)U#UQ@qJgkm0~)tH;fdPoKPA}fqS&>P`3zFF%o_YWL; zLNl=#7p53X4a;DR+NM+`3w}jr!3-*MFa~{o8xO1r_1{7RK}JRjAjr`D+I4o0&8I92 zZU2#>QGc8(mBXCa%1rD7C0^N}+IbVMh)Q(lW&eS9n@82~F3uaI8UDQ>=dg++GdvP; z(M@IL&>-qpcD0V3QH{QXx{g1bly9G-!(j9o^{0^7N0JIG`@!x3bY&oSX zp^c>#to;i5WW>bi35^tP`rs+l-(ND;sx5I4-)pXQ^ozT*bs(AWu+y{Ghuu#?D`|MR z?e!+fo388szUoN_{VXz-+?70-<4U^mGiw(C--yZvPJeN^x8o;@d|*O;puF5}!D{cY zPy*B06#6EP$tJQwc0$2@&48T-*}8gFfuZ512<AT%Fz=DKV|lnVU=tTPPm2c~)mk(+MgpfTRMSB8xj}l)F6z zC-H)}KEatNkwyM^8SGcH9~l``nu>G$kqLBk7IQ)K{D4%o%ap6 zWdqWGt}Gza8iiJ%!oKjT0IiqEm=$6k1!AGQhZ4D9slVmGVXpfkb}=M0K!MVB{JoFw z^z3~X&OJk=-78z%!MwQqr4ee^sH(<3$GSQ3F-;Uc2P5F?K(gg+p4hE-_yxE00k_mk zc;A~N8#6`srXkV?vSYMC4U>6un~q;j9>9FD z(GX#w2$U*XX~@0AMz3w9wA!yyCZN2HFDw>AIvEX|p;@%5e#7I7N&RE}cS3uDjo~*T zDS8`NS+|i$=#j?MAzsFliu$=4xEQi4Q!gP!=^yPECvejA9L7w2C=UJ0fjJy50BRh%TESVu}kVpn@$D_8~5b>R#W^Tf^{SaNAM61~j%k zWK3|yPbq$Ix)$-eCW2OPf|~eOlebRR{3A)^J!@vS)<>1p0T1T~avOI&JSZiO(NCwA z$f?M1qHbCd`$Lg z%({M*+i0m*^TA_0sFC3j>O#R~GS}|y(5eLH z{CWQx+i3LSvQW7doRcWmB(={Kc0kn2AHK=&P&Z~GQ;NN-&3zofuGfC3Q(>Pux$ald zc)5d9WQLOnKz#mM1o4FOB0SL8;ySjg2^Gn6qY$UtQ)8Csm_)vS`&B5(5A7tnsz@qI z$jhYm$9?p~gk9I=JycGHw@SJ$uUgiI@Qy+uy|7J&IRdCfX;Q=6nvc50fxs}>hOPxx zW9nW}PO7G2MD%j;8{@WKqrO*jFx+;;YnVShXUq3ubu2+S`S>8s6IOI2hCcrtm)#BE zukVY8KW7uv)Q)R}IsQ;#(m4$qQmsF7b|B0$cV@o1>;xWbt+Mh6NU-b&t++SXykHm= zODrQV6n)X6uFQd@JtQj8cKt4>RrCCgI}d~QNO7}kV{kJUj|wvORh{`s7k)Vnc22v1 z%4b}gO?wDQ#YQ5UvKt&%OTOQ*pA@%~iBh%kiwu?~K;a7VO5FTlRULparkW5O+URRZKZI?UB+>~;FA;ID$S0@#erF>GP|0@|+!4!s3 z2LC|jL)-slI*NED5@QfkjOlQt^yCO?6_Hf>2@=aTKq$-+MrzEe1h-$jt$w?EG?>1L>}@KY{N!ZpR<#0?)###T zM<05S*1*{B!S(Lqbn_0=n|+Dx3Jy&4P@9o~q8J#W+a+t#-;(#*-k^v9+t;wDah$hy z@t~oj;IZr@jqljbn`~-5o2Kjm9p)TmPU~=P1~M{*mwgphh_x+)@htpY7iRGn<#-M5 zF1Jr#eYVg%62p)LFYLUt?uG*M4zT0igR&@BivgpogF`}RhossDR-Tal1;u0?OJ8&y zSM_lr$6;v|X*g$#y<6KD8ZZxx%5KtN_PN{EoVBVueXzR8Ix9wbfwJpxi5{&t<-$m1 zV-BU`zBc;h>~yiF%a*x<-7z<~hUe##oFe=fY)4yqIHNcA>M{J}BQk#e-fnvLH>f1g zJEl&fkO-3Xb6(O*e+^fl-AvfVQl_m1R*;)l%wzaEo_==yd1ix&{YpC8&eOUH!&=5( z(Z~w1?iij{6*knHs4%NvO1Wd+4k5~L$8#W&-I^fG8ISqHSPxSKtPvQ!jd zZKfgpXGq>BM5?pb?rHV}QviYNW@Nvu$?u=G)qV87Q%(c?ScTwg_Y`e<14wUt5 z)c?;}bCs+9Atfqz&bi`5GdE555)SXim3t73xB@*}NL;;NOZl&EPBohH)bcJ1=OH@5 zX-oME=IpJT!tqg(rU7quA3tJw6JYUmv*aLIv$|!<$J}H0Qk*5VyeQJY5IO(Vj#KRD z(G2MANg^BOjuVsM^!lN#NsCj4W3?KP7-MiaJNpb}JVGyxp={Dq5mDq4f;F9M0KF>9 zoLqIAh|>eRSF~f1$lcxQZ0B9iSR3 z?Ld5P2vI_HL$#;c;V`O5;#e)G87en)0e|BPp1 z#9w-It}jfKwU)ryqu85U`AP!6cU#JAOb?ffe?31!YY_!k6}{5;Q(b9%bF|fviU@w8)4xIpnlznc41C)NDI9&&bO{|CGt? zeDzZ?(pchxd!o4GI*;QD%Za|~9m-4edtSDHB5{G)(uqo~MlI_2{dr9NZOk)%MQ)zN z*}-ZwR#F1ANv#3NBbIn)6n9l$lbS6OP}?_C$R1mE_3-gn0|C?-4sdx3W7ZzQCA*FL2^X?k4smTR_A~rGX|Z zu*v-KLhX9>-`k-Hz1R?28rQjs_s?MOd+~VelIhvqW+K1Abt*2whL;rRm8_D^Gxa*%r52%fGt%yG z``YWcoM)Nj=_%6CHa+XUPsrfgTmKW{PBjkHFHwM)`|1iqt~+Yu1Ao0WryJ1+tqFyM zKg*XtY%>f(qrs)5ZUz_VTE2aueq5>91m;62H0}LAE-NP{C$)0WMo>sqIC+TO=2`tL zU0>=c0`+I?lvQkT^te`&e7Zt5noyeQ@$r_DA8&+i3E=+Jd0PCVj<+@TaW$as-%b@o zStv9|xIid~7LO!}cHwMpa5~q}#q~aS3CH94wnNtUH^F7H{d&dKfKbi8yL?Y8L)9)b6K4Xw2#TNBbDBx@e2 z45KJL*iI0@_E^}t_ajU@f+<`(NM%+^QU>AS1Nt6IW&OVzaCtx+|Azrr(aGM_)#TIT zj@H4{T-8jI3B=3}WM*ZhLt+teb+NQ}qNQU|wQ{jB`@E~T8hQerp~mVWBhkQD|xf+ zvU9PrF#*|WfIym0IyrmO{}+j>laa%xPyVNCpplKU84`=4s)Q!9q^pgMv5}qKe>R|M z`KcHAy#B{V7y;^LPR^fG1K5~B>>v&vR!$B!CRS$7|Fy$UhR?OjTDh44K34^z16Vs4 zxmY@z83Ek>CnF~_8#5c-f7}nv>`d*Azaw#Ta{V8#PW5xg02T$~?F37XUZte%&-nLOr7K+a*_LI%@Q40p!#HQ|4k>H^Dv_ zd3!d?n046({vA@tlvXalzb}U16Rq~1TJLrpUd?Lk3A{o_Hx3~7AK462k{ zaoQZsd~9>Mep*>mIQyi)bXFr>^x$yXOK1QE<0wwV;VFkeb`Tt0;&~JIf@uK zY+4j8_z76Ud}6l}&L6V$X_HuEkQDF(MGk~+2a&4W;gk-D(y%B5&{&X_Rbn{wN=Xc9 zM_5B&qmi(=T1;Q0G1_~{lex#qjkDy5;VT(ovVRh@LmSD1v(B(AP~~A>XklfD zB}N=C@CLGh<~y{*(L3Bxr10DhrL%p)iO?fr+z3e`5Uk9?s1hHD5xnpT1#i`Yg+Ho_`^^E-jPt4ib zxu1vo^Xmkv!m;pV!YANc(*+@p=ykx3quca&d7LiRnoPSQ~_;wo6fzW()s zl(aexLp8``4Fw*3!X-t)9oM~qF(2DW$@~_5>nCDc&2Q;G!|0dB*3t1jn#9Dj2{B&E z2?SlW)XgWIF#_T+~ug?tl4xaViZ?xq34TC#^7`o+u^X-jB)+NVr|k>=OaG~7p-S1IB5VssP0PI7{YGskzA_l$a* z1A2iUc7ijbhZNc78|&{iPFx5Fc|^MuA2iu!(N>Z-66rXnHrfXhu<3`<;T-8gljA-d zFY@X`PO!n~xxclJ$x>kDgVX5i*R&q0Nj)_KeofR_iygfl9o@B4D1KnAS6>Wb2sZl+Br0{|pwkIbS}8I1sApA2`Q*6vifCE(cJT@Meq0Q$J)0mF zGyss$P9~dg_hH}JQo@fs@JP_-=r~E`YNF8wOjA;SygrOt*P|a_ayd!+(TwbcWF=T0w>Y2rGoOUAd(eB9>8;um zNt6ma2K)L9go_i}*z?h0bg(nT-lBASSht4`1T}SjXlU32rV35ZTqglI(Cx=Z#pLe>Wt{9(Ai z@V^Uv?^L(4AoU*lkUap)G8G}Rgtchg!UH5{$GH9YOOwBEjB?Mnx1piF=~cVp9I3_V zZm)9Q6VJRH0fV>q>-VLn%RE1!IQ{#j1!2C<*QW6{-%m$XZwq+u7yY)_BTnD-GM1WG z*wOe6gHGRgz40+4l(quj^G+~7YQ*7;Mo-7%!O=jIMlJlGbOP~g=X^JFsH>f)KSCE| z?|zy~l6U-L<|DdMkDF;|2+q&%TZZU28{f!@7Czu(1+7YUkxG z!K#G=?A8O&Qn|IhD;f{?=!8T^TcWT37I$iAEEZm#;!mJ6eM6?S zW9U;}5xuZ>reiH@kxTuvSFpZ8p<&*B;pI%V`pdZtZ+HEBh7Q53H_zkRVlIVIW=Vo% z%a3hNOluc#@c~hDejjHS`qUC9Q}wuHOS!sageuby89OHgbP}xPi)C&yZVolqEt|@m z`V?;oF4~{uPxPYQHe;z?3xeb?^!?p7tErh#S|M9zA%3g#EbVt(43)MN(&FHrgt_G8 z>CtakOsU4$sZ|XMnr}qj^dn33gd^8AtQ%O<9U%=EfcQZ?d%6RkfpK83XNb`T>*U!# zPR5vrG>)p`%&{ZRrE!Gy&zfxkUyLrMTY9x^&N-p+K=av&mn>6e5Z~+|Mcw+%^iHNK z4UcYkZfRcB>zx!F~cuOk@kqFCk|k}bA`6|9`sdU0oesvl6FvN(Ne4fh$mLO}+c-VVmgXt=|mXT%skIeTOnkm9(3w;90Ewt>1BmoXp zu<^9@v|M6sVow;{rL<(cf!-Quh$4a&ygXq8HutzTLFA4dt5spTxqsmX7TAtR$espD&R8r@H#&*S4Lhwn*#H!TodP5{7)lnVpOChwzWAI^gzVjGk z7;-HRjzIJ%T?>F1ILGq2LLz%nc36x*u{l&|eeIH!sy$@H|7v(By7-K?2)puX6}zWD zS{LSH8M0g7!VtS?v-v_45MIsA^k@72Jyi_CWU-~~OW+`Z25H(#70lfSPp*BpwTQ(x z2lA@6<`1PE;loL-A0^;c&Gv^tZH;kGnNS(gf*d<0mv^gL^?G3!^0hQEHKoy(p)d(U z)p|pqWJB5a#(xXraD20Aa^8V6YPSab_Sb&MJs~NYd!pq)(7P+fEpDb6D$!}rndRDW zBG$k%vnOMvL7;qDJe4@C$x%8w~9M z4bbT>wU!O)5u=7+|A?zXCLJu*QH~fZiP2p)m??E7BX4u2?KiY}M4%cUL@XuWjX=4REO*NNU*nuOGLzH#pua z!2F}xTvB_Lj*Q8^llf6OkyL5GsheH5{>uz$X1|P5cb%ZE9oy-?1!{y7i){7MwK>cx zPQs6E13cl<+?lD`L(c#HI{Qk9;RCq2KFL5g;Qlc6{Q2YY^z6Dc*uB!GZnuuA`K|NG zAjT#1|0)G@{ufbBQ`yWMiRGJ}shI~r2MFK+ap@tks91TK{ilk=q5;qW0oVYb&rW4~ zdza5n_Rk@d|HEN!|JnMFSpA=tI6#MAf?b>yD8|9g&ISUCiLpt5L_iWCF-{H+F-~qV zaS;wd!2g@%a~@eUJBv@*nw5UUOZhZnBV@l9QW`BnV@rgit;G zfcR`8u8xV0=3vYRAtak9DJbx0GihVk@U$k=s~y)VOBCbGxHOPd|IwyZWYn(KrdNZ> z9~ZF{DZ2Bs|9Hx3dwfjsWOG008oYg7t9i;f^d6q@Un*>xeS|8Ewj{WMwHQsth64oY zlD370h#>r!pwW=TM^xG)9AyF!L(lDHj84%IBZHh?9EjUIL+UW3n1glcjQC?HHDqf- zfRI>Y$M*+Vap7N`CPqUMX@u+dYzW(o`@cw2mHIMM$OgMO74IEjm=4WyibCKAS>X zaCjndZ}$iFJl9P(SDH+1L>T@vq%vG(M2jY`-$TDszH?fMzuA~33V!D!jdT*SG3CvuW{a6kIZXS*>V@-+?TIfUYn$`u_HSRlOhXFn?7`y$TPyO zmD|v_)v>q2VKT^ssr9QNEcd~v(jzlYnOiE_V(Uc6X@Ig@Oif{c9-1tt{s3;*+LydL z-Chp~A`U4?KD{$WR4yD^b*Z{`0v9f_#+>ND6PNqp)3s_mOGwXx@i#)&${Ng!z#BJL z;aI-$ex;)txPwpi>Z+1pO+-SvV^Y#WhwE&?q;6UQuS4?ZB5-==9T-tZ{!_FB1gEoV zNP3pNSW93*WOyOCR<6bWeDHf6Hgg(og4gNUFAm zu2?yaEo1oIN6?O^LKO$)m=wS8e!T1M90A%01KS)Lt*ed%pPgH4STW=7h_uYZNV9KP zyKn(Bz?J|)AAD%Yh#&+6Q3Q(E7L!)IMY!COv^3K6o)8Vqc8(w=#wHkvLRxU2nl0|Hf=cJY(aT|%zr;0(6e@( z0v31OBzYYH@|Jjv;dV!X`bWWjyF8qRHWuV3BS<>Zx@dyKPOAXwvaR6c?d2r9$- z1qtV*fF-OvMn*LoIsx$Usxbo50pEa!y~1x|4y(g!pqF+RD7{0#q}xr+ z-|WE_JBi@3FgT--lQGnk4q3;p6I}cZjbl`fz);%({zy{u_H4KsitbM?4P~+3qT2pW zl7(9%F|pn$-vk<{aBN=Zoj;`_X{nO!J?#X9IA}wr~EmUjA{# ztd9hG{w$Mq-!kDsy_BCN6AbTav#Mo}%8`fuQ75en2}ZlgHf(-4&55Vlksj?`7xP^% z4qP)rFblHS2Tqs*BBeV5!*1vtSugB1LoGt3WXMuX-+eriHGL?Na-;u5-fCLYExRe| zA9=&`HFXotrm?VY@Muc$P{Gq22g^bN}fLCJMBld_2ZV2A^3%SJDIfSsx&n|7hQn5TF$LIK8(yxer zueBhRwdY=7`AJIflNBp0+D}I7G;tVCHX-NuO#StfyQ`@)cfpH*Sch=YIA%5P>4rW7 zpg?q(WM>{?R{up zLs|JGW64Z#H#(I(7)1VA|G0Wk+RldDw!cKUbi8;$8QbikBDRnf+WO23CC2TDJ^G!U zY#K*!98-Q7ve1nl`snufF@(*ke>LE$Rw_hcVH6yt*dl8NPjDvatv{4`n_}Xr z;7gOiOZ!N`@gbn2ngn#PNyCnZ*lv5G&;R{(adVu&sy_JNu`l3sbmpJ#=-+$`S~wr< zvqaGw8r)t?at5`uyS#)qc=E$UV6p6Im)__^C{4&~+f^0tz8)xdvYLyDT3_`Vv@2@V z19UD0p04$0xg;n*L`RFHw35Za5|H=oWr~(#AB@HA&0ON(PKNz%>_|^Q*d<3yB!^Wd zN1Z1}HjXiHQ=XX$Kspmg5f?Cq^F zll|=&NR--p8G648uwLqkbbR+B=clwOgDJ=RFn@LjS3dYr%d);#pK?sXy(|aGhzy4(~!QoaV&+=69KjOqhtOrSc z0eedEJ7_sWQ}4tF{~=_@Jlq$+mQ6B3!W{#`{!TuEudxu#9VNy6>!!KFRn!)M*v;@0 z?=`+NNAz1^Ml@?amR3{#!w5UEwdiJ#nhuEi&MCgxSnkL$x%ut`S4E_Ul0FZsBJUHu z5p^->9raViB=QkCi|}k8V{QrgCgw=jD8hHN3HeM__OW>sw4Z12Aux;VJ8LgmTHGp{ oTG06c87sXW`(F(q&MrnyE*_sI3nX?9POeXtJr$LNf+W&^1AASi0RR91 literal 0 HcmV?d00001 From 57f47dd27a3c34a2339d913f41f63dd7ed153d80 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Mon, 23 Mar 2026 18:57:17 -0400 Subject: [PATCH 07/12] Address review comments --- gtsam/nonlinear/Marginals.cpp | 3 +- tests/testMarginals.cpp | 116 +++++++++++++++++++++++++++++ timing/timeBayesTreeCovariance.cpp | 57 +++++++++++--- 3 files changed, 165 insertions(+), 11 deletions(-) diff --git a/gtsam/nonlinear/Marginals.cpp b/gtsam/nonlinear/Marginals.cpp index cbd4c7f596..17070dd3fc 100644 --- a/gtsam/nonlinear/Marginals.cpp +++ b/gtsam/nonlinear/Marginals.cpp @@ -13,6 +13,7 @@ * @file Marginals.cpp * @brief * @author Richard Roberts + * @author Frank Dellaert * @date May 14, 2012 */ @@ -90,7 +91,7 @@ GaussianFactorGraph reducedJointFactorGraph( return *bayesTree.joint(variables, EliminateQR); } throw std::runtime_error( - "Marginals::jointMarginalInformation: Unknown factorization"); + "Marginals::reducedJointFactorGraph: Unknown factorization"); } /* ************************************************************************* */ diff --git a/tests/testMarginals.cpp b/tests/testMarginals.cpp index 6b732a4064..e439602ff3 100644 --- a/tests/testMarginals.cpp +++ b/tests/testMarginals.cpp @@ -166,6 +166,72 @@ Matrix extractCrossBlock(const Matrix& fullCovariance, return result; } +/* ************************************************************************* */ +Matrix packedSelectedColumns(const Matrix& fullCovariance, + const KeyVector& orderedKeys, const Values& values, + const KeyVector& selectedKeys) { + const std::vector dims = dimsForKeys(orderedKeys, values); + const std::vector offsets = blockOffsets(dims); + const FastMap keyIndex = Ordering(orderedKeys).invert(); + + size_t selectedDim = 0; + for (Key key : selectedKeys) { + selectedDim += dims.at(keyIndex.at(key)); + } + + Matrix result(fullCovariance.rows(), selectedDim); + size_t columnOffset = 0; + for (Key key : selectedKeys) { + const size_t block = keyIndex.at(key); + const size_t dim = dims.at(block); + const size_t begin = offsets.at(block); + result.block(0, columnOffset, fullCovariance.rows(), dim) = + fullCovariance.block(0, begin, fullCovariance.rows(), dim); + columnOffset += dim; + } + return result; +} + +/* ************************************************************************* */ +Matrix extractPackedCrossBlock(const Matrix& selectedColumns, + const KeyVector& orderedKeys, + const Values& values, const KeyVector& left, + const KeyVector& right) { + const std::vector dims = dimsForKeys(orderedKeys, values); + const std::vector offsets = blockOffsets(dims); + const FastMap keyIndex = Ordering(orderedKeys).invert(); + + size_t leftDim = 0; + for (Key key : left) { + leftDim += dims.at(keyIndex.at(key)); + } + size_t rightDim = 0; + for (Key key : right) { + rightDim += dims.at(keyIndex.at(key)); + } + + Matrix result(leftDim, rightDim); + size_t rowOffset = 0; + for (Key leftKey : left) { + const size_t leftBlock = keyIndex.at(leftKey); + const size_t leftSize = dims[leftBlock]; + const size_t leftBegin = offsets[leftBlock]; + size_t columnOffset = 0; + size_t selectedOffset = 0; + for (Key rightKey : right) { + const size_t rightBlock = keyIndex.at(rightKey); + const size_t rightSize = dims[rightBlock]; + (void)rightBlock; + result.block(rowOffset, columnOffset, leftSize, rightSize) = + selectedColumns.block(leftBegin, selectedOffset, leftSize, rightSize); + columnOffset += rightSize; + selectedOffset += rightSize; + } + rowOffset += leftSize; + } + return result; +} + } // namespace TEST(Marginals, planarSLAMmarginals) { @@ -455,6 +521,56 @@ TEST(Marginals, crossCovarianceOrderAndLegacyAgreement) { } } +/* ************************************************************************* */ +TEST(Marginals, packedCrossBlockRegression) { + NonlinearFactorGraph graph; + graph.addPrior(0, Pose2(), noiseModel::Unit::Create(3)); + graph.emplace_shared>(0, 1, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(1, 2, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + graph.emplace_shared>(2, 3, Pose2(1, 0, 0), + noiseModel::Unit::Create(3)); + + Values values; + values.insert(0, Pose2()); + values.insert(1, Pose2(1, 0, 0)); + values.insert(2, Pose2(2, 0, 0)); + values.insert(3, Pose2(3, 0, 0)); + values.insert(100, Point2(0, 1)); + values.insert(101, Point2(1, 1)); + + graph.emplace_shared>( + 0, 100, values.at(0).bearing(values.at(100)), + values.at(0).range(values.at(100)), + noiseModel::Unit::Create(2)); + graph.emplace_shared>( + 2, 101, values.at(2).bearing(values.at(101)), + values.at(2).range(values.at(101)), + noiseModel::Unit::Create(2)); + + GaussianFactorGraph linearGraph = *graph.linearize(values); + const Ordering ordering = Ordering::Colamd(linearGraph); + const KeyVector unionKeys{101, 1, 100, 3}; + const KeyVector orderedKeys = uniqueSortedKeys(unionKeys); + const KeyVector left = uniqueStableKeys(KeyVector{101, 1}); + const KeyVector right = uniqueStableKeys(KeyVector{100, 3}); + + const Matrix fullCovariance = legacyJointCovariance( + linearGraph, ordering, unionKeys, Marginals::CHOLESKY); + const Matrix expected = + extractCrossBlock(fullCovariance, orderedKeys, values, left, right); + const Matrix packedColumns = + packedSelectedColumns(fullCovariance, orderedKeys, values, right); + const Matrix actual = + extractPackedCrossBlock(packedColumns, orderedKeys, values, left, right); + + EXPECT(assert_equal(expected, actual, 1e-8)); + const Matrix incorrect = + extractPackedCrossBlock(fullCovariance, orderedKeys, values, left, right); + EXPECT((incorrect - expected).norm() > 1e-3); +} + #ifdef GTSAM_SUPPORT_NESTED_DISSECTION /* ************************************************************************* */ TEST(Marginals, orderingEquivalence) { diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp index 132752b979..c0f738b3d2 100644 --- a/timing/timeBayesTreeCovariance.cpp +++ b/timing/timeBayesTreeCovariance.cpp @@ -370,11 +370,11 @@ Matrix covarianceColumns(const GaussianBayesNet& bayesNet, return R.triangularView().solve(intermediate); } -/// Extract a left-by-right cross-covariance block from selected columns. -Matrix extractCrossBlock(const Matrix& selectedColumns, - const KeyVector& orderedKeys, - const vector& dims, const KeyVector& left, - const KeyVector& right) { +/// Extract a left-by-right cross-covariance block from packed selected columns. +Matrix extractPackedCrossBlock(const Matrix& selectedColumns, + const KeyVector& orderedKeys, + const vector& dims, + const KeyVector& left, const KeyVector& right) { const FastMap keyIndex = Ordering(orderedKeys).invert(); const vector offsets = blockOffsets(dims); size_t leftDim = 0; @@ -408,6 +408,44 @@ Matrix extractCrossBlock(const Matrix& selectedColumns, return result; } +/// Extract a left-by-right cross-covariance block from a full covariance +/// matrix. +Matrix extractDenseCrossBlock(const Matrix& fullCovariance, + const KeyVector& orderedKeys, + const vector& dims, const KeyVector& left, + const KeyVector& right) { + const FastMap keyIndex = Ordering(orderedKeys).invert(); + const vector offsets = blockOffsets(dims); + size_t leftDim = 0; + for (Key key : left) { + leftDim += dims.at(keyIndex.at(key)); + } + size_t rightDim = 0; + for (Key key : right) { + rightDim += dims.at(keyIndex.at(key)); + } + + Matrix result(leftDim, rightDim); + size_t rowOffset = 0; + for (Key leftKey : left) { + const size_t leftBlock = keyIndex.at(leftKey); + const size_t leftDimBlock = dims[leftBlock]; + const size_t leftBegin = offsets[leftBlock]; + size_t columnOffset = 0; + for (Key rightKey : right) { + const size_t rightBlock = keyIndex.at(rightKey); + const size_t rightDimBlock = dims[rightBlock]; + const size_t rightBegin = offsets[rightBlock]; + result.block(rowOffset, columnOffset, leftDimBlock, rightDimBlock) = + fullCovariance.block(leftBegin, rightBegin, leftDimBlock, + rightDimBlock); + columnOffset += rightDimBlock; + } + rowOffset += leftDimBlock; + } + return result; +} + /// Convert a Variant enum to a CSV-friendly name. string variantName(Variant variant) { switch (variant) { @@ -734,14 +772,13 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, (void)rhs; const Matrix information = R.transpose() * R; const Matrix covariance = information.inverse(); - selectedColumns = covariance; - recovered = extractCrossBlock(selectedColumns, orderedKeys, dims, - query.left, query.right); + recovered = extractDenseCrossBlock(covariance, orderedKeys, dims, + query.left, query.right); } else { selectedColumns = covarianceColumns(reducedBayesNet, orderedKeys, dims, rightBlocks); - recovered = extractCrossBlock(selectedColumns, orderedKeys, dims, - query.left, query.right); + recovered = extractPackedCrossBlock(selectedColumns, orderedKeys, dims, + query.left, query.right); } } else { if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { From d9f0d54a2ff64adbbb707c4cb79e15fd24aaf705 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 24 Mar 2026 22:05:46 -0400 Subject: [PATCH 08/12] Wrapper --- gtsam/linear/linear.i | 3 + gtsam/nonlinear/nonlinear.i | 2 + python/gtsam/tests/test_GaussianBayesTree.py | 105 +++++++++++++++++++ python/gtsam/tests/test_Marginals.py | 97 +++++++++++++++++ 4 files changed, 207 insertions(+) create mode 100644 python/gtsam/tests/test_GaussianBayesTree.py create mode 100644 python/gtsam/tests/test_Marginals.py diff --git a/gtsam/linear/linear.i b/gtsam/linear/linear.i index 1b7ce58a98..3b8afd9df0 100644 --- a/gtsam/linear/linear.i +++ b/gtsam/linear/linear.i @@ -719,7 +719,10 @@ virtual class GaussianBayesTree { gtsam::Matrix marginalCovariance(gtsam::Key key) const; gtsam::GaussianConditional* marginalFactor(gtsam::Key key) const; gtsam::GaussianFactorGraph* joint(gtsam::Key key1, gtsam::Key key2) const; + gtsam::GaussianFactorGraph* joint(const gtsam::KeyVector& queryKeys) const; gtsam::GaussianBayesNet* jointBayesNet(gtsam::Key key1, gtsam::Key key2) const; + gtsam::GaussianBayesNet* jointBayesNet(const gtsam::KeyVector& queryKeys) const; + void deleteCachedShortcuts(); }; #include diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index aaa73b4d28..31d7af12e6 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -170,6 +170,8 @@ class Marginals { const gtsam::KeyVector& variables) const; gtsam::JointMarginal jointMarginalInformation( const gtsam::KeyVector& variables) const; + gtsam::Matrix crossCovariance(const gtsam::KeyVector& left, + const gtsam::KeyVector& right) const; void deleteCachedShortcuts(); }; diff --git a/python/gtsam/tests/test_GaussianBayesTree.py b/python/gtsam/tests/test_GaussianBayesTree.py new file mode 100644 index 0000000000..b330ff7789 --- /dev/null +++ b/python/gtsam/tests/test_GaussianBayesTree.py @@ -0,0 +1,105 @@ +""" +GTSAM Copyright 2010-2026, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information. + +Unit tests for wrapped GaussianBayesTree methods added for covariance recovery. +Author: Codex, prompted by Frank Dellaert +""" + +# pylint: disable=invalid-name, no-name-in-module, no-member + +import unittest + +import numpy as np + +import gtsam +from gtsam.symbol_shorthand import X +from gtsam.utils.test_case import GtsamTestCase + + +def create_linear_chain(): + """Create a small anchored linear chain and its key tuple.""" + graph = gtsam.GaussianFactorGraph() + + x0 = X(0) + x1 = X(1) + x2 = X(2) + x3 = X(3) + + prior_noise = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) + between_noise = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) + + graph.add(x0, np.eye(1), np.zeros(1), prior_noise) + graph.add(x1, np.eye(1), x0, -np.eye(1), np.ones(1), between_noise) + graph.add(x2, np.eye(1), x1, -np.eye(1), 2 * np.ones(1), between_noise) + graph.add(x3, np.eye(1), x2, -np.eye(1), 3 * np.ones(1), between_noise) + + return graph, (x0, x1, x2, x3) + + +def subset_vector_values(values, keys): + """Extract a VectorValues subset in the requested key order.""" + result = gtsam.VectorValues() + for key in keys: + result.insert(key, values.at(key)) + return result + + +class TestGaussianBayesTree(GtsamTestCase): + """Tests for GaussianBayesTree wrapper extensions.""" + + def test_joint_key_vector(self): + """joint(KeyVector) should preserve the queried joint covariance.""" + graph, keys = create_linear_chain() + bayes_tree = graph.eliminateMultifrontal() + solution = graph.optimize() + query_keys = [keys[0], keys[2], keys[3]] + + expected = ( + gtsam.Marginals(graph, solution) + .jointMarginalCovariance(query_keys) + .fullMatrix() + ) + + joint_graph = bayes_tree.joint(query_keys) + query_solution = subset_vector_values(solution, query_keys) + actual = ( + gtsam.Marginals(joint_graph, query_solution) + .jointMarginalCovariance(query_keys) + .fullMatrix() + ) + + np.testing.assert_allclose(actual, expected, atol=1e-9) + + def test_joint_bayes_net_key_vector(self): + """jointBayesNet(KeyVector) should optimize to the queried solution.""" + graph, keys = create_linear_chain() + bayes_tree = graph.eliminateMultifrontal() + solution = graph.optimize() + query_keys = [keys[0], keys[2], keys[3]] + + joint_bayes_net = bayes_tree.jointBayesNet(query_keys) + actual = joint_bayes_net.optimize() + + for key in query_keys: + np.testing.assert_allclose(actual.at(key), solution.at(key), atol=1e-9) + + def test_delete_cached_shortcuts(self): + """deleteCachedShortcuts should clear caches created by query shortcuts.""" + graph, keys = create_linear_chain() + bayes_tree = graph.eliminateMultifrontal() + query_keys = [keys[0], keys[2], keys[3]] + + self.assertEqual(bayes_tree.numCachedSeparatorMarginals(), 0) + bayes_tree.jointBayesNet(query_keys) + self.assertGreater(bayes_tree.numCachedSeparatorMarginals(), 0) + + bayes_tree.deleteCachedShortcuts() + self.assertEqual(bayes_tree.numCachedSeparatorMarginals(), 0) + + +if __name__ == "__main__": + unittest.main() diff --git a/python/gtsam/tests/test_Marginals.py b/python/gtsam/tests/test_Marginals.py new file mode 100644 index 0000000000..824bfdea16 --- /dev/null +++ b/python/gtsam/tests/test_Marginals.py @@ -0,0 +1,97 @@ +""" +GTSAM Copyright 2010-2026, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information. + +Unit tests for wrapped Marginals methods added for covariance recovery. +Author: Codex, prompted by Frank Dellaert +""" + +# pylint: disable=invalid-name, no-name-in-module, no-member + +import unittest + +import numpy as np + +import gtsam +from gtsam.symbol_shorthand import L, X +from gtsam.utils.test_case import GtsamTestCase + + +def create_planar_slam_problem(): + """Create a small nonlinear SLAM problem with pose and landmark variables.""" + graph = gtsam.NonlinearFactorGraph() + + x1 = X(1) + x2 = X(2) + x3 = X(3) + l1 = L(1) + l2 = L(2) + + prior_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.3, 0.3, 0.1])) + odometry_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.2, 0.2, 0.1])) + measurement_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([0.1, 0.2])) + + graph.addPriorPose2(x1, gtsam.Pose2(0.0, 0.0, 0.0), prior_noise) + graph.add( + gtsam.BetweenFactorPose2(x1, x2, gtsam.Pose2(2.0, 0.0, 0.0), odometry_noise) + ) + graph.add( + gtsam.BetweenFactorPose2(x2, x3, gtsam.Pose2(2.0, 0.0, 0.0), odometry_noise) + ) + + graph.add( + gtsam.BearingRangeFactor2D( + x1, l1, gtsam.Rot2.fromDegrees(45), np.sqrt(8.0), measurement_noise + ) + ) + graph.add( + gtsam.BearingRangeFactor2D( + x2, l1, gtsam.Rot2.fromDegrees(90), 2.0, measurement_noise + ) + ) + graph.add( + gtsam.BearingRangeFactor2D( + x3, l2, gtsam.Rot2.fromDegrees(90), 2.0, measurement_noise + ) + ) + + values = gtsam.Values() + values.insert(x1, gtsam.Pose2(0.0, 0.0, 0.0)) + values.insert(x2, gtsam.Pose2(2.0, 0.0, 0.0)) + values.insert(x3, gtsam.Pose2(4.0, 0.0, 0.0)) + values.insert(l1, gtsam.Point2(2.0, 2.0)) + values.insert(l2, gtsam.Point2(4.0, 2.0)) + + return graph, values, (x1, x2, x3, l1, l2) + + +class TestMarginals(GtsamTestCase): + """Tests for Marginals wrapper extensions.""" + + def test_cross_covariance(self): + """crossCovariance should match blocks from the full joint covariance.""" + graph, values, (x1, _, x3, l1, l2) = create_planar_slam_problem() + marginals = gtsam.Marginals(graph, values) + + left = [l2, x3] + right = [l1, x1] + union_keys = [x1, l1, l2, x3] + + actual = marginals.crossCovariance(left, right) + joint = marginals.jointMarginalCovariance(union_keys) + + expected = np.vstack( + [ + np.hstack([joint.at(l2, l1), joint.at(l2, x1)]), + np.hstack([joint.at(x3, l1), joint.at(x3, x1)]), + ] + ) + + np.testing.assert_allclose(actual, expected, atol=1e-8) + + +if __name__ == "__main__": + unittest.main() From 5704a0c2760a68de8f3772a6a96fdf8c1c8e3a9e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Tue, 24 Mar 2026 22:16:33 -0400 Subject: [PATCH 09/12] Update pdf --- doc/CovarianceRecovery.pdf | Bin 459298 -> 459550 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/CovarianceRecovery.pdf b/doc/CovarianceRecovery.pdf index bbb0265b99deeb1d7c8617f90bdc3c0cbffff607..8c579928be8526b9394975004885027f04787d9c 100644 GIT binary patch delta 67312 zcmV)MK)Ao6gdCoR9FQafGC4MvfvW>4f5jQglH<1VK3}2AiBmO%2?Bh@r(MVEa-3Af z-l@vL>jNZVW{~AWCdhf@>(dW_qO^3JT#}0jG#ZUYzZ-ggfAiIcyxGZ01*V{2n=KVzbXlD8&4rKCi zX!-2)z47+QtKau4p1cEg;IOYgsB9`SRZY>`1rm$(=3pWH2%3ULxGA~hrf1otofCP(N z&xV&5 z8tf;o;4ZW}#C|fK2Nub^I=CkhoX{)~{xFO@=uFRt(u~hGqi5o-XYlkCxEN0G1&luR z!#o}W^t=0y@BYfe*6l|#f3ieVsX>w`QL;3?`69yoa8LXX!!k`YdUV~(M=Q}3jCK8HmA9&7E1KfU? z7;+lzvm0jL@{O{~yX;vQ7F|47$;;@bi6=UlPvSP!S|)$LtrZ)se@1fNvPClhj7rAE zPnp!C4-4jS80Ix58*oqs0eYK)ITU0Ldmz(>1&#+u9JjyV&#=N|G{y3$f;{}z^-Mcj zb3~8U`NDcd3;_Tb87ge+i0?q)AA>tve_^#26k-im*ei?M7E*O7 zq;OhiEk^Qi&FPA0J1kVK4~vJP>nOA028e|oM0mGl!_)9+(NckprVjZkZy<}jVqhj9 z1gxGzL+aBNNyC!soVo>vy^r4%E6xD?yusTNsLT?HuMvJ_1PWhItfLIZA!rGx%$)*DeZUG3Zq#pM!(t z9GpB_&;y07BLgTPAvzR?kgq(?T&y8EZ~>$r`t?d+jZ#2MF>ne<2?f8P+YQ)*NV(fz*2+hI|FCe>sp7 zIDSdCI2bLu?~#d}#sN}n$1D3#<>A;|+{1DxVqVZEFt{y>PbNpyA_H$;A%R8InM&?Cp%3$P7u-)*P{_-xB3CL+LFEr%C0Jxz z)1xUtNgZO1iZwXGmMXB|D)5!;nX2g?it%9ISZJG>Y|uOM2Y`f7>cP4llS2Wn>P+6M z7yYX!Y8+s>Rjtacg3B$jrTKf(PlFwYf1lfl#~2*(YxqNfIz1N@VR2o{A^=kYem6`m zoN(RKAar^%VSlKatd9#}ALiy1+s$K)j#qd1tp*FsCRS%uRlxLN96B7u;uJuX263>Y zr!-_H1fDx|*t0|?Gc6SNvqQ1rFoGuRrx2g2djPmeurcap2i=p>CH3bJ^T4bXe_9)q zw4qy+Z~>VY*di;*=^MV_JJZtTgGtLwG+85&N=AJ*D4F-i#zZ%AqXane!j;6J$4$c1 z1Fo9*<~*Z<{EuC5^b677-yGu>=)Nwv9Fp;WU`39ecHMrWYoHe7}#oV z5zH$g8$-m!8Rz>*B36CYW7(BcMh@Ess1cSj zKZ_>6P&ikptILJzK<1d&xG)5Tqd`av(4A|Y85x0n2}hWc%pR7Y0yr@0f8%IQz}l1J zcma?uSfOn_??O5LFtn`=^f>7NCiR_I-*g7EDT4AWYl6lC<_7Q44wcG7jODRuA1%}c zJi$}nx7=;1_{;`A`Zv;^D zz}H@EXI)TdsL|;+?gbZVe;vi3ro6PH80Y}b{n?1`deD!MYz@~+uxKa#npWH~0$68u z$3T3j2^U4-#=-@cj+QHmcHr`vOpw|g7bvex6K27%B3D)N>?pe8(SCik_!fZ?v*seA z!dmXM*fT~Ne8(e<5J~~Fqvtw&7nvLwAnzlQW7un52YoDR0ZY9Gf1>CVR{BFUKhF?$ z2B3V7SO~t#yjuaQu0^fu-wjyxe-g0Ne;crnN8_1u6K=xNW+8>JrA00Er4?NmC^o8W zpxk6ORd|*IICwLqX?L`-Jzf^pZjPH)inB2{Ae`Dm*b-fm#$ObDh{;7?NU37W{J%9^ z!Gn2XK^voA16>B}eJo0#Ace>_Bg-<$?|poWRPpbB+S$9InpyEu4k!FgI{2v4duPU;MF zk+0#N5}F(Q<7gEw|FS%jTxeG|Ac^8iz1ZiRQ5un#%R@=d7^S`-k_nZms}>82$_iSn zOmg#7SM^Rof88CVzFCeop`<;dh4=JOWb=oDE-J;*+ZUJ1(7GSFJXb+a2lh2s3;#*M z%G#l~gppzAhJQviqK<9e|JHLhBKn3^X*wxeT_if#ssUK&pXfAPiw4{=4)k z%k!-hYXRC!FEO)hTVo}ZxRp?K>_7nN=G*(5UvIGGf6jJtr$DG#tzefD5}fYP-TeGZ zwmZTiL^YwoPG1PML#Y;cjdu6(=Es}&_y_FeagkP&gMBv_7I}GtQb0#v!G%L-^La}@ zc$_|4ZCY>Jzr@bJI%_G*wrvN85$m``s1RkfWcI*Ok*&Oh8PcN2^u^sS6{$s~P@Lpa zQIBeiJEw+WN%_>3NbS@mr;}f69P9dlR=0nf0bEVuj956e&1i=M;TZtB6ZIq0UD&6rfE=Q zV;}{ZKFAW!v36z25v6nKukYL_Sw1p~yc~~)!y!4G%QrmV9o~KQQ58EC21Qt?-Qi)E z>0K5UK^VhVz5BQKd@_UC|L5@cuRdyhEg0!Q>1Y?S*e4cQ>ry&Ma^*xCyZ56!fAx-S zzxQ?SReSjJ1$mh_UG~bm5ZeqaHV#eMJx*;out@m;BBR;+$`c9GHs_`*$ENRsy`P4W zcQ_dyYPyGhIMWa_%C2UjLIpi8{j^VjkE>KN3nmOrWh^iFdl*J|s+}LlK^De4UqwL@ z7knC47)2rgm&*uX0m?kr3n9qGz$Ta%AdU ze!+<%I$ds7vm>Yh-;N{AzKzVszHFIloW7oa2UCG(XRsv45!onG;JnG&8EFA@-g7xT zLI}0&z|~e<0H1;gq)Yz!e`7MkE0Y$Z>5jegJV>M2n!h-w(i*93`v#&kh||K&d2Ys2 zKaIQ;26WRs@`oJY{+20}UzP|B*cdv@1C_Bc#9cm_Y8q_wB=-)0MoQ#zQT)3S1zt(Y`r}}3)nL*a4BN0nvC(BL&~qv+6Gu*qe@6Jt`O=!R$eWr~ zHZu6b!RLdjG$^8Uee1veV=IU)P6XPRT#Dsmj_gjS=`gOexJUzGs#W zmHxow_wHz*Q+Xw4Ycxl$T?&r8pGsrxGB?9`#!m>NBi(lHE*OZjp*nFYyT+cG)r{7( z4|L9OeL}KX9EBc4e=ZYO#>3Cr*lK8mSu^i4n5U+nZ2P(ge`76w{fH&%E?-o0Y}ebDUrP$&Ct*# z0e^=kvaaDJj(GNB3r+Wn3 zC28t?L_50Om79k;urG$8H(4{_<%b!ptvoU_^4%{x0ucQXwR@i-`!WO5P(ynPLw9aU zDOtLztRYn6aLz+NOUAQX=?BV5u4d8lVWdC+^((W{c2oAT)fTsInYRA02yz-q!ywY} zDi8HT<5F>fe-7O7n)s=_hq4-bp&v1Sl$R5KaWEkMQK|Pg#A?KTcIgagyu87VtoRW# zUB*KpT`x#LwmcbxOBJsV`m3s+W{)W3426=z7MQrM^XA4SuhJhT0+#}lblXx%_9oha zCHWL6Ium6@_$b@Kl=UlrKnPni?-m%84?#Ka78t#Nf6LCd{WQ4cR=LzUH1IJ&Zk&j; z#eg%b{(L4J*=<$6GzyAjhAf|d`MilWia=*G`1*#^pJMeGeH(fKhNcTf{4;vBY`e6^ zqN@NR`E8%a9vz49M#mDzscCE31dny*S-yv3GY;kO>P!7cCd}-aW|TlYv^5g_gVdrp z18}Qve{I=Y0U_q4v7?msc-JVP`wg=ULLy4*a3d}^5^t%|g1*SbH0AFVNP1;1 zX1|PqR1`XdgKAu}Qnqu_LtQxS*GUdOAam zprnSYIwLYJPE?>GwaUS4*cfo?iM$70KV!E*CcBQqNYaU-03_>I7Lh_O;&4n$7!5zS ze^4dz*B&J6_cHAAAM)^av-x&umxOmf=o;n#zp;G_okJaLWw8SW4kXX<8cn-cWY7tn zhq;sk^)MvBh9STW4SBQYqGE){tM}t+10*X%I{fAVzsL)3Z#~TLJh~Vb(+E z%QQ-Ve=iOENR60sJrfxJ#l0gmb7pUOf5>v@X8B8O*78liUzKP85!r1s6D_UbW!NXM zk`MKRsQwA72%bX~pf>@q3so8F_jZ>FO>3AsU4wZrgKWvl)~g213x11kMW^d;PT9Bh z+~DZ~z(lb&%iNFp*Zn7K5ZITJZb}yjzG~(@V+q&_!x-NkiZ?}P-OMk2^|yDDe?+3@ z18a;_2+$u#Ub<%YCuf2^F|5)#8-{s!eEOB>Lb~m{M;{vGu4X?5)@H*6e1R%+e$BEV z&u?1d1y6wIiCv=DA%R=7DE76H>UM2IuNI7qE}z(f-mgFq5YeLwdxe4d;!8mJq3ayx8#MMWnBVO1nt z;h}B@HTE*KIZm!^EnFPle;$U_Vflh`-_>k=NCh{50wo56kzkdcTeas>lFta2&bj@E;lk2ZWCb|Ev(?+c#9mEYS?o z==CQK^99lK=O2@cROW!&7zbV{;@|VKj|O&x3v!HyF7$!83jGj6f8Y2^#?6ZC2GW)e zFwAf1Bi=T-V(%}*b6U@?-_as@0I(lq4d}Y!wb8XR`lih_bZK)62f*}X{3F@Yl96#s z&b<8-BQ`NU@&~N)X1_>CpuaIbz|2g=3vv*!XKKbpI(1P9R5_!|zNszqYSUQ}Wb;UcwJO(3xk;U-AGEc@Gn%w?dvV z`{4@&V?w>%Gd8(8nhO950aT!uNSrzJ=ex>Q-X>Ca8l(ssf7^KZ=fq*VN6FM2+3z_p z1fJh)L1JA%T^0plx_%+D(`9b((3Hj1(_d69Pk&J%O5<>Ot1s?0TB!~efcO9VEKJO? zB5)3c!MgQI+0ykUMO4DOkQ$8CW+#OM+(|7*0Aiz&m!tx)vbe#$Z<;Cg(zy}4{&&XQ zXuvrTD!Ug5CUok(;%e)h*1p30Gy5&H{ejL9Y88;TbICP0^zN^RcmD%OaHyk`))rxZ zE23_;+PC1Gv}p?zr&-`UG<~3D?k=;scqu8nKEJ+mqb%Fnq6iX`!{Kml{AQ@=RSbXh zO6y&;Ez4D|<0#LIRn^?R-svbVvm|4d*_an)rw~4UZS?Aw?(R4E6P7kX>SiYP^TXYz zFS=ZnQCTF#>fv#PZf0Jxg=LeDSxc<+>-@rxSps37qHd~}<()_gEr7A+( zcj_T5JbBTUW>xKglax->o=&iJ*FG^}=$LDg8f?}Iwb`kzAHYGKzrV0StAp_`Jo0S8 z)kzgtjpiBGp4D}M6+%%!D4f~Xw!dd{O?&v*UcFUkk9j8Cx)F$HCG-wXlc5+L0n?Me z7#jwp=vaq4)05yBEj@@(!%ttba;38<&58tX9Vnb;QMT2rZ~{AZlB<8&+OW7S-ntU9 z74m`h!=;65T*jrA{Rv3R6W&irnrtzXN*P6e$9epBgTW0!OrsneMK(#OQ}v6jYh(R@ z39U1g#Bm85HD%2fOy|VP)X{K&IS(1B7=u8_Gnw$lE5jP&M8lbJyYtS;FSxZa{s~g8 z=Gl^$kiM_k@CpUJ^el*-gv(~h#08g?<(12TFu4rIZ*F+*M&U$0M_C!ioRvf+tijQL z!M42+7lV5x`+FQ0D z(m6Q(C@!z;fs0+9aXra11}mZUc%xr`VSXJaTzoXufcJ|x8KFwG>H}RQ9gQDcHP%Kp z%#teq2suPXYwdw@5ypEiK?^3~x!~QstKAUl6at_n8!+Pq2>D(SdIhk7$-!2RI1%W` z6~O98s3U}5D_uloT3jCaJC;c*T%|gWz8_^Q)vQ##X=JoFy{mZG0n|dr@WYaS(F2~x z$imB}=U*;xz&?68!P}p%8)f+oZS1&MmNOt>8Dt_1=FkDtIdqhX`rJXR(YVc$bw8bb zlVa^S^H6$;sA=)oGG?40E69yNxoC+3I=~*!Ii=MF+MIY%Pyz+s00ORG00Odk11|Qw z2$?6;r@GryLX~*TX5p@0p%z4ccoK{*fo|bz8|tPBRT44eo~h(?*=gSg8!~Ash!Swj zvL{$Il4wC)795hx9&1y9YoWDbiW@%8HLh^^PB0?Lx9Z@&$2zs%GMK>{)wO&l+9S`K zWEPI8ZJ}kT`kTrIIH{N#v=jky2;(DjL$^Y0E`=N&rput$mU4?Xqfb$PG+cHH*@qc6 zn3t*bg@h5TC@!*KD{zym22VAt!8c^CNB8YDX4D35~R^j~H zI#1lPYWPP0HXKJNy97s9MYWt#3Puc^?vIdoMUtt%LL4E>vUqm}U}%4?UkE4%dp2r` zl6>A0C5eub7+*h}FiUNJ6KEKpS>Po=5*cD(FoT#fokI-F5MlzHFopdH145pA9)kv3 zgcy!`0!>~LCzr0Fl9kBg00&dla1x>h4G6eq8)JtPc2pP{NX;jEEutU%SPfLmNXX;O z5goh<8lF&*#Z_*J&`KuIZDEi1a`+eLdxXyn-*0~J29KKFLd%bT0Fs+?Wy_$WeH}yk zQR32wl+XA+B2O*dfvMde2&71Za)#pe*yBU4n7Tgku084~V=*sR-`0r1RKD8tdBihy z`82_WBR)pjmKrDAEK;)REwxl#`TawVNYvZ2<51u}Ky7I*r=Vb>Y3Sy;I94|DhxeWL>1}AH%lh5#{_747dn?I-?8R@bnQi%%E<7w=B_I=KntZe z4N&!QS^5@qo9jW@hmCg*ZFys%VW<2)^i09)hrd1agn^5y%h*8vQNN3%8eY`cE#lbJ zPj>H(Ob&;so#;g-nTCVu0Z3n1(76}q8kd$=DJ(?k2{U@xurB6*yf`nQi{^({Vy3s}S7H`E*$|ap zi8zv1A`Y)q!P;CF>Yw-k^31_^6#9b=wDbhldVBqdK8diNf2Wj`6IjmCc_%cC0qbUj zg1NugRZv|!mu3RPoIe$2Niwy2I3CF;V5Vb|RK5z~l6j=BT}U)7|Jrv`i4elkO^78I zvXsGpQr?|OqB_|p=zH@mlh!`yRG`U;$};(%oysoS>O62@0f21(Dra`osM3W7XGKt^ z7nA=$J&BIzpEKfg5iw)z=b;^UZO=^SI|55|N8)thTS**Vxbfx3uz2ZvNSsO4!etXS zg%T9c9@H_$!}S9gaNB7>@vTuv5liEim+~kmKoWqX!zj^1s6ae4u3;uBK}8%I(IO6g zGgdJV#tHST6HF$ZU`zsXlPMrAHfhBFU+{lt7%G;QkxsJ}1RzSXlvh$*x%>6u?!Q`$ zs74B9Ze(+Ga%Ev{3T19&Z(?c+F*7ii@q+;=l^_C3vjHLb1_3jZ0T(EfBPbbvYiGTd zvg^e514Tj-Vv1w{%9nh7PJ`rtAVHDRDrS{5g8>`er!Ujfn1N)1S*8VZObW>&lUm}6 zDPeKRltyQmvAF4(37`thslb$E&gq^~%$vxRWj+|D9E%`P;37Z(u2Ol$v<54I-Y{uR zVA`V(n&|+h0&I!7Q9Yv|7B`K5Meopql?j5?0)WW^mNTAN;Bp>4B>L!>^-KlGwty84 zRFUYt?Ky~)Ml%Nmr3Y@uw2JsW0un(MfTSbyfMUFXCQK7w{An+t8K4FmS%4}b#9mO$ z2+#+M9uGrRL*@#kg3~MjvZnhHDk#q&$~X_3NLUW?BA$;B9yPO4>RvQ|%ql1mEmVqu zkt!DWBUEz`hFg~Oijmm}zEY5GQr4bw$|_tK=5(YB%bd}&2W<`Xl+rER_A$YL>jraW4$?lC`y+z!fnR-ss+wCoDT**-w+x3CoUu*@G${%!Z3>v|Wzgl=C!k|CYE{tK3f$;#DT|HP&n_ zR^R*YT?Kap$!&f4Yr0(<;t@5!x4{=_c$RRt4E%kRHGf{&I!eAIiFZ=AE4II_5`1p6 zX-%4E)EuqeKB4Baofc+kYF(#cwLMjI80IMPI!kDp4A}2~2EJ3XlSD90%^K<*MmTBb z#-bg3Ww)@iHu`+eL}I!U$=1}hBQ{r&y=e!_IB_eIRpw!{171hk_^F+d^0v#?fNlx$ z+fItTBXIShS)#v#YoDcuueN37YVQTvZd&mq@fx%}IJ_bH|DLqH>R7n8EOakBl$fOW z&)eLZMdopTw>3U*OGQnHZCTg`9fCJi{L;<^jnA()=I?PEb+sY8sjSu{?(aFb>AAJY zIO~X{;jL2EQF7TuJHpq@aJ3z#-wAWtUMaq|`G4E6YcnsKDR#@K4>v7_(~bbX+E(j~ zx+AJe$VNA=K}|vnHy3VIyGma3>YkP3#^kB#|4NO2+@sKKsMQWt)Gd~dCHJ2bLD9DJ zeU!zatJwQBu^D!7-ID6pW_8hCA3m=I?+#FAOZMHbN@$k5NjpYo-Lv^kd!-n*)AQyk zwKF|56M4Q&?$GwewPw`L##`P1@1E_SCLv7_e%etQ#!bMt%RqZfsu%4Qt(^MS>wH-BpH9BA_kz)mkfL3ek3Fy`@hp=v&gqWE;|W;3r;RC+8tVJB zEme1N-l=(~=bf2%cHX&pHwPW(T;iMy?Y+!@`#GPFy_Pz)>|XYCQV#R7#wkB$f6HEG z&oGb}kY8w`W}fEOgY4w`YzCIut77~qJ9_e@7LXm)KFUtA zf4qH3{|_!_vuX7>%ZB-A)X&QqzbIyx*Jr$#WDkL?3*3S;t66WyDiT(BfYX+c2}n49 zGBBwFkMN2Wf@`lqcf{7CX;92^z67O&ROkJ{Y*N;tbw8ktBH;}vhl(D~JuE2axpyjo zQt&EmBgvLt4 zosS1XBN4ccY@ur3z(+`z#@Fbyj@!{Z9rcSc>cOb^&vkx}6U$jFl%c_c2^M8M7#<04 zX$Ksl_71!hxxjLwl;HjbIKTAss*>VM|Gd24tkVMH@owV7fxys$s$&A9(QCVZCl*!w zyKG@usb${%^IyzM<}LUl<&UpNqmSFjP^u`gi$n{DW!BwDrZi~iU{Pu;EV51e0##J4 z&5Qad(k*H(I#CkK0<1pf42uCB^@z9_C=0G)IWUY)+!h0cfm#gcxJc^7z!8~Q3@pL2 z%K=toxfDtVOL8t0P_sAXWN?yy!#61Zj$g3sH2*qVFQnG%LTxtcLVee|kd6ZD8cz8| z9~S+h#?v>|cDIi}_=?Uso%GyN&a#@*$+FXw!@^-I6=ef=&NZO0_!#dF3@Ui;P{S=j z=^#0si0=gTe_N3qhhY*PBLx?DW%z!0C=ge&ywY4qWOdX{!q=Y{a5|-bRlY7eJMo+s z7uRLZ2mR^FA#IafD4Fb&&RTR-16X7Qhl9mJH`z*K3un+~ff9b<3FYVCBjnv^V^ z-FIZ0wXEieZ260)BmDTMl9Jm@O76}{$;@p*`q#ZNi{38!<^4s{GK-{T7D>x4UQDfA z^s1f2py2R&keBSiba;M$n!kI5%0+Oc9zvrs?_(mf2e`c)B3O?5vz$FReyjw_EiJu> z)@b=im>-1r0d%h?!(Ak&Wq&%&hcI`4RKa#{PM^QyFW}y@{&-ASPA`j!;ct%VFYNcc ztRR|cE{(Jib(VgFvUmxWeIShNRq;8;imv2`hwRg|KfA2*KKs0Xc+}M=vu)2&5Uor& zx+xJ_MOn?BUG_`nd@p;|Um5&S48fJrR~ogSh{17Q4a#ClmXa>a??3HVc^#oL$oZY; zH0aK)fM7XYK~j$r6x9vI%MB=c9g0`ChhpLi5^Gn0m@Poe1`xXe#NHlA zkSjoFkbt-?K>P-O5WfK=EP=eIkAJxPhzsi@k96TAGSNOQ5l3z5sYaot6ePLg{5;2u zr`+&9$n3YZjIxE&#B4Iov)PwPHoGkIJUd5z$<7h=Syg<^s{C_4-j5R^C@c3Pbv}D` zPbH6qX`Ey_Y95gKEaq;Eju}+AUYZ?Mw}@rGy2m{S)DXgdpq4=Xpf8%V;=<0cNoT(= z7K!rR3g3XiYb>(nVZdm5GYa&vpyHN3bHqEgqD2^sx{Ti!i>WI;m#|o2c<}B(V5H&n zA*V8idrw=6C`;?zJoE?HHM1~EM0t?#Ac{PF1$rPnS_tl_urkP&ilP_q5<*e&!-Kk^ zEPh@V)m48&?CqdGxX-OBp}4|J?GlesD37UFJQN-kTlO(tW47;s2Lhy=O|I@UmNBV= zZ?MqLucPmo?}UYFcDLh&;eRCve$c9aHDErdLy7DCg4yp-}L z3`&cR#mvh@+9>6{473VSy#j-;Q+S1aEfr6BTZ!I=)hZ`*-v!VFwqeZ8Vh)w1s$t~* zgm`kXP?}8ZY(ziYSWX)kb@e1}mT+8Iy$?2X$XuAk1G@B06~NmW?oSOGr27aF*ox$T zxbhXezP3{Wj`S@UAQf5)62 zz=0?tWb$cLvMS9~8PU0VQs+?()oCS)xz4dGQ_S1oJyB*YTOxoT%xf#4^k!gxX6hgn z$-D)OWwOdjss?<$rYK`jg>Puw`x;6GkHG+IRd)I&B~X@sR+3rm>-yOA19lL@g0~x)^=>W%P*UT+&NYZdkT@Vp##% z+;3SHPb(qK5P1R1!YHZ=^s*_ydWNz%b8{s|mcPZ0Rs%$-vy+|23~;GZ%w38~PRg`Z z;b%$N?CQSd5rrn17R7ta1ajSS^i544cgm33p9f3G^Jl@*8$CoyF#2eJK3gcb-f?ZJ zd_o5S24hGPV)S99dJd;(jWNdPLEO7EDF^UEr2>d~AhKa2$vID9=C5%pnkWr*3F z+HM9GsGIim16XzZ%mMx{{rAquX#iHikMk&Qui;kafjTOB263fa<`=&F_7TdW=%UZw*a}F$CfM=gwJ^SSuVq|t9E@V@s0>YT6G0iG3Hv4Bk{+wNGVG;^B zP(XQc=UMl79}2~2FD{>b`|Q=@|5g~+szBnZ3<*#y{ZC7U2P3E5C`N{z8- z8+DelYCddZHQ$&Oud=1%!9@dRWX0kRmlj*3RqhX2SM_MHdF=EJM6zaSu`l8`0G#z4 zK(Zndy&->-GPHTM)$&r$m>{b7cT<;pnflT>Urclk|f}tRp z_^^Z-^DFs(X~ctIRE>Lcgk+VxE7iC5Dj)#WwU<$3+6*ske+2J@Oeu=;<0=z`aM>WkE=3joxE-kZR|U|r9^ z8g?IO@@|L!GDa=-cpq60PZj@`OMlbay*=Q6KzZO(<7YV!AO63j-U z)XJ**g95;rm3F~SC*3+zfa zzWDPBJVnSj{|BFf%x;sRKxBViUgTk&corLE5dFWIzXPjrLB8t_R7X3y)@zr-H zvHMGZ^$++9ONYSpuyB2IbM@6VuXYuya*^+D?skRPsk~$y=x&a?eyxsJHO|Ir%df=&h3-w?r9P%XB!;mN!vT))j^JWf8cl!Pi9LH z;Q&(&F4jG={NVgF*qPx*+l;imZ~I%vSjyyEJy~lssvy;c%g}$;DocLYmkQ57g2@R8 z`^E=jY3dFn&`v&7ohRmZ9P82SIhh7%v<IIzRWKjg`EKDgmjxiI^vvbxws}O+TlLAdo0hDt~a$wB`ij;>s($F9eiuBP|75DkEXg^&RjBR`hwNYgc077?St=K*OVf z3vF!urGHRDIpg8d*%b#}4YgL|P7BowF0OE(rI}iHFl^e>E z7s=xTjlk|8s52dm`@w`O4QSqY8G_6(MQsO?8b4#9;I`;fyjh`+I}u9fuIxvG)ir+! zleP8&92+|heYg!!jt4!iSg!8U%P^n{KIeFxE2Uugh}8Y?D}4oC9BvNZrH}@muyMfy zU$^8Dr(+-3QY66uO-MoP{zB9O#Xui3?c5$ic-sSoD9#g1%_)de zF8pwyJ4=x;GwbbgwDS&~XkcX;qi6(>9vVln)GdN4cleomJi#NE1MXQB|1^IygV^0f z_$Ckv#>TaQJh=(W8uyX(dGmj4@JUZaQug-SO z*={TH#mF$(k~#pM(QYsGZJvJ!ZJzXP-rL`d^<`<1C4cXl!$0?M-!Card`T<#10pis zs=0vbgR8;fotsN?GtJYr3vF0K`+uoS>fNvV8S+|-xD6sOlPBAoJyg1FJ3M%-gK43Ze3Eh?xfY@BI4wdv&xdk z!Hix&Gg=P`5|S&saMqJ}NDqIu(GDND^W{0``WbM`7IpBX2qWnJ5du8XyLj^k1?|cz zN-2-WAouz$;JF66f}#4P;Y(Il#i#pcFx_c+Dsw!bzui1Er0Xs`yy2o#P8xy13mOsd zAOIJ0$ixG_4yEN6G?Lk~jpTLo5eM3=S=6uNJg}pEv0pxFs6ToZC>DRzI!F3UdJkCj zq#hWubVVdto<|-HHjE^o-z6?=m|&|}eB4BDm6NOh3|*vop{e0=Dw1Ew5K*HE&{I|~ zY2o=7y%A>5LgWj5_&KEgI-2Skn73LpO3S6Y7jVy@_n`!5Y3cvhA;Yz+w>MY+1>GEs z!3t$=WOH;+jKFI zDTb8d*=B$D;SM886t)njN4w?DxrJ|j*wgH<{oOy{=eJfK=PE$@{lnciZ?Vc0Qk?MY zVV8dik}<&%=PY~JX7BR1&Es*X?^m>7IsNv2#b}X#XJ5DVxT(8s)!h@BPj+oQuBV|k z@MXT~?bgt&k5fHbi0R2;YqquBZYKTr*`BF(Q$09<$sO4Z4pG(Gg zV%7^DvxTl7hia;~cC9~7NK;?t4^NH53;%!rdH6d>2V{d(Sz3-O*rYT+4E^DL1$gRV zrVp0;o&C3Lz{AiRsNUWL3*T23Tpt}BuoVe4Jk{+^Q^HvOQ@3$Q+?^ke_2BMl+|l<1 zW}oWq8-Hsxx&3qL0s0n10w{4lx#P#tb93zcU0uM=LWc=)tcR-G=-sE71kk_cT-bm6 z+%;YA$#W_g#(LwxXNd(|j>m%)azB82;C5q;xIn4^^9FMSVkkodOH0hIZ`)pD{%FLz zwV2ldL;GrYY`Us#eyyek%qCD8%d57v3t&JT>}9qd*sDKn>ceDdAS9%LFc1d=QVa8haO@$zO(6l9g4dBU18z~txCMVbq>(YHJhJyiS)}lRP#Ez*pDaX4Gl7&S3;;)j z!fhCF%CAt)P|3?IfPxFL)~n3_?6ArZUI!5gD-21d?1_J;=)(jFBH;c2@Q@(WGP@!O zjvJtj11bU_3h_vsOC&->5jj&*goL4j^8g7>iGxCjB-x3YK>X!J@xKKN5+Z;9uNB+R zDZB*ur0V?kSZEwboXzM(wsD!bBsl^x!d^tpHcbr|@&+w;2-r2WZ z($3*H5evP>7ij03FL=BlweneZHJxl)^9d#Y;;P~`;&hOqr=|5J=KFdr}Kc>2SkP>iX)PEX`+fFX{-+wB)xvH zG0g|Vq=Ob5;gc<0w6>e{OJ8PfZ!}K|GSSvCIfcw(mnH4mrr#fqCb{ajq23&avH8V> ze~_q=Jdp}a0HO${$fqr+8TQ)Nq{}<-0HUeqT1CsgZ6FnyTukyGb{>D|QpClqKmyNv zY|_zG5F8nrK?=FLw*}BOdiq^RSDFNfghJd-f-W0~6SPL%>{1$}0vMww7d;QI0)jY> zlF25mXu(*RO!UQx3&D?YxwM%@_TmMEoA||u`D=qq~hF>z8d8sk=4pLiAxd|G;xs<;e#7B!ar85zo9PrqD&PL z?acrGTmajYi$RWsmR=%Bg-2BsNl9g^2kQ zI&ziP$7XtpW+KeaL`2@Z&fn$Bx#Mp?H{Ii6jIypqcX;ETg0|hY@%8=?j$%erG9RFv zw&~go5VZ0Y>NZt z_3sNzS2HbI8hUxF3qG7jBQm{y8mQC`RXiv2=-op!=n=rXWVz*Z6|(Bn<=cA+g43l7 z!NI5pUM^QH0v^>1ixxujww`P^2OR6MQ=&bAl3ClE4_trqu!#~=^l~*13=__R3kgAO zHpYkK^guzFx}i+e0VY`{VqYfW#Uu|FPQy$szP=lqak7>R?|rge#S%P&sH?J+5GH1> zTxpKYY|1(rg=AKUSgpSFv@=n<9KMcjqWEJ!I4^pvyLtee#$MjowVf?#7bC#40p=Bz zKtB`#j6(gf-iDWP?6QTCsS>!Bl% zrc;rW#6${hEkbY`4F%KTnqQ+)XB@~P5L|u8Ocu8U9k6Ql#+mm1Q35+1m&P)CX0&eSq)Tz!3%T}+hILek@7wb56eL>EY)qZZ#ws7Ko1)_f5r^9 z)$I4+QyfF7+}JU_-te8FL$$U8@U}NWLF4G{e`Suq0S)^m*>fwf2g$xdGX_BtOg(^V z8_$1gf1F0hA4!K|P-B#Y#9`*DM{%iQdt!k-F~o&&7NxFtj+826SuQub!1Y~F75KT8 zPNr@1tCk~Z1{7t-`OHc=EFL~S^{tD0rpX~E`COrcle`kdK*VL41yC>Qvo1u<_`(d5elUF;EGV150G}Fwjj8AC1znx|%t#85mdV=Sq~w{ProM7e zBd-?Jk`_+{Jt>bQ`*Ms?iDwmG@cW?QO@H>03h`*H5B=WBPzV-aZ`9-wDV?iuy?6Jw zhr9m)Ao2hklc7Kqv!hxo2LU#d0T(EL)ml++8#xYs_pi{~w!p1MA|+8e6bo#d&0VoA zuGj{5z0LMv>P%91Q#(6$y1jpYAID?IiIdoE-TDp)B56!gpGb?q`7oCTk37*q{9M(>v?Ae6im8+N#u>$g-5vMElCS<6Au#!*| z6c!nMP-SHkDFd@NkrjJHn`l6Pga<)^;$aK{QV9AC#iIje5P=!QQB}^M5yi)1Vh)&q zi%Cv36TC^p;KEuHRx=>TN)fOrfF{8r1kNNGG%!&rSQ^13;_#1P5}E6>7*RbCv?z+7 zpkUF*1VagjIG_~K!S9qrJNgs2)S@s4I#>azHw0B~1bc-2C}4`1)plTiPr6b(m82$v zhC~F~V9;bNml*6>fe|EUs1jZzg>}W?E}|WHA*n7BI!Qa;WUqD*I4G&#z*{osJRnS) z6F4c0$(RY9Vse2s2#!`9uqi|FiVx~6owvaOih2n_F-6f5%u;kklruU7x`0O&PC6I3 zLN~j1RG@%8WbJ?k)<;Kw(9zii?8##hutrG=9==h;b$*Oa^n*u_2GxN%_K@w&FQ$6+ z?_XgD{3R=pJia_Xe?9o&hr8$klT{D7Mt3+F&&;DoraIJ32?y>t4nwy?`vFA^TsHt$ z_39sQ-ZjHH*VFgdYkc+Fi*_=6+04wbsa_l$n(CdU<6oPlL_8^?gfy z%Y7UAHui0glNNk`(zm&9d%3+mG{DT;Uap_ZyP@(f?T10k!ZWJkk* z>zVcjC$UWk{>Z#)8x00FML1}S>vBv;YkFg?GI1z&T0xs6s%T0ffGClo`n|W$=!Gk+h*FhI2yL~ z4$&aypuSpyN!VRlgzg7Sg6p7!TA+zgmGitA&C~PR`?j9$4hrghtA)rC3X4UFw+|?b zunc7c(PNZY90c^7U|HhbNPex~zaPz>*Wmv03!=9+||#1GnmKc^{6d8JRkjW+3avfMcvP|gp;wc0`Cn@#0JNqGo)_% zW&Iu`SmyAJ&o+x46~ty_^pdSZ>a2D<*~ql^m9sxFoB0 zcbhPMt)d-gVZFaxzzHY|^`7sW!O<(D)%}Hpsh7DK)hNyq-fK0MI?H9xx8gY+on5w# z9o82!R9===(Hy`Dd|J7A)Z1QcmPBhel-KDHipgm;vyo1VpHj;GbU2^c(%oZQpJW4n zEeaVyjPZqRLPc{wF}8lt+tQG6+}T77qcWmZ#((0=u?*|<7l9ztR|nJ& zP{aHF>aRLPHuLivR2^gtWHEpj_=Ny{r^50@SGUY-SGVjx>FTx@kI7FihfQl9T%4R9 zHLt!$7R1q(9%8n(sSys$13X>~;dBRo^{g=u4*m+$CC6S|hMv;*E_~YsAq4dO>I8(tjVHae|TN1>IW+uS08$K$Ecmop1iGpTa#o^ zJ*!s+{~Db@YWIq!)3pjXXr{wl6(D>E5Lp9%64rq1)=N^n9ZGa-P|{5((eKhr4r>sAqB4?9PF9@DEunG=QQKjlDnlS(0A;Q6bg1b&uvMv5A zF>_I_D{U_nfOI=LJ#COsH1+5;fAywrZ{(~yh(oC+U2wStIg zyK?Xv-Q6#?Z_+WUwt%{S<6gS%IhFN+wOYJ zes2wTRkq!z2v@4R_4o9If|$Rk*pu~QPxe;qad4Z8z3U|Z_r+e}&oB0J*l8Ls;q!~V zoW3-TuL6mmU+m@lg+O$$1d?vAC(2r3Q`VAr@n4w4J9^Jbzhy#f*hTXA`e{S9OdGOg z+E}F{)GzuKR?yqUa6he&dd((=eMXqyK#bDT>eohudWvtmqqs&)2ql^XLbUq1;r+xS z-8I&yTqUd~n=P*euBD;t`DHcp=$Cl1m`A^G%y)eurY}LZ`9kc!t(mxilL5sPlW1!e zm!cE~DYK_*i2{FMj#5%c$!v(h0#*=4IWFKtfNv<1$@{N$KR6`iS|&G-TMpos{&QQ1 z$y|2k1DeY=ztkl*e*N(WYUoo)Kg=a_#20D&o=VmL40^owPR;XF&k z8#o4n`?vvxrwDJ;(Lbm+xvvOT4fdX3JZ2nH$KYKf=VoP@vh85{579~h;z9(9zr}U|3Q1)kxr-%pNrV)uR4%iP zCWU{_e60nkKBYu)?^_zL$TURKjOs0bvC`2U3!-Vh*pkJBw_CFLmiO^OL&#CXS0Vl@ zwDW#6?n2nKphQ5Zrc4l-<%?=`rMoRgouqo9{Hpecz(+~-(i!Z`8R}(#bT>Q*jkh!TW9B(Ru0U@sP0@8TC z3@|M9ECR5QeE=4xJOiVv3xXr?l*)kymXI(y$I{-R5leoJM>`Xss~RnN8`CbI`#3J> zS!%YzV`_GUv!r9uJ_}G50 zfTo=ohS<5aX3M7CaV$izOHyFXZyPh~T-ri09Wn zF!(Gm;07gJU}&uux~}sAh4`6Ky^V9Tj|raJ#|Sq?RHkCw)={(KhUtUp{6c^B%ZbiM z#>WU_YpneH7+F+gO#A=FUYGt!O8euQ)^QS7T zH_=jG*n&dOC8u(#H-yMhr1=qhUxwFRE;MEc5y}ank|`0iIJ0~sPKP#~Aq&h;_b~?s zLPronXm|6n-;nWyD{HEHfMkDV-xcj#e>wnQj5n!V0-E7tc;qE05IdZ~rvwkB<9m|r z)Q98V9Q=!td#0=W#QY^`eM5K*uXyg!>dtr+#fJ%4>p|H*uH($e8{Nd|;`tVe0VT)S z2~UbH8@Sh`XgMtAxE#s~#)!~s$afDM$iFh5pyX^!xO#?1fWXNsdf|TtL^+4x90fha z3L0vuZ6yGw|aS)YSi)Jp^x$x8L`cmC@8pE;D6`4fi>dp+FO}`Ewr!kr5P=K-epPBsw#sOmh6luTM7~BuIhM$hKUm%|$~3 zAkf|D$JY($)x~!|yr$(DC3#6odUkPjrr4PxWljXV?aqG5F3&eiX9oV3G8=CE!?CH~ z9sTodHQczTtL~g;?cw}?pBI1q;WcCNw3O zQnM?bms*EUFH@6?ywEI+`2Kvu3C}*%f%3+$cG*=8@UT5+D!ZwhYuCEnPu#XmpsN}@ z|M0;m0`qYT1F3Bs`%!{z-`AJ>Pbum*j1)On#o31PT#E8u5ot|-0~b}ZOHIdU&L}%w z82R}|2$8+qx5zK&0(h%?eByR*zju#zBe1u>X}e*299;9i&rvxtf+FO=PO>OCMsb6WW3z3lnXzdo^NDPD%`4)DL0bfFd$(= zp^q1?@ec`7%3R@GH0MD?|MH`XXcW(dECWZs5<>hK5{&_BwF+Zsip-79%K{XW=S*=o z?w15fAQx6LP-I-yJC3)B1z}rZd;NkhNOCI}a1VRPbE3U}4BsSHEb@XBv;FY4AjO%4 zQD9A0&$(2VIx6Q>>A5)wn3W0Gj7S#Cy?B}SYdJ4KV;Km*GyXiOhy}@cDW?sQgev$; zQ!>~v1*3tajR3(*?+{)k)shy{i9wxe2x?{sb4hqZuzIOedZ|v*%i^2pr8-S7>DSXs z?etRJua|0nwjocamujw;OOI9-Ch6 z)pbyHP-&r^?Z!_2!Uh+mFgB#vfxsZhs1gr^ga<4^<^nuRG|&b+SbGRW1gNp;>z!|! zg)xkXT4zmlFc8t_-#RpePw&rVkyTw?UG9xvq1tzUrrP;WZadSP2ID1$QdQs@w!_1X zg#5vS#F6`y*zRNwTT-eyzHlNZY)#}GB&tTESaUwbiO#1`?2gD`?I94cGyT>yyUNKU z2p&4_2%bcOpJw2|#%D0G7ohSp z!HqzF)Z&}!3TO+k$xNupqo3Y&ZQBEGcW-tcZT&4RbjlTg;Bsyp|47QdT*SY}BA|80 zul~;+|3WejkXXrxCH3>&lSrNpc;R(&+YsKKfLe4aIxMlKh6a|GO7wja1q&C-!a|Dcy8%i`2jwzbaatfH76*<$vCwS%Bw)?%=4vW;x`L){Raj_o) zZzyALXg{j_=T+xF55D#q{HWQv&h|KXmvs?VnWmkmg2CAVIZYBPGno^C=^ZdHcwnA? zt0a!nY!O=$J_Vv087l_AOKvrK)BD5a9MasURs5l7xB|tOS?&^wzr_%wle!9nl{yXA zOnRkay~3H(E+6awfsg>L((921{9h@YPhd~(-Agd=dAj-cly`^hNOSMqAB*bQTDIw> zcAHobA!GR%RA0=fT56m{^^@N|$&sypMH6}wSvp15d^G?bd`6bn$~S49C>GG~QGskt zAS_bc#BLQi*bSMjw+O(1GsiOE1F-3ik+S=(DV^&ONM@#r9PT6|sayvICIaxbj*^ks zeZpI41^3yRtJXSYc&!@uYd%(6Kl0DjvG429v2B}OJ=ASe?Oj8AIUu^FnXN>Bq93Ov zI6r{5pZrw&`cOC3-~t77x&VSSIQ(t8ak5a|41qiX!V8GaB*{M9)O+I|J2Qk>gs*Lb zh#j9?MOTt#n&p~y?jgzt^q3D|$4DXO13iW&T4b-x7DQqe^WS!@ExqoJ+aX22FKu7f z4Nxy61i~Si^p@5~%=K>OXq?)AfmV$ehopz&C`n$V!;;ge zlLGL)-f+3#BK$&1M`XMrI647o_nUP1U77S@F6i^~jiemU7Q8cnou#FJ(?RbKt6gNe z0HHvs$ISAoYY&UW((jae3EO3nn+J7=8XQA&?b3e0q$OXRD!e`iUBMNE@@8)z(8@lb zVYQpss$DOx`YDZ%vD`H}+@DtRPg#yp?8OQoqQwXdu2T92@|B~;ze|`P?2~faRLtyFy^V*Q)Q$0f)gx?Oc;n8T@9fU@)q3W`SwCgaMm9DiS;&st){N+UO}Gxtvbu zZdVx9kIT?b12(JWNE*lJ=jqiD-;$Hg64V2k0=4IA|@cy8pOU=VYGa ztRGg2;;XTzX6&&qVejFrai$AcnJidlsx9uc-`e)ddwvGsS}e+l0F|b(Iw}pr3q)V* z5Go5zu*GYVTA)3D=(%!cth0LXW8VQ}8v_N-X6-viucNcSG_LWs>V|rI+*h3?Jroga zPwi(Moq?OCYVJW%F8+Mz>R~XAuPgK`$Qr>C11CVr&+sH{)suW#T;N|C7nT~b2sMw$ z#>-g(b0=d}3|Wc>{-!*!I?WT`al|Y6B7Gv~LZ8;TJW)x1>Tz*_-^W|JxK-wo@XxPp zJpp~o)JZ7*HFf86vwbTQ?!{>sJGN}UHl(znlP%hPgNc2Z6oUub%;WSgv@ZbUAzmJj$x zDi)PdX`+mOI={c*@?x2VU!PEm%zUhSSKPGC_Y^l|_NsE3He%R*Gjztc2kcw_r$V&t zS8Ch>7HVU|-c=a4IL;;E5&`+)+4)8>6)2itUR?s{@ph>uBk=F)%i~~+syY-jA-(T! zst#9iBagRx;PHFBWJ+A(p)i?XwuI1Q={KsNx^}#O-Wrdq{R;i@0Q@=@@cq(PAMm+t zJZ&LS^(*>>E^y-uTIRi#WcO)s*JrsbGqdlFduki^>vIj@=y-c;?_a>wuEkce@OOC@ ziJ#lENXe)_i^K_FmAzT)D|T$FuxRBnlosc6)Xi5KiP@QJ(->SYUG27v^;Q|MGVarS z=0${m50QMSO$iwfC2?Qb_eJ&D)gSEfI;x$HhO=5%!{@-TXJ>v)5Do@{w#PG}w$E-e z`<1KVW^-(iiIghBDp*qIR>HQRUdHCcN`6P>vCY*bdpEp4USETdiTVzhOd)L|z z-Elh{$9MSND(q0>1@gvyQ8oPsCv&%q$Qtv1aRAE_Ot`EUKTRj4Rd-nrUDbV>>Zbm2 z<+fAFb4~BBWNLhhZ;*5DlXxdxZmZ^v*^X!Dm}C1>^s7ZBcXT@{8xQ2s_oT|BWnt^e ze&vf~m6hdu^u?hVT!DzIy}c;KQFvx&cE5LDgPZ_CaRFfzeK5zQoVttGWjLo2up^Xz z$?Rn$OK@dBd0E2a8*9CwEY5nN<$YcGuEEreEr{81m&jb7qMX=L0GB+zl?EFeT_j&x zH_#N!K}2;EXs&n0xsCc)LWLD93qpr(?`^cF7r*XZ&k&Y%rePoLp2dChA|5pO^QCsO z-m2TVkI>G-^6fNFLRI(e__a3z7%otMmktL@ir{1TK-*M&D&k|`9s-r|&q2?H)$=~3 zO^g+JDT~Kxy1-JVcSZtKsTz*(X3ZDh!7Q<69jLYXCqhL@;HgAYAKc*BMqGWGOF(mr z`gHFU2DmMXtiP=qcaDf}pwRfBrn3-ibuko=12ru1V+cai$WMN*wDmJZ^M}rVF~Bk= z$X++QSi2@zpv?G0FStYw zsEIN6^m8&ZBmlIc~J_)_?6(YrYpVg(g`8n1|b1|saoEWo5M)1rp>_eW(Au8WGk6S^mIC>5lrW7Q6diiWi>zT<9JJzT8PnFhhfI^LSHrBPod7=K8?!B zsZ<1`-&C1GW~>`w;WY-6U_W!<4#Gl>$}m5csm&ZZkyHfv*3)`lmKNDsiYTnB+`?ECJ=i|_smY;1=vld+f+0W+6@ z-T@T?Ff)?@7buZX1b^H%628x`=%WTm)8d;9ki&Yj#%|z449_9EaSobpc}9j>>PYH1 zv%h|;Sk$YBJsx{)1V(I%k7BXvW7Sve@J$YX_=a=GtoIw8bLOPq><(AIUvZW@%?(Xi zv}rJ|j2$ojbDz{Log-HH;72L($z;O;OYE@29eRxOOUIpof&R9{1NgtM2Y=`0pC@8_GQi z+SL`T>7(!tW`D&6sMc>cKY?MuEX-?7hdoqHbqKpzp6%MEDR(5xipB9@tUne_Q#E(= zMTdkrq#&)Pt-r&As;p@C)Ls682aB^rcGng79oO7;MYF^2dm3#|LtpL7ag$<*o6nkv zELy4rNdug8c_>4N0x8#9sbzK>w~|_s%Gi1APIM6bfPc+MTs6>KC(+hAS7d9PQ@6o) zyP~fCTMSj(P&Wu{5hpx5P)9!mh2mf_Ow&k#Xe#WRos3`mlE6_m`?$Jo>W8rvwFgh$ zSAEKb_Y)2r;Xq2%r915gz%j!mFJ4KwV>$D==LmU_AO#a9O8BvSmvhxrbT*ZXjMFN( zCyQ0aGk>LFZCLXz*ZFiAq|QelK|fDz>2fA>KCWgd`HpF$#u+z+*K;vKFq2P{CIwLE z5hP)i&@0InR@q53O#!r6=4~EkXyz403}&3CS#MH;plOxdET+B7g#ZKOdK9}plTb{~ zMyq@kUZ7-0~x0pT0tn)ezb0t}ONs@gs@?V`1>I@vh_09IoNx34q94u-v#$Aw+!I z6o1eZ5g~4NI&S~r)DPpKqk0gC@Wx>?Bn0@kqhQm9aP$#ldx+xu2m`4Z2j~SDsA$k* zG2A1tl+E6EEe0bM(-3y8a}N#$u#njyv?h_EA>VTSOl0_HA;XWz*eYkIB#RnqQmemj z!098EH;*w0M)Z%fXthZIOOL|oZ&VSUIPtUw1An%*i^@I(Js6hZ!Lax$GDgI2b zJY^jS<098f^TZIpRVHV~*tMhk>TtxwAl!%{$0rOyU%=2jmM6iqr=bWMY!YZtR#Df~ zHPZ{q}DG!>Ar#k8TF4pMcb+O9nu#&gcBfd~n7t@GUm03w<4XMgs) zAxH@WDR-IiuxA{hdjpL~->5m1O+QUVGq0x>U0sDdh@(xp{o`62Fm+Yj)^Q4&n_9b~ zk9~n6tpp9|qK|m8b}fUVsbOB4^^xi}x)$g|kN0`llBKp_qOu>_F6IK-RT7hEsabTl z)zB4zmB5^lpdfuHhd$jWYR~Bw3yP+`;9nj&+%G zJPOO1_IghFVfTq15$wc@gjj5js5_>_!tHc^$x~8t0K95SeSapvYnYJw3j$mqK;am{ z259D#c~e))Lbh~M)O~X)V9k8uj5*4QIWBe|?pGWk&a2{RHN=jY%b|XkGk>L!P*XYg z6@p(PH6#chls({2Bi9__CU9?vTFTf9WK{!CQcD!PeoW(4ZbGaH|Dv6+u^^S^Q>>O- z3x%mUqqWwqX|2yEq`kh@ka&~chx2K}XYX$%lx>k-LhF~5Y?U+4r&Hbr;aIV11f3F7 z(SbdI7lt8>JJ_f%D1reQEPwtbE?%n#Xw8*f`gp10SdxN^JtVs`R64d9R<9P7v`qjuq4UNR#>% zh3iJXRZI_U^J^k}0B=1VrsoS>NGuH47}OhbJH2CK*PaOb4#-CZU%$M9{wBG}L?6Bwv@5%L^dV*f~LU541r>K?R42F;wT}AITUX*vc+2QFf=D%zq07!`T2RfDOO_NVbdJLpdDz|d;imHMF#FiSo%8VIoNTYnh$mf%~r&E5FWAVtW-%ZEiU zc+%%UOXRnCErj@^vX>8ZXU>Xqygf-fIlU|e|BpAjM+$vM+u~0bHk+!pv#K7erzBr= z9vF-Gj54mS#TNZunyi%$AyIX$+m`5pks zvG76-F@IZ%730H@`wYhCm=J$4<9n8+R(mP10Bki+dW!S$XK_CNl{ugID>$G1#+>i$ zb}TvHH@_S%{Hn3I96yjTlFDQHHvVaKEzBNKI@Oe^Gj<%5QpnX^QVk3KCjT9RdZp`p3=UmwAmp zF*<|4ukQ|5zy6kQ_R#+mTonn)?PHjA*x*%?aP)ff_Ug^qYK#^Zf+-9?ApvSGg-QRS z1Od?XUnaprZTwjW82|Tz)o)7>X#iD9grYAv&yVK%A0=q`+>^1G6SHcOaR-w@h$*uK zndbq23xoiTo1&1Y7Z_JIsT7JN%TstnA!L#KUeRV3fv;s$oVK7&`Du9K%N zK6L<3#==F~d^`3RXF#-Z*m_gsoux%n5bvLd6TV;8#D~mc1XL6O2tlp2r!|K;gj2ZX zOnW`y^Wf&}#{Q1j`Py|1a>i`>URkD;Y-1Gwl&Jr<#e=S-33erum76}AmFb_Bh z;rQ$E-`EORS6O|>w}51sHdPi-inPfkI8j>G>_Z>6q^r_gZh;5i7W> zfLg%p2B6D~=S*Y$n(m1mYb!r-3N&uO!XRtNHW*XS+76!fm_-A;vk-p)*l@5RxE<*` zj0}L+>phy%bbldj!*os~u>#6OgQFSGmW6^jgo1)++L=2JN2dpplJ=bTSrs25cehn( z!mCNBUYPU_H%m$2-Wn`0gT-V|NSY#lW<;u_3Bx;Qbo)xz{I%~v@Gn7ZJfzPs4u_kV z7A%UH055Q@v&`g(Tc*W#J!FlJd7bbfNA$qf9{yQEITuiYf*X*D7UDXBSj;+7=E2q# z+WL%XA&@q7f}Vn?!SivUktJdHX>^1|9*|;$){uV~lRmSjA|gjGgp{1EfL`}}3_e1A3g^IkZ>1Ch)L6k++V=Xh?R7_+#nZz>Q@P3N+q;AOW!Zo)P|Cq< z!(9ZT&GB&7lwZNUw42y1@~ooh0&wtDk?_v;bL!Qxt3WttImFdwgK(w>1`R_6EUXMI zUY^H}mkYm9AwWGX7HJ)~RAfVc*$ao{UATtUjTW(If@RPEAA%wQO`EIaw^@*0Pw*7X z$@+hlGc*xf*~L?ljTtDU_?BS&(j)CORbX&{)<$BGto!>^q(T8fctk8LE@q$x5Yl#_j)m`*g)rsDw(&ufbBF%`d28 zXy6cfS~L&=z|P=lr|C0L9=;2aa6dc(uNUqH+u4y|O^yVMTLLBSv+2-}R7L4_gV-Xr zLuJCQ*HJ?RHD4^XRa*6g3AdEY2{IVH7&rt_v_i=0dBm z84tqJ8hAPb6b<2N`gq8EU8FX5b%=j);}LFmA?o^IlqOD*$eF)?qzd3a#U_>r)C=ju zC?(cO4Am@o%DH)hQrz@lw9Taw!B?^vMeaYk@>>^$81FPW96ppkgjO)X7em@syUC?d zmSOw|qJ49oD06U@f>phYls5$7yim=y2bee0W&>L1X*CZwo1G;Dcu~(Nlm)BRgi24r z&Z@|ms#@3&Hc{<=RqsU68g6z`PAHkNTyv8kVFFX4Sa%6L{O2WfjVIK8vZ0~O;XUW< z0;eT?z^KUd#nYB|xT%7;0E_hrNp7c=eAV&b)-t_CrGniNP5nx1CLa4BmW3RQ>>=+4 zqh-zcBU2U61Zpu8lxZ!oYf7uCBE;*)a-0>OI!sf@2s=^fIl0#Q!_8 zLDI>J<;Vtq9vE}RT)rTiVCZt^F-MN4BaEA``R9hTEE*6EqE&Dv6Zq>7KJT1_k%)Hg zl>;wN7QaHQ=9V`xGX{Dbbdu@aEVvYwMRMlT6(+)V*{Y~m*XF*ZUo&8V6*HI{n{J$c zfir%7g}xs-=~Cn4VuKZb7v$T6F>U&PGca^WMGF1Q?g0LPk4cZ1#YXCH zhY5)~ld+f-vkam41_3ma0T(EfET|3^qHz+ST~6Y4)`?T8r0m_Q*s=Y*u|SdlRWJDbIi%hy|XxssMIYq#mvZbJ`k?cC+humADs*V@i7 zaK;xRGqCT!zalW9$6za-<#MqafxQmc;Pk98%tPs{P{PC7f}p-7s43N)XWA@AP&d`P zOJSF;AzI4={kr$%x~1hctd4c{YuSHR$ME)e9XN~pzU^FnN6UR#-&BWk7g!PF(}mKR z0PYx_eM(WNGX=B-h@Y5dDMTt0z-<6}pAbi$38^0!hshLIV{yQNJiAi@!$Ar90 z#zD+*s4-^Bft{KT2m2E;Gc0hxQ=0mcGzHW_1RKA2K(C_66ie!rO=MVPHlHbWq!c;P zttfgs?-B}8z*i6OhXe+jsoX|@s{}b{K5}FmJZWMhGDPAOo#jI)c$t6Hb*|+TEHMB7 zwLmekz@L~j2|?tU75T&nKc3b;*o^1g1gi!aiXw#KO*$0k#wJ3sJ{yX^PpB2b7=_}Z zupd#cYNFODP2h*h!dEi77bJfn#F;#n`-#``o#CHq*Ot}6*O2g3wgi8mLpEuSl^km!$qeY;_A1CiNn=nZ zVp`Jp@<-$rXy2c@wv5z^ya3EdggdyO7*{RrVeNw8?Y0a%Z@Yg>C?qdeP!7Z5jyBiF zrX@gN1(4j*Ljz)S4T0QNEx>Q-p^ap`Y8{B9rroByYU_yIrL0$4mf3;Rb0sr>Ldnd) zPsF%LtV^J(?%6#Amd|&Ocv*`Bp=DLO=86nEu>a^>cRpU-2ND@5( zKe+P#1LlT6Z|Iw*`Zb_)hxM_e@4?+SBylcv#vn|3iHCSs9hz!`4y9ReO;rrGgS*~# zT+(PbR1;>18IKsvvua{cw<;8R)q!Xt;((smJHfIy=?#A@x^-x{;01Y&r#?6euE9~Z zGh{dJxOZ*D2Yp(COHqi-7UqdY@hmPs!E-T6wJ~5*{+Rd#k*%Z%)*^XSG;CpOIe8Tv z2e-~?4Z>cLs~JDDZap(x4PkF(WU>5adX$Ko@C5a4In9Xzl49|2M+ddwkijr2BI;&e z5*yfJZ^D1x34$tY-_hfcKR_58kfhRP+zC#3wlcFrJMtTJ2u&A<+I0j5G?VgjmgTvb z1vK=*yHm9$!hPPtINo``-O`Td)`b)oBji06WbQ{A&rlnAy@1ZoH}~^wrE&prr#jH; zRF~jEJ{{vDq~OMZh7aoi=~a`9kg#y&6B3O>>Ro?%I#q`odVz*fxd6W|!vVGH8W(Yd zMN{rwJa2!hUDNczD$fcz6K2!a;N@NIb3OyPb*GaLg2%eWfFUtp_@Mw(%L?!vk+@-C z1E2T^0dGqm9PeloLco@y>4r9lM}({0%I&H>)ER9=LBRtS^aFNWLqc%t z;2pRLydNL~&`=GYZ?`d4hOhT10pleAPrb$vHcHKqUNK1JIuk zgtw?Qa!|7LtGYZ4maoXU@dfyHbcQWxbKM2C4MFV7lV`3Se`Mq}KpIpZ66_AW2I!UW z6f0y6EJ9{mzH(TGmbI_M)bd~59%Qtpnocdh@#Y0_=-nj*DYu8X1HbKOV1`O9zdGX6 zyGt-^RI7I){OUWvIeZjRV}vKs38+69W@v~@GV~G04sFrsyFO% zh_+=z`$17YdBdYOjsai3Y>)J!tgouJE=fgtWQGW{t&iQ!Hf2(Mfub0jL;>3I<7BJ` zFe`AgECV1_P>!Cw`D4kw_eF6~ExrLN8mc7-8OF#4e-x_?*sXVtTYSaQRJ+}Vz}CTQ zf+JJd1emLsr|`HpO^Tbrsx9iG#XwBM@Eps)J+0c{!MGmH%kyP(*R*c`=gU>*}hD!)Z-n#0Hgk+^1c+4hL<5$-%NZjKV@Rxj8EysgXpikD*46 zsD+0Ue->@NqNnGp=-#kyj=LdPn-Hu`NEb6qkUQRXC4}di%=H)!qw#yP-Gc-wY@Z&# zOVj`s0OSW0_ZXzX)xT_-ZttQ5Tp)8uTGTyio)wl);(u?jp?f8Z7-cVtV8Ojmh#_4C zY2Y{E+jtWp)ks>f|2K%)O% zfBcy(Ht-T6OQvMLxb>iWl)pwcc8gaR-(I}9f4|t{QaN7Pji<&_4sa@r61HKO_a;4i zrQ@C-DW-VtMT%!x#eBeML6#G%U`aEiWu$(S>~(O+`sj)GsDG1~XQQYT&e55g&gy5Q zV*~XJY*^E~u#hS0flXznCiZ!{aTE|of7N96nI~qS0uUB@)Jpq1mK;hV!KcX!;X;D0{$pUr zHDUq98-nzINhqMLf->+uL7ow<6c!xJJn2soxt{2Z+B(k&4#Vl+60uo??MNFHM2cm( znhk>ca$1iXD9d`fh2`fgtx&L(e@`4^QJDYcL$me2q0i3J(Rl{(n`Q4eQQ-H4)@xMU7eESQSP3k%siXg#ye|?i4 zudxDe(*|^X>oyY76^gbW&Kp7n9uJ-_gq_s=YmoLHJ(Am?c0WCWmi2af^o_Z7f1M(xCVpSnG$S%gyjSymKJ5F3kDK6?+)k!Y;oC^g^tK_{ z#ri)vLD60H*A8e1jUUV@6=EB<9%Q66why;`_giOw*%ui1gAsw3w9?NqG_#MUn&JbJ z+skBf!+1Z5;x-kcxgZw_V}u@jnb~ z)7_KN_!E=pv=@^>h$)jOwL5>29F2y<-+aiTw76s(l_N~a}D z70hf`|4goTRd=-(d6C>U?G;ZBS3)PJz3Ho_#(AA=n#1wbTTf-bnN7ccprw9iX?D}> zPlvh-v!-v|~n&)meYc5%)O4?0ts@iUWuq=}seEor*JG-}=zN+tV80114)4A=#<5wgH zqNeo|rt7>MmFWZ1`>Njs9!(dx%mv0xNtwKBo32}L8dT`lt1O2tRHoj{-qHAurcFAL zamw~Mckkq}wcBjE*d~9jIRaoJr5gF)>@Cj71UPcw)Zy!|-U~6qfnbF$fvIEmfk@_1 zDVZpWKw;`_jE&$-a1n@piLrr4Ewh17>xFA>!az@!$Czp$c11TAK3jI{UT?2 z6zXl14Ucfi8~uXTF&el@Kx2 z!3J`@5|U}14Vueh-_$JA7=I>8eiJ=2Ef`M+pY$osQYqm#_co{smZt$CiioOud)fqS zjt1Www0b*O3|r=3%60j&>`bva}E?b=-R6|XSoI)XcrouLN8}3l`F}(P~R!ZUn8QdQ_ zEKf1T)#agDJQ1o3#bl;uky^zf^(2_y?<{1xF4h)^p<| z?F@f|seaDd-N~lv88Eq16)ArXzv%t)^1Jdq@u*qn^JtLq$QBe6N=~=%gu}{b4r?jC zg8CFBo3MHvPvIogX=(a0jD5-1~Fp#x8}9{}7hGocx73gS^FQ28xUEiKIP(oT? z_HuL?dcK`&WThk@O4N0vI>q&`mA$9(v8k?jQsasBxRgS@-1ipyM@V-=CFaJQI_rOz zo35ud?1xp>6K)$?t{cBvj!(|+&YvUO)4?}TCB35CzHvF{{{5=CsQ zZ}j}g$(5Q(b=k?~xtJcE(>E}tV=2?gvA}HCL%AJKY$2CXgVXvJktt_Fs^>-0E)-0t zpdQM(NPZ_wfke(GL73KlIaO^C&CP$ps_~Ng_Q0n4lyWu5Z#@r(e3)437|^hBZ8tg= z0R^3!^&b{i_0q$<-iF$a>`z8oDmb|@b?BJ6J|PW`ZF4ktV<)5Ewaw{nH!~19H4v5D z8tik1Zi!ppf-;;ZD5P%=#ZcvpL>6h{OyhI_6mPIEBQK?lmblp_lf#Bo2(D)lQ6D-9n&PXMH189QQ-gvWD68xf`D@jg&lqAq- z{WcF(kIhb*Q5(_qI9fztP#bPAR-}Pp#U}7s4rsHZ4tI{^&2eN=P6@?jnJJ3Kg&(icNf;)Mw(Db;mqRsw;*7}IPB8L#)7RZk z3C(n_7G4UnOHIjUcRCzE{y(fwQTts;VLP8DVcxm*#F%=xoL45l(vHh?Ovfj3!NY@p z2h!SDf3d{N*1?$LkyA3B4IOF9i^?I1bLrWv2q;JYiGbKsy7`h$Knek%ma~L8dWK4S z7!1byK(j|*^lm7B@Zr=A68PnSMF&I}&w!{30wT^M5K&2V$S@NFBfe03#^kY!$xe~Y zmlG7Q>#-1z)X)o8I&W?XC7#P})PE_vk)xuXNk2W5VFOS^O9k~Gc8ju<8f=mZIrp6$ zRLDh^yn~2{<*>i-*IDwBq8C2?u)l*sq~9H4qGO_o4LLD?Ek1Y-_Fi>9J%mv(QWs@m zJhV&D1qnnyfnIVADbYO<{nlHMr=`LC_84E|rLW3(a47Hq_SV!}szG=@-WU(rgA)z2 zhjsLyHYV)|ynm*~#sO7}x*7FN5n57O=1yt+caOEpq-(myxzRv7R zVFZY+s14vCjxD5a6@8$klf}j*1(I^yf8S^JMCp#C#1o|!2vER2?(NRb&d$!uvvUg8 zDXW6B%K3m_uR@Y{Qfw1`ql(1%O)6!KxvWx={-R19XH`HGTu_DcC^)B_MTZ9yXQNfV z6mYhfe`xX;JtE*G2}5T%aF&cT%>_n zCCCtF6_L_sg(cAwAb?E{@+t4Ir%)S=hL=Wx!~qh8jK#?-PbI5XM%grBA6fVjdM#!I z7FLY6%A$aVg)V@Gqs$ZaE1<#lS@bC?Vge62I%bhHvx;@C3?r%9%}GUH#dT;veE~v7UlKTD zf2eLUVO9{Wq#&jRJ~;WvUK*f@5qvNyiN0b+LpBkmM-B;Q6|=7@LL-Jz0DUZ0L@p{> z*-ddOIS~-XkvuFKDotLrT?maL4OU516!4N{BT%PGBuc?yBudZ)c9z(SJ}nw`=NO7M zqX&Fa5yhfWqzC?yVX=xZA$zPt*ia^ze;dJIGh-(NJI%@R=;h0iIr{fyqs-g!r)Fec z&!)>}x?G5j!580+%)4eWyPBUii|PQi>&ND7GJZAts*a^2Vppm7lMz_VF&A{DrTcC= zoq^SH^+5Dg2bABF(YN2$rQgnHXIH1qTs^xyJ3neZyl|SV_Wn5}nK$F*3?t}Xf4xp- z(}VG{QO^$k44;Y?p}=O?S$tvX8*9G--H)@gT_i{I@#ST6rp)2^^8$N*d-VMWeR%cx z^T+XYDzY41Oco0NTABW&ere_lEUkieFxuiHhZkPQm9Xkpkx{*wd}+kh-LKEpZ})dqq$DUx&w~Vk&)fw0l5MBv#3|C4T-WP(7CwPU&f9rx+Bc04e z!_moWRtyJ^)}lAsI>9rZM64rXmBTYet0fRh+u0I?C>ELEguykNBrG@;U1T-H5Dh=N zRmV!kkvW*0pEvL>@x$X7&8w5X;_jd<$&AfMb85~^W6tI5%zW5PS;M?uqpc3zIiEL^ z>2J{OY<||vYb z@})BGmHEr;Xr|18dUihfbTx1E>G)FI9?qj6%F{@LRSOQ#m8hMhc^n=gQ+PSb!b7B? zt~3YgI8@~FPMHsX{|9!37@c&6rA-l4PVS`h$VX8lU+f~|k~A{kfBkeG)`#rpBWX!> z_tS=q0{}jPeM^GBpV$`=XH~L}=`&eAy4T}q5PdFuT{K;VycDoBkfAvZJFfc0J0i&4rhf%Z# zc&W%~JC1^d?v0~}A1(@&jwH+-LGFN-i8ch`4MEbw1<75N_#|U}nzYvSu;)Y8K6xW;%@1L!fASG9c=aZmpC!B5SEp z_?mg70DwGL+z{x;>(DRIu=L-flWIWJDe+D^@_BpGU!%j#PFuU1pHE(gZHc){SD|p0 zY80#vneTpL5Rufo8~`HwL20~`QPk6Df2rJ+t=YbZ1A5s$VfSS-^=~3f zScJEa%J(sDBq(;hNKn#xC{KGN{NQ?$bf8D3{h>$N zBj2;_=KD@|%e;TSPkZG1lJ8W>BOp*JdmK*aNFpycf~5Tues;GBpIwmJ5#%S1I$yVv z_U#vqf1A;ogW5jwny%k7=5QUqrEJH^dMU7LsZAH1Dw2RhNqO4pTF}TmGmujOP096X>sns8vXkN4> z6)U=mQuvn&5Ol;+RAiBaqG*be@Cx-jxgfHx0m}*<{|Dtuu&i57V(BR)L8!p0-upon zf6Wlgcs`%~KA(KLSPm?0X7f=Zh`Aa@&-NC!4x162IlY)DS;(9|WU035Djy%OtFF$> z+S;q+BeQ&}s%nPSNBQ7Lx_;V(oo1jVFICo@hk)6*4rU_{1G7Ck54RHVnRe2#i<)RB znS*W1SGApV1QRcLH=Q8U9EKH`x?r@2e?NQ3v-w1+yyLd&c#k+B=*wqz(!iKIXyGVU z97GEKeiw1JmB?iTv$SJts|u|{u$Q~hFk&y?8{%#;aBEc=`G5x*aPKm7_tolde*^B{ znTmYp-*$oO`9`cCbsl5OfHdp2Om^Q2DcS!{g*5HHF{MA=jR}dWhsyH}7?wX8*an8_ z`kU!37^blPU6ovX?&%7X^2KuBdkXn|zP)#A z#@TlS+5gWG$lqLM{{u(VW;P0ClhgPSll9IQk{2m|wOCuPMg`6p_HnUZKKs9*AnJNXS!I{o-d?!eaV{cDa@PBfq>5Qd+ zQyTZq8ncRAN|qNzMECM)2FQe)I;IPH{ zt`BJTw(4p>cxt*wd~>ec6Jcx+aesLYK_~JAZdH$NSOOvIXp=wD7k{~63L;XlT$8%{ zHGlBOECJ1B*)5mg=n};pmjI$nHQ&sZRUJV#ZFBOBXcl%dwu|QdZL71S0=@*@$(UVF zB-X6*11~bh3-KkS6ILu4eJ9I|38}#b1^6k<;sbD+M6WL_prv z^ojZ8EHLmFki6oaTYu}`n=6cQe~7RsY`_g<`#XGTaH(hd>mWy z?ZpWJuS8ezVLkfF7RmzzU9GWz?gTGmVi|;osxh23AIUCT7c)|Or&CAjO9LP48gLJ z6#nG~(aw_iA6Ef`(fH&Z-+|Q%Ff72&vQ^wlg0aQgX{`aAt@`iQKmgi7Z*X4M)cD@wJR1v~p&SB|V zlGOnurhiP81iJ&Z_?Uw&-f^iuJ~dcS;R@Ko;iy02Kkk!Lu@gq8%0clky!{Hrgu_{` zomt`adoNR|w~Qxhs@S|n6w`~;8hmESDD10CsiBxunV`fE)psdKNDk)bLMPus`PrIJ zjq?S@Ggc6PZH9UrhC3Amh}B}|HlpOAkVQ#Ac7M+}=g-dnKay&mB5mhS+t0>+&yO97 z5g`eK?jbqEg;Xd6Nv1y;7oURL`L9+)aeoSVDBMqeut$dWaxK31N9_M+0f~zE<*_8( z%}*fu6s1t15GRDH-=zz&;SX43R6oLssjCHRql3WY(EM(2D)^a*z5^3SA6g-K!vmCJ z&VPh{l_x(;HPRIaCI@!vtP^h*)X~OdPvdg-6kWLe|1r z`WCMIEN_*wfQ~noVsQsVw==#o-}{zp7n=$NC9k-uPi%$h%)^Dnn4y|Dq73R)^GiUr zhSJwWUVff#5DUCPT;#@y*E}ecQPG;~ua=4Q(SUfbe@*~G*>So|`u})BQPNdJFp4aS z7qt|uXh5O5TM{4dCHVB(TW;Nk46-H`Y2nQXKY zJf;B&7W;M3F1=!r*sb5}h+VYwO&XO+q|^1=IlQ2tTS)3H@xmft&6qCqvYB;Qm3t?M zw|bC2DIUkRiWj=EH6@nrMU_crO_us|eLSUHne*H&sh zXX&M`_{>H6-CI)_=IZ6GDeQkya)xldSP@jLh-~2x@VM#^UicyehPP-q=yc17Qzg)xfB_&L(EWrc;8X8@&>Barx%BVeeE0C?KZ+Uw zsgu$86O$|07Xdbt0T(EfYuH8tPOFo%*gby&ZE;k^l|pUtO{hV4rdip)c4ZRSU6{h> zce_v*f$jD?_&M!V(85T88KCqYo9uz*M(mSs>h|1N93J{d7Kj7W9Q&ajPpxC2zVjc- zSFUb%x(ueqj9%#*)1AyXnvPY#(mO{rlyfSk%H7O{AS`?iJ z`=Rb9$F&C>tsmawgwe)XRF&D<*f@XC-;8zmg_enEn#c<-=~%@$3z%4u=-~CPOhKhc zn>~(j;+kwRewQUUc0ou(Z5_+?15F)T7)}}&s?x#9sAobkAcukU064^sGBEO0eLN9b zMSQ6JOh$lp&&9za^xGas{D6NfEnh&E@v@I*I)Yr1mcjjC?V)dB+DQgV&SQVw*1zIB zlN9FC?L}2Ct@Es4*jdKc2Ys$)~i>G~fx2=3?f4 z$3U8_m{*{-dF0YwmYZd8=xam6Vf!x=xESlaIRCQob2JtDnz}o3^?ULe6PVIr$<;}W^v;D_X2ae) zzXI%j?|2SVcd&!>vx@_GZmi}{Z~y-7n?Ivq;b%|;Z(iO0^&J-RK!SfBn6(3g=5Zdp znokk-9$?)yK%(1^-0+LHLc!IGS`B>6zFKFAl%<#E8aK~Ud3fQq8>%POKrfCw~BJxlH9Tbc7|>-0N=q3_`B%OMd~fTpLCW7E_f zi`c~u6~Wy^QT9DSklbAi;5*qtc7db|FFkJ`psAOzP~T0X^<#{(X<$p)HZ-(AWr1~W z8BgRMQEav`9h!|T1cZ>`;k>fp!SA?nnD*l|5Z%D~!t!a3!Nq_3C;x$Ir6e|1K}ddr zPtfdO@N08C4)$np$7$Rw_zPNv!lllZ;WAZal$CQ_{rShAw}L7N71fm9CLK=D0vBkTkB z9gx+z8vQLwAXR@FxM#5j>T=*C&A{b@1?yQ+-`{hiL?>>nMWIJ^D63fSx)r_w#t6PQ zlXG%1(%FxbJrZ@zEz77>DJyyVVF$t94j*d!Al6>*Odcf_Pzm5hfKY!dm-FkM1t;KC71!J>aeZY`fl)77r!X44GT93DkI z__cGxSFCbFKkxpmW{sBRr1d0cl8RS|qM4~dPvSPhUpGEva zw=T*+^FHo@SvlTB3QYwDR}B8xLa@NizJ2%Yn-^SuIMuVyLJ{Yig@9rsLl|0-M~c8G zehj+JAl-kh&{$w9-*AhwBJ<84i~Y!Oht4um(H3S1V2IY=2^tN$;jkQ~=*0U0+|Q1i zI4s*E8U*VU88@~>rRn0LFmHv{+gtI+%?T=4#0(b=X4lAi*?gKU$%PJ%5Eb5y7I@*n zm7|5CY3g4MTMpa6qc>)6X*DTvTGj!ir#W0a5wm~!B8kfCip|T_Y^+0$PLJ$2?g1d4&+Ej3mUw|vFu=hTw)G~ zO(%bI_RIw9WSOiK%fL|c29xx3p4kc>${di;%gC!aZA5OGAs%}o5)^cgGcoblB7xqG zd=hCg&|>%p?^Pc;3Z%h|oz8Q6`JA^hgiF7@8{|ty&d}NB8;KfLq%WIDr#yMWCT7ps z#CHpe;UF3o-M2LH5##S8k6d3HVW4XvZXbVD;SPML_aj~nvFZ&obN$?N{m^qWF{HT8 zE5IyAl07Z_4B@+`1}z&LbB^@r8FGp|Ffm7$cb!)LLnxP@$P(gE=!#pQ?1EdM#5gcF zeJ@pV82BZ!T2Ac{o5W8cfOZGxhX-cVJbtrAf|7)%aa`n$slJ}I(m0p(y}^WEtD34`nD=sDZwr4(_wzLb6vir1$zlU>4u zqyqktX^z1~qzfR)x{9=tL?Q%i$xDBJ2lhvwz^TX|ncKg-gwTs31#G)aKBY@ZyppP- zLg!bMMr}lP1%O$--pRhX>=?g`L$|Bc<-^{terF#33k^x7qU2|mkYUar0%#nXLj&!?b z%etui+U|QIEQR+SWeg6~#|vjWajYnC;V)2G^OuMx^SVAxUR}w`+(~jWeh?$t9IUFb z;hZhzR(5?*IGcJ{bZ)Haa`nt$n9+D<3pF~8na>YkH{W8hG~I=xcLxyeL%K}VP;8po zF_-N*2Z#RmShqf2W{cDUmYaWu3-|pru=wT7@*NMYQo-eWag(I%ASEkx;jtn5?p)tY z<5nz@%u5Q|{pDqS`AzeuXQ}7JH|)&R99S(e6D$ZSxPn;al5ujy;wmNfL#9YrM>m^* z|9QC!^Rfhs3@i@zcOoLl4_CRtEc3gFX_PYe?-Rsu%RJJRUhg^c9fW^cO((4gj>{ZL z=g(3LHyX-~uFjRe2twm(8k@)HYagL$6eJ?!AR5g80sG)jx@eq}N?4hJOACYDMFVeO z*v~B~e9EN&mA$+M6#)ThB3dsyGq4P?8W8X)a{{U3K0^Oep=9O(j#-gn3O~UV{>H^f zr*OY5%O|8|%533b5x#%wg`^ne0tw^u34!s!bSJq($`qN{$TWLd_DLG(uo47xRz-1f zmD6eA4hT1tCcHPo@-j{IY8uHGQ6fE;%aq&+G~8Z0C+DxG(=U*bG!011djTSjC`qxP zBp@)m#r+a%{t4tyH*kIt=~U$p+>{RH&=m$NfMF zEsZ{p&&f1$J>I&A=Q>iw?A%^%PCSa|<-yt#m9V~+(!h!#_SErItfNv_&lymq`ZA!x zC&ff-%)vBPCcuA*>UiEaY^(h{t@QaACX>d?f+X-I*8?(Bce%A5Sk8<-BcP%fIMgz7 zEEk-{>Gpzw%B9Jd*E_SbSf?qgqgUdXa|vmjeP;h)I+c35Idv9$?f60h_v*Ksu+G5^ zEl{n01J%U^KSJSRkLnk)0&?T=8rHa^an8H6EZ~5%HD-UH=n}8NuF@z^@=dT~?Br(+ z1|QTv2lnb&djV)K3RXyHhmcBWf9ilLUcH7tX+%|IeniS_s2S>+PmE`mFotdXq5+Ld zj6)UE4=l1dISrO9bn%R%SS0`5#yH$Bbom@bxnE+$y9@jqF0IvicW;^CEORxSO~U)1 z&!2Xda(aIdRe&2dK9K=PYB@swR?cAtq`w`)J$R`1J{fEzCQX=^F<9X<6EMytfXe^)-BKw-X7&{Cmc zK^yp^1J`Kr(9h{K9F&`Z6QE1|)w|RxxhU@&e!PFBsrWYlSOXB}m^QFF+E2~`;j;+jaGh!JS1@ysp`wzAxx75ykD^jKSCjZ7A_yfVN>Km zd%$4h;$N{FX%vr%Pt!{W2K8+pf&Ukj7SC{CNvv33D{rvmF#UMt7sjhnUMLsCvDPg~+2f(yG22J+;xpphsGN zot5d7r4OS9*?C6zosNE&m4jcMwlOawW%k+(a%@!CeCP(1Y~v!Wqx)@@N7`)v+`WHw z&&A5!tl&wOl@Orw_VdTjBy<%ME0ZiQg3OO#pr|88cI4RJP@AU-tBQZ2RXowkNq;Nk z!)+*w)rL6F%7n9g6El|7LeR!DOX2T^{wzPZkKhKG4E8vRA}> zfHSTl)yUa;DG(3K2Fl5sI-_c3Jby#>M#=V(RP@^E0G$}%Cay$M@yzG4pvbVw@;oPB zaB(s!?uKp5pvqWe^cE`Zo3k+}ijm~H;nXWENEQ)UPMsd1`pUA5c0rqbu)3co|J8PX zq%3oL3@G=TS=8Xd%lNn_)Jd_aYZpay;c2f|PLL2xKC+DhD?&B&oj*-OdVgI^ZzL*u zbe7N!8&5`IHnTE1C_SjjU^=rZ8kID(qJskgi#sG{q9ww~nbLGRAZaAX8sbeyIbQ9D zg`Q;ZZ5eqw64iEp;Wf@h6@Ah@B|mEE#r5z!~P)N4=;$>bY-e?Ms9{u-q z{VyE_^vb?fx7sD+&J8dBjPPEG~niby_pmeHo0kEESs=8f#uM^8Lfx-Mdd%Eh#4Nk?O|C@t|nw zYYy0ZqX(kN2RE_wJkfW$JW=)g|Ha0t8E;P`Yduz)@?8{2*JBLhk6A+ih*pbv@~q8vLrU`vPY zy`xJ5+QYek;HAOB$N5O}oUw~hYEPsTRYEy*@zVEJF;Rnf#PLytA-x*VNEcD>g4{#2 z6A41k@vAGBNg9Ea9=(CY`BWF!?su@Bw2GKhVN>?rR+hvO6mUAqp# z_wHZdtZf&%pnU`^HTVt%VN#Rn>Mat2_dVQ)zLG!@h8Kj$YUW=M%abVUB!6*1v+O38 z_f*SAQRU-sloj#u!?iA;HcY4LYDOG@Bxch8m|IF zsTJ&V66bDgH6cf+eZ)IOg_Fzc7y_TWljZ9+f86+uD|7&&9+n&I6BITOKTQg*s3Cbf zpL}%2#SMJd6ugT@!ASdO)t7g|t&kUdA_6{%LnzPy8f|g*-I^UmQfE*kynt)qi{!U$ zm0{U(fc|4RaDI6Q=r8n%4bPE1Oy#+_JjRi6?%)R8m}&q75`K9?t`XrCnt2Wf*K7uO zL~zl;@obq`EgL|yn zNbRj^Zfy?^IN%EGU7IZ3etm5Zq-50%QW(#Bo*6&SfRn;MIH_6A8k~^2&Uw=$?R0oL z4M}O5{txU6$mk1Z{)2w0yeVe7y(t>w1X+|2Otwi zIT<&@E^~qRJV=1r8+0)iT>l~i@XIJ2qRrb5h+i=ztP;AFE>AN?2s);X&+tZ+Md{9j zFpFDD(dp0Amxp7`b~+SEhH=iT3S?Mt;eWup(|@a^c~b<5BTeY;Kd~^+X?^1?VK=UQi99aF2%?%FtXlotM>xLN%UIH*G_tED6i2nsBzsG+bD24sh!NA>8!iD%$X4m z1b7>e!Kil2sC~^lMCe|+S22An3#FCrVd*9@j`5tYnneDdt!QBcD5tTdeMfSi{WK^C z&L0J)Fj8UVhS!pm)Ry&;7iRqQd3`aR>VdA9FCxlOevjKcOnzMp8ne7Z`j z!W3`Afs33M9Ea&3q{%B<`2rcwYeJzy%mVlD>2&xDeF0qm3T19&b98cLVQmU!Zj;{l z2Dkog0YXIrF*%a~7bv%CvjH3e0@7r+h_wOg0e?WNQhpxCA^Hq#73O}ZG;fvp8jP;O z*!wtCP|Bz*0*d+s2B`t1)#FiPK?hBDKi=OdSRWkJAx-=wQwJRGAKBDnbC z8h^lMa9DI_!VAD~zzXMjJ2Ew11_nVm*kBIe2W*QTURP966@jxnyV=c~e)pofxvX%Pd?N44sG&fc5ZpA=V6}mqvZ)T6$q!12hSGMV*|e^hu&J|_u|pias`q141evG zDMSGqJx^ahEKIIY5(*9IIx)D8tQO?Q1H&2V!lQnUBVK4P1*dZ($HJYL_e|b`>~?wp zkZt_kq9}+pO#Czv4T}hlArDhmF^+S2u*}~SDrmCmk!RL1AG?+jh&hl+jxzmidg)xi zUEBk<9+?Rp+QkU~oK+qHK5XzNJAdA^y$!}WT0HLUVEU4V=_MkNa zsK7xjAOvb53wAyAkEeA>#hHO(`z&%2a7YUB8ZSI_@fQV3kP|Q|{@yV?$A84?2n}a7 zigM~v>woBq)ee|gcNCDtHjNlVAL?O}#MS!b70OA-$!HgLG|bRlh3KY~y@_`N4hv;2 z<_NTD@53>RJO=&?p|`RdoNw{fWUrYP_n=l2;v6i7*3;?A+G>$-aF~ei(c!Pmk%lzg z1UpU%#=}YanxIlAow(Xd3x6R=$>w$~_BxZ{($(vrP`!Ia4t;}}N(1V385~GcOXNoJ zBDLWR=kqAxfHopNmslKOw#NTfj$kN?qeVWT<&+G7s)nKkz*k~1&D0wWjm|nNgTSBaBiHx*}aAz%$JDLjJ3D2p9_4wh;#(J{pJvyh>^8_jugP5`igVJ(VOR> z23_<*#=21>UlSM!+zP6?sr|9GKrqjpq?uHp)lgK4>kYeLsR}o)6;uLp?}~~_u+$a3ABF^^n&Z! zFb-2WP6OeM7+aXSE9+}R$Vkm#t8W=o1&|5{nS*j}4Y-(mQD+Uxqeln9##qZ7SB;&7 zd^&x{xQQw_FA+edws8bgB?B(y@cPSM6`&7^6W0Pp<#JjCqvOzb=SI3@Dd;-7HP^Qq zjGDtR1HJL#ln=#z8f2_rrLGYLnvyR8N6;22wM0Jdr>-52KvIeSw@q zg^_oQ>KvuO8pd6~Fjqb5iIP5}8lU@r8t<6IB`}M?JrlUcG#GuVSb+sBdbW+Pawic< zS)D~b=rQ^8LV^u;+!S?K$f?rv1Tc_`IxIa?BxZ~5FR0bvxi@hrkU>V7JN#dEp@kuA z$*Az|0u2jBK{VS50kXYscA;TYe&c*8zc5_4FA3DlP4NZ(s`#Q-*k!MvE8aGyj%Bb8 zv{~EEA4x$A+?x~w-s`gf`PMC$IeIPrOkUG&C&uN^n` z)buFj$7p}E4YWx|^5VK*c2K_k_@diQ)6JnR&3);c`z5NAReL49{7*ecV3DsQ5L65^ z2+D|6dR7tq+Y41_s*^l_@$0^l8{Pyg8VO&_VOhpoTWwxgm47(zC5K6?| z0&p~c-WEz+pyL@HM$7_kHBVk-yWd{_B2PQo}XzuW;? zoGK%NnW^qF+Wv`N1~?Vl!DtgF zFyGZBj>|AA)L#G#m9jXp9^Pu;J8fK*zY~^a8b(?1<)=k|rShjyT*lZtI|d4y3|s#`f4JAc_^x#t^Eom=_+=vjew5O?4JtjQzV^tDS~mKy%rn9`Jg4&i&lGU!ZeOT9B!=gUnGkorc$$l2ii>nyUY{Gz6PU$C^F zZ(0ui^%i3>OR>B}Ram6*yQeCVdH1*byFUSmDP-K2VX*-exAy-5u?hh)lK~eff9+ds zZyPrf{;praZ*6eb<@=BJma@1#$2b?Fv6(-A+QjIHrkDx zN)SBi)NG?drCLL9EEoup1uHbSOcH!k=SiJQeAIK``kU&EW;u!}H=J~)1Y zuX!Xr{6)zS1cJBGeUI=6f8MbWMZl1bT!6z9N?f!eDeie-*Bc|yyQB#P7`kLQh!Ake zU_3nfl5B1dI&2&o7Kym21Yarq8~FrhDT8N^vC=AFNIZrYT}E9#7?yHnktMWD7-6jw zEFz8*c#+FE%naU;XDMiwIO3ABBO(qt3@eP~2+LuPG1iXjC&yC$e+7qKK+q6}8~V%= z3_zz5{|FZC68aQ4roG1Bz(MVeOQYMjNAmfH(^kj_^Vw=7pPjv0N+-FF{hMv4PFe=t?omN<2>B`$1Rf_UDxBvngZ@C0ah3it*dRfq!5k_n-SwbZcO zm0*Y)TXfdiorX=i!Td2Y-3o^O2x*q6g)K?3e*@8mE(rIYIvF^ zZjShE3YrI`F| zcrGQS@V6^THWrPwZucI`UBfGqL7Sb7cP|Itts_2?2h-QD+eJH@v`g_KMfplj7Pvo0^u)JLIVk6&fRdr`Jn-6Ezqv`B7Oo;j7uwA_1 zX`^4t@8v^z?}f&LdO4C$+sO)T8AKJrJ9Kq0O+dc)m~ezFv!h~67$ghtVxzFy|EV(8TmY2DAf4>g!?aW0?9}5` zVIMWjeNVfa1yE^h*wV{u9((Bl(2rKB`^5vp8OoFg1{}!iMmt;aLSGj2r|oinw%|#@04EncZV#v9yYu%VM>U~;Az@`j6_`FNU<)(M zI6Q*Ln0tleh90WrnE`CFOOK*$g55(8ff&sme|iq<>>l=!PK|;Scj@^Q8n=fU765|) z*{P=;=8@Z}=a8R%Kmk-RrY2cPjT# zf9_qMJ~<&l93&)z#KSuuLOk*&4&b=qO&mpqgcL7KNR#QRZGJde&S#3Ilf`(LkgjHp z1;k;r-dn?fEPN(of=6aTibQZn-Vh*oePY|F36w53=AYwsxzy_2`1RuYjM0vVAgrw+ z*J$3H|DUYcgfU)Y5r$(Bl#N2Fz!tK>e-;wcBQ?o|3$0n6y;|bO3}IrUuhAAH4#k^a zAPFCN^9txq441J72(;T4bA7fr1Jr{B&L$5OVzLd1ci)Ovd%fEhdwsTOY%^5y!ZH$L zsEN6x5HXgMz&_*Ru5nxt7l2YsgESEfpTqbltU4CkD{swiTm1FeVm(}*47Rb@e@?|r zyJSFNP_8c-mn{gc^)?0%dOy&!p~s*{?bPuGGe6p$dWK^zd_r;!oKG*rpq9Crcs`$Q zWm@JMRk%{7jps9M{Nzj2C+^uj8N2o{eYAAw#1E1dZ|j93jKpULJxClE;qZzs7Ic zi|a-Ock`HvZ?wYR?i+?5*o0!!VXS@GX`thaDeGY2$U6+RmY~A+u&tB0F6XmWuHMZN1G4@7Y@XLfYb^5e5r`{pMW9*^JW9x#kC)%rW=j_y2nk9QEAc#uy5I)6ee z)ZRm0v^((;L@JXLV%a?Y0I|g36Nn`uo@EX%i_amJ*2ejeA&V2if3$uU4%NZWl3!xi`fK{L~a9IGDXDW}HDRM!bbsjCcpJH2#5U&Q9d% zz%2fnVXP58_qc_jjtaTAdFF>mq-fa>0}z9rq=v72N4eJDKPHLS_KH|x- zVw1`5_*f)jkocZ2rIWgj(U+5K{@mTpdNfb+k%92F5E01-V(+n4qY^!x zS~RQ;Zsvxo&%sk=GgY~P^M;_eH=surk^;P!PbnG6&s`?B2Ag zCp-RR-hrugjE*SMxCqfNU!Xo49W5VLS;hm5L~?YnyAg1sZ4^(_>;R$3p5O}+VDYQQ0fwBo;#T&0WF*6miRo%$WWj?7w&TNLwT{1km z;Dm_K6FJoThs0SYE%iSQVK9&B7u}Hy>wad}DQx{3fhWNq(*F~;Re@YH?ovVJ zXboyWF4fito>hY@ZZbSpWIQ{NKO|dtO*hzF>5<#$6^dae;0V9I8xk0Z?)MsCfi1MP zbb#{%(Z_{YfHxrFII!>+^;lJacxB849)Vhk20-Yo9oRQ)q3fCbr8d@jD16_*`1*a> zV7C@a>mfQpPrPk!ELF&S_5v&y?xj47cZhsD&@KG>U(?EWeh^7HK@|kSWVr$hHQEOS zy3kzNlHD*7))yigsEu7k+7Ke1ur=_pgtJ7(|M1pWycEp4!G*-<0D)R4FUj=R6g`yybrjT2EjM! zaSt3RecUVx8;u({sRPL&Vn}yj!s=9;brpVEmhm>{-FKiZgU1l%SFI=W=p&x68Yc!` zp76-wx35*z4Cx zz(Eg4%{c*-rpS509luR85gqCStYyzRfg5ynyGOOhiB@SJk~i`jJ0J+#}GQiy?jI;UEnhr9z^b zUY6bAZ(XneJ9395sufR#ev$8qUx??~he3xlEp|prR*EG>9efp9`WI$3-ea)vmm}{Y zo;Xst<2hMQNy=sL!)~lNOY##kf*~8u4@dwECez=yV!qlptM9YKUll&CWf~@sW3Td% zpYkcvdA6H){Aw%YYG@-9%4`qpHg6N=>gqShre%>U8vHuCCR6EXmf1E`ptJKFgCyEh zXKKYm!ACeF7?CH|W%OEBA5jbGxna-_SX$Q2EUtl31Gk`>X%a9(3@2t*Lve5A_-=r| zRaAd4&0kUw@I2gw&wss!GfU2o2YSBu~G>W<~|Q8g|HTEWIc5W6Q|{XT#6n-2dU9XaA&SU zk=TeP+s_`dy$a$^s$t`9i3Co}3^JfAX=);1Q-B2EKKnAVf>xMzwjGvUK|0wsr7=Mt z+sN!s-NyE%q}i{$kve5!j*u`kKeMG*4KO&rGg6lhMI7G_oig)d+6vIpPJ zAW;Vb`$2=xY3ABm8WU6S1T`|2hzItzsGh|#>9w45BuMRQDsD+&!v1#9iwc8Ci+P(; zrHYFk+7tIY574ac?vD}KMWHhAFr^>ZJOFXqpJXbR)Q`Vos)jcuzWAUqWJN?~k3AOl z=@Vf;R^bt*2atbBcBHr6{G54^ti~GU*nJhydx~3S1wF}T@Z_ftNt1zO&vtBGxU{8w zuck=VtfgV?{`*4gNGn@_t2#QR6}CYzB}>|%u&BY|01Jl-E^b;`CBCV%1^ySPv0y)Qedxs>EV3JUE}v#mBTbn#R0Dd{6*sEo zQBmwp{8Kh7VDh;Xl+t#EB3hT#Nb1xCITrTKYjcsNdyL7z0)45QDWdN3RxX~_Ih%*l zXk;Cl&}t|-Q8De!frg7=*JcpyZ2$9i-)ZomL;YF?%RN0de%itHxp?|T1p z@Bm-eu&avG%T{d*;vCIcv@`{|qlwN59Kh1^V4#2XI>)e1fq1-;lfbrxOOC zWTpA^?$DzXG9$-8Vp``IVVd6-3ibY_DdTr2Ga{MTGXAAEse@vA+i7e{7J!ps-pa?x(Qdh}*1e+iEl*&^Qtx@E5 zlivvaOS#mcE<5L~Zp&zBHvsgQ!61&`edx{|fA^g;q9b*Q2<}SAyd1Cg0u~uy^>+-+ zMrq%Dy9w5;Szv(qlkspgslvZsW6clK+J5RlY5QTGNp8X~NVX;I&d9lzSIT(T>3ET$ z))(W0w#TgdO*qBF1^fE{&;rP`AZv8&;`#f`@)k46V<) z=#IrqrNs*LVbMX)QwSg1`YGA2$#yA2`P$k;J>zIb?b;VY13qb-N-AA_ib3g zW|K!fA$0$#E$pC>8w6a0=V0k{vHcc=eG!fs%t4_8WigKh&M9*7^_De zqNoA3qb@h4NiSd*MvigZskR~QEb`kut3BY<89;{xs|$pFskpf4=)I3mxujl`)-gid z(taF-6jEyERjXaCxst>gj~V3h!M9uYZ591|yV@g(p=KwhBqTc&B1~Yg#|W22d#J+A zEM`DT)~`OTFYL(b`?K?bJs_PMnzn}zhTb+I3D(Q7|N`%4@jHg8|l3;_Q5> zU)w01;D}h@Y`W9Gd@y>TT>i!NmjH)UTdb1Ln!#pc!;fRPPf>1PApsgXS9{mpEDGH7 zM^|rCqY_2+>wDlT2xzm-bHwG`J0r~W@axa=&z~jVW3YbPK(^6UZGr6-L2YU|6y-@D zfrJUrNuMbgfPFppV{2UeZwFpw-X$X@D8XK?u}`8LGR~V3uVS?8+Lqd8P7my$i*84N z2Q_paHvhx^6KFf4L#>89Twe9z@WPg41Xm493d~<`V zyVl<&X_}Seoj08|_d~U$9Qlg6x=2RnlZ^3vIYB!BKphU|CBY|)=yBY7hbGv&aD2Yf z=FJUyBM9@_SJXEh>Q904t>qP^*I(*&6Z3<^31Wj35N>wzt3<2pBUB;a5}?&xE}=(> zJ$h{%)Xfqn)UmQucf_VyRF&PSAQz8za4A%(mI1ZD1h zltW>j00S@gJ+m*B2V>?Dt>BzO?f^9~hi90o4`jaZY5S@g$fYI6eU=3Tl9Wy9W?npm zolcrCsG(W1y%7P>32#Z zmV=wh3D=+6(ttJ)=0PNYBmC!JiTdl@&;_t~J6!w>k`#IQ3 zbZPuz;Dc*E^|ZNMJb~yKEtIskGce|s+$Z~Gcap%Q^L&&OM_CrPa>}ggV{N>+k|B3y zh1Uwlf|yvx327W|Ek(f#~jqHkA%<|A8Vd>ifB(#+ElqCoavR_eMI_PAk_6WxI zpGTMQEI3)D@Ph(Q+G#?z`B)3O;46mD$gqs~!hhG2;Y}3w+@d}Vls)hfUulxXWU#e+ zg(inv09%cPyI%|X=DlV14Fslqj@!6el{f%ihR}+{_hiLBz_NevcgmeneON`}-T*gn zkdfwO<@h*9U+}ta+dU7}t@Jx@IS=LI&ni0~_mf%LQ4d)WD#?TQmJ*3=< zDj}~%2gB2v=VzuB0oth?43O31g2SNnfHB8B!`M09Tx;i_YsWLjgiObc^ha^*qLe=Nm4Df77Bqgq@s&Ka z$Br;C>cZfz1lvWtrh6>J$-|W@h)kvkBrf?BO$UY)c=YHQ4SDAMlAW&N{3Grao>l*u zBgxm2B-F}^WG&gqLjbo6nvci_7^ZM_v;9yAw;1C&)P1AK77;vG7*ClnF|1&Z^YADq zy;hMDD|;L9H{W?@lOJ$97nZ1PoOaDtU@1v;2uj!N82qVuOzC{ZbK~DEnF#KW0^D$9 zUNk!s62-rqQU`0@+1X(P)_F|_5%a6avs+lemVS=su_2xyx4YG)J!1_3exNS3B6S#5 z4(O5`x1xyMEW=Q*po9)sLkuq4Gi3&AnUE;Ob7*Ry|?7=u-QwZ~5dlTUJao=3lgbokT~fE!n49xc_d zFd=}2FvF(l-Xi;#-UVw!rm3F(Ls^NVz$E$A*tc{KhZ8|5kk7v+*I0l4VZU9Ft0tXP z1vZTHX3y;?K`@p&z!U zXYy!{90Q8u^B5XA@XniD+R6}GwgckSs+9bi@xq2z*1X?V8?_9MX5XuJp< zF*4!d??$c0ezxdr7jiUZ+bAUmjLZN%9nMYdQD?TA8;%G+M~;v`C3C^JcxLOJvX4za zbV;1d9cGyCjVOBDC51XPM8C)Nw((SdnyzkIGdmL>hgK5=U}l(zmY9qeTkNd_d_hbB zGauiUz-O#=!y{F~lI{BK^3r5Mb!Z7$IRisloP*zpaqtngmIw!#Y@msCp0Y|FTGZmy zK9JPqQh=LcR$cVz4C{4$jGOq{FSC+tcMYYOY9W*1c0#>{kwt$v(L?_*f~Ooi5~{&b zcA7=%3_1Z65MNAMYHHiy;bO*y3yQ0^`noZ*v(Z|^!X6}s<&%E!MMZ`no{wNxzY=cO z%3wvPimC;}2V+A5adz<}*ns=GpU`5lchU=D02!t2D%Ul)&8zDnL{aR|!u1e`Xh^xs z0le5Ex5Ld8K874_dBxel-G-^C2T@ThgBmxlP%WzhG+?W!DMUaF3wT59BN>{v)WxA$ zUghSOu5m9uCf+@!Q;Swdup!W)LShyLS&%6BshkRAECyyOKnF${eqQAz6)BU0UqV-g zV;(w~PxC-A`njV`4k7&AcB(CQ=r2ejf%5S6QV$*)#bj>$m11vQZdQ?cf9LB#`$Gvk zeT|b1K=|Z=?bD1RB}@Qm#sB?FHjz6vC5h>qia3I;eC*BD_W(IrJPK#d6k)E0umiO$ z#vwy@ZS`{BK8eJJBZ8OPSByhMD`0ZLqC}mf^?SaSVFw&$>Qn{ARYAu>g(k~&u$;=Q zXdzbN%nuEBERJQeeL85_zN&Z9x;UB?#7~nAU;`7V;u08m#|@^`i$aa65d<>L6H|U7 zp=w}Twb9ZgxJ|j=n3d~y8-Qr2tE_{;_DB3{x3fydPHitB2H$r_oG7G!_nvaz^-7Ht zM^LWJ8GA+^Y+4|cLs-0H{(`QPb-&9q<*oz{1_o@1-S`?aRSR4rQmmI9&R{rI-br>H zuyoR&mzc{`YfrtHeES$V4j0mi2af?83Got<7{{+7#}wGsO7=lj`X&Mj315AWrbe|O zSd8HLtxOg?DagzkwOEIPc%*ev#t+YPi`!p+o~)3n0F{LQEoDZ`Q2gc1=zPl`C)K_I z5@ihZMuOvv4P=pAX{^lf6I)5DDyEfD@q7m(d^Z*ySDD{WuOg2Q|)*>42&Q|1-51{S)k z7yZr0nv>T8hp6ZC#UjkQB?^d#Eff|gK1-&~Sv+fUZw;w%G9JdP*vbb_QYZT(O^)u_ z&0LKcqHd3c5WT1sU#s}~dx^KVzHbbr{?HhtsbWB(r?Cfvxq~str&R@m1p!<;wHbaU zoh8L_))du+r*mHX>6p&|Qn}-7jmGS1)`NomZc5R2JGp)#n-%`0FwRC>lIwK$u_#SD z9G(X!?EWUB(N!C`=Bg8NEE&dW$izgEWIRG#les@G(aKf92xg7OJcMrm&i#hywNLB(jbYdKB0o+vnGFzAzGgprK26^>V^0fsepfLFJCHc%FhJv4==G z;XTci5qh3XPu?xgt~ta6N~S2~i<5pN=9h-u3>vnXWFtz~+B>n{0&&?dnHeihpZ6F? z_@}gW+Z$`%c2m=sA{(5HT3B8U$C?Nz7JZSp(Uy$iw$ECp0)WRUTX;0O0+egLBy@p^ zCA60IfvnxesE{Z7t6kQ%xWh&Q(@&x!dh5V7?l;Ac_ZiMqM1_`Op>lBIma6R|5YyIh zClb|@aAQ|1_o3avK%>)^+xW!kbqJ>fFCO1MQX3G1&DO6>&XWABh_+uhu=J3M_b6G~ z-G)w%<-+9$zOvj!1*(=Zy9efuhWo%FbV%i8V`Mb79GJu&xRE|op=ka0MhCHP@W@OQ zz2gHwfwL@Tl$I$fERCg5cJ%2QO2u5{LdNjr0T@!+Z5S9nz+zW~x?KU2(Xe)}ydgvr z;k}o#(1am|Shg46HkKU83yE3N4v_fw?wCypU2#$bLyp*z7f4vv!d->BP0|SGdCszX9IX6%MiU8-W{+S;5@i!qt+5lRK>d z1BwoCsb}Lrz}@&+YdF8dHDI88|EUE5zXrtQZ#`IRB&3!SiYaLj(C#6Ny<0N`%+fZN z@g_+TjSV6)p@{sh{e?YY(xBy5*(I$SuH>dVreu-(e#9P zoJuC`CUXT4RB(II@DwS0m_*V@DCM6~pExKevKk_yMUlxXaV7y{5d!JWBM*cr_;ybx zxIbLERF6oKK#{3qL6hBo##|>UOcX$&iCG{)jKXQfg=iabdcse$+Mt~9TF?aRw@dt8 zE5VU1X5xpYO#gF~qGHF2P6^k@f{@ApIA?)O6{Ov?vSX)J_-Wy8Cdm1>!nS-UB!Rzm zVWqGxBr+egOkvRl%O=m#InG-d>C-Efh1`0bUmDI%(8rB{oW_x#2^qNIKv_2&VC(@} z1c|&Jv*a~4A_5>)LrN#6`NOIbg@pTLM({p`+9T0iUK_gWaamLMb4pmr zLch<&xqB@)=Q`)NGB&k^uJh;R1B}O&px>A8`=fB1g|M=r;e}HCtkb=tw_}{2`r6eN z|7(xW=GHviFUK)R7*uw|xsAM5z+2a`Pt$>9n&S2uF9`FM5x>LZb6FX(#eFbxw36MU z!#~B4i8s$qmyfR_&%x1^iTgw5@Z#z9&g?TbaedN^?dSUr+2;?O`k-j9hGk*s3V2>f zE4U8m1uSRcV){dbV&=p5*Sc=F$FswI1kDCLzn6oDp$nYV3cXp;zhXotfV`!^c#)OB z0h{xFYLb6r3};}aK)GX)j+Z|xPlQev`Ww=W5LaxC?}XRGjMAb{jX)DxDDOKin(yIt z@8JWS>HOxnY_SKo&9Or-pc;%pDEqf(8C=5)Vp1pF0OUB`fWx1s&<}94)ZIS9nvR4f z_T~q3PlhqwcG1T)A}oBs60Pl$N~-{&dssW`z{%b^g8&I~-K5{0t}O+x`2FF|AxRx( zS_&{6TUt`I9$g&FG^}r!Dg0P^IN<(3G(NG1Ah02H8v#EoGw#L*lvHu18<`$fCt9>& zR^d8Nj&PO@7cObajE9yeFcHG8N3#X_hK(#S3^g!5_F}9*SRF+p`m=5lRcQjz@yD~moL*vf>;<1DofvP1c zJkK7c+Ayt;+(Xd?RB$=H=IeH9?J)6~kh1lq*K@G!X-d`_~i4Lf4!mUB6sCbSS; zafi>Et2=#Fz%qEm$17vq>|w+zOr%{4Ir`h{a?9@gb%WVZlv&5T?UVN*h$d-^Zv@YG2 z$n*6y4BD7YBZg{0P4vD-!#*(_x2-%KwjZLAeR*Z~6Ro!M>o>A6+S|Wc5=~_3c4Ti) z+2$32{550~aBS+^Pm6vnJY&(A0Wwu{hx#-gk%n9j7nAm-HJ0$lb@!zrL9xTBHBH^`x}gm;Kp$;;*A$aa{_{PC^p_DgYUP zVx10P<%bSf&&rXnB~@3pc)za@;ix6?us=kS#I_g)m;{`MDr0>U6tS@uGE7HLuBW+_ zTM(b|uDDbl>%Bsd#E|U>XDNcxbus5EVV8wdM-RPrU1{=9pg;dhSQ^=X_%QSXG?X6+i*iH7ZA^jYvTTx}Q?Wy$7aDy;A^;4o zWN>uhtYqje`H47u+IkhDjmZv*HnRTUgP!Ei*IQBU8Q1b4r`espJmcS1gbsn*^b)QO zBGLmcA(cTeJ+vxo{Gu5`50H7#@jV140Ae2iW!M)isOME4C?N=dI+`)p58#9l?$qny z%q2byjx*b_bN&q4+0yt4Du+xFTa84bW3x>BOf52^)Ady?e2x7n`At7Zy|Dci|J7$A z*#q+JBD+n$@$sG4`R6kIW3qEAErOY13GY147pyVJ$&y!t8M<0?BAdZxrf|m>|en@DhP#?2rV6LDW ztRvYN5`^;JV`0vNpUJ1N$U;=3^1z93z5*BEHu}QuF2n(1Q z3)!d@JAL``bn>~AKqMqRFS3sj_>rfjm{TI#{C&LePZ_Oxs!9;Am$80gNRH&PAM}lA@25(l*Y)amBj-tc7D+ilfF@wC7?LUJqFCdm<*%5?>I*ge# zMu02dcB2N{+@n{Rf93SJC-`2s84plJg(d1s3r}nX;`J$OoK6qjq#f5g=pi2GA2}!X)ebRS#%l}#XM<;N?nOb1Yl6S5{jR0BxdSNTHN zd7CKoX3TcL?gV&R{1edmp&O(v4LgjVeT4K|k{i@eP1p}x8`JaJuhfKohXAO!_9dG$ zZZNl`x_NYawEOUS`N=QWB34BWS~7^5xspNBTP6%FbLDE%ze{2p-n62xf8HP4g*cj% zTRxX@2kkhLztC4kMeGYX4C8?$IU{7<;_){SqX+t+eywK4VpXcXO*;SS26NDlL$|zU zbdH5J8qn=Og&h!-TOlLahXZu|NvmTE=t!>x)xEhqDYjQPqsKFc5iwFg5fNvRFHKk% zX$sy@G{YVr>_1D+x(Nmo(d%8o0JSx06Hyj%@{JX4Xpx97b)80E6{5oxn;b;96>FoV zmeHS#;YgN7fE6drIP_!eW>rkcgz)5_%RGosNz4yG&Ih4?Wrc9ahXZWoyHNDxve^Wr z!3uM!q;N@d{qiW6VM9zOwbvR+N~d34i1y#?0{+!Hb$)i4+_3loY|zP7L(fTt)tS+D z!FY&KCqae(t*~w}J{+mcmOt|D=U( zrVpja(`?tWFjKK~;{||@zpXs;(OzveX58VrImfW>9$!9_d}H_SFj;{MC)5cS$#~HS zxXxZnzH!RK+4=OV7R)bz5I9ahbg_WDthwl*f1oPS5cQ4ZcwZXDchgrsziu|I+t#+~ z)WIg$lBIR9G*d%6CR10Ph)ZJQ=gU)D0FPR&HQ%EF8$p>@qy=o!rX-@vjVBR$sO57j znmiJHWf40@Lf7BqOwNB9pMF3oI31-t*rc|fh_I>|MaU>Iw|T%JAme5s*@JOvZA*OP zg5}8Fi2jA*mWvm!Aj_r^9!GaroPM%iKZ{4EoaQv|VnHGrS!!G}@M(J>=U`|)vQw;V zKA74%e|vE;KLwOAo(rioBB=p0($iw`;l5ba{qjfQ@t>Yt4eRC%M7 zsr~jlJZ_BaSW%0vVmjixmua3?YkkxJ2}uLlD}snnLj#a3vyow(=y;QR$ge-F13!=| z1)H6fe1o!0{<5Vt+Nq07FSF6Y8fePdNz8fE{Z*Bx;1>{s{ml)eoxs6QN$q>;AuxrA z12KP->6#17gH!O>V7H zi4BfSL>r(ClAnYyeq6PrQ@jHnkl?0Keat;ony*ccIpS1FqLuQ_sSP#-(H)CN{m3^j zY#lU5LfKy$g9a-T1pKsGidv*UvX0qXt?U)S9cWBJfTyTmH76%gk7O@Iiriu}M8B!s zo9?m5!yRGV77QrpfuUJY=~0XZ>x z&UKdMb1grkK={!Xq`i2Kic=Gzzhc1A5-D&Ib3KAl>5)aRtk=V3MTE?%aE4P474?~- zh|9Nk7vQ_&3GFu9FN}-3&As(ZK(U#vsR72hLP0A=5R6v6*4TAaAfwI`Jr|2V`;jk# z_PYC7VL!~3;*iBs0xI>AX~}W9b_O!cQ|R79@NV~GgZ?18X|^1dr=qF8N@}AJgY=n{ zNb@jT>!=k_tl)P@xoT>NR1Og__<|-1M7AY)lwOcWuBv1=xrlzCdc?xJ+CT7UH34XB zXtNbao3sKbF!n3tvrcgVK4e89*rz+JD zB4B3|h|>nh zO%9U&u>0dnZ|1h15j`vsSV|sEu?gr6V3ZQ!gTD1OF*BG{d4v71C6V_Z#18p@jCwKL z5E-ZZ#1_r*B#LypAc;Uu^ysE>p%aHCf=>#7q56bLvi_;DJHG5Z=ijxc@u_HK_(7D+ z!96Thr=jj1T1(TY>J^?dOvs9UA_)lbYq^LXbtGtIDH!p zIW!>O&U0(Ow6`_(Q%6?Uyc=g@^a}f-XXUq|u7~had0_Q-;wI(M8CEW*xuz#ABp;NW ze3yG_@3X$~K!W*4EL?F@Cm!Nfb?#Dabp`Ibj2&0gArpZ{cQ)o!CH%sl8sL%{cafrF z+agU?F@^lTx?I(3_pBVs-!g!38nO_b;}ANxY-lJZaL)U6uxE9P6WF49qYeQD1u!@(> z)ruvGDaS-Z*1!$-*kFNuTFwq3&Lp7x)!-gQk&}VkzceNLdG&%4GqBM-6JQy$@0f1> zh(*eUIgiP16B2fez!c|QwgQpCZE&t_TE0LhX$Q-l&63t&z|jSy&TUc4-IIujQe`|$ z*q7YYMjHr8NJfE!vo^p>9|eeQa5K-dr*7SC!i}Ud%#kt?Gzokz30?9c9Hz(ds-R*7 z>K)~#DhyGH+KI(KN419nlXz1KwehLX9#7e)7L;|RawyqpIw}RgQt_DLFfV4(8MKi9 z4z@F{X-|-|kt^ecCf7Me%D7zy{)$nQl_q<(saxn=@Rej-cL3CqFR_+P2MuoG5x0Np zD(aPNW-c`SxML_N2rT9~2rFx4d~BSmvM)^BrLfx+3YGQ`3~IDh<#sL&(w86>lYd>5 zGL#YaZ@=H4NB-{qe%QvZ39Bp8e|LHyB<|$D+teU@VUdU>mICi<&JzpA$h!Jc)a_3x_?*iTpB(te(As3b_4#E*w4_P;r`piPttciJbgce zYlQPJ09L{T*WWLV<9+O7xo zTTdiT12rmj+CKK9vUQcp54{v(J7UM2fOuD6@M zfR)*JY(P_R)9K#V$H#-?n>1ju4$ZnLHTub#bs>6D3|X+wphk}=6P_#CaEKu+kU8#{ zdhF4}4f9V~^T<*T;3ToW{9 z;+jpWm7mYmdT$Z@jockY{120ESidgmwt}e(u?vyC=ljlf9)vMw?~ReJU0gXrpLut$ z8-7_hvPpkV%wHJsy#W`IUAFRO_Uf76b~GQ8(&T$SFXnr=Qn2JdZT&6&(BxFz8`O~5m;RB6Kb2gogJ3?$0pgmB^?wy zGbM;!!sK{*)iZXdf8RB`Hg|lViz4v2GdJaeZDPIBv*Oyg+T{Os1^0J!@fH1xD_)OB zCi1(#YnUe8LTNKY)7e@HQ?TJa1h*aSgan*Fy=Tn#M8v^-PaQq#LPdN{+}9Zj`q2JZ zpDwB8X!pPJa+JCo%HP!LS5K4UcmT<@xZzEs;vS72dv5FVxfL|?10Cx~tg^$`Wr(C!ruvGroqPGG=B)VnNsNZ1G`Vd{67zh{w>aAXC3Ir3TA)a zq6Ord)B5Memais5zQ`vlq&2XS39#8>^o2*zXW85Whw(|hmk^Ge>;HMyL1Ptr+}dgz zckx1B*WHlxfk)}JNhhoS1R8IB#ST?f!iOY@X)4yvcU`Xl{eE0`EwpZqbZ5ezK7VIO z+yez|oZ5v6ov1-DoId50lZ9cohE;`52>v+p{A_R)5$O;ns`GWe^}(Xb$oGwRiA7~C zY+C3pK_R^D^O))QIuaI8yl0sAH7*g`ks3Lgib-gj#{Y8Y9p35N+`xBij`3}{EJBm@ zUkzw(TgWzUTPS5eXbv_uRyIz~wAfQ9g8!M+pF$0Rv2p!}ypoo428Dq0xAf*hSDj8h zfRrlW_b>76yI^0G{6pLMw1G1yYrxVVV!7!}e@%;{DVk`8TuAU%Mlt$mKUytj%%TL$ zm@yIpJyfzWa{=X=m~ra75g6osO|a7ynk?^?E&4=p5WdJ5C>iunu_K=QugIS~(l{VY zpcMh6rYc}n)#5&8g*2Kh^ORAve^Bh(!GGuL!={sSDyM|tgCEi!T@34Jl>iV;G$Ze9 z1Nzl=QwP<5q-WAldzu(kfPb|pazK&=F#i@o`oU2K<{nt}3*ATq{sDP9If)uXhrV8M zP+$$kQig*qP#*C}1j`oog=e}6PcYFEIyplL!Q2+C7!S^w1+Ry00Hxo-n3~+E12PT2 z!Zt{VHFN(Tl~6SRqM8%Q*BU?=1`C<6i%uV!t#y;JEEWh+08gM6SwuiKdOGY>KPfiH z3%f1qo&)4rr~Jo9f_YMfOW`q!Ql0rUX-6MbAQ37)41q?7!VL4rGH7 z867BzEBuC#$N|?3q`pNe1lfmH@IdgZm}d%OHIK>ViIM&L3~s-N^Z@w!xDV0uH#CRk z)nc0DUia2Hta8>?__*(KMIz_-=_20A`)c-ZwigwUzg~%~{&)1J?Ia1e4hU|dyy2Ah z=N9Hsn^_3{#-j8#7kgS*-el>CwaPC(QtY@R*)dVY{A_upm0 zM){|4P+oHE!z8_AU-yj_{~|ZB8UF4~R&UT7*d0o9(|8Lv4_qWEjk<6L`c+92VUb)o zUu>Z83G?yw)B<3ZgoiyXL{l7LeZ{{_(>G(6L3cDfOkjw0dyOY(cA~;D@)DbAfQIxl z8j?b@e7pG!9J||jdH$Y&eY?*FhB~i+M^+?#iR}Vq|N;xj<*oocaUNdXd#FL@dB_gnRXaM^y0@#3%2>->N%)j4~t= z%g#K|lS6`}$9ZLJ=wp!aibPjLzuQ(21qCs9c*INcQYHT)=J*Q2&J?LbKXoR5K!T8|fjVWbV>-jpxYP!!g#Q@$Zoo^J=_8Dv2C%~sD7 z(W=NA8J#{DL*~Zh4!|9B>qOYB2jd!zV={~}HUXxi} zS`c~Z{>6l*l z&GGgM+?|#>ob@p3spX#OmV?AV;GcSBdlOI;ziQA!WNGmW#cd{ZBLlX-PvpJqb7+St zzWWL0-g?)Kvr>N!Tcz*$@52Y&PCnVRJl7l(-|&=3hkx%~d>)d=cK7`x`LSZhfLC(S z*p`st`{rk|p>Vd><*#!6CTb<0@=r+Ut6l5oyMEL7k!%7QWL zewI5KlZ?v;Wb^Zmqt6-QR?1%-_}NbH-ly$N15I9k&kIxJ`)owtnIrfl+h@D#>j%-K zWnYO7&%nFwsULanuS3oE*eNUi7CWm#0ZbQKR!7V?-hIqhRUY_TGwJY4eI&Dwy34uV z{4$(;3Qb%W^ad*W;eO_Z-}w!JNKAm?cxA?~H(#!vyzg?M`csacsg*fZCgPiA6R=sx z*1{LRjXI%8hkVuM?aTVU^4iW$=h7;hWl75JH@TZvN;-(g7|O!Q zJsB0weh$gcX<~O!JfK}|K6g-%pnz`grfhq|6f0HxJ>7SY%29O0pD~lqJq2g5&${iwe7AzpG6RM43M#;ktAw=_-Yyh5Vy&1^aj_steUO~y%Oz_>?Jegxm;p_zT}>R! z+37QPeZ*`5lQz^Z1KjJjz+aLR)0bd`zqMJ~4G+(~I$5kUm5y1oxRsZ8MH6e-EAOll z?J2XXj7}VZY#PNjDd!^oDZkD+-TWc?Y@c?As|gumOdrs3J~OwmV8otM*>bD|1l^w31CT?T znZz>x-2j5c?qYFXsJNKvv3@5%swJDaz=K1TxGxWD3@LMMhY=nWoY8)OlXp1`_*h1u zp3yE3e~RfY4|j@bWT`97m{`xA*-zl3hAkLbz2jnpu~x6u4$G&G(a6uokIj#(f^h@o zMfK#_^ut?HTd|n9cv1~|ZX+>r@+zqIw;urv=28ejj4cGLF!lJ>`=$Xqtnb z#$+tPFVSoKdM_AqdAjC+pY*wCsAGZ9l4DyZy7_!L)eBwI?=ABxuq>G^USLRkH5o!6 zs)#Qq7JD;7S8g-|5oug0M&p@rfjHHz+&uxFQ4>*}KX_ z*UjybF<`e^5z)hnM@DX%w-Q;5T!JyBBXJr@8j*v;8-vh66g)V&6g+| zmS-aILr!Ze@E-GkpJm?AR<1&Fh+^1&6_OQ~vJI!eTIz?`wx|tQ@xAWAn#c6(cD^oe zUAuoq2@ZYOyO~Zh0e3-Ese+SD>~bWkIGu>omNEj*AA*Yg@oM_0Ql>*VUk%&Mr!4)h zn2DzKovfyhD@IR%xqU~1`>Y7dffo+&j)yoERNg0OaSW{Es&s+mv6h|17JoXsR39;QvYXdkLHTb5eO($4{sU@ZhTbiUj#S?COjnrcG=} zHlTHO%W!_23aeso#cx&E>mYCosp2Qs^bo84(%4;-+9!YSnOI@@-7xMj>SL8L1N2Bf z;|>|iBhEAg4?>m@GSI)@gFnt=aA3PL&Jp}_z41?FbQfqHZq4KVhPPM@J^WwzL$kE6 z6DX*(e+UhIH3=S$f6OKpHdbCX&VRK!ub3FC7%QigI4>K!6qf`$yAX-M|M`jj{|HRj z*jai0Q`G|~*Ss9nmkIlCU9Nn*7_=t_fuRf{YiWm~Fxs#vNeLkr^rV4vjmV5P&!<5V z>I@_Q4i(56d0IMa!Nt=h-q2QeI+!J~D&PthbajMo3CxBZU?=a}_iy%2*K_Wr$4pNo z>j1X{)F{Mg=7$AB$wGe!)D*2Y41_~usw$#r`WisOq~xb5i5Nqk7VI)9ONtg_!|TuR z0Y?-0NX#Fxp*&VXnIg7C%bqeMK&9#kYcdK{dJ3+zGZ-1F(%CF=PDr)L7Sw1p#o$CV z7t;t#HA2XuNUJ>f^0>f;;i!n;rI|>$!%>mH3o~K0hh1&iE8>D}P3R+j=VyX<1i~sI zlXC%btchZ%xw6+dD$$L|8Wc=^RQw&HFwq_^RmnlnS&)A)@GEaE-J1Kd8grB2`s|s6l$`Knzfdh$~? zc};H&`g1_crqRQi8%vb&rxyBq!6=qEr!o-$nm0kw7IrB?&08P)L4=thTu2M_lLds{ z7_-faF1gaJHj}a+B$nzF2qwuf`#HGlAWDEg13;F;s9T4V!r`5zwVGSSkiKG zwLjg~Z|L90VkG>2v7Ca^kD!PoKeQqC;Ir-3|NTxCc#~!z}S@7XV;9QKD zVuEq|t?+Y@cv%o1Bo?-nLj@`~wrE+1TvO0ViK(0-N%0)m+Y6s(5IXJ_T$Db ziwbgxkTV3Eln1`nL&)Xh$pMU6QwGT9iYo%-v_RDBQGnu2oXWn{m#qQ0V4eAwbD%kM zkXv)$Ju4q?cx}8`>!)VV+V>you?>IY(n=3h<1|Z5Te5pev>D5)T7n*~N-AF$lv4}% z{8*7y7HoB7WnJtrOSI&IQ?ww<6xq7sx}8Cl3zC^6B41sKQ%qy^h5=9wx{q6X~OD<;1l5se-PHJ5!NyX>wY4vuNF3BYX91x-r9}jT4fKqR$%YDMr(Jq z$;G>9@|F*T-M0(3wgAj6ggY44-bSE$=Vjpsw`d!>!8mhVv$gwV zk?lSnwSR(e7bCxmY5LJ*V6yL~wR^S-_x?&a&-xkFY3@#=s%rvDbyiJA@}Hg`ct%hnbTgqIoRsg-b3IQ^h-X0`CgRr&x9M#sVEdaQjVL4J7US>aD_31`m<=QaaF z`16;AzoZJU&JkXJJ1e~2FZ}hq@Hg)Ldxh}EcZGlaPPjlr7s%{4w*hN;ah`CA)q1NI zE(&jF0e!ywhHxcAcsC-v_haGxO!$iM!4ly^?)Yema5Wd4@SiT>+D!PZu|f4I!-VPQ zAg8TcY3;`sH8uqF*wnLl&<10;W2~GYLHYp5J_<5!2$}bP>K%%Oz{Yg!kRP%NKqe>1 zmW~HG_Y1i%3wbhxV1lGTFmacVKNSuOlS<$@VX~}3FhwRJn3e>xt%B(?qF{!sQ7}`+ z8_e1x6l8-Wa1bp9+2X;R6u2N1eOs6(Qydh_i4@G2RR~Jv!U^qe1|&lYq{2uT1*2gM zjD>L!XM@szD|&A_q;cNs2WdPc*r0WsJiaYcFG++X7-56F^wN~hk z6?&!#z1xL8$(&%t4~72U2m@Tasz_KJ2TaZvTR`$9SR>msSX(2k+bFCbDr{h4H!`Q2 zc);ccI4OK7AFc^onCGp9AXyx2s|Gp8gYEQhN1OJ4egUm>BefMd#$%gjHyC-x+HdE-7j5l=Uy#CN>!^v{`grkxr z;d_jK#+KXgORKfiXTw+J_X^$zCZ56YrNI!6mjl5GX)jLiLNBcDvvN7iqrFvcV zc_eMM#)jHRk!;gQ%R#Ni+Q@x7wG?L~$Gf!@ZzCtGw50#H(631Sj;Mf2SO8V95Ej8= z&_86CKn>_W5$ZtyjZqH`pnoVXgC=MO{X0M&zXbLF8|}~m`t{!h-OvNQHgZ{BxRD!4 Z=KoOrd2y;?Xq`7$DlMY33|`l^aO@9%HE_*PXLSqdes+1x*D zq|1fUZc`Li=-h7Z51XH}ue)1SWY4!&WxlU{yAQWpovZApu)mdA9E3lif8&9FuI2B0 zkK{KR8<=!|TUJ>gp!@6n-!@xqh111mtE8x;!*#DUGe_*Ul|3Hw;9@TgV^<6vu@3oRvY{q3z&S?}AAu#PIT zzlNsqp&zkVWLy5c)Z-HmKLt2{pUa-#xclyVX7IyM44}-NL79SdQ+2TKW91>M@>Y`MxBFu*i|v(Rjj`^gX72)N8^4dg#6Tq-!8vG@frXS*f-|xF=$;nn5Z-WSJ*n&k^ zvWOil)5HPB6kHsqzu=#4!O3izRZ>Qk3>U|Xx8<8Y_yeMXQM2eJ2?PWXqz`z;QX$@e zK!|WgXP(Cga7fyJ3rN3Bp|1(mU|=Zi_W4>b&jI_m6e!n@H{=lI7^nS0)TXDZ=6JPe)6J`fAr9`l zP5?L@K!tZ}ha0=cfR+kkR4&FmRYB-@MQkP_U{=fMupOr3(G!dUec!bQ0twI? zTnQ6>)1jb$*c_j_A@FK+7Q8d9(ccZh4zTp$A#IJiLe_bfOa8T8le<2insAI*!MH6! z(p$tu_FE+78B1J;fxC?S0G3Z(KklcIgp%c1C@W{o0hr@S@rL7F9VSNhJOO{6wc#Z$ zJNDCloO(0>8~_#Z)EZFu+Por2b_A|2!80m_;|NH9_$5on@d$=|8^8Uo9(%qC=(3?x za|q)K7|2o!HDke#D_G!!g#0WrP~@o25+!4Rlx~<#C(b@N4!Nuzcx2|D(>aod)45fd zoXBl?1yCSm0Z9}lJdnBx1H4-anUwjw=#?m|VzXcxPQGo?Ul^rIBMNJ;%pQd`aK;&V zv9oV~YUpDewV?l@W2$c&Y`}#;1kziIwG##u&Oealz!}LtvXbM#Z~>+5+U?ox8G3LU=LmI+Zet;?y^AY>FIle%|j& zk%L1on7}ApuCsfN>D@HmMGrJ3r1SC;_I{Dt5U%_Q3!fOIV8&H0GA_#* zmsq>`d%B+r>yBY+Ms6cM;@9(suzGvWDdONVokaph1^ljFT~e>SZPa}eEYO^LH>Z-ABa59*6w2L`wX^fSH$~pd6=lkS5HTex6KzUg4a7q%IB@69lO+ zu5oS%7mfxY5ulHCQ~RD7*q5+{A<6Gx2$Fz3vp)9z1fo6Fj2A#TMk@@>z_U<~KXgqK z;(8o(fRjp3OmU7LqbZV9o>%e4BIk=4zO!%x7XEN{&7t{GJs5ms}^eg9r zgETc^P*q&oQ35)kbBWgD^B|NYq+8GF5)6iszrGQ7%mCJz-!T!NYvMssxhZkMp+n$| zqUkt;CKIHJr;aNxOcQ$1u#!||_FNOX;?~3RXz4iu5z}!JQDQoOcbe@Pkp`b|i6cTO za2``~){He6AkQO}BkVQx5lUIS1453|Hg9?59WypZ9=~a3JsV^_X%wu zhcDc)sxI9SImnV=fUU=|_29t#77OWhT=X$MO1E*p#nTRSm#;rF0;@id zu{LW5`+Zw8R_Mz7L9r3*X{wZ6^=a~{sOp2e!x)8~m!}$kp9U4xion`GQw?@5%5lQk zKat?($A>shR1`Jqj}16a!vf(><;qS+4^`xAJg0=>27iBAz~$fPmy(Oy zl@(~hUR^JL);VXEN~mIfD^bkh@{2`sp>uszVrjGZeF!R|(rqABwNdM<>1Y*G+A~{x zQjbYCe+YE(Qfhks;&d6R_XDTrI^NTseGSIqPg^jubm%o@IS`rUkU zfAiZ7mfT<^8x2a$o!&?Vu@3~;A8&sCHQyXy5Kv7Ru+tY}J)%}E9;4ZOxcTwsJ^qe+ zx!t@L9HuDEg-Ko>p%75gmvG|9^l|Nia6fZ4+pSx70Ewl4dA_DRUpF3XCa%NULKcLc zL;J^nm7h^rAR}ykdA7@-pE5?oo%7pd1|swmswn~c8&f3<2rRtu$;mYB+YuZ$(&FjZ2T`o+<30;&+lljZqI_NeQe_Nl~ z$lOwkHkSb;0u%u_mw?O$ zDSw?=Td(7`5q{raaUNx0t%#zo30j~*y4y4jiX;a}fo>mUi|1Iow&;-3x%Ag}Zj>w^ zxheXv$HUQZNDk-n4fosocVB%_^_@!MI;qv&{li_E-jzumCmD>|yMIQ1GsEUz_kaEB zLz-WTsXA7wx=UE-A1t!eq|!LA${^C3-hU2evrX$P8V*A2?eS>#LuY#)+Xwv3qthm> zqVYI%Pn*1m8rL;pDll?l?2g6csriBvMRYu0t>y<%6K}SePNVz4e6-DxsV?ZV z{Oio#ZqgE#M4b+gc(>ImE|dIjt8|=aH6M)@&|1U#?y>7ppVoLdoH(7J-y7!RVSiD& z;h*0|<6fDB4XEgby{jrN^kmJSV2foHeM-_4sdD`WbP;Do9p*fD!@-UNFZE#Esp}tk zAP2a;P zUM`1oPNwN)(zGMI^^J-qDMil0D}M;%V>5yT8PS6rf5kPc$oj#!&N}9GeLL<=%Yz** z@X8t*K9?%uS{KW6eM(gJf^&3LM#ru?7F(DA~{>vqq>24O)v5d|6J$*k2-d6 z1Cs`{OACAKAHhS5q=-IjDjngDCk0jX@&1=T{m7ir8~2`f%_c@B|HAqQFn@$$+U_=6 zu-<2gGdf+u=gRq5=zSe+NvmKA@}w%e^rT$JWvPNE{V0C!*PJfTW0g;i+B|^aS^L6h z?~#{AkQ4Z$xZu@=<1GS!z4fps(j;c=*ul2P^cWYt9F`U+~*Ht(F(u z4c;6d*t6Fh;AgWRo$sC`!+&U9+z6Ku?sPtylgRT87vTB)@#FpWwyTSeQIcTdnf7)(^62tV z%xUBD|+$B;dcLHRAO zB)CfS400?` z&i4Tf%Zb)$Rq;?J4Kb`PIAiq)^3mw>ZN$9xXi?AJ||krN~YNq>5l*p1z>l}+%s-aO0L z?YhA=?sY2=0hutmq#uWf0);1u)H`9Z3GwsZl1I|2TRZjY!* zCm8AW6iO@c-e&H-$X?;7SLR}&EE#LTNKS}qj+WFyTuk*9B`7Q4_gxS`bzk@+<&T#E z(_}-{0!f&PV1G|30ec|#R`<;$cy<;bCOBQ1We@{j5FBQZ2@l;KH-6xun83+CGtCe- z3#b!_tEi-J7?vykmMRt3bsBu>e%0MntjkHH6O9l*1ZZ#vJKWzZ)6*`3fr005AWT)o zRbI^qb7k=gsUShd&BeH&mx6jc0iK|ohN}i6GIY*Wtbepxq%1aU22l1u-h-}RvRfdN zT_+S9DiSOJW&V{#0@Pt~IHsp!hr_kV0DkA~ z5t@rOUdv+l7&wqThfBa6Vv(yiG$-cVIBIi9fDJ>K{0N(eGh$6K!sFE~oc$8N!_^LM z+z+D@*ndvwsbzYS*;_9?0As1er_*`lw0t`ad{4ca3T+h_|3y;0>!!?p-!GP3x11kMW?e@r?kg*>H*U_hJQ=5On)uw_OeBV4Fdbz&`qT^qV|?~&sYN1 z!Z3q_&rRD@bReBC%o7Cucq2*VYC3R=kqQC&{lH7N?Ed6TuqVdgX~l+N9v+{5Ln8t7 z(e{s9=%M?T{TNuQ$QAg4RHpn|mT^^Gbf$34^WKTgH2{rvwR!w1iGPD|wjZ{L32nc{yzZ&XLm58cN)qO-qL8JL zFfY&@GP!f0g+S2OkEc^Zy&CZMf;l0Jc9_VpWL!EWH1 z!++=_IAD&?5%6b$Am8MS0y2x9K!4f;zdKbkqUYgnV~AAdfZLb=UMb?=^RkZyc7zLZ zj3*)Vfw&0$1Vi6!=Zss{S5I?Nh9n^}a=_arSG3#t^OV-h%LfT9k463)Sp&MRY-#i~ z7=6{|DRgO53J1XSWVSo9r6(ifmV$Zh6C*Y;KJpz_d9#@%B+%a&A7EywvVR#l2-q_% z5dh))T`!$|3^mVfsk>%KrR=G5CgW0RZesQ{o5Km~fz!I{pUZYo=Nn@HVg zkTf*5nbQBYL8{>Pr^tTKfg$kxY6}wU0_sW~Cq=d>=YBj-4IY}Zo?nh}5MGXvW~Es& zKj+ss8?7RZXMp$neHJF>Oc6MT!r;Stjcn<1lOihNT}ur{YPFNX4@ulf%|`%YrIDAU z0rDfZH-5xe{!kEzjsb0Aa>FA(U|(>t#?t$&62C-z%t`{T641h4UOGD$Z0 z?cJa6-~9(0`3)bF!xmwGJEE>u`xcy&Hf@38Gz*-ErVq5t-DOr6FC}Hy=ht^`lx166 z6hUHgI2_K6-wYMKir|l4X}#MPWx2|9w9T@7RW*07cX}I@X`C|4Y|M+YQwX2FHhT3- zclR6o2}_$Gbu$zD`Qh%<7hSH(ZJEdU>fv!!#H+N7w=qb6IIR9At-iRY(cASVNfV|2 zwBDq7rhZ@VQbn{>^}~2L@p9Fzt0cZ{Q+u z(6-DnHd~}<()_gEC2EVd@6c;wlFtCK3Q8qG7VJ*(>iD}*A4P&l)%ZGX?^n)dLqy}D3mk9j8C zx)F$HCG-wXla3f20h5!g7#jv8=vaq4latLDEj`$xhM&F^*-EF|B+X;Ib)ayPZqq`u z!ZGaBai;!dYs2CSymcjHE93+1hf53BxQt3I`(u!n#k`-AG%hfcHyK5LM_KfDgTW0! zOtx8CvP}}|MEzpx+E_neLhDq;QB=Z4O<7Zb>6}=pIvNfz=OH5%V-N^=CKKLxWmsdJ zXgD)&ciuVq1-CZFKS8S1JX`V-()TqRUZJ3uo&~X!aM>)GxZtv~ymA>3CYQnZ%?;1p zD4fXWC@Z6gvy!NUH8?td*tQqqVsNiye~+S^yqc=7ct2^q8yxQ%@T8d$a@Wl9Si4HJ zO^cF}3x5x0fXqmDkurVXQDiDdd=SV?=Nw?#frlYuL$HRV!IB@JTM%6{DL|ihP#G>y z!!zX2Q)?PmZH~SJyl$E+orB|#;_}KKxY%VW*OM$|uo7C2H~JNS=GSq;#Ya;Oc)xg) z5vo+HKF~$d(fGktV{K%^EUB`OkV9m&)*dJqVZ7%Ov|tjR3*Ozk+6|#jAplyk0W)5J zkna_tR{$HB9Bk!?6M>Fg0jz$6Izsrh()qSb^2;NC$1+KUt5nC)_oIxZnw6?Ijg0oD zcNGsifLiDnepoVpdcgA-S$Ns>{L2Ln*heoXc>B|Jqb$FnjU5-uat0(UgG_|M96De+ zhmJByA@hX#RCjwys1lFaEZo&A)Pe|qPlC}U&@FszL)|o?N+O2b zGnJe!JMH^mLnciHQ38%x_5`a&5-q69f6QpnL^x(s?1 zlv}(ReTt%g;j&Z6KFqMeyiBbxB#dB1evt)*z)hwaJk_uU@62c}cV<}e0a#8vp^KKQ zA5-dyAif)pANH7%_0VKSJW=ajO0bafB>O zqum*Rq5ZjjA)p-W*{CIovw2Gt$9fw_`1;|5S!$bqK*Q+F0xtoQ$PfdA8N`&y9AaRG z5EI~pDeOlW5c1sf7&IslVmRtCGeZYN@*N`-dD6tG8#zp}>8B+R|K3 zLBT}Fk*RCu=n$zkGgaWFXZs2vaw;tn8G3bp!L1rXC`ZnNTz!N4*&alNjzDh~<49hv zM0+-iEwwyy=xGJ&!xM9?sB$5+b^MF>9GLnBl&7l;w7;0K@12ot{Ry5t4d#1Xo(tZ* zu;3x@kSUdvEZ9WPFhWo(O$VOUGqVxFUHvmu7<#UVD$ZJUKrFVM1vSzg+x^S;+!o&;1{? z#&CaA&XiJ3jRSv_i8zzd9ut3*S1Bw+=?PPM*|09=yf`nQi{^({VycVtD=`h9Y=}y) zL>$R05r@6-zg>K1eSAj-U$t3z`7Zs zVD2w=6;#*GrJ2Am<4=WY98c{Yjz=;InCX}}k*`9yWFF~j7ZOd&zxIFKR3e0MbQ5C9 zg)CvPly_$wt4{U_`rdrYq_qz^6=-s{Wf}j^PGz?(bQUn8z5P)r*CcKj1%H6LIcmD-N z&!|NTWo~41baG{3Z3<;>WN%_>3NbS>m(fN7bhGXt`33@G-e=~V3ujY9Fsz_$fTCIVoF$C zGNsWOW-M-cW&)@Jb1E<;nRB|Q6!RuBWtk6#DaRs66u1ZwfU8tqF|EN$pf^lf6PWhs zgJwE_sQ_DIZdA`Gh{a7~(SJMiU}b_}jR0V>faQ#57Py>84~afHW<65@vMpdm163q? zZ+i|RrP0hmLFs|pF|8tgkAOsw1t96jJfIkFpb68&7k}DIXa=akMi!t-2(cFwGXnI% zqQ}Ef)sVRYso*pVfUN0$gbK$o0N^GoU#fRhB+PS!ZK&H>_J-tJte&5EcsAIT$siqxFAxv z)CB>bz>O|iauRGHBKcl050f`R;2Xa1owwTcB%J0QEFuBWdr23d@s@~TIuFof10MlN zI?qDGkgTEMM+qAT1Am`O*dsWEjr1_2x3MSTVOWVKj?Eyp7+AG05S>^=IZ zy~Dr%D1>-T&4`*QH5D~uY6jF?Q`1ksmg(2gxyBxhP=Xv7(Epe}xxt}J+#b$y$nWKa1B{g4@3F@vz8v2W6`Zr07e&RY@Cipd3 zw@8r67SaZ-uYb>y;+y<oOsp@pqhDd&3I4lF+5EE|`uPT|ZwPtIv=H7qq zDtJSX+}4-Bq}z=lo>22!7krt9X9;)5z~4t%^S>+GM9G&V@lMKaitTU91UFqaok{b8 znxp00C)8Ya)50`Ot?M+bx2K8?hB->S&Jvn71Lm87?|;?oBoRzfvx0h$5l*_fvFrw4 zwOQC%7kzPHA~Bm1$=1}hCpMRnz3T?cC~+&3Rc2wc2i}IX@l!V=6+%b`n@nG-Id~Nm;bjlySDSPonp6)`mk#;oNNf-t8KN;aC1b} z3E6Px8q_AVu)A=pyH)avR}ZWl*CtOx|7U9C0e^*VORe^(qHeKtEV%!i2+FRV@1raZ zn~J?(5}UyWu3J+5%B(KC>%+}T@a_R+wq)PKs)TmA8+T)Lx_LIg>#h`oZhBr{rS_(W zb|TM~$vxWcTx*8iY`o0pp7Y#8e-E$G3(^4 zQ?pLbIy39+taGz&20G5T#2FXbjGFZ`K7XHj9d#Pnz3ln88WdH7Q+~?+lD*DeU?4Fd z&H7XJ!Dz#2&&USD1MPSz&AqhD#=u+&E^z2z9AUkS&l$~UMfB%~P zA6-tTllp0v4T|9~FRCfOD5sa#XS^I|kAZ9xxH)Imu-=YUB&_fNr!65X1rMHfHGc!J zD_~YUr~tYnwi-?Sa$4{OC?%vi&->GH)r8jlfHI0}uUk+K6+N8$u%Mjh-l+siS;3>X z`#~MgK}ml;n%*BCWeqpRwRpVa+L;H#<1JUTz3nA8+R>IJk4#|-Xzjl{7zq@#o1D-@ z%Z1YqhDQg*9a4a@o(I}o4;DBGpMT&!>~Pj!$HQS!i8#5qx<51~B4k`lXsk5c`S?I+ zBm&owEllGZrkvokKTYVAj@!{ZALeBhb$?j?`?|QtiRCO7%FyBoNQp8&7#<04X$Ks- z@eXiBE(9GU>Dh9!%~^R-*HV1R&#U{*Ivp?`??6?%KC^BonbMBS=3p^$Iz!w^YdlAyXGkM- z64oJog@UV5{8e*m>E`7b9TAB|t=61~hWWsH4B~u%K$lX?2Z~PHX@WK+gxB z$jp2YAV=DT9C~JffR5VaLVqZon5vl^;LhGvitA7LJ3Q1omL{484 zAaJ=srK6?9>g6`#IWI4+tAh9Q$x9eROI+>+QT>-1qZ-o_x$a`Pg~#vGe3( zRX6!S!NGOEsMw>);D7wI_~QwxT)~xk42`NH#{^`LaC|_ zw0t7W4?_F^y0_!OK9bWapG=AY%$*Nw*zVow%Rl%lIPokWjR?!>Wmz-)%`p9m{Z>>p zL^I8$kv5{P(oawZFTk>ogps`|ZwdyP^5bLnd6G{r>mp}2^M6NOa}wM29EHl#M4_7! z0aRA?^u=XfG3R^Pn|x{TdpQ7CMqgz#ej*0PMcuE;30X?IFuVUeuZt!QWte;P<)}X% zl%tF0lMK3ZDj1J?32+FF%NS)7K+*7Gy zVHziq+%*qKeHL>!M#qeB+)J~k$`-N8>wDZ|z}hbiYJULa4@Z@*WbN-v@l9Ud64iRiadSw`9OHI5ZtNeQ$ZdTMK9g~greeS_b%eg zs;sZ_kwLfpynmltQ$leiLc(K|LwOq?4i8@3m+ga+AG7@cJP;t|bbNK6v5ZL_e2c}B z@96vGJ7J;1-09tg{(k}7J$w6;@pBWiYBDJYe=AT&kwQTvQB=6>JWq=zCn<6`laLA( z3d!)pDwou$fOv7WY7mRVBcTQiJ_`k@fBG5|Op%Zh;Q3od{)m=gYY7KYy!H2ZM!Zjz zK_W>O01xCj7?TV=(xt2HQENbncnSrq=bZqR1&f52s2>3&?neNLYj5;PoCp?MB?A%c zf8p#b!C4Q{RITq$l!kyhxe`e%x=CeumSerPw^Z+7 zqC`La&SUCbPmhE5BOKj8wh4(q=uvqRCc`-J9TSPQK_w>6F@jT(1;FS{k+m)7 zs+1MnQ!^U)F{W;aV|5cad@m=me^8OiVsy^?*fM1*b2VGWqXwMvYcs^`Aos&}+kr@{ zdfb!&W~Lmmye}l21#quzD%|lXpHZr~qss#zgX~0|)r@rE5e)!$F$uVd$y9@B7l8v& zM9AdRsAN@|sWPH-^`y?D8miMu6my+pSEiV^!F!_2TDC+0KbY56K2xtqL=`DgDMswOj4e|^Za7}d zi`XJqpVbW}e|6eG2;w6Fe@tUTFP9XGeu!Ek_;fM)^vmcG%ekbNq};G<^~ACQvbo=~ zES^?Enj!K6mW5GN73gJCfb|S@cIM_vj4XeP9jyk4QfDVSj~U=nrI@=Em7J7mtHRHc zvf0&r%OeU+GA)Ytm;H5KJJtuwLcG*kmt{Wr8jzrlwkDHe|)x3aJ}Q&RQZGs z0u08GB+91@w65mJarp$cHj@BUG?m^lBj=Y@+SH>tPktB+CUE$AG$QK5;K~rQIknvk zEKoP?=?Adt_?ZLzU;6Kzk<$RIf*_B3Xt^O-=A`q#lf5(X~=`+-Hk!J~fmR4$vMcb&e zlvVR#8>{)otoU3k9S<%VFe57#ceu3JBCT?N$hxXWgUw^7Zy=I2ON)IGzX9N^=Kzuw zk?0Nio0Or=L;o@`^|_{Ejf(KCx#v1w4^SgfPh(lBe^W{t%M=@^ucwIpI(pxAA>NNs zz?R85M!hSiJP+B64Z(A=>cc=$%{LsIH>{(t z(B$0?|7DC??D0Ob9-b=xEtmeLwR?NO|A6wqr^e569zOhkNxc*LWtIc<7t2!dhp3fR z^#=ujGb{Tz8gLew;{RdPC4kL*w;vak`O>CKALHIDfoR|g@^jBDCu4*SKo{7RZhZ0Q z3VDi+tOCuTK?= z)Y0bH6Jvt`+!R?X*7>oD=DQUB_>S{}>9X9ZB4?T0Ri~@>SDbO4rHUw4V_NhZ{lr(_ zoy6`h-PJ$fFDxAb)5F5`&CS(U*Sy@7tjtBeySdwGu~T`$IMCf3cmGO%uI>HQ*ZYG| zIuWn;2bGHC8~iMiH)b!2Z&b{3%t}9_?tm)-(eH;dq|BH5H!uK*X)*;^~L6>+9`7 z$GRQtxCeQj_W!y0E0_v@48_VUC;jnMDYE3Q??@NZ(8Py*mL;aQ=C(nOI5kUCA87)% zxZj~Zo8FA5s^6N=TVLUvPE70fobZ&X8SS}wvh6)hg5`!9hk4R;&UjUjquL)h9>kN` z5=7X;RE>*Ohb%uhKlQ`RaHDNT+TJ(atz#@@@~xSM!5UOSstcEYp{-Sx{ID++o`D3D z6A<=|4|brbJCMLQ`A~J9*xzw%M!V-^8lW*l*yXnmj@}^sNc#KJi=@MiExKwX+B;`a z7}Otdw(g(kGiXd6LMhtHiwU6vR3J7({ax_$l$B}8G5WzAQZc2;8Z&z@oZ5Ph)~r{= zhoxgG#F{A=isiX~2Ih`y6+2ilEqI{tqUmf$z7a@q;G$%*D0T<<6GcRLzOKn-TP4SuGCMx3wj0kLNQ z>d^5cjb~H$^$B=*8o9j@UPsLh7b}D}W^g9?|0Br%K${C)B!BWqR9tAGaf4z-h`yiW zxCfwyVY(vxViuCl@p~3mv9jS z>cWFL{8py#txE#<=%&#RJQW3c;YtAre+PiRB7oK536T8ccP!ZiU*--(pr z;HrjyJP85`ol^OOgSxRN5EoZo;e8>Xgd1ro&{7!*gSKmdKd_?DJ5#w53&)VW=LZ@d zEnH}0<1hV#63Q75m(H#@Xe+3-YIj*!bek53b zU6U|b885)G9>%^4w*kuWV8#{8)m?fS22{c49FKFQ6bv7cy6b;hYgBp9FxDQWYIutJ-HZQj{72rzHDHG{2ah}E55HqNxfcZllNfW${M zNy@R(Khnt6zA09Apb})Cb*x~*^fgg`(D^A}+dF+mgw$sZ{{GbMfFs<=iI4U{?fg~5iu5Vb(j)5lCZx5p6P!+}B+=Lx3f z6vQbPemF4gK#?#r>xSiM=N&rH!pby8(Fh&4aTLe|^@H6*#f=4a~+_Nfw{%K|g zvAc=zO&}DEwQB=;aub#}DtjxAQe&>i`C39v^IYbijpQ zo$c!Lu&u}!Bg14v>Hv5~yS>zZw|OG8dD6FeZ-29cFH3cn{JpIY|J=iUzodx%l2-5s zL}a{Ga{<){SN(u@ZZ65qG*8zq%+<39_~o7+oXHN`WW_yX%WCRF`4C!v+-d#q_&^+R z97`Hx)R^{uGWRax!25rzqurO(B`cP~`F$+#3MR_Ajucep##=7|Ni|1*sE;#}#*nZ9 zh^b10ty<*Ig9(*V1Ya;{;wort4b*4f3jU|w;C;O47CGNk%TBCWPg%&N0GwKSbHgz{ zbb!Oc=OaNB4(W|d`!_O}80yjQ36E#C9im;FN}+hyFBceZx>91dE~#60(wcD*adOF7 zX31l3M=ziq2M-Ank}JD^aMt#TPX=EhGOXV3q*KeMwi%)wK5*yDbI$cM;Fc}w;7Jii z(ETF>c%pal<_!wkl~t5d9*;rp^;^Jm4Ri@Z^-04QtSI%T`)4rSX?ZGhJTkp~Xh_#x zczDA_r<@D|gBLU+;6VT`=8%a8d>u-QFK8sQXB)}u=pzoaS+l5rU&nc1NBd&GeAG~X z^emtk)H+A{OnMJk^`sscBwrCpmgkX2gAF4I=y!<=8z$Il>W`b~t#XoSz|cjS7n&L_ zC!PF4hKL$XfS$5^Nej=v=#4OY79wBh!_Oh@*U?nZz`W&}QCckBy?}cLy$>ZgOAG(M z4jHapy}h~mFRsG^jKP!fa}%?7NudYJ+w`FkZpNag)BLe+$8<=9dam{($Zdgo21yo%G7W;Gn~gaBf3c8k1iaRX zMi6761&t<^$+q;`DUQ)9##7HI= zcYoW3Vhf=pky0$~HjCHE%kuuv7Pm{DiiCf8yA(W4zQLcHqFWdBCa-UqPI_GH4y(Q` z9DSCo8+_H4t3zLONYOudZsn%H*JW@2eZW2Wwl7*w(EBah)-%d0T=@Go1IqT6CS|^= zkh5JFI3sm&-{yU>!L{bl6Dxg|+&z?@FMs_1^X@0G4%mj6EJKZRc*%LPZ=3z?68IGD zC?700Tl|k|z(dMjg>Q2tw_7_;j3(hur=r?gNrXs#sn?!~KlAOOX#F{*-})w{ z;(f7sF`SzB{{3U?0s9I}0xW6L`|XEr(B@DNXVrl^vpbBKW7X#M+P;05iU9X-HGfxl zotf%d42*>`FahQeAc_;= zZA{FJFi8iBFJnx=rVw>3TY$DC6Mqs(_i<)In}OMzG)rUrz$k(ZMDLM;i-jUarH()n z#^E$dB$sC-7bKI}BA|i;sl8X7e2w%h!ghck|s<9Nu>;!(3m+mq)4_nN)wnrJ8Axx;D13%C4ZsW zUd8w_(36|Tr%#P0LB!FGuJVo3!bQbVL@;rcG@H0I61*e5(o~EkufbIC?-l$rDyi|; zHtOfFovGQqP7kobHy&_*!fM%*>RLJZEQY6SD1*8?bwo38gR+_lXE0ES(2OF@olSbo zq)Ag(AM6taZK?f*Wn*ninty%YyENMF@Yh4p`hB(zxc9)wiIk~{NHTL-#f#Jx`y7g1 z(_&5=l3_GJQ%UI2mri=yMfc0E^R^dOCj*seucKA9e4oK6eCu#wy#PkMXnaJo;990CPE?EmsRHj^j}n2!V>|EF7+0Hg}-&1DOU$4c+Y{$VoJ5IEIPN#lEWU-8DCz4}nr_p?FBD)0Q} zwSNj4Z{LU)yL~uJ=^W_Y10cqN>qY>8X^G)-g60rLa}D?}?`&6ZpL;jR!BvL}hZkLs zBN+GABo*p{P=6a<54&)ZVV{~eDdo#i7HbW=ys?mtCX*qTT|bUQ3eRdf=^EJkhsmf$ zf$mx)sOd6Pbtrf*Z#5Xsf)7T6VGaB^jXM-Pnk!)k<4INY*pGq6c5oDFFaY#wJ|^(O)J zcN1+msfNg4=BzC>#Qvz22iMe1moUgU)T2~QuXO;AIMw9y@oDF0f}k@0Du2Jb^aDP9x%Ojy@uv&Dx|jFqLjoWtc1!8rJXqjHipY*_4P(;;1e4I_)AC zU`Pg`?k+%G1i#crXrR?)2WGPa0AWC$zb|c|b3vw5q=dKgJrp}>p8(v46)4j$#d!2v!(x5SW=`-02Oq|I@Ky_8GeB)h!7G2C+baj~$*-VLxXZ&Yc%TJJ9=KakqyF_~&8~<8QDkx=7RF`qQw+g8E?Ak0!;~vixKVBY-&PFKov2?uR6LBAW)`@?y(T2#$L>?Nw zqoXjYz~8v5BU<}Vk@nrq4|g~J0^;5Ac9ZdQ6SJ{eEC-W;GAV!6T2XHsHxho=ui#q~ z;KC(2B!@f%1)8|N3!319+UVu#`e7rjY^93iuH-cL@B7VaB}1tRUEQY);B05tg$e zV;UKXtcMI^6*<9!r{oV~T%}#CBkhvQj+dC?Jq2&?GF^5!jOebC8^%N_Y`xk`;qHvvlBvPIM8` ziPEtuS+N7dL7n&wyd_ae9fxUC1gA@^5@tdttCV342S>{W*n}Zl!3TBb#@pZkS-iwS zF@E0{h^5}XvJnww}{U$n3PK$@E&>fFQQ}z70 zDvp~?X=WV95NBb$*}%!bHUn@K@Ba1vL)D#ez50l~MsD%$Z9VRuR8w`Pinm9{syMAa zPt|{7veW-wRd`WeRGs1_Cay-)34ED_y;J;LO~%)Cx0*EW-8_0z^#}=z#=vg zXLpWi${M_g9d<_d!)P>ysIw;Y2o?!Fvo^GCY+4CDvoW`AYTNdCG;KRuuLPZ0+se(Y z+}z5|v29yITHCg+ZK-X2+lGI(ZE?CeAGd94+g5ICDc9OX;>)a^$-AZU zMn9e6t^Jm$wpNeDb1r3mB+13j*KI+7DC^UZo zy77F2hJ$XR=Wb}+;6uGnG@NxpxSOLv2GJSLxfRV(H5`^zJ+<5)P4|a~tv2xOn5|~S zd~1wGVq)WU3~3yhA{lhh-?kvmB#X;~*gC1Wg<^Bl)%b_;E0OQ;vTw2IG-U z-AQkcrour-6AGLKD&%#G-F0A8!5~@C0u>>N$bn%is*^#l0-6uqi#-~StksV54H^pC zm-M4gYt~r<0p627KF22iv|aD7-$DL zKaGdOsy6xR;^RK^C+mQ-`5b=?%6Y=k^FUx?1Q?!!p{9Pe+rhjTmV-J|cR2Xty4vH8 z3bLQw0#3rl@^mmb0UI2LP9K};7xlYmuZjF4pKazl%Ck<$=s9VF*yAH2VtQ;W7S(ac zH(;z|?FHOn&|p7j5`ure56d^L*fDp& z`E!9OXB@rqK`{|LC?~(bL^*1?yW588TNUj%3(NiG9F9j>DEEAi21l-pmiHGDrd;MG zRHHacSS!_7Y%G^7-HE3^xVWw>-7T-CsJygWMsoxwuyN_;QEq#&S)yCJp;8VvNmBM^rTT6JzUpxh?ex$DM7&Fe)KhC2R|y zce;CBx^BI75i6fd+6zFC$)|(%hW9wZyt7MF3sr7L7KmTdCg)VA79Lau5O9e zu5QVG(ba7$9+UU3yH%~8T=n{=)w^fNf;if`rtEy=^3?b$NAF^`MG!IKjH!p8ohwAHzcL%h5=%oL&wl3V$<9 ze^b9y^#oHZ($?FMT@3UL4l@Ufx1o6R7V0bdRbRh(MJX=`iR}dWbnC|RG+HRZj#{P#jcZ@;!5)0uwM} zDc&N?6es_~tBhQ{Tq%g!55!x`!45ssU774EpHWS&5H1GIjeWh&M^qKwM8t$fSyHyb`Rd?&(=^YAUdQh>)>%|@)tk@%OwiSD; zB>(rtUZ$@v_LARg8qfagi@g*dn#Pxbgs(65QhFc|87zRryX%R(R@mgVB%bX9lXydK zN$7ufObGi(9^XD~@Q!JNcT5}0bPn~4{0hsjU4JJ zy6cW&h1emKc)3alT7GVLKQVK2jrAp03Cqc5$7_L=G_;yumNO5@kJlD& zAiG>M`~}coxMK=sZe(+Ga%Ev{3T19&Z(@^hYZ?JFmx0U%D6_L`i2{GL+)zpiDVYs1 zSilOxD8~hy2=EPMGI{^C?gxjYT+8I!03a~sQw-+?oPM!PF`Q?Kcmu~ka343I@D$-~I{F7y2XgCA zz4E6W_Yq__un}a3Z0KT;c7qFGYt07dh6p#DSsyg*4;oC_IP3kgcD2vG9XA5J!m(X@ zI3N(Y7;ym*zz#PNwFCz(_ej7NYTq!WZo4u??@t-P2n3`HiA z$^Y#d%wZORMr40r`>N`3%we@{O!Wy?MKHA1-jSVrqcaCcti9i_!9g=(f$i-vDxr3& z|L4*@j76Z$B@(Jg!POF!#u%~@Cq(jN+w@Qtctd;piwkEDvccXHjK_>a>KMFhQhP-_r9g^icCW! z&8Xf27%Ls!u^^h}i!E79c)KN=Z+RatG=v;Ad==uqLObtA<1U0v3rYlpYRUwWS-z-7 zSGwC`)Jdur%CBmF2z-=OFP*{8oS|N(_+`)Y*l!6vnOD!Mla4WNZjaiFR!dINx zC3ErTnM;5E73N}>%*D^l1(}=5!ttge7!cwrFCdNQ%K*bt&msT|*#}^8$}=#!x*#|L zPpKSeUzxI7>Pf?W15rl_XT^ zl~cdx$brDc!X5r1bf!F%WBhkAe4hV_zjrACTP=Un1Y|!~6y%{^0F!+!cdoL~i-HO# zZIwNv)??L@kC_6Rt{|IJotnCBqC4d45+uihOuK?i&u>036$&zX`Q|R*G)|}J5BZH2 z#q<1@3H}0pJ7b6!#j}(kWKMX-7dNcicp#{p&2F}~4wx!&kqDpHr^gtWxehJL}y2{B%IW5Ht~xLAVW@j@=oiwK^}i+FzR14GOL18z{l1%}poq3b#?P>7!y z)!R5X`T1hMXaVsrdBrlqY?JvK7XphdJ`@6g)J!bTyiR>dP9gDMVcS6 z_hoq9>#(0y;C7>BThDTn40x}p%_qdjGgeL=(2%(O^TMoVvft9tYC}? zy@q`Ez=8ZL^9f4M#)PY9cmxQXyrO>>Za|cC2+mQ^Q%o+1xSXEXg!o$M8+WUhhp9## zA0GNBe~}T}e2IdBt3`f?aE&Sqbo|e#1D|{6q#DksTBX5H8INjZ5vKTEzk;0ng*%Ew zR00Ue<XplSJu!VYBR|E_^|s7+VUJjApUeIDeE_Tya7Do^R|& z;YWwhTO6z+c+Uz_FvNTBxBtYQRzOCc;r%nze7eN+_e`cZI*O_Z_q8O9YKs=6;2tD& zc(DFI_FeZYv+;8>2bU780Tcr=Ha3@m%myfb?OWY*+_n*a&tIXwoo0LtzK9QdJgwcv zopkz=i5}7>ohfxkNp$Z>h2%wc|N8FYg9Ip?e3Gq9Ces%k34mDaV)wTnfZkqw_4PYy z&L}AiG4$->>P)dSMNB~iylu~ZTwR{8nO@cK*OaUA#y=d|=I4WdzOBX^_jJ{t(^a>B zKmXUo-@bmwSUfGIx?qBz5jX3>jY&zHLda>v*eys_?WP{auFuV`cww{-pI+uB7lqU; zjCgUr=7g{Any~WLQ@iY|7I@g4Gqt*D+H2Rk+0EQ`ZCF<|dj8>qNd)zW4Gg5Vaq342 zcEiwI?mp&Lzh*=hT*ip=~rGR zN+RG{i?cNs1=VhKZ`?pG&QxI(vEy{1CNX&L14 zLx!R%lujvL<|dM`ePvAUC(4BzsC2rI(kR?1!#tk^hrtro6#BUT{7;#sm_n5rm&}2b z9rbTNN=2i1AxaZC`iT(Y$IxgDtX8WqhUS*J)`gLvm%Lzr3wGR(nI(Z-m|>vDNY&%U z`wT%2+A9LV*Ce|Y47i6qXY%Sq#0=v#YD%& zSQg%BSxA}3Hq~(?I~2d zzOJ_ZliR)?>K5H4dQv5Sk%sN?(MCr6fFQBsKE<^=k;9G{m4+8iULW>c?7{j$34N5NbvIv9N4(6`U>Mi+rE^(9f}bfKK1p! zveJg{Fuql*de^zYWt!9q4p3Wy#wUWC;!qpjR9CRJ5H;0v(By-EpTTu)x;<|9P;Y&( z_4mBcDOV5!o5VK$nH9Yu^8dL1EV#drjEhICWcYIR>E@NVJRL;!F1u|Q+@9bZbj~>} zLro10tT1L0goXE3@ED_LIw zc_w?Jt5{lNkvIx}FX6X&32VttvPf!Ey*Nie*SMxcGvSz`D{5wc$(byePBCHA?RNEM zTqI@=)*6?^#V`b5SjJ#zKdSuaRqsC!PYS_w)MHobss-fm~)T$l*>hl1p`vyD8VPNXbZypYRr10YCftskrk&kNj(O7=|WvY`S*aj7`^8JJ--%ju_q2l`TXfkW&Nb2jT5UKh>_;H*GaK zPXV3IgWwum{9X6cWTChjJUIlyelM31HbDQ~O|$cVF>qgxu`lXc8?d8$fC+;uSteTO zjoPj2+Xe=v#6Zu9!LqJ6xI_oMu;Gh5=iRvm@(`j6 zm*D&T{_aS~U7E>mUmx)SR8F&8)lZLxNA!MBfkGR9yXzYF$Gy3e6x)8|rJ9@sV1o-B@hJe` zkUhR2q#!&hl^%@{(|Bv+N3qBQaqv@Cr72N~l`P^&S|XRzpr^%>czmT|VI4c4VK$c} zkBoqi@uw30*z@ssPZ=OHFtl8K+Xin3reac~yRG`M*&KFNpPnLNcGCE|$z*=EePjK9 z8t3!DBfi}A%{bPrcN@bImkrK;4cU^ErduVqg5T(y#!1Q?y_?eR3$APbSh_`&&Y>JZbr)SO2u)b8bvJi@YN!@vh zeA(|v)a#%QKKlOBw^^s`)r zU!S*%RsEqET-C%j`x=6BH3S*g5X#lt$|bZI!w&1QuYG%ncANiJShVq!T1TLN89m8e zXQST@j@=u#_e-DT<8#;gwS{cZ zQ}kKWqS{pdVkOys9No1%UYb>Zy&G!xgmT1RmtDZaaJap-2fHw}Yq8}u{9T@M;OF*~ zqh!>da^M6&Wmhlu6+1RnAX>Q$rNjB$>QYM6Vz%{l-PTAiw@se0!72lm+*~egD|xN2 z%SG~~_VOa*Q?ZSaxqg@4DPZJSoy*nMI56zlN$ZcH;uy3&o(Z)*xh3g;DMNC2jQwFV9;SEr z-YV?a;KkI|eNnZ;os+pEBUWwwVFb$(OrVjuPpd2=Re#xxebs+-X{jp|y2G&iiN4{5 zruxBxp~k29W-7OvJ4qLRlj5#z>&7&xf2gF(wOB z%ExKCz@o4RBLS*^RE-BL=-OJ4K!6yrG#plI^-qKv5d z?e?(2-Lgw^Wbmpz2*nnw;dSEK(v1`kS#g}}vLMUb3^HGRkx?qbNY~i0btY_KH&v%FtXpWu53*UOx``9s5Xi?ey ztv27$wE2oGI={Iv_i1MQRg=Heh_Y=xyEgk_sS;f!@d=YN1kOAH>%dqRs@C}LA`}dS zF%Y&tmi=?4c2X8f*vk)6>xXO@mIC9VVJG~T!O>HHzb~Xi{F7p*sSaU9NO2d*w*h&_bmr)y zBmpvyQP%E`etgsRzQ2ng;Ucfcuxv@DLDK?o&B0ye1gCW&5Wx%%5}#DIHV9M#_4bi+M-5&?L4 z4tN%q^?Cd+P@iGist`1>Y6ahAu(OUr% z12Q-_mx0U%D1XISOK;pp629wK@W=te4*T5j?2hIPnpoC7sONi;a*gyh85 z{`#%zYI4X?OByR#ECkE_C|1|IzHad(haaAB?wBo#MCY72StQ&2)$doF8d-$2QvWaW9VEg9!>f5)xND5XMVSkeA+r)}QImvYHlIvaaYx=gn zJNDHk6NO9lcbiNJn_l1hg(CehR&`tTv^yMc#=Z(W^+1c`L|T0*x8p>3IKarIT_0Au zTOulH`l+ki4eXEEzU=Snwrpto_hZ#RY@A9N$RXuPj{6Ny>%02~{%t_MvDy)%ZBxTH zLtx$mRe$&Z#ro~~Col|{g%w(pvirKN_x?1?({0zb)s}c!u}}~8hC|u5b$drMQW9uL zK>C`F{st9QY1!^*x%vYY3sfS#>r0%6Z*Kas-QxV7cDv&^)Vpdrq#VQHCrLyaEL8!g z5j0&YWk@ODvdN^D=}kCFYDFUB;-Np1A~=D=h<{x@60MVHYn>~yHPSSl_uaN^>i?8u z-Lf`l{SLgh^lpe#4Nk!2`H;N+Os{zV%`Xy%baCg5}16!d}E{ zqLDVStgyK!(X3Dc?7@sHi0XY*;hYI2lLgr%^QYr5PD%&yAUx3QIP_@>|MwIEoez@F zm~lS0cHSRgaLqU{&N!5j;FUu;-lI2_O@D9u4kJW`+JH;zf`D5-d&ue#?=fp|4MmXa z$r?XKtznfSYq)2uVVUA8Sx{khadxhJD4`~?hWpN|JWLAIL8-ZLcq&rIqB?=shq~QH zohk%p>dd8Q&Js|J%|tRCSOy7vJVp2_&6MI7#>#Wnf!q?gUYaN5U8YRVjIrcr6@LP0 zsP_lVR^g@)a(oUUSo0xt+RLM{w4<#MG&rQ7L0)Ck(9)^4!vv~e%(zxD!R>`H@Tv@f@`6s517wmMwZIJMAa~MJr(J2s-*JX(Xi}q>aj0U#vzn* zs}pJg0(}JyK@{M3NyjV3;ZQDg`VM*Wb?34={kezatPf2Ub38K3nJ)C?o_~r?pL-UC zomhTjEDoorJH*&RcDkA3W3KZU9|&H^&_MJh61;{9sb5jx;6P4lcpIRZW9E&elr2E= zx$3@us$i*^Z>+@99P zh1wnfUW@BIhE z!Oz-VK+|>+uR7e0h%^2|TmUEwf~2MW0E{hG7NnRFv4a$X%052Oq>FdDLNJ-zv%Gwy zspGSkz3gQ;d{PK(I7w9wvBCspzF-ndkATP#`h`O0E-7^K!a`SEl&;0H&D~nK_;EFjF5`X;P-rWGoEW~-He6jNz{|aKMg;-g^a#+X&^cX$I#AER#gwAXP zF~JbNpa7w?){pIU#zqw9SW!9*bZZUS(O8LQ0-=^xS{-GW#@Lx@PIY7L6aeuMEfDUu zFe?YIOhEoc&q%v6z}holAY+mR)gl!1lcDf7a-aoY@z{Z9eSeDaVs+prih~akmXH|6 znAa&0HJyQb+FT`f@w6~DmKOTS{{KrPAS{IMy2L#n6>^(ijILlQ`qi;xP4WQBO5 z#~V1>E)?J|=Jj{++XWmemWB}W#BE)_GLVm%953ny5}ngGKWqS$LZQ?mZK!~qKm?Y{ z@Pram7_Kibc7G5a0|{q!6)el`>W0*gzRKVEN?wlDEDK49{hVrf{6QiE(Fy>w=XipU z&tbYU-3FXAtT0?Z0j_d>{y4qyzyyHnaX&v_;D-dm0FJ?hLuT{q5-#lsv2OvrmGsFF z1rRgv_Y#MC@v~RI^S^GRib_Z+H@pAGu0>yA!{jcd^M4*_vc+46f8}d-wBqH$CxRzo zAeVqVggE!GiedyAWIo2kbj(?vEU3zHEa`Sv1#!GfQR*PCkHJ_@6qeD;ZNM7Q+GS6D zT2S4J#V6QYs0;8v44qrS*x@)mGkV$Sbq+>tw-VovAQ*c zo6h&PvwJ<>pQ4D-6@Xd9S6t+pdb*fBQ&Y8BUJsw@Sv=aa^y8idjEm=D2hc~Z5@_EO zN()ZRjUtq~tYki$pG3^1QjE69f>_X5c0n12uf@|ph+;=9OBtFsj74@aGdp2K|n zBFtB;68i3GMB(r`*Fo%Oq&uBpwXaVX$={MAZK zfBIehg$Z~-a4F&Me%^`2WVZhT^(JEI3bSRBg9n!~69g%<5t`=#f2#uRMcNdFM7_Yc zvPq>-Bw3!qBMKplS; zjl5QBNZNeIVZkN?J2z`DxnJHD#g zRcTXY0i{TrT!Is&Wz9bHVN1Fy%|*UjV4%y`Z;*01TF z*s-?q6Q@Aq1}qG+hHQf|^{nmSX^&Ynz&i`^7k~{18-m-BzQf1>c)i}EDNXkm(l$)z zG!iSIOf)!}@oZTrm_sNic&44X<8X9(ASr3jX`fZ`A#!(Hl_tEJgzAM!?{Kq}1n#ZD z0y9`l_JpJLPZbI8Y(J-79lHvIgO)>FZ8ivJYGBYXRKUW@(BkEJ?0C8G8x;c7(_)d< zaZ5!uf0Vs&NZy5OXx(TLdnQ;04e%i-6411{N`9LK>GcFp!JMrBS2;ryv6Wps71@}9 zLW*w*#xFh6PE!R22WV|{XN0fanM%1?5s0P=powshnc;N6-NATw8ytjPI|#_G4LUr0 z|M-AaE!&Bm6cXAi_%<>XO72em!>0$4W@XdVe}uAF(;?qvz}p}Da`)Z%@B#kf(IHYj zEXcm&8K8m2NtU5H$(^iJT4&t;zqe0UOod9Qr2HBz1={?ADuxCQp{GRy5diEAo_3l( z1Lfhn5DE9gBk+3RZm^vl3D)FDu(%~q;y#-W{YX`mZa0W6Vmq`}9NPiAt{||^ND@UPE|hQKpzgbjnClo9syt#6l{eR__KeqB?ufz8hy8l@ow#Xhsf2yjo(NOss7 zWFk2RZEq6QH`i{rlsb7dIZ^b{C?q4@PO?6p5Vqe@m(W{!?sXi9o%OK8#Xgoy1VhlBb-TCn&{D z4@TQuDiM4oi&5nMqbt94QHb$Qlf&Ud`9o+01AH;0ZMB{2@)nSC5m;Iz{7uDLf3dg?I#-=${gNv&Mt6T(g%!+OkX^0d54=S zhzqb-pOEBsTFF-(4{j~fTU0989nsXUv}WS54`Nx!!N?x+ZZKNboIf&E@l22}W`Z)U zC3a0|RaJy|-IyF;Zp~D*+gBT8f9f>9P146L+vhOBirs<_HXNV=J0fP0+5M^L-Vf{eeLs_Nn~sefbn2L$FiHnQhvRXg1|G?1lCr3lQi2CTX(^*7w`s5x zF$D55Tg-k{y}S;SdY0x5PC_t^HDdK1>u|v_3?_P+Rz>}Pk8F^1vSK;1e}M9nkzEU^x8S4xT9a51(KeIc4Kj351BWAIY`WtdUi9WLgq6-HBGnawP z1}Kv_sSXx`aT1_iPU3aeiBqYh?A@x^vHif2IFnqdAAefp3&B~=bFp}Ry>O1@DqC2d zGp=E0v-olOdRtzuloQLk+;r=5Ll13TmX|-j{>P_ZTQ|cXxL8PLjic|c2uzwW*h;WW zEmkA2*94~Q!m`|Q4`o=crH6GnL48Y5Q>ukv#x6!sH`TjK>6T?fv=#^YE#DXGmX_DB zI@Z;%MSoiz!`tI^;4Jd{wkzv9TJDSbraBb6z=|B7F12A2xZ`y8DMg`S8fXg;KXJoT zh%}SHZ2)?o5J$$OGLMVHGA;C29B`mumn-Akpv*Bx3)sn-ks5F-W_0)r1e4I5FiaQ` z$xQ1*0+K9(RHy}|P_Bm*+nHs?0b5ctEyc$WqJMf!h?<1xo+Ly!2=Q_yty_MPvU}l} z1yG@xi}L%gmn{gxN+f{Wu^U_p;qSb=v6@Cyn4 zVbsLSCafx!$=;ykR{=tdAbP~5U4cXqkFLE(GLCC+Kg~z zz<(J4D>XIY30WB!BN*KPnS zeYhFVxd~PcGL(4;#hY{}&a6v>VskbWf1gk*gfR-mdG0=O2T#4--1p+IGlU~ac%U8W9GQ0nNu)_-_b zu$$*M>uaVSYEvGLZ8_v>T@v1FB95wAW-Bnvh>}AS&mE+6}oSrM0#S==XJN+;mR#f_3>&~?xD)GGF$$$Y}3(&Gimc#c$?d$7#MsgvOFpU`G0|xGOSPp@*=y zvMOJGGd)U1O?ZNOx18og2}v=3xTAwwaL8a76%lo_FNh6nu{UAw1b;ylw(sb1$R8k# z4M2r0NJLBof2fb^=# zWJp-J@(GE?A@!~}oqwvs4ZT3asLBApF2VtI*)?Uv5f)9cFXMUpQ(ZPqAFMK#tC=vH zwgxZnYM=8t$gMk_d=Na=Ed~sQ0mBakxL#I(?})?=0~`3nM+kUZ_~3X)n-BuF6iqj@ zK|CT{U9QSqwTC*RjVLI1z=B*2S2uNW+R_KtzEpv|GDzl*_Ae>8@7ikBm&`*Hes^iI zWl>iJWI7B9dGIZ#(D{rMVY&h@ZoI;jaWwsaow6Yzl#?K@7Jus{08hQf5H?E9l3p=L zWhNFeh+yNQ*AQO7v#yU#6ZdzZtbjLW3xI(b)v(ak7#yc4usie`pjW|DtdI?`2$^m9s>Cw1 zsC^}-m;dVaAb+DZ)pUCKjW;idL+>sjNR@ktJMi0n24<-B@~b00y}Ja%Mzwk;!mqvq zoWn;EHAZ+6orL;>V}^#fq(UEY?9djiS^l*=c(KFsn*-qoRAt>%ah^7f2CIk-ew7K_ zeR!fvtnr1V^T@2{2bNPvLQI zniMyKRew9wMT>!$hT$2OfqPoD!Gm!M#lm(d6c=c%)Vlu|9@cHKG%|P~2mX z23P;GX}WzGB~S)3honW_qY*53ViNy*gALs)S;Q!NQ3MO_g+dJJDo6vr3E#$>2&G5T zg8jci%x-MUkK=|awu5ELKz%~iN$(<@#D{Yv4NKmS(sMY z;?{%iQT_(m*ezaNe0%ZY{{3Q)OJ{gxH-DZQPdUJ;FiO~kVcwhc?3Iptex#V&v=nraBZ2;jIO2>0yDRW{E*>>G$+FyjeDh6eLT0}2?G?eZq!eA+_DO$|$jn4%)Yf@Ma2QVimWa(FY)9ItAkv&=dNv5|%V{%epd9b% zmQI|rv|PhdJSJh!OWue2p)SzxLVkWd#!HHfv1Lx#N-^hn`?+WqthTGrd`(KlYg1)zrZy`nsLTVQ*)q3x@p z@qL_#c8Zvq_wo{`1Vwk%Upt^7 zG=4Crb%<@)dXSOQ*go9$-EW=!WnW<24@M+j(keg8Fx)+wYVr?AZZDI`4deYJin~-4 zA5qo&H4)CCxK_Wd(0GLI@6XJs^Wm>!PbfuR;@`N^xlD4-te)nw{E=MtqKs2Q(Bv70 zb?*K5_b#o_fAe%{C4X}HsN@xt>+0jr5I%|b<5ie^#(%e!Z@Y?|V^{iQ&<4ok>_+{B zGnXn{BSd!`XPv(D-#6*L0ZJf)|Ch@c#K?!m=zd#;s>T)S4`-^1(dGP;4fykO2CVW) zub}w3e_enxbLKDMKpe4q{g_4cd4JW0Wo26O)%ESFC|D`;l}<~RDxhpv|4goT zRd=-(d6C>U?G;ZBS3)PJz3Ho_M!HTm&Ea_Jt>?1e%%y;2OnftYb9jzQ)TX&+U$vbvv1%6gkFEauh0IwruCwloAuSdu76pr zdG1!T=8|Qqq}BAMs_hmS%QCsa*B|J*vwOSgtNIRagI>sEI=6hd{EFALl%L4$t1%5qpjW$MlB9gXj3TBK7MNw!DYz0=3m zZn5cNnfQOqF@O*$)hPdFZ;>JskjOz&hp)eSFT@N7f)%<1p-$KbVwppwWTGenhpD$Q zF@iI}MPT|RCI&9G%mz8FSFX7U8->b;jdE%a8x{E=7lLJc5chNRi=63Eskc!vJR(J^ zm1d<*$v`a4B$%A#Mft?)N|vQS7`f0;ZW*mLTZex(cjF*%AK!|M2`w+*ircn1ME4?N zdgS^?TuxD{z`@9eR0-C*F(fe8d5=6QM%*01>7?wG-(TT9+*baEj{wuD}I`>s7dDqlkwY4ohHXf=oucb#v)Am*P>>1V|=BgZ`l*pNc zjdp7M-9t{#ASa4B8~uXTF&emk=@2!2)u<5|U}1 z4VKGd-_$JAn13cleiPj@Ef`OSnDi;lQYqm#_dci!mZt$CikPZ;d)fqSjsep91QPAO zI#jjK(=MpCfK~_I46?dU9NalL2jQBf5Es1$X&!-~c3I)ifS|Y(g5^^VB4J+?z_foD zR*^>bIR_3MZ0${)vs{A>v`Y<7p_en2%9UhXsPEL|uMt(&DN73#{qDk~Ipf9jvww+d z=Ps8R|KG9Ef8ycfZ4QER?{L!3C6mg?!1Ct+n>)aY=RSEUV6zK?98^NQkPE0_STI3lb6&t{w05ElA7L=-Ao3r#&Hhb4dWbQaw83=$)cr;3?V`@^++`- zQYO<&IvNhm_OzPxs!AE=1qyUN9rx$eung6(0vk>0<+IYb>)X=?T1e~LUXCF{&zEzJ zqLk!Ai@J_#BjmfG7IR}xo%Mf@o35v4I1j6= zXWTaQxNiJY(|slij^rGr-+2+Yr~Tf)W$Vs9J_*CQ6Dpr&av~7b1~gIXKxTp+ft^JZ2@Z6L%SU>Y@wD>L(uvb(J5y_s^?YGE)`6;pdZS)NPZ_w zfkw_JL7CQmIaO^?%~5~hsqvcn@xZ3~lyWubZ@mnMd>|}s3~1Q6u^VlRfQC-Z<_`<6 zdg)mP_I*3Yc4bC~kw8TB% zf-zhqD5M__#Zcv(L>6h{T;p^A6mM`YBQ;tB013eMPz$C`huD8pdd$+pbLT>`Uzsyw zbD$_yCa1c#8{2gThselg=|%sNx$WJYMwf%9gHn&WhBF1O+)sM0LlB`E5XfEMm@b&p z9KpcG?Zb}PcBUIFZM}KTmS8|}-rU*lH5pMdi3x_6EEGrZ)hq=AgdjIe)tYMS1qVAx z8j%M+n2qMl6&i>!JY+TR15oGk<74?0IeQ@e0SOdmQA}bOZO(^ z0l}e`^X3$b1sz-4+13x!eEdBc(7m4o?tN3=+4g+?+j!4wO+U;}bNF{#*XoA(=c(+#);-a1#Nlt%^B+zO7G7nXc!%mse7}3o* zUBWw$-blCKXz$#l6kfWgQEiwDAqfDKKx@CUO-m#kyn5kH?T&1KxE+sLknULx-QL=J zx^E!v$@ReNkz6hY#b@Up!1vlYk0C0%i_G1SRrxe}RRIxSY4!;3F3IF#U86~r>R zricDbPk8m=pjSVCH7`EGPk6KrQr8o)Kl;P25(-F>yG$UULk5IsUrD~N?oO_pP-&uH zgX3pK^4poe!^5eG@xHULGlmK#yd49KyB~rH-TLB8okvK=yP3|=A=WBPP%6)oAAAT? zsSnv|OrD|kf>t0TlHoiJa;=L&ctqyn5|Vu7K~wy4D2Hf&>Rz}K5$T5h44DCMx-Td6 zd<++O8ffui-O|vz>4}H3$KaEr&4q@pK`fgO==LB8YiNw95zAd3S7o+z$;sw{81%@2 z2~Q6SF`hRbEaXbJO0V~p?!qZ$J?PrBhskP-;I>E^Qjo^b8j?1&fH}{-x$|kMn_&(ldMHm*2w(DbumqRyy;+)9&PH^)0(AS+$3C(n_7EubS zOHIXQcRCzE|39oRQTtseVLM+YVcog)%vgH3npY;j(u&J;EXOB$!Nr4r2g=&me6hsC z*1?(MnNu>J4HIdqi^`#hbLH8r2`I<-iGbKsx%rZIKnek%ma~F6x`#@87!1z)K-8me zdN-7R_>gpi4E}Mzq5~q_&w!{30wU58h-f6*WT3>rh%eM$Fh%TQvQiZDt^0Kgby*hfhj9spAc5#7 z&`YkNB)TW2-+BxBv~)8+J;v8~>ANx>0t#G!zcuxidJvwEC&okd;8ervVIBRajmbCy z&!1_qaX{0eZAN=jhL%*8xm_Cn-DB-4dGvC60+y94^S!=yuq0u;#HL23~uxil3B z#zO7iKTqsclOfp?v-iMa1pzjffy@Rdf9+arZyUK0{;praZA&wYT+7~-WJ_Kf1r8_>uejuJI2_K)!`TGulvTl5<$S=e zS0T$gsc18PlS&lvn^k6vIaawye^I55M^!)*Tu>$QC^)B_MTZ9yXOmUF6mYhfe`8Zjpc2C$)0bw8(A;B*S&w{s> z7igl;WzfVVbZ!(xS}IUx6gr_vfARvZc#{dzke(tlK%DBLpv!U$1ez>dJ=Us95BMtq zG7DYF1ydDS97PBPjfe(WG>SBwA}31)LW9whKuk`!dqpu|;f$f2!89jD#l=y`jAIw! z*sAD6b{u*X#Rd*45_rhb#V8wvW>Q^?VI)<%oK^C25;%n9p*6^jM#|pLmeB(~xdhQL z+(CNa9}J6CgbD1i4q-z~f3Q39q&Q+H1cT&kzfe0F|)*38w5tMiMa=F=;u$!hOkLXvqiUd}Lrf9}=mWHvn*FB|pZ z;E&={7NNj0>@2;q^qsZef$rzo`7V;9`S|LpIalUz{AGbXzd!o%lRmuu^5t|qor)|+ zmy?CUzgDI{sJ}Jy1(sGpI~Z;8DTY^GrI)vs6M<>jIotFJdx zlMXt(Ty4A6_#t#Xe=;AhPnY#oI^D<|PUef{+spAB_BS%`#;cb+GJl_(gKG_dRlmaE zpjn*FCs(2=hl8#CZ^ny8#t@TS+wI3@Guq_4PpC`&eDb861axoOOWoSm8PH&fOyZ`Ww6LwC;S-DLVJbUT}$ zH}e_`+==u>XgNeE~76!aAY9M_YYLlywLXbgm8a<`8G?TK~oivaDp}n-O`rVSX3{q4DZP z>>}N~0I#?S%7^{VzDtK>4rL-tAl`7?lQxh>_Ia4t+oB1s6$6Z$c5rsED~k|`37P?z z9wcVOFaeLSSigfb3yvjZ#~tf?s44-+I`6aq+g(gc(H1BFXbbEcUDwXABj;`{Fw6B| zt8D_0^X&-WT(H}Wd(CQxSY}8YmKkUu>=Ly8f9!AzTHOV=`Xs*_xRvjLTQLrYTQmUV zRD`u1Z^bkmZ&7@_C{#L<#Mlw!9tfIgLy)*3NPfH^+*Jv8HL@Ln;#zr!WM}@mA0}in ze@FXKQZch>W0t?o%<^*H0DB^snG3kASxml}Mf0_p?#JmdkTpLWVD*`6rU?QOQ$X;K zI+9d4Si3^|K*YEX5kuS$CiLi}YLIl!aVK3Mrz7)jI$T@)I*ePVt5BG!Cg{8^+xLiJ zu~aK*Fg@BcJ@+zlH}Ce*VmFI-va2~ne^_y$Y|Y}`{NB&vtb8t;DSZ=RN~Oy_DUYYk zJe~&U@f7}_$A?xcIz@t2PFyb%6uVv|D0w|Z=K+a4xSk{(NWnB5Qse=7Jlbv^?_@2G z!}E9^kjD$(tCA-`n_LDQPUuJ?FSml^;fb8xT_TSzNbLyn6YflW)5_YnUo>tU39Jp0S+bQX{&2NTi05;paNV5g;lLJdFcdt=eSZ$XMhkWX!iJ z?>+l^Bf0is7r3cIDv^Y!mJoxSft(6x3fHHtYkA=sos)%DXR?396)yi{44_W`MC9i*l`L2BxQ$^-+pHt(d1E@`5jWPsdSzN+n{ z1Lk#wchfo6iNoWOX%CF{e_(14nci2r>><-ll$nr1{F6}T3b}MpCiBobCYSxrzDws4 z5*ot*;QqU48_<$FWgEe39*ijfcEUIyH|4Bdavy5E3%e|IL5&(LAp1*+#8 zxJkM8JK9iNmSXXmEt3rcZ%ovFy?*u^Q{H`J%D=xG6B1PqmGdnamj5)c4Gh!GH`6;X zOkw@IDzygng!@713KH%Sgf|4C4MEED6&xwV!39V1?)eIi6w=^(3i%=5-n+G6_8mcn z|91rPx0l)f0%0;{0SJ>J*%Ok`7Xdeyfy@Rdf3;ZOkK?uxe!suM$de458S#fiDMbsk zX;Pp_3pCk>1i3!QGQBIDEcqxZcbmVyL(Wi^ys~evMPF=+qK4lLXTF)?Umo6k{k_gM zoU<~^#OC3+(PE?1lBJ4o9uAvdlb>AmXtq14vxI-M-DPQ-)ct8Id9rW1%JsIXT72F1 zfAG(fx@w!>E7$bh_TLYG|N47gZg|SdwB%lVy4i`8Wo3raAD+ByDU)|8S9WmzK_vt2 z3G>a+x0N#kJ~>>j67#959nM*E7;AID2Uy1wXSX~VYd2b2-5GO;EB0GaB+oeS;_e?t zW1mTaafn-FbKEkQtWYK354iuerd#1he{lud?vzr=-MC?o8|ypfrhR*K3~~v7|-YJ4#4!5>|D1EXg;h#oBx4$O-*J`~kQ&F{p042ktf4ra*c>=epM>i~ikaaQwQVoMSg-u#>rQRZrr+|b7 z(>d#6an4#W1raHj&Pd(;nm_nsmVoB6?3PP#bcy1QO8`-(8Q;v7RUJV#ZFBOBXcl%d zwu|QdZJXsu1$+s*lQFxVNUT}q2VUfi7vf7u2Mx7g^qnkoCS(RSD45Q(e;2$ih}S#M z>f_1SrjDFm_gg6dc`gF-uBK1SCuf0yzkuWw_uN|d-dtgf`$L39VFSMCyY?AJE`A3n zz?NXY?1IA26V=(q4DpM~U42WQ6&~vCER>xqhXwi&q)DSR@kfe|b3wTup(|+87TZ zfn)kMb>pig)Jc)%+H0N3oU^G6t$9G`00t^fA^L!Pzl3;AHc3Nuy zXRCg`;hd#VUjXnIe*l={$-j^V#g^t1&%aBvROax@so;YXfwNqm%q8z2d%nn~fuf@0 z+Yp~0DeX+()_pskI`WyLg}Q!44WZI`j#;%v$%;}fvJjw!0*_ynsaWr;6z~mW>u?+* z8~%~K{b;3(SDaugpQu0?OjPtK`n!LHijo-P<(xrGWh=A=e~77DQ~8(z=JrK;o&l-| zVKC>gbV5X82WQ867YkQb%6!S{01{KCN`l>iT71mG7Vo%JADMi4mnkqK05ykW(wFaMAG79_ZQfeqBRW2y; zL-kz>5~9KUe_UkAw@`kz=2PQ*f$@wL#9y1C9*5yh1p#6+F>@PH@=(a4Bp|zIobzYr z{~t*;Pm#9sr|oBBzvsse#fXrELHCdx;zBAEf+W+QjEhgf?fh3OqPRZ=9SZl8AMBB# zyg7K1C^1D8vb&>UZfve{A>z7CF_Auwv?J!P@8`FgY~8 z8=MM$CZg}a#L+=wcvb&f_t|fP#qY zErH;4t^ATDy_#A_ZD%BX0~^;gS8`e;DBSAQn} zq3k$aCjEarp(yDpA{a#$#fw@BRy3ecf8m&LQ$|%0eq+tKtyH2xRl zI52TZCGc?e)o#dp_)Ioh2_Dmc1dIJTXqR5GNbJ^ccEm1P`X-IaB+}{n?HpcE&@CkO zmUv+iu;wf)vSl;tuqyXX5O4J$ekz}ejbYLM+!ldW8%r@ zr|)gj!(o9)s<1SZVc1q`U9(Ro z$9|~CQ|nl$@BD}Im8;vGE`zBtqgVRIbSE>8rehVbG!W>W4UdC4pIGK#M&qnsSD9X| zOC?d3R=lnU6@SND%hwu4|P8|u07yr{qP~Vw>*JO+FyDY)63ql%d>sYQIXzI|yaMHL?l@3luJrjxnISix+ zz#(>&fswE3)ZLM* z-;>Xnz?2S4t~T<4dvv310Rd&E(e0#xC?HeAsDC*CW)g=0%?;yzk3J3S4|R8-2|lol6YzEemlsfnYrU8?G5Uq08CE?s2Z7 zUIqK1cP`vA8}{D$6=3&!$8(svgB_%wT^zu3V>N$z`}c3({22ucKZ7E8^Xm4m@34pm z5`Xl-tQ{CMkMrQwe2TF50PC&+65W2}hF`oD3O>)qar-cJ+$!M0(WJ{r&%|zs0V4`P zYG4n3zD#ioW(dD9fn%s*_@&d=B9gF)27;#68iER9hR@xBI|j>9z>f7;_Z==ZO_Sgj zk%tQKkah6Uk*jWMTf;!bszfu?*YJ+6wSV@*C~8O_P2@mmrODCW%A8MIr{5V2eFtw} z4vDY=G(D9Zo2Kqq#4dKI2<|3|vhN9k3RDAO}&JL`feJnA7hkF z16#_rp`isT3#@a?cp~?RVzZ6u&}?iWAcPDL=amf)e#ec&v>&H|=mypomQQmGE`Q!X z`43DhC9$yzLh=)Qf@TMUUz_7`ut$SCPUB|5U(hNPE_JpHm#HeFteoTO&p-aW6;wf} z$mXEB?*-4BBmyEv5hY2oHo-r@T6!~H>nJW}uD~t~JiuLJ$$2OYp0LW(5*t(?=&MW& zq;l8>itnKtVIR2ffUM5d=x;MW>vN`ht-+4pVRcUy=|3ILnRzJN#_M>?Hh`v(Mh5-1*IW{_*e z5Q)mD0&A~!>9dGm=+;FUXx_&?Fe}HKNTI2~;EKT?TL>1o*|+b$ee;6L52t$eSt#Os zvk*{hWC%km@<#ywyKKEE>(xS%m*LJPmgroW?T0Oi4kw!zRWlfpLkL>?_rSdm-MzVI>1 z`xwNDjs+(m^Um%s8p}v;14K6ccL3zAa4O``5K7@TY6nC#97_Sk-f(Qg%hJfd-hmwH zXhDOwIF=nOkW0+ruz%@f&YqcIoh*};Vi_1}-e8iR&NExVLzx2-dKq~&r;W%>GsI(0 zM1q3uaV91nTO`oCkxwE`23idN;JxZ2M}ah$vD0~OFQ4;PhH&Y(cY}P%$Qe4@d?QiA ziu7d@>69l=*u?BPoA_>FF&sq0qWhL6K4ScR{Wn!e8i=Br=b^T8Y>KYC>d!n{NpT;?1Q0QRd^@CbI{FME^d_z z6NrmX(`#A`buv5+{^`zo{LOS@8H34zOMiD*!6!v_Eub7MY`z3dRd$tD z1$!(B1=f8=D)R}f%-`>@h#`aWXt|_!=o5CQB7LE#P+8=f@S8a|xKwXHQZnGkwQG(H zU(Fo3oPRm;#*uE5YyJ}PWM0?D$*U__ znL9~N#t&jdn}by~Hk`A?+{&&G3TIOfi_VQTU9O%P3^N+fY@tS{G4uHW?B-i6mZrOK z^zHz{eMpyy8j4L*JLa-I=it!)9_!Y}%WRQaz<+YnaN)k61{S}ZS-#_;RVuiAFK&{Q z9i(KXE<83w-<|85Y21n>l6gr%yT81wFTZL2^epw9_=cUCnggpPW`YGl1y>NOTry6s zSX`yVe#jIF>*!_^@INniVP2MCk%7g*{!T;$`Qa)zm}Pz!F^y8@{(XWNZkb2A((65E zzJG&ItLdZ_!Eu=*>HJx0;YLHb(bc)~7eQ!TO=I&IeeEMOjeKZNSPuN8<}P= z%RWg19ae&X&Z;Obu5vmp+yUW+(uDU$SYD=yUQHwUB1)v^a+#7lfri^_=j8m=bovD{ zlBNNPc`rc35hW=WlmrB3x42(o?vXn^;wXnt$APcKj+?F$k$x>JmIHeO6sP6VV1Mu` zF0Ciy``Je61tTeW2RL{cz;4?+Xbkp6@`Q&mAa`jx%Tchy5$25cat7B^hil)NONXI9 zJK4azhzfO;`?wz{p{3F1@j01BuE$#!@mxo$n4R0p&51|xygXQ2q7v5EQW{t>#GX2y zigi@#>Nx|dR9^;E_@tOMpm| z1IwAwX9QFf1BY5hj^%>WINe?_P`Nbu@_J`>7V9)+b@WOcb1or`v(M}wOs7&$H>b{G zuN_}V;9mW96V^Gnp#`e-Z=kxk;72H2>{0zfRzPk%Uc(xfG|qXKmIWMewtvP96kXyq z*i{*pSh}>_)RXQz)HzexKx}~%iAg_)Rc+x1S%;OS*!W+2)p_J zKd?C1R?4~jmjsA00*YYYOc0!ba=pY!E2iftX+IKYrP0dIkcT9$B2|5vJA`SHfcGm_ z;YTP0(8A@TIBbeMXkrg|T>L9`BaPxQ@o9SLz@WbEBk=!%(&8BoEQuBCYvm1=9Ht+y z{K9xu3hdw+E(w@`A5GqhDW7}r%ijDyCiKbWlR{f|Vd7+Mi9{v6Q-z7T{J)q=vGc1} zw_p7autWRdlOfp?lhfuGmw?O$DU%cDCkf>^+h5-q4k^i#L+4(9XQQ@pR#j2;dK(Lo zM{lH6eK&e)qlZC{wElWlrc;(aj2dL;8R2(2`dwBIes$W$yo{9DYct5PQDO6;8&tB5 zi?ojJw^bf#v;A}T{?$DfD|fSkCs|fPfX>^`A3u}ORZOf*vb+c~KZ1dxju_dIV|znw zo+hj+{)JZYL@OtMt&k750gh>pF#CC>lGTY2 zvkw>kk}8&D6%S%RfRCbxWZ&b0M|*uXwEDJ1y6NP&<#1M(s7-&ilky@{cQ`s`|40OP z^n&@51wyY6w6Klr6)_*+jH^gB@@%~nh=*kZ<>XCWP_;5mo*{dqWcx@edhK+8P7H7p zS0br+=5tw4WLRZ+o|7-QI2jdp!!~A6Wh^p!3zhcG*%%bXNOIk9>J=6wi-;_zPLEK1 zWm!hMpiMql-IMF+9e=d&wAU*qNC+k$*+zjCp&I(mpQa(bE~YmU6+Jpj=!T6aqcEFU z86A`!)MPN7Srv^+8d}l8fq=yw5;M^f;p9wdIvtQS5@ZeWrlTCM_QOI?viG)(JRON@ zyT9-n=c0-}>7J4wKR|>n@zwXq$Oh9*TOT{sxAsLV`&K< zDy;C5MVDjOpuHn;IxnHVgT0{Ya>SZ&ADIsY4IuHn-rP%baIwSMQeu>9&sbJot!r^b zz9{MC6n4NF=GaHQs6Fa)-_qKb2z_9^-wIv26UZWoKRL8qW7M28@LT&|Itu8OeXDM@ zOU9uS2==V8aeuxRDv~^_g3M31T3?z7Hn%2D#!pZkWPPcVY_5~+X$%j&9KUSob`ZU3 zRIiK-VL=po;wY*bDqV~oKbKzB_@Ht4JmRECW|zUyI<1-Oz6{1%mWoXbjWsVB`TpVU z?%gM>mK2lsNOfc6cu=(TH3#gy(F4)sgPU0TJkfVL=YMczj#WHKm!b3emP=WZW;2Iyb5$^x-Zod~Fw*&duvX;3T7pBpfG+3m2aq~DC&cF?^nCh!SjIo*h34`G zeB?0QDoAveh`c64q@(8ZWvDYKa(nJ4v|Dga-IXMa%Q{Ge>kQOZ)9iD+_~ zOMDe4&wnxV*{$KdKA$>C%d6>K77i1Di51dV=dS>yk^djHoYYd;xV{_)VU2@OTOan< zbC@Hh3oD<7c`&+EXK+OYFRxR*OiRWixOHtGbYQ1pIE3A7aC|x!SU?{+8{2*JBLhk6 zAu2><7{%IdCu5kl-d(1MU_wvT|D=_RZP?% z9&vmWVMwnAG}1-XyCC-v?L>mmbNuScWs*i9<#;Bvl}ULD-Z&IF^!foO8A-)Z>_a!M z3}Rm*JIZ^|;W&js*RF%`z55q9Yukk`XdeMf4ZcG`rBIXa>n#$D_dVQ)zLG!@h8Kj$ zYUW=M^OG*@B!97>S#}f4a*?oNo?tUXA^jeA&gxN%>4Ay?+j#L|iG+$^p z4G<@?mqXWgv{}H!85^S}#4#mj9uR_5ul5s3oaCr_A|9bz_Mu}Ekcn%a)ZqRVSj9P5 zaMbN2Axrw~@Bxch8m|IFsTJ&V5|?glH6cf+eZ)IOg_F_j7y@6qlk4m@f4T7+SLgsl zJuElaCn#(newq|qQA6_feDcv57dP--Q}8Yt1taaBRWI*^TOrT*LihftsaG}_|q zyEQwCq|Ts7cmdbI7s+qiD#Nnn0R6{s;Cy)p=r8n%4bPE1Oy#*)9^=TkbZ`T1Of>)k z316O&Yeaa3W}d^rHJbq*M4WYSJXiA8fKyZbmvhW6QLRY4a-Vxv6CU$6SMd2UVZ{NAeVv61}J}Z zR84Q&FbuutSNJFcvunxnhjtvc0NZU?Zrcv3t=JlDsg;~&-LD@d+G$d>F%VOHPbBq3 znkEH2G->L*ZfU}rCKqj+bo1_Umse%c@<_NcBShD2tK;tLOpD~R-F=5=!?HDIb`|u~ zVRyHuA`!W$S)Ck?Ny8FWiM+0w$26;IMt&?x8|BbD*)(G< z>ExvU$wgZe+>AIi+mtorDFsk@bk5c?gAaHL)S}W1pZiULbPSuf$^)F zNT;Rgl+V+wW{m997BajO<*ZF_LzuH)OEKy1!?(LV2>PN!kz|zSqN-4aGcAAMhrAoT zN}jhxkT}w$>EDP&Mb4WG=gi&dn1NbQY60eE}v86%lK5DXtEy;sZnVuh9)a5D2s%CZ3`c;xh-D@$#(8F1-mIZg4L zubM>tU7YN21i0X_rJ*AQWIv4Bqw`lmIgV6V`7t)}c?IEumd#ojMxB4rxC~ub3<}Jv zi3>i=5b8z^gB=P-)G6sV<|X*7mJ!FJzd2Bi2fA*Fb%;w&;)Ivm=z^i7n{@0kKw-~x zX`bzSP;OHVgh{#q$+r^?%g2*)I!y649JI(qA!wKm#@f8%6%<&DykQ(Gq;=r#z8rS{ z0d>_}{R(AnWOH89~J0jRm3Ct)J^ zRO{5waxv3f%v9hh1$Zxli!ZK!0c-|`MRz8=01OALaIUu_Q{!b|5QKvb<^Yahj+bMm zF`;M`OHQSwa)1g9CgfX5KlMc6oZH>o)ALC5UgqEmDL}9qhY13xT6hKvI^ZzoJFauj z66<|b%A($>G0fP83QoFWntGLwNl9b6VDW3yk0Z+^-Z1ec>eg81V2}}is9f!_y??qW zdOJ6EmIJKzgPD( zh4xZ#IyZ7G+^`EPZQCwh~OCVFm)B@{7s>PCaWHK zW*zgfYZ-x<1DWI~)8D3-&IR1XJz(pRnb4tKoB+UC?BA61v&^GVnOZOc7u_tC8as5R!LAOPraAY)q*DC9NFAs~fPChvED$c#fZR(` z1V88U20{xEiu%Wb%H3`cS|fl89Ml3rpcb-V*Hiy^T9;Iu87Q{TA}0Zdq#&>H!b2B- zQJ@4l0h8kI9n*7vOstO3a8{!zryjNbhpt%dfQfZS0amI_NYhQQ;5R#N^Zr5V3GZ`*jy$%Z1 zyI17UH<+n3pk9~3fi$&5ZWJ$48_sY(j}i`OBjR(3#Svy}{BPw5hN3uHCIa1xD z+>b0A5B=4D@`%5-A+>6Obm++u!*HF%p<4;(#`&AwYxu!@i73rjdn^07z}JgNN5I=} z4#9~SS^MWm0UWBYI7b}4c@9c0vb}s-0E_#19_@U3(-5q!scLory{&=Bxq!ocmbNPb ztU~r~c`}UlZvzhU6}O358Ff|>e&gW(vZ*2Nun&xXQvHT6LIayb>HqAlqm?hlHw$pW zr#)Zy*2u2d!;mBoW2*+SAH;fv&1k~bdYpQXIK2C2s zeH`y@m;pw~zGA~rWy=jybR^!GEQS-#XTn$QGIGdgWQ}|PhxsrTEpqly^FKZ`<$p9i zy>}FU3NCdYJ{Xrk`xikkxULQ3FqPvp5Z;Kfg{ix;zBYu6)C{)zmN8WTsc?`vDCgFI zi^&&t)}TCkbP#NewajtV*h$Ez(|3%UsDkqn0c2_$M=(_~;8G5+zwA{3`j9wrEnrkG zr$sP24t;lSq)V29uA^IXeXGH!ISez<8y`*(S?s4l#`;z2+Tniz1TU1wmtmFx6St1N z0dG11F_(eN1}L{C_yKnU0g;!U`T>Z4(n?b0!j8h=EFNF4bV@u3#jke2 zeP9cQ9$d0A2TnU9Xcqg;iN|`RIdHokcXq~v^8U;nMdSutqX_KrD)xvVE!E6pJ{3G< zOgsU7A>E|Tay20Ob)0)fGo&+r5P@m6w>H*ksJqGOZJB)-bM0PKt%fHXwb8|(nsI`{HMCsRph57@ed7gv_tTHx z{OfxW+Vhve1O`hF340!YN830sT9zkLpkcu%h-Nz>K(_bIE;MY)Z=5gX7l!NhC4ri` zDZap86<^c}yX+No#oNZzu?*IMHf!7YBPnQsdy`_odwmul-@4_JJQ(dG!Q!;1nmi(? z%TB~M)I;Eo#VLJlPCl22i;s!@RwAz8*^~HIBJ-_;X`$4yv#~#aI3^hB;0}?_^luTe zfm0*<$$d!+F|=HtPY;@^SOR&m?oAVw2hA+_zNeg7oj=}~=+C4cQ zoyk7HbgYLomq>Z=RhlZAtcT>g7})}z>qVXjo2d{2s{vHsOP&7?f_)sAi!(BBE{f%N z=|*soO89Ht0DT630T`u&79j@l8Sc)rXNz4r=7!?}=dr^(32Gg7*e9aB35In7zc~pX zPR8v<+t5=QCq7THi{9Apwd2N~njWS680~Mifi~$#UR?Lf4$8M5Uv#@^x;eC^xi5Wl zzeIJiYOkc1|EcE)EYo!af{I}VK^d`1&nkj{d!Y(Vb&@B4e%)7c!<&FbBjJlVEX#On ztIZ3m@=r&%?%*o*X4L`>LW#Ir0FLI*+d_$p+>)QTMvQ{P^N3}S_On-pdE&X~9LF1- zOL#uSsaN{zUAu%)qWlU~MJ%p!{Ka1o@J5=81|CN?N-7nmkRTfy?cO1yb^q@M%LTF$ zld+-;;Mcc*Juv(<87Q|jDc?Ri2+!jUo-1nFxjiahpPV9DAf}S1tPtgS4?`b|Nad;o zBX$5?Y~=u)?<$|hNf@W)mpdSf^F@CSMu^)YPq&69uaw2wEAY+VxkDLNW%0!x$fAse zcaGZX>Yc>P$`HEVCGX<@nRn?b@8T-=Po4sQB#@DRk8&6`<8XC6lz{iT`hbV|uCA(p z>KA{xu1V!}yjJ6lH(GwuL`W3_-}hpiZ7to65sx%Cjx5z#MV{&64Nv zhz77YGu2&2+dt9E0HHu7gfhenUgl2vv2HNZbwhJ{$-9QbZxIon&4H zj$ztJvjNJ_f#b^@BVgw_a|P9WZ0Ks zmH`vB`2w;E0Wg<=%myfb?OSbg+cpyZu3v#~ZRRe-`vT}>I+Mi7HFL?Od6~9%nS4-W z##ZY{t|aHBzy6*D0g96CN=bZ|nbhNVR3ll8PR@lh* zJyqIhLck@1{_to^vbjF!uyLqZB;u+Pe5LR=@(IpT2G<^arBy(e zcyuqCjIw+%Eak!?OQ@O9!&)a;L>wpZBH!aMGk8LtrJz~jh)c?jh&bfXtuU4&EQdMz zSUWDC9839s4Gz12pdk)7w3#IsfJP(!5iHszv?*{*dyU_~LG6u8qg%H|^7)6;R>=GF z*=i)8oxNJ+OTMW`^8R$OT-`k$F9eO`!|_`Fd3v}yUgnXg#M4oJ{h(b=7Sq$!e1T9> z-Tgb`Wy{ZSCvFh}GXyrTKfBz9?q&TpD14DIfiBlI_;=;Bii05rfQnlm- z4}gY;fN$VYg(&bWnGl*-?;4i7JLuxZ7M-gi6Zxj^EH9Tl*~qtB zMctmw=EG6-a60=917f~7Y!@$h*yxw?2l+tWeW7uoUXJ9`cCtcU22q8%Tod94V+8rH z;oPbNqEIL3-4?fQ3HeOOf6SlHg**`7zMdYPE!t)>K3z@cvnJdSFr`>?AYM3?2cM9C zzx?|@0`q0?7z>z&XJ;oTFE7(GgnBW-VpeO^4qY8g6Oivc1{@*F>?jxm2Fb#^*eJ~Q zf2xc*7XYO(NGCh>Fzl2!JN0;0*hdXx-_!1D0aO|rw)FCx$6mS*^rN-v-nef#L)mhH ze$v21<$|+QRSP+N)hC?&>IKJv*7bsa3o!K^e$rV68{{vKU;WDA#5O#5!w63I&wgCY zC(l}hnvg#p+{b+1zF�=>2hg)Q;p`G^3rZc%m;8`qOqfKU?siV1ScvJ!%i9<2&>B zB1bjBqL47Nq6iG16|jXFW*qK8NBf22h8~LLkpXP7OOK*$g55(8ff&smdJgk{>>l=! zPK|;icj@^Q8n=fUCIAEAw^L6$j3c*G&mmnQ>HN8#fiD<-16wu*Sa4UN7WpuGy;Dzn zWHG&mo^=hQr%OiDAj-Fg)^KE8KAJX0AR}L&K5JYAb8cJ&^-<%ZOB6^ld4a&T@cN)T z+j8z&%!`BWT(5mOQ#prn?%MQ!$q5PKAR!qf9$xtn;*l3|0LKk4;wUO4qE1)+qT*ew8&~97I)!E_sTzWyfwRR z@mFVy^>BGISjJ*G6*KLBk^zOmeSJy4Y(a3Xw=sCo`+=SfJqA5$r;axm`O)swGaPf_ z6OwCmOuAi^Y2hKQ()oP4jdc|-GCwQR#`BpresZP_TN(21q8&4F@$IAW>hxs3I+?x_ zZ!s_%_jhr;TAePxlk!dfsF^R0Zsb-Ro=w`#w@wdVi&x{xZ|&@Vu#|A46pyet7_VCK z?ZJ0OVRdDVG0H`+ZYuYUQs3OTh?MCG6nW>-lP3p1{q3Orb^O!Wv+-;>WN6fYpfTQ` zBV?G{%U!TR^4O95*Z56)aoH%~PVQ52Q!A|PZZiD9A{3!utbN&Opy7)t>tN!@D-5-k zpu+aBua}uq+~j|Mb}qUx^yTt&JZUjE%2RgbN&9-$NsH;xF&yjV@rTpnc822RAMIi; z=d)I>-pvsMvi<#Re1c?%u}VSSl?U>k2v$B2f#gH^2q7XL3nmvtwDOsJE>e(Vky6iz zSb4O$9i6m%`E1p``H6)`WlHVyPCox>P%dSgJ)> z@iMEsI2BCCcVdl7+@is)E zcnh%@@eX3C`~%aRoyfz1S^PD}O6cV;d05_(mDg6rg<%$?!~2M_+P z7L{{$@gFyB;72}uJ&MozqB;Qvc10k1Dc|UNr-s2rZu7$u7`&U*Y&j*K3omV{rqrU>;;SI_!igHgP5J$uye?A9ldN|YVUku?4Q)cr07MSriem!7+ z<{_F>lJC#L*S$+14X1mg;Y^P-ob8c>ol|gT(X;lGH@0n?6Wg9>VjC0Nd1Ko)CKKDX zt%+^hC*P^>{HxB@soHy0ch$bw7pqpS>h93JQ} zE%!z*F|{0B#ZGoa<2#mftsW~*7koQdV?kjn027(OXM;8WlCP5!l{$>oqcq_R0s8_F z1PX+>-rZV<&=_#1GyT&g$43f_3E5*7R2Uc)Ibvi!r4wLnKJZg>X*T9A^la)y_)ND`2e9PPcl!D2!Y zgVPuGFjr{*GFI#FF%tZ>^t`cJgn(q))kjRD3TymiBs~8(ZZJ1!ZeUF_?$nt9h--kh5eRfcjs^ zm36m3sg+OtjgHe*VEGee^39cL?&WA9IKd-&pM+RuAnjyG?t54U2)RO3nyt%xKR`ED z?n=?2-f0GN1iveCb&aOuWlmn>DJW9;nlx2PW;%rvuLPq0$(F`Ysmk4fvM!^l2BsTK z(=~Ow&-L({v_TbIgvj4968DuVw5Ef1NStt)6|@HeNj1qndr*f~m#X$giw?qFRs0uJ zUF|x2>T~;UC-ySkyVRnhh4&|V;@8WZShAqNkpfHQ1JDa+ujzXlX>0K+U^&zCT<|yB z>V_vJJLuhvWZyMIjN6{o1n96AsMaz!yZ~5b=-5@otmhxG8LGSoTUC(_NV+NAM3G_E z50@FQ8U1IppuFl`v>@H{D{&$+140PL3AU?Zed4U){rBpBsd=|~Z&%2laA-dGl>gH$ zNiCxWz%>uz0Nf}5tXru9f`BZbhg#Xg(T&cY@5+c03O>Ej7w(1JTCOhd_)OyAPEiol zi^~s+ga$t*t^6LisW3$c%bPPeWn%MdSOg( zpPpYY{emvviffsQZ7yJ09x(j&IMGJiSaQr$Os0VAMLNXS?5ALB#b4M@!*jOTf4?QI zWUX<20ivBI$+x*PB(TY?G<74sT~6@}(@0TtFPtIhqV<(<=jX4tCjqk2m?4acEL;NH zrwP!#p%B^hHY-X*E`?J-@5P|@0{Gkn;k~ITNg9r5pbn`zH4Q zhL&Q8X`Tt8PF)h_CXGE@EqC){F@>J7alih{+=0XpT^4_a30^GWD*NcGMR_|+fB*%J zy_oS8_rjyDZm+NqcU+9BG3EytgHlbi4-C9Z{}eQ*_*VUI3*uuc7 z&{eXFdSdn0df5_d`tOgL;w|T$ZPjl15I=;YvUT}Mk1R;$00A^#5K};8ykuyVH))?A zd$czk@!eCP;;6_ocQ4ru&oU-}uLl5_({-Sx65}BQU-Azhl=5H}1a|?X)XqH@IS?Ky zxXmfp9SY@Mc&e;QXI|}50Xpe}WI7r6YVJ=c9T{Z{iKH9Wlzfh1M`bDc`38(h?EsO1 zo|&}M)0rlU+zFh0@=LGk&*~POBQXG*`7lG>JAaSJVGHzk!m?*#LlabYYXig ze%c>VD$oaasYwSLbY&F_r7$q=j`em#zk;W9{#cIL8V3Hew2D_NC(b&yb58jQeYnA* z96+%J!w_EZUdrC?f)!n`$RsxBD)ysd>lK8UC_A6mt0YzyqmpuWSPF19=MLa7uh^4 z*UcIT-VkKyj<*x&vxH}zx?dR0am0qd1FP~)>w#nh{vMLd9S&MWE)7K;U(k=ZLx_Z2 z8t>v7lX>G;yL8Sk=U!lCBNs$O?g@OU2R=lde3$?U1za% z5#$r`Gl{0j`5w2`7$T^!@ew59;*>~gG#r?dQ9sSB;ut+Y!&_@RV+ZkMtvV)QXmQmD zhKl&NBE(@1L5tCO*7(X@smxnJFy_W1>7DhbHXGf>An}V9(jd z0O#3C@|Jp3g1@v0o8@XbQsDF_5+IDmuKJGag?+?^@lY*dB03W19=FIEVG+*{HZ&ms zxkOI>)-e*GH1mtCXqB}r@r!H)`-{bTfLXen!dC3z{2=~5*kYF@+Iyk0|LIYs3mp*c zQW}c1RRM}T5^vBj0sP~42qjHqzX_HVPld(hA=4A*7laQ|4lp&J8i3Y3Edl6a{{Li~ z)Fw9oC2$)>cJ}l60!t_$pi{LxkonldpyciBvO3i666o$yTnC5otQl7p`8FwDz?49I z7l^#Mg!Of+^CR<&?eSmsfrPQTYU|V)l`n%i&qG^hCb^kKdl zvBZgfJ@xJFzk>sKvHI3qlZ{XSI7X9j1=Gv8FESj~=_sneK zN8@vujrx8gy*dWau-V4!tE;;en(=V#St;$t@(wkHxh!B~TMcy;b_~GfVW?i2j8c`v z)UV|d2<71Jm*DkARfa&-f7qrf*!)sIZpB;u(xN&(_p|GFId1dAsm$50!ZhOhJ#-G) zOo)yH63W)pZFc}RFi|P>`eef0BFY!9^RcG0$<(-X>MSJC_SxHAQRR63xQA1kb?NNp zeyB$#^Y7*nLp3PCV)+tfE&oXyIW7FIO!2Ku<|`KMwS&Pls=D62qtdHRK8ZLd>B*fq z5iIE`1!dj9?$m~WD09m($MH|E4!ozgP1^@yHYxk{phppEs+$J@;k)(=Rh!7v@FDTo zN~gJ?qT7i|LxUseXmB6Mf#g`RG98umEsvW0Ck@FH8p~cI&N0KvDU0|$Z0 z(6odLm%pt_z3cxj1NSWqjig8nQ3KkVimlook@GDOp@z#g>_%%ya@2EtxY7mD zMOS25mJCXd5%Q9H*7*BqzXGR7>eqf-fwHq_aYeC#K_5J#0BvF*`6^{70OF8MzL_$V+)4A>0^Xu~0L%9QIcld@}@{uelqLr?zFPEM2SThSijLA49!7P3y!5jotUT7xd2puqsgUz-+a zqFv7=;02QWEKvlR5bJVdh-8H20?kN5;(m;OYWmx3Q3c)Q{_BF7t=M}Bx#Odg4t&o= zHW2lb?{P!uko(;I-5lpDkx!6oJ&oRK84(|v70r^Dz+cb&Uo7Z6;PvT&9w4_{r<6zC zDoS0hSo$o#H8iy0KePy4PTeyhbsy-r#>CBYqz&wYD!qUy9Nwmrd1@EB2dovhC}Duu zxvQ694L(mW!~V=7hk2(aK!CEwRZJ1Ej6 z4DKj`Ac5G-kWl8A8}FI(@bM0jY|T;afS+obikv(!Fh_ zY64-aw7*CklTAyGOaf>sz0n3b#xP3Sc$ngyhW(!k86xnn18WvSywWLuJ)!)w(62(R z`S|>_t@WNX#(ZD#*UI4Lm1Vw={7kYG0`^owb#^pE=S1W+xr{*kLf8awHwPmJR7-Hx zhET(+ks(*PI?dt_pn`##6}8p{TnC-;>jGJy0>ek7g&Y38$bHz}OcIvRryA8n$Rj}g zUh0NWLhci!*inI!iQKFoS;o%lE`B1$zmKttCx*q99iF9VhJf>(vI%7AH-TY9K^*e$ z>gAf*yzgt$C7bCG0W|0D+y$|7;bx5VF;WOWSeRYO+A5%bqaq-KKXk)dyyp zbg`N%MX|xP_kHb)q0w@r6AhW;#whh~qyO1kKE+wW_{r2}v)o`5B1D0`)Dya#Ec%En zK}cUwpwT%;nb%$876$ET=Y5C_m+N$)oOAUXDhd5Xg0@uR#QdZ);i!{Nc1@iOx-6E$ z&Ay5(K&pDc_$+0G2G%brM@3MJmJj&8)U%q$&j@+pZZK6nNkY`t(wE70sbb{s*M21v zr7?yVgs(Ogq~K%NX*Z>s5P#+h8O1E0wtoufL3XPdqZe4p8eVBU|Va)RuV?(c{4)jSXq7)p9s-JC*!?}x1;}u=_ zjLGK1+S*`IVMrMf;SZXa5DTDdk5E zT2AfY=FedhRsd^D)m>wDccYEAp&58E{Uh`6$4@cr5Fwm@29-!_)|$XMo&wSuWM||h zA?StG3n-%>w}Zcya)Jxr0PYynX0t38B3?(<8*g!OuZgw!%k19Ce)Af2Zm|uf7N1#I z$jgVu7Uu3`MSTDv_H10@)M5#O>LEQLX%-SxYE zc~U6OMBtu|^cGC0OaS)!&4DTcBA$B3NQP2dS$;yX+SK^nMzI{Xo`KQwi1W&p{`ss3 z_J=)s(Zzcvh4?0$vP|21rZ@3e9wFY`O*AkAUwOcf(AdxRVgwk?W$Hb?-q&S|<(3Gp zStvZwx`S2#+6Pcc5umFC)PBUen!XSUX~@S0Itc30kFC$SD>IDMMI)akI??Gt5Hop=_@*JmS zqjvAmzh9x>f(#UVK;A|T3jKSi zhGjztO@ZkpJ%I`UX^uf-NE&<5E~o8`%LJ?3v&=Q=q(9iSZTm?B+lbM9QvLoC<X{?NN7whGJFpJUji|fR!I0MQ^X_=pR8KG0*`-J3`>lByS%{#kO4LU zyz;pwXIik|hJlH~YS}>}JQj(6Uw5~! zejw;i2Wt6L5+?v!Do+r=6<{r$S{DQe0HSZuW70~yNE`k@s|HvE>(l*7R+}Z8utysmn}K+X|6LwTT?w=mKWfi+Y0$0>T`2m6jG*#22zr3 z5*O2R&lN*!k>MPAsNw}l$ zt)NwVx&)V`0RxI$-#%kTdOEq*%LSy5H0)3SA;np!x3*nQxDL7WuOIK-);IJ#QH?ps5? z>8ah?8;skJzV4yEO7em_!YA86{{*3R&#Q3#2ZrxC_bKzj*82!njKmXP2MF1+P1*`_ ztp^M}6eT`|qb^$VQ+@S^t!SRO@)%?H9)L+km(TrkkLD|`*%43}o;t5v54QoLxm)l& z5QBJr9Y6$^6HdCv2csr(M9Z{~$CI=lyPxIS*gOs0YyeE3gse^p6mAW4U+Mf>?NO0E4dl62YCqLQWH$4{hWg%?*b=E`obZg`;Ih@xz$lX` z%CNu*(d&(>f* zP$gRNkMOl&2yi9n9&XvB39632QZSDz56@n3THjlv=EV|Ok%Q-;v|>z$EiWd22XTf~05-X< zA7Oal!XY}Ps5e1~YCJhrHf<#3vUlwz=J^p#m>(N<3ohd86?J_zmaN`xmn!mcgLu&U zwSR>YH~^YW^o#6805+7SpfSo)4zS!)>>f#gWXZdOSzr_#K=5a3JUAG7Xnz>s`vq(6 z4+GzvMBsvDk~6h6ceWsA=VbYB86NOL$I1y^vhJfwe|Bprrc-YDt#)SxT4-d%j|G~U zV+SdaE$rs>U>17sJrPl2Dw0XHlGhH`_x# zTcH(>!;J@f3!;>VKopSQo8Ma?XP(qdEMo4ANNi*t1(EL%V@UTpr7?+z83cqvnHd^{ z2UPTy#^`3GDFsR_xucfUPsP_{|D+~`bkNKnYM-LZovFR*=(T6@tI^w2JMI`aiOEJn z2Xww+vw-tFtP1VswdHY%+3PaHvTyqN{YIuqD{4vz9_#xn>?bHZzpa?frorDPi^~W4 zILij-G6UIcfoNk-$FpUb!3Zp1-j`mo#z7Mr@YAj#DW0tujT6H=&PRW9ASO^hX#yAAa|&n30E;o6+m%KFwQPK<7aGzxKS?w>n0Cx;LDN0tHUo(6thkz3m%YRo zA5g+$ac{@})6CLlrJp>;a>s3nPMJAqav{Czh@Mh#_6Q##7ytE+R+u7Vl~)qhhTqEt zpN!g`cM9q7pB+W@K;Vu$XdwjBYSecj!hq}9Hp*jciR97 z#(S1#Q@Y6cpW_0jV>*!Qr$AK(xF8tQ{?BU)gx*;q?IMs!Tnh+V(OdG%J{Kskz`CR! zhiE0t(-fB)?Je*6#qQ@l>$wNsQmVU)(U(taPY%Iso6(1-J>&J(r~TFX3-zz{oOd2y zms(B%?%~P8n;mXUHN$qdt9#?8lJ-K3_w5)sWKuKFyvA|dIClI~$ zUeC?btJrBm`I6A9qwIgD`bhhi-rj5*-CmCFY&!>=-j44P1Bo}oM5R!7PifNTO`jij z@t-h!8YDw}Tc^4H3&Hq-Y{BbLmT(>*a~O_*Ijq}_d$4MePM*%R9om%gCty}*Zq_zW z@)^yD&IlQO5)bg2WrT;>-G<;9-Gt!z9-M52=N{)$>^zuUrd{c=yncsg?=xp()}QqiBA8~sG3(|_QISO?1t6wJJq$1wWjC3jH`fQwTN z*lN9mdx09E?FI6BI+0NQXt+0Zmm9_#5PnD{#DrTgYz6WTv8BbL@QSXdZQn!NV3Ndz zsviivFkmKR8G78>ImV?zy=ma<0WctXW#GdNu|d(w@$-qaAq$9*B%;m_px1S3s>$iG zwRk9@{rG=Qbs#YrniPuGPETCt$`DK!z(b6Rb9A>> z;4>G4UIIdOZW|8FuD}|mS??3N@~ncmf1m7%?BLTz)-gZ97Q?sGqSlPixA1kkOwslJ zXdK1IWvIXd!4qIbLVrk)MYCw^H!Jjt6wC9dL0 zpnk}H)ofi{bsG{Zt+3=MJRWV}S>2C-m4SFgL1R@kl7%u%m~sZ-u4}g0b)CF+R((C* z4+1Th?cDS`GYR!3C<{MsR=qtvS?3DA2EY{o4d2h;0l$v!~BEwjVhC&cqFCAVv>7kwlRz1=4>@5WYUPlfJR|D*hJcba#W zTX)6O0@7YT3^MuvNDe><+9eYxzzyZMnwuqCN201g2{m6U#1=7{jMpkMI~b(_4|MOm z9^KD1Rxy)E3JzD|ese^8I2Yv~_LP6fqSLP(R^ETBAH~kAdpjL<_jPsV5zOei5Li(n zZ2dafoId(y!=1kE9aPSqoL^hj_Vo^anlvu1_O@SMxPJ*ICI7+d;6Yu>_fB+=-v5S5GYT~=jAOBU)F)SFK>Qy_jWb>!)SVVPo}@PnbF^L zlyxv@Jh)%@T&2#Cs&2o^D2vfq2ET(=7eOP>_l<;b{N34Oh7@^x?E>9~TB!T5K3 zectVgGR?_z7%%S$7DbnSM(G+q|1YtK9W45zykZHGPw!E$F+=Fe*05H1J`gAelJiz7 z1l6-OY7}n1rJqG?kad+iMY(bVGURmm^akcq?c>$1ssk;GRWz!`B5kXmG1B zep@TeBk?I| z*vT2BPsHaER0!H{I*R^66A876%O@u3@3TnWo1kw-u7b5NEc0^CGj%do^CAMg8=jGJj{3kQGjx!84o$epUu76i z-3`oYL{=VM(jRrf$W`><7oYbc*LaNJz(Ez1_Lgb9T1dYl{C=~Jp_ubhv287}_eQhA z@ZV8gtOT6XJ$R{m&`Vx{I>z7{*O2y}V)n5KjVs7NhhWvqadVs=9l2#chHv9Vl~md~ zjA&MHVrEL{yvDHj?F>`TY*=%<6cm)SbjFllgdFh4<41r9OoR@HkJVN1nh1L^kPlk&#Xh`Df zJO3Y=lGItshgk#vM1RJ4XlnH3+gK&5l`8iGj|lie%70&(>aK+}daw0N|FXCtRky-A znLa*<(xk(8{RR(@4KxG1j|OsrV$TMiFRzR*K;bC1xrfPf>3&(*nNI5FbJ8@zqRJMn z9&v2`IrG#4mJ)b9Ov%hIwryj}%Xo;AB_@Dll|{&?B_*x0JSQcfC>FRfz)7M|hlJSz zWmf+xO2|`_$hzuC`_Hn4FMAEx`Swzv^pLvJN`8fw-jOj6rvI9&Rz)oU8KD45ouN2h?N+psBWwq`1E?Y^_CqAoqsRd4 zMWYivvs-4^X652g|Auw~`!Z!zG=Tv>NRSY6rTum#du!=zGtc`Y0d#|hmeUn25ym>jo26ec9$%io%z(lewc z<(cVpntp9MNnDDBy~Uiuxj>$OO%AL5LLTFM<>wGt9e-MX%S7dIVz0WgZ>`FxBxcVz zj&)YdtGFsXL+l#SzwxN+(DQJcEy%bY=_s|vt3)$7O*p2~o&{mvphgF*BeoqhOoRV+iaZAFhtIfppvZ_apulu2Nh<4Tlo`Px}Ux;!K854{8-9QA6Z*6t$4WOq10N zrQMY25Kj;ioenRK)-Xq=o{}kW`8C`&aB=crjILuc(`Kd&eR;X6L#1PaPp290wXwom zQkQGF2im_4LQz_iOANS3IngY#6qn5{Etcg>kWQ}o2x092Wnv#ULM4A#3}2kv^E9pL z$GF9I(+rOaJOLv~WCLG>_+HHH#43hSU3OaFxUi>>+HG?6}L1~Agj5CNCT^+7}4vee4$ObNJ;y55NAQ5I@FhlEy z;QUD`S6$|0B!9xa`Lyn_Q8$J=EBCNyONc{n+&2`0DSpV8hGE$*_b;7IT>G^&PDAZ7 z*Yv1|8UQ%~@3%!C`V^T?fZi#`P8m0KYR%^S!%MlHwbbmGtZ{WBq1|31+)<6MTwcnl z*;6@j174taQ65-oosd8uu1-^V7)VB!$=prS>dk!Q94X0}phzK0M~N~h%jJOT-)Num zDqj7*B9c-PC4MQ=s54c&tUMNGgH*=_>yzz#7W2>Zo4}#gbgG<^Q9#g)(>X(Dxq2O` zud(_Qnvb=4VfV)zt1K$Y*kR$mSPHqk3|k&uHf+M*)jS~TI`&zQR_cg$Q5HM7VaZ%bnp4`O^4gR`oH;}>7U;6sol^}Fi9egCW zs3U`L1%AMk1fi6ipB`Cc&bvR-U+w?!A=B>3NPlURQ7edQ8S50Q%TW+47j@)Up4%}f zu)CI}n#(Qnh5ubJ*8mf|GyBA>mqXvW!4!LjpzzYfXPKdA#P&$B+UHK^>)3_jUuASE zJI3VBkIyX}s`Jw3scb`@l*$bJCQLh77Zqpuh%CK|06fhKHkwoX`WGLeNc^(7z+3B zdF`vapHERTmp&dNgY*EWWzWK=qru8g5^}C^>|>DjNUESDQ@{;QthP^=I{pV%h_nQ` z*S!v`?vy!`xx;AWYZ!3};weeeOek#{f~s0rLRCL$D!D&T5(^H21SuIpP_WTHrQlLu z6C+C#`PbwF8~YA`Fb%J;-IjxJjNlJSxlN7kiu1jC}f;_ht3`V43+mg20?05uvSyXOZ&$1baz9eKd`o@RfI_QZOTJv2UpFrCK=TNtUmumMr6y2=DL@qhNQv z`u0HdM3pyly7n$`7|GZBli>W_pmGZbiuVX)*eOSllru0tyX_w4b8bwy@(p%taA-uW zS;CihPeJBTGSTg>dA`4Y@FA*0`3C6A_vPcseDYoF7~QeB(~5IZ%cqfZHsc90`;uzh=RB-aB5sr7GkNByPBj4`krxB+KSPOFov^JBKQ@{x)2in&THE zl^_|)JNg*^bou%f&UaNBCNMl~ES4+!Nod6?8pnO95K9%hN7D3N4>|p`j_~uD1?n`) z>d8Mm&Tn{CyNO$N$0w`d>Hy8j@yeqs+R^JAYFTHy9*p-EweUQXZy?qHGkvjltwP8V(r~CoFsUc%eG&9Mr>>wsWzLYUFl!i0H6A&Nq?_PH77$Z z^W2GW64?E0mc48bjCQh9Eu4OpUY$mA?e@Bna+cye*DeTBYi=Z-{|AJ40g0?->}`AZ zJ-E~p8%F$EJ9yEyMgG_`-|F&y6;WBGFREf|(R=EEmbmTDTTAO%jFVxz2Z=XFabl$5 zJjaT?wEMb#mmGP;_jf8(T;pg_<0c;coAp{iUAN94qKEWAD3j&`-ty$`{r+gsA?7pS z?KLkd_W(DbZ`7UpnhUJ87=FXLlMV!6UDosjB<_KIjyO3g%XjNW#fBlha9$k5O5Gge z);yo#wzLSbBPeSQy%a_|wQSm9B|3ewVhx;lJ6=CZtzcml2kT(e5l`<~DjD?T9UPV6 zkG@A%LeyG~ay&mw#0dcgx$) z9>$fbdB=iqp?u!g`)jGw15#F`&5foGCd2w32hq{{%h;o9OH!wf@GF(A(>0n5lMdu1 z*rC4OJxO&j|G$%MY!q@A)Bs%+{8hSL{ zkG5;ws_pqRu+!Vwp}$k(y6-?xq$uj()O<7u^iXaah-PjZNO>QqAI!{boUA`mV@@IQ z|C7|7LiU5QB>J<`q~@GK!ej50T%T*J(yIEAQ2I@piDumfdL!rUTQ8;dok9KvqT2}( z7_;syX|>db=gCp@^b6C<8l?mzqp4kxV(g!T}l3Wphp?%-73=pRt!Wx z!ymuILLTBApgu|2Q-OI*ltx9df^df(M`=iC4b4W5o8D6#;z$hF1pX~v(TvWKY6u(^ z%Fd7a3DTBN3{^N=jtUR@{_Q6LNYS=$jUS^tMk}P*Y#G3Ykm}Le>nU9V8m1|NzzEbT zkAy?yYBHcpA-DCABy)|C7-h-hLzUBmXD8ybff>rnW}Ty&BglilQA5b!iw`?oV)bV; zo9$8$MecG%5JGX;m(KJGC4dc!azQ5vgRn9RA&7s$gz-RC1t9nHLgQT1q+Mc%WJ|PT z4<)g9?lM!RZy~h=^Uk~h$C=O^Uwo1&_6=I8_07*LyS^@qQ}O00Ivw&jJWIvHtnS2WSCW1b-TLvOG3iRG-Q!}K)Otd3s9szh+%(6vFZk@i!J?fxuix=5lEhvb zaY%FakbR%1=>j#dgvz^Z(j*XeZX-?IZG>@^3~E10Cr;M!r$EB=$^F#>z3x`OuK$;< z!1TxwX|~zs#%GlyC-h++-X7@}RkmrQrNpgxI>wo`*5Nor`cY&kd%EDnm^b^IyxO26 zL?BY`vgQd<3WR)M8g1R0=3^zHhlXFxc&(M_@%!=deH$rI@e6q`8$zj%;u_%vX^yOj zv>dFf@^S!Kpvk*GL8%J^iAI3TQi;A>EvquZJIAF*Skt1XlULB^>vCZ2)flFro){MK zbfW3*0OIpUO6ajW76H;M4F}=Rsz}6slav%wfyuFhzmd^`NA^0Mom~Q7+p|#zyb&cd zxpF(!EnmY7tJu@-ULc6mV%uGpI~IsNWUq!JNb3w*ZbbO{Ssnb>?m&7XSIj6Xq~Hf> zqtv-8NKSOCI;4{;PRDP@*x~)4tOTcASi!hdf@??$pdBljQ=Oj(=mU!5{%wf2zh^CF z-28~(KHZB%S0b<-{PYOf-P5rH=o|&E7lQ&l8U=TJm8alONS+s4i|F(GtbxQ$R2KR# zIw4d=SOElm-_L6{Ww_A}tP2qj^sYkYWq5UP^W|ik3ag#USc3$`TJ~6|)lYuqhFBx- z>=H5(=q1Lh_R1@+>=y8uWpbzbLJ;u_3Yl$V8pPQVarE{0C^FCqWPd@bEu_m`8-$WF zKR7t#5#<+E_iX9SANko*lALLzdQBo(@?Td>CF7ai4p42kYikuffNuFu6OmI%9q6ntPN<_$pwRQBo>!_X@K1nRH*L^9G1C$SE}XcPNX+~rC`bF4 z-Pl_r&?ic{Tl!;guy<dfVm*HSm(bWy-s&ySgZR6W_3e()*}czzIAA^ScJ1v)^#**S)#HFAQe(H@b71+# zI9Mz{rjuhH-+db_Ag7ynyFC}-wdXk#vX+H{Isl^|-mF zr_Sx`er}9(mxbUxrJvXF#IfY|N<8{opg^aCc=}#1=e1#+s3g0)=j7YKs@excccpf2 zOh3-z)yF}zCjX-d43#!jRd97nW7qM0Paa#Bei7S4#f%sN_`nQt=#=NafZIEwg zQ9VF`Nr~hS6(@?SrMy_B?D6aG&WE_Y{YV!n%~iT`HPC?4w!f$KDh1_JEG!CV$i_TT zRV_79OX?2`dK&qE2cwqBXK<}Mq0-A7ee4q5Ql;-8xj@&N1MVOpK!NY~p4=N<)bj=F zeMDkD5HBY+6NlB<(0{os!JXlzkl`rcDfp7?lfo296_uBz9J8kH>PnlkpUUjC*@+#% z2yDv~jYPsB!!NO|6j5=wM5?8lV+A`NfYagGqWyRDhQWY zFP=G!Q5hxk-0(}2zu4UsP0phJdTSMF!(3T=a>?S*&9RTU5DUuGKVlAwXm6>bW4N4H( zS3ty4*HLqdwu-(WbCpsP@%VeGBf>e>9>Bsv<@I~Xea4}9W)|dqD}#0vDh~{ zhKt-K5k({uvJ)b1_PiSg9Z}CBQ}6*N9%kEGs8x*dCtLkq_FmuqsN;hTkLKflTrE&X zjn!>NI1n>O0sZ&x6;U9+#X7A$Jr1ta!#xhR)WfJhPZVQ(Supz$II;HI z#ylF^jG0HJC4VsO7#mV@<2ddc+R+yT*dFDWG^Q}5W^rhrSlX*-(d~hl&)3vI(U3x1 z0-)dq166y10CK@>`(w*O80^y4jZV9ehHX~F%RsHi+*5+0*%xYdXx;l_%;F}h!4mDZ zoEgqd2VO(!EY6xn!aD+Wb9KA&i_xA~U8x+mC5)Zgvv6iu@vSZ)7iNbA5xHvqgPzP& zOMq|EX#_Ja-q3aIL&?uj(30{n{J_O%obqN!V0|cN=w8~Em>AqpDb7f-TTsMEtsr(m z4VV7lKC?a&&6VboejQB2AjCg070{%^#agmqBPCIqt9nzV&Sbb9j z8MdZRIlFQ!wlA#JPpxi9&0&ttx>&Z?#+WvrzV7X+s=BVfuUc!{Ip_VHDu)v4Ho%P& zU`t!Q!-E3&Gu76j>bq2URQA10eEE1%xju(ZcI`%uDeUyYA2OW{oYpop$A@OXFb68p z>Xl1Vh-Hkp?~hH{ap$IvOqFgDzR&lWcU)v|;@g|k3?zN7FB6Z%_@}e;o6Qj1m< zJbz5sLb&MO*Y4{jtM%zA#p8$DVducz`&!jY&XL#9IB>DBapnn77-@lX4Pic#j0OoL z4$vWN4Gt29jvuE|m%xTm+Q%JXAjbcu^k$4qQsKj~IKJ8Aw|WHCB1d+YSMUkn? zRRuAFqK=+C9HPdAk~@x%1jA4X)$Lp3wi@-JOHq{iFp|mzIy)BcA0nFxQMSJ9o1w`E zosFE-Pm)dqNbiS?Op;H8;BVcLB32L3v8jtnBh5kNLHZO z4KG;FV%M-?5n(cD+=3w#Q>4=rt6|Pdm&kKO*N0SfA2y7385k|In(EKvh^=xf>8f?m@Q1EB>_S3T{A%rYN6gJD{z7iyXBJ`UlWwohDbKQWK7E#6 zI*)x)r4`uUm6PZ{bj!UsZCJl3VgL?FvGboNdu~o)ESn*+)<=dLD#L;27gp+)jF`K^ z&2!*VY@1fjoXi=r7C>TLZ)`BoumEUi5oprrX5(l*4~`nDki@8F7ELEKKOfF4zC-#u;)YU6a1@;yF_4lIEsd?#BEOD#rI z4^=J7u~WE&@H!qP(Ihv){H1YblGxu5gB<}WYV*(xm5s>_Lvy&rgY+7m6opo0bZ1T& zJeFV$*n+Y^Y0bltkSL-~z3DJ;*eTZNl(NQ&2GiXO=Mm=39XQXLuIw_B@~eIN8BP`m zqcQ|uoDvWUgNJ!>rzF2c)I556Rcji4*^^ZxXuPX)?oJeOi*$Y7es?>CWqfwaqZ?*V ztxlHoc7Ee7S5=_tqYYXT&Q)PxMj;1%un7&EwrvMcw)hnc!>|mRuDV_JD@oPMqyBm@ zvM;$bn8|9JV&^wO7G{-X@-1)5O~ zy3rNZt}o+&Q<=jPEX-NZ0H)!)8p(+n2{)t~91VrYsRW5lVB9zE4+h8W_`d=|1ikyi zP|vp7nEGE!u7BZuq48az>8j9tMGv9SEo;Hn8q=~zerPQOI@z{VXunhFcwXqdD0CeV zx?|x5p@%2xc~$6LDD=H9^q&<5wg`hS3q$`EhEEA2cL*!vh0!0t1>q~N2&+bf)r`UQ zj|yulg&R_|f6JiRn6>jXWDVL*VC~yhV>Y$P!J9r6?tkLGcgt*<@3aEp=1+tzcMJD4 z1L0QsvTc)aZzB+X_oVQ>JM|vAz}RzayD{7A<%jKDYDczkAHBbiA-+Es_6iShw+Gh? z5B);e*$qtX!^6TOJA_@o6CMo;k8!=nKNfa>1I`IQVrHH&@I&FpZwXI!2zwaQpBxjO z8U-%;bbq<9mlAkJ%F#UgneZIf+qVj+x}WY6env$+AEi&!Z_JBZwKZVOwF{nn&D?%X z^scdHbQg#K-2ik~=`v=&z60za38pYmxBwQQ@5d;cxEE|H3tsODu-zPK|3A%0SUOa02)ZfY( zX@9bV`00Hh>&VaeT*%y^XD9}I6YP>g@+TI+5g{v8nDn5K{RbiEk}#!A$h}?2%Y`R| z{JHR~F!i!9P3qa75e>4e{DR{`VZShQr!ec=!kl!FQud3BL6*25js+PZzvP=jsT1bO zj^xkp6&B2f*R;EtkO<=;36dcNQXvh}A%6>Ej9+$A&&_}d?DzUX8Vhm8?~qCHJ5%(K zco+u>#$Pr;epvQPp-a}eznuPcuM~P@MftsXLLZ|x5GM?76NY{x40G_v9APvB49-`Z zLDrkUN+#4_T`gQM3&&q0bLHQ_z^-LX*KvUxm%#6Z_1Pe6)xU{x{(2!iBW$Pysec#$ zX8LzatM+~-Ofvqh>ov><{S$O9%rgF_BK=`Dgc%5Z-V!JUeV5G#{ruH0U;XIS@7+aE z0hLe%)vy?9pcd+23DiS_@i+fU@7rknmzuQIWCDR*+G;j|yhGY*F@dV*JQEoBe|5H* z!1jA2+$&=hI8-5=c~gJrHW3N3F@HuBOL<2;a9MK$CgP8S+8Q(w=jA;UOq5{?7RfLL z*Oll8u4h7@$Q~Blc39Xqq`80zzAKX#{ExhzLP?{Vi!z}SS+$||$21&kLf^ktTQMf| za*wuRP3T~iw)FoNQ$fEYDxeaopc)oK4b+1E4Z8&DLH~)+2>Ne~W@rKZLnm=5v_U)Q z-vRn1sQ=&Sg5{uJ|2@zPeb8@0r=_?;m!iD?0gXuAjhFQT2OkPIF)|7zB}Gq03c9L( AWdHyG From 87ec75de48874a5fa57bafcf90db2a9c730553d4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 26 Mar 2026 01:40:18 -0400 Subject: [PATCH 10/12] solveInPlace --- gtsam/linear/GaussianBayesTree.cpp | 10 +++++----- gtsam/nonlinear/Marginals.cpp | 13 +++++++------ timing/timeBayesTreeCovariance.cpp | 11 ++++++----- 3 files changed, 18 insertions(+), 16 deletions(-) diff --git a/gtsam/linear/GaussianBayesTree.cpp b/gtsam/linear/GaussianBayesTree.cpp index 58c9dbb952..c3dc340be0 100644 --- a/gtsam/linear/GaussianBayesTree.cpp +++ b/gtsam/linear/GaussianBayesTree.cpp @@ -117,16 +117,16 @@ namespace gtsam { } /* ************************************************************************* */ - Matrix GaussianBayesTree::marginalCovariance(Key key) const - { + Matrix GaussianBayesTree::marginalCovariance(Key key) const { const Matrix information = marginalFactor(key)->information(); if (!information.allFinite()) { return Matrix::Zero(information.rows(), information.cols()); } - const Matrix identity = + Eigen::LLT llt(information.selfadjointView()); + Matrix covariance = Matrix::Identity(information.rows(), information.cols()); - return information.selfadjointView().llt().solve(identity); + llt.solveInPlace(covariance); + return covariance; } - } // \namespace gtsam diff --git a/gtsam/nonlinear/Marginals.cpp b/gtsam/nonlinear/Marginals.cpp index 17070dd3fc..017cf17148 100644 --- a/gtsam/nonlinear/Marginals.cpp +++ b/gtsam/nonlinear/Marginals.cpp @@ -77,9 +77,10 @@ Matrix informationToCovariance(const Matrix& information) { return Matrix::Zero(information.rows(), information.cols()); } - const Matrix identity = - Matrix::Identity(information.rows(), information.cols()); - return information.selfadjointView().llt().solve(identity); + Eigen::LLT llt(information.selfadjointView()); + Matrix covariance = Matrix::Identity(information.rows(), information.cols()); + llt.solveInPlace(covariance); + return covariance; } GaussianFactorGraph reducedJointFactorGraph( @@ -133,9 +134,9 @@ Matrix covarianceColumns(const GaussianBayesNet& bayesNet, selectedOffset += dim; } - Matrix intermediate = - R.transpose().triangularView().solve(selectors); - return R.triangularView().solve(intermediate); + R.transpose().triangularView().solveInPlace(selectors); + R.triangularView().solveInPlace(selectors); + return selectors; } /* ************************************************************************* */ diff --git a/timing/timeBayesTreeCovariance.cpp b/timing/timeBayesTreeCovariance.cpp index c0f738b3d2..404a4eb42f 100644 --- a/timing/timeBayesTreeCovariance.cpp +++ b/timing/timeBayesTreeCovariance.cpp @@ -365,9 +365,9 @@ Matrix covarianceColumns(const GaussianBayesNet& bayesNet, selectedOffset += dim; } - Matrix intermediate = - R.transpose().triangularView().solve(selectors); - return R.triangularView().solve(intermediate); + R.transpose().triangularView().solveInPlace(selectors); + R.triangularView().solveInPlace(selectors); + return selectors; } /// Extract a left-by-right cross-covariance block from packed selected columns. @@ -714,8 +714,9 @@ RawResult benchmarkQuery(const string& datasetName, const string& orderingLabel, if (variant == Variant::LegacyDense || variant == Variant::SteinerDense) { recovered = information.inverse(); } else { - recovered = information.selfadjointView().llt().solve( - Matrix::Identity(information.rows(), information.cols())); + Eigen::LLT llt(information.selfadjointView()); + recovered = Matrix::Identity(information.rows(), information.cols()); + llt.solveInPlace(recovered); } const auto extractionEnd = chrono::steady_clock::now(); From 86ee482d078052932ce5edcb40ab56b6259c90c5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 26 Mar 2026 10:58:55 -0400 Subject: [PATCH 11/12] Fix equations --- doc/CovarianceRecovery.pdf | Bin 459550 -> 477500 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/CovarianceRecovery.pdf b/doc/CovarianceRecovery.pdf index 8c579928be8526b9394975004885027f04787d9c..078acf2a351f36ebb5721207fefcc422fb820b9e 100644 GIT binary patch delta 195904 zcmYhCQ*>rgv#w*?wr$(Cla6gW`C{Ad*tTukwyjP&$?5-WjD1(nsEM03#(L|mnt5S( z-AVZM5jG$!Ea?H$5Y&JXZC!`$RuuoYx^+qV1he6;lzc>aMZIQA!XT`(lVYJ0bi1pZ zofV12Q73?(1=sS*_GSkVBm|v)*ztY#!S?IS%E**#UY+OUBimV3Rdy;mZT2ah`aG@X zk2FKomg>1t8v9D?`VGNqrrf%BGVsbuuFbZ*ykyj{-ynM}bd}7S{Z0WL0@vokx|=Fq>v~_2 z{}=Iz^I(?lkJHN)%`dxlQ=Jpnno@lSL+Kms&M|R{nC*;wIFE=%?{+Y13^UpJa@ z6tW^XtHxlSe;t5+VcJP;8fI73SIP}%ONzN5%uZmmbwMuUf+NRs8w4b8#HKw=9?uQO zV;fx;^VVsn2%Z%fYOl7NuThx*=sWsF0yedoJ#jgF2h?tHr^E5E_QMl~*Vbk;zZ`+; ze0-!BiH`Hflhx9iH32PrG1{ugbuvZC#Y!E&GQCx()eT^$$=PcoG$XY7acr1!8u`oe zI{LJg2aUH7)ZfH-ntdtLPvE<}P>;M1?>q)a!KVCzz1)8CRXpBfzX&|Q-Tui6UJp%P zUGHuXEZ`y)XB1a6Z(rvCg8hJKF~y7~`$&n2aA!;~q;pInT{e3y(-+ZV8}K!hkjvH0b$x@Q|Q^aLH-Xvk9bu zfE62Msjv(*g)topRoL~f-JI1`v2t^E>q|4-=J?S+vkrl^*hSV`|Eq?+{C-nLSn=>( zYu|YTO@M^w_wafN(!%}g0bMgFGNrB( zx&fd&xX<5u>8>Nw_JiU*0}n2UX<$Sum8I%>dqgUe;u4(?lstI1KU5OFjx*Tz{8A|H zu^HCu&~u(>8;Bh$T**yZI(wFusn9FGgTWbRhK?``9udA&X>PN=TK~GKDm=Dde__3K z_ih5o3;zLT9#^o@`rbUHd4gQW^ar9tN(qpcGi0QWm0y)Olg6iINoKV@i!9RPA?Dn; zMW2X9V9xL%4niom)fQ3ORkf989R>mSPWyHiw+e0^W%()J7eIrFn z>|Xi(cuO!!QaZznVz0$8vrPrh6M|Ew_NeM-NlXVN1o?L*vkh|B5EClQf?~kURhZ2i zrb-IF)#rRqoD_H-c186s(iS)s+Zup>LVh~arnFh7-8r|GZpseFnBMUPcQyu&X8Z^_ z6I?z^sRzQu*4A|_M>}t(6^;4SNtSu%k%PdJihuiFyzYnmpc}V8m$_?#TNO#vj%ZWH zg*93N(__q#&H0b`^;~tP(}yUVt%y;^9qQkxy2SOOrqlZmsy`KmxWhC`wakEKG7D#? zMlQ&7Ujn_4AK>)=L|~Yn_O&hm4o&_5tn_2Lsiuw~BDmiL)Szi&mbYI z?uC3L6p6Cd=9g6|vc8d)UsUZ?*a_WnI}F*AT(jq-YcbQwHm@P5Wx=Zg*0${nF*aRD zmmQQAKf*qN2RXw=7LoHsfGJTfioW}P%3}x0U8F~bBEzbVY@oZd;GpVwOrXZOkyS|y zcMPQkGKmdTYhE$>jeY9;3(!XDl?$bn@N7O)8_q9y^Nrlo1f(vN_c-*emO-J=ia ze#zUOd4h`e6-j%-_VEbCVh@S3N<1bksZDTKJhf01sL9h9M*++z0L@4ke?PicC0mJy z=I6$qx=o}?`V?S^ZHsZVHuW`452Y!tVn`i+mBz7!JRJ!i)KQnA>e)Od(0oMD^8qY& z^bjqEZO|)~U%b4NtjxvT%qPOAIdicG4>62$j}iQ97B_#)l;F6P;b8ytX~NmuT-VC> z^$P4NGY{OYj9q7%)Zq^UTAPGY2m1@Q(S7tJVh&F zw6X*m+QbcZQbm%(vA#O=J)y9u9%4m1`Bx)3fAwT`y75m;0H{nCOv$g8WuPW|@3(yT z3u&tm@Gw>}obvf^1}yoIG>3Cvx5cA`iJv#%FeHzgva;o<;lmFc`+PCtk5P3~C5$Pn zvpqj!K0yp3L<3KHA$5emS&-n=>2fMw$8xvAdD3X-G#XiiQ>!tTOX0|mQgC>!Id8+F z;(}mE?`wEI0LD&&)wVXWoyL zvZAUBoSLZCV~7x6vN*hZWw1Gx92B$%ma=`bX8T1W^|8*6({tatpD#Kpc-jm%r%Alu z6DH4V=9$h6o{tu&m#GUOa%}2%yuWEtylj8CJpvNw@DZp;Gpx+7yMdDY>-akQ6tA^B zaaW_xL|2@}iqoE81j7Vcf4WNtSPm(~XPuc{k^!TkX`)1|1>U3VzvHGwy%}Q2gq>JB zW$QhIM7N3WYs|$QK6!rjf~FMJn;u+PAk$H*fzd!Y*g4Vzry-~SH+tIfNA1Y|dj<<$ zE}%9wp2@seL|wuZQb-|9ZWMq!Lv6G*bNr-2FU!BkpwadXpMxtc_lIb+LVw&6*6M_G%-eL*AAHBuUvUR+DVm8Sf}3DT$n+ zl6Dw4&tmS`$?7qh;H_#bYZ<4t8FUqzf%Vq>p0w^0xc>FhcdN|zi1{->K>db%C8Mc) zeQ)$z6LF*Sf@p7T?;|rhFTs(@#=p&!?kIRvN$rKFj1HT#?g zTG5l{E-1_aP;`_ehO{t$RF{aXUg!!KR<9<7zD7N86ht2N^XQzDv_f;9R65ZqU56{J zC%cc6*8Fodt|nJl&zQu7HQD-6=0F~-L3c37M*Bf6uewJ8zu9lwV!fHL&X&%@jB=br zuExA}J2svYz_6^8V1l>8{)vPgA9(+0-rZ)Ef{KO#K%_I3uH-lJkAR~>&736Q{i}fV zS3!t&T~=cd0C|oKs zsE+|Fc{Tg&GfgdD}1F{4Q8}u+5cwm`5dYG^!Roh@xbnMqG@9 z{G!GffL_F|2(%m|u{Vk#qnePD@&Z+ZE3yYXYt;s{-zwE}-ra^1#yVWGZk!?GS*1I= zZ%KivLNmxtG<`T8QS%Ba;aw%XZiK(h3*KHG4L_@e4W=of>lh0kIY~qwxLcG&=f2^B zP+5+@iJ_6-AoR(-60VL0wOHO*J*o7v878;~fSn&zPpoP6y1_BuqM7699ZRRFa|!>5 zyF|N&HkLE!8CV8BH7n9JfrF$cAJ_Jl>(`^>Z8$@Acg~P2BdFWb0BP+bU_l!rFru=x z+$FiCs9XDEpUh3*UF$4k?uag?;*N`s-h4=}nf+h~Y^jU>$9yA$DUOLT?{^$O&NM$0 zpxgTzm|`kmA_mLh!SDh*)2I9 zEO2X`HC?|<*_)f(U6oZ&UCwTLvbVu3KStx$TX@u> z)Y8&tSB6#qff|LHgt8Ebc5&JBR74QA94r<7nlLYvL+b(5W}x6L1uq$GLFbTb%+B{ri*5bHJ+ub3V8r z&~-m-U|Jk-4dtM$sTeRtUB~tS&SVbw<}j8!1WIr8WX`GSYIEVcpsNbkmHbrn38GU$ zf{MPtqg9Yt2l)V#&CJL;PQQoBO_-q30N#xXPfuSK<}n;45u30n_j5+j%x3S=W22xp`gEjo+b+saS?44G{lxk=ILef(TRz9rqRlH#SspV5t^~g z_J#e1ZEnsfYlbSNdfOR*Ue&A&Tn0k})GA=z@CYV1I-p5+Gk!2El(V*`OsVLW#P%Uw zf$+rx6FgOJCN#r8xL=2j4Md6*L~&F)QEcXdiwFlkZWAjF@7$2-z6L?!QDbB-v<02+ zPk;!nCWLlFb5+!e(eKYytecTN$YClri?TpQ^ziMqC z>uc{AD|e!S6t_}19~C>-D_Ob8a`^Kz6{ar7s>zAk20eePJ%v3HV^dt`&?l9(|A%Or zo3)t5!H5jUlNdy}&dyc)UL4rV(~>RT;$GFnyjl^US1<74eZ>pIuwjX#{nvl(zHJlp zYKWt%TduhADI+$V0M z^m9~zd!&F_dilB~>AwKKpO_Pr#*H_hg_84;7Cdqe)QF>{)w3PjgR_fo^DoTP)shB< zUc*0U0=;obQ5^tG&ZO$Td}Df6*z${<_mXbItLM)zDqdL`;7hnX*Mi72+f9jEpKXhq z09sp9cm4j$YAbj<(~9Z-s?3<@Ds9p#Z7=|`q{2+3&`)>3fqb>A`&0d)_Rc45cI|Kw+&%tRkO*ohCw2Q$+l`qTCMywMtSIa{cvldZb}N zwKn~e=Iup3qvKsMEKzAqz2S-U_A6m)@nhY_)^ny12UooHe6_kM!?SzECYinZ{zE0wqPGTWN7 zu#t37awgwg`PO;O5R2%QFjTtdfadkYB(5UBXIkY?G^y60i}?Ge-fFL@umPiPMxfpA!j%yAh`IEbbVROv89lEaCnPUt{zZihr!yI zfHS&%Dq6vehNb_ha#~3D8c~{ERn;b9g;Nj`CI6jq=Zv?*{~5ZX(4Jq|VJOOXQ&4G= z))SK4y5Zt^#!JydI($2m(LV;pQ1w)Vsw3Z7w;>+fMKh%omKDu7H8fib_S-HEiziR& z5j`F#Z@3i<1C^ZWF7;~8c)+%Y_UhoZFP zQjprAHWE)RhN%+Tl9ez71T=RhhV7E|@4~Y@D%2+teKwTGC^u;+BAUCGic)3$8F{!v z_r%drst*2gqc*li*!`QUb30bd2I)_j_PP@^a%LDf2N&wfp^aXA=}XSUg?=%% zFC@}zbi^2jS#pHp3vd<1Y9|`ILZjtf;D9z#X7Sw}SFQ%BJ>=i|#kNnqcuJ#Ygsv_u z`c>jCU^~{*J`ls~TIq9h?rWmiL}pbtUL}ds#H_w76pOs9Zmb{)?@FZ}K|>;vaExM} zSm$(eCR~PsyHD=Nz8--3?xiw#h5jgmY_2hPyioMjE7jd%MS|qzDtMIun#{+M-`%d> z%4yMd-}N5q1@5uG=s|thq#-$-N^9Aq?LJVjJFyKRb;;K|ux-;oF|K4O<>sK6gq4GW zfd!%ym%?>}m`+x7uF-Jk1fozpgkHLJrGL&QXz>vnEfkB!Y_S2-u4llCc}@Hi_z$wD zvzb6MwV=Jk9@dWX9aacVnfH9m0jk_W^5{xSne5YTH^*koEdf&- zn_D9#7(y=xf4|1n;EfdB^E*)vMS!Z;~IXSZz63vayZ;H3m365 zIR-$or`sM{&ZVQ(2r(jLNs9utJBuHlZjBYg_zF3to888`Bn9k-4kl^A=ey%C)34T2 zo}&3*mgs-yKylA`JDH4w8y|kQMcL)0ELsi9;7w!L4TLrnN0!tI$#^Re21CZRsaTKt zvtZj9BI}jw$)%+SGx|U)9(FYQ{C-vdz&4y#naTALXz2~O|B6m-7WV%tI$N}49kw}; zdOtOALzl)3#^Ru#S!2eg<#qE$GaM9+%+4??NHvjW*?&h$_2-18YGBMF#K7*yS1dM-@hjWXjime%XN$2^>o|;(HUmSk^R&`3 zidvB%;ipt-fj9`A1^8drWi`}&KpJjbUf)z840)7w@nSjEKTEL^W=%52x-AusMBG|m zUwLP|A92$@B^~YL8w2N93a9f7$+o}1(VI)a*4|bQ#P$b;_tw55vh7^kG`c?toWU@- zl9_P1IQ~6Mj5FBgf8VnIaw==R(7|zEv#@C@;LUP`qQV1-0$>5xLn9;A-krLDl#?wP zf>1ieIIa({n#u#SbsjA=6q?Tmcu>(cO}P=XLK187s(s1djJ@r0Oq%34mYDd#0z)lw z0A1NlQh>*SjIi=CS_)TG|9Yy%QS@`mkG@niiM2iIKI#huW=5FhL`vMFZ!%fp7^`<% zYq9IWB^Jup2XKg33l$K*cy=Rz;U{cm*aB%fWWR>>Rt^C}u1fE;Q-L-eD}!2A2H@%g z^2Z;TR0ZCfE}1I`rnL3%C09VNQ%j)9pfh{sLh~2ysDaVI0DmTWHRG_4)sEu;z^&JtAD(B1 zUqZ0LF7;4ZPjtUjQpzs4xenL9pxO2v7l!)p^xmB!yc!-`3|W4&`TS05GY!q9>Q0cR zjm+6tl%Ud(F%6fFoQg(YYC`dl&Sj>h(CVIZ%j1z`E*QrCoH8M*#6`v*lI}@Fen+F) zFESLN0|)~HPae=r5-<$-c8j;UAe?K~eZ~b9xNu&GfGpe&iYy^eGka2N7fe!uXFdly zL3e+t#~QWOoTZ#`$n*l)&Z2pG5HQ`UMBEd1K#7o>tc?bpIbE@Y%|?q`FGHXhTe-~T zsKdAvQBRKHVQT?*MqGz4wF$)8JDx$@@q@)b-HhCiGx=KRiak z$6WB&f08i6wH^PhTuh^j7aKeKzp`gI)8Z$iOxM)N+Eaqq(w49ls*+pPMYkmbW2FwSv@d!TeVk$S%aLoX4>SFoPb)vZANc!GMNuxQ>xh%;QUveq8S zGG3dHg@Z*w;PXx{y>nnv13m*d1hi{KCy!rw4Z&=HX^rV)cF3fbP;Ck*hc5nL54w?Y zvB!K_LDneWn8XEmi>FS7naf6?04TN?o$+Tw(D$5he9<;yjks2Cm=aZ7aFR8?3Y@T! zG`BvQN;g6@p|L_=H|9ad5A!$VEMhrBmCp%E{3?TY5(+si;_+Q+)55f>7VD$*F^{(g zR62OX=Fo5PB|<1c%h}qW@6cjC)1x?ZePY+u!%u%tR;^rKuMzk*b-?nE0nY9a*AXh- zzkuxpMRa$X_wOTh#@E}0du7+GDyjM^w?9+*YmMen0iwP|gGeKeJVNYc%h``quvU%p z@o#-db*GOu2CAlYTVF`Ge0+2czxDel(nsS*>o|&jXH;<=-%UlTj0bIK_ZX;)f2CU= zJn5jb-|aO+siaiI-r-(uo>D7wxH9ROLKy%NukIH6*S)XXT%^fy#py z=sF|TF>(0@BFBuml>HU+rp2JpZ-lg**}***!)W4SuaKP*mZQoTMwzc6pK96DBDom3 zx*6#U(w>P+Hcg5|clB_fcQxuw~>4=oL{(8%2)C& z0|jwHbdy!a7e%JKQ`w?c=!X^USbG6P721BI6%LZ{k zz2K0kLdT!W7n=`!^XajAbdX66M8FW%6(+Ql->2s?jeHTYi~#KCUUjsK$Mj@@qp1lSM*;@ z4|Vf!Sv5bNdF`t%XqUI28+;V3GqLCl|0J&UtQ!!1%#14<_@=k-<)YG$!*C`G6S7Mi zch>7d+Jn=lzED6pl$(59XLZQ zsTh&T4Jqd=rT+5lz1ynW_GWS1-BeJs_^`vpjmfKGc)&zq6X_8~8-mmYP=tufiU^x@ zZ>f0E1fEK|(DAFVxOq7lGmh%SQg;dpVm?gg&ifTNqI>1%ct1E?+Pzh*yf^JvS(b3M!%vNTI=KxXqhP{ zhzEOWlLVLcJjXnBqLIU)cYIt}(h5!}Hz~LwiAP$G?a~Qgm6!ysrI$0)qFPSbA5C779R8fsbtXW>PAvM{kot-?Ad6$_~Bgd~1ot)JYwWdC*A-qPim0Tt< ztW$6WV@#V<)9J3Bp>oH+FRzq}w+vuIG}xqnWmyRdz6SOfG#S-4n-Q02h9SA*JFOV5kh`D}auI6l9~i%Vse{(Tac0ha2()X=#G z;HHW9f3?QDq+9UAqObFJi1X^OmC>~l>o>GkZsT*D~Hmoc^z9L8o9jsst(8)sD{h+|`Qmbcd2dar0oB=?whgYIBl zm;Fuy6yzCmr4YTE)KHVNA!-CxU)NZYFFb{Wqi|GmlcMZP(_qtD$r}kP(-XqOY6$Pa z!P>7Fo?OvTk#2-u>C2JG6RZ+e31sET`Fl83eoHL3l?(O3OlNvGtgS?EX)@9RG!MBR zch#mp=>0kdqzIpUH0|8e;!45^dXZG;39nfIB%rlemlV*=snn9BL8$2G;mFNcWLCG~ z)OhJPE8QCvbKRz1$JI)!>Lul7Y7FvO-4_DpR&?=n0aA#GwFbbX<{@MT{uiyFaPI8v z4A=8VShZ!NJLnb?Ii^N;nMg?(ser#EH-0>SD9`u%&ru*t!nCtT?`9OXD}~MuKE7v z!f=(s1Qjo4@>hB&!uy@v>*}s0P0L+*4BN#J#Qx{if zGb6kIL=MK*Fsz(h|9*-N$*Bs}ESx7&3W>&TkyCYyUEDHcd z*;`bYi7ZKG6_NJt3l0yEU4kz!6v&~GFPzz8k$k-!E~w(Z{Hv`sK05dcTMczzQTUe5 zaJpA>X6#|HW2AhU?N?uN9Lv%d1E_aK=>P!m$j8wsr4n3uD7v;pIRE-80bX0qnEG0)n|QM` zGcQ3k{8*!%T~`@0KFVuCz%xgKe=wxF)5fi3=Qk|ksYj&eUOLz7o$Y61jiaw*)s7Y3 zbuEJ2BT#v`BGhrlw4>%&u=~ovj;2JX=Bf$qOZT(A z+s#vAKCg>`BoB8j)`Oj6$gsacGASj3>ZI??Lz=t(<4+M~)l#r=42WpO#x#^5D-=ij znf%|&LkqE+xthxU?p~Q*=^g;w9l&`SkGOhE^Q~g`5wg>ms~qT zgEADw65g>(ke^<1F06Swly1&-iA68@0N&5%Zk$O%B_1Cqb6JYxFDB|HsFXRFgB7ph zngkMaUDi@LWY6zB^9vmQk&rB~PdVOxau{&qdl7I;gChVP=~F03S{g9875~9Yv@G`p$68eA#Lxdqco*Ow-(c1 zF@MJ%5fl*7U{?dT2=x`KG;0Ec23b!YwU^(F0DM77J}g5LN;m zdLEi75b>~gzS9i|rJoM`zhNEilA*wwj4R=B))uo586kmE)p|hkGSXSj?jLtjS2!;g zR436tHZ;c!x*v`0?)zwPUfA;92b-a9Y$ka!Rry+Zl1+B4_`j0&y2KDl?2Gb(97i1A2$lT?U_28{@7OG0PgUBCEg)l}^% z5Iy%=EE(uBx4Ha7L=2UP9UynJ@MqwtHlWR=_R&#YGFcdgOA=2)6RAUr)BiM6lp0Z- zE!b*u$B`e@ZAKqeN2&OD<>JC8sU zJK_<_0tj-i!8-RVZZHnJEbg1xPfBr|tN$2KdB_rMyWZpl;0k#j$T)$#P^k)t299dR zBFvk@T)$NX=F+~PTY@lWt2}rhqH%WNfJn5gg6hWPtBYeRfdY&Qy;AucB4~F}ojWP_ z@9X4Ci6;Se9d_0z%e5jBsz8>=m=Okei z3`vRf_)d6$1XZwwzYv&aw$AU|bXRN=5b?(U4JH`u=VN5dQSO{E{WcPz8ub160sXU_ zKJq2YPwz?1C5Uy>ebEQ;@f>}hoabr(+S8VR;+T0?`?uibD8arr zE=pP9=7nk|bcNi2`aA23R$c%lkUSqlK?kHRXBV;KGj_eTjF02{(dB2hHX>bcBS}nL zNI)R~IKP8O@9R|(=f?1X5(*RgAaIoD*ncnx^I%a?}<)mw9+F*t?IeD(PoUwjYR9zWpxFJ z>1dF=oGUn8SH~^W7F}eSBU_LUX??7s*Us>IyjZh{YN}qOAPD&VZO&qYNz1+3=Otr6 znkU&Z;okL<=E>r&vVvb55Vvtx_lzmXqHN@hfZ*DV%xcU+;Kc8?xvxFw7PSr#6=6{K z6e7*dTA(NZhn7CUfNP}RaXU63o=E|iwEL11w=JB&c9rd_9{dS^WP@vcwsi6YLdCZ< z+jHGAv;-)E5SMFH`yMF^MYu>O36F$qA!2I(72OFc3dp2VdZhdQ#^Ye>>;2C83} zH`B?<^G;^++{2IagD(s{JyaP=^MBQ6~mU`fSwdVc?I>Fad%(sV<@Z?dKtPWsVfcmX(Xs1uX z2l??0VpH;&#(uUh*m-3q>YzWG`#5MUQNg9|dnKL2ZVN7dfXCCzTcH;8ER24{%8vgD9&L)Y zwmwrWaHH-QYZvePR?GC$wccyEn}_A5zt07-X=CnBe`sx0ueG%Z4S@6BRoeyj=R5f4 zaO|Yv<>WR|;EJJ4bwi`?ouRi_a%cHUUUzj%*Q!a>jkfV4Phg#-L{xi3l%qYi`LOMm z`X1qt_SRO*cmQ$YP36l?-|cs^4lF8|F6@Z&uLQ$!SFaF7Q-PB5VZO2e`V&w5Z;vgB{%aX6<46q1F|D; zg_qE22nK==0|6#5j$vCwy{F=*f~i}1^GcEo=jGepAh}bm@c{pVj+x51e#z#J@xxl4 zTw$>6K*dzCpnW2+G@3ef;@G;K2C?(cp}S z2Peq!K5avi2+PcfjO<8pTGh?P=~1lVHd-iY%0!m_C?o0q6`_Lr%h>6ui?jvGL$ypOT24VmEwiFyTPfUnmR{kdh_Hr2<@P*$el;b+Tq~+N8P!vz*ZOO;Tyd zq!nHe_`AXg;@iIr1DBhsqfkEHoexE=or1#=VxH)W7v%5LXt9k*K|-(@+DK3nU%eoS zyGC%)wgA*(d~W9=o4d4-P0kzWP{dVsF-5PNRan80u)cL5aZV9YJ_dhPh=08 zQetMxya46)C+3`RmB@Wq?HCeH2-1>$q(-w90f5@CnAtaSZakVwT@!j@F743@x{yn^ z8O0K1oEQ@0n=L=ZOi~JJtq!Z=Zc?dfSoeDVexAK0YL?%*hipyYN2ZBPT)LFJQ zVNLOtM#)2Fk{;MmRjMh@42OV8#1x0wSOD*Y?38#QCsGa+xp2=hZ3TaZc>H(f?qhUh zZI3HEhn_=>bbP!wZ09w3NK{eMW#l@*FpcA~$tLzaHzUwMHys~^7lX3>do{vXe_1L~ zgXD%p=% z2e}(4M{giknaR&BQw^bXJwx1jnO(Ait%#w~Me;Vo8(ZS0Ev7DW2Y)I?bw8m*b1#{E zz4yEHib;i^GL!h}%!eDPoYY+nvCu!O;X4{afm%91=qiv0^*e!2mE=+CUjnZ3Ql|d( zO?q`0+yofY2aYbu8)8EbVT`3`n$a8z#9p#cUNC8p9YPpBcapYX$LNlk%9j`}?g)k3 z^5JOd=Z`oB|I9n1BY`uI`zwwk-0C1ip|nNq0}RTwuY#O_1Br=+oY`TUGRu*soaj8A3tQa28=0HLx`9hup(nL0miF9ou(tsy`v@1GZEo`wJ zC8}XSRg}JiS_UwMk@u6lSe6_xp3O3q8r17uptqMq5Iwl2iolE~RQ8fe0(hm2mM|ID z)iE4J^_ppaU(_4U>S4PZqp>&D&_M_Snr1CV5jx|u-ovz98=!HW4*)4S!gVP~y}HdU z6Dt;;`F{Wp{cE4o02@X6KkW+H34xPoY;CB ze)ro7Rt6JRy(Qu?2t!pc~OR-rWoR5kA`SJb5^r7M%G^0mrR)cT@ z1n(fDr=WAEcKC#NOdMw+UbtvU5c}*}%3&V&E2E{r%|S-!0KlWtOB+`d!21Q7VVMn3^2(KYGf;x+L2qb$!Vy@E?O~qWdJEleGZSx-blYnfA*rFJ2mt%qznbwBc~H?sBY4T`zfm|> z616Rnwsa=W*<{FkK%wd~nlzdHk)CrNh(6IJ3?^J&wy2s!;x`=Z)Dyp$1Z5CJiA*iM zkYKWwK2n9Lo~rCa>2~DqLe)_;Ms+;sJlc%P zqGS=XvkQ>i%Z;+;V4KuE>R=`0RM9gNOk$QkO}Q?zBAgFlmFZy!XEJTQ6HbTO2JUYk zzJoJ>M4AvU&T0LC|CIFvCKGR`Vlc*`xJtFeWUIy&06wkpKbV}IVhdbKBYk_yFCE=8k27O$_T zGc#Gw{AX2S)FmR>CwT^zsHJ`1Xfi@9)D|H5l4Y=6II7gR^wlb!gwgvW(A7lc(6&0Q(Xp;!xavpH2xSu9*TD$IYDkOndyn~ zy;1|K?e|Tzn>*@7k_Mg0bcc>x4I0)_1w>*L%LY2gM5PAq%j^Oi4b^s&{F!MP zMfQUbl)(plK{Cm;T|L1Vu;uolGLQ!-3GfQRXNl;PC~&kx!IGeE30W$DD??*$$hFX; zhAw*ZRT-hoaSp(HqE?fkuF>eys|%qVF~SihYzE$C;6$Mf!%0JNtFV9=3G#^xh7zGB z`d`%Lz%7NeOS&8nWS4#M5@4HQP7-1&YBZ{jsS%n0>aStM6oSn*cTD24mm&Pfbm zCNo}UfG#|K-RSj9}!k?hcnS8%^vSJX!o;3Km-&xVHQB0F35~AO09`>-F;P?G=a&{n{ z+3@xCTP!)&(Iq%>Sr)>q7RD|ZmT+F{ zs)h(PI0l|TMBAaXK~=DYmYq<+Kc9!;t#Khd51jw)4s};Xj5k?kR7itv18yYaU;a0Q zDX>%{KzaA<+Lg*D+NT#-1G959SGDktIqwc&;kPMU!B|KA()fj0c zu`@hUV=16!66r5;V$!*1k#7cRKfByuE!m^_N}pH|y8wMT_I*CE-sC77lC9)Vkpxa1 z8-OUoU_$ELL_1Fcf8xt!s*j?u501SvamkM>8D(%t`S(=)w5$vK&*%wv!^qQ4-)v40SI7oHXy&k%@IKJhc)7qDX(qIHmga4QXZg&P!l zbMDC)Y=&KpZnt6VO>-`*BmXL$K2p;9Y}h?`pn6%fCvup>4xGZ`-S_MFo+*Li#{sHH zn=>mUrSnHCxXHmV0)i3yCZkIWNkNMd8Ie!Kfyg~P$wgNnauG+^ z0vuRs!`e>&0tdS_Bo7?6N7}O4!SxjBpzhY6U%d&m7aG`MmgY?iLm5W4HUwmV=A_jS zjlo_K+HWUOW-ZjCMDlIqsG8uvMj{Q(#Awm}KkX*KO{gTh&&Un@VuLpkVA`T&b;Kwh zl4M){auL^O5Xqjj6o;Bcs*zUk$&He7mYj*lulvjBO)^Q1VN&a)atI}gC>GusDPN$k z^^zIapBW*J!BQ-^hi-jgQd*(_GQJeDQp|b-3#cj;l*P)FV)hYeFAuq4dt-$p_^c)h zinS!aU}-iVLlSU}{k8g-5WTWe;ljf9QjIGV=feNT(>sP&7Hn<1 zS+Q-~wr$(C-BBl5u{%yyY;}x|)#;>T+vwP~PWImC{eI1-#++4G{T!p}9?zr%=ENuV z4m2X0PYUQuqI=D}p!$C36ELFGFtN#5i4hLjwtP4GefQe86jyU#)19MgW#Tq4DN0bI zvGNpA*g%Gyw}i;HIEKGje4z)=j+91}(wFMH@>gGB)D5WGkjw}syr|XkpjXev%jR9m zVI7bAO&;E3B(PJ`Bi+vj=d$4s@VoiH041w%-*Oc!XgMeYjj1BW-)CISAp>Y|woqa= z>VFfpXYfRCKl-4lTZ1#6WaXa+x(gP*v5ei)=gE<4n6I~wl`{caY#FNRTVkN_ZtnYd zuU?WccDWSm9~5T22Wpy1-C3%VIp~OFAsi6k#G&A-(U)>fm*nqCOrxS@fVxY$*}lQ* z!~QvatPQT@GBF0V>Wb0Ow_>u@p&}GD@GgdiLPhFDn#_*&zAzs{vhsDUL|7f%V0f*z zLNk|@(0MTMQgny1g$iBD$ia_Ic{d}KCbE)Ux-FuM&VKW`I8L8;k-y%BaK<~WT`sBE zG&p13e*Ur)G^XE0s)dCA4tzmtoYj7JPm>cn7zZ z{*;6$+fs=vKOcJV-@K<6x9kiQS#R{;kIjoS7!dYb40IkcDE@WJRkUzkr_-OXCT3Ih z*>fFXusMFDK>h8T+d1&t-m!D_VXxBNoB3+X3n5>TuncvHO)(1*9;tQPjtsS!Kq1jw zaT+*LTp}Ib3SKpK(Z)%{bN85dQY!=0;KE77zFGQ!&uwQ}!)JpIh_fiRsQv zDj{_#hM4X`^Ui0$MTvAWU@I$K?Bfb5{@$hxabe*P$}>htK8IehTXus*8Ln z7WLK*d!~ToJz=TYkJ5BQV%@uuZgqwB?s;;nG%oc~dh$|GN8tO_!+rL$GM>bdZ~+kq zc;(EsHnOk6(mC*chPh#ABhRNZ*X!AM$$RDwh0f^^6SRHd8WX@fl#qANgX$wrZ~+ai zA_PPYHH^-$z3l((C)r8uvOnV2WAoR9>A7v+?_He=_;avVbA)Dazojv7O0HI*3)Y1m z#m#54Iw0%DdP_xPb9v~q@9$?dhT(H=zf$w8z)EN8*(304;NCo2Moj(sYT@$ubNfMr z7jjL4^6VV4d!rvNy(@{*?XvCn+KmsCA%1&6cY*iAAOf>|;&DgC%Dt{`MQ_9#|5_UB zX@(6~<#!u3iuq@PVdp%r0Rn6>`;qz%ohfjMYOX=rYR!6XSdhK^M&*b6UpK>!Ea{pn zrX_q32_X@>(OOlvaK-uM^JmOC@TYkvx>GLV2ZV8J+X~1G0UQ%#whF+2Was`$%-c_(M2?;F#LdtsCJU*=j zKzY$x-5C8)AvrW%sn9-@dRkBk@_3>x=&9;JijE&kwSgK|34KN=Di!Kae z&0%2b7}Q^NIXjU(6p+jYHkJm|(RP;0*bqYW2p-$}sd0~0I>@Uh;b)Tlam;#oa>n5J z$&*|2FdQ-7D2H2+J6KDm3Z`Y+k$hb8)j_JtZHj-lH~tB0+#r#HT=|zrRBDYc4;Bx4 z1RJx8bGgPNUcmqFv}VE@S8z?&l8;PT8yu?wjdE`FRomlv27%N#5K-Dm6^jVkoQB4y z%jtxuhX3++o7Wpu;zQ5**#*n36tdc3{?Onh@*qQ8$XxKyDpYsv&vY4cl&v;e^Db$^ zi~bhF=g`H?f2MlpGHPVH>pzVN)tRDnaU_~?)eul3p*QDI54`TW5I2!dTQ-sV^j}SD z0y=p6AlrBQ8^W&Efr-tFAN2;P#9^j~NI41J07d$JY4DNw`FvPuF>6JHT(wF_FaTj` z`!!;B{BxQzRZ0^Y=AiA>oy*!oTay_0VhSH66KFZi+|F!S)497(eVTrRQu;WSJj0tM zwP;GmnDFVx=VBl@9O@G(^YSOdz*!5t>ZI*7wU?Tjn5(58kXZ6t6r5No`tl>{=cp#O z1mv~M4cHwWxtnUVs!Ad+;cyg2awcM*Bjz=fUopHL79sCfRVn5>5EhJUr%n-rfSB!o zi><@%$jr)UO+h=vN>ou6WcUapoKR@a_*E66zK(E|k3$ZFc?ap1{<(4`KWxBI$|_7y zByD2!atG`IISN#LhzTKhM7p}4UHgOb90#qtXw{LTbpUC;YzF7ffv-Z@H9JHD>6+qD zK8K{!Jx`z)H?CJ97TzLDWDjwnJ+`@f533lu`-b(cu_UC%3%v%$PZcG_GJJacWmf%1 zY-;m)i0oNKrL)rtD+J_1&G>-i!#*`@)yPcFNZN?niEx>)()8~W?zAzy*_P(0=1E1ao6a9bIZP8$S!$s!s#A)IlxZ}2*8-3Z_4K5rHYv>;&;z+=7( zS^8=Mze)->P$}$v3ST)Pv=fs*+^pXbCI-U>YM}!ZFl^f_&Iu zT-5;hC=Vo^#D_~H=?L3QU|O0g zX?&LOB&>nqVgDCCmn!w?$U#Id$1m|e>V`IU{3HhYw9;tpECFtMKRkEjO$fO~iQaD4 zhX?xatT=={o#BJ402UG9-t9o|^>n0e0#N6ZVPrsO^E_Z%XCaW&y0AZYy1-d2F8>!$ zsvo2pA}s}rMRyNwP|=^z8K6+FDmMonJ{<|;#c%G6xb)`s{f|l#668qxH(B@r%ic^R{tCt; zp=9sO4Wn7Y6}9~XnA5zOl3tKhPM9L8@-bK z1eh{ibsV*{Qh`Ctivu2bQ;nKqcFYWu`|SCcCd;hUkV<)Gy4aJ!EHoK~w6r~&LYpo>lSbRf^9gfq!!~Fg`rT)KvDlAM(xDL6k z9vgfb5x5W(K!zZmK}X!U(c$Y9jFw|p{K2Z|L3_GaR4a^(c(s3hf5~}|F`uQ2a-3Jc zO=+-8r{B3C)jTp1QJ7Kj(s{-^`-qV!zrFAqW$r}%^>I+^M_z9J_V0xf=wkF&oObQj zXC)p}m`Yj%zf?0xW%+=j1*%{q)-JUOfg;aAN4zuXYEfsTjW4xMkcZP?ZF7#{@LStj zxy|a|1{&wrM}EW-*E+{7l=60TIm#`aeF6G&w@=QgS(_g+S}Zulr))wCaysH-5zTsP zh~H?c>9#tmr(#8M{-}-w0mtMbW}eP9%rlGfz<6iI-$nHP8{C=%x^BlJ z0Y~v-XR9-%BdMIzu}MzH?(S6Ih=3TgQpH5?CERdEiizP9;XS2X2Ij(LLa6D4k4JuE z#ca37Uoid~Uefr_Z0zu2OWwrdUnoa#XB+*zkB_e&)&)Cd83NZNX79jt1{v`Svb?!k z|9;8&o3BOgAwmZU70Kwn52ncaHwxVW6A2!u*zRVB&OqrT*ZHOWe`XqTFj|R!4D?^X zz;)$;$M097tEY8Kv_SXVAEcOIhr0Cba-L~D#Er43RGyN<8+bcO z?^a;XnV$H7Yb}?lWo4RDKh+v(KP$a zC80l|k$x?wj(tt$#F}U?($R_!zIPN)^F~wL%T`6es%6s-PoQ)II3Ud76N5Jvtg(v2 zEqG&u*aIO=^FlDzX26=T?ars*(I|6yOw`j3&0l4lH)@KrP^%Bt(Y+6)`eTs&<$|F1 zyNH&(ombL$wE%v4K1=TcRiqOH4A%Q*R_+`jxf>@K?X$}#zbC8Y-p2o)WVreTAza)g z$ki9PvO;l>cp7+}nZ@_LI_}hronQcriz~~6$IP?t8Q7GW^&@LD_%J+FPZXjY^ZT2+ zH~I7!&8Y%(mBlf;a3dQIqIPm$qXKlciA6o;-W?9S`x7S%gamd$9&LwRM4z#?!&@)z z!;lH32EiL>*>aF(FR_9T#@OwtMjZp4D;n43?h_*SSuE;5r|O^?Z2%So2PfPA()b!Z zJ(qRf|ClEp$>7Oy{3{&mV`Sy%T*(d4v$QZJ@p=$TKXN9s|5;4Ya=7GzRaH^Uv){31`nf*BiP50! z{r#tuC41I~5TZp+z$Y8Lcl2;_BG3!XE*U_>7!|EXXKs*BT{_%o*}DCD>{pkJ`S3$r zzhK^8j53*aC4At`MVQ~1Fc+SvT!5lz8gz#F0kCvfN*)_^jEHD0NilQBAXGX z8gvOCT}r}1PS4gHFhk@CGvR(aZ#b!Yv`?$dOR7QD%f6M*^zY|>dNPI((Cq>3l#Mg7Fqs?NUaDTd;wokwK9~U z${`3Z0M9=FvWB*Wu2t^UbeC;6*_ZjwVs=jSH|Wc2U5}<&*-xf$*`uoyknkcB`G`t= zf9do&#GeMCSRh^Gc;mzzi#*8}kd9)~5PWkh^sxE979i2UM6#0akr<#`a?#<0+;aON zIA?&|gPhaE$6B*8N+6G?TI)-6;NC;GI3ESV6YxlL`_h$Z{);r>x*1O2T(g z*z9te#!1xGelB!6A}ru=Q11W!D!PlUp1-NmbvCwg3O7L&U)8%|EXOL}mQt`Q8K&35 z0hU1lWb*!dd~%wG$*-g+&lu~HwU?&o^SMU1@!s710{Qtizj@hV;`oXHagT^fS-HOB znJZT)JDadz=IQz;Ow11=n54At(B>LBMFDEJt<@Bi1BQWo2)R3`!Cpuf%5f_w!EgNQ z1amCW0ZE${L#A&k=a1qr-P-uVoCV7fB)JzgZ~(=25;vx1OpIQcj)g2bDbfQG*N-=h zM^ZQ}N_OhlrV^3&s5c(>F@v$gfzj%!!CRNzO&8s_!cP&6&%uytnzLeTQv#26OAkCC zscKs748DD2+)9*L5oXO)P+9TvN;<}fu-3Ivm0^QP?;=^crTp1Cx%pfna+jwReW0=8KPk3Cx3wg9p$qC0Y+jT@-niIuNuxCg2KK4(p1IEe$KsL_3f~B+-9x+^UnKcw*c_%Ll<|xCnC(uDJ_`=}toPLU(H8**MvN08%W{t+ry--Nd%pazo{*ldiG zp+u1t_HG)pNmG>9e#%sFL3WIc=d&tMd@G4tCpc5G7cDEJBFU7L7Tmc1qpe`)2c1=U zY}G$*6PY8^M-Q5w8A+49*>GpBRA$#A4VzTvVXj)JsdmMXDtQ)J1st@ajt)`L?76xr)3s5l0>0nu_JcL&G5C`%WOCF{j|QTFu&EJ_Q9i zWG82#9%JY=2B9c(hM~MN8L(_ooUQaa=BPGTWb18d7I77_+fbFX%M^ND0)qr2_>|bt zNte&Nd+$_;ENMWqsXDgw$#G0~nU4U0VS^M(i*h~}q z#!)55FTvlV^&a3khllMmg^c)ti_IrN&heR{#2!%uY!|oXWE|c-2uR(DC!W=0&o*^s z9hkj>Fg)?Vy5WzBgR)Fk;K-wkZ$C;jnA6;J*EFm0Wz-`GtDI!Y2HcM5w7r6XQPZGE zE`^z(+=RznVUP4rf=HYHl@kv*MDqqUI<-Nxhzy0kU6)6JmxB8+i(Ho9hzk$Zlpzt2 zf?+b*#$iN>oYFX;%3Hv@IAM-(Yv*pB);E(c;2}I*Qf%-f8bzTFc)JaMdcX5W?vSv> zFD>}FrKxw1#v&f%8;5Q%QTj- zuO`N=&Gu7I01YAevAfh!doA{~=ARF|EXKH3{Or9)Cpt7adZPV6-nZ6$lnWMk(uwhh zWQE~N##HxXj5l^3u3p-;v^>WppL=leXd?0UDkg@xd(xcQRztoY;ff0hltjoi18{9R z(<)E(DXZR_pD;4iQ#Jpk6FAxbM<+P-Nq}>+rZo0Nt8o9f7xzDXw49`z-2VqBaIk+3 z{vVvcLCVSV|KNl#hJok*+HKi+zXtzDH+;bioIEKeU(`a&9|wq(A1~MtTpa&Ds?e;r z7Qa4-7OXc}FGR9;41G z3ikzqKXqUUmBMU0oBSE#uM``X4u}jVC95!27!G4OPO?iNzAP zg5EX9U0V38A8LI*jGgv6^Ig9jc!1I{Bs|f`F}3trxsG%qNJb3=l`Si8uP=u#CJZ@P z;l8O1{0tqdC$w?583`Rd{mfO0)1c0lm9dPe)=@ueA(mfC@4t)tE<-W-Lowa_(?br% zA`T*J>A&|D<1#;d2&ZpAl6`;Ntqntq3q}hhiLG7tI=4oEKL6d+$|}7U zUExO-G1E@mm;fv3g%s8Lfmt>Y~Wui(OF8p9GeNQx2jc7Rd??W>qGYq6T z{Gqnd=s(#qxV-IE%|l=D{AJ8kVtGKH@yOiB$#0i@ayBNt#A}s8a#?AHcihsE*X2$3Z+6+2m|E^d(c*B5y+!q1j1V#p zl!3XpSlE)jbQj*tM=U%30f{wNu&#AUVWmgIkX2sdi|>z0(O0Eiy#Q?GI_;@+uIz{H zXf1#COo$~$7P0JK( z(B3^kr(Per|BpwCrIs^7cbqZ84=#X>=BNK3J`bl)1OPBJ2yW|*!k8ODqf}`Bl{Q{6 zq&Ei10WGdgp&f5RQVK{R%(Rl?qANc4gt<@D>(S@C#j)_qduegE0WH7%e04Vqf3>3l zInJ#(m?EUMo!S1(``53S#h3dIJm*eZ_*+^(4tvU zfQUoCGWwycP+d_^ry`|Ok5&)V0YO1wsB@c-Q?m_R+kBsu!vyXup=`9R$vZ3lA>?yQ znj|Ayk|*E|r6^ae--&u0U4HExr7969`;7*XuxjwJ?_oQg#?Fu3AGCLOLtwq@Y$Ye4 z@%e1SVo!@WhL?30la9|6Q+b}Ej7QzZ@A)odAZzcQKJv0Z{^kXlNF9ypT?C77HTXx;tRVeyh1PR<~{*Q4ybR4W=& z-oi)|lB#Uy*I{(#M5y|^5@+o9>={wUS=AJk3LnkfLl-d2&*&C?dP!9sm6S0s({x5^ zc@33n8s>g0FGT9Ft=A2!&5#gZ&kM}@Y0}VNra$SeJp`kb zI|=iA%#A=JmKizO4m4|(BRCAO^6x~#)rV__nM3-Mf72PofZ+uO^ga&?&=l0tO{VF2 zZ4q5I;S`oDv-?<-g@C(q);zGO?=?jWr!jvRb4TAE$KO<2dBO`u16F*Z9wB`?8T?o@ zSit;vHc21b7woZCkE5<+Ubwd6*OKxWy$k|1KA4U(fhSMy}<+iK$I&-k~f10un;@KJ* zy*~h@@V9J5OS{DAuF0s#HaSMr0~8T!-u%jHO&x_U9;%Jt^$=_%lng!=ex*%;>)-IV zz4Vk-R89H6M)+M5(C-**N$Um~1^^U0LdI~T5zK!oF7HdL^T~0M2ivEm*3kLR_>1Hz zuV&*|))g`Hp7o%p48I6Ja(e~xdyM+K{wazX@I|(8`K6l~tm=jPYX{pDEgK1SY zRV#!JGm86R&zQT)8C1UY1%kWhXW1Ug+yCMGwEoAN!3#q7&pF~YT-kMLn8By4`dzq- zOtdP6qc`w)sPgbTwDm5?JX1cf*%)!3i@B^7BqH-l}uY5M(I2m~nLq&a^| zhF7PdQr}CG&V$vtX$rvRP)vvgFF9y55C?#BE+hc(w>X{r8mzBa9A%>((G~J$BOg*}_CI)HsIkvom4l}~*%4Yyz zBL=>Jh6i?yDqKu9T0-V`e=J#w{xaiy5(E9Y__EkM@XnD{1VkM#cvLF(-6JO3?3jS;Q9)KpiPV}9+DC{?Zm5xdKs~99o-f?!3 z*epp*gr4l|;q-!2Fw&8I+1|pFFsi^>6y5cWMRr)MifZM-w;U^iRFehx5A4)Lq&7y!IWTp^X znqdXvV_7LmC`g51KI6GgxE*;Jp&j{`WQMYUhQcNzinBH@#U(Fg&+&SofStPLN-ao( z@3}Q#B;L~mDZY7Z(pl$Qo5v>op3y!PUPaVRy@%BW?^w0N-#gW~3lb7;1m`4}$C^`q z3s*iQu)zH1X4pTj>VV9CU^+uM)w;id*Zwbg6c(AVFxQ_+Uxo=`O57Ix2?ob^qdmu$dx!>R?jvQ{(Gz)>q$o}($7|+Yw$Ub67G;;i- z78yZXUpS0qL)kA22(xX)i3HqxS~$Sm?Tg&jqgE5Bdu9-bt@;L8h4U@U3O5_rT}7UmOuq0(K_~TP zXUU`ocuRp+W*oxlb9?f_a*2!FLi8kR|M*!<3um00%~^fH^HyJ)~z2yJ%xl_ZuFkVx+^tk@*k4XewOtJXQti{0LT?F zo_@p~g?|+>RhEx; zT@3TJQB|~)1>WoLxN$aX=lz^NLMbEaDnlCDb%!W-GdvrXgPbR*a!f1iD@qWcmQ+Gu13vIdiwcxrwPkuUbv)(iVKG0#33{WJuWSC^+v42nj8r|GIVdPsI#VGe*fs#Oqes(Kd#fv-|yQCbIGB}i2Wrw zB8OTOqdP%H?2_m7WgC!(n3c1*&?lnGP~XgRnP%LnpPrh;jCGdb^>Pc0%+EYsBn$pI z9c@$j8hwA5(K@`;WtNVumQ~hD|HNaf;1sQ_g^5#&^KMsX_9$V2T=UIzhV$q2F*@tN zQJxC1zg~J9W%z{+A>+y3xK@hQQA6r?3?%U zfXd&8!dwqhsR0fdg7OSV9?2DV9)aqpR4sA1GW$h#?gNVb_qOZHC`v!#Gwd`igpg{@ zY;4lKp#|!EGOH0}rXib*r;*d^N{;cp%^K}s9OCQ9H$7!K{w?DHr`Ve=Sa9k`BP7b8 zp7e`8BPA+%)mP4%f#M`8pJhw8DT&ttVS^D$hsc)c7MGq$%6oEytC}(D(bw` zY(2YTD8$+a6t;sdzs@mlU~yAf!mHlS9q&W)(|fj7A@I%iifYX>g)Cj4LsaN;K$EzX z?uq(^SAhHRhDozxqYSRc+KCKLUQIo>l3Hk|^1wQ*_>fcBbZ#Jruib`2F-xTa3`MKj zvKSaj8+1j3io9U?b&b|^$xyex&R}M%jJY6brz0B#R6_b0-f7I%EJ`q;QZ*9k(s#gUiBFAkBm!ye&R8*KItXAKIsrI zE9bjZ2PUg4b;v66dt@J_ayaBFQLYJbklO2u7Y0!sqw=bZ?m9vQZSmQs^Ha}$H3@Ot zZaw%iaF>I4LI$b1V}9AJH!>Y9W+$O3s39R@Jj+xl1gEg6fL$F*gN_Nc6O!v&Y)qj_ zO!?o|+H#-mIG#nh4Dz-(?;!%1QBOLv$xjucsd3f!FoVa ztjlFNHb-AAnU0n|gYqA#5_qr?_>->6Z3wYJAhZCDJjB0{8c|I!vT$T!)|OANk;2#l z$Z4<4z-Z9yQ$$q^eA<>-mZgKmHn)_p#5)0Fv-zxA+GioxPiUW~wK)i8z*#4G!VUY% zPtJIBqw|xo{-H?Oa<@#h{z^HCz%10ww_Ek|k5v)>AfO0l%&;rfZ7${t))~RW09Q*0 za3WnEef{--6G{DCYwJRyrl}dL!k%)RzPYllrGR5O_8P15v$0A{VwBrfZWcf9b%%UX zGDQUyw?KYum)@s061{=MI*nyb$pcDCs{tw&rwkIl&avj2vknz&m)}8wnS*^=HS-ht z=ZkV>az|UX!fz{Ztswf5?UrPos{s%tFrpXf*$z8xjQAj6GYZmV)^D>v_9d$V@@mfz z+myV}9WpdpyU#-eXig;hu z_EyP6Q1mvusS}YAphy#p!i)+IXPSzAR@=J1%R)wV}iKLUVh0TqZxtvGc;-522O79{uN&ACk_KTgph!#Rpdp-Hcg!L}V zBrk~6RYqQ*Ed_dvg_vN!ORT7iH6vWW0Si%~ZB5QWyV6j%b z#&5WlG_}9d@y{Zp4z(~E3)#;nX&p1O9W(Q)Ip0i(1)gCtq~72HgN!+7z)mQWzB733 zbT*!hA^P%30O5LyetLj2!A(qV=y-Tj)p6H_u(|E56V~0mM^Bp#0xi{v-(@ z>()P3MWpDAEZV2D?tfEd^g7gxYI)6RnGdHaUBGm%kc|VbQ#>D1?miGB7d>wz>Fzq9 zGuWP1owYc1ea-yu%X=e76>Yi@Gs#!~c!DKup9Q@YpvKGBEt5Q0;mhu~F;6vo&Q1rX z|5KkzDAkn&0J&;zV^ZM@YzdbgORq>-GnUgc%=>k>F;xhiblkQ2Y=U4 z^$0|xm?g}qY2G2!$r#;-Y=-ZueI!dE8=Uz z0Rj+Ad5a<(o_DtJ#jwn5F&1lE)O!cx@B`UGqQG3j=bNr;E#?~bLm5kM2+Z!rSw^=H zBWM8yuK|tVfUg5M`qF}q5zYlxD>`2O8RDH!9I_Bdh_9p&*{wv4>x{d;{fzoFHJ|J`)02YW<3p@ej z^rc#dW&xxCkRa|?@NEvT0t&|aQYZ6(aF8!P04v4h-3Ek20KiIL1h|3fz62;h7d##m zK?o24sVo5wz`58#Y!3j8))QiIP5^)lRM-H(Y;^_zVgX+r|NkLKL9UqqF926MJve6T zxeCDUE1rag+3KJMAOe8U7{8)9>Rprb7=#(TMK-rQ9fCGSYaeyjd0m)xEFJKy@ zRT=KTOQu|ZV1Ptv!0kab%3r%G0{DYCRK9klN(*iQTK-b4!?fT$0Faj2SJ2f4d>Is} z4!~}$Lk6G#K`pWAUvP&pc49E7R+r6SP*6QIs7)w*sB zpaX#T^}d1*<$wjysNUBcQAhAl07zW_YxN0EaB0w_!Iwg@0(63I4Zr62+W^=Apai3@ zIjZj9yPzTCuh+nO01yOe`lZJ106#z%|4~l&fIpxJ^RE@R1;7yjpb|R(79=|lFUS8b z>2vj*64u(#K6-lpkTi={N0m^@1M~}yjba20U16Pr1CQ<@EaqC!yLppyCR%_!Q?9al z5B4b=n*hC@xZ%v5ER% zJUxN+-Mx$RT(|Sf*VBA(EqP;`&ME{d++M~vp(ePB7RQ?l`qru-?W$%~xAb&>pqa%> zz(ST^H%E2@MVcl1s^`QtXI8_BzBy$vLwxg!=6N1mOAFD_n_^;2K}%h$axp}YY0NR7 zD7)vq4te8g!t{DNjvRAvcGM*B{dYchnZ3j3&u0#_QRgU6LZ4_#3g2V}v9s2ONZ4^O zV(VW4{l%NxDVue~ipw@or8We8zLg08ACtzU1t{JlQvdV}cncXi)b(BE3`Dl4Pr zICGEaaT7atE_**8S|3G>+*~JKSXU_$S^~TY-%j`W7sXBByH5qs)v1%riZ7HYri66V zC)-D@7`J)ys(51KhDIofEj7fieUa=;;9KerH)+uEa2owb!pYNi#My;@0=FTwoZk19 zEtU~oq#dvfo7|MgzW3Yaocl(cv+5qcT0r6WnPzEp7E~@rjSu@_>kr5=>rUa_ za^Y|*&03kI#cSMK=>4UvR@4xV_f!DNwb~^MU3;09V@~OmjwieFi)-Z_A3aK?Orim; zv6*@;W?mcx9A`WQ4el6NfB+#>qyuUt@*jjEI}b=0h*}y8W#ur1$LrHl_=of+oSu^8 zkJzgO#0M&Pe$Pd%L8T58F#HN%XWMs&#Eaeq z^L*T#cQaZR?-Uz{bHb>b=UH4OYCbw0cW?AyCQ9ag6WI<9m8`IFfE``_o1LNGo+W?U zN@V`wJNS)I_9#%Zp$p1|nbYAyjLFgKOU0l3L3*7TV4=LjyI7pXINL6;NWk&1aBvcj zsn^nK{rbC#sGKZrUOi9+%Fbf+5=b3wsCea!TcN2ckvznYmM|amI?BnPRoPnyEwYwj zH{UE9Wq0ZLi}HAU7${)z^!m zL{8mPuKaEBM>fX_Rg_HUf?;<%rXPKK=A_f|zq3 z@q|4yNk*l*>QctHxMvMn$s2i5F4oVl1z)IQvPYai1O`oWrpg=k`nx#KFg$Y8 znC)f$8q`!4T+bk_nF8MM_LZ*YCtULu%0Kv+9KU zUG5YLYVV((FOW%K*QMOaYZ?<7{Sm_2%DSS{= z;BJ?+9J-B{*OCs%8ZdQU?yse#oALNIX?YJ^D`jBJOMr-E$+R!s3F>_moZyFrA4XK{}p~+CkU|1eN zbC8vltT*;;hasalf$(PhDLSS7d~LSSASzem|k#&N4`4 z;Sg$QS$T+G2~eZ}N%k~*$g}Z^!*Z$8IE)-znEl_o@3ksJQ7<~<(i z(VyIg&zo+4uRbgw|9!xIrwB`O`5D|wOs`W4?gK*i$TEBu`T1t4;HGMcuQ>kKt80^!;|z!0|(}mX7+-I&RmfBI===Pu+_tNgvT* z>bHO}y3z!>2`hKm=lCh2)q1%=sD2r|33#!SpMXBRuH%iO*4oA}rp(-GRwT^8DF1+h z30T@*&3sv5>tuJUda&pZJd@E2l?}V?A~7K4X}e}YCEj)eKvhqz*Lb&`IcMSJk$7Wenk%@#37#t$Hy zKCkW6UH|b>>1pozvNu^@)3O2OuS*go{zDxDbUx1CwDYL^8_VBN!($4aaU*@$z7kue zV0CvF%1=tp^Lo=@$Rm;*>P^y)DZy`C5KJ2I=e}=$WuSQAXphjSm-OQNpJ{&@S!A{` z($L;6NnKdwM8he`yQh^1eh(DOn*stOArSuYaRe@a{Be7DnEpN5u5x8dn7H`vI;O_) zP}Xw=Z3-^>J%Z%@GMEZI;3=H#_=7~t$FDXwHr*NAKEf$2=2O^a#a+z)_4D1kKBhb} zZ-i@8FU+0C5p4W~8B-vJ{bh*f0ZAT$>b1#OD&Eg`r}q2zs+12ZXeZd+kst^dqe0=#`1Gyc~k{GT4gKqu&B%>&eiMBAgaHTh?&GZH{oDl&lZmn8uWHX6j=A z2+fePGTtFs4FiP57-W0_HN^KM;-WQ1+okMONr#EaeYcRG-xM8?=`w+c_ZQQ9kt4hymVN^r7675EH(a*h0f+DxF8qO?Q z9~uZ4vO5qWJ1)j^{It77uC%%S0KDqjU|2mTElU|mY4)_x>(0#bh9%A)M81vh5B=X^ z_kZnFL4gne=&xdeOaq)gg~d|=(;8~Q| zNV$0aYfAp5*}wFEDT^=7@ufLHo5TPDa30RqS7N{*Jp?B^FG%bZnjl4F5b?kMVcy_e zzzKb)6bv5pj|-DR7r1X`cOU6R>QIb^6`>G~287;WD52iV-x`K7_NteV8_V^KU8EK{>C<~*#$w8-y&=`Zt_8eh!Ro%`!N)!y1!B=A%b@62@o8~OhVAcO$%a%G((hu z$!`GE6rm47RL4qZ1YH<;{uziOOH^FMC6_i!v(UoU#vp@k;Ro|zC!L-bi_oS)2P*4I zL{p-Wn^zyv$#cUbFoYJhN0tyiRX>Kskoi-Kv%-`I;|amEgbX+$B18H#{#(a@je*K= zEYlqwb$u2DF(hxVVqY0*1a6btc%IE@>Dj9kVj0V4bV-^ca4dxr3B<>8c``zVs~1@Y zjZm@DD58HtQsR=vF?J0q5@N3#0PQ8bNNL*<@9Efwr%9O8#?TIyAnZ(U#3wN(bMYr4PQQDHXr$yIKC{8t`=rz|OkXmjGNsIIb?BV0kSwx;2l3qI& z&{Zn6Mf~CP(Y6*=CKi^CE*hCj#RA^aH+#EXXg7VHf&#gUQ_?rKHxEutwq?84bjErN zr+>{K%-Hw@OuC8R@8(=nfH`{vj%&0mD7%mHwZh|jC;l^>kzVI_YpsH4W}oEH{dpNm2Ik$1bh6O==XIMUY6M-e?w>n-B}-5_o()8pL3?B6E`htF=+njC%Zc(% zCwWZPySva;%zI76k>Yurz}kU$a-piJtfa04KCZci};Rm?+--QHPsm- zSyo}MAgq_NHVV@mA9VjLJR)^rFz|unxpCHGt)SADm>3rni$OGG-auUFDf?Zs@8^k( zre()+wvLb@(`^2s@a3q=@%A`ZNNZq+(TiS}+(!-{i_YzOw{Glx(8gObCY2k^hI7t` z$g|FeokpsRKo&%=YsV-n4oa|Gt>DX%Gta1fOSP%P3AzCd6GpZr8yXa2ZIlL8my_dE zUFAs{h2UQ7Ih21=O}gf`W(-JE^x50zP8#7{y4MVBz?h+wN2DC(VqiB_VE$6ot(8XX zqmjm0>FDNaI_E;6H}Q3GM6x3G*uwj*Utg#bCCSohvNFYU-3Z+a(}!IWV<)eD`tDy# zWxe+4%%bo2jdZIA=JvhSQ>tP-O*S6Lp~)I3au*OIJYa5}qRIasRc{?u)$_f9at__y z9SYK2(jg#7r!+_--6DsQ?mBdebfYNUozf`XAl-d8@csPmy?^kqW@hb~z1f@fto6QY z&D0}wLPTQLyu`G%VdcEouu>Z!AE|gdZNydxVYVyKQAw%HMPnKpxDQt=Kz&)5bZa75 z8GV#kTFRy(esJd95+Qy=!a>~4@KLwy z5?)zyn*dv8JIf-srzq`H!WjmO5E##}`MoJ}qqkYQX+7KQx2V;yy0RWCf3Lt|jV;TG zCJ|-PUKW5}vB=2lPoLu0sV#|FskhSlYjqEi zMt>bMH1fBd?b@v|g+tZ|oR?!Lp=zSj_4r_;R`2NbhoGzM7L?@f#=*a4yLVi%sy5Jv=)}MOOLd+I$k*5`yM@e<*^GY5A zE&*pE)1CwK`&VPrl9CI|sTEF{HNQ55Dn^<{+%wgVfHViav;x+VKZ<9Yc2+S>ERnLm zR=#Jyxhx)I(!YfJ;JO71-Q8>| zIAwuFgn?Db@AH&>Fk7Jdug_4t25)VbRnZ}H-$*4aKXC}z{`f9LeH#zqN+D=-ZH3(s zt+LQ9M#;kP$|c_HPqlRLLgd+y-dfZ39LbxhuN55H28Im-$BdAiwiO}V%7_GRE z`wc=ao^!lLX`>HvO{s>1nuPIuE5aC+{dZKuS|wMJF*VUE=&hwz}WK)Li-fiMmv*o8ydBK1WQmz+v$kF}# z&Sh6Z|BuofZgdYiEjH&Dkr?~H#r!sgd=;Z3v~WcAVp#B zl+4ghqL1H$u^25045x>lc>P5xSWB1p8Ee%4uI{Pm3+_FMhMb(3hvCZI*Xazd+0Gqu zz|_;EiL&mZ29mMArS88uMzV9QJ&p|#7fDjeetTS$eG%ayM=^lgHt-pag|uL?zvg3> zrsBH7a78-g%D`u-CihnR)RO${NX60~&GS1&*`Zz1o%H7)ou`;OUm6BDE+lx7`UPN6 z>msH3y<0LL{zC8s#9td2#71kLb$#%5_i`Jn^k}qRXrem$dS5f>TM(g>*Al+%LV7A< z@2Go>^nq|!6lS)oJQ{9M7WInggM0WzV3nD?2>k5!vU5zv8?qDfiWf>^Zh4bb4P)KF zkK)zDbR2rGU9DSD)7~2)*xAULqTssuO5B+FO3S5sW5}Z4zo3lc^~x6(R1L;CnhY+m zBjRqb_O)>%5lu>EUe~V44~V@OFh6p4VVDO@-Q@{*3U2hnEO%aGshb-}Lfc>TVsw7$ z-eb7}ec-#4X$xMEaC)7cP|k{th53-*x3ga)%3%8|kY6YS4Y~8H!w=8q*Wp0PY#DtE zdi_vU_8LT#E*2X4xip?Fnjg+znPEv8gTLKGiummYhsTFwp@`3NAeww;+#jS68!X%` z^^a*a6!nA-F4DCYSuSrRtXnwP;;YsMpToRc{G9{rpp?ck!7NnEjEOJeko^7w{3ZGGZyJ>h(R z{e&wyJDNT{qeKbpv|6mIqBQ-rRT=KCx=a3e=)9EPmp2VQj9xiESu-&H$qA%rvehoW zwaL(i6lf9(X3WT$l}(>DtvNRoi`X~KLAF^UrhkO7+l#c(M>dKK9)=d7{(8%?j}D&% zwNJ9tvom76<1y~TAm{{#sh!rZ*lQczF4G4)ec5g#?>1>BC$LcU3_qXK+N-cw0?(a$ z;qM4Ubosnyo@;n3u1{`41!sk1iVvy8qXv$@Y(@EH&wvkinJSu9jl%TxNXPpcz zR}oxwX&>C>#q42s5b97qw^Y(g=}oLp?A*JT!~2?}bUIi#+y2DywaLgDd+(-8p?`mX zH?Q%*o`?kH@#_!+thy7M;4*D{Cc3{Uv>ydt+5P;zVxPRCB^@$fqAx0eb}mobdESKc z3*|~Q66OIh+~}_n)DafoO+;-$=+N5`&`ao<9OwYV2R#e{aY6~@K?7hu&SygBaR3ZN zH&5)&;|QPy8UeH(nI13?-xD?SMBN+)gD{{?2_Ph>oDwJodJqCaulqO$vIjv!LxB-= zMlfPsB{dkJWR$}|7_sC?bs4H4G7$723{ZTx0OA2b|AhmJpC>_xbyympHV`x<0=Pdk zIxurx<08PvY}&JP}9$3StD~)|F#`uz*G^HtsWFqYwj7CC`M-(W5wT0Ac_^U&et5 zpdSlB<51jqp!1oWDFa04UJ=L(`YHkFWHbf2f}js5V5|M3d(cf>G#vv|W)L^i`Hi+yJsppnY?rgz4Vw_M3G^;05BE9=qk1yo4G#p_*19+I_m9pJ8q#uM z8q4vm*VH&vqn10-i%oQcR66BP4yAtz7~rFuprTI+SXT$JjO8V!q*8pGSQqGJq=$Hp zUu(p9y~D}%=tiBH(z`MCM&5i|{q2}s>fl9s-p2BXA(9z>>T23`acRO5=MQ;~W7LRJ zzP~$7FpfA)nkV1m4M_WKYSFCq__}#f(iN@gxhw^D%UPYx17Sf62p`ys=Q*tnPcX3S zq5B#Ni~SN-`Jc4w$VaL)!e#S*kD` z@`Zj}zARJF;wmsn)ywAH`KH(X>z!7dwr@jGr2JiF6mq0%^AU~bT2FN^Ayw7`J z0x~Zk|A&R}0rG!X2tOeI@ASBL0)YHfd;;imumg>!g@qqm96;--mgTX*2{is&n*&%J zs9Jfx5ny9ZUe5nk2X32}iyaEUEAOEqvf%K#GDlDW4)9n!P|zSK9g2O0fCt4Q18+m; zz5%8HFl&)e&4Op?C3JKUlmPJ40Nf)56(t92LuZN}hr&RIP>bUK)HnVoJ*$H`xt?YQ zj2&R{q@cy4pkL66vS*VS2@5>HvsHYY8v3u|(NqnBVxcybj~b5?-&X<`2Vw7GU?0 z9;tH-5Hw>1Xg?bNM{^tk=Hac2)d%qcYx6v^^U#BDfPn-h!Qn#L|AD4~NuO@u$sPl@ z4Se``j~4k86!SMA0rdS#=!{g)^vIED{1#E}O`Tt7Q zUw|Xu;jkwVgs$;^lCEm}!kJ`!0$a@dO&*ykLKWefgjl4_tgN%QgvN}tJ^ zn#^!T86Je_Z~RyvE7Y6ZQM^E=2;?A~3JL9W@{%y1!`) z@()2gnV+)fePn%0`#rNGg*cVh@0RUtGWb@Ive)JEHns2F{VRU6BIrijt6?X$-dwdw zVQ-(qxYDIFS1DAtc$kHU8TjSxo8@JT%kMVj$}W6#E%>+$jWpKYDhaK`3OM{UsSF7?~Bo3AtEEz-ihDa6ogV!9g{22l?J^{H8As-4JSv7 zkbkVlo?wWFs-1tIXGEKz;v`-WJF0Jpgr!jAEfB0t8^rb>$p>|8P3C@9#WL*YuHA#b zL|2;`OTdj%C9?7>dbk$<%IK$C$TRx3!%462TU(q8+D~@^y}$t;q~Y{ASn8nI6Uc`# z`#tt|5m3R^LFi}(Cz?1PlZ>l-_uU=WFVX9vw#c%zT%wrxiB~fEtiQoj3gCi`qt&ls zcC<=^qnxgp1_+K}XHom%`!-4RtG9w%i7s#(%Lq}GR!Zf)>M-v6HlKdGQ$C#4Wi{9R zLt+!XJ3L*@>sc*$le{!wYoBt=LI}wSfHg0zrE&E--Ovj1o5NA%Z5^;Ci!i>VBKSCZ zemmo7HBtDMx>W+PlnoCxT(jzz8rScTZ}Gm{K>YF@%`5=7i=$|Hw(=6&p8K6AEvZU7 zL8kYImQNQT>a;6QlEgTVTFf2s9efoO@mFWn>U7_amf&bOiVM?UR)W5CjIl#*bxNDk z`#j=0$8anDeWoCokuk31=Ui4PHH6l6!;cOLFKvbT(RONtv-1#jf6BZSOtZ=lGI89S z{E?$Cp_qBJe8_SYzHNkrf>$Nqi-qtb5DEe+*X~Rh(Qm%Gg zEZQW@5(9}q*zXDRn~7Apmm3&Z+?;|z=;*XAh9eGMFM@GxS;%=iOGo^oAo2W8BIzeH zIoUs?y_o7jkgR3AUi_ebvaSi8d*XjBCS0!cg$oQWfnDr>5s!LNVd#W>oITJ-3|T?a6lw=+LXh37vF^#LHS+!B zC9#NXQ<3Vyfq;r7+R(+dfZTAhk#9jb7hyCDUxd%!9!@Gwrk+vG7l;LN8`)?1e&(cO z(2)I0&K7iZWY#Luyuyi$E19y)$8f3po#gLu_AB!-(r?;y1|$~YuYw@fVMoJw@fu*V z!)*l&U%tWUJl=qid~*nF2Q@Jf>ZFp8=r69BvPo&9ufcOs*=C3FEeT3S95gt{G14Dp z5>`hMEq{u#i;A!Zle~BcgYBSNq)5)8K5C=m)T?|0yV@Y-kHtwc+rb*D-Y!*$bYR?R zIKkZoNf3S|gptoGZBj^HE}spG$RYi^8Dy1SVntE3AY1um>~lWEo<-wLo2o53`Lw!7 zV7tl`RTe2cZ?|iJISSQmCbq5_nxw7Z527pqji%N5P*r~WSbyf9?sVG4KbKH!o9?}m z`-^;5^jbB3IfQp@abw(lPZZI?@xrUvJ4+3C$T}BDI=_nL|6-6L@P**|z@`kj1`?fZ z&Dh|0Uc;Tkev82bX@`|>kN0MKMK>(8k6V^y#KCI?tJ8g`cjsdxU*4{YXFjs@ku%W( z368Hg-{_z~{?qrx0{Wns)+?dN0}_5b8|~r5VC=kK+U+Pj=t(H}vHn{lC^)tZPK&%h zbwKlPU*KT?q6@(QP+gL?n z&bxN=ab`z?P|BVwus1C#ECwCzE~~7gBQevOg`D z`(i|AX(SK#UL&+tCYexaBy0QTWSi(RH*$L&!HZRQ4a%F!kMcLMB|>Qz7+&xl!CZVX zf*)OR#q%o6fQO8#hQ~IWY*MZ*8oyN1390S{UHCEoyq8FbgyF!SIl;Lw8_6%GD^U zg3@`U>qYx7!JZ}ieDqOJiTnj?J?NI0gl4}jF<<^id;uiuc7 zl*r*rBzq}IPQaXcr2523E)N5dzfKfhvBOAbnyTTH)C7O|B>uHm2hzkS_z;|(>V&V* zsmMy^6RT(61%t~?vMgse{02pSX<7y(Isca7SKszDS@ytY62%LgQod0^DwPOp@E(KL zsK1*rIswG@G}q=PbqPi8c&Br5?dzHJZn#un$iG*@N>m7OxmafsLCMVSkbFLihU*~W zw>{AiGtw~r_zTNRPD36gw~IIA9rF{{w}@2%aRa|qRx{V(QA5vf*Nwoiqg#pClAD4% zBqhOgi56l~L@#o;6=9b4X1XZ#);VkUe#ZylRc+b!fr1)nVBlnye>7s@9uV>Z@Xh?HsjSFaynbV<@hpkph5D~2@>dQMk`5;Oxj zlKfEFX25^sheDb`#2Wnn7e-L=KA-mlL>@rkA@E-i1H>Hy{{=BX*dg#=5CcRV0{;au zK+q%bU+@G3Jp$0ZX24Mvh{rzItUGD}IiNxj_W)P;$>o0vGBWo8pY|y#pg4Gp3Lc@B zC&%COsreWr$Q=Gp9%ZNYp`M_A!L=i9DdJm=fO^0D(m#cdxEpahTup!4Km0|7)d zh`r|Mo)YwU*^__$6fJ=HIG(|jr#xFes4*JoDbdyv1T`WBZsR{_hXMq>B?Y7Z585FG zL9fWb82^KIpyYt!kOmm34oJUc0m1SCX~aiHK;WT-44@;x3QxBH`0X|zj>j11Deu-z z6CMa8@PLN|V4M$7E(#!(7f8P42SKL*@iB~;g;G)hodA{tB;Te{gYloSoFN)8VVwgO zhz10`rv*BJ1CV<+V zf!d%U>_8t7Iru`U9$_gUKNlSYUF8Ae!Ex|&@jmD0CKB~I{oy^`uNaL@ts?S=tNWY! zW4m@dMUlSwyRaA@UDZY|)(5=J-5Xxnue1eju%~mV%FgtLELu^BwbP7cfc2DP6NW#x4D; z8mU{A43MzN4!bk0!)6hM0DXIx1Vl#9hJ~;BC?X04<6gL%;-V1>f-}wER}VW2#*N%v zc?5;b#K$}4X$lq8AXTrMj~uJL1yG9@BA315&8!Y@)?daCyVmVaQ*APrQcR2e$c{o$ zj3AEAO*hRz8MP_{tCU!K(Vtd94LuG=I_#I?A|a~ADc@`h7!vTTmUh?}S{FL1nEg-2 zFsAsw`mvbv&-fjj1uT_1M_8F(uM($BX=YB%FUGzdvP^jsM(gwKvX^drFL}b<=vi9RT^tcd}s6ZLOmCK@RVqjq_EXhkr*WrDA{C%$>@4k2{5bjr~ANyF;?e zB8{)&kU!`W=-fNuPqwD(^LS}b2~5yyd#NkKhk;i z&Dk29ZSwNp4FU}^*>L-GM`d`HQ5C-Wk&BPZ2w;8EKzu%+AuBvd9*Fme*vm`QZ-D5O0N9SX_^gUk* zQWSm>ig7a5MT``)yz9mj^Kwm1MroH(7az zR-4+#v<%Z3U@POIw{C?9?^wTnqz4sK)H86mV}$ECOnC5RHlSc+!@;q^lTt=~cL=u1 zdr>1Mi{33^N;r2yy_Hr3Z}nO-0INS<%7ip~1O8Qe0Qw)e(-9qyKP7Hrwm0H}Lm1!G zd49tL>`+F3Yv4vkI9D6Dz26gv`%U-H0;&89WMzR?-Pi_FR7q zyJee}YhIp(t6Gw{jnO~!s8Cgb7n+J@#C-lkGJf2apki?(HE4EmLdtwpr5Lc#`giW zM&`_e6=O;Cn)GYcX}8prujKq? zokV`oM|aeQ%)aJKCK&b=-u}iFCp1`n49Up3jpQCq*4-_s-#n2{^>*lDqZ2D?mo3ry zBpRv87X3ceD`z3w=yWp5`F6+&B456aAg@T>j7U8(tiVKn-~{6?32{PmYG+fpPYTe$ zmR#7GCQVN;6i7xDOEgXwwm}I`l{awkjQiqwN=_mrz&Riu@Cm^KgNm*L*b4=ZZYIYJ ze+S#EE3;~!e_}q*+i0y>%ShBrQ-6Na6AEq+J-w z`j;;_IZ|J&RGDc{sTRc!m|FlU*9_tY1G~&;0r`BQ zd_4d8d>mAKJpcK8oPhkF&&LJG|M`5}fc&4&#{LY5J2e8Pct&dZOaSrO%|iPCXg=|0HILGhbERqyNKYkCtB=x?bERtm zT=HD}#J>)B&j2w}1Qy_Y`Wj&Q1h^j4I|(uP{?EM!J_iA)I2gQH*Dnj!M1dk(1Aid& z5g>$kdVvBw&z|_8J+Q!2c^kb0u)uS9+c_XUm$$uk0zcQXaXABBPql2-fbL*KXn z;u9VZ-Fg(C;rJF;Kzx4X>Tdt{%K882gag%UWFRpA|D13DbARzvz6N!52UOpgfLoph zpFs9UVieGP1p1$__{Xb&&*sUUev}`v{wE|JDi8>Gql)XGX`mbUTK@N<9~+O~%j2sC zo;wx~_$B~Olnz*d^Dzd%gW48=CLSBWCyQ4XgAek58hZL>pLkGU>=EMszxN8vf?Wz+ z_lUtiUiWkdk1rRNpOd$)sthCn0#qtVLBO|g0$Kr7p4|URkoBWB5QN}CeJcSLf&Z!Q z531_|j{2|c@6H9>@mTct^tQqLPep&voM|2$EFL@+7dyxQirs+iEaHJ;x8{S2WLga~ zU^AR*`qycWD<7Cbg*8Mv1;psyNCeS*hY>jcSE1A*rb042_x(E|wk3Dw-F5xh`F`+p zo#SU*8DsLvqoMh`cPW1pRLI{DpU$N{z;%E8VU>!2BC50GQjn%nr|{Rc!#qu0yv8pp z*x_Wc;iAHxOPdXXI$kR4(6nWqCV`ohzrHiX8x=2f37ntiG>j%(s=nd3qigrqZihL! zyU%(b(tdA5>9IFZ(>{k>nlUh!#j8QmTKknD0D(ZU->BBSF4S0U9L-hN{Ay z$q@fe=IdgsprRhsNCl$(6i=aEn(GqByzL7GA5=d7FTM{DWJv9wC{0ugE~;(EctXGG zH)oNf(WwUivb|QLs#!!}K28tdd)>jaMb<@(vj(-AcqBlnGEcxZq%`I?vsg`{z|1QyMO*u~Y z!r|ca9{#SZdqaHY@U5(4id}r1cZRN+*~9(fXlSIm`)Fc2&vtVWZ!0TL=vvM_uHYszj8m8xQ zF_*F5nSMafCu#P!B690!f}$YxTgN!ZO50LoZ-4#Oi-;Q~^!(?+KSCeuIJtO+e|DZN*Q!}`;?t;xFut) z$Dco^t;zG@5t<#t;`UFq!*lwYDVR_PPJZ`v4H;g7J^z8>rj%giNm zN62g!Ig0g3;pUS+?9I~^#^+zIFTbnO(-Gy&;IIo z^hHy0)Ld#%I#o>RJz1B|h?{O)8qAIu2BEGuy5(hXz&B#*ZJ?{dI30JUz8}Ek>W6S zFb~@i=uykll*h40RnQ$Np|R-bA(Vj(M|QHh;L}tF&3z4HFf+X^gdYARUIw|i!^B&T zx*Ct{^jR4kg|}hJOLgQ#3Bf92!&LFy&F<<#=us)~o%4=_``(3BDuxe)$IP2|>6C7| zBNl%GV>)(jX`128`=V40Wd>r+$`v>n%`MY3hVa9$Qd?-4L%qp&B@P~Uwr*}$$OjJ8qMI6fUU$L=@;VJ)y% zkXHnNv*T;B*ST?7b5J5;I%fBKeSZA=49R?*$fWUs)IjZ)?~p-`8YA|Pyl#+gJPSSi zA5ILLW{+THBw{3DQ$6x}#Q_p3JNf9-NwRIYY9uzsC2ab5JX{VT+sod8T96$g6|6#q zf+}Yd;k%g~ML7y;S$J`gGk!)bt%BcVnPmJ%7H`gF2B!uXxxdy?`FG2jgK($V`60iv z=2Hm8lilTIk>RewtmN?4Ma!+0WyV)fvhwKWKbYYtW2khLMBHlVUxw+zTrdWH`s+OI zQ$gPOamSApMKoJTd8H|dLi_hr@xq15r-&punJ@O|ff=(fRyH<>4H@HEIq^mmv_3~2B)W;SJD9XcZBZNAKoe+(_?wUqTD~C+Wp3t5V#MA@6IO_fF_Jftqm2V_Q_)+v z+hQSHts`77vqrrIs;Qt_-y&{xG!TU))eZK)if!v|tSJYmcTr{y3G>wqOejk5`v`mw z=%)EDKQ1jH^$ISIm6I>wVtm#}D%;Tqw( zF8m|zf1h6=TPU&4NHF;*4m!Bp2*2_qlT*C6XqBH|gB$uxJ8K{T{yW;?&pl+w{!35K z@s~?i@4HO?At+&AKoR1dGwqG@FqJL^N4p5c2Ks9bgl-(7D{8RQni7X|IM?o*l)c-3 zCpoOu22?}tOxXLS=HiV!9!(|c5DGaY<|8>6z3#8gg+CG7#0QJD=*y?#zLECL+MmsVR+uu4iBfd%Jb8K4~2l<*6c&piu zGPfh@$0*h85ocxq|bEzhKC~ zP*3XkJCW6>2^*GzaH9;y2LjuOmJB{IF1cN^6_~M_gV{5d=x&s8r-E&?(|M-8bJbps z@_!~XHhyX`6k#@s;m#xiT96WN6i-F!7^Njj0X*bB)vC9zjN=h@zx)s`La98JY?&7? zJe}>xBv!H(s(jts^t!c%s3Gi?9CIQW0cm(6Zi7}buG}OT&-tI_ea< zG#azX>}Nr=Jk_3%kPP?;>A-Re3IqukyT8_=)FDgj3}%p`m=27*uzW~}Zl<_1KFdI( z2ASSBYY~@tkKz-k8Cv{EACdAr8}3q28NQ4N=NZKk%qoWR(TAdBs{}tqFZ74X++~eq z_3ZwY_N7+;d=me#BA_p8n%PW>8{qCMhUuQHu-Nia7h1isbv z**YJCcge zLR*c6U~U3;f^+$8?xm?Zb3VmnGvDgOwLh$;3N4r*!+dyl;d3ZP0n1yLPM77X+IY?~ zW(V~c-1qxfWUbw?LWE1Cfx9<1MXLfhQ(B5G^nK=XFRn~oS+Di(jXML5?Gm^(vBt$J zzQVB7d{%B#^~}74{B^z(MLTaK%zFzyU1Vin)~k8T7=01sV-RJC*W=|iJK3T?OkL0X zN^(^cZ)0wxbUztS{rhc}WC~i1@l8r#%+CZY*5UP!WS*S$HYtV4?URA|cE6XT4b=J# zHP?3@ltvtXoB4exH#24kk4Jso+ENg4`;Pa4)Qy#ZkvYXf1QNWTut1YJ&>U7QeoId% z(HHJIj2Tg5*e&J@>L|SpV8{A!A&(}71cS+=p!(f*9pz-vIs9UYNEu8wP{Tw=yJ#Jd}4H1~emP zgHRg|dJz|GSRsWPZNV`ul9^#FB!sFX1-zm^zo#0DHUWxGF>Fp ze_>V^Ms7)M2M6_bHh3Lxc1 zJr^AyeYGz4q1L&@6vc$}d$K{?t6;pI1<5r5^5lp3!-w}8%@6Fjn;`=EiU`ahV`sa% zt@s0Yd5Z1eg!i@g8S`t|2|sNqy71=P5{UbNufBiZ40?Zh!c3<}b87c!CA# zb3+jgXJ18SRK4C=o5@@|RT%M)H9{T7D|%U^_%|~;OP3)Ahnz9~3o?NiQenO8ZY>tUG&li})F3C9^FD_QMrYKDTl-?NYrp zA%rcdLy358SrD!ic-LQxB#q(BA-G-};&-jO5fGlpc7EJDf(z1X+1(|tU)g>rB169e z-EBO(hozK{9CTbrYr3{IeaZ``d{j1HgwL1Pmgq3Ux`(>$5OAs(vz~?9{0o!0i2v#5 zk>n|Bm^q}887T49!a1j1d-JwyzPxHO&uU9P-`{Xhiv+T@G_CV3p#ExpKsuAD1^wZA zRrS$73}Ng#EUo1FyNl;maihJP)vbi4^faK~{~Uz6;8~m+ll-K7|4{-bzm26S zWjyb>O30JSIY{i8ThFNLT!s@{p#kTmtDZwWx<4U-&?232B zZwYSol7HmWZoK-KgScvB$BxmB*;HB7BDQX&d{gEQ8HV|$lQNH~fYnA^b04JjHN(rW zOgPz5cssffj%hxnr*(i&=em?t;)gtSe`$;v@$dy+mlD4;7yNtI;J~(dBoK z?jHtY;diUedyV)su@bLISR2dtY)HC5yabLk!}(!MRC=eSEo%R^hUXtCi#*cc zsqQ?&zM041!YacscNsAo^X2z>{0_XCqN>H0AOASFR*CxB*WH96$-@OiIwEgs9ex=; zqJ;}ji3mVVw-GSoNv0b-x&1OP^(IKo_6PT80xO99PqQ)h`cJuUS2GJu=6FcCCPk-s z)C3!%tk8Adb1sWDo~*4XM!LI!&@L~D@Lslck&MiyMZJL_YwZ`N@s z&jj;P?n_>jg^bJkepL+quJprBL2j8QG+?(HLe-lu__IjYp&mCbpo9)tq`nixx}D@9 zJ=!_cTN~C$@`Vai(Q36XaKguXK6 zCTsgLBQ{xleGb?49qYRaiU?2dkOm_AQY$aEY9@)+qxa1m}=5L8Ltp1Ed$5 z1f47iYWeIlgucy#!;q`IbS9t|ADhX25Ah7P9V`}EIipV!;XX@}fwy10uVPER$5nD9 zSBg}SIZ?Rvpb3Ts5WRD8HFq zmd`xv{!6Y8atJDH=vnnrt(zd4k<2f6v2}O4HJrMtn}k^#rwk$2>hCvb6f}5^)gk$_ zg;J{g6ZCAR$D@uEe+5HP>~?)F%Foo$K!f^M6;agLFSLm0AggV1S#``iB&INfQn+K4 zg$$It-EL_tCe?q=jb&RrK(prw(%7rbc!suCZ9JEH#e?*I5u{#=G&uf5ddG2DAqEm1 zTaLW=Or{KvQN+2v(SqEM%+BmX*T!K-aJISNzo%`h{+fWjO_ODZeoI8*j{4 z_yZtSl!XU(wuT}VGVJg=R;hXh`I9<3gGM-_cb|{5u9Xq`-g&H=9iaO|YR(}}2kwJ! zYX4y4xn{x>B&O2Q3^Lg3@T5a%Y^lA{{nZ=xJS{qkY=3XIhq@T0ViR5=Q#xDr!n7Ls ze%>)U*nqi_tB#djRuh&=rZD^E(kZEg80XCxPyDqPL!bALgUUr%c-C&(AGw4OxEK0f z>D{BqiB#W=b7N^dlM-4TvBZZi???3u&wo^Cav_ zS~||J+U;4uhlXn{VqeSFG>3dT=x0)AC5qut`_Pq^Yd%|1UZ5g;jjVWLxk9tH`TJJm zryTxYDm_smM2oqP2Q8lV&9erVCFDO$I>gUs#oILRhM_qX3<{n@`F|ldMSeRzmwlJAmL-$Ax$U_&$PjU1O-#9ha6BbV{_#@%cRy_fMt3-Mp5+Tx>Y z3KicwoTfLtL@O$0(G(6h?IuSUkt`WJYk!-xFo`*@b*{jLOz~GFGI~cAL7}vR0XxsY z|7~#jfDL&Q!N@871yRar&-Mr9txLT%hg_+^+X+#z>Gf+S`fZv^WlqQ^n;2B>d3kb< zRZl8&VQyEdX0Cbj#=}fOfgmCnf2q#qgN=HU`s!TVspUh4 zZ*A|o$teo!t2Mgh#iDk5%#%HKO-{4ihHC70exIwM=_4(Vwn`2_*s_>$!uwUlBP=~b zt2uOLVd<)JE9_U2nX+^iK_~g=g_Prb{Yvpv_*`aVLL~b)r{run2g(YwQ`6!rg`!+v zhPjcylU=TVTi`>ZURMd(9D|6Ts)_WBd~0V2J+SorRGj}RmTu$tr;UO+R0eLUN7|Qx zB7j{oHsG_6HO8GHWctIf0aZxaOBI3))KRk}DU~fvrj@(+QT+;dELQ`(8F%U|^RhDovzWT8Slf@rX z`bb%<;T!HK)fD}TQ%lF{`Qz3*Ny$#a=seOaDjdq~sOl;*mJuY^n5g$FGxreFIZt`l z+nlf61WIKYaJs3%DvXA_CixOg=|ZTJS_6DH$5_NQ;~#N|SoH)*%lm>N=&ci_{Fmv} z3A$y)v2lF4hA>5$;D_#9JRim%V2mzs+@F2qg@3R(@Kl_HsyYljx0oLsR&$5ApOzf7j*f*6=0=51CGRIOC| z-pH1O?Do+MlclJfHkJz94mXQlg&QW1aZ8`CFSwO~oADxT)i>nZc?uIrw(ZhsR_j%` z*`2lYN5~WrL50xj^%O0~@iG(eqAG{4tszYEMXB5(S~2$n}Td+}CED?jNAp zdL5cZNSk&OY0sYh>DIes9duXV3s$jJeLqd5j?+ASXsVx=i#qj7r}5_sWl@Qx%X9IJ zMj*hAglWPPVDhk|uql|?S-4nIadWf(cR01)N9Vu1arYuE{)@at4KW^&*}1vm&i9M; z{mq?@jC~mclrM2ulr%HPh9k&c0~>f0fFk&lK13Rx>p|6uka)$hEM55ODbIb6sojfD zI9!H3(oG4uM~VhG+(ovA88qR>iT7|rMu|&Y2$_c!^Jx5K>6BL^GU3YvSA{=Gyn`Gf z1nw#f5@2o*r^bjS4+|=_yYc2B&AG4!q-C>*snWIjI#I>#HM$uSsQzm-P7CD4SPev@ zd4c0iRm{q$cj-%0&w5QZO7wlqKWnXlA<~qvrcD4IOMEDIKW-(U&)327Ko81oj>qA{ znWA6BDiBV=UXuVuMw0Wy`86>7+6^*idzUf4#rPJq|a6e zB!lgYOhazsKQ&1N*<*~nNB6Ay@&h3^G&9gtgD&wmvmlyzS?C9>1XQC1L1oZ%-!XD^ z5_7}A7GsrZ0aY~IFG~vrFuZ1Zq%EQ*8C{ec3SOsx{D)RY&b}N`=vXRQ0~zGXvY_cV zRd2jjW_(=zpr8U`Mvh^xsw5;^$m@h4ZbBKhkj!GPa@aAw(+%S<@yyrrg%8Sp>QWV> zO+m)TIx;A{#rfp$#pp75Q!eHs>TueyUs8tom6VnJIM%pVf30cD0Gk#yA;O2!S!#56 z_gPU%7q!N?vZt!kz)QXz6?z33#34XrlvG`#*M{GQ7cpj;gFpXA^$Tu(3(L}gotpgn zdJPfmdwTftI87qhx6^%UT7J%BYbYCKH3MGf(3Zg<%7ygkc?Zb%zr#WH8)>oXeBLKp zN2__14||rkuJ@~5@mEecoA4kPP$(0f>OXBA?*pM%v`=zSRZ(%+$PAlv<=VdnL?GX{`tMVmYC0o)^46 z!#xkmyWSD^-N~ajx6$l}b?ZkvAF71*SS{v?%{#_cu1*|LWd3y04ANRR=U(trjoJ@1V)?FFt z`qq9S6R&^U|C3@shqVZ#ry-xG>Yy=ca2AaJzMPP1cgZ4S#MMCsI^ueZ-z#|kc83XZ zlZpxP0ZvDz$LJRZ1YLSvu$%~%b+@t-Q*XjA+!0;_anZk&He6@9ItoL+Lz?^!{DJ(A zr&sWrG{)71gn?GGCZT|{b5n?!>}SVcGCkq|aj~DhAzs*T`H)@{9B=w9F<;Csw9odX z01gVKz)TY2jb$(*`{)bsYvcj6f7tg?Vr`~}y|5HBVzEM4ka$6p2s#dukH!*s&FP+$ zDr}a4?}bK0ocnPebb4wOf+E&9i50^TIZ(6C3?@ZJldytnUqr|`Ij9hc%PH<48@?r7 z6o^=^Qvb;76n&mTMVGnG?n951DLq4$1}+X;N~W;D4$C6bOEbeWz&h&9OP`a97V>^w zJnW{A4@OI3gbqJ=+x)rCKZsX2BqQ%It5Ct5x*wNPX*)(j^(|Z6xzj9Vs=ip` z+LPz*xOuGKbgEt60aLUf(H~K@>wecjn%sk-;VFBT8m1t&`JzL>wm9E` zPc-H0U9*tc8qz<+xosk_j`LH)(jh1YrWF~!%uZg0u!%)_nLm{-i!_=-q-KleW96n% zb5&VD{%XWN_vcWm%q(97)z8TrX`~dAP&A+I`Sl}~ycc>xDA*t6BR32bYMDigs zcNc4?)ufi(@K3>|U^00#h8w0KB468d+rgo0p@KpLPhfv9Q%qv)qSyxcZB%0DqWI1$ z97yyAM(85-(Q7)N;LgQ2E3H8}e*X^uYe1C0yIZj4emmNj>Z#2`FysU_UIPx9UsoRm z4qG~A0uEc==0I>*;6I@VbL-?Klzh&v4ZrnJ$EU57^m3kv)j5YQ42f>W7f29xafiw*>#+EpQL|ftza&3vj zhaf}4jIm}7A?&D{J%Y>)C`P?Y(?-2Z(?-2Z(?-2Z(?;zkKrw3HfMV2PFDV;!Y``(< z)PQ5ub<~&ecP&2)a+jQqW|EwZW|y3erjEO_NL2YrRWZ$ILd)SsvqPED>`-Pjc?v6| zRa00Qf7^@RR$|KpRz_rLuaW@b6`veumHa}J$RV9&&Z z*a>f?azpvm@OF5;*UoVFM6Xr2y`9%ReTw1g36DN@~mOFm<#OOdZ`0Q%Ap-myPifJjYA$952Ch+)L5M zw!MQJAY$9#QGsCe$Ir$1C`u_cG^aXWiUEvA-mdjNV!#t@a z97kwNP4{}HmUI-ArlUmYo1u|ZOoYXRo=OA-KGO1-8e>WiY zC3HzG=UAXiYFWo(ps8gZ!Kj&Fm1K5UCAC!J#PU+hIlkft0S(HemT!Cmvi+b8(oCRC zy4>_|2W9S{%pH`ugEF6Jm#5LahZlCq^bVr4*7p4P$7R=J8t=cY@*~;tuGe_`-LVrw zFJE;X&dn!GR2pM@e#WK21;5Ebf1vHTS4zj!dw&o&@vS^%bcby@-EU|3BUVpyy{#Pp z16Vttom0L2*QP147D_TfuDCMw$0RM2yR!QrIrD)@%T#`?lP}xKIh3=j=kjBntip26 z^}ecSy`SWKUqb^qF*FD55>o_?_Xjv8M}v#vzwk->$eq^ylBw)_f~(KU6hcCuo!v3jeml68siVr2j?b6dPsdNxkdb3V09%3I z4)#{Oed?2o|Lg2%6MOCs*zx1x-X)@Z9)9S@GaQKXq0g`-gqq#~8M}~sydB)k&;9kd z8I@lgujil8cr>C5oa2rge;Z{V|L5VRnvQd}xBOVtlu!rWjDLrwo-9trrB1&dpKd;( z-B^SJpy?emjKg?^|4?oaagsai7rFg*FjanUqHb?zQ^v}_y`6Sg0x`e4opU|+hVbJO z*1vaH-1~Zi-}~11@z&QHk>6W?)CU@=?Y*8x!Sr5Ha4Ld)po;Ppe^KGxtM?`x*48V4 zN_|*ctWh}fgW7uFFl!I%mp?jl|Is0BUCg~!_OP~CG0NtH+S&|oZTw+v(JzxA2eno3 z`tC598J~K7m3~lL{veO{utVBv^qb+%Zdf`K%imi^AG{2%fjlY&>1Sh;}JjIJ=&)49$O1AKsSI+caK6b`Sde0;WjDj2D zdK#(k1K#m9$`F8<_*xAbELk?f5L|iepmr141>7c@`s7gKA|NR@u?bT)uv?%V)ALmo zL8F%F(UgvPq5`6lA*3vAf`zGcDZ>zJnS+%ha)Sy}Fubp&e=U|cUg(4Fx$8l59AOIP zP6iaFZn$keNjt6+{(G9c+ME@BAok}3?r+ancamZDK6HVN(!kWo!ua;B! zF^OQVe<`PmaquXnmc{m_cS}D)!$PNRrzTaNWBTyAK0d50{Y=Zc4wUFY%2E@v$Oisc zH+>c#Zm73_Agd+z`P$MZ)_dp0m^^hZa?OxUu5D`1rf6R1MD(Ss!Ms3c_i9sDW~;T z0ECwS;iCkIQW7-PG9nb{T6!aQOF8LtTJqm=O%JV{6Q3Zbn5pJcPM<0u=4zRg1g|Tl zHo|B<74xWN^m2p}n%`NbBx4*<*7mjU-53-2SOJ?ZQMHI&1Y4_giMQ{(Qu06+NtG_9 ze_-%xsa=t6k;49P?>OZvPr;_%9i|A1V_QmCs!m`%5uoT30EjTih|`UfTBP3tfDk<^ z*5fU-EI+M`R20Xlf?!du*JKGS6Y#d-N7Q{uv;}_M!UZTLz^0562}pvL^=Z_e(<|kE zjB)&}r$8COvg8a364>jq5s<3H8BvDBRPL5PuJNwn%)Muy79a}ZvswIstXFL%E;`OO z7QHdhxU2<0T6q)j@(L0sT8aYoLxqe27AG~uqDuQxTCqa@f>*9fyQ0YYe5s#4$@*ur z{{bio?3cmW0TY*5!Uh)-I5Ra0FHB`_XLM*XATcvCH#nEUT>}*aG&C|bm(h>|D1Y|_ zRNL$F1`1=vU5Z0+cXxMpS~Ng#2<}?k-5pvSihHr*?(S|yTHJcsa?al8|9xxSyRugD zd&b^p=AD@&RAj0eOk!qW6Oc66-i3*cnUx7&fPcG{izPrE zQEmMSzL}$o?;5#lH*~0e=?-*A6>{}IT_{!eG1sVUgb0ch`OWp4p6x3UER zRHPM|T|8VE0YH1RKMaAk&VS%Hf1n%C$`)wyX7DF!stZ)KLUH~xA*=JGPklfGyfwE zGgk)|Eqg0RSCE|K-!^X|#D8QKAQu1^D=RAxH!lF>2mpDQTC)6cfPbc^1L#jB+aKb$ z9DKbUzzzWOw=_V$R_36$4@7Tgpc@F_;^YeQ_5Qcwe-R=Z8^FxU)CFJyvaqs8{3rUG z7-aqze!G7sD-VDk>s$M=0a*Wd{rAb>t;5W~_O_n?nE!djEZU07Vya3Ef2aIkrMNiQ z1K`cX#SLI$=VAr0v43%M0(jmYeE&C&D$we09{=){vo{9=`2M2%R;T|^cKf>rX#XA% zI>7(NQUl6JMV{Zmi-m%;y! z9%yG}>-o3ETj#pEyiI`;_-z*K|F5YI=&#Wg2iuzcU!9x_@PBO<#Oy6>|64{YXK5=B zkeRBLi>c*b?edpg>yJURwXz4Pf}O4YSSd;#WQC&WK) zl$#5{BKC*qFMq@hU=jZZ@d8*R|BHC|04ys1MZ6pU7L9)pCxAuszle_qzykaSy+twk z2falx{V)0>V-~Z2K{fyj=wFZ>z+(On`~zA2OZ!H_;$QHMgXMoA=UZNuo(`68`|BTz zH`%}a--y}%3%)V4`v<;_5X--O--eb2{7>{Z+qbp;FMstLH-~@JZ)J3N>uvDAQhWQZ zU~&8xd}HhMFZf2y`CsrYfXlz&TR~m_1>cCf{R_U4asOA9-k5s+3IC^2OkJIv-qz)x zqx{xI|G|ImW)R2&WQw@F05%l}wyq2AxUUf-bZ6S15Spdh*GZ>i@?LiO=K6>VmqPb7 z`_rb=t$$d`a4-7Wt`zN!=nCnJ_i1YbTv%I@TKkjFvr&Tj^nN?y($xEb$KbbuDqzKg;@9QeKH>P{pG7;p$q$J2Vc1rkel4r!&Wo`}qNur2;rDqxdex9AblFMOo$j%(zB@uax?* zb4xT+IRCaMibNf$p}zI4S~4(m16VBg>b zO`#ig@`dkCxv;--BsK9|1vARAHJYHvZ{8DdB*tzq#h+3gJdup$(-TfZ!|SdB$6Gt$9ta34?gB^)*^8IESdCC z&o0A|WeC_fyLRBez?lZ$XnV~$lsNx>-$hZ-kD62`Go;d85y)qOsS4lYXt}KxkbgOm z|GwMWt$La+)D1KM3>hOZVJnVq~AdLuJ9R(muil&g4&64VhbSz zCl7qU4mhI?8tM~i$!0zo3hnkU4}YR=Hj%?FEzD9xK3)}F9}BIr1ag&YkyR8(S$H4u z$uHrj(aU7TR(LuWM1;vJa*J|sUCvU6-392U_rqI&CYQ{xlx1c zY$gkmE>5F)-$L(vaD*~56{u;(Hzy9<`W%J+DP%=2b_|$6nQBqT*8Xgc2B&|N0>^rc z!1IFys6J_kL7Vxkh--~OF-m6VzQNv3(QZHLv`y&~^?O3DuNY5RR!YC;9DK>1wgwy7MfHw>Hsw0gCcwB3Pjd5>rEUl+#fBDhI59TPCLP`3 zE2@j}t>Llw_s1~2o%vdQ*+9RO4_HRGWuu7=uQ>2eSf*6nXnwTVWGjgBZi~*SXuj!# ze2xq52UA<#yZPLqn19t1&J#%(O2HWj_ta`k-yJ?3(nL^4W++kD@ibtxVx+o!+v30`;k=G=feD0|` z3c|nN*a#n4<#hBepP@rwV|mm>pPIC~_KFY|hfdcf4gnZ5F0@;nbG*7!p7+H}QT*Fc zWJqR_3kL*EZGX!KE+(5uyfh?ao6VqW6=O=dVRBN(T>867^`X`brgZa%Y%S)XN50u4 z8hoHzfN@&BdB;n0(I&jP#Uq=S-);=q7YoseL6oQdkLL3b$@JCaVz0pdsC-hF3win!nLL6^~Ef0YQgDE)$g{@vw2}iVWBc$E-vU{y9S6O zl;sH2+)DU3p}g9EM{q9Q*#)8j?0M;kC38+TO$-K?bK!mqUW{weTI}B}J#5f^HdbLz zi)wxOjJN7#!tsuE7isi{2~ShI#=GMy!o88~MSpyhVVGVg2+LM{aAyZ4EtdG1Gg|p7 z1hCir82-LhSh!0Flvl!`mNdnbNyF+nz4@aIFE5tjMjl=VzzV;)9!|)k{}h7ha>-S_ zhR+d`EJPaneWC+@sSO6V6s>o`M^8O-yH=PhP%Z{5xID+H`3Bho-Ll%!lWf;UdsJhn zntvxu4(VRgatNrIbc4MPJ{=Cc3y!6&M%FQN){?syx-fX0%|KW3nSGa;U?zXB|DjwR zwL-=-0IiwRj23-UIc}Gz#hd)S?Sp>d=#;=C6++X(1a~M^-9VSYBE~{-i)Op)@8m~!& zt&qZD!<%YB0K=}}`s^I#nL;Ab_8Lpfqa5R}dg9Vyog0jbRC9J(MA;ojSPkN!fPW5p z${JF8u*Wus0s#G{_m?(hr(U66PxMPjy1AABKIdyxOkFO%8mx8euf)gT`h-YWi}o;5 zi?mJf#u^G46|oipc6Wzm#Fw)6HQKox0Q=2R>tbGgS8Y&X2_s;;VJqXC3ZC9nc;bYS zzDTT&%c$T`2#Y{#400p+fjUu@-G6#-bzT--^=%n;mQ<|1(~u4ua?k8^A~^ZW6c&W% z?n1;eo%mSfrGBUAibddY^rXCq9YD&_aXC5onwQgXVR~c-t!r8`uZalw%*TVg`?;li z%DZZ~Bnz|RBUyuyF_Y7Z?Q$IbMY|*9r!2hOJ)-5drN{yoWEe#WNQ)Unet&xtd4%vs z#kM}jID+Isr$cKl!#+Ofa%FYxdU>?NDjpEd*3WqRI;ykn$r`K=11YXUE(`vtB&#st zxSRtmQM-bUPw4sOH>ORwnoc)#UOx6e5}sl#-YkJ z4S=TjJm}XLkCYZUs&eoS1sVi36Oj-`16EX=>4)+%t#3N9FVcJx^REOQs|p<8=b2zaAxQV25)q;b0>82B zkI`SwYc1B}=Y_&~^`B=nFy!-MNQ zJZ0ZV@M#LYX}a8v%eo9T1dD@mP%jl)3h}Z) zRfkK`0e=c)8b4$-p2N`z@(K1sudlmOCJqJ*gg3&M$;yBtR%Vm3v|VemkGrv=f>ECj zP(IzhdU-C`&e8pTA+H0hUfw7aU`_4@b+2pLfoC$#;g{JzLzqIP`O*dC>>he0ZSms^ zV$|MU+^hymKae8igL^OggV4)z_l{%~(L6^qSATeZ3QDbB?7Vh6M(FrSG!#DAeZc=E zbO_pIHlun(K42C8T`aJP)fLy=Ou2VuI02O}%=jUjnOOR1E%`HKW*!w}vdnkfHf-xo zMrw%j_gd5w8kOa&XeSwj(G}?$RpS<&`nxT?Pmvj?>(ej{mb}bi*kr>c4I&A@Iep(T z^nZ^HUl*ibm`RK+6bRg&lF0OR))WPN9_ar_A=Z$HS5Q`eF@p|rlxh`5gX&UOEJyhC z8lbQwO6jvKsZ*5^HG9pXs$36iIF-Ud&#G{<7kJ$FvNq66=Q|5sEq|J5%)iupg zy<75&Xl4Tx9m4~Ee%dqq($D#VGt5mqn@nd-tWvxJ!~ygHQ4GPJFENJs6*JU)Set1P zH}Hpp6;y>?f`aZlr9w6$$rI44uhycKsy;+Ex9|Nqi=*7fqdaj*>E#!1*xM5cC2XhoT~T?L@6I#g zw7v&F^b8&X09>Slog~$IrjukA8DD@{;OofwYR;*C%U*sFJFVN=I)(!8PCkk-2&uVx@P z2ksj)pNjHZFwYWl%>LGlE#FsBDM|KmwR2uUl5lv&wCC=Gc3-ei7jG~gk2&XvbV~NP z6@^3gefS_mNSS=xO)s=6&wXMF#VARfIzx-8)^-K4rsg&zZ7v;Y)3cOo_bQ4xotL{vi${x1}}Ok0ldwJk#Rf>V=$F73D&T>2sPDv zT+bfd@N!+9G$rlj8efUB@qY)>@zETMuA?$@YQ`b`rG<-MTY~y5eP;oy4Z4LmRU+Jp z;K}pv+cHM48v*&x3wD=D#J9EWXUeu@w6n`OsTb-`bCUBNxdu#Okav5kzs%`q&fK0k zBPT0*q~x{zC-nHb?7j#3B!c%#o0YDbC!q&4MN;d6#(Q#Awf`C7?TIHduJ3s*?2M*zh zLW=FaUBj5)Mk-mwYKNr-q#Zc`OEzK1&xV{0sDIPGuI?CQ+x+^`tI?o% z;d!=U^lE)Sny$XsBzUn4_&L@(5AVd%T+xG@WdYZ-=1IJ}p-{w#6WQYxGtc!^E_t;0`spK^ zwNuv9>3bxNwsuR6b%oZw7`hgmcL5{;i;v|55h;zfEhgK}mxML1-jJvKa^4Nb)Bp{K z*ZDc*I>^HGgz66)7A4Tad}Vi2;{fzEr*U(#ApW979DnyMdsNaD0kqZ>z_F;%tZ*y`kQL!k5!hI+lj(6-AQ@4FBV(MYElYW%Vk7RhcXi5up5cZB4Z8S5L#E z)vDjk7DaY`TbagnAK9aiwx_~TMPBZRYFKNsa9Pv2xjckGzx(Wu z|9^Vsba%FVkmq9N=_HWjz;va@+Odt zh#hk0%5r!T3)zm1KxTyu490;fWZ?jbL{CK96nGw*Ts!k5Bc=+To&gN`XR*6rm&pxvI zaj)|u^XwX;jL6;k4q@O4h#)7r!L_N0_ZS6@W6L4+nHNLSkuhnYllp!gO^-tf`G0!b z8Me=5fdy-_yr)GIS>W(I@u>+-LI5Y(KvJ^Sm318ot_XSlv)Z$skXOL#$QRWDdIbqB z$3&Zah~%JMib-sdLz~tbBosO&gsUGgP4rl{E)Nu5qJ3uYaBg0^8*)JUsncdGUu_9U2RLP})SeE^6?9Q|i$< zzbKmt=1|0bo!UCqs!*Dv<()zy$uN=XQahE!+=oSXVeU2OJ|s9>DEO|0J+_2Am`A@~ z;IZpJnWtj47;oI{#G-Eso{Z4oAESVg47?K(Rk#(~XV1fIF5b&MMy^7&P=6$rwNqJ6 zuPDzqLFI#2jnD5SfNOao1@{i7Oe3ZYuLMu2U|X#Y$d&f-=BjIHlzP5rKiOrlk0DD+ zqN={$_!(t17?(x8jiD>(I7{jq_wwR0tSa7c6qV5xKWIG9^W_%uOFvU4RD`*5F|#wH z!t7_Vqbq(#SKb3KQ$yD+!dGtnI|=Jua7mo7rDq?0ZFv|&c2?w<=+sOOZ{aHkpmvY z&x`WCf1(e0+@vVDG?E11hqR$r>pk_b=dYI1+m^N|IiTGNM&cSDWpkN3@|0KrM+={R zPkh}yj?s!=K^086y0trSh8e;k8I3BZ#Gh+=+$5xzZZW?e{C{90#A`9S-z1tN2R+IC z-AgJWpUOe4U*`RcBr@YQHMQvpwQAz=A(!_DC+;%nA6(VTRDK8US2vL}0@f>i$Phb7 z8-vd?8F$LhKVQ(9+b#Xd(oHZn-U}`8x+57RWld$fRroBn|D;q#$1}3?>{}+L&bF6l z0s1!pPHSqj34dm%Z(1x3@LUF^lrq=pspG&yi0^hr7Uoz1DwyZCPF!Rzv0dZ*yMf3; zMVy0eHT&c^(m(=TOWOF;&3F@qI*O$AR+OtHO>MOkcT3Zhr^lf*KqoR(b8ODL@nHLJ zGK*0yHDvY$N*nmo#DrK=bK&2bNcN1FqG2qk3?nyJqkj}j#wTv9GYRYJZ@e;S_RH+K zC629by5|B8@6T`|`E#WDwCQ9#fgIPCpOO`P`xp}NoK@Vy6D8p`o>V_H$?Q?@#RIH6 z7m;rT*NwKsDNfAHDnnPly9+m0XN$&W@1I4mZw_~1zSviZl1dm8j`{N)+=lthdS{W`REuJ;%)`>7*mNT=m)-8$NXx2rYYZ^~KlgRR{9SUs3^V_4UJ zuxgV*yW70-;xiznDBA^3L~IYtsNK<+eNcUOjDHDPxqu{zq=4gSS4m$ocXAqh>?R>r z{fJO!HG=V8nXb2Haj#IMCfQPgWuowmwcX?EO`db|@7t!)%(;gm$Ft*_BYWCcD(s%j zcqC;C0JLOBW;CH)ao-$i3%>%y+yZXa*r2L6Be_)-GHWr2P1!<(44U$ZI-9@>E#+?Q1fN=Uq0hMR;RqDIvDV2ku`%D32j-+q|g zJ-6_-yvup8>QTnu9`ly@0=+BpJICV#$*INqvWCJfaczKf0=sO)7(b{PRbupBlt!DbV!65l-6mcci-iGkb>{O5>gvV zo)-*LBNOIEnKK#{STppw{`Nc(C)?wYMiX9lBz8$TZ82ouKo8;iZCAlvD?xgUGeINQ;kIRltWPi(yME*>}*?pLM_3P zRJLc;3Bf(PAs6To8Pb#2lx{hnTyY2Ju|ouO^M4X-%I*M3a8?>o zsx*`$?qF*m8EtRyx(P;?hM1D=9M2&O1Kb|N1(-G-U^gNy!zRvk?8Ne9qAPBK0BeZ5 z19B+qb5t|FQG75@spG=>$)lV?k(ZD|VzL zuW_taP8psBbg|}r=Xd5`r8Lm*_?*etsb1-~CH;w?Qd;l^bAO(9j~_NAf=lgXZINVL ziJ$30B~cu0Uw;gkGj*0^rQK+f63|5PT!Q&o@5lWr@eJWHI` zxrme39T;#6Av02GY}Wcd_>+G~Hz`!r@PvUaL9=uO)Yu5S;y?>BMQTycvZ=~__tBYx zFxlM{KdMU&8QoC6P${KLYl-NAtt1I9rYxov+kY}7pgtH%jlo7A!!3u#8+6WG0RWGS z4{(>O9e*dP9k*VD{0P&mWjV^}k)be2$r5Tm`0Tj6Ga!Ple2=U(;my$xgE=dx%(J9m z;A}madRx<*h)h@1IPBi>PPe3SFSC^~V%hB5k}os817Cf^0B*42rlXdh2pmZE=ibz47q9@yI^y z_k`buT~?Gqf`-dK;pU#9zu`<0btj=pY}GoxqJE>8sLc|4RvM3yEOVkp54?q3zb)nE zCO}5Pam02OHT;@O=qZ_?(SIT_%8{Z20e?7U(jU(`l&iZ{wEXmw`GihNg|n3o3g-u` z_a`6hpWW*Xs#6U=2-j_qW3v2|+UYP)ZrPznjG?FyYUyafx@8$1I%$fg39^(-s6@)J z+#2pxa7&?UX`jFMm3UBi$65T8v|Sv1(Y2f>6*pMHZ;4l?ZS^mO7nnO`P``fQVSg2{ zet#NuzH45|AKUC!Ff*A+Y>c3++`76L=H)&kAvs*g1M6}u+AL06>RkSlf8K`NZz7V=V2jXjpntx8Z<06~%{_j_C3gj=9=WUK8DOGKV%e7_BAN-Dm z!lt!emys*s21FR&o;=@b{;%P!${`Cq-MP~y+EF^R%1NdGFsRFSbv82fu&1` zzBWHBib?UIxy%^PtYi#U)vz+?O!7rtr=c09mt#DxEEb!xWwmIM&JR}O)%lmN5qhU} zM1qtS%a!z$?EB!&T@qliAi%)mQczkf$xaLH03Oj_=7y=s)rhaR%#sTUI+#qh1?jri znG_pNkW1?sB9DrZ&B5@D{C`mj^5&it3g3@`+|qLek05H#E&lVMQ!dYXpc^S;d?#&D zCb#L{51-}J_PnhztyYq4&87rI{keGy8}U?mQ18K$j*Tmk9y$K~R4!0d&o(6fkY-#~ zUXy$}|6BI84sO6iuAp<^l5)Bj`n%~G+vd@5Lj+-%pNCCS>M2k=k$=onriE&`EB=M?5$2zKKAepLQ zTGzIpf*~WN?*JS*OMlkcQCM4*vu)Hb92n?aYQY)Xlsy9ARxHC{&IblcVK7K6pDDhq@H{@D^{O(tqZlBRTej665yh@AxC$ zTk@+&WX@s|tT&oHNcq?XaIKIMW#>k$T3~V**z~DxBYvQVY4+#;Ho}$aiI9+PoTs8r z1h{Sbx&Z@~=t`=>f&OXXqkOH}3~Ka|_GN~Io9na%cK_lzQMd0gv=z=!MwGS}6)Pdi z4?Tnk9K_L-y?^hAWVAH(0Ts6E7`)=d(sJShEKpl9COo0ix=zr) zuke(JWDFPl3U|xku#5nn7W=PDGsya5LZ^{fjf@l%iT^hHrq?0y zPLP8(6XIpL16`uNC~l3YXoJ`9p2vcHcD2d14)}a5Wypdwpw7k1+!W?pY1(9a{VqfyNZRZ%P*|9H6QXUqchr-q`HB}xhs`9l7jRBtzY9*iCLSG zAQR8h8cJ7eiE~#(-Ob;wNR?&%oD$`;26K!=Btq?Qsc42dCiKm1QyWxmD8 z<){`wL%P5*QaeEC_9ySR2>yn0@=~uRj_bb-)wGZu>ZwywwE=cdpJg0EFq*mOhO^}I zM`cpOC3o;okk#M?@j!*7_hpn!h2q&0|9}3O!i-^~9_J*Lnw=L+l(sfdFD7@a?J+8W zSlcwj`Z+dy2Zesbr6 zxbA zWPGLxyx~EV#(oewR4;PJnT1z7Hm5L}I>V!HAdSZG;FvBebA~)JZ1rbX{(nSwB1{YJ zQzJ<+3A@U@XXmIq_b5-!_nT;gFy5GQat}4^NZ5$3=X+wHhxtw*I1v6F_RBfgW4_9k zLd(M9SdDeICp;<&)f25syiayYV|yB->lKSSbFW?>D;1Yu0s**%$6pME%1Y;;kOKji zB#;VhSv`_1Cz{Wnk5x(y@qfUjs30s)EtF|NF(A~5ajZCiR5R6n%0J9GRRtgi^{01M zQTyQK+vqL?bs(?9h1DP)80Y6LDKP~Ma4H|e%!_& zibX!=%>0=U*z*nf-c@>c?Zz{Zdm z%YyF}=_0BW`PeNEAJ|^*lL(vqC(y8iU?`AOoxX)Ll^AH#SK(c^z%f0oe(7KxJz&rh zsJ11MQ;CgRNzI)q$<~kU>e77wNR#X|cuATIfh(r2i}>D^I$?wiNh&b>w%YYg6`& zrGzlT_6J2)F4bUM)Aow*mLDczM{~2N1qN1pI zrEO_BVd4o-e1DlfQ~a1aUl`Qc&H`orm-9Ogn;BDu4qVq_7^@nS<^phJ-8;h}8`%5i zP;*;w_x&IPi7Iy7RtY`?3)E%C$$a*yN>G?+7yOXGf&xo|pZ(zNTK=NMdlR(7I&^;q zLlgY-PreZ6$&gMIYJDo+-ZQi`T5Z}#7gMboa0;t1(|>m!5MYFw+z#joXG=Uh7zmK+ zAyn%74u^U3?TRAfj~@tSyi6e0R>*iQ9Y|uV=qJV8-+!Mq9K`ibXpT1i(#e`* zkZ8Sc?jSqqXC2a2pO#8&@_n@exPl2yIK-8~4J?9``n6o}(*7wXwJk`;kK6|B=B{>@ zB`y1@lz$wpHuI{+y;GJHmmO0{A1&3IUh-^4rH@p&IS+Yp_1LMn8L8I#@)UC3`y8pu zKZxoV#3o0oxy+?e6F!}$&`yF~x22^GK|N`cNn%mlTe16O*#Z{s2!_J0%sL*-`W*DaP&_bM-Y_}>u(ewav9 z<`e*IaY9C-#1NxKuua+l_!_Iyxr|I&EUlH!-|=QE5lA^M?HY0(T9-A?zF6~^&Z`4=u4 ziQbB{3F+O41x-}Cc?uKk6A@U$Fwsr4F619n>rRSYO-+jE?)|CJ?Q1Tf3TO(I^`b-u zj&7Z;j3~E0hP4L~Lswr=MT-_=mxFC+oPYV^i(CfZkEO>hi^THj;S52a4Bi!T4T4r! zz0zu%J~)q!180nwf^~S7ms(9HXS3xmg^zzevB0%nRx=^gCB3HKv~q^cD8%v*3ow-d zhY-re+co!PG2aW1l)n9M!8heNlKF}Q>9T4-k^}bCJeT_@6ter+6A>yj4V}uvVSnXS z_yU0~1D9aW66Dlk(;ZH(v1KVA@_oteZvGhdSQ3KNx;~8@XJiYGJz1DNG>QRO<6%;5 zt}W|A;}CfoX9g|@V z*OjH^+$SO7?H*UeaM<2{-TzjW1T;7HVm%F5E&o<O* z139l|izrdVRsAWD!8K%!MP7`&WUyor)&yH!4PSdI#XeyPK%>+!rhm@ivCKXyUZS^` z!yydM(~ea zA{htVp6j-)A7)#>?WQu@LNI!Yli*FyG^KaLUP?O^cXFv|_}z_fq;6!k7e{f33@*6J zP*@nJncx~K7iLFdTw7suK+&v^%m|(%(-Q8V+Gr(Yj4DRmk z?oQC)?gR)9A-D&3LhwuW-e>2W@Bgdrt*M%MpO&Y)S9h;^hvL1GD!s5N*cd1QwuR6$ zGcfT0MCIkBnVA4gOsot{Of1M06lx%dHSj-jWC{(SgChuR%ky6rq7FbK$bXAW%n0&g zC=a#;$T(R8m{|eL96ZdNJWNag7A7X{{}_TDcmQHX&LC5OJOe-mYzuTmrVs_&xjBH$ zEg&y({__Z+GNA@Ab8~aj{pAi2wgEbTOpI&+@EMMTGoEW)6e^*qOLE zS-IE&Kzjht)x?7FcYgpiH#^{8O6K3wkHaj6nb7 z@n62uwq{_!Z?fO{z8utla(4b_2&n$q5Ng2xk|}^+Mi&U6`ZMVtnb?_3UcQ+BKhOJL zF8}|={5Q-0>!knRj3k__t^d+f{cZ67qc^evS-bsX@iMwjke4-(2fr+X?f*5^1pd9d z@<3CNlg6zIWnArZ7gB&G5u0T^I5X8jd@3Hw?uKs)BtU0UpdRYibH~{cE}bj10D5$cqc$rGI8GfEm~U`FEo^H~@?yzeRr| zP5`6mAH)q{6#o}-vH}>T{~$I1qs$-l;wS$HaRC?={zY6Y07jKRh#kPF{s+BSYW+bk z@wER%+%G!gKj=kg@-Jd#enA$Xe=+-S?aMu3^snUi*)p2`Ddi;z^WRtYOSk`+yku?l zU+{&*=6_F!mvX^2K=c2iWPTyB`xEmeKf9N?2LFk|`odsm0b>4F!17Y99q7LpUP$f# z3%(@a^arxMr0n_^{GS$^I5{}H%)no}`O^RY;J>g|V|O`Dj2t;mmIDGKSNvV5Jl z$ba!J)tKu;Bg4yB{lq;HelpJfJ7?s<5G--tVIna$gldiDeDsH$66eEoY!72e9HB$g zfr>TiFnUCCWiLvaKaYa%catn6DO_#DmNMM?V1QKo> zHTu#(QoXC6Hi@ldLV{%77H9jW)*qZ?Q-7p&Ck6wl=;Y)1pDMSHyc#GvqMXfwp<6%H zBx7xh)8b`PA9$GsEX`ylz-XTDMGnuUmal^g&pa>Ucc;_UYK`x%FOuXvq@TQq^P@#&Bjm9YJb-a zJ-HzpaFN$1_jVih~3k)2EZBJU2}9}l6^0Sd@=pWWfgm0t5|Om~@c4CN1?Knr}Qdp;LvO;Plf zVY3lt8hcb>ZJckR!5#MKq|L``-G9dB#@Yx1IqgiyCvGbWVOV(4<1A4{qxs`14+reW z$3(UZuV1y~L{QJv63!l@wwLnzAu@26{m4ALVl^iuxXk27C(-RRAbB=^1{=IS6Cu(l zT)P|eA4O=q&?F@}#)sZ+%*yCpH@esd>qs~%#!&|*7E+v=vRt&dL@Km>ntzcJxEAxe zK0{o}iW|^QLT^9*T+3{!Qx#xdiVok!Y~0zBDN}CbY1nBIRbuQz-Q%JiaB8AU$z+*$ zR;LBU>GsPU87I{OU$rSHpAyc;3)}9Ae)_;{ULRm|KW~6MKxob8uCaf)XRC6#-bHK> z1r(~Tr-63&OpZ&^1Ti#mkAG1|52a;@1gl1`IkHZ~#8~Ch=|>vJr=Pixwjdgzj0Uk8 zh`?_h;J{%o-w%%8F`v>-En>~Q!Z^}wsACzi180ieXI6y4bh-+Rn0=F~ztbhrQxpH$ zW0|fp9PZ6XdylfcjduV@PsLoZ=Gu1GT8_7?yUNMPl6tRkv+QTu_tyOBq3dM;t=Ue-PpTRiPSa0T(GJtGg?V*Z?O3?9e+QwSSBgzw{HZrVp4RY z#;9kt2CaJt%tkThR#umZ+JM(~n8qn8z4Gjq-kARIu)t#z2*(ab(036lJ`(~eUzwu! z!yFiaOtq)<*M+(o1QG2}L9Dz)b$%iPEyBdW`}=o8SJ$X8Q>33{P4;&Ukddzh9=<%N zfv5NjX^3!|zkiJ0xfS|;C$qzWCr?u!Co(Gbt@F)dS7y;+<$0UcL^#Z+Eji`E{Oj37 zLmIyZhJ(t$L7wzi7$nHl*Ee9LT;VX7Mb89ewDFVe@|pjX_^U%&o3qQ|$TrcM$lYG=InRfzXjpC}YJaGz2_mns4|{~_o$_O@7X{B4v2 zRQPdfd#k}!RS*K!w3#BJ=ISK$R%uSD(=F4=OS!fvRZ)O~>_UpOCNN&h=E?%|%Qc{fdG!%DB#z|HQ z)qfA#wQgY7$wtenlN8s2I@OL;n2&A^)V6N~TeCIx{AC*P-`&E~k_;1C83pC);<+!6 znWfhHVyApFlcrhGHN)qJmdD0pouQ^^KQF7oOt3GnYE-0x>-tEq^F9*)UG||&AF>oR zk%RKj*al){_MZhlYHy9@ych+>*{!gT-hbZkE4$+DeLL(JAJv8a^|_%2tg>c6fxZo(%`Rh z|IWJDtu`;?-M*_^*V*ti$7=ZKocm;F>ky!hDzBkgp7E362aYy9WG^jszvfdNi+k4G zd0b!-R0uMkDhGtQ!McCNu+2DqHykRb6-xRLZ;IG}I!h<*a@GKdDUPlRL4PY!H(@{e zD!L&Q;SU~Q#~gB%6Z_gFoEqNf^EjYTOgyQA2#||7&NLfz-DMG@O7b_0(U6oD5iqNV-q40;@Z{0erGu_yTbmS^PB%4_=U6@Z% z-BEVlqi0oTVJPrg%L&4dTsFe)->-jU!kTs}@RDw)dB269iZAW7TYqc+new_BUsSRf z-8VsDGN&fGf6bE@Ad7Iqf!Qs*b~8I>J$-{^O{RT>>KF0U?NxhhY=8l8#)uuLGl0r`?pZjU@H0YstG#}CLTR|89Y)`iLT?(w=-JY9{)w)BI#d4xl{8G%CUPOfFs?FCi6W14X^|X0?zNt`f4Q zvIEMnCTF5>wR-<3n#SYHz5l~toW9M=%3E$q=*MwoFWRUie}BJzg~h@FwN-US3kZqJ zcqZ92aZ-UcxB2Fx;wYVI7(5bsu&HvTs(3?xk4pUbiOexIi16q9PLS0*Oi_=&Dc_1)RUBmMB*$)Eg3O^#QYMy*uC z?P5BF&!85T^93g*EI(S^Gwyh-!S7Ecf-}Z*aROt$4#I356>&*YV1?O@ zw|_YtY?43cnMt~{ee5MSQT06}WPe{CpWVuo6u!AA6!bp1(R*7AX@-o87u6^4;`8&R zBY!M$j{ZRnzq#mHe%xoj6~WuR!*A{gyio>v3GEKvFMqqG5~{-(ArB~hmwOzdWt@`c z(JiUBUkG_HZbkUH$*&R4hYsJ8XV5fp#9iMFTR31`zYjnn0ao(vjiUQbYYs4!ntIZj2*A6|M>~Z#Nc2xq@oKHOlQ#IEdHvchm*^$NG z=Hy8*n_;0yw(;&KugCSZS__*$W^i{-Z%m0o{^=~{I((yu13cI)xP`c)PaqMb4PTa0)!@K>^$8B6G|+tc8nk%#ef%L zHM>fmk#)dEOi@zO2q#f`dzyxi`fKI5j^GuHuwo8XRj}h1vswzO<$Jqvu_Y-|7D~8O zdb@BG*;DVDFypN&*7y8Q;+M+%iGL}GREJ`Gy!Dnf{Uc3xYu}}JZdn|0iSrxR?u9>_ z2TLY=RZtxYHyLD^eQ5pWfXxuRvc)+k8m%uXlDiSHSA)yH;t)G!n0$eoX>I?BibZdw zD@_4Nm?gWH$W%{!Bv>+S$DDj~j-nrxdV!An8p}}0TlJZQUv}kLQ2cgRmVYoKgR-9X zGOWPiBRLBax$d_}M%Q^e)=sFyO>OnOO8Wq~1{!F?Tn9kejWEim1a+>#p#g9#jh!PZ z(Jh*I(NAlu5@R7-W!lRzUX{2=+wAx-7PpDuYP`Vjjb88C_GI@LWHr_@%G+!%Ad^49~tKYEi4Wp0394$HMfxBC$^~ELxP3 zA-0N1;UDCDXBvh!Y4Gl8!ILRM-3o3#^(*4Bhs7Hlws4bO`TQio%cuREGa2;Y-RF5x z(X@s%i-mKg#^})XSWHrVD%@{;&^}b~`F`8FlET{kiYeX5+wn(&n17O}0-Nl|#+8d* zL22&{e1FEbNtrnPEbKM*Ht!?KhMPVH z9lxtVWKV@UTw6@{S{{cYVu+>4;ue=+kYM1C9Wl7JD5y9h-RLVfvBd9P2sWC<24wNZ z5k}9+o-Wi_(uV68pZY*XMxI84jve$2GFfVNq^!fjLX^91LLJ9=n=}55@bE#<-N|6a zpD~ar0u)!2q<_n6+A%yD&c;)z34>qCd{=LoogEc@TLRQx)h}7iv8R}7Io>5pMb`$H zT4~yG?%2DjO!E!B+i*qUzoO4{4uyS?oWS*}(QY|$H%Xhls-B>y20@?OXw0usRm!C& zZ)uuGl)ZX#80TlK#pt4BmQeE&*E?@#&08x`r68h|Z+~`+D$o`!Ohhui-D)n5qD2yR zc`aLjeA59S`V^OmR3Of=O>C{{5W)w~_Vi1B#DG9gEi}#hL#lH%@x7q38?xnk&}4Su zMxsv-N~$M)jfos4Y~a;rHCU{i6L;@nEG+2EXF|CN$LhVnk{7Rn~HmKiSnr|qn?d-Xz=(w zA(4c1CesN_*aJ+~O{X=VzdG`1w7Ni54lz$B-sF+ckiT*xI*@@Q&@_qV6T z0e`m4%L^OiOa&stLZD?4GSGzXS?4~Us4DPqP*+#v@mh4QaWse`O>c-SD(ZE2RSBlQX_um8s~IL}^}6csF$2 zlTE}Ve+?$Hu$xlbr|7@fc}1_1OC?Z5Gk<=EG+lZ$%)%aO(Y|-u>M6~@?$l$btWP^?-20mcaftsb0S%U^UPmSAMM;97>GHE=gl3_*F$hz7%b}&-ZC= z%zP{Qz^>bDaShrQ<_W5keUKT$w6d@z?pU_}5L;Ic*{#_g>9a_8BYB_D2mH_xj(`34 znuqJi7r(7nCDR{y)-n|s-X|Kn^j_^5E%VzCrXeM|N-7kRR z<3|^ju7~JM($s>Z{h)7VWiG=(1o5L4Tz0tl#P%ymw2(6_s^9MWBz~x(^|`W z#;dF2@e3}!8nSjV$LNrqH_$&;v7m^A@!W?fy~~pOSY4_l@{5h>SqeLVTed9HW@pRk z?E<_3*NCD@ob4?Awg?7w_Yuj@TepZIWcAnq4`p;iA3;L2odnwt=zqNQB*BwDmeP;< zGS>U?juBNumXhPd6mL<9#nluMgI;1lTDAPday4mJG= z6$KadnIuW3{`tf?=&+T6kEw8F-Sv@pRxzTLg=gdeJH2&*29~)6SE7Z{RIT|dlgQ{} z155=xqqY!?edZ3uuz!APS7W8nAinSVl|<{9Wz``I-FaeEhlrYv)G^)2U`ETf2Y`C{ z)^Qb!t>6S)!KW7d6dU<2CD_!~a!F3fP+v=6&=iy~meec9g^tj<4>|{$DZHx}`|C)X zPVgy8mCST&Xl^1ps*FPMDX8pcwriVO-!R5(2pG>fh*+HFzkk@22?!CebY-r7>s3K^MBE1x>$*JS@y;dDhEP=Y5ius`=Cf7dchiw& zMmsP?#47`^&Dt9$G#2YRY?fS#M*e7{Kg71Jj?lFu$A24xb6U+SCidQToj+N)D{X0Y z2}*r68JAkXV|UZYiwkLt{W;M(?S88vX>2Iy0aMeP zKKVLlkRm!-o#KWvwkoV}c`|K^C8K)_CYr3^$wF2}*3)N9IM#7h$tUat$)z=Nch|vQ zK(q#g^M4DxXBwQ1NuH*nahX<@e+7m1&Qv{yoPVTCQ`4382hxShMqTGJP6_e&60|MkKoW$&@omRncvmd$dX>acB1cqd}Y!`ak6knPu-1|d~?libcq2G-;yK>lYa|{vDq5*RIAi$_b@a5MST}!9>-4p zjOE9}o;F7K>Xf{eRFsJ25{m@k6vstpt9BbZZ-PC0d5WKR?s-&uSr+3YG9h*y<^Ibg zzWLSK$y9O%O~0Liu=wtFom}Bp)Dz6_34t`%k(-5d+|>=_WYY4`S$g^liVqry+n)Ck zi+=;o5>xL}b#WwoA?9Itc^n~AOY^{VIB3Q?G?*W@l8J5!PTP%_A8?XKGsF`)Xomwa zLDfKHWQL|4xioFVV5~vBSED~lrqheK61QLDrLd=dlz-qkO@T{y_gLdCVRRxs?Sy9d zqLt=5fpqVY%1TqAf=S_N8dz2^l_{$AHh(mdC`_XmmL9I6D;Un`K94cM} z*}_-+e$NT)9r!c7ZmM4e&vVXQT%Ch)oKcBwvPS~+Ccdx-2{l!E@6rLFzgk<#GvNZ* zI8WqcPSk&naHE)Qbsmu83*DG-hs)&p(H*2{z-77n)FGDvzn?pMP6NYH;jt$*{F zk(~B;QR!lF1UfvMsYN~4dU-Du#IA58C@V#^@FMJn%--mn~oplGM2il?6 zE0-kmz(_3Idj8hL`U}eh(SiA#*tL4qnEcHBg2T48+9$+`ZbZ*|C9-jMFB4`vGTM*d zg&p`#I@E=(h|&V;tw<&52Y*r{Z{2T_N-$lxOJwGoG%M>;R3W)?IjeUpTRwil@374j zTw_x;G+DGk@5X26zvVLx2w>T5bm8VKbwj0!RUa-VOlPkFtFM2NiAb>~S@5i2FG>KM zzen8zPAf7#P>N0;YNj)Mkk{<;)SGx3gQpj(Ukza;wR7NU6t;>~w|_O%E#WGoq4$tU z!iLec61GRR-O;rV4pK5nI3NKsX+>Koy42}J6%Wi{OK)IB$NR64ebLn%(vX!A^zVyU zbC*CjL&9LOp=_@f9B%DK@geLiU`U%9*8Ymh=}tVL32_dovD>;zMKC@+p+UGn8Z43? zvoUuf?wrV$JSXhh}ErIe)CVZ2*3i#=GG(m&VU-Wnc$9j^6e(18>v811=54n~J7>q>#p9|8D{Lu` zV6ko8n96gjiXeoUoIajfO~)MWg5LfW#_w&!2Y^XKV1G%cSrMklB^V~y8LyqcIHK15 z4Z(nFON%|fe|^a~_fz;snhSxxj6s=m330uP+U+DLN+KhJJD&V)c^G1&WlWXC6O~OetQ3CG zejnQ)B!5?U?w$Br`;?Gcwu5Hg6=D|VtH-?bF4V}GEi@I{d36T``q%pKW1&jZ`Q)Zr z!dXAW>UltglB+3&_^UoFp}8YQycn$qM@RHp2)Ydo9`B2Nvp&T7`SFrVul72*s z+@)Sx^u}D}OKqIrDF3XvYr^Lnbad@tA9j`JkAG7iPbvvyURCdy7N6Ij=^BQ9cyw;+ zmgi)7#~nctjEk4P@aQQzF+I2$)1$!B`59r!ZSF{Uq?BngGY};i=!zf6Nc6>6uOMYH z=mQKRba^N3jPl>r$Sp-;f{sCu4 zvhEDiuUGAL$>=T(Wp(*aM}wOoqI0iR1Ao0a<`q@>JH^E!XK0-l_!JaM$e(B2>af|1 zJ|=q@gz?klOOsF2m!JDJ%6{WQJ$v36P~-mMUFDqRXqvarL$OeDG;cTrsz z>v6ov*FOR6X{F!a=))4QO7a0^JAt+uE!B|?3iFZ zaikJSN=FTJRsy!Lq&CGOaw{y2B~Ca$!RYcJ<$p)k)d`EV8s8Dn?_ z(E`EsUTa^Zv-`TC|&dJ=T&uEB^i6+{GByV0hM*= zuL7sgY2-RlBoL07K*U-yOMf|&>tnA&Zw(PuZp>>g7Zow(#&kzT}z)^IM%_;`O0W(k5o3`hO^J=>-=OJ>3cx zv^=&Qi&1B#*1koGv5dJOyh~}O5KmIXmg6wGo_G=WsZ?Du{ zaRAhj^&vLSO0K?A02VCiRmDjW9iD_iX%ho+WTW$A@=0k3eOybjyS83{~; zoe(ka=Fp9!tjFO}AzB)DpH3e;(xuDp1KTD^4V6k#9Ywygv`8Sf=WhuG&atPgMO-6^ zu?2Kdprz=a{C~i5={;6u6MlWcmrv>6xx!U0S zLkPv_EdH+5v9IQbzwVJCWg#~wYZ>cS?ALa@IFdJO6=zmdf|DLmS)Zl8M03(m7xzvj z|2j3~cEc#_*LtJYr>~reAHo zl>vX1m*fLt6N01$t9RIIK5uxJpE83>8=`DG{3oCv>&xzLWxK|G6#jdIc1->*n&c9# zhmy3&34cfC6uM`6N46T}#?SThPum2md^A&f^_ZV5Dx6!Q=^Idkf$n+k-`YpD^_NWV z9czk*WpO<`3a27?1;|f@s)Sbv4}PwE;~c_L(~^o?xIwm_Guf9suEJ4F*;Yk4G3lfF zG2#LF{<>o3N_0_L89G2;9?^p^KLq-4T~TGq(0{l0`p0_rM!Mk2d)VM4PF)61oZe$H zSicJIrqWvY?gy};ekXrFu@6s=Von&i##>o;9z!d|$$sT~xEN2&p!|s}!+Mp%pf?s(Gr58YmR9lYK z_sL2jRBn7q%Z4ru{_!wJFlPUTna z)toN*etyK&K+0&v!$E*mu5=T=O9?eMDu4M-Ru7I;=-~_;t}@*+#ix3f%HtYutI8c& zSR*%lY4c0M<8o8{3o|P;-#Rr~W26-krYZkcU#D-;cs6`tw>dEWmHZ4@OvtaNv(_^r zG!!!`ow1xLbP5J$C=@;@k$B4QE^_p5Lqt`3@Zr;3qmZ2sc3D=DilGyfCm7(DpMQ!+ zpx(S^qErmq;VjzRAnFS(>*U2u!_5%I{m5R5{w~xvfF&f@Sv|X5xwjww@xOY#E za&?nWb(1`(*}HIl8?YdmKqAG=$onc#)>oOzmzyMvLR$e!MB-Bvtj~&}e$5;vV5YsSPSWP?fXy2Fulw11muxPYfY z?^p0{dVz-78PBhKs&-nDieRU_6FBgzzUWgnrdG_gF~ifH`Z3|?;#$taf(*KMWruId zstTl@Pnzs+Dm$1gMgcPgW9_$TiBzZXOWf3DAHudqEf2$3h^Ek2W3;AqbAJ+XvJBO6 z5%>po`8BAAysGx|natcBU*ut?Nb5=W}ju3d`QQ?Sf^d?p#$KY zN@TBmelIK>UQ*Rt?cy_UjDM#PAlPUmf%V2^wIyKK9-a#&F{~+Ph{IVWxgF*H+1DVT zq52bcv_Sw{M9jyi(R*a+5#7uZ*U;c^_-TkAy3^lns<+WZd%s=+&*C?&4!fRQ6)Sy@ zDQe|BB1m*%AM|rC_g2+;`W42-W>_7{qI1^0n<*={v@w8>TM1L5MK5^FG=#nMC95$kx zPjRU~iR-c`D%^!F8h;mTBMQYKT(o`0?J>G2EP9 z7La1C(z~;p1g~A8j?Z8O74Zn8%-s@TBfm>Y5voEKDfTuvS{PHeD#f>_pnWYP%8G<~ zsL64}d`Nq=^nh*XOQ$bCAS$q$5G;uw{@#Bm5Yw`(%P`$Wqkm-EI^*?4RmJVXOk!Jh zU^7hVn}lR~fri}VZ(DS4M6VlV%2e$y@&@^4`rHo=qkO1IHBVxUYnuyFeQ`G18&72? zkJmYvO0(g5Zw1>+b#^xIaRpmjten0dQBs!0c*fpC^ya5eFGsWnp3p4z#R6rT=pTY# zKUb9HeHnFWSATA;e8mwohGp-1Ja>1Zff~Wp%fcuKO~8Sr7GyN;HFMtt(%b9VU_9UQ zC5S=rR(kcoXAa=k;+0sULtfbZV2Go-%UD!a&_N zbsVzT+3%Q^HZ5 zn<*6TBzp?4G!^D&#?s6$E2>9t0d$jKc`3#M^%<%{vv_Gg)ui|;0gdvzp%MxmJg{@= z1}@WH&jP-#O?izF4l&!dA^PSPKAh97>lp(Z%zrbGtK(tRwOzYeQMl8(;^TSFt~LzX zOGz$!_%LKx&q+~d0C0|Wa3OXw8746E5utvmPC3w3ujtRm&`C4>Ne>t6j}o_L5V(CZ z026ZsR~#$lmdB#NqSp-Wl^%U0I-ZgWW;({3g-%=2ny$gBpkxidO-N`+%q!J{zPOE; z#((92TTzaCN^FltC1k-6R+^M>Ia$Y=CO#ZwTlAKA(<|RJE20q}6SO+A=uFg>Le*UQ zI@~Mm<#cF!hJ2v*^h)9u&h~x^R<<670BvlaS@qVKWIsmHs8Mb)T~(PHZw)RPFE-ac-D_}DwE(RL_eyt zAJZHd>K-kGKA(41xLH^9z+tXl7LoDuHMJSq?t&oH8&KTH1X5O{}&YH#IVs zfXoIdm#)qO2Y;qJRS*GT0O=aKk?u}O8DM}Bn1Nwv5TrXL6cA~U4naz#8>Bq2cQOng53z1?Z|gag3~4Ei1YG#dV2DJoZWa}aC>QX zE`TQl;ePudmgJbeEy_gD6>LJ;WhWRQ&w%-ID5^@c$0 z0d^24FhE;Lg9qV--~xc4w!Z>FPHr$%KF9+Eaeo3?qXK?+4gx62>HXa3sw(>A%XD}4uM)0dY1qd8$gF1F^-aj|%2!(k_xh@ck!|E!_|g8bD5@PF@ARj3^dzz6)(E$W#5)v?E41YrA19PEI9 z7Sn>ESPKTQ{Y`Rnpb*do_2K(}Q~h_!|HklNRsJuM|7Sx=?oLj>-E6=8|HBP(hB$fu z6@VhGI|3yDO&CfB(EkiI2LBPQCfF9@?);x#RRjnn1X-v(ip<=6f;>RMKRCoq34h`R zw$*_kY#jbj<_~W8OKMIKC|C#P2Kn{2pt69#|L~#oW#fo?Kip8f{Nn<-p~QyxeT~0t zFiKAU>_ZW11GD|5JANTy00<5Tc@v%RT8i2uGU>kzjDVU8!$g`S|7G#wyjVJfUuq5_TI`RoW_i(-?9->Qe?CDC9epcq3 z`a7lBPCg~eXP>m>T#;`Ur@#5G*V5N{3!Zb+D{b4;TPIB2o}*7B`(Ds8PJfYpK+7>s zm7^0cf_I_mJd7s$jQ`lyzDu8()Q`2MV?j4t9pn= z>t2Hmq3=|z*{ja+!D}(*k!f158Pz2}UJ@jER+26E^!Lt_cRp;3exc?Ov~m0>3_-3a z(Mzi!h+AnipG$I`UF5O%`hSkEwenq=J=?C*CH7Qgjn=8d`stnp1BYwpn+B>*y!`?V z<)r7YbK?4wWQG!}z9pJZm4!nW?|JbJe|iiZ#9|m7yAqTj-_*o-uIo+M_H`^~L-6RL zZNfe0ymb2XQ2d?I!o(s@WJpL{Ly)%e4V&`-c|7i`+G2tH%Dl7Zj3_umj&I(FHxl(9q(mR;56)g%OY1- zeq%1?#uD;=+RNoYpKpM9&l+9a8vKPRy_amk#>e@O`RA+Fq9Y<86zhjCbI9uRLu`D1AkJJekM>o#l~bhA8vepg`amC%fmug+EE4Gr%LY%?G*xJ|6`=wZdhMD+SFQq-&Zk1w9p<)Q@hjsKW`H&1DC+cR|2A{7rg}d%WUE&oo zV#$Y%N1vY-#}Azw3=`0_$YsRE%#w7A4N-BY)c!W5)iWg|bS6!3meHYVLc+5{)dW;ZK>WP>qSH*)Nt7 zy{%UQ-dM8Rq$G-ARzb=htT-8!LwAN12m8`DQ^Wd~?2mE)HHL)ru{L#{c_??!cbRp`&|Vc zWJic%g@$N8U8}|kC7Yrhpxi39QzYpg1wh}%!bAbCd`+bxE3<`-X%opkOsge9jQ`{d z2wzOQvwuTN!?{3+iSxu{oIOL@)2ZajDQy3HNJ0IV4@>O!aWCHEk6}wATM36aUPY<3 zGPs_u-;(F)R0if)y}#JnNwy3jl2=8)B3_+q9~$xBq5=uMqsQXnK51C&lxX@%^Qa&} zey*$INBd#kjJvUgE00K~?J%T2k2UqqX7AtmoAkyQRE&p`A3euluI6ux_^th<4Us*3B$$ zDt{4qyjytkA>1<%CzR{0q%(GIIlDWqy?2nDeh+cV%xg5)G%WG``v(=Tw9CFv>5B1K zWhXMP3_NCu3S@b;qB!}*(nF;gQ$*X^)WmU-s=tPRKuXtSFphcVMBjx=i?pC?In&eo z*stV5jO-~_mP45TWDe8$JEmUa0}vGeA+thn_dvJ5f^ey+z$)#0d z3w4NJKXWye9}UINj;y>$4iV-G;wKqk!St3hX0y6{SlWLo5%lfBW78u&CnRq@K zREPGS5vgRbO`^$<+B|EXb=`_-)akd_wBf^ zQ>S7j<@5FR4sQwdUh_WjkXwnr>u)ClhCMJyixxUjO zxZm)ly8?OrwE*3jv)|O1@{e_%RB&*6l2|d)S}>N~s@gMM-7)34n^fJHJGxQg>^=GB zYDw-AtF+uSfuWiZIb>#NQIWhrOxAyRbLXM{dCCT*G?efv?|`vD;AgN}aO1RRe&-cph8u{=Sztt(2RFXtr9?nRW*?TlwtLMT0@~Y4E_EQl>A`un&PQ+Q6~)HeOt<@4n=;oN z!|%I60f{k(4b~bnbarMu1}cBHqx`_CC$7E#f61;XTYr7|ubP-fcuYy*bhpK+Hq_6F zZ9QLd+5iwG`A5F^6D~BAVojx5nE50b21WTu#UUGH1mE5d?GMT!evR>hh65(Xr^|28 ztc4Z7zV9;92#6;4hq7*(lS&s;Z~CgO*Pw58UJ(S_-sqpn77fP-YjA(5^RwaC>KANE zH2HpOn5Pcibs-!JZ*P6v%f?^Ttdw${9B_7ob3Nlf?7WrSUVTWmsfel9=E*|wl#$qw z@V?24X-(T?YMfp#9?@9fPL|{#Nnra?^ru-X^jwyk12^)cy7~Y)bwi(UH}4#?egiL3 zqOrlZSZIy4S?RQnh8%xCnQ=yIgsFbK-kiB7IsG6iBxpd^Y1q0kNiaabU&mC&%T=N^ zaYNs1GVWN2u5}2J*{-QJo*lD4J=J?R&B%d31G6An05RPCWE|b9Ld7O8IVzIoedb4u zWAm)@-s1e93t-0{wqUxntKs0#l^m{6i|Y zc#A0xL$~damD@4S8M2@#y8M73sy0)ew1IB?B>%iY&Oo00x6^yZ)_!*_C2&lzFWu8- zsB*goVf;~Jrla%)q;%SwBI$$(#1zt0k1FX3p8mRYZ<&LeB^~Z)P|BvcTpt6ZVBE$Ee-)*oiiaxyQ=W(o@kLAO(-LK=Syx=U6 z#PQ|D8145Htniyx^70{J(um$JVe^4WEnCOUyq8zu*D@gWZl?@Nu+0L>ZI;D^TGNzZ}s(5gGxREm+VqQ_NB0(jT8XW?y?_#;ZDcuwV}@!T#9+6d<}T8QaouTPk| zibU-Vp^)W)fx-I>=C?CB9|p#a+O=(G-&<045TSqH1^3Zm2D(e+9efT8kC;3oOxFLx z=sUdfQTSCf3*%?^j48);1v#B3*_j7hb~BAKo<#K@QZRRzYt7LH_SxLV=GEBon67+8 z?$^KeKWM5L#PL>5W@X#XIP5QZxK^2Q?9%udc=#iRz_3>|<{d9KMWT87X29E&=JZtm zdsTn)l_l0ZT0A75dK_l3L(7)fW(wNt4|%uVo%3ELoI#Lk_?WMpkJ~2U0(PCk>v-|f zoQ-t>X_43*t|R8E2{H2z=N_nEMc$iUo1U2Fpdg*PodHT`ZIt-9e!%@Uam|tDEOTF>>O~`j=v_Z@rkb3bT?cfsmM)kLEs4V^qY*xlvTssK0Ghy1V(>s znjk$EgD0$c9HUhhV9ol?F;LxhCB8s8J?TgffR5UaM)uW-RY#ZyLuu~9$#A`4?LI%t zay4TbboW)fkDlzY^@iH$($oQqa^GwDHv~Hd6xfO0VSWpbNiTH2-Mfqbodm70r#(bq z{am$Wa;{L;^9c!dXUd`Pz~IwQWSW1K!bI(^cf-JDESKY|GvSA|9E&D;vPPtnNow~M zb9tVjf6ZjGJW)*DyCuc^2CZ2x>Il<*@#dl`RF{FBTUCV@>zUyY-1P?Yn5Q7Z!FG0L zpRq883GYqC?XlE>ZOBZAY#1G~{->nbl4-9Hcm9ev9q`M5>vF=*NMk8i<(Ge7684Xi z;Hk575NypHqHZS(R;fI)a`lF(*WBh8KA*k6^^7b#cb)?{t?>5srhbu1+i3iI=9C$& z@RPPHM_zurfK^NuE<039#eGP!7%>ZO1D{MTl&yworT=cr8H%8(D>6J zx;Lsg&r_fMs43M;ijSQVdKG_yOW)yBsCN~thQHC8EdFB!bdLnltxqQ_9p8K{_h~!d zwt=pCroTi&V7jHFO1bCodVJ^l6n3fbaJF?b*0UV0``NMiH3KHrn+Vqa<5R~Yfpeq6 z1SX5aZl*!q*FS<5IaXke*-Xee4#^Q9}8!DL) zQ14DOoK}~{m?bc_{lHv%950jcD3SWZrxED);&loZNw4fk9BJ3jiNx)g%1X(B4cByg z;S(V@P%uBDvD?Q^5O5;Nn9StG#?c^ItLw-cJ?AJ~-Z40yT%&vp+ zQ~Iy~=VOCAF7}IIRM~%oCOM6yb1h4UAUR?DnTW%m-*bdr*;5(Fx^-t&Xb--|m@|76 zygsnqdHVc|Ttx-%^A}}AGI1tS9mM?|f(JW?th4-$@mR$3qbXAqMz{+A(KM2VAchhR zy;g0KGVsYY*~VOn=;Gjq zthZLK`Bqx14x5rD*MymVu)5k&^l{@>_x@tpe#G*8;UDroZu4|-2gdAUsv^zNODSW4!ixJTRwLD#QO7-XUv!q$s+vxL@2LiHs<9+8*EPp-K9#CY5@*|P@M z>>?eUmpkXzSX5Pob($WiS>tu>*1J@@JmzxwL~^|Lk+*-UDCyCy*6@&Ht!RuhPM8mg zrBtIN4X=_0)4C=f|JDQ^RKlcs^s(xmGJJ6hL3HMY_@T)3m)p9(0@n` z&Q7aXh!AWkkgUR>-l3n_vE)I%eTgrAX4GhttrI0fAy?(VaGSMKqG>zrKHfJN2j4?)&5MIr9RXH{aDZAoDh~$@>OVEEK_oDQ9^}VLrxZ83?-TvH6>U zE(^MXQ$7#$zNMXm(Oo5LvfC2uVx-w*bowir-6u<_RPuFO`}4mDG!CNUe}=i^ouOtC{HrIFAJFiT!D6++;ZfXQZ)ci-khqD zj%+^Azkm9Jm{Ilf%%*C`Z29e70iN9Tz9Hcm1?k>n)_U5br0&87?uoLdLCSUZlDxCi zOiF(~VG@31Tc7vgi=Dp&oS6fE)?P5ZSkANx{OOk%lQCF%bZ6pGwKV{)e%hl#Yqk{? z0$hA~Cxupl2c1O7hzg}7i{|&76eHrg@zw$M3_`h@7L7G~M_9d96(dY^&88A(&VzrG zTfFP_3+&se5GseFMOi>OPMPszBfJj^8KPUXZ}-gS9>07PwCn9=NA7}r*c)rGV3x%H zSP3bxRAfx{{LMLs@}SO-ocg#)p^oJhTp|9qmg8c*(}WV~wt-PiLrm{dc7End8FW9h zfBF`&T=2ouUlKQz03R@ zG~p+mMUKRp4(Ju$T>Wck8K?RVwKUHrm0_(Cw`nFvO44UrabyjjY|+d(K9WS-O(DR` z2@DM{i9=)fvfxfVNwLiuPmOD`Z4rg1kkDL(1lWeW6BdmoyK5`Omo9{l8=>4C~NHrsjj zc%(Hi5n^(#_Q0v{(gm+<81Xr*0P|(+5q0I0>*#$K$#JW3KzhNm9*^o)JOzMWZvK%| zc>2Xq8%8BH03QrD@Zi8rzIZJ*KULmTupd%%U`5ru#kw)!87UQVVvK*Q{-{klR^>&{ zQq=t2y|*)Iibu%}AZVA65n3}brwu`A-Uz!=Cmn*>X!`+gj9jPp;GOj-> zMrUBwQV6Ivjm02Ia}HHpEqv%W(x)Qg#DvYbsKPN7UeqE>nq(d}PZhU0E=q0Hw=1!m zY65QK@YwPs4%Fq)Ts=!F*$8Tg9c#vuiRp<#;uK;@!d@P+U|)Y8N-p>Zh%%Ma&%Rrv zbGvv8iFr?LV{@cv(D)$WK+r zjCk|gFJhnaxlA0WIoaQos})TtV0qouE^DEBArU~RTqgNZ;vGi?AN-cRI;({7YrBTJ z!}2ECHXAe3uvNTS6{d_HC<*PB(pj4iqohJsD$Hu08FPR7Y3fQJMPQjjYMOmEgT)>W zcFH8W^~S3^;_ZgGV4~P4k%v#1pY%-TD$a!6JPxm@wHe z2HsSCQO~vJ-L%P#=5B_#{Afn%;ibx14kaA52l0QAa!9jnjf?5n-|}wX7+2v&N>1^6 zW4No{eQ6~F^DyPNvgwkqqXm%kyd@L`CczBc*+A%4=s~lL zu#!MIHqPR@Tvp68^OHlVDeg!#gJ-&ro@^Qmwx_Tv46ys5G5X4~KyNTsWOK*=3!L+l z%$Ff^0uur`GMC@%0~NPntOMpD0y#66-}nU;5Hv6fFHB`_XLM*XAT~KLGMB+!0~7=| zI5;<#fy@Rde~oknRMcDdHYp(?k`gj>!wlUG(w!nP32A|UZcz3;vM`+nbA-?wJ1-<)UfXYaH3InO>!bXvMxGFAvns3HQ6dHa@Adrt62;{|OV$y>l9iV@iahVLDF0L>HT=ahtf8<=CVC0=m9*n%>sUzS36*mU} zhz|e~6a@*10)YTtAW-B#M1+edKpyN4vjV7d15^-js4Fg$9Ky-V1!iN5yxZnKO8_f` z4FD1m5#szE4v=w#y1*b{I6xhYw1qm}?Fa!o0CW)$7!>LCuN17}wn(ItC=ZW^hX*&< z(UlwFe_|ua#tHC%A#DLVP*y8R19X+u0Gduv_#d*`9|9-fud@MwxIurX`z!iaA{hL4Fc<K760f8dI^iwC=dVGdx+JHqeE!2m@WZ2;OtBNUEw#r;*EJj?|OxjS|*ow zef|R0Fu0ZVuO_VAoOtx%FlRTYvix6^I}`3dHXA4sAOI8=;uGctK%D_lPlzqguk?Ce ze@@WfPS7v&T?c+XP6#J}^<5KCKbST2?hn_;73>ZLAYI&`em?)(@o$6+0s*XG5G247 zY6FAg{*(RA47L7)?=Ig3<_RzX-f0g60RH;@y)wO%mlXo;;Pnsv_xgmbKs&f44 z_-~)AEW#7u!vz9x@d^L|AdnCUAau9zfBSb9Eimk_DuDllD#NW201)s`wRgw#pNif8 z5&-L8!@&mlcQOscoob-~)_+9)3@8AE+>Wp;d=k!Q34G+pCNO-wlEc+~!Wqe_SAb zZXo|3JIqxP<_WdZf*~QceutG<0s{ZbcQ;=U`@8qU^-h<6 zTwvF`VMG4D#$OnEH%|YqLjev!SpAwiUI9S>*u@3xg?o4PcSr!>1G*bfE2!shWdnG) z;Rxhi2;i<~KY%sD1^3rA3km{we`J4|{vaU$kKEr#2ngU&{2K}1A+3K9AAm>qH~LpO z5H}Z>yLx}C=&siP;NNco6zU0u;4aJ}AY#FGwZU!Y)iP8bTpQ!!m&>`!wiKI?U~^E+xBf_*wab2K z_k*P3;uZeuaDR&ye^&cfuF_vwvD4#>mEL|WZ3ye|*)ElQ=Q=ZAQjjB3_vyz(iZ)9k zQ+I(`)cuLlhH#dOha2e5*?OcnGiu*uUonMLV}-$v3>`=h+Qm5g3)IAWwafuzGZKUm zkE>peU1S4AV4=Q!rC+;@glM&N3Pf3^dx`f*#aFt+<0Xo6nUGzAA(y(xQ^_M&0MN509` z8-SXhhyMwZhlBTB!@6A~@3@V%ASi!C1bY+xip|o{o8I;6>4`|ypimt14{fZsq?F8P zH=7gg)aO?`f946iXg)uw`4$69_eVZ9hQB1@X6dnrM+k?G;lJ4LynV(de)Q#Ggl`$& zu{?$-|Ej^y>K+fqCFd-y99KwV_x5&HXmJjcLP@y|wWjYkZ(f&=G}^Q4)3QB~OPkaw ziR}2>N78H09>&<10dB{s75Gn3o`_Iv@}@7MuF%O$e=nZZLzRs}2cJ`TH@4pB1jaIe?!&OH5Mzkcow4oAj7 z(xPZZdvHLW35gWS6;Y<|kfWIRiaO8YtPS|p-T^+sHWN2Z)X;sjerTEg_DwAzn_X(| zly=*8fAm%9j7LLyE*-QvJW{LZLiw79iR)W7^$N;QNrJlO4Caxuw{0z%CSwUd(bbC2(d&)JhThS2 z5~^``5GZ_sn&-)754u23l<5~41e_dRG7_|{e|Lp47+&>|h3;OT&h=I18L$&mW}0z5 zRkAgWySNTh@3ER-uJ*7-yjX8|T4(N=_Es~mVfy?D!XV)b6Kqb{+ajApeBfox_SxO$_T*gTD3L?fkHnbAuh6`@oQv zf2y5Vqx=4HlOx$Jz-RS^F|W(csFR}ZyDIBqJhUHqGpq!~RV4zJ{2^kzEq;tg)Z`T1 zM7Zd3q|RidX44iZA21E-J=atf<6N_d&ldS;L{|B*z)f!$=%U zOM7Tf(T+DEq9`!l%S0u!@$Pfbf2YvS0HNZRq0cjoHBJN@(z##CLy@=lIc8#tW5Ub* zJ5LDK%=qzJImuJU>4O3qu}K;Zcif6YsuY{6Ah zhGa#P8_n`gYzu=cXvESfk%!xVgW-uBsU0@t}Lc5wq&4f3JVSSY*HRwF@F! zb0eoMJ~v+3vrC!jT1qsb#gpZ&7Jen7Dr~*6=VTMkdq_JyFg%5~RqtUg*NFK@BUW^3 z)7U?p$qInNB6~)7_Tc5>MkX<+?uFpNN#(i7s802?ROa3XcW1ZzB)&3@bIsl@0~(w1 z)g%I>RAwY4KhMULf188Qp1e-qT7(W!VE5F2eqoVZHJ3U;k<|~ojR+Dgq&aP0@)kso z5a>+Yj4H(*D|_E4eu8F?pEIXJICv+%4Z*|xMIt|!d4J(gUKT6N|sfBAYmq3f)~A3`0uz6*T1 zH_y;&nHG8JRO9lcmggkmonpy)S&OT^2~;n#xh9Q@kkecI+>gF$ZSXPXM?nXF|Ijf%z$l#Kee+_%M;}<{HczuGndmR(Ty|47mriLVOIo=hjJXW+ypqOClsEa748Ql_< z82oCZpdPu7QsZ{39q(lDoXm+?$V9|>iAWov{O$Ux!5|qUR-M-r+#7oV=wd~ot+@IU zc&D5g*hTd(m@bbbTX?$Lo=`=^^fp=u>=Lbi_qO+pj-8ChxmzVzf0zNOFPTFZ=VL^(f5iD5cvwW*mC>LKo)yN(Eq@eoQAJJt>ZOy`M{Sn|xo+5-w843MQ)gL! ze_H0k7bIbo*V&2B8nyHcpZT%02oUt|JOB(V%H?=x#X`joSerkRzQd$;wa+W~ia5fm z7oiJ2pO+%>44zC`RcJ_Tcu--|iQ2OopMBP(BFX%jK3q2F2!}!!l0Fx4`snenUx0x8 z^9@IN{p2>=nQheokUE=v|KU6~o7NdNe-jsv1CcLs7qcn#2GahMJRsqV9-g`FyA|6S z)T3zor=P(v3}$;4VEaL8L&_dr>_N4=aTvm0gn4+L@2rlb zQh;~fXh7KIYAj&eRB#K#u0W2KjGiBAWFL(8YH7ggo&}ey;adGGi*1Z&Q;{tFe>dAB z`|WhAiuE5R)2wTRWt(QL7eacMi&@!F>Z;P{wWB{XSx!n*^f`0Hn`t!)%Di89qb=+8 z`-~B+CHjOF1Jmxsq7u7`ADG@kXK}_nrvXVY)YtL^<&-+J2z%E@eMOj7p1oFw^L(9& ztNf;tNN4ubY=HSho|bo?_Ne{Fe+q{4y%}{j1EesZ!)%Le=Ldf6GY8e!oM^O)Afyn3 z>H2P7*+Wl_BpCyFEjwhWc7sfHERo)V@C^7cEPWgszf6`wVYWGB!yHnHsT1=cgV$Z- zVZVdorwn~smZo(t-_2nKl>9T|1wN`Pni^w8#A}OgQzuv42>kFQrnb|ee+};?dHfDR z)X;+IH$$m=pA(;=y?f?U+p;Uq<)k?z9y8ez67tb6?Y%1X?VvWZK3>84;2_yO9=zrc zVqOJF`PaRZP)ct_wNx*r#M7-PwSxtGYxFg$LV)f1fgx*2~zk)$E8TN#e)OGSU9M|#Epxz_9qu6?!;rCz^R?qQAvjbNf4O8coMC>ON44Ug zFHI)a8NFx*au!QDBH38uF+H7us^8b2Z}(m=PtLU?E5ctRGZNy8+UOtfAcJ|-pC?qz zJ{<9AUHpE53mu{n;;_P?Hl+2>`)^6A;k4bFmyQm?Z<@9_oKHVP;OQWV%`btwP# ze!(NTjdwcd0`97t3YRd0Pjr_}TNlmsHDb<5gz=9Fu{V)%SDH*hhTaJ$Df@Q*HQfjL zHpb3v!5jNqu`#+`)XDWLhlXP$;?^IwV47{C`;vu5sxfK@f4ua4k|I@%;aN1I9}g?U z)&lOO0W9L|aTNsc6|1{YsVQXb95RS}<)6=8ikG?7cc?B>9X#5jm$*U|7UtmQBfoBK zF`Fmi-sOM)gWMwX(PpBYcf9{(`072%h?(;@OMKnvK8!=e`YrxHOVVH)AGrA$#$Fx_ zjK5`;pmdDGf0@v${jtP}xpf#dDKXYvQl9=$E{n`8Z`BU}=jLa{Rh!zQCLiPB3x@{i ztUHg#ic{Z9pYMm`yA~6zeytg){Co|xie0rme5^AVoRE_QDrNfda;cnr3Gkux^2>Uw z{$T}bzl>5O#jCk~ipK^>)YYoxWk7gDWq&(hVXhAgyl*CO+P!Q*eO80STnC7KU{hO2Mf5yVLH^3sI_oBzt1Qf@j1Rbvd76se) z>`)E()^gt(J03B(F*HZ0Su8hdq87`PNuEMQacRb6>~A%O`N{X+mTHWV9a6N|Lo}Vw zqv#`ogsF;|*_0P|;-%x?ypAfwb!3$&G2!QTZVYgK`q*uF1E^)r^J<}ZS89>oEunco zf8=d@ftYkuJ)mm*!~AAWL~=O2r68+D%&ni50W<83>I)?kJCi^;Nj@j{##TUN$%sKb z!ul)(!Yx+N_5NE^#C>Y;1y5v^6Vu>UfJ4da+a(-!H+l;7QQHf_RL=FQBC2o_!M;z0 z+LCtGr#eK%-zoLFzNu~P_Z2S^)DzG6e_*>3(DtDf+r^@=c5RlHCy>A8W!gRf_62c2 zdS!vA^U(;xU^{yRJ#@1ne*2XyHbItUmHg6@E|^U`IXIL~dXQZNa9OaxnSx8mC2%Q@ zRpk@x?eZ>Z%bX&Zm3hz>HPB-Wgem^TMrQfjK*i9KaI3k2P{JFsVJQ0!!|Blvf2~8O z3QI1f1oNopp2s8g9XBMxL1BlS3>nXkpHz;{g9LCxHF_7oPNDZa3jS zgM;K>h>4MIoDnDZ^4*ka1#{a4)^Gj*`Fy)l z&IS;j#W*ogClEp;VOmR?7{+SJe?(?Zwb06fH}|$=J*VoWy*T;DQ5e|S+q8^%amrS+ z(kcf7$IrZ0ZRYhP%TLc4&rK?l9~ve2$b+_#q=!1-jBz z=~1Ty%`FC7#)?GDAO0*olMtv%(|+LDY!@1JBcO*;f84YfLtG%egr z?!j{(B;Zo*bToB>kHxJze|ya)_M9299uc-Q**-Gqi%CrtO7g|NL?LU6VKUD9x)AuK zaMug(MDuDO(0~|i{5Z&RsvNYxfNm<{m;W;q^C;l{OWrfGnesS28RClk!nX0@3%tiU z7;tYXwPY-9$(MLfUxdBWRo`Ci1b;if5bmSyqqk49kyD$A#hsr2e@S05k?=b9@q_~j zL*`B%mIzsbY@oVbyV3J^0XuwC6^qq_XS;BPM=b#sdb_SACJk?i#};$mQ)Aa^RIPkS zf!eKd%YPkt=vIt>pI1{mcpUsF=hP0On`*^SQh$LkG2N%{I^6Y(Z+PDG3R849lbn17wweNj(v4*P?PE&f^bj(w^5bNMws;B>#eUP_S#BQ8pH-|d)k+sQDD7c zOJURv^`;6HKPMWefPn|CyBr+Uh2*ep-StjgyGv=2*|cXLe{D!kgqBiN!Y&UaXUWqg zsnA|N#s4`1mXAw4n6GJ=iIMi6$H;J=;e9`UQ4^KiIg=vdWAMYii`RndY`D&80BJb* z$r$W;mX++}(6BPWsKs)>(LBqVo(6Y(>ieNw^S#LmGNzD(T8XRrn~6seh27CO-NB!e z7gcVZb&DHjf8@i5ool0`HQsqP`|?F=)TH23;yK&vrzf13l7B2d`=p;uJp06@urmuI z5~XgqW2&WXYSe5k`dexZL5-F=34%b-r5O{(oe_8=tdaUfPSoQqiX(h||pYQ0X2qCLbRkgO8odRFSlo1R>+tz1&=6fsIi0Mz6FWx>J#*-(6)8=tX(aNDQmNP zdy~)kll|xtuHxf70?~3M+vH$vtyT4?7bKd+l>5P{Ys&BwgpNMl_s=L^EjHucWxY2X zDP2Lyf7ri5_?^wYPKX?0;9afxz=)X@#}FMm)F*~O#hTi0w4weDXO9}1`~03n9dkT| zFhPH6Yfqm^SDU*|^A_}pQKe=Pc!>NkDwR-2Z?O}l1{7Es+S7|iN0O#%ovcNvm)_&s zu_GSWe$bVhJhkTes0Sy0A9Ei3qYecvsd8UTf31W9*eyQvR>madTebWZWrJeU&V2#u zCAHl_*HEuK31d?@nBC*i-nuiBda*O((5}%+>ghhx~y<&&iU9;P~w_-LH9=9kwEh2@A7O=8M zeG`^NU&YA@rpmY<5t06eRx?}|N zi~E$1j9kUKto6`OHEQ32U|3||%(=9+cofn3`6%Viy!;mx_?ka>#bklDTt<)p1EYUZ zo==uhT%+cvuGmw!a)_**0c)FQIkFTJ7n@O+kiPpvKoctW; z*=<_}4T%>pFonPH$bs|*e^p~?(s*i+e=Cf+RkWIPDymp7B<;id$$65G7gX1utBM$+ zO*4k=(YAcO$H2`+;>46eaFxNBg5!I{C`-7UC7a8Ixx!QI{60wh3y;Pyyz?m6e)|F3$l zrfSb#-K%?d_qY0^B2!Xj5;1`qfhD03MklH09hw%04qCym5Yy+n-2&CumOR*{~s!(GKu%p|5rJxlscXYJnV_|V|abX78I50!)%>;kx7y&L8j^+Rr zumjlM8EgXh)i6K-WCQ-w88Z?UK+W93;g4MvYU=0$vIhg64AvILV2Hz0gcHOBY!7() zI6zfK4xnfYhWsJR{UI;{{+bPdm6`SLbbm$vN@M}~9SkxyhT7PIAZ`{AGk~duH5i~M zDaY*S>c|KHK}>!TLDqi`(5HBiGswakWb{P%T{#FKDWVJjJvI1Odk)6-7PgKK%nlaT zzglGZmF8*65)czHsErL6;^=_%t3GiHd$94-*xgwEoU9cD>H_ij3z%9!OiX_@Vd7-V zq7JdJa{|kV|3!H+A^l@B13LmZfjr#oJnR6l9RTcVY|ip4y_$cUE%>*S^_Tgn11}F- zs4c+ssR^)`g(>*y56Qy;0JpS$YZ-m6k3NW!Sb_5uK%`6~D|73qMgH8Y7 zr^C0ma0TcBpR~sc0RH;@{igpUFB2%l+U+0u@AGAmR#j4z&|&z~@!vjCQK&1xgNcm; zz{JK01hBHQ0s(*APcL5ookj^{@mCqZe_~}Ircl5W|981hbNWxo&VMO@_OI=r1N?U~ z1?ZD(!2sHSRIUf)1R6g*SpT23{yXIVPvXC_{NGgmzXeG;SzG^h)Bg7Vf7~D&3v0K( z2v4eYa(vnVdFay~K>nAi3I4OS@?aASC!7EE$~c0aHbH*`V)mqFCRPq+AjcoOg@dGp zE7(NI!qM3Lk7oYZ)qm}pwFLyM1a+|Zb-6r60fGPHds;AKtEUUZ;YpZ(Tp)+1ZFBs6 zjK47WX`lYP4he`c)a2LVv2k(%K=$?^H>9Vde?pu957ws*H37T+mNtNe83J{D3IROz z>;*7|+9QAcI%Y0z0E^f!(;vhOV3GJ6adQAzWdBAyPd@Fx5ibvb#poaOLN-lJ>O1`sfQxLVg%37T}^VqH-t##wLU?P>=Gb1&MoqfD`HvQh? zl8Ag3?K4cSW|AlgUy*$ej1qAKdOM-6`Ci_r>^<;F4Wk?lH9UEEefse)x{Zd zI7ENE8s9fn92<@L)pj_4;?ZPp+QbBGMe2nmE2NRX6==Oiig&3(U+)|2U&iPr?uhV{ zb@t!+K^g3bA;I5IB+h|QrLmlcdY4_~{4EXB!$=BC3`bQymrMl@sb4HFq45|`?~VdN z%Q7R({5{e)JhU%)Xp}xu2?3|qeJjs9A)8rv$;T|ReE0QX{t&MXbgOj+I3-IfM z+t$eKZ-ZsGG$OU%*CiqIB?@GKU4R4IhVdH1}UMmVn^!R94(Kz$>fWkPJ{ zVYDesx`nCjn+-EeVGmw^FYz+wijj97N=pBmQWgT9OVu@~1y@TD`j3ScE- z;kV5Q8pc^Ffjr{oJiMjfZqM^_Y~8nV(&UcQB{O~WXSP#XT5NO)weK!+_pWDZ^}7-- z0cRKC2B+p4hI2Bkhq4#j_ah6Xh4cd5w%H!eLYJ@fh?=F^lJ&3l_cH{=0f>M2jw8tG zg%l6RJR`UPjFpSG;4gW5QcM84Syr(}4vIbA&6#>p@8r^iJ@E(`qn8ioFAR{m7^C0t zFGoNb#}&?HT8*qiVIp!mjHCBF39TO)trELa-~7@8~Gt+Qp*vD%0Va`5&!CmG$T1s+xsfh=Ff z4|W$y^i|@U0#t{P#NFM4uc%a>`My81ChAgWN~s=E(iPFktG>HvxO@W2raolqy);;? zmT1`^tUoe64eUiz!a&@o7*uw&Yj1E8GzKzI4jO0k9nNr246~~+n0tReb9=_l`LXhT zlY{MTU`c&I?S;+G!HT9kGhv?D4w+??$a8{RuzXx?Nn#&f%ip_N`YNnN|n1+?DI zWLRsa3U={zu}?Fnu)&xpD24tQe%eDlz9l9-0F!^I@AC?*R9Byj(BGEne9UIq8nvpKYJRyq^AtVbuvr)ZJ3&w@ejr=*;Q#_20o z{ydG60nOJp^!i#QLboVFmoLd--s*e~4G4y@6jtV;2>`D)J8o(<*ZJ*z7FfnXoxg7S zmT0w$?r|~Tz@&czo1JT8XBTAOErV&ZGHnOr$ifTC4pzX9cwuI&bBr@B8Dd&VEbeJt zd>|LAecd5yd1+R06I7jE=A^B=ipahHy3~srrbhH5;6^l^AY*&Oa=ko#A zQ`sB1i4mD`wR?W=1b%7^y_+~%MEMu)%T}tiq0g>Ahs%DLV11`>>bFtTyeSPw=XIz$6)<~vI8EqA zpVun~5a>`H81E?|=krSXMmy;nP1c<8Vb_Nx~W0~PP})V(?e@D#syZS_&!7_n=!yE*U+>%04^S92KC zCS`v_+IXHc0q?H^$^`CyYGY*MNT4g`3y3gLKK~R;Gq4ibfv%{BQ+(YjDkJuM+ux_! z(0*rF+85<(LmQ zsnm?^y@?$9b;Z(TREF^y!fOX_I~`Qo-mp6IL-!p3K9qv2+St#-ubO+mw!;8| z#(rFW$&JL$+G`#teGA(yArCjlGr6(jcs_qS6iRys zlda57YNb<*jF=L-ntqVW@hN-U!hjcNjD*_lL#V@`waD~fGCO_fCakcl6{9e$r)&H6 zGD}Y2!o<{I(j1-Qtbj;RCq9POPmLLk$me`P!PfegogCIGR+u+vu6}m0S^0YV_vqFP za{-EkEjL1v3EJ(jAkC2@X`6q5%!Axdde&L9h}?q4CG@xAV2J_}PejwZ>YQg%&Zt~i zdhmfEn;0;;MM(k{8qTzyDGeF&eLY5}YvFa3}sk6V8Lmq2L0qNI>d zz$+9Z{@)k@GNhdb!*LJOMpaxL@OV8W_nLFCC|RvWL2tWWXKY)Q-TVyrNf8oMhlzCi z%<+0-_;`2Sux9@LlH>-_Z2H1DGevoSuef$!mw6+WkC`05Jg~W@z!ixo+)AhQ=g0MVDk>N( z14&!iBBeK_aE<-eWoRMGe(T?87JKnc;xHK2bZdf&?n?vs_|IT^hJ+NG+&Oo#FVPjp z=^Ui-dS5Az+v4oJczAc&-2fStt099a$Th+1a3>N-U?=U2o;T(W_|f`*l?oL}OjS4R zWT6a#Fa8bjG~$+xd!CxDoZMZF*VFQ&+)({jTO9oxmBo)^c)3z?s~?#oc*bpX-v2PT z4-skbVsc+TMTuE7Ip*hgeOmcc+vL7eet`FEiooR9cdE9{V0%~Q`BvUSh7~oxvd7}@ zg^L~{y)Yd3m+nz?*~W=~paP#@Ie;Y1`!43udu1zrX+KA-w)w>a`~qM?UxlFB6!7| zs5-qBe7pMVX_fbX$lb|qOgAnz3mP#Te8k&jTJa|{0Tf>f5>Hq#N*4yFbn+Z##E?v0 zpHnnmyG~^jtjdpXwZ3N#;BR=(;EibY3f-;BeMhl-6m4|L`6FqHiQFEAaZR=8ar43w(5a)W^t-d`3Hzdh0L{*Z}J1+B8nKT6`jbr@Vtol;J^ z*%=phZtaVpv?ZIaz*Y6fzo3K@>2ASty}x;rK^h`mT5W&MKx2bdDd;KRC#Z?&aUEh&g0N8E6XoP;~Fr z<#JmnCbhN=Y85T4Cpc1jAov|A|H9AS8TW^cmQ%-><4sw3_xux!Z zlgaJByY+}Z6iPoPB2~=M$!Z^K6TSb4ayXLl#&CQoKt|vUonE8j4ebz5-W3JI6~m4j z_r4HBXq-x1#Mhxfs$w;TpFQjK#seqZJ9^9h4C!yz>fx*iFc6X+mK5}A7uXs@)%x^! zvr=I~P&tjmB$2dpiz}kUZdc3VJG#VwCR_jKlQC0g89$2YC~uN$dWdoNb)0i0MVsVM zrILA^*~;1|K%81gU&s1576Y?>@?M!J3<$HQ>+xzjX2qmc&8o>=V)*=^;yc{NnM}u< z|1dtS1;=}i!K5GKL2Yoo%SvFx?d47#Tt>m6Z%TkYK)^{`Z7opp>ct3ByErv}lRj4U zvz#gZk8z4UDJop2t?$QvCLf4GgZV$irvL(yqNy;MLC-i?nmd?u-A`=|OpuD6uHQ%Q$+W8u?0XyM#SxAd~~E+v6#fr!-?!#-u$?0 z*<@9ktixqGS<&g<9ql-A;&h7O=AxN{{^ckSu_1pt=8NeH91WN^pI2hctv&^1zK>Bu zkiELllE_3pv@Cf!t`nOB#bXK zG+g8k1Fbgu0mL$fZ-B;BX5+3m0j5820TaFPNeC{aSrAsVUOM{-p;^;BAFJzvUH+@U=?qBDesq-nkmpfM>_NZVTIqKz!FUh82ktrQ(t6vum~ zzwx2P{pBe`ha5*WYjSWNrgEw}rX5lwN$EMZRN8w{Jd&12l;!stA~d;2s^>*_c2gLM zuPmK+t~vtfqH$_}FgcE@Pf({&$0J(sk-?rbL>4`5gw}>m7y&F1y9w~nW+y>|`5HA? zx_7GZ6HFvQ5Erj|M&wW(h0hYN$Hkugthz+jMvhW}2iLiGPG9_BZ@F@)C${w+zv-cT zb#%`bG@>Fcgv$)bwGArFrs!Z$K<~s&zF7eaDxH3?$6Gpolj)~&!~1qE{2ZnP!cLR-9&VT7k$GT&M9G>(WcI!u20lHesB0Lk*z9;JMaeL& z_aw!e-VTDXIF$4EUA&m0`ocrHP4eo8JRX97tRAp!10n$ddryJ~lCTg|q zI?dsS=S8o7qGZHxW#-XkVfH4lmNSYLaUY>c1%6bV5${8j0PKufwT=$y)eI{J^%tFL z<3|c#nL|<%`RGrIc5B0hm4(t01L~9{@Wg#p&-AJyZb}XSEAu(q*#*^sRbn-GH)la- z^5)9Q@3SXe<;Rj!#hvH%_amEg<}Pk3Ckx9qWJ~FP8`U=RD3;03Ce4=!gXT^wGz~bh z22&FW@IY@z)QU?9&M4<7LSRA~nc)wP0Dis6KajQIK=3wSeY@Vk#*UeuYHm_=<6yKKcSnBWP&f$)ZI(jbuirjQC>?$297d&1X1A{AB$eX2s1pQSgG=J^~I z8#Jpp2lgLVmTUqNWF|j3dLebyLdCnR&`up51sSFXa7env=kIxzZ#dVy60J8P5B*gc zg^%;}m^&`Ca#mOR5BT=S_%TD%>PL`Qy(kdflle`A-t6t$Yl)(z=k+Q%#eeMy^@J0D z#t^zO5)>a@Sg$6d3y$AObVY_=yFc5@S$7z-=1;K2k9_B0}kdDRhq(9q!PEb|5s03m} zD;_Z(qW58cT^1>^diKq00;9!$PKVaHm0+sSt%|Dgjy9yQ)^vk({JcF{FM52cFtHf6 zKK#5G^JV10^MsfrnA)J03Ygl_XFS1{xglyliX?qw=5UX}eJC1?ucMF6h6LDL<45nY zM%0g(YRkX#01>mYi1@b#cSZ^3k`2f_-?>e|vbaWy(#O*u-(POMyAdyW1&?n-_az4xZ8Y% zb-r=0a&Xit_#6g{I^Jx39hia0f{z7>6OvAafxf(FzHt9V>bwpY4U8--84iD;oVere7Oe^pUiwzm{vsG_1x6%^vvqRh%LunOZV zpiKE~QZ#Hlqfp%Kei+X2tpvQgAP=qX10k@y86kw9c$X^^>qH;Gq8i@y!r7p3UGKw7 zNJ7UYj>dYy>6tEnijWI2mkq;F__lVzrBQ2sS+GEt!4cC!?N=9=Z zwh7RkM#$hh(nk{}DN-hTvP}2DjUwcS- ztB~PV?Q0<~51VG>)`q}S%q_o1G)ker*yJn>)?5FXXCjVD;ro3BQ2KRzggBb%3U>N) zH^M9DXts8LLf(?o&C}Jzw8;<&_D_~@9H}~y1#vDEQtxAz@$N=%Q4jo_YO~Y)Y0-5d zR9%rl88Kn=UfKvRaEa?)@IQ~;RR+Zp#akt;ZL2HXbp@bx)yL3;7s6f|I64+3Bs^q^ zRFJX&?;?!Y33zweop6ThUI~4J3zHfS^p^*H`N+0^^ut)M#q}awn8bKMzOMFAEfE;g zNSHo1wh*ecASMaPZV^oq8%t`TXi)KYj>$N0<2AzEX_R%*dEK9=UI zG0+oZ(){vxv6lfUvsfmHP>uXNy1rpBGQvph_`bUj#`Br-kLN2(#UCiGyGvZ8$Df_h zVo4Xpze~w&(2j5Z6e^Fgw^X?-y*$c|+O%>>{%pm5yi=tYTcWks!4h&YmD;{Vj>v3( z%5YCT~x3a9a&v>FJRL zz95T8*{^Z%nU?I9Ex9&Y^70m@Vp6+*F@;MPTIXGvc&V9}Fg_?9TTI&e>)V~k)P?Jb zA@wCo>%}&*#8e-xW%v!c2#v7_j_t`gTAya-eO%dp(X==JHKxizte8Y$3}=aGt&^aY zEv0C!T;c@T8<}YKt1o16Kpl0R3rRlX5Z$}h1d3M&`&saV_K=sIzbI9D3W%RXRj^!#k{8AL0N%XF%Os`qDNZu@6? zsfPXWxlFe|dIhh##lagmTNp0zgT%-N<4mDBG^-kpE6S|Byt zhP}~`Xgy~XdWYwt4xQuTKmd;j>Z`6x7f z^@!8wY~M6pM!*#9X`E|}(Cx@rgq)m%7tekH7FxWhnk+MJK#|FLk>o!uEdE?UFQIdQ{Po#RyLvE~*JA>mBQzU=TD_wPqHFK;|izfuS zA)bEU>h9WDTUX$1d}nw>Hu+WX=*Q1K)}z6>JjP>MK#FCzV7tW)gB%}`+lPJ;*{GTT zQ#vLUN-%_N5CRgmP{nK^ zqj+jzJTu6s3?#y7^Jt^DsTI1-%S~XB$SFiv>)S9*@%9~mfQ zN5+8x7blfB$hu`EeYfP-nyAJfxL=0`9+I`zj!PFa2>6JxgPWLQ&xr0A$r#&E0d{)I z7CqFc#Zg;--5BU`lDwG+eg38>9vmW>F&j6-^;k4)dCG;n=;QOm+F@b-3h|y4`ua$F zx4Xdzdy&bnx}O*M`)Xv0eXlm4ZH3yRBrxvYuR<}yPM)r0)SuvpC_&LcjG?~(N^8A{R^2^kSAHJA04F^Ph;3fl5d{=0yQn8b6 zU7iPj2G$&Q7Cb0KK(~F>jM^FXWQ7~m>LNz!$!=ggrtl@8#~GXB)eDT}<({MCKneQL zI1CXA_JlNC1S0!BylC`eZ&fo|6?trcaI*SFh4xnF?xX|)8bQOOmf&?wh*axB{rB=X z15Hlo*w+}*QSvX%6%sm$VRs2H{|`|6 zCta5za{?0rIX0Ky>;n}LF*yn^Ol59obZ9alH#jvlmvO8E6#_Unmw?O$DSwT01ys~q z`z|ewAR$N$DM$?^A>A!VmoN+i3^79tB_Q2MOSd2?9nu}r9U>{6f^_~-&v(xMeD|(( z@0zuKv!A#2`|SO^n~_#cgI&T5ZVHiw!w~FT96%v}l!}UiAOHyD;Q#`;u^AaPp$Hqu zUuJAZZHR*-6b=*mUjb4M5PuNj-X;w~+{dZFVE{!Z8vqv%fa|#s7rzh?2;c?+1^*KW zcMt+dgPfse02K~^A{+*B#AcL&+qpSFEi4iD+x%w^1hcRu0%0e_$?4+a!U3{%AynmP1yg~EFcH~A5egwM}QXqu?Ik0!IqrA%4@pWL4STbxqg}N8F;$e!R-L% z_aq>mP;W zCqM;$KL@b?4%LDDnOYTy8Pv)4zr6|w(ETJxz%1_7%zw_s%K_y5V~0A*LR}$dYET5& z@{eZz*tLGmnhg{NQG+`|e?2buSwP@_`R)e{Y<>TLINl5Mj|=2@KW&KL*Z2!V?&s;> zeaOJTaI;^7$IbT~0CI2uxnbX5{XOCXxO3f4s2Rldx3mGA956WIJ_T^k*%M$6cfkI2 z&Cj0$IDaL7nf@St0H@SHND#m&^EVRU25`Rm8wm;kI8FaS_mSYg5f9frvV{JP`F?rt z2N?9Xg^TNcBd32LHxR(-`Wya>9N5Xh;hz0(P2MyA5B~kcKp?IVF!t;e9Q?xHs=~kV zyiDSW3;WuTF#18_xh^;RP|j;iM3>B%@p6ntT7T+Sr9#=+PA=KkRxPTM_UGvf(?8u; zD`~3Scu(1BWH&8nOrxgmPLU^K-OniLrU*VGW$DCAQVZodbRnrxg*|M=5;L>t(qJU; zcv{gh6YIi6oG;6-7|^KN+*+2Os!U2LsJ*-L3Q=d;tGUK^{P=0cifyFd_i)3I1l43Z zC4b@O3+xz|(uYeueZAiZJE_{jd=#C1*M2YrA_!$(^ioRmJ}A}xmW_X%k>|XVOyq7V z_egxltgC2|CH}lZ^~iGdXvc{5nSEz^?c+|&-CSk4n77GU5q&Y@gVAL_qYbBugJ289 zu3SScV%AySuBGGynxPRFfw_GFk~~UWjeo1at1?oCo#ok*eMi2OJTx1oGVUYSu5Q2L z7F~DC`>FBGmrO2fDPyH0VNixe zsYz^OdzluSV@wo~$soNvI$BM5RtA zS&Li@Y7>onsjop3YW!&7*8@=OO-g3Mm$jzR;Vy$=$gR<&@uy!E$8vaA1q&HG`oBWa z3+IGF=j3T*vqjjC96B>GxYcXztbbYa4<<8Zx`GlPmPHaoEkeFLFie;9iVD7ijIBB1 zGn2{6ci!SW`}|fSIz{**%=O)BY`AXqoLfP#QYi{`==&v!;wM|;n;i#4pWFzZUeu`K ziHS3+=+~tsrI9>Y7%<{&#QR#}jnsR}TPA2@+_LT|?!Hy9lz5L9pwd|HckBfQqDleV{8#}M>CyeJmIs$Dv zKceU(BVNBt?&=4T-ME|rEq|Ef0{aFd2Gq#YB|D5*Z1#HY!uzb4!8Fx5e}CYmf?m9kMXYE5 z=|RT>_1To#dbjbmn}@K5P&vWAkm8Ley7W26L57iH@iaXppOO`kDBCd)-)cQGSZ>IS z(0OAxv|PYmxyt9%ZvANj@UG4s@0RW$spn2+)OJqM6TjJjDix-XM%=5!gDvWrpT5*=H$tjMK}C$ za&(z`W|^*{y9L`gt;=TC&4ARXmNrH{w*Z@4O#13>1KO{x2t^`|0JU+=#%*urrHUWv zv^kvOYbyO6Mt`c^>>Li(s89+sQT)Jp7t%^d0RfSYT0Y^BsIGtd5Mqu1r@UYW=&!$$ zM2pO?O{Nqv{G~?#AZPx{p}#1SW0h-gWFZ>+vGE(LC5<#oy522C^9;ue4GRIMZYyf5 zeT#4NG6U8NqUl*q;!a`_(a45j#c$x>QP^9Rx^Jr^PJdvNrJRMboeCQ9Lz=i~`_mDh zbcZtei#`2~H^L!41h+>{ON^ajQHe!hrm4o)y^4v>t{x| zqUdfM(ZX_d0A<)FZ{?j=L(dw~nZOl?h%w%!=U2}hC579(47&_kmNq$`2fb$cZPXH9 zrqFZget&|TycU&ZKU?Yf=r3-;Q`Lj`s=nc9(^^vY+iSfeP)jUC3DHh7`haoZUAk7W zVYLC}`d03IVKR}buzVt4+8?xDB)qkut2W?b^C@~c^&NArTGhk}Ty@vSnKhOHgxoGs zW?~=ORkW}YFCXfjF}S62$Rp?@68P!;O^xi$dH7Iqa718RtHq zd(2Tu`tz|a-;Nupi+cO*=)~tE)BaEXrF;qD@KGhi{$6KWsyd2utKyZ)cC`kaS22?b>kNuGc7fyjUG(U z;D4-&ibY1w>h~SZp2ItFfloSr^{ZrnlEnynAxhC?eA;SThpCOV1bfyK6DE)W)0rbC z0t5?=4;xP(`pG-W0cN|NK+dKj*nZ+RFQW@0eRaK1yL(PfO;{lQ+4*OVssNQq=H=;a z;MChUraztFNx%!9vl1bWj))fpLJA*&K7Wt5J*53*znZd}czAy5j9M^|WU3$i^6Ybb zEnk%!)$%)8%PJdoVQ)jM?$2P}5BlECJ{bWs3l`riDhb95Kd6Tyz2SvCs4~c6`@Ep* zT5I9bQbzgqR+qbKlKTfILlUVZI|0rsc6AHVv;Daa=Y1^SAg5rq1N1?=ZdA;(Xn(++ z>bpt4l_$`ULUs9Ce{p`pQDLVqLGhXzwwEHW7#Me z%6K5O?2b?pDZHKd9#(?Y&t#%z^nX=Yid1@Qo4Y);$=Dp3uKLF^5@w=n8*Wk-D>R>T zMa)YoVqRjI^SiNA7Q*D^?h}ERD7UOt3ZD$>-aJW~WZ}m0UhEZc))?~;ZosD&UKoC` zuSpT{k-Q0Y0>pq_#U*+?`Yn~^1D9jarh|y>*;bq{G45S7>vG#Iq&A{f%6}=!jz9=c zKV*-IrK4_^l~-p~3I6Qzt@d~b8%OzRxJMSw_5#oI3;g9aQtz=VQP?(N$7=r8cc zg{6tc5b0tI{1zW+fR<<*xWMa(e%zRZo#e*xl#n%-6Qf5l_uW-F2kAzvJ6cZa6_6L5 zn(B>`(1VS~O+`;Ltx&XkAb;ko3=xfBou0Z#3tjN1S*2Z_>WTbm8omaB7!9I&@9(2- zU*B7iH{*9(r02-zgy9_1FgS9ysH#qmi+yBCi4hVn93UqtT_C)$S9*6z3?@G?PrVLR6vwS-t{(oKQ(&_N{ono;4 zP^1tiI;(u_3E`gX0AsLa?&t95i;eR7JzbBV8DR}ti(V%-GnmVrIw&zbNNxPoN*qx_ z??>+&AS^VKd#OAiQGZP~XCF*LStcA`dnz}v+NQpv+NySe1QQsRoQZBI47>Ky()YdT z3N?4XU+4m_y(49xNd|$x|P;&kiuA2e6T6=QEhE%l*UnGVW-T7CVXX;B*lxpc2P4$xVA0xB1@K1 z@72S*jcmrk91ljpg_PUe@=C07v|-JU@2nEG$|KroDdU#|d4H2VG=#(upOwM}gLQ@a-7!vY@xp^G{(rPE!P{-%r%6Nt_m9an2S-==ekZ|?S@}^FS`)V#DAc{IW8(lcS`?IVcKJLkrhcjY_iby%nv4G;$n+4xubaGn$qi$#b2Eip_(m}(`RRCeVRfQaQ1d#ISi1md&BOj|xr<-HU6Zk`GNJQiU{p?5J~{?dKgm@mzrYJrUn{@B%~B zjDj)kXUZ5w3;{4jMcz|G`ySK(tQE z{`x1J1=fqAUH{8;fq#LP33fXA*?M&u&00 z^KiXJyx=v73Fmi-RV77*oVUGVI)Nn3l%*2N4#dZpm+o=UgGj1(??IQABy#1sP;y_F zfwPh&TM)5cq^+}h#4xO7?aVe!CMU?K*-Mh69h%T@7 zC9dF>r+d12FmmyVnBg6?FwU_9U6YfY(#)~x5=||>h2mo}Jf>~FHV4<$F6kie^5>(1 zs@*9e?(gYR#RPaLeGYVO*;HAYqn8~Q27g68;hCVYF!DaR8=oAa#@P0osWHK{gwjer z@!bRA0B41j1YzuFaK2--Cq=S;c#!PF5<=>l$BCq&tK>5x@!r_t72L7(mCX5Jaw{#l z3HW$EmS>Rh`6k5$1b#!_J34(p3BtV0%>*eDZOGqeZVBtgRpA;(Rd3L{;+!9iCou6r>4jn!z+Gn8l`nf zjgs%t_sO?6rNA$qd3NeEfZOI!SAS)b=p}nBFzLbFV*>IpYfUo4Z71)uTYOP(p~TSq zb`m8~ORlaP5#+03zo zzc1O?A!Ofmx>?iluYV^|E`F;btffrh6OWEV_;dULCv9HBjU{Clb(xLKz}v;Avp$%t zM}@A5_-q#+d8ZPvd>3p82f$g0f_&!+0B*0N>@R_49%wLJUe)H(E7I(^X$LkrPobnT zwX1X}C2?tb4ouIJpEHJDe}6)-?&)*5{m*2F`BJ9haK!LB5UWVDJcpgTqAAaG z52MdrjU2kGttJCx9_c=uki#(QOwu>mpB;+8A-)noJG9D0?+F^+_J3j)$g=$cZ{@o>HhL1{JJE|F*D*zIe@*4;`J>V@c)+*meW4JPx`GdVqGwW!S8W;H z2A#Ie>(4(alFQBxJ%5rPF_4wCpTvRdW9wXBte#Fql(kKw?h9~vHdCkJmVCbxt|{QY z`-G~{UM9b4j|fFK3Xl6JL-KL{F{5FkuUR@ne@j9tBL}0eQ-KEbA$bwa6Ac;Ufs?dp zf1of}9wjI0mS7DoapUgjAARPa;VFrozDZVyFptS$mfe~*uz!mg4{Kyhv{?sdtybeX zJ{pb}P(nlfkY2?8)ilLOLSJC5c2|+kQ17ZO`NzB5ax<^;I4(d6m68V<vcuL6^D|o0pvszYwvy^k3UiC^U81tD8hKR#WL@qKDJs~wnFOh-- zs5Nx=5wa5f#*@OvlpkT$M67TpOs+pCKHefyg@5)EmEQ;+{}#jc?l$+<6{$awQn!^; ziR)`wv#dkRQ{X-C<@*tdV%8S8wjU96dG>wg|^iRM09aCIrlc!Kyb9Cl& z_9Sa_w18@fYCWc3%!8f$m?>Wnb$h@3s5H|fZTtL<2PNMXT+ft5N_tf0LMCTXc=+^L zaeqYUbG1y<(0FO(?&GJ!-)x^4#Eb8~+@QE}nfpd;7h1B|()8h=n6hsbJEp3-_0bCJ zgInj-4ydz$006TmLG&Z361EC+$PI=1LS7%?NOn}D;Ew@ALv6GEl&h4&+eg*I1?xv!#98y6s2NUF0?L$^6CUPsThZqu#cwO2h zul$IW2@bEFfeI8yK;(m9*{`CJD|@Q56m*^h`)jjmk3BQk>rN^=dposWxFT?L?qL^;VwQT z%M|^zIX+a}`!EVXtIadHv=kB+#I!rJtLrV)WH-uw@!kvHa-+57Agk!^uH$2_T$Z{* zKg|R!hc#vU3j*Xo@X{(0K8t*)6p~AwNQpT6N~1#tux&*MD(zrCI)8F7&|DJqp33yM-%I@z7e)^pVZc4Co5F$ zZIuU`o}$jy?_Vo}49Ol+AxHAgP?c~ABu5&{t2@~_S8buxhRNHd@D%a@C-X{LTPf?a zaFMu?$Se))lY&hikAG0mOojJSHiw33x|#hr zuk3nCWopmF6KyYARb|dQY72EM;snJvq~7>^x7n@rwFW;_TpC1Gq|)-6N+-Ms2*v9$ zqzQ{nvdu**4NSCs4LIt5ZtH0fV9y2G``#&;NMSHu@7cPauZ6F>c39Z&x@=j`aM`g*bwJ40HrY*pOYNN1W`UQ`2Co0iBg~` z0Qbu?o+{&1_gIk9JA3XYkdL$-l&KPeGCuTk3LaU8@ySR^5^~eaN$i3_0;Bp{-O21I z>^X;+2Y(SzU!t@?ur8CDySvowjWoGea;&oO+x+3eqRPBedVW9CBV9A!>`t+eR}*>Y z^EK#K`jQxIB#V{yAfo-PAzuH5IyGf1hgKp*P~g0jyj!M0AnpU%b@ebZzE9y^XZZza zt;&#Cf;yY59pi_#QaX*QmGnrYLHSl^+Fm4KZ(jJ`koz!_W~p zaFthQmNPmz@*xgPL_eV9>C>w|$?6T%ktiq8O}|1Fn-0IOdUQ&qjz!ZK9lqE7X}nB} zD>^ssM5*~?A~U^B#Jiklu03GTL^6=@=6`azO~T#6@AZS9qM;!J;|b;If+Jz_7Y?@u zl_;bhp1h@sw!UK9EYDnWDYsKT#rF!8`}m|HwU@8roy80t6^Minkb6jG?35qj(wt#` zlDOD>;yw4CmZSeHrX_%^=WUDk%SOiW`Q3;q@z)hdF-wok;jd@9v*cPbv>MzI=6^r# z&w=f8ke!&$o32_>Y)>TYeDFJY*{$c)6VzH&thS1KFpWrp_Ze4tDaf0^_XaU9t)pkW z196p06EICIPmWo7V_Ex*J$mWe9a_blBA;PdG`5BQXhoSdD%G=~?u{&Hv|c6`9AsUS zJkZr)8ztzK9ov+4MQg53n`={kFXT^&Hq^Yv?i2TmP&WW^M2Y_@NZy;tKnYTQq?Gy+|Y zq1}A!GlxpX6K_~XpcAh7B(2EO1ko4X;y+8lv+|x&IB_lC7Hh&R8B>elB z_E-mI+N7G!30@wgPqNL;)QoXkU<797DDMqr-@(nX28?JfFGqL{%(n(mO^S@X*8j`GU=ND7i$Ltba@0PmF7<0|BP_5rEp3Yu+17Hpae?ajN?69PxwMVv9ti zkSHr`K^#mD$he^tafRPA3a>`1hRD-J1&_RuN1_ikinI6S9rQ`oT3-#e)nLM(#$5D? z6?#6rjjV8g49&we5Z%YcBty}3BdYJvs_%CVPmLh_xGuk6a~(rd!GE|G+?FIbv`?Gb zTSfkMEQR{fQz)*v>HLg##Z=mMgAhc#{dA{Kp#R9^_mrS78QKVv7Q)?6+uK>#g*>MT;akm3&$b90kaP zaK|?sXv#{q)V1hUGJaHopS{b~cq<$AO$*pd2bqh3dQ-}^A31orhrO|mVQlvOK#I(H zIHyRiv84Zd^;;R`L&?w!a_w6TFl#akUDfbL-mn_Wvzj6Gp?_|hK3vcs7bbXsgy>8@ z+h%zGTg1l|_rkn}yr^)bSBB%ST`Jt7`t@UjD}scd-C4bCrOlt|Y{Gr^KIsL`m@4H# z#u++e+wE)@efX84W9oJQ&a~Fb_I6y2TY}D`cVZt#dy-P&3-<77_5T5Ti8YA|Wo~41 zbaG{3Z3<;>WS1{<0tEp%x5qRDI$;4hm(h#`6}K0b1WhyoIWV_o$^@P%1354%Tt_g zJ6nPkoS`soJ|3Vr;HkQ{5C8}i-~j^pv6z{4Auvbq9~6sOAMEB1afXWjFa1+DFbD?6 zf8;_3LiZsGtrkSD|%pw0tOafX83v6!Da zyZE?4Z0%t1EdMzI*sRzAd}3lET)*7`GEQJOh!qG5PzS;6z)tXtRv<@!j|>JE4CfLepy0Px%Z9c49uh6@<_$5`!;0T6wo z@cZA2e@j?=d;n{R6%1erwuL~k{)rBU!8U(n_~hLn-T-4DoOpZy;IGf$CsR1Ltev5b zKL42i9xkuErnZc%5$ErQ|5nM$I(q~BxcPtpZhj#koU1@VfC&5$@b4&^e;~+TRRI6- zRfgI)1H}Fm3%{lR6zuue^x6Je40gc3V?A?*GZqYB`-k8rKp~(N{EP4Zo94e={%`F5 z73Kdy@c*ty!Nbw-ukH-r0O)_4J_r9X>D0C;-=02^mFtY7mK5(V&DIXlAB!{OhEFdu*y?CJrZ!+#JVe*plm4Fpc>zX5(Y z;Oyb{Hy|hm;DtYK|Hwc9uM7N1fjWY1VE>?ef1!UE@pm*K0IxgP6Z}sJLV|Dv&i%h- zxFgKY4g9|&RPY)RE4YtBsn02<22(zyZYrC$N zq4wh59+&#ey#4$Qe>=C|f?K=CEgpIbdsSx0n%kvJ%1}4K@|HZ?#gj$)d%uI`59r}7 zNm{LU{y)qUv?sS)vF1OK^-mNW$kg@GV$yKyKH2fVclFl~c0g`M>`-COb@dR%)665j z_UcviuInpX8htgpt+i7ntcv}kY>GQZFWMxyc$)d0W!4M@e!_=$+-8p%yjYIYyJ0)OYT`_94cJBfyyaP65vxfg zqi}KE%Y0jcSz3Uy`T6YZZrs!N6n$dc`Ibb0ES|d!Z|i%oSbykE36)Jp)x1uD4ze=c z7lSK8J3$Sog~CB--lniWrN&Ca9Iddh097w6qPEQCHA`%@>Dioq|5qvzQM@Q7?Bou^ zFE4}F5ZDN4T6TseW$(&tRoM^tH2jdA=agU|{Ez7~^ z-um_OSmOZ;D{l+oS&>N?)ieQG(_?1lLyzUE&)U>`LKjqe1aFNAOV#i1KNPnnhN@m+ zf#sLk_iG(b;S054-KAdN|$NOYc9QGee5o!AuPi-TGJ0O&=c|BoIwo7`t{^(?fg~|p`+8VLU4h1b=*oqLxv|yW`Ie`B*kp0 zgM;EYu28?7&m;55Tov{nHi|-7$I7$J&bDn^AAsq21`hg@ z*-~-`4}S=z;v+NmC?gWQ{E22W=t~Oc=9-y7_YSpE=ki~V^DR9pmXy!ypL((ZZr`QT z_SV-+T_NmY50+sHYM-98m(57Vy^WG^_Hvjg-cfi0TvulwX^pKlvk+kJCksiow0MTO zPN^H#(J5k2tQdSfqorj-sR)X>hejNd6Tg+c&OxMjiRs#MsP1AU0a% z2ZSAuib%v`W{sih3e!*9nQe><-A~?^u+Y)HL zU?6^uLIAs{3WW{&AjFLHehUALgAtr}84h7eAH~kF9(ROg@U+5iM zI5g0gMTuJ%+k^i%OXaz-E$FgPdVhnF6<^zqzK3-i{y?{7C*SSCu^T_^{qx!rXC&K)2Aq_j#-`-%?5uP*jPIVaeYt;SV%kES4C!u8C^nM>et%u>ZOiIL z((mfo11TqtrBcQ74Km}}BW5SgfP4#Ykt}(cVVp|0EbAurM_c^ECMYWhF3pW0Y@ijg zz!+rI8w+RdQ?=`p7-f3t=SQK`-Yw^u7Zs{c-QGUW;}1lAWv$rkwmBA@@G%Z}W{#t; z?DB=)er-yC_igr+oJy_6fPV`pC<|kxN}@nTxsOGt`mrp3PNNB{`bsqjPb(7QlAm^$ z!kw7!p+;50yi0{G6A{Mrn6RM=;Q_KDd*H00A-Cc_NEz=&d0o3n_r^V@rLM_W{S|55 z%L{VhLYDK=Y+vLssnF;%krb{bPoiQMJFh76BuV5iVZNBlq@-6Fj(_4tl=KG`{bZ&M z_ElR7B)TgHniUB;dQ7V7x1tX}@Rj&Ko!>t5O1P|uIp)O)9dhsH9RwPT4aqmsnl-u}I|BUy|cm!6NdPIiL7SVYOukDx{ZsaD3 z+{X|}+VI6cP1MG-Re#X*ZmPA_7EwJt?MAfp&n}YIp)ej^d=zeUk@!Zmp}HA)dR91U z%Z||xfHNhTz?ox7o^&91&;HFrOVt(Y#f|w8*1xdj1nx*^WKdo(ri# zi%be`7;k5y{eNR$V+OAROJ?%`=H#d{#NMz9mgQU1Tt7_NI=0a&jUSSzp*^>!4-uSv zAw()1hrR4-XY*-vl|@ad5*CE4WDx?rq%$)p$~59(g8m~N7;I?}cc|g0i}xc3m1b2Z zxxo;2Pe$V&x=8{85n2@nyUQeC^3m+ql)1fu%{JnnS=%1GEz<@XcQH{*HY6E#}xE>F8kloxhU67mz(q?D<81d$z!ij+wMeIhNJ z+X$=ucrt=#Y)Z3iwA+of4nLw(FtKfyTu2{a0+d2H#WZ&dc5Mh|N`3uC?+6<$(<|r} zaBiy=ODI#%#!Ib9`Ubu#vJ=9zc+_FY}av^Ui8l+PhO%+%P04a+hyd zGJjwDb|J9h2yeI|&#AODN&HrCO+T6VV~S=gmaY-!!GS5S;^I$4(AEuCe1Xca7ddLr#D5`I z-kWXI%7xrjl2lD~44?BZS&vDp!lEK?zsnWI^1F5q*vla;6|{FD_ltkW@4?ZmfY_MT zt;nJJ)O6{X)ef69c*Ssao`m7$w`~;K;&z`3Xn1pDwwxS&GsYdCQD}M!v<9q8Cn00&o0}Z9O`J zv+tssVJ;UfMvuYV?uALj6u)vgxz^Q6qoTefXBrhi~WVAPoR z4gRT|x5h>2Xt=!mv0`X8P<|i={2@5N#@!RF4>fY_++HxNts~vs}GSB5JXV zcSt_*72aUa#X%27X`>F7)PHFRc$~X9M6Y{R+(J)l8%LY;=BF3f>gXvoqn90uhW9&K zKT|bhG3gktZk@g&S)@aw*-AWKm3ua1$$^7Il{$>b=TrNU1#c>ppA#RQ1bcr`1TiL- zN|&8xITP8uwBF#?H4i(pogqaxO`!U^SA?A^eFR{~;Eg2o)4K{~vwx4K_HIvpLV$N< z(lu(=t5Sj|G%6h>H}Pq&Za%r1VvGyHx}kxmF4=9GIa@KlXx~{ss<%u0mE8snNz-m! zx3axZVXj4$yI6?fbED0yb!qNln+&alpJsp)A*$>6ma|9rUUOKeHo7v!D{X3GLoPX=)fTKl6YBpnUgb@X7trf~lR{Z@73}?qzO-*|N1V>6bY2<8U zmVK~V3UQq9C6vCG-k6L2k&#%$2n)fb32G^V>7U|BD#mTTIsLp&PPbgy`5@|=)}KFP zNalJYt;72fDotsMz~#9Cc=BFrfdwDh*UGS?E1XbR!N-48#Vc*@(hg@s=$}(*? zH}0@f!K)_^e1B)K3(#1gjc7<5*rN{do8u<`qOaiF?o5>nPreDrqZ?b7k8PZJ^_2|jf|yF<*Yy`Ww|JU=k1JC4}bkH>s`34Ly(sh-VTH#ecPn- zG@i<7$BJP6k&@A9X?B-htz61o-6p|}b9rTXy2cV1E~|3c!NDvV6J9eCwXm?I(;huI z+da(^ZI2N(r$uw#VkZl7bYucfE6l-6j7=vA535~WuiFdg7ZqjXqXm$+y49w2hD*3# zP}Lak-+z841g>;vQ?^1UZYdlnpNKNPaGg)JV_|uxfBag+0bC?|TF~hQeM$LVm6H9w zJEnj8X_0{fIIW$Umr2QX%69&)tnkBq;G;>#&ETqbjHWT!8fQ9Wb`({gI$JcxVpW5s z;4Adt!=TyNrkGJrJze$jZ9ilj44Y3!2TIY%GJiRj^=aKrpIF4ozQu(#biR!ol(0gl z?xFk^hB`NLG9vl5`AhL>$F1d&7FGgB7C^@j#eK%;QQ16_>tO2Gu*3}GskCUnK_fGIyaT>!~u7e8qxvJV6z zk%hiLbB|XQkTt$I!QHO?Ca0#JyV1|!3R(1hZ_T+L*bz%^`tB~2@uOht`^BCEaZ?^s z-ThGV1cCE%-!R+dhkKDCnOglT1OvZrv46w)E(x^niE@l2|7k#=`ptfc!E3Oqa%4;Dq2zX9A zXkMt9b`F!-ehn0*RP#)dtEiVajoroDw0yr{#Gm8Kk$koJpvT;~b{1Da+_Bc>2z9Dg|@eaKJCAM{>GOO_P z%yHMFzQgWkQFm<3tNB48fnfe9AqPU|_>G;Qi9Eh6Y=NHM->OP+q2v*+wki28t1YHt zcIHDnc0h_y>({)|(nb8<)AG)^FMlgTt$Uo5@?^_-!G~{zPM8Z5n-+MbMiJ#ZtB@4I z80Q(Wt0he`;r$Jbw5_s)Kx4+9-934&AHnzO1BF*>*+s^Wy9Z!j6^);rx1DXejBN8W zOQF85uzz)Uo3`|5Y7=2F-kLTu)f-cOr{{`9-^L)B%~62$pJ6%m0g$KZUNL>jz+8K^qY2K zBEcBmYy8(kANSA3+lyT0@Qdo|rArstzzIt^`)GHLxn`ZL&JX$XNzd2bh-*tm4M3xI|}i3}kBA5e$SiZc=>> z_0b&>LDjSfO`l+HA{yvViVI+&le6=a)XI=XM$gY`5a~*{QD>Yh@qbpm1pe{p9S3R8|L!;;@my-FlfzQWoJy#^(EYAtq=~ zMR+{L_1&cE$w{9nD$DC#A?mYtRi8x--ppt}uYQ!XH6uh#4}IbyC%C_(0VYg7sD1Ns zxpO$fFXH|)T6It&c7I3%^^J|d9)i(%P&>7{5S@SsjX6wxx1%>nIbMo5~3=fd%UWOb$#@<8R z_wYbV2qe(StWr)GoO$M0k;_GxJ9`JSQvfW7YZ-c(o>x7I$A75)6n@r1e_F5}Kv{0u zXP)9XYE;60!>~NnB###?me$m{quH{mXnRr+-i~I0p8H9Y&+k((F%=0kH!^l6TVc`9 zQn!7y%?9n&=C|A(nNvkihe3l3-6i)YI}W7Nu8=~D^79&A9S@s!!y|uUwsnW1vnTr` zTk4p#n<*Zh3V)N;*fcz3RAg}(n0M!V{lKXU2&15W>5Z?Bd9);4ei`4OmnBPM{wDHenC5<&sdNE@=(v2-O~^*B-CjRk ziRbx4G4~s3c`Ee@T{&7FZe!8w>7SHo{n{#eER16m^gni8Ik^>?zJz)4nEag4l+bw^ z@jCk2mVdC6qWsh$n?#I|Ui2d$QYa{E%#ZtiXnBwXN)a9(Oc5;$W~MfWF_D z9JJu3c+qh75N3dK^>!!tlxNW~jpw0GQDhcG*MHmN>Z!-Wy&-#_0rtioIUSt_bj za64rqc4Aw$E$<=edloB#(2aAc(hKB8!_rVLHJfT;s}R2|wMR{w_Nf#oo>s@%z=+Ie zG0LDC*k>co7!tm{H0F|1i6KwvM7_m>Fv#*{g1#Y-)Ce7++oB?})|zTaHp*9E2+#A< z)PLJgdt5mTH1eMN%0D+%Hs#kb0&hRC)5muJ#D0S>{N;Va*hRqqcZDvpVr&JPnWPiuF0*PB@A(i+Y4yj$TlV#C?xH@>Q7?nn}94RKpT&(ePEqf+V0-Hps2^k?5*niaV zo_GFRnIs&i!lxL|7Gr|8z|?IzkTLDz=h0e{lDH{rMKwKH42E$6S&QDMtR#0?yX(H( zEJNlqMwW&}_97+xUnLTsF{vM1tys@sUyQbRDZ3OJU_b-B$Xbf%v_qmD=kzb+5t76w z8THzPMgioe2;4WiINgOEn8#n1u75y59b<1RJCesz->cgF5L=~+`9fODH!eQuCuGEF zK3FL?AT)e*$#yRB;ied&tT|(_9^>s-E1}0Ryw(pqaS10;y(yv99JorC z2K6>FvoCT~MZ6v?5QJYvCI<1LBhF8&5f=teP((+%acnFx2yfem= z9|(v=`mwRfBEZM<%7<4+*X3^C^Sy4Z%8!mXNdzRgsEw4q?-(}uzCh@F%(%*v zWEeB6G35XSRm=}MU4OnSGT=0**9rE-9q9_qF3McyW#br>HM<_i#%+DiCezw8LVSYi|u!|wWk{X9e=Wx|C3*=r32e+{U{8V zo9?`-FYZwxaivJ`K^K>C{Q7900cpRc25ov0PK5hb=L5e3S_mMXhO#g_ku_pXD_`=( zq~H)L+JQ=o6@MfX9f%hvL2bCNFq365J|^9-G4&1_A&zM-)@yE@Ido3ABvq!zL*KBs zZ+2*C3AU+hG`94U-ts$0H!9CF!}%ekHe?VNzIVQ85X2Cj%&%jkVEa+Mry49d&>`@Q zRURrW-_qXqJ=FlWKm-r5YHj5mJ^9Ka+(w(nwn-BD=w=| zo-yE6I)R6e?TLI2g<-6uLPy-T_}M|%EMi19F%`#=3Gok9o;}^k+m7JElk9rt$krxT z2G(|-jeoE&cdz7&;@sHGYh}OAimD_8604p*7aM78C7pNB&F5UnPJVrp)YBFwB1+pk zQ;}30SBEPtJ{H=1YtNBJTAX`Nqm|}YeU3O#KVGpp>h$#yQCLWvS3v&`XyOuMq^6c; zd;WqcTz)F$&+EE?m+|Qa6PE!60TY+-_yq)) z9P|VZx7iZ~ZXW_UFqhu!0~VK$m<9|4H#s>qm%&{F6a+aiGccEd%myfbjkX0;6Koqd zPDzXorDf7RMuT)pcjtfs1GW*PJ0%sQLsD7+MOvB(h?Incw3MU@O7o#U@AEwG`~RQw zeP`!v_wTCvir;mgvE9=(;FEVi+Cf#22oxWfUqBM5sHHCk6c7;N7Z4Bxu(27!P;Ssa zQUIGV)YA)wL`eQiujmPXg`jR^N)XhInHCZORQGlRf`x!!QAx0vq<{cWP(VQ9KZZz8 zNuUzM2j&3O;s>fD5l}Axn5+Z`wmhkC;7Aqb!r z1mz5c-`r>qaRVA4?O{-q|9^$xlyXL)+$BLEUteE-2;7Sw>FFeY!^I2qg`u2*`cN;Z zrw`Nt_^Vu?HUtj+T^K)r4QS{L^ZFw;Ksus)A)Zj+jld0N4@G$0ICvu*pq{{+yMYF3 znm`?QDB_Q?<{txI;9so)g89LJhx^O>S0EVTw==}v9tn4cApBtnC!izD4GPpz(d0+@ zp?HB1gu^dGh?^IG^2Q(H1A)0g>~0KxCk_Fs$m;`kK$NF9G&u0zivLCcFc|0nvqu5#piVFZ;GgI>VyNREd^34Zm>k{@2t5`e$9Wpbju^`2T9vP>`D)kViPV{oO==n3oF759*)`L)kn3p~@e*(XRz_ zgCU^0NH5s02L;Fn77+L!-OX0nyWTt+UN?OFt%BYx&3|91jIc*K{Ms%-5m6w-(-Yzk zxEb*c5&;H+Z`RNO>i3($KoCCyiMnwC-jo*%bVPare$7)t90;=eCHjLTfFS$7(XV_! z4*!CGU?2$kFDM2Cx&8~@L~{EF-Y^`5{2L121ipFw{=qkq-EZC;gd5Zm^^X+%m-G*1 z{)r_71bO@m3Ijo&|AHbwkk`MUC=m2--(Pt^419)i8$p*ILB`>( z*e#fy>THD`-r^*>#gr$$eX4%-=&JemG1KdM8?~YugcnsG_>zngEyK$v*^2C*PSG%b zDd1p}dfWcz{Bj8znkub4Y8o{1@*yw1M8DjFB2&T@}V zTKbqHjp@)cVa|t1W{yeqh&H3dOW@3Bz6Y!9E&ynR ziBQTAp-V0Z98!7Jt*aZN>1lCz4@a#ctcw8wo7B{FAGqlWzBTZ~x;j@*V7cgj_-?g- z^4P^9ICN#_P2I4O4aowKroU zKHYXN$^1oAS}*A6u>l1!VFvfGYC^mw?nh3TE|Ky6dc~cYG4DF$}PT`oX?{)Us4x!4m)_U zIw$QcKUcRj@*Y=`tdk`fX*ccDx=1Ae?XbLLIwCFF!|W+SGYX^*ZrwVz*R53u2t?Br zJ7P#LoisXt2MEz&`RsrN{e@kf*S`TEm4~iW{g|qMd>D53Oqdfn3u040^0NS z%|u%XzAQ*TZf!SH_K{M(2h^iGqlf%yQZ)m9Jzr5_1-_s1-ae4^_)}KWo#bL}A>^Bt znyd)3Ngjbf9&P@Av&)7sw9II1EQfSqcvHWc`Z+@{z|rdcLq%pUcSJ;8p`<);FqxM)Mgxfc~RrU(==+3jPeU^;Zg)ul1Rdn}{0IzZ6Z*k@5 z`jZff#Rh+}Zh(8!tL*2^^b4NF7o|O~^9zBC_TWkxTWh#~VKa>c7(e#^S@Vopxm27~ zmF%Qw1O2(LsjovJ)}@_f^G$rOL6&W@r8OztbVlPD$$*H&tDMGQn0q~Ig)-N^SPRoNthj96)o#oY8fP&TS1aNpveXG?J1*4 z`P7@Gz~ecokZiv>pI;~x-R%R&&0N0s`njY)pf|05Cg5&w@tFKwym^=4Ko21kYXyu- zj;9Npmy|SSr5FRw2!UynKK-r71}m}{-V~=8bA3dYSi70#Xr{Wx^w`I+6vXSbsdv(| z?agzA{aIW)seuh%wbEN~%ZTuZ^iFSbH)~aA?E$74T)Fd|Wlo07WG`YroVGL3+o`h* zFLCUD&a@teb5L-9!EfZit|~)|uFHO2-$8WB7q$fE<=161@wR1yV*_)Qf5h(cPwV@^ zwS{S0U6(dEsW5ygb6ebm1hh`cs<1l?<~LR>l`-OJ>pcP2TUf7`@UxHIFZYH~d;SXq zbW6xRQkhc#W?=ah#3r-0$>2v5|8$8M}G--S56{7&<kz;qm~sP;A;iQ)p(6Ivtpk7N{5brbS1v3({j2>0mf6#Rsl#cZ{^^@l=~iRy zq&g>Mbo0K-&?oNr#^>M9gMhU`7iw1K4$n991R5HU9UBhD>a21#K?ezU+heE`3Aw*i z&~@bc`ySr8BqJx%C?FlZ_pNw;ibSAhYe(n=+rtMZlV7FAhS5|$qevzAM}mlng1%;bb%fKIx{22Oc-s7GC7Ng_RSJ}~;qQ*AJ0@Dmejxs2Ba-s0YI3GOX{Iy1S7 z)7F6sk+aGzvZg?__D3^VGL-NAZ*4}rLXIiEUf7Lfk{6WjQaF{}FL~2{&8#0wUI*xQ zvKizJX*~bw!LJ+yL?GXfW*Um#hsm18+r1Z#TsR6w{e>@ zP46duK%{^5c zi_V9K&jEg7RO?L!%6HmC>Ppge@@K{ljNVDgB42nA)svZjSdw17yZv>YslX#1tBjgj zcM0PiO6vHwGv-=DPyg_WKCe%$SOTfC9YzFtqt#r5N}BFirZ@LA6EFJ^J)K8&Qo?e( z&DnrLU%q}TkX!+ zGXd>tya=*?HXFtD=d%h@tJ2j@I~qD9V9*(){odZahm)zCw(3JKKGI6?KkU~p8LIFH zJ##!Ay%SayLGxldWVp(^EnfYli?7ls4OrrEK*QQZO!FF(v*AOh z>w_(EPjo2tt|BP$PCu>6qV}j5uv4#plP$36gWcC#joujqjpwVz4oJfm zn`&j&nDQ9lIEALU;!e2T7m{VNk;ln2T;(j@SJ0BJg=M@gZmD82I4(Mv9{2iga9n~^ zsQK$AFv;_ylXNSw#>_RuR`g~1Mkk3hnP}XP9s7{GEVeIjkXp9QYRjLWs4B+O+M}1% zlJt9jI339`UlV~zWmnU;Wq9z+H1OyZ&8eclB7pUA z+JUP$JLy&A$@rr?%@y`Zd2x^{z=o%;nMY%P6C-7hBmM1y86hKRS-zgA%M(0rvi-Pw z4a6yBsL*vYOgEu_(0TA(_4BCh)d@c2Q<~fWoe?v`3`MIA*knKG z?CqCxpa!jVL)k+;T*!dpU06|IBJO?6m1mU{cu}_H5BKf^hGJ+k8S zDg8%OWyza{&%pT&&wvXu2cBDzKXNnn;uG(yjNMh8F8|7L*}*9J3SC*^aC`TT>BCV( zklLGLtKo_gKM&9*4H*C7MXMLAOq1O8V}+i|8>d;}CBfbWeZg1N2HS2VsOu^hx8&U*bsMPjXBv+L?p!B+9Ph z5bUh3=xQ+KqStuRW@^leAJ@!Xa(Ajm$kaW{y)LFP=MK!4qv1>gPb%z%+el&p0&nwq ztqvR?#aA}PS0KX}E)av2-OHNW=F#a^Jt)C>-g4p20V_3}-P~D!I~?ymUVS6W zYk5^s1=&U>bU%pV8ftxyioFc`;)o~CrgC>QlVn!D9kcsES@*tSDCsvKS)WS1?YD^5 z^cr{IoI54S-6V-76fdOGe!kovZ{|tH)brvw7vD9&#a({#^VwmM4Z`=Rm16kt+^*Zu zrngarJ&G#6mk)#5)||UU2^HRr8-I zuehE+7I%**vv^42yWKp@%~{RdX2D+VT`W1sjs4U!$9tb|m>^z%I;*0A*;7#g;pH?% z|0C)!Z`f(#WEAnLvPwB%PRj1pNHv7;yMMs!!&Q17idQ%PajpYKpH9w$RD@HLxAtSC zTST8DUsgP){&xCoilm0oadOxuHQ8*ZTfp=|C7W;^kJkJHY?SXF4R9>6J7Ef+Gx*dk z?0etb8%T&k$)&Y_pM8oDB9NydFw1WAd%8exMNSPQ=CK+j__Isdn&llb3T)>V0;6#k zg3V$u)9UAK@D;whmYgZ@CrPZy>OIpuYiju^N9wK8I26kIAMJu z%i`Zubtv8=2hGSMqq{iEScO0|}ihd}&M6{mX2ry&R!(^r>W!B-tv@#<46SSbV&aiAO1ZekF~r;D0cVov&fU!hpb z?QBca{5AQ3&fHMpT-*0nwR;&ssXj4lk#mCJPOis<`IpfJ4(*~i{9-Dtu8JF=Weo6) zx`;!6?gkAsPqp`D+!}ycnpW&8|!@ zC9CPNxV^%+W)84Lu2ux*1A5Fa7D=OfK7o;jda0oO8!3H9_~CiG7*b^`WGH zVEVW=`!^4AoZ(NxS;xt&MSu!pGoSjNw+|X|Tc{0y5wxnFggmm3t1CqZKg+Co1s<|D z)l|w6n+A{*eLjE1^4X8#!2=#8wnQKE5EGpwSz~-5v=Fv7p-S{bc%H-%I5T-Aq{&1l_IT5ODeq~2ede1TeH>do4e^&umM4e%bLnA@0?x;U zFM(lFHP_-)MbX6mkuz@r60t*;Z*-SVca>sVtY7qlH5b9}qb#FYG05r^J5=lrzPoAZ zVFo1eGqnz_79Fb1*J9L(H#_lg836nhaZ6!hRUa2x2EX|^ip+E_$9Fu_rv=+kp@+yL4hb})p{ zlUF?2weWjCkNp^ggXQnO21xNKgb_B&qy#LsB!z>IE)q@byI?n$`1PCi5D<=HAM zLYrv7*K0&INJeermxHx@ZTnt@g=A^HGdXYshQzaNUJ0)qA5&&^y}~J@v-3V zEyHU323pycIw{bX2h?yvWLiDl=e;eKZy)CM3)4c+D&6@lKJOd7WN`^$A(aK0aY|xa zO;0U}u%3O2V;S1-hOmmB*wb{Cc=2V8?_Tq0q*N`$Q%$<<2=m{*;?YN2iD`*#9#6^M zf^}sT6I%@J)=Q%fPsLw14V?PvFt7EO&3yJ??kA&?6n9t*a(t10rt>R&_f=9@vD&J5 z_R}na7FLyAdFxzjTLYwC_U#N&G&+gsI(CgTQr1oh`6&UuI$%+Db=$b%4BZdW3DrZ~ z=OHg|JGyl;Bz)d2D?9a*9qWpKZjCLqgX`K0`K)upC!Tpzh>zPqNNZ ztNwA-{tG5&?~{bV6NcCV(xJnpgXl{>KXB@d^MtCT#hlXSUdWlE@Ligfdm5?rOedBz z#ezM`o#%bII*&P4E55KQ-Bw8Kq~`)Sm?k`VnBgrGGhRxJ6B%kg)SKXAC0Mv#Q(pU3 z|LF{W#qE2n8^XL}wRd;>I8DEQ5p;O^v#n-Dv~SBg?RlHo5q**+mrIV4VDYhRJ7(bh zYP`n*)RUr}xeryZ-_LCMVD2xlI#yANUZ{nAgV~BdI38EoC+g6{-J?NC7;s6hgR8pF zd=I>c+@Dpq=L5{+=J9c-=!;nkU5s_=zEygEFbB^{m*Gb{V*n}IIC)9_aDESaP?${~mCC{jAP4lW5(mrz92?01HL zKI5%!4~g6+IaqsxANIVzr;mvL6X&2^TsBmiZWB*GvpM9D@J`b4VD`ZLau5jDyh{vy zWj{cZV;_lj4+Mq=;bOk9uqCh}+h~ix{`f(N@5qfqe8PEMy`l- zg2tb|>tV$ej3=HWj&_$EwKmh$q0RY!%4xkwX_Y{%oB9=dVZKD=Fq-8ZyrXiE(L|9x zRhYa$lQYO>t>6Wmama+@@r4dE8GE$6#HBn(O5Do(C{4M0av%M8!q8;nEGLQ@+a9y5 z@!!Z!86At-rJmcN;jft&Nv)X7G@9-=8XHEX8!OQzk`|G)$J^lPlOb4-`>7XyaM-x7 z7kzit+of6gfpa_NK?!tN0;v8w2XW8doov!!8F8w7|GJ1kscMv^?M{Mt^n(zlku`q2&+Kk-W@8K0c6Yf4ZVz#b zRk`dwt;~VD5Iy4~VtB={?hs9XzVGh*r8O+2m@EGPK(bkl*-*kD={L*uIm9J5kNy_U zoGVHtA;4#PWWJndeM5Licqd?gOd8ODqYhK`xuF^n$PTU8)R{ZR~ z{#h))c>*HjMRk!_&lPL_m<*`4TmDep+gri9UlW&r6uc|d;6gXl=gUlgX>OmT+q9Y? z_dTz6JK3O-Ecs}?c8_jRD46OtjNSQCb1oslnTs+^k7pR%cbA+P zzZn@2C3$tWRGz(ud+kc$Gxj`elqr>w<~E(66!zQIqpVP(M$w=$rcR0Eod?2gF~nj| zqo`h#1`2~mGQKBp8sO&DMv9OyuCAWS(YBMzb6|wGa1Ka+8CTHj<+Q$h^TnXb+Jqck z0~nhSS-aOd{PV0+G)r_ALA|w|9O03-tM_v!>U3{tEVW+Xqaywd#RE$_IK}W+!1t3N zxls!APy!vARlR#|0$U4ZZ*+`s(q?x5Q zv_@yML_f?iFnu1Af3&Q1cwJKNd_Dc@jSf><2`9Dul{t8AS zx!|(Sbya|d8*RgOy4|4atj$V#=yuYxSIMcam$J2!itA37T3e^xAJNaY1+z^U14=oy zLb2UH@M=3p>7edAWbt!*s4Bc^Agfik!)#!XAu$>I7*mbE3yJ2_B#QYz6kcuIm+|Qa z69OE!_f=k_w2@CI6`BJLf;&y=&dOX04fb zKRe#N-~H^phLhFML_paAZU3@$nG^xp@l05l#w!y!-$k2+|o~4E6*gyul8D zU*!VyL2lsRg$d$w0!*DDo_}ByxFgaBga89j02E>mhIyhKykHJs1ORn6z(h+IVBijh z{V~@4W55si>uCT$LEzuv{__462m<@<46?U}ySam4eh`=wz!3rk0}Rx41(Ci;egFvO z@XHVc^@O8;{6XFz2oz+8GWeZ12%xTP1OTDx`>Q%ndj!NC=_%+5f&Qvc=vNrjBdft2 zRN!uIU>MR9|5tvh5CqsB_3C~?zuW2xgZsb&{+t~lFbBt9B{+Dw3*Co7JiNeKs()Fa zApCzYComEqE-Wl8DGdaGJpf=|duO3v!A_Y?cYq_R1aJ_<5sdo5 z5AXzeg8@i{7dR;3e=Ghi;RAsH2Z%iqU(~<;=%x+u%s|R5_Jgr zcN9Z^5ah2cg#Yo?f;qwg(tnagz0!XY_WrB;Jbw)aFW}#?^x-JRf&o1L5Zp>wT-YA< z1^oY}`EQs18@qo+`F{}nzw=S|fb#kK(Hr62*NzIBEi5|84pJ z{AXPCzzz^ExBu2^Awj4aP=+}{|9(V>r#i%c7wljNLE1b2p~@fp{;vUpLSSG+xF_V- zLIDT>g@yl1hngyTSJcw*MDg*r3XB?>e_yEvvxhtUnl2G>2>=Lz0QupgT8xs!0RceN z7&?G`e=`^$BnX2eQ7!;fc|ib2I0FAyKcyuBLZDyJZ%G0O5CVI6p?dHiL|hagpo5Pt(=(f}dUV*6VL0#O$3|EPsg5^B4^pkPPjKPd1o^ba}y4lWK5@&tRM zmd)RY7z#m+!QV2<5$TKo|F48l7a)D$|AdwT2>F8%e}I3zmAw}NbtCdOmr)P-ANluM z0)u_Q_W1L&aC_M&E_F}Z&uf(#d;~UsN9CtDHy=FX6$qF|ba-77<7DvG1}QQKAEwQY*=#AX}*$8qYuvFBfv>wB5-7zIp~wgPWF z0?oo)FlMim%px56KogPkw_`$gKfXvX0oc=g4WI{#l2ogzQ$vd&A7o zyv&B?>L4V!Zv+23EpP2u(VmBB`FkHKt+9XLU&(*k53Xor$)eiM(_BYDWi|0+hIxEb z4228_uhMUIvlxE#k0h9!YjJzpEi<&0%ms&JGGGT9zQuIUpw_oHplW`9RjoWyc5?Fi zUaeW*=WaG$Q|FY@F&h;!5?_p`v^>V2{WAF9dGhjUuEfcHc0+rAmqu}0K{L05Eozuk zKcP)liremJ0apW?BEh0N<6W9vzr!k#4P=j_y7{p6I2l3@A_bqOdlokJEU$&D^Fn2U zm~U%DH_Y){<+;p^s-y&2#?E`ijs+XrJh{M8UG2@ ze1H?EL7Z_#H?)7ohdUTc-k{}Jm)73t+;IK%7w;75*Xlz#{+CpLoTQH{&dHvD18<@Y zGKHq>4#I2bqB=ibefeUBR~e>5w4Q3y(%cg%H67I^$E#QUE+Rhivm7pl+X_}fx$N-v z(-g*3lIkD>2cWfu$tdMEvzuYK#LRWuSQKH%au> z;1*h(9gBQ4491rW8DsmUB+muzN2qp9xG7?YjyCMQe8P>pcR?53S<Bpt?Hk}8N^Y-9ja7UG^l9ID-?=nNPTxa+6@%BTzN@G2#AAXUyAFs_ zoaV*aYgLqOSJI;xF4@1Qzfz^qX?~KV3L*IdC&Gjg5*falH)(%wV!o()$I|udX?&7X zzvTfkx2yYz;`MzSI>nU34}%kqBC*Z+L*FIOPGi_ZefRI9?R0mzwI+6)JaTzqKj_-P z;U&|IZCpWrIUf-VQQN-XO4>G4G)h_^x7WVjI3sBDkn8oc#Yo0v_%egEr^0ihi=pne z&Xm?o{2D2jPJcSBsl{EDOip;))OBTIwgF6v;fJvk`%_uf_NPM(`QxM_DLmSI;X_A( z^AlaT8o6m@J2U&aUny5zr5EaE!zquze#P`;H|0Wq1JZo_0(PQ4Ez%E?&m}Q}^5(uQ z0*J}>zxvOtm9#K6zxX*a^^*R+-;JsJ5wY@Zki?{Cd1}-)H7oYC zK@Na@7%~^nv0QJps(j>*;7IlnPcOG38FGh47e+sX0ll8PJ6IkJ?L%F=?yy3Q_cpwL zgvN<~#oPKukhkyHGIP*ln^}Il!cNn)xXC}$skuT}`J5EBr-pcO9@y4ps}tD}v|`Ga zY@ns=P-aZ$4MeI$I(9tc6qs9VdRuR-(7qmPgo!aqf>b&l>hFb7>q#Y_f!4KiDYx7kiiENl~@Q%a8u4pt~l zH8E#1#Ptio&(ZtxwKy0oi$6W&*NluMf6>{iwV)u9Jx|E{weY(23PqD09i4k%U5N`b?G;qX4iJd zMfG^(QW&OJiw<=zv|_BgX6>!dHo$d%Cx}=J?`aEuuvzJ3B$lEuz6Hk8{)1kP=hzqC zw~NpQis0RYzWL}{OL2s5RFDU*>7loqi^}X~rJY_6xr|f(+J0Ae)G1z%nZZ{|$mrH~ z+Cl{hb2WS5grD1)fY^ut|Iqhb0>=pTQ{M-d#0edh9d8ocJ)6y06C^wYlAh>)k#HYS z+!XaDEv&Es`}_EhT0MOS-)NbXWMbv?o^ z6)1L9jQ>9PEqf|ea81@BfOlri9rvCy4KANp)lQPveLRA@b(K39YciK^X)k2um^eKj zzh)J{f3ZF&Wu7y_=guW|>XJo&wL#Z-YGBh2eEq`I-8(@w!X`7BvZn`!B|dwR=-8Lz z*_(YnN9gf}Z)yr%(UxRajr=+t&_qIk;SfP}smBoI4-i{j5w^Z1$}AZ%&x%kfT^{wPlPVyPG767=dHMxYL(3;x8mm&yc-v=2le?5PS@p0*&V{#b{-0U8r+VHskC_` zH7`d_-}gH_Zfv;d==TVC><}IgJ?Om9tw$?0nVkCPd(dc~yGs_P6<5o=)}J?0rgA`U z-;bP`d6@A%?3|667 zF=wz5A+*a@QYoFxg7JRO%TA#e%J!{y$0^WWDtB3lG0Eyr1vFrPvxwd97hPkCpHywU z)2->6muEE-7bNJ+3qqjltX(ltzwmgxVUmS;m)rPKKA$*LrgIRfj&2(iW?&{jdq5XD zPkNKBo+AH!J&{TFu0=sx!jt8$!dOxbcs%$FUoCM?m0y`-4={H0Z2IEMJ_)Kd-Mw_{ zB=5VkiNkTVLZv@{$*>gGsE@@o(F<`t;&-F2tcT?9k#3o+u6qK}GW8UoMoWz^*n74}?Yv4VkN&JK9PQ)$qI6fUfqQ;+?0glqFM*nSx}dLiA9ND|>6&s1f&M86AmLIxKWKvAEpWeL-7;A@#m#d#Q zoA~QRRe$_{*|JXz++y^DXDg#ZU6(CBqYrHDZNP53 zk#f@=7-rea77eE~EzPI#);MZJ7q!GkDe#b9v%K4Xrp?fHF&UmH+###arq3U;;CRZt ztuJg|ecG+xqPU8$S1>@hPqfQj`@yzRAlsA+%T2|~+kK7cyh6OOCd+n~PK$`_R?tgX ze~9LNlGv*Wq|)`y3$N_rtw#@6rl|+oJ}BR=g&x65dOX&u-X*=#82W(jG9jH&B#NzF)l<;)q{4)DZrb-?HGSA_|RW>Z7@CH(G&r>1Gk(9r?{N2h#Q zt)Cq$T^WkSY*~x#9{l@DEb@%iX@YR<1d&TTaXS)J-@#%w7h@*+`Y|3A5*HSi) z_)^*F9Ee;WV6?|x*=!!zJUGL;uWTmy%GW4=7)-@}pr$?SC?t+NNqyPDZ*lI-Qcyf+@Jz1F>q#;R2{Ox-bN|h+1-8`}FdE zJL|w(+JX=JLB0TaNsAvr;pF|f4ZHc)_D@T{vd+2$S0pF~aZ!@mnLmHl>@f#XixZ{6 zr0`8~yBSToxU!I#DOEd`EUs7Cw%y zhfPGrfCiC~q)5<{cIy7{;)93e#IunW%|*vI7L4Ij6HXBh-FWwUr z+LBW*anWwV&#g$V$r&}pvMr4L9AnULQO zV284X20cDXt|VBy$!|fAzm9N!`4|)Fre9Cg_7 zhn9?~j>#LN`?GsbFO@7kXI;@k&cs}`+YXh4UYQtFjKLmiTd}zf&~F}p_y+)s>hCZl zq`&!jCwKEM=ACHmYn_An)Icnr&SF@nj|#wVmZ* zi}sdOSqAN)F_A;qkIuf!>jN#I&tA z=kL1ntxofaO-yjrN{DrT;fJm}f;Z7U6Z-iK30z8#&`Bpvvg4&sz$HT`4Nt$q%2W(7tPkxqT`cv}g^W=|qUsYgcJvzwdA;WH~ zm~?rnpc0!2ysI*pUB044o|lYEX@|T*M7dztXFl-gJVS;mT53UmSmZn$)}~4x`W&2+ zW;Zl^q5}4X^C?wqgg*)@orLkZ_O#&bP3hzijq_c5wtDjMT%oH~XAA)OBK6YtgKIfA zx#5*b!-4^Q#;HViCplHC>G((MJMVwlAfGqv>xyD1b-_+oml>{KN_M2j!n1V!7Vs$i z!O-n0I{1c+;YERKeH*Ae;Cn@yeCQ0iMCWhx)0f3SX7=OUl{y^t6^YO*sQ$77r` z1@Wu3pHcA=Oe>Wk$_v?A+Hu@T0RqaM$OFPEDjFB^j@NT6)dwV_F)w# z7E{C%anpgoxA%IiWw%Hg*9wVDqnT@4CxSZTmcrV<90lBeJx(rYWW_PC85G|ok}Z8F zvC=o)qcxNgpXDad=c{ytF}3(1$#c^3tq59s3|_oGW0K0e-P31$C6KLm{Hw$G0~csJWqP{m8~H(7%zWISnE94ZcY(2@itExZ2NB|vhc#((CVp?M z?CuX*V(vkI3_JTQ-Wf{xCpMWBPHJw4?LgvII-Uz3`@RZHHa+d3n_?dwSd5=H`oLJD zXbbStF8!?XqqJGV?eNhLapVLz>5{@KiGj88ZS7h6&*OGHqwrfQIs<4`bo6GA-E%F2 zff|bOCEky&U>8?mWl4JIH&V#}q1h({f<;zlbur=kpvx| zDDUYDWm&D|$$9z4C*AZIV2$#ixt>M5@cBK^r0&x(E^@_`@F4*tq29(#t{`^xvtmFO z)G?4~e?4pM9!DM;ul1c=a;%-V)t2?u9Xs;k3L91*Uc8PRK)+Xf%NVmFA~wkOO`ZMu zvQBP)weGFj-Fv%kFBw1i5EL)j^AFZK^B2gmJGS|9{^Vm`(G?df%<#L~eQS({o4}r! zd1T_*oEX73j&tl%!P(I_ur_-&x6_UA*euYl%?o>*T=%$^q$_NL_`@09CeE4WUgoQ? zN1w3COae1bxIt8`l9s2l7F?l%_q=ta!^HxBf=6n&)zWF88>gi!OBeT~2_>A~$HGiV zxPtbF)pc{k5x^kxoxCCoVHUVSYbwfF%*J;Fg{=hdiddopyjX= z*^yBzlV?yJHKnQ#oHW?I&yCooaWPc#vlQ~wwP;Q1>;>jneLzFFR-@lD+CVO3dmbm{CT-tjb za-i|*UMH+6>AjBLa7^B{0n=4{Hu(5|dg)Gn=u}wB*KRXKXSlJr-xI~9EbqdeW{aOn z+zkhO@7(;JiEk(|%ed!HQuQA0;(D~*f8;lUFS3eT^fQ=_OKGG*A1NCiU-7Bx}Qa$C**?8PHjoQmj z3)zf~-tCr|cmRE4hD-UkcY%(B(UuyIJFR`WSVl6)LR<@;wTi1zC`k2_ncU-~%&9C%cJ?5Cxa9h=DNc-W*Hd0eI@Q8Gs+7e30j^w}r3Fk8qr z>;<2>{!ygasP67NQ!T}Z16#RtUak@>eTY@3@>WoK6dpCwL;iwvTTi}!=BMJN*S1)& zvn0qxaA6rv0i$Ct@LSS8h^?8?(W!WFhD@KM%kMrN61u)sI zC7f)*>Y4JU`c~72n-*CD>DE-Z4eV}g#aG1Cb3?Gc=Ke^t@0k6_BK_s#Oy)EwMgsUdLKl%<1DRykWY*)y=hJ|Fi zB@PD1>|0IwTT{};min!K)C|gM8sGn!8>AW5cs)I|R?jyYey>u8A&H4*I*+yKnQCqs z^FzCWwJyWJVLxdV^pO#6DHMVlg?n(xE? zn%Ql_gkbT}&(}q{B8#qxge|YKZ^v{UphT=u-f~3B&ZKdwA*~|^wMK;rjXLqHn6#El z5+5(uHlV!H#kO_?6LtU9x!|;G zf{;?Qbn`QF`MHu;Ek??LG^KVD}&b>6#% zO+ji}%7q(SnQ?SY%pzauzybyJ`31NRJcFy9k0r#C^?j65{QNgR2`|nGAgJvah=lg` z^p@gplJGKVu683Pardn)P$U271H_6z4`EUM&4Q4BxyOAw@7g_u;^0_0J>#IYsR?8k zkJZuMl2#GmO7qmSP=Yc|yii_9eJUI;1gB`!h(;vPDJB1?qpI5(BggKRN}#$rTw6t6 z!^Q9FCHDP?(&(!YA(M6!KVu* zcyY0RKwVo^QpiuSjj1?ey(+tN-df^Lv|;8j+T38fl{fu%^G~0|TJ`mqo2H!IQ;4!v zTYJ@^FS+$<=doHLFtis}g;`PfgKeT_X@V?fbfg#S%aV_{%rXecxx#%cIhF4Y=1-U^ zu+BQ(h)oX;gHBEqu@0+>*jw54eC|!o&~Qb6@ub+~S4umu-ATMz4RHkXcT@*B(sb9Z$SMz3Ek0&u~U0)#2|jd*i_KZ7e3EH6|s*8 z_Vb&bIdyx1Rq|ZsVY<_kVFPG3E&eui)c|o*AVaVh^8UyPP(`M?{FE+5ccbfjqMh7- zU>cgw!Q->9Pxt1|9wwz3R~jj`@hdW0+DboCZiPAs4lAvBjWrb=T77h*Xaov#(k55( zGUnhP`7M91oSp8AV*WPV_9&5g^|7(Hrv8c*KaN*q26N>@c>{r{CiqgPz8$mYmWTdJ zVf*ZfidDx`7+nbi+Zpo**@F^U@Jbqg$gi*vZx2u1Dxm1=LWL+P0&s{ZJq*-gz&rA0 zrsbg8+zbkqO(|F~q!ob0CfQ#cM~Lwg?xpnV=A5&J9?*R9^{2YrE;SA-4KQ#X!;x16 zvg5-VrG0M;YtN>b?LW>Hug6~Yr7VtU*P|syx-tA@4v1!WJtS_vB-4yZYnvK>nK3#F z?Xu~EQ+{kxq>AYX@*MV%CX{rSrLAIC6V)J^OYgn6rx_RBx5BedC*nlli%3GpvT z3&5$|zj$p6!pDe7S7GjPrnic1_4E!>kli@MP|SXFOD2#h8G|Ml-fCieq>kPpB=DlW zyxu}v(~y|DzLaEjz$Vw58y>Jw50?2B_0yO42kYV+E$5|obLMpyc^}q9P0Pqv(aJ_hkpOAIMY3%1Ap@D#x9;3 zT1%cS_}Jb{Oq~9k*$7iXKxErDjmA++78cSw+2Q`=R%k1e*7iY7gtT{uAK{uK;zf?^ z@EHrP{oq&F{7*7;eVGq`w$K#Bj)}8(3XCHkmx*OX*aaIbYwOCB3_x|V81ty8@4g~#P2t%6? z?0XD$nrTcr%>+wDWQn9rNzH6rK)G_!K`r^WO*u^GRL6V%-EN%Kd28b_&RQAJU4>Dt z=>5{g_sxE4W=XGqELDA9g)m(k!u)8xC(XKwZnLW&NcZQRemf{BUVqw`0gALsKucVu zHSV0wsVRyI-+pi~J_=k?I!eJd4~_v3^^Cvg+wv%WOF(d}1z2Wf5|dp^1p5J9z24Vv zmUb`9KK|Icko$#b!{Ux=(2zz;r|R;PWj1zm;C1x2N@Zq$f^kgv+z<;uHq9iNgUr;? z!RCh?xsSI*vrGeD@2i${zkQ_vnhab_fsfn%m4Wl&_b?h?k=owV}q#zd7^}K&ULAS5<15@+WrTUjZ&)$Wo~41 zbaG{v`RN7=0x&n1-}nU;5IHppFHB`_XLM*XAUH5LIhVm*0~7)|Fqh#311^8mZ4)*w z-Q7|P2rj*JcXxwyF0jNdEK8T9Gy($BAt6XNf{1h@-7QEf0!s6t&+|TS{Qu{C-{G9) zzUG>ld*+^Ne#{KodYm$LFdMKU42t07;R1;QcsV%O8u4J0w?=>JlqY?Q&9(K zxq+d7IjjHWzybLCX#hN2JpZKoJNkDb2=q^|wXH48)y*2}3xPTS>>(~-fR>^<7s3a@ z0kDSJ{dTl=@qj(VTYG<5LtLzF9vuD@ZVgbB(E(UL^!Imn9=33Z8^VLj1LE?#L+;;c z9v)c%Y9|MCbp=Ba9@xL@lZU{;whyoF%l&7p&QO>))c>!uJp^iJ|GNb{Pd9D@D8$_p ztRnxn$Aby`-!=y@0w4eafrLbO0bq9k*vHn9`*(7EUpMd{lIMT7`Jw(me>a#L!2Y2H za3I7U{O}Lk-^1Dq3_!p=!GZq&N&Gj$=HUU@L2MBK8?XZeiv92G4`#6aU-)72aEK4U z6!aiG9sua~-#;hw2W{EGpf0}ucK6BcNTwbYslYKfc_n;0=0($ME)xF;g$YXu-D(y2mZYntbqT{r3rgbEEoX% zx4_Ln0wCLmAD;hbng0p-|5NwxEdLjQ|8G5to-QtbSm1B^|HE3lLR@_R<{$LxiFnYy z2JB%2p#SS?1paGXHNbWdPuKrtRS?z>J0JsfaQWvEAs&B<5FfCeHUweo_?J}vvK#zf zFc%0EtPS&k{QjT-IC(&z|KT3C%GUYeqv7$O$3GPKVQK#RN(HDb%X%a1%)9VLI4l#1p@40aO~gn6a;YVK^$DIe_Q_;M1%m` z|AB-7+%|vzAf5;LafAPXg1?cw=flMQ?Z6A*w*NPLkU2N(AILBAfS}<2p!osZ@c)1h z#UTE`|7y|J6Aph^@IMlK=>K2%&({PD_5s^sFU-Ph#loHH!rL!uWT?G4x5p%=n755y zvvT?`z(06i;bWw-R%eHmFbj;*8RY^ih>L-`!IfU%Qax!n;Swr@ps*X(V!X zTW6OPV$DYa$Iq?T|-Ewbu1%UBXbEuS-(cDKV` zcBTEN;U{~ibectx$@+W1j1WUgEnaT4_vnAhGto|5zJk0WRqt=3MMp`mRn*9xHm>cd zjBY4yRURL5IeWxpO2n^dmgGz7sp8{ zjxGuwT&m_!xJN&dL@7FvwRkgOkN;Ghw zbEw==!Wv+DIbL@Eq*)(If+uVZhXKXc%aP8kIn6clSBL$BxO{SxF|T3_(ms&Tpv!v? zUw+?9;eOejIuVmx@kR*6^OYX&{h5DP+satTA#PCAjxXZpu$mp?(6&8;NzQnL6xV)J ze}D1u$hp32W1;M=%Z~C{cK)z}foZsjVrX5NmCl(jtJUfR#qx!N9hgc{CA}DKz}cr7 zbWa`YbMA1&AF1~2xDqeX|IE)ZB~9VvG^8YHMFk z@to1bexrB%O!@~KWU7bb&PQb_n@x+GF|8A)85_YP_QWN0VC0?|uNRO|FnjIBR3OV< z7&y21yzTme>}g+ZU5T!qMSg!V`IPo>V}|t$#q+%y3}8o4P90^#Pkbi)*3Po<@D8v$>S>NSjycAXThB?FaO2*uhWOM84)?Ghc{CrcmL-?yVQxQ%Q zk~BQE!LL+YMXngEu1$Yf3JeN}$n=b}b%tSJqV0h?thtZ7xFDqxNx*GwmXzor*U8Qs zz@DaEUx9fV*~bfmWP$2;=498^TYfx$9|S z(j=8bpswqtbM&MAjpIdC2=$PY*!F?#nK>A^+&CIRwOxgEjZA2>LKR`%hRH5JQm%2k zU?Ik`2=#O@Tz|Xr<^n~+Baf}RNYJbGYxnF9 zDd%05I*Gld+L>C@(eeCkf+`o1OMHCbahEUSqH9$rgC)~qsgKR%FE;^A(>pd@Uyt-x zPYy(FxR2_k0md0JLuyy3B>whq7uJGa3sp_g|H8V&+>n3FX8lwKoJShLr6kqq#ft8< z5TtEYk{xeim7}!J?sJLmbZC+I{ATY_+--eNa7FQZ?0z>U5{3MTgM_B{iD@uq2;?sH zgT62gW|tQSGmF3AJfjMuwx^_l3+`kIG%N61?q1$z|5o{%eT+HJeau}aw1Q>dTmoea zi_qMxmr{Sv8RLazYP%zm65={m)$WKLEgNc#rkCA!M!S}QMrHeuOr(~_{CQ{|iI%G! zIqw)Nxc3KbIJPF1$;;8VcKtGQ54LwY3`4sd-ncYgP%Q~twxTJ$b#fZ_kyF&K=y_wr z*v{iclf#mpVn`t!C@cKRsI;{3{U9PAO~fA4!Qp=f{nzRihQ}P%iW;peZ6Z#fkLh_o z1DA=M!-`DaD&QWBXgDw`PHo^b-xzxvJU<=ae;6!q|9))k6 zlF_f4&|M)qQj0QXSRc_r7W8Q9`OLa3iUj$z)7DbNhT zrNDom6{10&E_9P5!uw$aC;7;O@nP^0j;6o*f+%~9WcO|HDLYE{XjN`u@J|fZ z1IHi3;-xEy#rYuQVkaJ4o!lx;zQBysH}uQ;*ra-%oaU6MY~P8k{5cwffrd?=+rH-0 zua$5tdNq9P4yR{epPn@_FF6AqF+PL7fOLN`SBJeSHSRyvl#usr<+DVwv%pIRQREj`Rjf)4kLsv6nW;OgUt=9ZDWla11)n3##LPx-+@b zsnpVGkNv2alK&PW@~+~UBkbLW%*W&W+EaCY(OW2xBqA{gF}1v1>)HYEc>HT7Cq49o6s#an;rm={+XUF%eJ`C5Jyq*BZ0 z>9dq3Q}(y=3HeHx=yQKsgKgW(u{~crq8NPh>a3(?P1OX)BFkm9d**6atHJ2 zL;SoCQNz9*p}7YRr4?(Q?_8GNt=Hcn<CWnkRfj=hvHtqlxXD&5! z6I>n#-u6z<0J^eCn)X~MiR?Di9DlOqvJp~1TZljotn8>H)%$+|R4AGmRSo(qAB?YS z6XAnpWdjXvWcwaflUk3}tVDD`n+}s@t;-{g!WSZANY)G6pDr1@TeE`UN@0jxRz;UO z`hQi7cNUQ)!dB<0`gKt03j^v^HnnKBXek}mIwy~Z5%VkeH%Y+o$2q^ zs)IQId)j<XnpJ!XGw<&n)+y<3pWQj)g-7yidu z5o<#I515J4v#dq$y6K4X89E3p?VgHY&D04|TH~1o3*9qGh$=*X6Mn%^S$i+p@7}5$ z=IK#27yOh@tgHX%Wm58RuI`Q|0tkI6iA}&*j*mNp{aB0O{=F5kOnNMg$j4^zn*!e1 zWM-BYP&I#HrRA&+F^Hj*8s6_{ZEM2`IXyt~ZqO4MZ!*sWN-;HmKs#U>t@wWNNN98^ zl0<&Sk%NON`!P~l%SOfE+~G5cr5}{iakeRO^i>gKI4S&6?vh_(84kCFvYyK6j^oye zM!M0N0Z-vdhP5iFLyeAnqhY1h1U#vhVGEQ67ubILXr=N+y4D9Ya~Eq+s!wBV zGZKFn$jF=3UTdjqytm1R{k!YuC3A><+R?9IjGb7__O)jLiJnd&2>^ky*KE!HDd{H& zpXLDq8?xC?lP<_9EQYhi0ES+jlD)VSzq(U$Ne0#oAJgnNt1AL5Tb*~bW=zuf)};#iOhVG>f&Z8@44a-U^lL}2 z1jnl<{Ahj$+xX7mHqPH^yriO3^%eX;YtJkl^cYw5S3W9qOs9<6uh88zyf#k9q0u8h zwi3xEOkb=o@<7Ij#dEvAuodqedOI&AKM^v0W?p^yGjkhj`y+Ygy==dd6nUL6V*`I< z@LR;Bh{A;)CF=n3WUuTOA5oa~#(sqTE@pMCJWIMIwfG$nPw4zUOEXRV>3ilWOP=eG z`Y0P!f+8rsZi+E2KYAqB3BQ}IJ(cr82~yW=W1Z~%X1Ifvxcch6{u`YZXoc~*rXcey zdWuR0V3yij_MISjpvOD&ZgkK0+)sa#kuN1Ises+u_?rqNBbI4&nL&p)zf#xSi!|Wa z#zt=ad^P1cKeC;;(FasWgPR3fq`(c>(fu0Vhk~=!8@FPldfEEy`-?PwkUj3T~cI4G z^G0YZj}=Vmb!jQQQHaH+S&JyH^c9WQLdL>Afjl{IDAc1c^wU>|6Alx8(RMSq2)dz+ z1210csrNmT72qgVyX3ZyU0+7DR*C0tfzvid=QC`&|Pp|?OBM9ec8|m*3Eyg2H{)r+N;+$ zdj#4ocAtA3cL-G@X+DG|0wCK26siM@(#9}V>KAWu094xx=y?7Nkx^aUC8@w-?U6^?l;9FZx*4>I!i&Ehe8|QydaM(EW;Hdq)vmH&D z^C{!g(vh8x2kuV0a}@1igry#Pm~Sjna!pCZiKPEL^>=#tVp26elwM96Ka!_%5igIT zIFf7_Xv*-F?TyuCCW3C=!@kZ^fR2{9>@yR1q358sX)`J^W-eP>M*E$ zATFgK*D*}auKAu3vmIwrcSCF&!@D^1(tt3sXhv)dQ#LOBBfg@|iQ-IkYLf6-Fa;{~ zSzcqh3T-l~j5@#~?mUUDD>N${#Qa0&1eMiszv(`6GeZEl+dc|s=vA;y*<->qUunNb_G@U_~I|?Zaie}M3vfTe`hSa2tP=OISN1j z0qLL|J{72Q(~CoY_erk4F5g`gI}}Ak#0PAPZmv7!?w2OP@2nf3-WH>y(u3%qx>6xy?coW>L4Y zOQnD7Hz8q96up=~sL3e@I%(m-1jw(Y^Et_~% zEw^4B@<11|gvN+S;4@m&C0)LaD;ZvP%`m$I#!atBih@`Q=gFquxCjcyrc5+7L*=Py zx4OR4J5rLxy$PTv{;u{_QeZNcO8}_0aYcVNCCQEv8OF}v<~t+(mTVO*C*iZ~%(1C4 zeM|eRbF2zlPOBTDxYX!ZNhhO848^6K0cGd9h8l1|EW0N}PVv9qc~^lS=e@6tKLRpy zS#kaRfrsc!!M37283>Nb-Tm2+2<6#!1Q0;|CYHduIqT1vpqH*+NLRILkna{EDZPKY zytO>pH2W{`ogeww#^hw&8@`$TBvPT=->J$o1Ws zgS7;-W5oYrOkcN;+)ri|3p34D8${*J_|8rt^;aYTnXsS~lQ`)xr=QaORF%Xa)qzXO21$AW;n3*-dfi8;^p`=B=7RPdzym8?A6piEscJJu#QZ{=x}F(Tod~sTXr7hgqd$li&e{D|5?` zd{yhMSqd`pebGhizSbJSKbnIyC904msy*h(hgS-J=;a@N>ze%Py7qI9IN|x~CBb0a zua#y#KM?Mlg1tt8h%Y>Qcn8)&Gexx>Gz5Ito8*$2`A2!fEKXT3Q2Kv{W4wY&?yw|9 z#1qEqk69Oe6scR9<;s5?(Z0OBWE=dU?Ku|cCFpDlEVmzPR(vU>2zu8!X!kxW>3So|v_7Hovj3^m`V zu52R;9J6+K@Zcl_McxgumpHnZ5^UwYU_`!M5zU1CLoLnwM*@Eyg}nBc=NhRNUy)nR z(kU}4841~TA|tBjKG#T@9@i0mDSldgx;-t`OwAr~ura^W*q(dxEfzGMxGzXr~9)V~~ zPdA4L0Ay<2tO0-0Vir%4`FJ#*_K0IPH#4=iYc>z+#c)ReWI&t08!6pg`5GS*1Xn4Y z=gTKlhspK@GAPm=M3Sx)eJ0upYw`O2HInIaR^H)+Sjp!klVzc!uhjdc<_bh*mZ9TC zwrGV`JJb8(0+K_JkKF6EpXMbTFSjy{W9g!ouGs@Hj@CxNroCo=KsOU2S=xbvT&GtR zHf`~e5sz$nmxGFi$1Qz7q4UXX;i#-v!!7wf=`u6UH>&vGMeDYAmbbLsnMLI;e#gyz ztw=eKHRv-Rf%hmgR@m|Et!hc)?4hhYiebDuLOt#0bJy48_xZk%72JK7G)SV*`?X_@ z%XC{wJ!Nd#h2#r=PaeZ=J|^?H0L-DKUolyFHXcyfTxgvF>+Gr;LIqGAWu?q+<6;w@ z+tuw=TDm}Vab3vTaxNTfTivGd$am1a2T2?Mqw}@%o|%K9haTUT+siv57*ST-N_a&C z*TyD;OEgQEj$^xWE8l@ZSuo2iyaTuDl>7d@htJ@f$eqf6!EAOBZH>My9J^#Kn4f=@ zS1X0R0LC7W=lM20<)izWAV18E!a%wzzbE(?WT|w`c;}x8^?zoqCQrHJNR0~WCbb5+6>4gHD%M+yLd-#pNQMG*# z7crwgQEiKVJEJ=%%$R`Ocdd%{?3)xsqLi`zEtj2wb|%r^n{9kpG9vLYz^~ea+hBP=_l2Kj-9^c z#`Ubfcaylq7TnE#y#);xuQ>re4c(}u*i%nQ5l8XYLm%GiBlX(n3H#QTdu!kIh1Mwl zCM9A~NIRpgUna{)p@o3Ui&)z1-jQf-*}{LOSIgf1cOPC{Fi8& zm7rgL&jcI=$f{jjeJWYtLWLxT?;7HyoXNH2&kAl&L9*?SLOr6*n1*|^%u-93Z%4=o z+V7vijkR32Ct{HuFLBUDj&rHqNwbR+y$w=`^gt#;=aDEM3iG_P3SXbCHd30pl=9*S zJ)S}3&Qf&<%;1T;dkuc9>GkH->4jr+8Kne&0mTa2h{tysxR)eL*#M2c{WCkpj?Sjo z;2^b7*`e>_SkPxPGIQ)Dk{$^|4zItI0zWP;d)B<=ldRTE)f&L=jdkEMZzf>_?e>oIxW9u zLK&nzbB`V4RcnD4zlt4v+3k4e9We*<%NGy>SSXi_t_fw88Kz%&Qz`i=Iw^(Jfkra)pEb1imHi| zM^VyV`zC%4iY*5HoJyV)TNW-5KXGj3@0xb$c>ee++z*-lRW6G1ZSM6;cBNBcx*vv} zx{ScmoAt`Bpp`4Sqd#zap`P>21YNTAT*?G2-V(M*K~|eYEDY zy>dyQGXb`M8j~=W-Dw+(N}T={_!iRPNRrJg8aZ$UH;Q2kNk)HtLEdhEMAb2zU-F7i zEbGx6V(1M*&M#Yi+cf+5!Tx10 zM!R%$cWe??xnp0cN0YsioW|@H-x`b>V)dfq#xKgw^UVYpFW-is1}jQdCDsn0{vU4` zlNFco=>`)4FqhGc1r-rEF*OP=Ol59obZ9alF)%SRm%v>E76dUfFg2IakOL@xxCKy~ z-4-rPDPG*2Kyi0>cXzh{fk2SpE-g}=LUAkZ?pCxoltO_PDDJLBFa7kK^ZzsVPG*v< zXZhOC+HWQ_lsG-#7}5 zF3{Bt1aT7l4+|+*pat|9leU0=J{zh)oB)dMU;qaffP+_%gHMp19l*)XF7US@#8nU= zZQ%j32B@$C6d_JPHxwEvh_kmV$kq<}oagVa0D3D10Ed78AM+pX00~E+E6B>i37}#D zwF5dnXSA{a1GFGkARyHHze3Op+d-kuf^2M_o}R20j&7_FS6fjAW`HMu2xY~kb$a3fWSb2nyfM_ z)CiQ8 zw%=i%$1LMyEd_CO1Uf<8P=41Z4RQrqJh^s=&J`<+1B+Zp(Ohw=~jxd(q=XNWVv z=D7`^Kgb67{DI=@X5j$@KwaH|{=WaI_-_e?g9Bg&Kv z1$hCC*q`ag0bu|A`sbU;GsCPQPGIkU&Hp%JHhBdtRb5G@zgqrBDJco@0{F6U3IJFH zc-a9Q92~p=K0Y3Qfd7BTQMUm7RmXq$Dmd9d00MuO`#h(=OZNDS1N46_2m|21W2r)( znF|Ea|4VdZb{=-C=Qoc3XS)C4^8d&3-%;s-|B?7P0BjonN?ZUot$!tM0Gsx|5{Cr0LV9y;nyF#3w-Q6w!GaWbIp9+ZU@1Pd{(ckmj zT!A)Vpx6I+2t1G8-RbWN{)-J(?yj!S4gRsV&s6za{^K470=!Y<+g1oun%wq6kTCbrjS5mB(l5qVc!{lP*Sf#M+}THW3gS0Qr)!`bS58Q-+^MU zB|D;tetEAO#iorcEq%@$9QeR>mao)T&0F~vhX~h4kurNUafk>nAycv04Te^d=Sr$H zIi8BB(D5zp@=J5R<-3{u!S;k9F84-TRjJ@tY5`+S?)4C!Ig#w%WFuJ2DOGmzqvYXfE2#inS)fKV>ettrAA z^O*Dm4o;I~5itMI&ySM4>R@u`Q5(I*d*NgN4lxamy249UO8Zs!(bvqZmmdc}<@yv! zP8T~ZpF2i+!%ra8M`UaBn!!ZJaX2a^t6Hq!9m^F7X%R{0 z4`L7aK6Ua!TH_!Nvv&QJM(;0p(|AkQ6E;pHQ>C0PLp$?gRXRl|cRZ+RKmLAyN7CR+ z@Co1Ca*pJqPM{f1Nq}*VP0U^F<@QD6agM%3eS{%6@_qN0z;&~aV`QC%gR!KkJyQpL zopj0DUh<8%S8yjdmLqb4LsVgf;PR$8o;InaLA*#Eqd^Phj*Au~*WNLkri)*w97fkd z+#A8praO(Q$If?UE|Ss!Yz(@8`8NVw>y;`&v;w|xs1dq>(rB0b*k~40jUk+KPOLC? zHccoSU@@gd{QP|*>US+sSoODZ&L>xWq)Rw$wWMr{Lq1m5FAGCt`R_c`xqkd)(^upD z>@5N5u00Ca-!{>6A(0MIX+?-I;9e;{f7^nUZxA;-manfabE5pfxo*aP+4`!owG<+s z?2E!d;Pr(FcX*GkyThHxuN{JRb9JkyN0X!f@@Q@1pG3&>zv;Uu7U)y;0rWSUQeQ=w{lIW zo^nxldFl~Os%-=}R2NeJ;k!p$_CcapZ~c1;q4$}!BBMVeDn|igAcSubkr5RSeVc?WysSKtzV>v9-L;svUSJfVPZQzdRqN}wLKjN3^+GA)p4&l9gy8V8TzpOkkXZ5q%)F!yk$JaFu;l>z zHH{IS56R`F(IO?n!S!wP#Qe^TF{C}j^c!_EZS>~(nF$s@I5}>k*{zi}EbJ3o{Mwo+ zLpr7QW`B@>1=>06YQ@pQRQ)P`aHkeko>1IQ^1Zt$j8-Iy1kYI-ucQdp_k0hh?`hiW zNR?@EwUZrGZ>FzHaZK0{##sXWeIup^hsASdQkdS6ri0L5Jd|2lOgK9Ye_wBy`8n%b zhNfB?0&{FfiFlDEEaKmGs zT)+X<8!HySQ9jYzS%_GA_}e-l$)4ztBXdgdL^I5!VkyJYM@~wNiYCMlxK!v#xl@}m z&Kom-TBxbML%r49D)`j-m0`FuR_68mPN6kjMc-yO2}^4e>SsB_iA-|DLXis-uu`;u$l9uxVn z{ittR@cE+LXBg(!8Y%sPe2|+3DO;Hz&r^8}6A^D9w2Lm5cNgRkO zW~%Qvgqodf{xP_ryiZpQ)QycD>2to#KRDpmT_|e(Wbdt=9uwTxsOvbi^5^}_zjaKN6lQ_DQcfW23T78Si|roSMYU{I*SwJqT{TSPI$_oa|Hp& za=^iMgC3p37aYwf!}I!sb@*w20VFoX*F>sJl=|_dEV7R+Jfp#RQrO z4ekLeRgrmod#PEKMl*;ska)wn=V~C9d;}5EEfJQ-n^iwF?j`A$@hXOY(=F0`?Yu*n zqAP0-rJQ_+^764L`=!A0d?XSlb{~Q=xhk?%3YW;{xP6OKJ&j!&pRgH1#k$sc{Q~0r zUM{GDH+z5AM^?C**O3E8Nv{jYLZx5Jd<{u-cCMCXEHAmNT~75lc2%3Po^axGdR2h+ z<)w{4C}TCrfxh5n*S6??P)E8TPpqIT?jN7+no5I8 z9*l}k1l@$Qezb7*Ql8>2>xAF>Wx%AoM)<{}8@6vVtrNB9q8{vje|`VOPvj{&{rUGy zFOQm^dLP1$Te`q$F?p>2#%2;D3K^5FvqTVc4f7`vKl^e{9xSQh5WbAdS=7YilDRw`0YAgUcPQ8&7JP%dy|&e8eoNHHAJAYN0u zmJ$*_( z$abc?o;yo2ZD%9nK%%4^d$rT0Zt`RlgJPv;d78TsF^W9AAb#qIqe|U|@GEk~IrE&> zKo0N4dIvmdu4_TDQNq$E5A&a>9gVejF$5RgfnL{g)K58oBw>YnldS%EtrM@t-Zz&J z{Fv;L9Z!32Ra2Xu5F$cY`N@Wo-~|QaXlEHK0^7DHLVu(te;d8{!os_BA2h3$PVqif zS_Q`s*-IZq^(j9)CIe4L#3#V`=z337Uv#D9cW$!yzd8`iCcq1O-(;$~qglL1+$${U z9AGUPJcfmTsx}n%M}Rr&Fk2iX6imVy2vlw`0-Ln*x1J1A7MvQ1Lt+pR(&A=mOBhXK z$%Yc>?ybaOFxCj~X`6@rgjXg83O-zSkxvsJ)?h#FEtE06w?eNBY7)*1@TPM-a1&0` z*$ozOrZnq~C>ig6u{UYJb~@+M7gfyj5nGTx3=&bj zdGn&v(g}?$#@B_w(tuu+YJs0|=UvzExI>9I*9~MX>IUWqAm}_&e!UkhPTF&=^~R(i z2(^a_(>b4y*H1o>Gf!e`=+Jt+*8V~No%BCgn zwi>g4T?$SwMf_~^{EjQ@>Vq={Sfe^ONnciyKwfq}@@7MI})#fydzGWns#grWyM|Zt{ zCS{z`=F9+B$#8}6m}y3lj+M_)J4@esn^D;KN=2m&rLjH?&1KMowyApLT54sJOBJR` z+0d=tQ(N8LHv!+RqiwS0Mm_r-6H8WQX`arz54EzFIydT6?Mf4G-!heVd@<+(^5KZF zm(wR-A%Uz(NYa%XglruU1wLWZ8z``U#7Be8t1gd(%xCeow|0z+smhtjFF`#bAzUmEiugB}sqp%1Lhxad6p6@@#rimLtm>-@LSi|T+655+ z)>qAL_y;eqbWAp?LK8)%^`jntUp*x9H1tFTxdy2~MZHC;-!iTTTS~p`3NS_Mgbt8M zxYp)@>6&f^ijwcoUl?Cp&*u!2DhI>vhvum#(ego|7_e9Fay~*zw%m*7(=p^i&F&0T zyY)i1KeUoldObQvPwp?J0_w%O6+_$E5@o4)by#cIMYj=PFPMHPY0QLwu@g~^%#=@y z><6E^?JggNdO;LTR=<@|j(Ohmsx7hlzsnAS?vDoYV4dXau8o$~GgV*}Hdj>k+>`M| z)$6#0q*u+A4tj5Ij`SxXYUe~t@!ZR~+OFv!^kedjQOAXUh^Fg+tB*RyGqPl^Alx7{x?>k^}7VX%Y#THKV zYVZ^@yZu`%UZFLy2hlqN*tZA{6GApjrE zzoJm2QunNwhxoGy;Ayb+7jCN51B0@~=06P$?|rFhd_j(RV7KwoB&x{rq#OBRw|%eN zY>!iT`er<3kO>a+07}|hR%0}oSsOv5nDyo&}cYMl2#2z@(iOx((5 zxjx-@rlKolQCm?E*;$PYfz?{12Z@S=uhBuWzwdL8Dy)EkVqbhFL zx;ToTL&+H$Ho}`xj!dKdrIpBk)ewn3h1+D%+lqUd*c9oejrJPt1qSR# zbIAVMB{#*8;PR+I9$Hh&@c2?q+Qj+70~N*Rc2m1$`F50jVF}mr^;O0TqYNMK$;4S| zI3P#GcZXS?57wFz2j=txZ^V7$Mc}>lM7vKSHbid|s<*wxw+5bCbyjbY{`gCwPhMz$ z$jUe6MA%!>lCKm@N$VBYb^h#wxM z=y$F=_J$aOzK)NkvsLd28D`U1e4EwcT5HtiZaFbEOL`kHygu*jBT+P8Ftv5HHU7N7kbL52ssiPHMEk*g5tCSAcjTVjn~gA{fl&ptS%RRvaZCV^!R|sIcw(^=o{8nLR}2 zb)YWi7c3DK0tgNRE=#bY)sXJb0>LlDIt!fBEuzC55#K&1QDJmz=(XjBsy$pzCvY>W z`P{X!TD6?pTfHwgpuJ!DF+V?v6L+vDvd@S8-heQz;p*n|$sV%=kJE_4ifmLeTc+6k zSXA07nu&!QYlAA=E%G+AiWTsGF4lTxdg|gXuF3(JpsLWW-r1GAGIh)av zn*k@f4YLkp6?geg6t#VocVH>LWxFawWHDzybKv!5LOOj?+e`)#Ub7z~><+dsnYHav zU7-AcI<~4bkwKO6jz)PyPR1er2|l4Ddbg?1z%7Fjom5HXFXiO80rRs=(}(n#sQ)bK>5 zN5mMq_u;x?5!=XxPe?-rP!ud(WN$l*WIeLqi($>^#oolKpwN9?Hmtu;xdd?K9nll% z;^MvSB!2!4d4t}YRV{`5(Pv)psR=Xf&;q33S*a}O<8>)mv7vIVY zH_wzm47J1G9?{r;2q+qQg{(X>Jporkrt;+(qY5_k3#oZs5|mCVt7^*&R8mk33a#+)V!;zSwQ7qNds z`QRZQw}>y{g=^X1KFI483La&sZz*^a$rp`0vnRF(h)Cou%&yKz_@vdh0;tVQF!hc^ z>>f}E->zp@kF8xocSm)U57C*_YmwLg#99@O1q1YP8&WSlg;6XKiY#ln-&h-AMqxLE z^E^*_S<$M0Aq7pXsIZVzHs}3#1CLh}m(NEvNv+lZ5>N_mI$P=#oP-;g+UFDP#pQo8 zD@&gGNua`_+!_hLY~eQF89*cM_o!Ad6LWrE%kJb%(Gq3WIthcE*GMCHNk0?gp?9k3 zsA1hhQxve!+QFNqhrgsI@DEaM_BaFl*;F+6sg%}m0iTL z#`}dX=gaIiGkHgk3n$k~-@t4A5D9KdpUKjI&X6ukoS2dcUy;36O~Gww`^>p)i>3Ms z&>gP#m^aSMd`SAp_G(`A>oxPCAyQexCso>iqq?e?xG$czAp6!=fogjf-8j>w+{eIo z`12>f*2<_sBR@E|UP7w7+IYr~7Yp}Ah~trcTtt#wb#B1vgO$kgAJof~IdrjuK?5h%anVfG>j;8(fdjM)7GoLah2osr8v)rECS!Zy)UmH4qesf=0 z6yfC@jbSTe-$DTY&`JHK*2MkPDi`@A+qJ~seCuW zg3@fG4JxtqaI22WDoQ(8pEbgN+QJ19XNj@sbhv#9fI0rW>B3%qtd5R=Yxk-JQiqLm zA{&Kb;MRxSTc8JVOX#5`(Ho$wtZ$TKC=4wnoDul6f*T6piC*22Ua6MA>=T23C0k{d ziM(zu)x%w2$HYD%x#Khw?Kx4?8_@jIL`+BBGasW7KKs{zQGYtjqs0h+MDp&4X!v4K zHB{8_r>6K5B}FkECPAM^`lF4O9{frq1#S|Cq~^uD@MdW#EFu_=zV5~|>tWB%wY zn`gRY38`w@oD|$2DaGmM1OtbZ8l+4-sj0CU@;eNBCKNq#k9kWpt3+Bp85jqu=u|XT z7w{An39fI;d(_YIQAdh@)v7rX%5il}Y5kO=b${`4(wXWjg_RSXa)0+MncrmyHk|7h z**2uek17jucc<-|Yy^nm+_{LofyHc_mvm?@9F=pk)d5*6{*x_hFs!zhtQzaxjrg5d z)*}roH)#3ufp3v@1K@JTkn5`uYo zf<1JfnvCGccTa5GP!eDdx!13K52I_`eIee-gX?T$sjZdR^Ij^yG6matzsEIVMbM-s zw6?sO6oo%syJOo`1!ZJXR?vv|y*fx;t^HE*K9?FLYB;l1_cUIT z|0U1Qqq6qdlXQoFB^Xw%xF3=ygM=YYq%Wi*zANZ0k<&XafPS37>*LX)JWgnr7gMN9 ze=s;R*GM2&-N@%Z(gSm-TH)cp7~zQ&|5--&BUy>gg;}OcR^`w@CgnASkKv%U+XdBh zantNVg29-aP&DKuuGBy`SVCK3bMcnPgzXA$Li}(z3YIi~0D)o8kh%~ztT!;&PCHDT z!t%)b(|X}5DQcrnxYUER-R^A6{l@o?kF^E21R)l`a92+KS?4*ij?0=~7k|e8dbk`M z3ShZ3DE^8znXbykjMOc{jEEEN&;#|&BtBsG- zoM%pBU;uJZ?y|OxwO<(d8P+#5rrdOwo-JJMr|U&tFZz-bH!^RZ)!F?(ow06Kwgc)f zlIT+jF6lGWy=lB+r^f5xyd7JcsyUe-V~$`zJ~)-LHwg*lKObgr6%-<6l33Tl^}14KtT zAyzLMg|}Xl;uU{&eE*e7ehueEJ~k0I(ye`e?*0Q>J3V_sho*>6t-`PVrG3KBFLXA3 z9Kl_KzF3~*%cX)7SJVn=>Ihmd+TJkI4)w`oI#6FN!M_yjg~PHq=%CU8q3P#1|NH{T zB3(G<41Q1)815yxT^akxe+;8uxN3!#G)aP6T;i=_W3E+gZA$u$8s9k8;oTh4cX0ZD z&ncqEyuO}tD4tesN0GZuqr~gP|Z|P31!hX7q-%75fm!@mbx^SDogn z<8#apwp^~q?4rn^L6n?n_hNpwrrd?yXqiG+J}9Yw zmYSa2LKsOjun9m6#1Oi&^S!mg!fR-MRA>|x2=Li`>Te_pVL~i14xn0PU`XG?ic#DG zCNh4z2J&W!5B6;UK^?YH`cjNudjLPIyZ((-9L&?M#Uh+LRWA8Nv8cRh#>m!?CcZjT~Bk3AGCh zqWIw~g84!9C8tUYhh$8{*e|BG-V2720tm`_YW-RjIGM*dJwtJA;p~C4GP74g&CaNd z#GbyvNbtrKt`84SYA$QR*c-1sq+BmkOC#XCrw%Gq<8|ZZ#6=rF8>8Ub(`_m#@yLR? zrU;`|OhhK)9iN{r$k(FOOP+Cm@gf1e4kgUD7&71Rcq5s&yn-YsY*`JVVyAr{>O_D* z+s78YfQ61Ol>08@Z*R5wo&;kC4J5)cJ|TT4e)4i|7$$`5x1Jms7h_wGvJcuJDz2|T zAy*zJU!-rlI+N~)W=MD zdILQ(HUtTas;5Z&^RxzLIJJe2aZaC4K@uH~MopRtl6c6ZsRn4z;a74gfEIR0t_3^-S(0?*JcfFTl%TRb}#dG(9%&2;BC98*< zODY9AcBIkcSurIq zx{HxaJ+(TO*bx;sb7y<7zo}D~`(DD5y{KDMXa#9dhZrTmjONAMs_n0EjBPgT%rcw>Mar>jylfCK(7V`Or zc-DMO&ZM2|cUz!;swr9(WdVWF8d)*&W~0hpbN!tFmm|d#UGGpe3N;+tLR`{urGko$ zj4i{rbwEy4V=Wg&Vdl)pqN*;@A^qr9k)qeQtM5iWvINn26%R9UY zUj)_U(};V2e#wpq4NrGRyH(04?~nzP;~Wy~EJ_+>rWKDv?}>D~i;drqF0_W9#x|;Z zkDxmRR8^qy@>k07!M;ZB5rLnkr*u#ORWcKytRk^qe8#YbXwJZp{DDyJOxgO;QFb;Z zLU#LQp#hdUPA)q5kxTxp3`q4E8Oz|Iz}s99F|Clf_3aF`;*{i|+a41AF^uDwl$*Y2XyuNU5WU$s(|#kNLFObr8%@Tb(WS`B5q<%5;k-z{0cCk(j^ zQtvVa3{G9P}^1BXsV0;;`ZZz0n2%b)9Bk?BAa@b9cAUMq@~lo=Y~yB zRMZvGM&Tr0W&ffgj1%Fpnam@Bqt5ENI2XP+%(B&I&Nh*hu)v|qdw%287~R-d@U-}K zDfYbN(Hm^qY6cT;dA^}gIg`evpmLGvvJOn$^%`V&jxZ1G)z`;XFb&e5{}0)=6~_vf z^63T>0Wg=}_yrXZI4}w?Ol59obZ9alH#0UlmvO8E6$3LjF_(eN1}J}xwgps_T^BYC z0@B?jHws7$Fmy_T(kb1;07J~cFm#usq(}+~(hZ_?N{DnSNK2!H(g+{M8_)ayYkl9E zwPx;p?Kt~7=i28UR%R_-Zdn_IHB<=!M{)D`vSigbe^;Nt%kAdi29TA^+*1uN7|oH_yysJJ@;d;$QUusENHI2a7@gTZ3|3Pd2q z0R<}$m<^!L1E?V2P&YhQd4!8M5@u(Qx>@F5j{rM_1K<-A69N5B2V|Y0NEpNl4yaq9 z?4iy#D?+TC09^zG21R-QqXfI8JqqO_&dclR>B(c|?8bvY+DU(LfB;Vz${x^xxQ4cNghFn%-JAE%$vVOjo^ap4hAj+kWBZGQjk^o)V>ry!9jdJG zH{=Gw`wwOZMFB!!F=1grVF2n1K)oRLyuZrpdAmS=JNbWp!8Z*2eO(YPfb9(ls6WgW zdh>(l>t^Kv1yD$LsK4)jJN{|m@$msRFbE2;hT6g4c>k$>14C{9*f)odgn0ob;2Z7n z0pMSse?OVs$jb%+ck=#E`0w-O)tA+j)6?Vn!}#AmIXQ$E;LFbkaEl2F0(^pkqJW4P zAK?GbDq4S5u)ke^|C6c=w?zPAf1177rGGW-@%Q}M|IP*n@XuNrh#S#D0rvlB+!QPX zhTMGd{XZ-Hcgp{tz<*WwziIq`8&Yz2a{BFN|Ly<(xUHOFPTqe5ZZzwTy3xNn;${lq z{~Kxm{WG)bP#c)L^Z$C4QC2r|APcv<(K0umAP;|7@DC1iQ-XOxZM0x0i2WbM{J|gp znlvXE9IAzIgZ;W%ZnD7O|MA_77sT=A`f$6EdEf}tO$u=`M2C|NdC+IeRn{iUQh_$r)dO4BFv#StmU*?mfn+lZRqyma$8h_QBR~0ifty> z*Io@f{*rD=YIMA?0csj z^o|XJ&Td2`HENY~FHxJ3*wO^kbXl{+bSpOsDi~Oes@16{1tOIvB=D+`$&gj(!m%Vu9Q8Bf(WcpJZQv zl~!0jw*d+ACK2Y-xD1soEkNt5B36IoFEu(%&Z{8Vi{&Zv$xG*}whv#R850{l;y?kq44paa2;|x2RMX=Oz3GrqbgfdJJM*TzoSwRQ)H5;_!96ZK zmROoA6$JJ#c1$j=P7WbK1zv5Bum^(37_wa`yetKB-82&t*vxk$PX>Oz`7Sa2QAe3z zUEDln0BYO#F1)d*);JZii>rU_wz{O(z~wkK`%`zuxJtX$jMIFcMA^Wg=K1byg;RnK z>jRh7OtNMXDcm_C$Zg_kmTgSq~(1RlSndM zyn)iHKEMSYia2cKWN`$c?_Sh{YWGueD+)PEj2%kOh9515BPTdOM zZSOFe@y3wokanP%4Vi!{xQ)f5IceOG^VFgT#nBce8{>>y8x zoAV9N#@NqA{>Uccs?8z&2bO-Kie09eL}Pu{y0*EpV^LZ!uG<*;Mb(Qe@u?~-A%%Q7 zAeQzr1KZ#TTtB;NlO~D-A0eji&#PLShy~2&@o{}M_V@GOUzz(x3{om;Jz}cFW`5Um zwj7%OF&%W&)j)snCX4jM0AREf5Cig_YA#yJH7UWhrb%BUM%Cy%5&ayMOvh;79@*`? zO>z!YOmb|rPJPuq!BYS|{P1b80<(gG4Qn|7Q&Fv(*xy&(jHu#`;$_+r-_G~uMRo#V z5I`G&*SFyqPl5Nvb)P^c?}IQ+g8}g((;E5@27@-qUYvgsv8To$iXg=OFAC|Ir}nw3 zV?~>9MSChZ{k6R8WezJ3WzvSQ;XR8L1n1M>qH-K~3mUNN~b9Xhc3UjE1*B^2Ix z`uZ5r^KGjpZys`-J(7KkdlY;4^nh}e^J!A0L@V??c|CzH(d;q9H(hB8HA)-`BezHd z-JlIRgvx*WtWvtOE=oB5pvz-$wq3GH?^}&Ar_0^fqSkcSUYPFLhA;gP@K0O*;xCx| z^(EyGZN6XIYbf9Ais6YU=6{&vR#`t$zN;f77`CwfjG@hL9VKYXy{HmhgKN=K1M6o1 zTGW3|2H&kQepIE%KNcdwM5Et{=O2wQT{t|A zm9c*mBT%cEJ5-^u9*RtFbbStw&w(uWP%zd)-`=I6A09L2`}i6eO-20UCa@!Td1F$lu1EElQu zxy8Y;tP=>Lz*{;pQPPS@w=FkL9|)v51qpxq7!}tD_z&>4Dv9Md+r*$HFvZ{7c6BO~ zj|S&Z`{k#uh~2aQ#Pw0N*PCi4k{-mbP5_$0t95ZKc*KbFW8ld^P8*K7{X2A0Y`h4{ zg%b(k{A&SY%UY!@Qw8Y+W3iJ7aae=3pun&tb9EQ$=8y5CEB&=EVve^4`VWiGl&3{1&A@)V?*r8ya=*JKUK zJN+_yv_n7NVmWCLD}#yZnn%xWnXW$os-m8~N$IN0(b>sSKKxF;9rR7AyHf6unSADi ziAy>8m;h(|G!^aH{GzPEmv+StVq$-iGM%GOxAm;}O|&`J9oBIe_u5&Y@O|p7ro3+# z3&rl2?5*qK6wYG&p&9s=yv1GkVMOE1iibLul)$!hiTmpdymM(PQkz!GnIJo@fRT7(mEI(7B05u|J51f?*aT{C}6ix%h7 zO2#w6(UK z5TBjB-1u9t;UDJO517j#$*o*517iCOBkplY2D7S;`m5X^_Zq%TO1)~IGFbB`krNI z*8{%xtut~$#_pizrqsxWldRLH9pf)2S%=Jzg*o{^@5_cCJvdzuo|f42v?2D zf`6?>*ZaCw(s0)^lD^LHv|ze_k@)Bft_7umt~d=Xb-jb8rA0>;ZS;m%5oG6(^NY9V zY^IcpT_%(LQ_1~@p+~g0?_UnHNo0bq6>sxbMXsVxa*XTPDw|StH)K3Tf0Oh&*n;Ma zb~e+7v4~`R+uPY$D8jJb(axo0P*5=a>qY-(`5?@LRpQ}g4*$~T(y4Z z=k&Lu4+BV>aZXm60shpSRs|^}PH>Fo6kd@IR22qok#t77iNNC7i4PK#=?S)u;r9>&)$a|z`euz=q>A6Q z%Ti^?X^el7AJF|@IIvs{(|Qd|5rWA0qRfOs*h7uyJX-?KW~TD=dArZ@u>Lk#c-?NTi> z!?&sTltU$k>pnNZd99A!MmZgVszmh;nB5w1+{qu%hxel;X+3$-{8d50wDdus0b`znyOE{`)AkDF< z=q5l^T_Id9%v5w3E}~vb95#7|dgtw~G*H3BHP;svRr(NrCsjR)<1CJG5fL)!#W@5N z>RC%o@mpjDnjP~%F^XxP5g5o9RzUrNdF5N9(rt!|TE&_<+2U&3I>dfx;bc!pDwU>e z1UDNAiStY+cm}=d?|;T<(y3(0xpRQOrZ^;nSpn=Twrd3Rg7C_7<9JI?j>32@GW5ro@hfqqtGdS989Y@|86b! z7H4mN#%Y_fdfA~8mSz3e<)O(2`Vm>O9&n~#&+v{gx%kT7mrJ!#MQpU?S<;wR0>xOp z2AAq!#mXUjVe=_?emZq0jElQ@Tl>UAWrMjvzU`$y*XE_`vIbG~+;#Zc)gXOAW&ndQ z;ify#WT=tMA=pw&TCZW%)t!KU&_^5PwdjCP6sgx$>=d-P(tTH(exccCLPVxGcS~o25#p~FS+8DiWwegUt51{vQM{@=e4*8Y zF^R*$Y&=gIJU3N{?$(YIuHD-D``u6Jo0UqK-z2N*IL~^>m}MMkQnYUuqx$yKDkscP zRF@#+OY|jX+kCmzt=<+H`wo$DR$hjGdPcJB1A$%pddY{a=Tse-$j>sR_z8BG*UW5- zw(eVu&}~`Ikh?$a4mDffTvfSvun(%AYgtf&UTM^Oel}!Bs}fuPfZo*kRY{`BExLhPT|mkdW&|@4Ef6^)#%-L6Bc-1o$SJ0`5qQ^^NoGqYxJrPsDJL89{;f0 z=j;9uo=R43rHmRC2XS{He~Rj|87G+9^|k{@xHr^6#D+opJFsN+;7!-ci;vJV4tI{6 zINi-CMv`ix+j&1ia_$aX0M(6u8yGA*Y4yP8O`f>461jdXo0bR9Hv^Xp&XaS5UJ^NK zEtSep>6iqQkl*XL=v=B#JDa-n;Py62)aBaxbqIrAIuystdT)~XOmq3M5_;Wz0>REguU7UPY7XeTD7 zIk^6~Jh`WQTXh{2&@3^31%j4J8z#pKk~UqBeV?xI$XP3DeHk^RjEDQ0ap2Q4@Q8!C zj1zw82_%gZn^9|pb0%zi_sjEwQm=zc2bD+~JmKj8a8mYePDH)^juWOQJ}FEk|RYL{YW1v-xOsM*Bs7M3<(-x0ViRGz%xK zxk<~s+M=eo(_BybwmWw`D6o1Ikq*g(M$4P*WphP6KFV~3lx_rI(UL*oqNp{*n@Kf{@AV3WuG zQKW1lSchK+743b0D=Z=RIi|p2Tf*do%M;T{DbNCvB$>v(&KF{KBfZO zr-&uj^zWI>8s(>i%c=Qmz7|b+{nBbJERjiGw;z!8ePb$r4Bq-u`{igr$+*r?aCJ1A z?>lB>fC3iBE3J{Wq1{&BsJRiB=4gf*UH4C<^wFQ*b{_m>un|32&p(7QRY%AZ()CrF zf>mBc$?Gn79#uHxb5_RL52}m_Y{SS!4Gcqkp1XgXItY(lkEE<`@{EgoiORzZY+TJ* z3Y}FTR9R4e1`|d)X!vr}nKkZ|Io(6Me@b04wQJ4x@n^}wtinAC1>p*&dyl2Xu%Nq4 zu~@as&DSgS(xnS?UutCfIOgu0hq&16Ucf@o>*)v^rNY-%MJvD!TV5nPjoVcau3I8+ zHoWpzs4)!au_UvD>5J#()^&|H_use|kl5Dx;VPJa;`~TW%3(KioMC78^YY(^st`F{ z6ZDJhOLC5b22>;rhny|7`pbHkW^z|+nt(*R%?V>UsVmTHaPp6x_}SRX`L|_#N6^yK zz~Q^q2r4N)%0-D-S6t=uwccB1I>@E6IebshrQtXlv)_7WhR#7b^<3$O6%>cAydqVi zsAH{vQGD9=w0xfbyYZgzcZ_#tT?V%wI3$sJ#HxBdNkdY6!57d_&XTcx_%;6AHo9KM zODIiA?n|@THV4h7oGv#hfuW_duCaE4dBOcg-!B1U8FPc#B%yd(Xy@DKuhjL=0mS6408L57~vQLle6Jr4cU%yuY_IuGe&<5dqg+c=76p3Y9kkc%DHRj0Or`8KNOf;T;k;b&+U1Iu zN>@Z%X!ou9dvfGHqIgfF+d{SNwX(y;lHNw}F*x=N0@&+3v`AODmXU*24=xbV3QmM}9hcfkLxu_8M$$E2_be5AU%lh%fgXJ)c!maBF zyZqj>#roT>cg&hqN{M}z<_Qho(({u@9PZXS27q8Xm>eum<|H0>VHI(lKGKyIt;OgY zf6yrWq(HZ~;jSSXzB5jO?3gWo?!vY20%R?`vAG6v%T7?w(PJ#~@gP+cVoL4GukXz0 zllOO(7E&i4jwFIie^Z~=(tNCHcq^vV@)AlPE1pk0X`?t2rg+CiQSxFjW~l_F)lcU095OMWfY5s+9#Q9PQ$lT0{pEGQL!A_?urDH+Zp zfCp8TZ-1%xV`Be-oE~Gfsf8|R$5ez zQ@&;r-K7=kc$pDK@-#2r7knsli7(1+)P~u1T{Hhwdew|IT@xZ@u-L2jlg0YBDMR1M zm8^Lgs^E3x0*;QX*qg9_$^Z~En%Vt|JEaXQ{jO*o_}~YVToIr>YxG-Hy$qat%~T!D zDQfz9hN=D*oV3`1*>DNM_#eXVM)%u{jAbKlS@WpOV$JqqAG7KBT|#xfeae#crn(## z%NqmrxHVpxjxm@T!CGpdIX2-bJEU8^>ExS|Pfe~f1|zwg4z^T(vYWK8+Gqu8E=8|c zhuL%GqRRa)C4@_iAp474_?`P?m91`p0*=y&WQTa8N2n%#ua0wfteFfnv$-$anJtnw zJ6P{RJz`=FNDRyAJx(!UnkBma?t-{YX6y6~Hbf&+hBKJQYC1)MD^7z3!F6^B^4%Ox zg@TUG<)zeAx4lY#XKI(C>zp+PgBmFUbV27 zpM{pd$R46C`I!Iva9IfV?rmPA`Lj;%PGzO6a`EPj^v%(F#$1}cH3&<3Y(Q_O zOfKFqKg~>lD;P54w7<+lP!Xm!%ttbyVR_^*WrqYWiU+l2v5Z2+Mm-PGuXx?Q#yiV$ zDrlB&Fr00F%l54`ce68!oocq8gT(0=+H^(1ezC+c6ASh+f!|p-?ZoX~WXoap*mpZnj;yor)AJ`xAJGRa2SF>uuY>6ozm1!Hh!QJJt5f znF3Mw?I`D(R=$62@v<9Ef4q{&d)-U(qttU~n7iECW>iCKH5L3}w;=f$cIX(os+a;D zWg%LhcSllgZoE_;tWN6#ZN;s5a!clzPug66vhN6e(PbYVmz=vfj=!a-ERMn>Ly|J# z&-g|SepOVsd^`1Q)Wjqx-r#e;M6FYo=tM&J_4T{N0tT&+(;beegr|LtmYY)3r1X*~ zGL`h!XPkFP>soO7m2JzKoYqIqf4I42+&T)NGCU6_n-^={1SbhgL~0tytrAd^IyA6< ztbew!l!7*Y4@d>McTx5 z(op>UOaa8qlkXe7Bt!#T(GLQzj~?@XM2yvidG3pN?u|WMu*pQJJ3FdY5M5~AQ*djD zJ8YRgvMAcnA9?oh?k7npjm`J*vQ!|_dP!?f5zo%8`~h*<-KP^#b0{CrI}N5*l~kFE zJ(<-ZrN!ZwK61Mp!%Ni83=ocTHqlV^#0v$#{QI$+B}+1f4$0}Vcq*9^$Y* zyG8EDvz>3kT+yfAeNG#YM=J95zoAmtqV75|{A!1roP4+y$o`0y#04-uML;5Hm3f zFHB`_XLM*XAT~2LGnc_#0~7=|Gc-4sfy@Rde~oknR8(!-F5M`Nq=Nzy!Z5U?bT`rh z!!W=QGcXL@jg){=l1hqzl!T;oBOwS#Bi$j=|ETZ#z5n~2v(`ClueJAnt~;Lle(vjf z*jTjncx0>*R!~I*9K{3Tc=`DFiP+fmVJJuFUoa7y0Tk&9L%_xU zf0u(C5(-A4F?lcw?Wci&1617{0U!YYNLUOcBF4uD;OFCe^tU4dDF%=SyThyj8oU5i z1RUy0#3qMu_CmsJ?NI1#{{97UKsW)QM~_4v{tgGoI6;vx2pA5~0Hf@nPUsyWU`K!+ z0s@1gy#AGfL&6S)aux#uJv=;k!A`Ece+ZNCY0Y*XrXuuH$fx=zU5pHm6C=!6)9H6J74$yLj!v8p{|8aN- z`0H!{AYRaa()|_vD-jI-I~WXsAe@}Ra4#6#7GMK&gaWh_)p=2#sD}VB-1?Uzf7sC# zfsO~egJF(fE40J!%E16d865x^-QZvCxk8XIXOt_iE6nj%i@;xL(5I{bx0XXVIYHql zSE66_$-|IP2>RH)fPW_I07rPheg0b5z~I(4znZXia|S+v!(7~;D)N81pdq4vFk2`J zAjJ1bSXfXL0CfRCJt20$U+ML|f1IJeji6sJx&uESXM{7r2HgbI4`u^Je~5fs!R}B1 z3h4&*^ZDO~f3Ju@Ab>Rtf&y4UZDDYtf3l-tsLh`>diY3~C%}{s%{>r+@7MF6zo%$= zStH<%UjMlNo-a^F+eA-Zmite~|FOx+B0K>;JRl(e&m$oa0K|`eiHPz8fBgQPMjH(K zs|>z>VpZTa2*9I1)uNB-?~2|3A^^u<;@|}QJC`N`%~~jc;~$cn@d@!k&@a&cH`RZK z{NEV}i7ENXze~=(ApWq)H=Bfzugj#FEP!PL6l=*`{`6V?+7#ymNaE1N4 zThLK_eE(%b>kHz5zCT>iy!>r~qUH1NeHGvkg!M0-@e2t9z(^$6i--?RCw?IzfDZ^Q zNNcF)ZzcnPyl?~x9Rfi2=m)StAc=mBRTKmO>imL!uLJ}DKy(g-f5)HE{SAZogaJS+ zF!DcuFh2n32uA%HH43eSU+}-Gg18}(Xm$Q354z;P*T1gLP1tU3#ZKMf>a9@R12$2Cm(oL!M@z zGJ@ukm9tS83Z2WcfBQVId(VzO*+QAE5%jjhA}P<7$@da;m~LB|;+Q^oVK{LaCekLb zR<@dV)$F=v@@Na-1St4H#*)l{ij~P~-olDDW?@}K^%9{}7cLE_q@(gyWy$JKf9$5CPRLNLb;V$p75X9f zHYxrdUA|K|`y94Yeb zoPy$x+&#wwqt(e*N(WnOm_ZY=o&fTf_>5bI>A3G7U?{AaE^1huD{CA^_O}ba<%Uo$ zT1`7=&6`-&D10Vw3CP6V>o-Sy6I`j@80yO*iBT%oe_P=DW_E23{C4#DP?3TDje3SZ z0*D_j&d&h(C>1HfySgK5)vOzXRpB%Dy*N+-vyxbks)M)s5iL#tMc*ti7T=@pkReiO zM1uZ)%|;f`bSzEqYeS*Ecayiv!U*$28Wp^x{F?sY>0BD`&G(***Myi>sXP~&%Fiii zU(odJe^G!7rOD;E@}tRS128TpieOmP6G;!RA8eMpr5>i=NEdQ!<$6(2Ce&5UkDUQo zowvg>T|2)aha>Om$(!`=N2Fqnl`kA}p@S+w}8Dhc{A+e-GtPAMqGVR%G-ltGcvNs=N<{`)as#H((;eq;A=zBDXt*ejun?Y7mMvwDxkpP#KDf&2kP zGN=Qg-0v$cPWQFMRPFI*6Eh<^ASWiDhXQJ*k68tk8@1hY33&DmOgZS*!6MyrLN?H3 zfA#U$nTiH}3s2iMNVs{C`WN3h3qlcD$aYf@==FTZ1E;gNJLAEfUkJ;X42fP>Apn6^ zYT7MtXKebIWwgE}Sju=Z;P88o^*fS$`X-$7E!5Lb^IJuC*4FeuGQ{0<%{=@djQ8*! z*4Z@##~o6~I(I+qCVgU0{1up-Rp7kof27bimO?PabKzvZiR7jqqnM~Ll>9A6L2T+v z@MFl1?!XLO*xByuD-${!Z|_6tD78KYVyY>+bJj@Xvl>+dFv{hyZ-A`jj;>gOuc?f~CRYe`S$c zg#ZbtkFV)R5VZXq(6bb%HKMaLSMb5CI5HgXMQ&=9vXEfMwBR~7B_P(Pd}1oa8Kw@% z_vd9wJAVDsvE-F5u^ObHd_PS~kRzM4d*jJRC*1h@FI=}o2wc>F9mTQY#QQi|6>q2ms8fcUm7wn8tr>!_jgFRqZI%h6N5TpZBsQ3nHrt#C*g1FORGY~L^*m?MMNF7*`A z_e)__W4UyX`C`kHd#Eq2r)O;OeS69kD=hUFzdP(DQ9e)RPt6=nZ2yi+60jR7O!QiTB)@&x5$A%YEdSqS$}UPf2Y9>>Q-`ie;1MEUgFkUcPBz|pS!Yep8_S1G*D$yvJ8h@q{ka)ST;ybR2g7KHZX5f9mD02B zK&T+%-1B7LjrHjqPRxT+=){vyArkj@*)WnP@G$;Yk!J1Gf8{Nb!uv)c1GJ0riaTrp z)7E#_)2m7pS%x3a@6qG?`4vUEDA3#J#!J;QDqqZXW<7)C0snnq9W zEg$(C9`ucqf6!wJSWC2%l|{(s!e~)u7UAXjH~t|lz_-~^2?GUjySK6nUIp-jIkNHh z4EU!TH3@{IwfMlcr8hw3;Z%~G{?z`xvughWr>FvL2Hue z;GfB+K$;+SF(^Yu@ffRMWtfeHeLH*PeR5cmfQ@MOe}v=thIPoLhHg5~#zVfhif3>v zCh81~2gW~?JVv(McH8kRxMFXtR+y`daLYVOC1s3Vq^``wWpk%G2gs`9Nx6o#UDw1; zHwix_*EYZNa)@8cF|sVg=}L(*Vrs0+u z*)k$se|hR_(C736AJ?kH3uMMGc{_f+ZaY75c^| zS7G?7rTz1*12X-$@W|>TE*BDh!3K5qM8CW=A%g+H6)P5~i!c4V5-uh)^|ASu$$0X^ zmFhyTc(>EW#LXu^^2g;A<@3Ks+-iV0V){mEe|i&UsZVS(N82;=RJBidv`DRKS>Ail z8F|n7Ofs7|mU4Ne-piXMXY4g5iBvn|I>OrM4tn_#T@E+e%z@br4g30F$Acr@aqX> zg$Xw?-ei$FGzKQD$lpB_{`%&XBn?slB#r8A+nnS(u~5f*c3UtLlZ%Y|nn@=@MrU`E zkAWZCcP2TmfuXqOsS1tJV(`qnwJ*^ma~WKOFFP%8bmyPt8na74bHLEpBxhXzIn4P4*93+%{iJuO|Q(E)aPL7hX!Be}-_Cg0+PV);yJ z7lMyP7F-?h3aBxCK$Suhk<*DJ775N6UDes%hlF*scAE!`MID+XrCBd17e`3j9meHS zXPHY>Zx|~!h)LGfZ5bCd2eqy=e>Tnds~R)u2$yV``?)0&{W_$V?R^Uf#FsL(yzer$ zR-3=H>+D);jZVu?7!>&0z$%<78l~uOD{Vn7`s3W^_{7cbt0&v2V8W7bU<*F8?Cfg9 zG2WsK?2~=n7@Ll$Y3F&=P0gSPNlldPmcGxZP>i$xa|e_X)r`k@B;_H$f7Uwz!b7_J zb(=ehMsy!OXq?Q?U*IJuXysv+1d_)URS`$b#c0pqzIYcLt&C|U{y>Q7%l^sxk7JZO z<0L|DG8)(S+vh)Hz5lF-sb|-=n3`LeSORd5ZgAm|hYvHF=s+s*GEMcxlcDuSmvm|PKyKFuL5$i$Z^Vp z)S?CHw4Ly+MzKEAu+0>7`rvUg5xQ2VEV8TCkDa*zQ=oqZqg(+0EJ@|zI`$5m1EEGu$bwH?jdRFXj5~~>C0_#8gdRgZYGW9s z&zKrd)2Fn2>ng=pf|`?CyTcc}6lbhC{moBm3YjM>~%f^!ge#OSNt0 z)J&OaedgUqhfYu|f90IkRIGJOaM;(!j!*6lvzUDCacB>f;-Qgbz|T?XrBq$z(UsxS zeq77q*79t>W{0zHrhUR4=PC3>?uV-@R__aou+*0LGI7Jpd}K++bwriKPwIXJ62eX~ zbxAjxU3tP)mH89C=A??C%MH1^T^TFh)7>rW?8lzL=GzL7C@40@SS-VgTRhVu@wVMxe`yBG!5T*S(6?LMJ#Bj`o)PC?mtQ14YmVX2+M8#^j*|&DQWex+GfpqQ z$IiR9RCEHK6OE0)~xWQeUREuyVM z5z_cwfAA{pgD!3~p~jhTa9-0C^SC!g*qxB7adR9F=}$`^H0e}flpf)Gm+#|7fgki% zPv%!_a5D)GC&`M+h_=c7R})SiWK;Pr)Fx>P-J{&|C+Pw3(@`gWI8+V_r{%$|xv zLubZ$yUZ?m`YcbZhHIb521VE=&N0%sRx zcWYVB&!(v7AQ^}ZqRCeda*u>H+DboHhke=y1(tc!@wT;{M_ZoAoo8RSX*k&EJfb73 zf4A~eXP3$g#`TNY3-Syx$84+$vMLA1^?t=3N#ol#&{7tQt~HObSAG2{iljxvVZ7(L3Lt`dI{6L%SNcx>F`02w_%d%M2jh4H$12CJ7Utnj6 z-VNb%dit3s3Wm)|3ysj@k3kfs*Bd*&Np~~#y~T%PZ`S-xqBQX$Gg88|5*H(FfBP}1 z$028jXnW8;BBSLSc_86*3kTz_(1`0EGMlyIC}A50lVQaq@R zveZ9sSz7E%DayUqPS_*!m<}u&sK=_ew#c*mB(JfZjcDr`jAfOW3i}ES>j=8M%)DN4GjEmgw!Zcr=Ad&TugeDioEPmouA^ zTDGqXlcKl+)MhR^awE*T9aebDcTPwbnH=+ss`MbszR2t6rccQRQ+F?Pf7l~RqFJWF zZ+eW%P^B3sO$VmPS89y9LG>1bHB+6sqr^VBFIet=W)q;8rQxLw@tY@_)%z6xRvX!rjTQZJz)@*!|4yvOln+s^o~oPg^JhO5|sUzT4}hrj@*7aZ@o zezB-v10{CJioZaozA#x)e_`Qm#~&GExA+k?^(@)k?}@rBTw>VC+iSJRY|{rjKaFf? zM^qDDGcpj6WHZYelw^E*v|yh|bL;#?AWVe*?T!$$XdqQOQg)>y$z(>ttGc>jBO-}H zD(Tv85D>7dcDTm%@CVSYs!H2_wb^IIl0JmEMPBaM!-CR|_P7pMf9@;*RR*eL$Q1W- z!uH!7?qAeBA%2Q&S;~&Mv(GW$AkZX*2Of89jKNK1-u^iv`7Brsr-^7DxGV6uM&`3` z6_yhBoW5-IMyBrS{$vQLfY!u;%(85qW7~+&s;lEY%Ao_$sR&?s$f0kP-Xa0IGQvY~ z6R#7lS)!0uv*R)55{m zPq9R5m4ico8)H3q?--#kOMywXkc1Zs%SbFUL6m~jB((~EgXnCPKB>*uiK7U0;#0X7 z_ebnr5qZcS5!~*4XPt%|{_6X)+9wmENB_IfYaPTafAdcBe^#cncHx>6H1cz3)(kIC z|8U9or;e3fExm`OqOWfRUtv&FT}uq9Vr}s#6^?W~_9kdKXdLP<**`H4L_o40F9jol z$xRNctE<1k?|C6NKCRmhL8lgT+e)m)SbI4ODfqKW@^zX-XEK>}>7&2z9regt%NdQP z6ICmAZYp~Zf4-&4+g%_S%w5Kh2sp8ctYFht)gdpL31NKkoTb}j2J_h&DLo&3r}sA* z3;IJqGNH#2#_e8uB13YS`>(CX*DB0b%%$=mV(pCyddK4gCAwG~8`lRoI~y^(6s&P5 zzXJ(oB4yljKxDxXo>#50lnrn4em7a-!CT$#rLYpJe~)+V-xB&2Q*)EWYnL6^EAZw9 z7E~3E|1_$j%PHx%6;)HBve@OTVhNf+9D5fShFo$9KJ{#4+U_V`!~9f5xHTo)E{K<`6$>Mqby# zclk^U<`Wr8Qa94471z7{hN=V0Cq~d?;*sQ0f1DT}uEQ;OmnZe8_imAUYcg%c(CQn( z9`L!;f<%|Zi|E9^EIrgtX_8)HH)Rp)-ws7h0+;^I-lUxz+CY_o~;h-g10u) zSuB`LCruno;S+it4>=&Lv*De^9m^^fQzO-CQNywU%ee?ajXgFPzkf&xm9z zMU%pmaC>h+kDXOcvZXKkEQL(9q)d&>+GRETgF}O@3d?-4h5b)$Mu1kdFSD1LlRKUq zoE#A|ZHIpOY@HMVjw`381Y^^BR4{qX>u{aOyBe>wgd zDoe-l1@o4h@1T`%U3-6(nrDjjf$)K8l<{%4&GNYL*4=zHLML<7S8bOM;-t7zu@s_yLTGm*gBH^@*e-)HP`f_y9|X z(pll#lag`CF?e*=30NLK?+LcVe@TTYguRerHAXxW(CWYNRL+?d^mP z8{8-k$9c>#epWTHtVB(PE{tU{t;g}{NnG}|@*>fqu{x8{^;6^dWN2Qi!A;DJCzEW`+5Z3x>qrNe@#zK> z0W+81>;o0Id=&%M53huDj;_l1fU}T&_W`h7-DW^B+3g7b8y67E%UEm056yiAS5Lv zaqo9HK+y$?hJir{fDQ=j2z9wy5e$L@43S_M6zlbm6uh#ISS(6fP|(A}LjdH05kP;U z9pw1#0X$$>M}Pqo14X+-A%I^E10I50pnp0OAm#=bIl?f1a6_a$)&qow0eQVZdk@ z3X2iIz~H}H6#SLuYL`_J5M`u`3lxFH5dW%A1%`%#ueRMw@XyIQBaj{lpTCAZ3<0tK z)da*1C1{L*xw=6$RsK@0AmaaE4p1yW3@9ZoE(QcZT>(%}u%qCw^hRDN=x=|g&@cF^ z13w=W5(TioY69v9vxi=Nhm;Fa+^`vR}ba z`#<*8;iF-m088MN_JjbyU(dh)tgqw+K_cK@|DpdrUqKxWbIk`jcmH(!Z=aG9(i7mr zFDwP%mlBf%2nmUb10*CQ0Dgb}Orr;a{VfCdpIA+VJrW@Gr`oG+`d7v7e+9t%cR2U} z|IGCed8Jw?fcHNlw*ra*!B;P#|8J@P4*9<+{8yI$m&pISAT>8Q{I{F;xBvfegIr*6 zufK#V(Yj%;20#aSH3o?PrkXj8~{S2L0-hbD>(^^i2;0st_BhU_57`5fS>>ZiM7xc#x1qd4b+Y)~Q3Ihb~&>%1r4z1*VEKTU6pJh zWeokvdS8k|Mn3y8-}!Mo=xO!-Mc`DDMkW?VwR2u+n?JkvWbc2y1C$MdWO5jiNDiB) z+KSa@rLeUmu)G~_`uY5+M4QNR`BL6R3uf6uY8~JLC^)3#NMgoDDQ2{+<3*TraLr=- z%&jP+snM1xZbq8MLl<}vu;?SDrbxyUuX)Sp)V}ZEdtP*PCX4LmJZP^FFAJezyy>mQ zk@>TE2h>uqeeh+D10L*+mcUH=bt zZZ+`mba4Scq(T-0FMB3r3m%Yj}eO3X|=yQsNIMWnH z?wx+FRPD?tzI(Y*x&dF>`~|`eX6y+@4>RX#rUgOAWgdUhO%4aMC$mHkMYpTtnzIT@ z#~*h{Yp~XbOK2Co!H-K~m8^IAQn>fyjKBTnw@?PP=yj!q`dHqbwG<|AA1T|!5+xks zTZ9j<@mC6w(LEosHlFSq9INvhv!TMRh-mAiqMe?o*B)9>FfQpotbWU``$3U%_lKy6 zOG={e-S2;IyX_>og`8e`v5EUWW*Mjt#;vT}EmfZ`rs9*wB*xIEi|6hCm~0nXa|7`k zYLK3kluq}*+w9hT{JOK*etO?+{Y~PB>|jJ?WDE!xv4^)ohR#vcC)_=dw7)lFL~^?=R&oNr{HcFKRM`2+qPkb-yImF>x_2#s3t72! zr?7{as7KyM2e%SAGiwYv(uY&FifoH;cv2(y<(WMCXdU`IcV?#_u<_XH$}4sz^BorFf|H7kqw%Wh&-%#R zRPVKF^}VYF(k04iL!ojvw_iho$>VPm-=lQhc9WQVbRzC1ii(dLS;5g8xxU+OGgx3f z%QFs&7Ff*IOkdZ1uKWfx!62%YAFo%H!){aBxCM6~694$BPF{;HSh0|OPoX%X-td2d zT}Nmpy%_ATxCo9PJJ!$4h5#zLwIa8ZscFRGtH&f*&`*~+2eY=P9LJ;^*c%v%M8G3c z&nry|$;m9ssm8gwtk;jnzuoZT6EU>6LwV_3PRyJ3M4Xc(jPmBH3!5x7RNp}mZ5x*` zW<)k2p-z%g0rL_I!Eb!hvnv{Q*NHOb% z9TNXcq*@icz=G1Xw3{D6?;TnsRpCLK1|UZ;{mi4bh`~|n_A0plvwZ4+@L^Q*jGcGe z1IR;;pXoZrGS7^@TeF;uWF|T@-ZK~Gu4Mq-7+V4(o;4!5w$=vN33EahCl+0os#3Ee z@(&WMwvXO$G~@x80`B|h*EfID)hR2$^CaGxMo5O{o5b9S)ZN6mWX#SilzY=>KK43F z@XH@1lJQc9wn{py`OCQ@cB8U;+`o&*qFiNaEqpQ0I=CLOCRHU$w6k3}Jd#{z*c-5( z_Va*UPuu=zu-e$gWbVI;ri{`gn`7S14{$f1Iu8`v@fxuz+MS;9-DrP9CW}}(wJxw3 zi9LC-FCeIr+hc^X&zV%@+aO#w})>wPE(wwQYK}RKwBRk(RTdmK< zgZz=N_>@F&aJk&Zhut8p<&_@)(oHk7U}F*`CH5z83R?6`ZyZ0U(<(AeeJZBGxvweZ zP}O}a9VJ=xCDPk_F@S$YbEs&4Pp!dDKjL$gtUoAhO)D)o2LiVBJS#?;&%b1yA$ zMr&c{%WFZoTI+oG;f5)%>`n?44deQ0Q+Rg41bX+)FEn5#W%hr^?}lh*R__Nnp?0Lq z+7c2+@3hN<@a&-$)Yf?8BHbS~qofpSDfNz--^Ux2XgRdnIO9IR>{b)sS~v2CPwb|p z?LYf=>cDinM%FVhor+5rHz)XAz1G*|3`stS#yG2pU^+>On3haZ8?7oOE9MSuqs}9Y z8O6XG#bqsi8!>-6em~;USEkd!!dP3;&(OA%Ee|{7?5T1pMd_fR+E_n2IM;vrAg1$k z=ry5zQf1DY3%8z!`}BUmZf|Hh*j-15Cz59s50$!{y@qzz<2r@j?)Ie2Ac>$o!ILW* zwBjq{ns&T@bvGe^ujl5J(dhEji|{0HQhSwWuFFblT>pOoou?+Ad$uBr`FdTs@{I~V zK^PE|+dHmZ<04AYrpdNYA`P`{ZA#@-qY^RPBq8`QBwBxJgD#SYZVGUvo4uv?1>hzB zbFj5h>J^Pvri#G&Il5aWEG~mTwg74@NPUJRp&Ev%+ zr}w9Oq1eGfE4d@?gI7bXG$vWe#xs%5Yej15@Xzl8cP4oY9yPeiwi$@{d8^baNI!B* zs9cVn4`)5$a%csGB|%=<0;PI+_^(+fr48ruMqhsru-Nd z_YiIKGG&fCov#fbTUfv%-e#o6!}NYuWxK$QGC{!MygXc}!;2VZ?FA@fxTE_y#@pCC zD^dShf2}9TDLUZ(u@kn)Wd3z)R_fHes1_0W8h0OFd2JQ;Ar)qO!gehZ^#3 z)98N(^ErX1;P(Iuov+)yD!XjqC;`#qjt_X5MWn-K#xC!*-r1*_%p*oaFq((xb;K_b6{Gf@_ktPQ!oVC)40?+xpr(&c}gB^gWS-RS}~getjm} z*K=<-XQN(C9h(?F8x7F99+;{4oQxZ_$w@&({C?u(ky&PtD$_8h2P4C}s0@acad1op z|G9cdP;c10S6olu6MAc;2+;`^_gh`c)0M|!b1W~bRBm-YzmrGu<;0ZJwE2F#WFS_%cKgl7%#r7!- zuD%LburWDo?lWT%SOC$htFM*HW}$y^_ep$n6kCEHSuJ!LLDkDAg?(diCcx5eY}>YN z+sVe+*tYowZ*1GPZEli{y|KNq`R%!N?pJkx-9J;)GdP_#**q%UdK#DU2n{T1`+W}_J}R0(JAozaizYugtj z>*XmOP+dB>sxCk1mPctzcA^o0RO-`m$0bR`Xy6yl${)=qU7y1rc}bTVufKYs+t$1O z`|z!Yms(E=BfNJ#IIkNjH9q9t4nQn)`y9V}h~c~{+=M*TIY-Du9N+8eWWblgak?yJ z_MwUN+e5homA6zEe-S$}=oq_25S9dzc}-(h_T94st0ZrG5mc@YB22Kn{<4>-fn2z3 zIkoeVE8~&+h2-_v+c$)L8NrG8fR>x>V4mKNdeKCl_*<>%qd6Qu(VPxY2tbY;g<>l# zx_rav!?yR*1U0QTDozX9;UR^xla?Xp=&$<|DwN@-$^}mN~%qBTGm6 zD646&)18?{EBg@(($))On=?of=Mtetr3u=DX295B&*j<3RX2A(N~@HawC(L)Gbu10 zPwxA)d~?I%S88!n!=$_t3lLSvxdsJOTwEm;&+xjtbrZQ)8|Kb3*0fyAUZE4Ft_b7A zQbx}E##kaF)5DXWk%S62F-s`<`$1^dBovK#MeZefflGrC;JGd1m7LunVP0EY5MXDr z^R#H~{ow)WpG*h>la!ryvdWMEU#Ekoc8lED2Fw^9%lCG&|lm^jqYYD-OsC9yhA$Vx>u6TScOqfxBn^di<_+vOwO5?duYQ4%N~owoe%Z>8~b58hu_R)h{9q=fIk&4@{;NhRnich`R6o9Ss`4-czcE6FD-lN$VSCdOS zW@ZPgn}8LbxT|j5^R{EpFOE-d3$aFrqxcA%s^^7sGI&o!s(HCGsg4zgnGH+^Up4`iD{F^Cn4D`+wpe>j@Qu*V;j>I*1Bth;Xmiz`*5ms_pHFy{koK1 z{iRg_;SO((?mj1I#|}RxxFd}ZXMelLm&4W^D)ZdY?2b)-H0oPr5udc%Rb{|-AQyCd zD2_C)kB^-qsH*i@d5kb^+zo$yTl4Q};w!8KYry$Ec3lsSAgF0u>OpDRZl@S){Yl5c ztT%c#7%|rm;TBe0N7Vq+7V`Dc)gYc=dq=*og%6VRG;tY7FYB>7dgJ_gnZ3yD47yy$ zj?7TDnK{3 zfT$q6w5UH=lZ1V8q#iH((C(MY0aim?{<sqIG5ci%Z~jDlrU1L|#hDA!M={P9T15^~Fm;AylNQ<+5>S2g)&auD7br?@{ z@w;lf$Lf|N(d$NrW_N8EqDO`!M3SAvkoFGyFIhb3$VG%^DD)WhzCZ9a2;N=JRp3ZNvL?0#o=4xMM)2p*i(>L9z2kAYe^H{tIEvBqM_ zK4FO^?n__Q%IK4m2>}s1A923Qh6J=Kg7$zTO~4`BKI2r+h13 z?H=15R2J)|?K!@>=yE)zg6%HZ_r2NF1|0v8TA1#x4l^RE%=!d>ly~anY$S$lO$wF4 z1R)sDSIrDVSBxcXu9$L?9f0F=2T3ovxjz@X%#P$b(i=rFWGT#deb2?2QP{B@&dVK< zR*v47$-iSto=8^ZL#7xGCyZjB2qyIe@($3I$xx;+a6v0f)ui8M66*1nv2YP{aUF@< zU>GjsRrsz4v!G$M)5BYsYvUk>n@+1;4X9IUs^--hSfj#};j)FB0npZ|RB&&R@>wDO zgZJXEPDbNU0jv7&tsE)uZOXu!^7_rG&^@%~dq~`RLdS;*_!}S%8v|wce@3F6!((k@ z1KM{#Qp;~{=n+k)!CeTIn{0m91MHo-VgrJGSvH!2;Iz4!*eCIxnW^yCU}0blcTx)Pd{Oc`CgJn~ z4uOS1C%h5DT7L@$=|6mG-kDNK8EcozkTV=vZyR{^@3(@^{l~U@Gv1w{MnP@+b7+%K0S6>C#qX5zAAcOOH{OME z7bIAa$m$e#a<^UO?piwrFXq-Vct2sfTT;(b-MlK)iR~&ze-Sk3h+ixX;o*ZUR3nNq8A*We+5fl^(HV> zj8qMpT6tZ109-wkRKN$F&X+*f*s5SOW|Gs{=ybh}Ha5?6g?MOt0HOz)eYOli9jmCY z8rujHT+YY_RM(k5>tuqZWYSRv^)zjUIe1c(8*~+R-_dRkB6vLS&0P^>lSQJI(1;LZ zIh#F%2;YO^G9hNL4MTdD4*a(}1R70dXgFkn)QB{(02Z?>Qe&O*jV~!eNEG;!lAu|? zUCN(1OZpAzWXwN!apy)ba`sY?7M}EPmDR5^1L9?v z#;ZPVzP=_bVtaj2%E-LH5VDw2tBzZ(eh7!~IfbR+rs?AwyR09g3)CU$KZ1 z?s~o|l*ALalf^#9S;TX5pmKR_aL=5%r8C3w19Z8+?m`*e90fuE$g4zS#m4gTYBRz; zza$g8Kx_};PTxcbBWU7hK8p*Qpf#tS%6DoXzw!igkFUd0ifxz~yyd9;9ALY>N7H2) z5eV{oZ>r_U^>6qZ8tC`izn*wr_e3c(%o;vOlQm8K+`_7rw8;B|UCS9JdnEq4UOvfa z0lX!eF0K?sc+WVjvAZ*3HA;2iQS)ABu@9#(d2jhmp7QNZ+*A#>?8I+zfV!1wG`0~u z@s{B4X{ruYz&P;%0Sj`e9y6$ouUN$$*iTk{vb?gU(8RGL*LI5{@y`ALhS_~1sncKY zEjzDzToOVOReapU5ygS`rhdJV1)0t20Exuz)qxomhR1p1!lh)0O=-FhXJ&)0TMZ_n zT-YZrNyUC^r^Pkh8nqMBp|a550muP^_OQO`f__3c_6<-t3BYE1MHDR9qBC7JgaT&n zk7xgU)F@zjOcd=#C}gkoN0EpDRD6XJX*4L~>S^_j{=(R#N*|%q^d1n`O-ktl;CI+t z5wl-?;3v;6ag`9PtTi|XuIcbymv-~_irr%p{yiac(w1`zrw8)fAiNnrDT!71No|Tc z9L0$;h}(IIE2r6#*pK_Awl4r1{yY=b2C9lfF_^sLXd*p-_063%IhK#Z17_{2Dxs|x z+KoMCK9aAerEirfiwS(2=EJBNP>eT-Ez56tDr9ucSfsZqGbx7)NO|U z9M^>W87Q{Fh$|DRT!&K8?>x~~n&dcX^-S=oiryyE9S1%#;aqePA`6SS^kns@(aKDG z|0485RX4fUab=gb`gFfyi8zeiPNU7?kCIJchIdt)Uw81>x%g})Kt5^hfSZ25Vue1;QnnT8)S2C+0?M`=-|&|IaoXYNCJMUU6%D zj??-jsDl*6CbFAO6qzP&Gc0UYS-FXOV9u|z3tzBXYs-G}@^92$qxtAIrg_n)z|E7gWI5^qmdRrlD?E#7%Ufx zoTwySMjbnON#LLW`=r4j(@)rPC$(jSa!uudGV2tu7(#ae>qyRh%hIXEq!+;hYLAY(ox_EX8^%b<< zzFxT#hzzVBCoJ#~c0_{L+SH=SQVIu&eXwbN#yf!{uX{tGRXb7hf zm2(5=f#k-LRLBRIjDe=Obxy5Tte**oNu9sjzkG4=$#bCcGTuFb>f4m6tV?xMZ zODJF*>oG?pBr{+!m?4i=^{CW^#x?V6wh#*{V=4gVHl95Yk{o7ZMwXw|j1STXQP!k2 zTQ262E{=D^v#p$=Wl*=c{|LSQ*r?|n{kuPDTQH}H3X}p#37=jkI6T;JYK4nas44*M z;a34<8zu(~RiaV?Y|p6AWpmb8P#Xw&1B1xO9?V}AfI%f1>XLBWF9UGjxDfXd^N^^0 zC{6&V>wr)wbe9~O428HTeYsiAG~YBBgZBh(pq4u3jES6z%%Ssz)hf${qBedEVKOiv)hg#!&#c?K`^UMunxj?5XBc^H&RJgzEg(&s*Ef z0N;$gia-?)B+QhRU73($R5|G~bh$KRxT1-`Mg(#h^`L@u^Oo^}X&?2Z`7nj>6bXlV z$k@ZUU~owxHa5jlST~k-(AER0fw>)mKNXKw;A01D1Ul@8uso6TcNkC#F{B+3Ep~uw zF!~1^)48r1mDYq_bBIhbVO=Kr2UBJF1H}yD{k+@5eu-Q%X@ozjf?i$-yd{zt@(l=j zW(ghS0i>T6v8?WXPYMa%AQVE;f(1H$MvF`PKN>su*htT#)1Eg2@qNh;>v5#)Adtm= z1>;pN7hsU4;Kc_2K`}AX!}TKLb@m0^^=OJ(6?am)M~-2FFrQt3P+JyR)YDIM1-IFv zLP*psNvX%TNY_RxNs1S%hbl>jqb3#QQ2eIDM0-q2lXz6&;tJZ1lcIH2rRgo3lP^6a zl3k#xVa2rh@06S0kBQ!7l7^4byiLlp_kSg_dkVpd-iY+BD#1!Jg2#-8H5&PYKQWr8X0>D0Fy!IMt^4h{1A&&uL8h-A^wG8 zKT-+9qW=Niq%>JeCd?hSg3sn4TfB=B`7}x~jd8fL>tZ&)MtmBYNog+^Xp~)PbwGoQ zRQVWE_ECY#Q_HC=BPB{lR+M#c_n90zz_OqFG^I$paF#Eq$tYx5TOv&s zi!5e6+MH7|FfcKNv{wRfaF@xNQq-X6b9GeMNOdK2qY$Z=-`(#Df8!ov3ll{%?Bpw9 z)knWh+dXt-%s@T(vH1n&{Vq=ayLhnU5${>Y6B2iO5P&;HF)lKy<{?(KfU(xX%aHk_Qi~Xwh#rd7~{o;vY3V@i}8$f(L|Fhfwtq-4e zfB*USnI9Bu9y}T#p?%{b^OhbI`kLBs3C8048t_F0$o|eFKKk_v3*w&DKRXLk_xnQ} z_RqANKrV`tM9l6x9F0=G1#J`{okvLu#1viu=wjd(>U=-%3F7W7OdsWUYyWfTUGO{c zoB7+2HM@)_TG45nfBoI*iGR0e)iyv3bcTpIBSrI+3~>$+HOkWrW6l%uR8V6F(R9c< zzS_Juy)$Z}=cl6=e|1%Lf*V&F_P)2jaoRR6oh<3hjUVSIegEtBM*52<2Q%5_=N*bL zW7gX~>k|Fsnc7`P1d-FaozJ^la|MpDqST`7Yl4laeNm`q_w}>qvkZKlG%QwX0q6Fv zan61s+QTtGuHjRThE=JQHI?IaqdFvn`=mv^Kh16e=!#nf-*>pB)}X*`M92!C{KR1!ji(y{T*>W}gD?yoC2(4`9Te)V>5I$5tn|y?tBz z+r>>TTAk#m+y*J^Ba_r?3lNbbtK97-#F`CK1fqkiNAg<_?|Kq#pLcKADi&*~wFC;~ znP%iWf&0u9>5Gkew+0{B<4-A*n$VvgTce{hGo*~mb=ZFUu(@UW6Jhlo1~P4wrrY7M z4+4NxS%>{X=#%p6C!s_PhfyIZ6Q?Itq;nrajII0UNlJOo5BTTz2CudIZ|jSOZMM7O zPj2aSYKkczQLfB6#@_lNbOK^SsYvStMAWky%#iiLQEvW;y{n7GX5@xrc9_Zwm`sIJ z4An+CnJ4-A(rxLOYh^HGnhzo|GA|Cljy?e4$}5RQ$VoAO!WY;+n?)$`z4GqBaCW&Q z>QQ*Aj=GM?trLIF&dDf+-^V=%f$4Dspg8A?C7i&sBoXjPk)+Xwe#GMbK`cBy2=VPr zcMLynT)?J}(Y|VmXCMf~eZZ(9rS`{x1kJj16B?te&n@=pjLQ3E0r>!?c^wX~Qft+Zk zH(3KzjO~#Obchm^tV7Zo>@hOlZ5wbDHGfujmyHo=p|$hf;M%Ax)L<}#7Jt2sOh>_U z*~}aaj7gL!{jMx{)XeV}66{-}<~LyWjr{eTpCh9}Y9OJKUD3nl;C5@>Uv-h4sD2fz z6j?u87w4(;V<`_oI?E^Ck{J!U_AEAJ*n!<}V=kQwa@Nfr!V$^yNoZcF-vIE29)B%W zHWN_djY}@$lHaglT4Ku;XoS%0mk8H6KjV4x^l^w5uXaN0>u4#$)|IpOqDWfpOQ|bd zJ*u0#y~TWZeofnADEiY?u;-Qk@@sV%_e*?T1e+TY7j*ewt>rNIO&G_C^R1}?14`xm z>Rw02CJ;aOPftgo-k~u^&>`S(&-z~|Iu5X#3vZWkUv8TNL|(*20#C90$FFtUds*0> zfpO^rJTl5Kt<&=e;A1&32QJfg!Xq;Jb|6!)0G145`k) z$6%~LaXh{4?cwF+)2awo({4_I-nD3}Clqk4I2YY4W71UD=>Yg59bN3M<`rXQN758BJGV>IJ&oQer5ac~b1q z6IQtk=rKrfkD9z?M0L(XUWF%DS2xR})i`Pyb;y0xWesm|exsod)$ly`m5(Qk;euphE0<^dwWSU=ZM8_-x3#>t77Yk?R`G2(5Ig_T9Yb|nfd&A zQhzuWJq;sobpOhD(t9wJIp@3m!R)qUys11Rd3KSwcsM$K16uszxUp^3My+I&R*Gr;nW~6e&P+lky=jTt!q25=A|{ zIDvnPR_(1VhyFJ9Ur&&o{Oi2jFAu*y*Uk4h)ELRZOc5DMc4jiuA7$nYeTi+)gvvRh z86(&;UEEBK^BaQ)&CQF#NC5sFVelZo9i7?E%hZv2W_q4mA56)IzEw^CJF6AnrQQI% z_>Cqvh@0Mt=?8!ZM<=*JF|%P5E|uW@r81ME?B0FT<-q5ek7)cF3|2FH4)$8}$2w0? zRKQW7{P?qU^D7v3_TKWud_w?;39(dr^gHjTb`koU#^px6<;JCXwqRdL)Iatb!JQoc z_geGpUWaB&RL^U?<1zc0p2w!T>5VpT@_wb`b;p^WPclH&=vFhAXCl}v+3wNtrS7$; z>eVKbPVO_SXHRBTB6hZ`?$9QgpXMpcd+lh3j!G|6JQ? zz{HMveYf!Np>BHgzx~_=8^`!g;a|te-8F5~m6XSgEAAN9Q|x4lKD{Y-V>{0^`?1KJ zj!y{N699i@e7EM2Y|0fP_^%k4ojxC{=I3fLh7;$U`G2-^CDo1>nDO-pO#ih)KgJcU zbJw)P-%MJFJvDY%KAzG&>BPF!t3~YgmP)bCr(54lmq@R3)a9N{=*>-T|MQ+|b0YB6 zZi%DMujtT-Ew5?0k8-`AbBw#)m$TUR%1o(|01zCzJ5bBj1=1LvWe>AW(wB!T0&bGo(+aL1SrwdAJm z;MxJ{e3dLmS8Efv z-x~row0l^5-<1KMSK?;b~9=T>iQ%EH4h$WiU7-S}) zBjKSw&SpH6>ZN-<3yc<=Pg%7_WhOW7&@WX`hM5{}CJ*k=Z&gx;wQOd%@b!GVTAUwj zq5WC7<8Cr!wlAgUIk;XPUP(2LDb)>!u(>?&6)Wf%T1^!g)T$OmPH*4$Nn!~moo#zzj79IoBwjHl@9j3o))p6#IS=UP=FxTmh zmVs#+V}#E8gl+l8p{PpeiG;};nED0hxi2rnh)fZ!9>tT1s-dx0s?drYqZ&t1SG>i+0uC( zSE|@zY`|cNE0G~ZG6v*aO$T+dg&fofODV|7zuIF{XN$iXE=f|}Wn(`ES`z-1{|~YC zz?6Zrl4q{q;KqnCqUFX~th@NIzK|X5KVFQ!tsc+i{W;O{ET4WR4lg54Q*a95ea-Fl z;cp2~6#?<41~J?RvSW)zD5A7FOZ`JMmVRVcaP-coYzEPJWtq-M3y5&Bq@PPN6O&7ny=Z-f}j*s z$1nj4C|b_KJRT4F&U{p|{h$9-}IqC+3(ckgi93&T7+m4v2|v3_lOo`}1;SuENi zSpgmrZ~$i;uD=!A&$20tW1sANx*dV1+3b5q#c~!32{Q_9QeC#x>G-F<^bABPncl)V&Q2!6OgAZcpzI7U)%goC!r+6&7K4Q1;BFu>O|X#0dWNb3%?pxr5%Bqz8kEcTZ)%C8bIM=EziFY}Kv9oC~m< zhM>5Zdd3M+4b}#60X7z)nrgcT%ft@R0)B}I>67_th+Uwix{!9FgE7MTV^Yg$oo7@^ zJO{3G{Bv4PRZy#Hq_T$IUt?^X0pD34CaaPWLq{T~OFU7kS#>EbmEPHAW-^_p)e4eQ z>C;KUNMrmzdh!uPL^>FxBecVO0BQ>@I*wbK!@>>0$G~0Y)dOX z7L`3!Z^0^|?qxPb%|jQNu<3<7d#25{!%426!Awb*z3{B$O6JR=e9XDgfJ)OC86MQ; zwLOLo4A^#+RI;$A+$mUtB7>efl;##rdp=T&Us1S-%KX++m{##6#bVb=`W1;@_UAp9 zcYms9qTgck9ZJc`U}eRPJb;Rz=R`x)AdiTp=z)A;iyEpJ&MsB1MOeQVH^aBH&e6qJZPjMj*KW~n+97Y4`C+ljSKOoVdQ^x!N71D zW$}+%FN#B!|E!?n`Kzq8%U2Uzx$Blr18FvON7`QEg=Zu;nJ1>B0T}!d<&H^E%JXB; z`LnEu|6?of?H1m^+FM-8D7C{7W7AXDE!3+v)Js2fE$CD$>6Uh1ZTqdK|LzBh=?FdM zhz+Q-Aj!5H$+n%yYx>nCch?IB{ayU3L_{pk{xsM=XhFWomo$HE8W2ZT8naPdTtK?u z^KY}SKjXeKEDAt0P}K`zaC6Gvys!Hy#(@Q^1oq=#=T}-Sz$VNBu+F&BZ~R9*|2C>$ z8{mcaw8ctdAu+~?M8%iz{l3_y|LyHSZAtL7Mg)L4U-Kd?vib&HyyqqQ?+?wLj{XWo zipa^M567%#?PE^D%gK{2`U-_^&&f%`LZS-CEbCz5_-~c#zmf!rt^kLW6fd^~2bUC= zC_4`q>%SvnVqCo3T&$8}qGGJ9oI)i3f0cjs6wDng-Ktg1cMm7-H63*#`~{PF=pt~2-Bp8O}C+t1th5FR^<_z+wyqGx-7 znjwf{)tYl`Mv#sbjOF;j0G8ImrL_6jAZ?q{rL=`u5rS3^8~M{Qaj;hFC9Fk7AO)|# zJ6x+!*F=JtJy@%xn;L2CI)zQI+ahVmx}OdFnT1%|k{(|xq+2s-_)o#sSGRXjrdB1J z`_p4lq1Lmd;|0b*F&p`c>B0?SsI>tusfy_`ew3&ROx0{jPZSI_0KSMl)z%;ja2>}+ z&`sWmrZsZOVvaG?cnPmkv7DbkYCwi26$@$3Y zu-8o4a2;<2RIOr|MMVgn737xUa|L8>o(Gd3oI)s52Et-NvLMxt~= zD-O|p^IFBAN`g*EKuc+>rWLvB8*lE<=^!YH$VwJh|b43;7l>Q>v@V59^ zSvOfO;EC8`)uJNkL$`>v!>0W`Ve^A)5c0!os6RQ(Yu#-Q1Yqv+_MDLUGbMQBBb#kv zgIV6|RWgHtT}B%>z^=ES{s{w_zb8dk-!9_>yL4}C=J;SCsmW`2OVo3~w_@-KjCtom zXAmfXJ`MgsmGO|`k*To*Dlv-gD2zGYVYx3T`YbW3#lqv0KCL3F#hjz}O4r55WHxP^ z_eeI8Z>jMj1u(MqN(;06&#+n^id0kwLWri1$+w2*P1qVK5X?bGG4y+Cio=Kaa5h<3 z`AgvSUj9!l>;nPCye-;95OtdYbU21D5po{T8!;qK5cgTYP~i4fViKKQI6i({!rp=~ z)5gETB3NKU%W>%^TS>5x+#=~P1oaB!<%a002$(h?A{=Ez6vu=Fi;T*PqeglLDld6i zhidIBW5w%G^BJ6|W!XDnHqvbXu3!-2-R5EVaSq~B@kXWdUrRcC>ocPDECg^P0t6r* z&HnIF%h(V}MW{(d(4Y#U_=^*5Egeme91a|2fo}Mq6V4z}u~jUPZO(xg->rR~1?qSJ zEa3#Oj-LKtVKJD?P6}cP+y=QZkW9^-He{RU|==9R*4ni2&6}p~seOupF@Q zzyup&3vRK)`mVIY^V9T6pBq^NY#$~)8~JdS5omy}_uftaF!XCH-lQ?n1O)4ZMbBcu~jGfd5J7EZ0 zSt_>fNBU_gCe@kn+Lo{kOAPzR6$r>F2L||tZeoWDAfUOVfgz|ue|lv+%-FxaqHlpg&F)j18)Y{hn~fplwJm*_6CcG#Aji<%i)Cys#epH za1)HC@-%BpMad{|oBNf8dh*qTK3i|9iD73Sz_!41o_C9fn&AWMOqucz+Vb+D-3&YE z2-d5^mBTP(IFDJ-eKN#*M*wcbdo%GY3exm@88>W}zUJXhm&il6sW+icCb2gg)S)}Q z^f^-~21j1~->N*45K8{^J!4Znd0^0?i}|pYX)pjg>}?~uZ8PBZVS%GNjN=LHb;7>q zH+9aD*R?&`Ok$ZUH1Pfz?%EQb7*N)pYH2s$DAJekx1Sb@yYj3(8^AWs-PWxo%#Fep z+o@8$1$K(8lVCq3>F|C3$4T;Kwmy`(BTasDgHr15&UtT=RZs-!AwM!5#>o@DY{&sl7Ypgz8(2;#zsCTIMZ9j!3{14d%NHG~Dv*81gUJDVhUq3e`{)`eeo4*Z+@ElFZY{NfV%cWX9^>uI{Iv);IZECp>vcZ8 zdY_|OHkV@5t=l0#7Y+S}je(8PJXZMvIDhxwfs_}bX<7Pj=*F4AuzZrSxJT z-ZK~VN{H6Z5yIQx51}U?rQLb#B|fV#T4TJ!OWGb9_P>z zeh_TA@;u@nDm`j>@=f|^c0ZHal{>|k1>bc#7S>l!2&yts1AErqRiM7Kn|Nd7>ycsU z`&;-rBY>4v%e;2XLXc5?TrB2qfGT%N<{F}FX}4#XhjjMZvwSP(*vNLos%B`UM4gp9 zfagqEqfc(KDLzKtSUiO^l8xd=7{z3Q1a1V{j%=x2+qqW7~G#*zDLH+qU_}wryJ-+fF*R?WAMg-skLZ-(7X@s#;ZR)cm!6 z%&KROF}o58azpX!!>z$tSXh%1_NjrxnlkpAT&O+o>JLf?V$mXy`WS0BcC~u?3r3;^J9#`!av_DVqYB@1cAB|-Pc4&)dxkPe>+Z2z6%AX*gzrFh7up4z z4Ea#6`pKR>%I8x4^nxn)BfoFktiQoF3;5-BgtF$>S|;PDe}`*Xa`aU*{LC{eZ7xs! zjazlsE^WR+->=G|?=vjS-fyz>Io2pkvL%)BwRAh>45co_yqdo!Y6HdFrDKl_+$UU} zR(?ZwzC5xUJLCO{Mk(RGJbMDJlT6RY23q_CA1;$MYlwj`G}=6Nw!xE1&$Jg+8X?f= zi|~NAIvp}71C08%1N7oH3~bZyLLIKwU&-=5Ku3VT zb_`ecp-i_lBqY!eq7y_uOU>qzt;lJzCfaE*Sjhq-N?OnRL(>+8S^&V$Ik(y>;;Fus zdlLin6D1uB{E6!xy9xgJfG!qJ%)~Jr!JRJ-u?k5)yLbusO&*&L7^}`oAjaj@(P_Vs zcaq;)AiAk~TC2Ap=!lCj!a+`je17UmzBq3^Jz4u$nwtfl#&ka()<9a^p0&29x4oj+ zhIjR#M_7YU(pJTVH6PG`Yaz>cEyY0pGWKUM;09KH^q_|$H-(p|R&~3O&y8sl*`|cm zEUrmEA~ZcuJVKhmc909Hr9m!=?g_qeu(qt>goe)99v7VST>zU}9DH@V_Hyurz;7o7 z`(AB8fPm-V#9hycCWo9c_tL}M4UiM4c+>+hJ>ngmdH50<_6L@R8te%@EliIReF-xU z8N@0pOOD%w_k*b+|Kw)e74x^JP8xr&a~0$wKhmP)jMGNkP5pA#4jMRn(=f%w5>U~IK|rbrrz=`fpZ2EBbqm9zpH$o zuG&y`F=DUQ2SEeIhQs0gLHxq49LykA#(#^OxI@v%R09QRAkBUg2`wQvaX-S?O7S#t zS`@?+FmUg?#gUf)0H%g0P0*!C48=Hv>jH`l)u7<=M}6)hSm}4C`^#Cx=l$vZRN+dd zA++A=i$Dtrv3YKKL-^(O#Dkb9b3>H`RQBcU^QvRDOj?(yPG13s_^;v8ZfC$8v7 zi=$x|Lm)M4g6x<5iUDF13>zuzj0uY3aJ8xVY$Ne8TqKD^8>L~5eR%5|`Z`?R@d!`327G4t z%A>owWG7~(8I4y4Z%BWnLH0!;B72A3K;fiJiGl4=6wXq?=vBWMn_?(KW_)TOD+Ef! z9B;I7>&Do`=A+LU{2S)~5Wp8&_N*oj2e)cBzNS9kiHMFV4XTrT(KY||W4jhvZO#`H zDle5q&Nzy)aw+L#_?c7eRq#>y6xJsp^*E1nIfZj>8ma%p7x$Sum*n|aE$vsi3f0Pb zu>ws0%|+oeoT1B#19 z{6_$ehEG|rV4#~W> z;&eg_-%VZaFt4@-u;N!^cul9tKZ9%JUaF|rpzILsVH9?vA8V!?d-ym8S1BMaO0&NP zlRt2Y{EFYPP~w}l&)8+!Z3TpSDDla_iW~=<`#27E#6Sm5tX-N}U-(y`Vny6~`U1T! z``3S5SYG?QYdrV-(uM?&POo!N*<2F!*lJMvx#vYZtQnu9?ro%dH4VX(FOc+##td@D zjJp-2q%Im^+C})JYjuiMosE2u!imX;85l)@O~`b3-xa>w-W7hbBEbAY&%6sop<`fC zgVj;{7cAr@L#aE)xhW1dcViTWQyloK)M#^AscAp-Ea>b*Qv^`f74rTI^~AEEPZyvt~X>AX<}vCB#3Lsbp5xCwwm*gvi@qI$Sg&f zQzd8cm{Rd8ino5~iY_CY84Stx#2}ipLI*5!&)DOTf*P4OyT1$qspP;r@oF*bU>pAN z>SO4G!qQjN<42vx^`G+@5A@+MSd9zeHG$fLsWH5*p|ky0%t%m*(N$Q5NJhN2m0}BS z`r|hI3AmB)IqNZZB>b^n);wVTp^a>tSEz)4-#DGu9+Vh&*e*UK|L|d8_~eV04FbT%%=Lfx;z(P@d9w|r=cZ24?$;6`mI7Gw zWXkF|Ps%Sw?PbHHtzRLT0pvV@Vp*q;u{s4#LUPG~`LPzAifM6CFygtb)6o@#)1_f| z!LHIH912eC?kB9<|v9PGwZj4E9EA-+%&B)1tyiG zsIEEs=$9{_LD*S=#en;fI=3}dgxh+4bK1^|EbEnyErrb%xqn^G_kG(>4ffX&9=yU9 z|6M82c4sB+U4iDDGa8*+eRwVOUMKQi55-ar2#%%NBqKL!F+l8(-&d@2nF4RL!@6(7113%QE{SLeG!V&dL@;Fu=ns z-;q-(Iauy*t{|m$%=v`p`IzJn*`pFtxBMB565?7NnyZpWzHw@d_J2Lgb}Q~=m?=XG z3=;B_uP%2gIib@lrKC0ZHtE`|ONJNB$+b68qTQ@aq~T25WhOQhEr`Ray+eXkp3vFT zVLK5P`@S!Vv_PK?p$C`fMHTtLMvVcr`VD7n5jhnzGYN*CbRz4>d7TC!MU17!s%WCK z#2ech0cogh==~YUBMt>iO-t>9fLOh%itYjdkHrxIym527^ z*I7F^OnM6JYP2NgWVc7glQlP!kTDKSAK;6xA{=tulco$IA(-|>Mul~i8L}v#I0mF& z<_1}hVkr@GK0-Lh3dYI|##zckwBD;i#j8SoesVwSw1h{F>1<^|=ITLtt1it7*g~RE zmS$C(CKIQIc_hok;=q#nVE5}-T-e-1zqDER5Lu&8cy_*$(P>~!cF9%IRnf8_=W0a$ zYXAzXgqfpwHK31ptQ-|7I2f8<_!x{&hHVatSHl}d45GZ@>>|fLGlV5NT+3X}l^OZZ z$qo-&u)@u(X@aV*uI_b=e!;psuyp-Z!H#z!3+jL(R9STww`FiJCitU2Xei-5dG*=^ zQCqo^yT^f)%0})GpS<#Ck%qItaKucR;$`fZ;S~vT1K@L+t#e|W42F>B8YWjPFwbna zZ^U*<6$aV%UHQ$8T7<*re5#;vKJ*58w{q%IJ4|Ops%E#(8Y}-E&>tfNT-?t(hqHjM zAD1m3FUs3?wcP->bGLURwEbjYaGAjH-*vLX|CXHS(HZI;CCzsot^1lK_!ePBjMo?s zr+ECkl_Z&q=&|SOw1K>x>#yZP%R}E#8VZ$~c0>(xv8!SjArdJ3vN9}Fzn7U(B$n-+ z#vu|K|F_MfM5hhz4{gB|kXS%dJsn_4@M~)3dVD{9;_7;MbA1A6O zf=E42xF6+f?K4kY9%-&9Y8j~n&vg?KOjLaPU?UQO5s6Rk@YGu>K@2gU?jQ( z35W-&nZHPY`p~DzRxnVw-jZRy_3U_kPIeEwlytt?B8oa+(`q>@am&&`CNX}+{-r-v zu4R=i{+P5QFrH8Y6i4$y)#MRh_F)Gh^!b^(GQnw?Lyb9iqZD8xM@+B0Ib?^yy^4@g z(+bn)4;W?L1+PDgO=x_tp~<;GmNYAk#J?sdtI&alqy)QdiA_vc^&QZ*fP7xds9NSR z^{BypwiZy+7QCNbYPh+WYp~7IQ32|$7?mVB2Imi@)H11?!W1*Y{JY~;!_a*lyFnt}%Vev+f}qGm4lzKI@sPSK zG4*J7Y>~YV3{Z=~4l9morFf7i(j#Y&3;LPzj5z^{1cS5G81jS-l98S~(TL6}Pr{P6 zejUeq&`!|nZ_-pXZHG3oxr#}rN{d1fKmSMRX2s`NhgwRncrbCHJPGW!d)uLXm-ItK zTEe7@l#2({@;S@pMK|NYkn!~I-RP2`D)&;ub4tVo3={;TDKn~_}#qbjbBr@!;O9=T)a^~`!W0H z$8kuifF)iW6f#vM`+T|gUgCnq;q+>O3%DiUEsuR0-Pf`UD{c~VHoxJ2_;rdH^sQ9h zOoN8?|Gd&kQo;E!t2SV+bTSLD><9+U;-^LBBdSFFFkC;SA#2Z;KebcGUW%KXlLzOh zI+Da4Jv}*FLf%PCnn7Iz&j9O=s#CHO^|p0z2X1EZsx@D6>QyHMv_s{I_N&~k_$nXb zF4iw52`R{?w)mmP%wc=v4bZYtSjG0A&|svD9dTJO)O38esh*hR9#j*lMebKMl$l*N zFd5$LRXdi#Yh=)Cm{l@dH}9-JO?dl3?P}3agoC7%Ht^6Q48n`)Um(-M%heBCCu-&M z15ewX%&MEbZjE<9P4K`WXUwj6CF+Wrdf964TFyhgyf@WzDEQG)Y!t4{@pA&QO0BMi zl^DN#PR|XQW9sN0=*DpSQNgK%CT4HRZI+UJG$pt4ZH)VM|eG9L8ldS4|J2A$FRHPRPTFewB%fe_NPjBz; zy-`Mpex72~luxy{`eyU=GdicqQ>9Y|htaAZz-6Qr`cnJ5Or-fr-D(pI)5>^oTNS&N zYldPE74&s)?e!-M26d*so-Wwwom&MZ+3n5w$p3`fvpDqu;k!JFM1t>+Xpek+;z#IbJRpH3Vyr z(ye((=Vnt?Z*jz$jCta`IIWHwv6f-IfUU!%d({&CsD@L|dcELtEFKI*O7N+WgT+Cj zaMWLW7Jpn@BD%cesmzHDZPHR7Jn5@9H}{i8MuZA%83h!y%-R9oQ>ymNoNeMGl4%EM zHIz@(23qp3F z_anYa?4Qt7&aKg7xPO6;Ad{%FZPi$Ua#SU%?wUxtOTL-srC*LmEh^*AayNA*Rz8vT z@y^#t9#pz^RmU-FvF0b~#_uW*RpJ!xF1)mONQZx(izkXq4KF7Aj-pIbQjUBch6}KD z0>Z1hyQznjJj~49dfoMdvO$C$K@HJ;nMaGWJEB%hxyn%M$&!KNm!{-04yJ;hnga)T z*4_E^GhPKpzPhiq{fjXS;cJd*V>)?-*{jMRX?#5?PmT3AsF=VB4Ktnw#{W&z1O<4$f>TShD2An!@hq>3E5u$mbf);S8lY&&CLwlU$H5O zs6Jo4{N@D1W>f^GAwtVU?i#-cZT#|~-8bGL1WUP_6`l=Q`YTW(7meXb6E$kt(WhMM z{uAt11#axE*)-NpKYfE4LHX}DDiLw1-3l=kqRrjapE|yoGD6N#Z!S0JP;Cs6)x9;i z?y=$a`ExJ%rA^2-t}N(r;Oz8w#xNoaV+ww?&5r=_zhN^#mOfU>F+I-CgJr^E5-B^J zk34K`Pv<(a1-C89zwsEO9jV-!UmIcO1YAnR8l99H`BN`qOl@L_IQrT)flDZ-P$)`VdX%qHE6EtWU#l2HmFGsrAZ6S@q^ z2N#|)6xkCSB~rw1Q+C0t0}q)Lt?)luVTL1rMfBOX6$)l{1Y#z}D}F%~?flB{PR9X~ zT`E9r*%+6unh74dlva@oygP;VWw`hAFsDAK;(hc28MSsvFhAbvA4bLQ#Ezv`d8Nf) z@)DX6z-gEnaoq-h;5E4teiQ`zNRc@+t}rsBv+^_4X_g#Wh{hRN7iAY1fC$vJl&CM$ znNmD84r^nT-K8N#BFk*_RQ9u7C}ia>}UOmAM|P(vD+2>F-y|vh?r^T`7>1O zzuexYUcV}h#i}rVLT_7$pEi+kMh)l2OX`=ma)`i}Q0LL=XS^KeM$5h^F z1Ub!SOXk{W0;Vt5xh$fMD$ZMT{PkGnR`>=c`&zxOeZPYYAm@OM-L`%8Dm7Kc%+|44 z?<>2v>Q+w2y%$~A7_-p;1;4TjzncHPne_Ct9b+7NW>^v zv(Buc+m8{7xH z34Yl1C5-AbV9_n2*)U}JvOT9@fMFl~l(k$K|1UXLm`=^ytMyVEck;=|;X8wBK}CYKx~u-LC-Xs3tMD6^s{xl}$JCrokI;Tw4WE{i{jGB%|=G z+01Zytx5;hRD8UO5`qvR`vxqs3z7jAw3k^q(faR+eM%hfZ5_7fVGS6+ zp%u2(eJ4Vm(Gci2$QUa8+uF}{Mx+(SpPAd`pq^4 z5}=sRI{F+s3W=Q?kKOm)BGN%Ykr#6K?T8_O9O9+5$Y3GV;Q__iJAD5g2D}0X`V@+xxx>&9@n$&5DAf;P{k}QARI2{wvH}=f8&nHL zHKmnB_63+1|KKdvT2*BJOZ7e&HjMcC;pT!IL}l0F^;&-X5$Boe02o-8n!j66AVAWL zd-JDG5=mHa8uyI5dUN~&Z}1q&opSDEIYBvbKwTN8u5Jilc#&ND=YbX;v#aXnvLjq( zmR4tBoNoYW4FtkzVVp;!8$(cGg`r;NW5PK{2j;10+_UFuVo8fZVI$Ex<1yH}Dr%BN zg{DjE(i}!WN?&$DKCv%#n82~cDllR-G<-^!%dD&T3ge)j28+i#hV?a*Tr=l$v;U|% z)-}V44{kE!$xHs#@Hv7I<#H%8Si>f^oVRpn;L62sTt(Rlq{~X$7f9J>ogV)N52iyb zw1?dfWpSMBsiHn1(&D1B=<7^lFzvG+%{>vp&FDsSt&UGJQ?+lwJ`|fV2`unS1C+!o zs&GGJ1nQHrlfw`t^Y1EEudI@pJ6O{~J3sDdjf%b<7p$sVZMiB!XW7v|JA5T_ig zRHtgghg5JE{a&uMteK@M?(SKR_ek0f`)fI9eq&FOY@47ba*>v7lLDA2Q`v^v(`c}Q z$U#;46TlyU6-pA#yIRgf4GaXuq5q;_)T@HFm`>4s^QhR@NDPePC+`HPH4SFiu7p5- zviPvSYqYIF>bcSnNwI!~bb(l4`WF}6jkPlT#LQ;F&_}FA7JJ$Y5LkC9{R?J=)F{74~W&Kihq zDcO?_Ds6c7FeYzq6fAfWxlTG)!)_vB%mOFO-`Y5DMK{Q1WS$8ajrpzOKMbw~a_uJT zHyR8()_aO$sRpIt4TSn(GG)eM4GQUt0#}EMr*(^=VC#`uhW%WHAc%~(O(`}o%sk?= zMv_69E)qh2PBa=T$ZSwp#BN1CgnIk6A_P1H$?&aELCH zp+nEb{r-4QYHC0Z-m8LDWRgIR`&l|{1sYfb6{V$V-ddIGN_N&jONdlAoxx7*lgB^Tx$aZFoS=8YVf?jZ;v zZ%;bqhd63K2-Lqxf=+QL+Wcr+;5en5O4~GT-U0W$tUrah8Gp?63eeL%ckJ7|w)(!j$K)wzpd@=@!Q_mkmg1`P z9-0kfvY*=3`DWzsQ`wy`@2UJv-<;KY%3A>fvy1>ME)b^vS{wU0byvG}dh2D5SbS`7 zGEAJ=WBx=)=CIY1A^4@JF%8MZd?wPli(iVDyPF>JJC3tc0?t=rV_yM_BdfBdsgkg& zj9lM^5IgE6nzgoer13H$zH+*et1G#|gVnfV6bBySy(}MmlS~~?a+^#dO8(89o4=*z zl@MgC0eCBdz@i~=g*)$sjw|nT zB>U#ljh=glvlpN7qq3n5Uof5}al-hG;R))kyZHw*U#a#_bKht>7_j44#_6uByQ+x}4_<$t&ZpO`qA@W8X?_TjfLbwz zNPQPVfX+SYQ}&D6erQ5te?JE<*~=hXf~ZOd7cz0p#vQ*AQCPfe{%q)C5(C&-{v!bY1X~i04nxyX zNhKsGAgzG|3so zrF$<`-0boVlJta$7e^6*-xgCy>mwmz^EHAa$g?0MZ}X8&H|KgExUFO1x=Cb`lfJ_L zK@|2BoB3+jv|vW(qw&-))TfFxyeMf>HFqDp)-g& zNDsPTp448lZaW+KQxj?VSzwC@E`>_4@S{Z9#u}=aOY_&HM_{5$J#*e;1k2~66KrO5 zEXhGekJoM;@A|kU@L75zu81I>#TeLu%T=K|fchc37`>200KMhvkWOU}(hkNjj!C^M zLjH?In@(ajd-4Y|o5O@SxQK$8g)anNpxeQ%%Pkt8iH9xU#R&0$l>1YZWx~hCbEC%F zzmash3BL`>j!4jly!tn11SP`+59ud##H1MNMpSODW?}*{u+@CsfI3)GoZ%a5kk594 zlC(eTs9iF<-Q|sqj+0Knt;X??u+m1EWGM%jpHRDHf@D${q)f{lBpmw|Tzf|)eCq3X zG}Z6Y(i)We!;1nN&4pY&ZNj+QzEW{e3KW3)}y~X6gFi9@e3UkM!4p88G9Iauu9vJtT+GO-`(TOk+0a**LBw) zP9rvNdYYvv;XnO0AO6`ns4Rg%2F(w+dAWK_SO_C#AQBhs-pj?^&MKUSx~A`FtG`JG zhbpFGWb-%$my*`5yFq~~cis^xmvOVsXa zZN53^p~Uhx+}kpbb7tQky8!4NY>&P;1+#A$i(BG!!m4V2t-edB{K@DOS>w;l>j(mC zIzdM`Ae&v^0I~HL2e!)WI%4iqx;S`O6EYBV)uEoGjo^$o`iK9@1%Kwe3y{Qi&_$lC z0c=7ns0e2^H6)NbI55zBJ%blfq6|7Q@hSUB6N8A;-PPu@JmyK8%r@D5HCIgbDt+rV~R)lxPKXA{Vm#(B%Z@1FgLKg|F2^~ z0)^p=rAx3lVZ2fBay$?_Nua5WlvIK#IBBXKC)|Yz>*1|0Ne9MX@7d>vfQT>LNuRep zuml}!QKMgd{pqdg%2gt3cwtafrG5N-qciBkbj_bhaiZU5P#2AJ%6WGV%R*NcKaUdWbe9CC8hQS1cwa!_5L4NUGkF-SzaOoRlaz@@>! zOWs^iT#IZIoXVulap@A*k*ja-cbDN`<-yVub^Xfu(@f=xmbuOZ7_=Krn9-YU*czOL93)KqSnI=1oaniU>DKkERSIY zg|&9()kZLU3qMzxv88bg6?Wd-fa7arC#$C`?Cf}}ADabAxFU*|0PARwXNVY+uo_{? zMB}+9N+ns>nzo+%B=k3ZysYl zy2TvsuHit(0~9-VlJhr%WJ>vjv5ekgxLv_v%2b#|__IN3ie;%EOZ1)-z;@3-<;@3! z=IIjDe)UFd@oT}3du^-`>>D<2e1T-aU^V7GEYWqf&hZkZRKpLLLSN@xYG;SkK-KQ( zWKM{^F2(5<=yc8nGjOdFOLipAtQ-mm52ab^WXP(eU}=T^naZ*BO088S4y7yA8?isQ zc5X`Y)ENyr&Pl|EU@C1pQXFqW!7%-lE5t#xld_pO2T*I)DZmWOOhL?BGc(tG8K$j2rCw}WJ`ty zYw4;=(xHoyLl9@{(!#Btbz+sWSKCAZyETC@ShY(`pZYxzj8zmCVARyL#5AnS7n^m2 zDHS-wfxv^G#^}v^M)Zb@&0)UE=w+}H4>k{e92)zr*iM`KWg*v=z5J;YfC zr%op<60v1u(OGq`z?0BsdR%0LLRAM!w3iDcft&2$gmAa(6mTX5%wCb|<5W%-0F)QL zOXArUeH(hJxYO|h2IYX;T4lM$%5hJLKENOV1CWlFWtR;M0QmWZ^bm2MDIXjd1z`ZO z4mW~WY(M^(FuqA|jnx5|T_nZfKBulhzWn2);?jqIp4*3E!$$D@Z{qlGD~N+NEukKi zCW$#wCJCa259}W-h_pm<066~#KA4FCoc|j>IR6Je{$U9h^Z$Ymt|aV#?7`G31PRKW z=12&N4#vusR=@{I1DwWPOFU?~^X(Dwj4YifbVSY9mEU(=j!>y6zTB!@ZTRds$&xP%*2A9X$-{hxqI_6v{f7PG1N$4f#l5^ zj+3{yq!8&CO(`reyCc!^Do{u_8j@bWApO4mS zYNNML9t2!bA3aw(z7mtZnmfP3oUk-d4i-Y@GeEAfb9|+h$^nqgkl}ghW;9~7XnnRI zUU|q8xv&*PK&-HFbai9Lz5u>X9ZPFy(^zh;KKTU80+80JX1Kfn1Juj|o`XyY)`d4@ zfATnD3@c&j|SLi}w@LF*t5fKu;*!Gnk4As8N1(7njJL|XD) zHUpJYPJi%{UucEuQ6QM}UH$Y+JFr1%=1M{1%yjYu;UQ?7pHB(ty_$suIVh=gxE-MS zl;!0-MAQ&RV19Cfc$BF`cyLC z64@XZfx-}Yy&gh!g=6S4=P7a~8YUchG;YP{+<$7Qy?Ad>;gtH+k#55vpt349fBIKJ za9apCnc(qR8j-Pz?W5-$iBfxHEV|Ynq0uvcfBzO@Y3R#KXM+_!%)odZf)UJJ7Fdlw z*@UQq!igje-k0M+KN+DEX%N7R>{Teo7{CtM2Nu>7Db-mOF4M^EhD{8pvvy#S14)K5 z_)_1~X9!#TrPjarGGy{A_mie5T!vaSK!r7D`q;?JWs#?@mX{b^(}R^I9)FKC1#a>6 z;^+e&74h7;TI|M_+7u_ZP@K1&5JCchdN;JxQ7{(1d^WVzd8Z{hgct8ZzBzk&Rx7DX z!2Xr^+g~jZzZ~1A2CE2r z_~>6XG@U*@9Cw70;*d;ioi|@(svgKwNTTwC3bx&Ufggto*`H>WzOm;!hdnj`i*EY2 zILRFuT}Oyzy&}Rq)Cn@Jf)GnI9pqGhv;=i-yXnkZaQ#9v3&)AWo^G--Qf#F~_gV_D zAl>)RUFGd>@^b@|FGqkx)|%vrOs<{KaNtXwB`3fe+m}V~H@Jmr#Wx*ks2K&_OV?H#KSa zF!M?d&%A|rwBw$R082EwbC7`ky&K=pOiOxhrjLrZYGgmK4I4;nv-9U5UQh@dFTQx* zY!g=AvxT)ul=mLb1x5}lY~2+CiY@8hDfOs51Cs5bzfIOd^MTSvv@LaIR9QwiK@47scuUA z88bP0e`~ea$wFY*8C+M}9bD4-`~$d~j;M&k#V$b`Y!?wR_?#jFFxS47MJ=@MnHuzf z0z{#E1ers6I$n=O@`wkMCEQ5YOKv~RRsk!S^D(%!oZU&W@u8}N??-CgSo?M;!b|KtfM5vdD-B70~ zx9D^x2=pRm+C5Ghz|hp+bwi8y`dfr1&83<0483>9kdCKY6c9A6VQt{OSLOzx(hR*k z`wN{i%r?KO+(|#qdHcA1(3OmXss6y03u2pDgv+o#po}8g{y9C;-|CMdNZrAQ5zKdT zRT=hNXTz-~<# zJM$dgVk-JBtR&z$Si~6%s^4Q1_fS|}SJ}cSCGKSs3e!{*w>8aSs_Yw3h@B+{x_)qCPOPdJo7?qjJl_2*?x@Jn14@fqNdbd1G6scSg|J%V9;@v${O4EaR%qXH zzjYv)$|^*96)?T*wvAIRGONFm;k?E2 z!Oz(8kT5h%+n&O*ld9A0db`+85{)e6YB@4s8BUND^XkTC8O%a7{$`onP->n!< zq6=xc%elAVfkv_k0P#$9XhT?W5(N5yA&mPsa!bfQ(0xo9{+$}p{toPU{Xn!sPaQ>LE z!e^JJ+m8?_mT$%ph0YLSP336^x#w1-zOwk`ad-bXyaC^JU9Y_{MXNH90u-AT`z2kvI*h%YMm(1TlhVzL%F$>3WMs~q zn->{_KmM@MSm>;er#TOhGcBWh^6YR#N0wMJdCH(N%L7Bk^jegD=S{_zChad9hd-o2 z0}iknD7;BIGg<76&cE$X;rkrMTP`HdiN`{`QSFDD{#exwm<4>5k4MlmO^tHy6jO>_ zzi;cI&?`v)DV4i+q1NMZGJgfY{4BNZK)Vg}pc(O&m6k2Gvx4`)_ zHW+0$0v*N+d;m&O=hpxozT}P)+Z|f*puSMV}DbVBBd}fRwc0d9A*89e-unp12TZi z>a)Xt3nB?_g)R9f7;fnj+I8q^E_6Enj+z~9yK#%f1^KAti7usgX-mUhWXPNiezJO* zA8UpwATCie2qRngEFjUKF17>}d)+3!Jn;C_Tb8$7dTR*HkbVLgwb=>P(Be2&|4gcU zGV+L;9fV=!=E$|zUyufx3S73%eQhfkL~=fR02?)L)v zCK1*(fY~oVx%ggipw44Nwh+zWi9iw}muBW_W`6VhHdYh4)8qD_Cw zIcwfYGJ5arCnK|Yh8n7R0KY%GW#}GuNOiUDMEL$Wdq*7~FMwc${Z9`J%DlTB+iP3( z1n0|a1t?p8z8Skk1uo}`0d^6WQOD&o-f!QeYrK4j`4?b2Ul8_dJ@%D-mEuvG$mgD{ zDoaN;un`pKH{);0a)v?9`&~Q zZtXl2e+9#V%3|}z7$_K#EMIwc*h#<%l1mC=m%6aL&K979Z-5P=mD(ek;nv^z(cTIE zuvysp|ISWq%xS_h*d&=BCl*HnK9jp1--N zqE{!sN|#Z{U`*Mlf6LaotGfTj^i0^~xWZ6CR2QKt>prV09r4Vu$sD``E@~^7_GZZS z0`p7!%q`s(E)~K$;G0UzEPHE{n5Z@c=CaQOym?-TJGJOYlJaPsR~F3_{&K!U5&EBD ze7s%uT5HW#wrlEtUc99(WuDk^S~F^vO0Ub=SFYOy)YB*7`FsZC@^-dn^;F(CU>}O$ zF0@|_9;lN;7nVMvm0olK@l(#g7v3v(APMEL+NK~!Wu|M44Fd@3$ z=K0uz+&M5Lynn&~SkGEfv$cLD6YRD(yP}CkuNvEJzUCPRz7QJ%cMYzQ{G7Q zd~IVJkpC9+v3yFzX3J2N!``~*5gQvqG3eH3{iN>*T+XOd9`7u@uB@@OT=OWOsZLFe zExoF`T?14H%&KyG&?Eq0p|6HsI>U4Xg0iWPZwn8?=Y+85GHP!ZUoYb7^x*t&V$zT1i z&3iJ?Qjl4e`k|b3S8Hc{>z=1r~0u2$MN&3f*{{;ttKYK3QS4 zN-8Gp+g6CQ^GMX0`8R6H3_l~wS8q|#_t3!jI;9B^&8Aez25P{dJIVv@<39bJTRq9d zv~NQtEUk%jH%;(O$^m=#`7kdECt;e8(4(B&Vq{Pct~~Pc8 zQ4vfI3Mt;m%%~#tXoU*Sm$3fT)PFipAb;N*WHJxj<{E@9_x-TMf11(3DIWGtgc0Q3 zw=xSTfenj}ORvB(ymVBc#fMS}KWtKJo}e{M`beI>eM4{3!MKbWUSO0f3v3nSr8A#! zIwsyxCXHznzxokW;Wx9sHC}p-!`!ZdK?6kWJ^j4D@4V-~E7v^vYY~4phKY_QE#G<@ zJUC&FXid`-_=ZlNRqsWhut&aVX$2Kc5B38n30wftIC+)ppXW8;QE2%El;Z$1axw+M>I*+fc=Z;A!Ve!Fl{n6ys(&l8>!r}xu z!P=5b3X?*&7#1b6LZVSBfi*)<`Hus2OW9g6mg>YDlOplovo^umP}8wcj8lt5ro0m1 zi0)1 zD8=zeHqS*`R&5#kWti$RnjM~2Encrx$1GbA12^Zw4PVs8g5S+fqpLa5O|an(Y{+b5 z!wq>9s<=&+{lmxDcuJ;}>)QBHdpaR7XMvNs)R<;ryrIu#MYNqj!GKmmXik)6f!6CkqA@maelCCJ9ItvQsJi-Emu2>>uGws00}~@tuvduF;x+8=lArP z9VY;pn;ki26Zg_N)Gk7MCy+Ipin`byaai#vS`5>2U-rNS1l_)#iHzL}90a!SNfEwM z9(qT`YifSK-EpsZCqu>9nV3nHvaF*8Z^IQTYfRGYO#C~s{Yp3QXIfB6kYZeBs0!ru zrn^^d5Ly8t@~!SpI%D|)zHmQqBxf*o%&ioU&9>WXI@LhPZ+mm?nw>_8H3Bp=jhO$A$=fZc=6xfeWkH2Pus8A%EtxJBUdwnvjX>PKNNos@hs z`JBZk2a;;sw0wpV-k(P<-9FyuZ7%!XKWpvsG+izVHS2R&12o|r4047CO8|Q-cT@1B zjk`+76aI>Vy_)VaM{qx&LM^mb+@aGSYJtvYkPa+C{oY*%>a)n8SP})s$&@jO1EaFHEw7CdSG%vft8R^V|bAgcO zMJohU`bhIW$lZ|kkx@IQA8@Fr2p25Gx>+V%?J59MHPwg4~AE^3iBre6aH>EI4IZJuG)FD6m4F+y}4ZcNoBhBcmO1!Wvc0 zV32ci^5}zNa3Tf{Yy^o!KgU4BH_TtnPj;6mwUtyuYi2z$ui2tZVVZ{`7ytPknvXzX zFymZz?UQ+Kmd-prR?5YbneA3WxT87_SD=no*os0Bs6WwI#-2_Gs>%k(ooZie0A4Nn zNOT?-hjLx4!HieJ$V28jj#ELhq>Q5=u&8T4y&O{U!Iup@OmYx8D5W@xRTt&Ln?&-r zFce|q#$y#eDATa zvZVk!?NW=W2iGVgH*V(6gD>vUK8bo;6U?Jn}WH$ zLZ!X2e~i2fHA(0{*iql^Eh3=49Qlhwi($|Dm&1XP&X6H1Nx6(Mqk)t4D0+_^Hbjlf zCrqcIq1RtDAjd7v!K?Gw+rd)gPTDO3X*v^%3Uh%{g8a#b;EG~0kdH)eQH{yCHi>ZD z&pG(N#>7**g2Ka(>U(cjH187%u>`*AdxJ!ZcLmQWVO?Ws^--0|XFKSl`dkAb}BdrCY zAv9@*xjy7^P+q}w0ZT_lKvknUa31AQw3M}u;D7^T>mQn2@+WT2>|oI#Ra-1gdJ<}B)cv;L;xIj z{1{5EWsx0=%T0(@XY+!EmP)p6JxE4I1&#yByg~wXI8-WH9XyGPhu2$>z!`5?IHXm} zl-qHsd-00V42&W0+A5K|KH9Sqm8NWNSYFz=$J0hE03;z}jLmNjDRtsB)xxYSq%4LP z;lJrKBF>G%@@Ib))n+Cm$%|Dai;iT4S6|I2K@+Y96Tqw`#mcBVtK`ZkfQ9)pQHYtC zQOW3w;fpwGG%fkJxF<;#G^!mXQ; z8~SF&@hu~VH)ao}VZV3FfisZj?sI$*jhS}YbuyOD5C?%rQPG{#>+IlZ*FRzxZxKH( zCyzHR|0-G@v9{JO88#69CL}0oC-U7TqvG;GfHs|PeG`>t#|YA@Y&H4*v`%dl{Q)&6 z8b7byYDU-JbeF{b2Was_eZ3*A?D^@YrF-$v>h(F;FVOGe9x=e@&&_%7sRv^nsi7i1 z@}pk*Lt&up77BA^h!^|Z8chU&QEy7ko_3;IYr4N}_w-`*=(IC*eX}Q@sGRM$MgjV3 zA!EmH)7MlU!km!fY7y4`a*viofvh2d!QTYy0te0(OR?H)wiXY(0hVw zvsGB7HP8|D?~LOJ;$o>@HaBkH?d~2paNZZvGQ1gm4;MVTfDGQ=lS^t+NLmP|HI+;{ zago1ej3N^s&=MCSZDfo55GaXhgye>*{f2mnAS9mNC#)B;AEHB(JtW;V-fypkiumDI zKHuEy4z5p96*OikU0gEdbeM1EXR$*W@Y7d9J9si_nfdVyEqJ;y(L`G`d*A#_6iCa; z;X7eH?OG=sE>CV-JIZD5j~$kEw;NG3AK5$@@}E)E?fPz1P>H@Mki(a}>pXVo5cq4z zp4o+dt9lC&a(=5bviwQzg5U77xrK4|DnlfHi`;}qq3{}mL_s`j(2?Muvm(ypl$*f= zo8qD1cU~el9z4z$yVvRqSlejsTA@?5SzakE{X>8>^uO`D|VPQl< z0u(}inL2`ul-h>d7-~1{@;f;bgQS1> z8zNm(Jf!M7h1aFwYg%^(F65-Kpaj?`*nBL`tJdx%e5Df>bfn$S3n~XDI;n8)1cn6( zt-EWO6SZI!7F3XvJ&EuURK0&xsA|IH4p;aZPEn;!^A%U!!yLEpDh;6c3l&!KB5Dlq zp=Pb@ILdspio4S>SV4FIb`_!a1<|Lh&sH!# zB@q6@y?FlD1krjbU$!0b0%M~bH*W~1MWwU&^t z`r`SEtS|07#n-}9Ty`i2@ru6(`+Y4z&Rw{#sMmAwi50V`M~784^V-@r)nQ8(AeNEu z87hXv={|^X4aWGwDn^-DjjYyLaopJ94@0e9$4*M-+PveW+)H$-{K!vjU#51Q;adn3 zB&4%|xzoEp#x_=Sv0RXBCpPu!RQdIpuiu1mLD#Ud{0afT^ZlWRlr5xG&bCFszMB;>y|U!`<4mon6Wa7) z;EKa(<4*2w>yGdt=lH5p%Oe`De4*Khmcgr4PIclPgNh&R-<5Ys9=Wo`_j$5&G|Tme zTX)J{gWn--Dt;SxNyl&dX(&}0{YaH}rNPjBp3Ln`YI$Xnc0(_YEw z7VG9TR=y^zp1jQNPK8P8?mPa<_$ce>Td9o3AM;k9Q|j~x_NUfh(2|Ej)C}YkaMjhEqEHiqE--w=xl_k)c#-Q7mC1O$5xW`CAQC(g&GBh_= zzCly(|M|0B__XZJid;+JTxhmcE*+cZudIlm*{|qUG#Ie;!mlx!uusyxCTe3cZ0OV9 zI}U0$WP8Bju=(<3Q%;hGD#@3n@;k5y>ZXy13%@?ptaXTdzzrlDuWiO z6!JqLfoo$*pCw%V7jye^DI1#3-pvon)>K z@p1hf?8>bEp}iUIu4TuSJM~F~adE-s1o6@r5TWGIW} z8SCZ%`iN+$MXs=E8_{i}n^ik~#Gs~`h-O2VfIYgoBlix?Z%Z=13icO4P zEEplJea?TQhn0&2nAGu5`%^l-vsP!h5oeIOJ%&$j2CTY#M4Y{0ikmF9TO7sCP0@(8 z;osA_?mN52jqnOEopUpfGe<0XXIV=7%7$gVs^YEJgoyF@{7h$rFYQPlar38_i!*mt z(LRB=74OCtX+VgtMu_X94c?>@NJ~A`M1Oy~1`(?|Gr5L$lkXe#I_N9^+$g;x?9;R$ zJ+!*mf!eT(jz|70XkX@Jex*YRv7ncU{?93VjP)rV+LXS#gu|;~M$C_98r`2Ni5Q}l z17r3yVEtBVdTy#PY%Ux3>_mO+T4ep*s}^uf9WY%XzTy!2GdL&B4^BE@s(l-_^AGicaymIb=9gWW?0g~?asSsqH& zBopU#bU%x=!S~{9jM=((EUzyFx4|v;rx~iy{;D{GW#jyba!OZ-qs2@VKtC9ZRMvq2 zKge|-@*4tw`fgh{K!|95Dsgf@kO`i0R7z}V`XcIPgPHw=AmRJkC;k1UOr}^@NMsFz zLpwphZ;|!Bo?{sJ8SH}+Hio}KYT1rMm_JGvrkgh819SAJs)AKgzS~=}2BXw{?Iu>q zbb=`vL0-G=EJ$xe7ou_>31#glr=9#9yF4;E9Z?IZv$E!>E8rsSAZ(>8H3Lb0RNTgi zr_d&CHpx$Tgl|%FTg4`&-@*?_(T~^u=ufJDcG!ais+Q6|-Do<{_Tra1al26=f{w<`kl$^+DuT=rxfVU`IonE5R^{zYxO=KZ0I1y<#v~j<|0scvt1pn_^I-T{BfW#IBm_elZp6)( z6Z-xA!3}jLLUeSzv!s7u;TNs|{i{Qty*}%B{JmQ|p3pbj0#?(+bWCp=`Xqwzk%a;^ zi_KcA)!X@EE4y4H9j;|BFAGvQja)-2{qw<=>}umBJI4=rjBm_hq3#GADV1aRl*LXE zrA>3>w0VNvbcDB9ohBouyP=WY=p*reSn;bWKF%ghgJ_EtQ{cYAHe9E@XIXMB6A|Ij zQC&rz>0B)pT@yV@)~LmiDH#wyW&eJU+!NZRTa~T5`p1t=qpT^G-tP0vcNyHtm?>g^ ztA2)qa)q+Iw72QG-5Ar}ujJ&=x3(qdA^@ODZmZ0X{tO)bKo*Tfh4lW2N}xOJEd!i?vLV1f@q?(6GANqN@2&Hxv1EOQ` zR{F4&J|BcXx7k$FX)2|Ppwgd295Yfte2$NouN?*_Xrpi--&89f*~cVL?c(B>w7yA)yO$U#M)^evI*hKs>=njy(HCY zKnnErZN}EiNrO zN^VO?pQ=7-4@CRFxrNBAesKIzU79G8#)|LH_olhTE;0>)v1H#B1D7zfjt8=>TuXct z>uyh2q}@+2=M&NV$2U@158j3Jr#V%!WtEMAnC;ZgTHCpdCEU-c1QIo5%MG~qxh zPGNI@(ekglZ_ube>B{}x=cR#gF-LFyPLFjWf-gQzD_?CsGS7f5>WknHyAD!F-Rpug z3W(IPLsBIDrV}PR9xU;zQ}-6X>Myf%N_|i~U#giaqEr)C8`tt(sy#s_GCW=N*Uu^r zVY@?JVLfSi8T|REdz$A8Vh!OFzom=1#^_!;$Eh~cB!c*cG;BsJ<{Jjkb7 z8Af8(wMFsv(MLjULQ{%8nmL-F0k^_NEbpO{W3@Q;Gxgt}8SeUdIqhe1N)Lm0b|JQZ z+4@{f){@?=tR9pvCS0AQJAA#2^+4L?!l)SewnxLhYhmN>N>-XBECZD?~M$aWp807%_ zsm1x^74Pn9jTo(_jzA;jNq%Rqt{egG#Aj`Nq;D7XH3+x%HY;BpK-ApAU0QXp-d039tYVye-NP`triKe|vfSRkaniy2} z|0c^2p6*ryd!o}p;74H~%oQ)NDPn+B>M0~IG-3f^G!GIr=qBKk|HCYv7b4A zmnpG~>x$P?*3vAz@K=z*J5T*Jicx^jaiH|VJ>$Df?hQ9b&012SIZ&<;sm+A zZ2&vEzU@hoa6DBi756UIo&DhjkXD9io!j2uR0)C)F9oj!4&RP-$^{eUUXW)V1aHb5 zBs=e2F6fYw-^$`g!cLOj<&mpYn&-8hQw(TVIeE9B7XOSj+9jFH9^%i4*KD5<%k}0J zLf`T?OMg!kS08979oWE{B1HsAi~sc}cg@HCM$a6pP=2o`wV3nG8@3?3Mm#!`ZlPud zzjy$y(@l@v?sq2oVwA#YP==VtiF zmSa7y!&0McGWt+hcXfLBQPOl0cUJyXDT)`#WeUf;tYtWG1VZWfy~O1t9mxj&z$%gH z5h@cCe4gm&FSVB7po|EfW-%5^ zJ+1p-^*Y2LDYfI?0JgPY$jy(Y(pCfi2)D_s0o z`9)=d_6XI*2BjP{5YbOxFZxTqjB>9a#c!Ey1@?+%RHSL=Hu`Q%7^P-fy6o6XcA4I> z;d~|B|IYtdck0fKcbm~7==R6&j0h)f!nA){M#SZV(-#)X+#&9kY;Fi9yoDVh4`RFG z8fI>@>B8}NiRpdb5juAV;+2`bJjS1n@R3i$?XQ#65r4FEo1A?xko+Bt@EOJ*8b?O# zE;4zMtX?TgrPfI2AuvB9Jfb;OZX$Xy5~gp}wIuihd=Pl-gRbFS^Zuef2G+-^VoSyO z@!>F2w7_K5S{2UOXz>B^hYbHzEQCC*0rvftEBW^f6|75glSLk}{P_nbX?#a^I3Qw5RNp^LnBn^tnPCoI)Tu?dIV5-*K6{0bzLM%yij zB7ITGEik8_er~&eA^1M;c;#@A3QH@fxFpGZa*8ZwrUxCbV^K=&Qdm4;!4P#ta8}$a zxDbU+*qI`?3|gbQtW@yFJhsl(L}8Yf`-_-mu%{D|$_BZbLn8-SMjQ)VXu|61_qx@N z+G6dv_u9OB(wXXOkONn(ei}Zo8H#QCOak)B1ib`^dT>KO(n?ZJN34LSnceXAK zp$^zLBkYC}){vD>EX9s|DJPa3`N`?3O{+=NU!>&H!q*Mq=}Ean(w71Amy7t+$>8?l zIyOr6-b7{VnFo;gC%95>2cFV&@`9!MXxVQpig12->I* zGZHoJ!)*aqhnWNhf&A0;qY_x#nPEX@G?IjRiL%k{43I$7mSM`p$}t@i#$}h7dg}8L zikSO8mxvKg^>KWw7bcOvmXV0jT2^aFi*~y2KntVsnf%Q2G{kWGxI}!7QboIK`RvYN zzvlH%dxw!2b-Gar(5!y1Z!h4pa<=7p z<*N4!R0t^%Fc8A3zoCvA*oz(>oOY;?j930}z;^^)5#CczK`GxP{0diTpAxP6QC3f#eV)pLa8 z3y)8;$m9d031fqOe$?2w9v`?kPG_itm*V`fZ8^uxt`UzlDFl!UJ7Tj( z-2HB{nm9uhezcNoD9DVA&2EuI5o;B)Wy+NZ`F6gv8lCO-Mu}OaB*tHC;y%S%Kc@L$ zU`zrr&9$d;qR?DL_bm?^;KaNO09jHNbHH@tOM9BW<;URbAL9Tr4u<)73sossO9 zi&>?x4z{2`J^b7$i1g{b(}S;JJA6|VDN>OCp7c3iVq5#8jH42&s>TM_w6R)Q zm@2;J%`vh2IXaB$aDh%9&l*E{UHKQr8FP7tnjZK zyC~9O1Ju7mmxr1=ir(ENCV^zD4BaiRA$D7Rn?s3w@gCo-23t!1&K>ztGlyM~S)!s( z^`ck{x>hi_tg@-x@@Kx&@o=ix zb^9}9k~Z#Rg~IbXE`1ckgm2lbmU}U*z#9?sNU}w7O4T7_jstoqfEe*`rPCy01hI;l z0;gt%qg>r{*IaK7osnTws&{Pqxh5ALP|`7ZuGUiB9vLhvu4^$T4k;kd-EUe3+$f!w zSeI>g^BoLLk?OE;;4r^n{2HROndIu$v&KkwDOoJ1Bg>Z=^yu4+a$W})gUXD4=}k@D zhoRlv!F>KL()J_g)iF-D%b?Ii3UDt&;G8T}Pl>+rMf@PC{Pw6i3Lo)6T-8X*j~5c_ zcEp*zJN6WLwz#y^>y*U9Frd2?l@^<<XnBD)WNOwvOQ|g zXNk|D{9dr~;)d{L^3TB#+7r6pu$&s+%?;!_Be5bhx%q_rQ=D$h1X(|KFGGR{iu$3y z1?%f|N?w&0Xs@NYBiUvJSUsA&PI=cN;EC^dcr5|G+H1Xp2sS82fMnXYJx%KOsU5FV8a>>fnrJ&@p4bs4`joJ ztR-g?k?_U_vKPc?)EX{oE2U`>C^g_vO0<`*5^D`*4|n{V4~kQWmBgFGV6GDoKucxz zIE^jPp?zHZ$-ltnaYHKIY;4y34dpKhYvuGiZy>@lvpY|gQs-R`WHiSs)$JXoW)KOl zNFqqiPC(*8Ys3_x@CR9^uutig2$2KrOSKy}3Z)HOLWTazyTJi+(Vp6eA>n{iHiD=o zsVvzZdao6F?ZQKh?t4ikY^ljj89Eij!Oy!2Y&59UI-{ zCjFQhjFYQyKmBcr5z@?XOcMCLsO*{#Mh6yid&7=Jfl=<;OEwJoq(MiFYn=O>pU!Tt z;I-a->MUBT&|A_H&ns5^NUthi+ow1DL3U>N@iDlkqfvci^9QY1ES4(VomI#R>c@RL zWjzjIS^2v}ex^9Bz;Gd2SG=;l!38SCWVr9fwaB6pR6+Qx6g?1AjSX?X_VqR6S`u5_ z4^b+U3Wx}Q94Uey2|nVFx|qmU=om9O*KDxg`)m^YELS%{9CeXzhx==DrlokZ@ZR`x z>yaZ*g*69vt_}r<-d=&0aW|V$acc9i=WTShacj%{9;9LR?)d+W#GZi||I;Z1XXxc1 z2m{0it>r*qgk)4?8YCho&*F>_MB8Hw6QB=bMTL`Q8)bkqvv3rH2I@jZWe zReb(9mGX-2fBSGkp;N0(RPE6=yV%+iVVOMz&&K=hz8JDWlBg}OtC?x|?MAre7`ATjru)YGmiO+2$!VTkHxw3kY?3CS)MHmGLv%WId+3|tUl=sHjjT~$=mX~v= zZVqo}{C5yi9M-8T3+^0KWak_n7g`|z5*b*mSdmXn!OT6sJntQ)^}xenN@ivY8Tw$7 zTS_D2wE>w~Qq3$uDvyTbX$p-G$TMwpIWojdhx3mPgx34xaHUR3jQ!+NSUnDZU{?7Y zgAtRX&8VCGqW0Qli>=H|Uh95TmI)>LUY3aZIw{B7S>=Hk z#l_W~w0jz?g>jTE75o>iB4eGrb=uwjL0nbT(|wTHcdsxp1`!7OGhY|jSqe#B%Jg3* zzP*^+g~=vdd08c;emb;Wm)ln}a3(}=?BdGFcogn9lslkfae>cxm|4%k5S_TuvO2}Y zEQgP!tDH@qcRNrQ>m{D)U(=F9|2XXhDP(r{LuI(i)SX)C9K8NYKP6vVW=|mPv1(hb zt(*YCR1~R;12akRTx5$XNxm~wbf#r|=aD*wMxr8P%3II*nnAd<-{f^YBXJ7%m;Cpz zpcp|~t9-i7{`3it*Oa!jeZ*@@vI0hj5n-P!jva}7UtPf6vTq8!o>ZYz!rL|vq~2;(px3&C%fihBoTn< zCq8`>$+IfLNr6l(w)TB#LBZXnwrft^?4zAEGgI}ihOg8=7tjf8e!ph;jZyIAKWU0X zwo3FX*_7b)^>FCd=}Xb;0?U#e%90OkQ88Lce>m)VVYb@7t&T-C702~kWB5$WXc$W_ z%GUb%RDAu!w_84une}~vrykeu0HW9iX1q*7VtXUbv-__3#cwJ)EU#W3C+_|1JI%G( zwMU=vD?rTeN93!$5E}Px*>JIp*A$XxgGg@wVS(1s4u`-PoJCKe{kkjA-ui69+Ui&} zVp@3qXj0ktz5y=c9msHG5rfjxOFnW`cIW2e#)arHjUZ!?O@tdf$vUpidrMo_v8)tmu3vj>B~SZjhrI7#LM&S_xf_o?boF>^7ZiStPX1x*wp zj#>*8VCTA;gI0<Q!eC4yQx-qtom}NnWCs~WJ_?0sc^{9?$J@Ipjek{DJvL1>@dmNDkwSr~!T{Thl{(fJli2q;k5-Ss}C zk1FYw$LMy>@OIkxc!hnG%%Q%L{5Z+t|iZVT=>n2n7h6%8cj$s>ZG& zr8in=BIZRGg5O7ScVA7+hlT4nCJ&f=@>G%o99&*ZQ6=Q6QYv4;9Dk3WJ!t;FalZqB zd*$w|r=i}Rl?ep?)L@Y)Nro{PVn^4@#SAiOb!%1H??Lt}F&j;eDWU3U5{1}7Sils;IIRIC91Gi@iKhT5q~=%__&OBoI0fIu!>|< z?;-|O$8;n`OlTlp;rDDJ3P_xP+91@RBMj~D)0w6ToRIF_=;Hc5V3!sJ9?O>XR1CGc z<~y%-Z2152fxJ&g?4G=#kPtH4TWEF-i0tX6Ka`CMjFaqn#RBH$PcFRTdHR^YdIfwy zO;$kL^@rEeNU+@ez|XriAP%UAGsp+bEs$J$fCFtc0DnmKS;KF_r~^@efLtJ?KXeEV zGz*B(U|}#W^cy@V6vPc3hk$UQgI_?_PX%f*AROoz0>~AXTYwL`3Its~5ckc|DapQLIgIs32Pq)HM=> z*F?z$CIx|bk`v1DnuIYxfc)=n4)n+yMAtO>2too%p{g;!m};;)71&cR7C>QJ}FjS((g{!;R2&hI+9p7q&<#Y8AXIeHAl?)ZcnX-j7vAaepT*Z<^m0rK;) z&g7#j0x%a3bUYEH*Yu7H=wn^=dRzX807Sh!8YBftZId4Qi5%5nZJe%4E%XJE4&SKX*j+!)%R1T>4>1AU_#-d>Xybc5Kat zhrC@rid5&u z`KoN(eNTM1U4V$Mi`6~&N=Pnfj>Lll-{6rN_GFNOEPr?&J<^ziwgS5)g;j-12J+%{ zaop&M%tz_nkx=#+eTDJe(Mf28`LNe(T={Uo`mBhgy+ zQQLrZ=8Z~Kem0W2@uizJ21#pU|F|KcP`bsBqa&UDtX~JRVbn+vrLfqBy9iddd^EWu zS-5q!OZ$l%r9Nm`*}eOs2HmDC2TrUj?Q6^L@yJK65wV%*yB|iJ(q%FAXAF2_wnAOv zGa^JGR39~M;+^-(>(oOAXIOjs*x2iqT*|M&-SQWD!@rf^IWkm_bC$X;63#QYye`Wg z%H6H_)-sfig%0OKlF(7=HCP%jEGV^O)S}H1z=Tqia%8&uk|X{!t2#sK;S;3N#uSdB zq_!wP)-C6rn*niz0=}4C-E=d2rh5?i7A1qv-qNNy$d#m}W~YeH8;8I@fockk7(oyh zy)>oMaY+9}egrmF*4vvB0dcOW`*k;+v}@;}qem-M7@6h)$A??t^-AByWASFC2Kv~} zOR=^bn;-ryZ^}Dyox6f#vIsaxBX%hZ`V!w2n20PG0x`8NSX2;t!a!VCXrKmLV|`DZ`)o==PeGGIUcMUeqy zZa^0JpZYwMJpTg90QtOt{GT1-1LXhg5I-RQXNLp;`PmKu^*Pvq#FJv-XUhecF8=4k z=1)a{?c)DWHwU1c|M}$kQwgA*|3B>(Zu|!ZD4zwK#e2Loi08^Dy4$^_;;p6@1 z3s>~O13>D3JR^|8hKiPeG=Z$=sp*C`I{#<>o(rE^Lxo)auRNeR|MP)*4(R_jhZ?#4 ztI-Tia0jGCX0QM>w;ZGm)aCxa74!4_Z|a|7=&bjDElGXP#*U7}c|% z2J)Y_1kYw0#QW@#q4!SU8K41RDRCQn01g0ZR0KGfKqoNbll6{(-W37!WfYHq(4>L{ zrUOB5ih*?Z7Z5WvUKA|xq{_4pv1;`GF!ZVngr3}bfCxSI z0=5mjP&H5Boq6`xy5%7BL^8xDEB+07T@FG^&MrrMvg5#@#Snmb`RBnCDglj#F`yUF zC13CwRJ#gD&f@?BU>yg^Ks(+6-934ApldNdKn9F_JoG~ip#Iri0M5M&#Pz%_${+v- zfqA+9ZHp40KvU!SRCsK&xcs5Q?Tjuqy?L3 z5fOwIEqpIbX8JdNmlzcXn|`dg9ouwkc7X1m;w>*Ow?5{cy+{5l)Hl8QaGDSv!QFRH z8KUNSz35lfJ9t_+Iin#SB(-Mvp@jYXo&ABJiA5COr8Sq)P`g_b-a3b3>oyHCgv*@$ zcZbd-6@>ZcEy@T{$pbgjR=}tDfy^OQlEL-fJZI@sX(@7>u-!LrJ#1rExln}g9T(d> zo#RXRhg#RJx9>+IR$SEQJ``j*Yh9965$~T*seF}A@>5bl9?V}obzjsJej|MTm8+*6 zmjV>2US)2P4_SB-D+wxzZ2h4q0J-c!;fkrk?sR;cp3L*xj6sG*L&fEWprnE@z3z8@ zz2EP=`+S%oZXPuC+TZxvk3Mgb#=iX^WSZ_397HEPgR`1%YMe=X|nba5ZdSg2 z!I8594bzsgJH+D;bTf*E_0v^89Z%y_^e0wY%xhX%aR`!Hm*5T(#l}DtXS{ytRsVP4 z0^^ACy+As`aYy;-b;;(9wYD>4PZVqtM1hcZ1rj1Rmg=RFB72-Hqtao)=*btWox7r# zut=wSiwm3Gso|Owv;Z?34EK9i$~utHqMoz_LG|vw*SPKe58@C-t>4R)RLm8ZZNwUt z9u2dK$%gcU{>$ONEtF^?F00V8G&Ow=ar~P%J@zEHSxmQ4V0k~r(VKRN>31QQk6@w} z*heh5)uo2FJF?^cmA##Bu9Mlk;`8A!eG|@=J^je=Kgt5)#Hp-xdL&I( z0|beLFY9_=YJ#n^n=U#fS)8eEWY~tq8sC78otaaL{lZPpM9~TY@aXlsq-tog$)j96 z-);2Sj^DRSYsk$|T(z=7M(#Jf!naS9s$=}WmM6oq#q^a}3hIB6$omo8P@T3CKBo@T zdBoOW%Q#4_(A2@fzggvZHlr^IjxtqmSTA=U#ya1hC$H%lDLN}?5J_=u)%wy%LYYx4?YE>>M)H(~i;6(0dtD@z$ zLMzy1j&Vi%AOwS@@5~e*-5ArL&dn)!%)UtSJb&t>KthHFVdLVf()h((6-d12Kw{yx3acouR z%pLz*)qzrGaP%!4LK&!NdR@(298t+zbZPmO4h88HmC|2Y4MZ~fz)}oLzblXJUfYpL zzUY?=#HQaL%QW{+Bq3KMe-{?yaX&c`|G){#xbww+8KTmld=FtJ;2Q2xg#V--bVdF3 zdX2c<%0<=KAEb^g(W?@`aOJLPltG`vtZQ;%(aqb|UtclTF3A=#?`0Er#X6R*6fzZ; zY2T!MvM=#hX;ikOW`7_T~L|RgT;`wF^8zLa6cyl&k-PiR# zUErULK9s14OkSZoo>_W1`Ic{+emX1IMB>4FQId!_ia%)%f&IY{v81m5vj$%z;wAj&Ly4z+PkOM~9kUy@iyZP9F@#OX6j9$&2< zN(|>-go6kwBmL}>zs<;1r_cU6r+`8w-@oO>a``%Wbz*uySGCno8a?2B`Wx6iPa;w| z4TTMvQ|g9Q)a`SI)gWGK5vUHSY2(jFt#}iL=mKex+|7@uL7&6(;oG&%IEJT4(BeiU zMCBf230e=WJ-UtKO=xUO)a^360{zfG}FQZ_kEqGW5z5WuI)+G z%kkwRK9O>u{+1_gNpW$?`Z3!YPB8?HoQQ2`s>?y~Z;kYT`+mQLnH8DX0Ex$K&%2Fw z?;g+G&fTD%A1r~d`I@smK2pMm)-jjy*$Q!No;WfKg@3`?_8WCOqs4J5eV5H6?+T@{ zYi1fGMa>#-l@I-aEt7Z+{jQy1+WDHAyGH)w!|2j$y&E(CdKh~DxpPnFxPxe6RQWUZ zMmx+q@e1u`pFgb#SsqsnJRYdxe{;6flqHg-#aP-Ji-}8i)-Q@DdryzTiA+8oF!7>l zHZHJB%dW-soAIyuzx1DGrHSyD`PGN$l7?Xp8K<_!;CWn^)Oe7cob;2;TT#DSeea6& z1%h=EvOmX;t|6cdyBbHRpVq>(Z!g&=H*8YwOr!yyfQ*>_-pvW^Yns2BHQGRdEMmt` zok3FVxa?5>*8#m>qZs+wu*8ZRUEwt7U|Ba$ZU>FRV`mraF*rLL?sEX`?KuYW55cD(*gahV!-f90|_$;&uLH2W0D${n!Vl^)2<+6K5y3Ga zHKEsms6bGKAs}=32@wzt1JW}hXc_?|01?#5>@j0wdHJ%y9CU!758U*Z?$3=nN@-vsmn|zw_A4K5$N3lIIJ78Y^XI`(#4iCf! zg6b=S|83;|K?eT+*+)MydO&Z9?!Z$$BL?1S5MfhwATSY69X!SUfo2hd2A>iD!}(0> z4Z;Hd?)mvvOq0b^r-Hfte=`2%!I-3D#%&ujTX~j6nRy0e(FLlB7R@9>@S95Ksi@$A$g? zs6aplSVmlECIA-zg7k^mZ2E^5dM-hDaGadn|NirPijJ=P25^z*cXgVqa!Q24N%6A3 zMRsA9n?ZTg3T8V%YK(JrvN~oY zb4{|nqoZ@fG`tk*hy6&xH@rxzU81k?DB38F0>ec|1*5tr-)uBpc~gjV)*zP)jbL1D zOJY$#>S)mh>x35gA|Bx=4%dY;)?dX%i}e^&sOT1jsGR?KC)6X&9*a{?K0KCg>%Thd z$sJcoA5kx4gQ%mA(BO1PQM`(mW8D>Vo=d)fORnPk30{s~o;CjdkXp1RL z%kspZqhK7}H#dfyVz_TVT+QaEK=GIIyLHkqJsN$-M}u%;nz9Hgw zszm{-NDe#cq8X$0WY9wlrwL(VtGb7kZ5n~?R|^_{J}HlMgdVah?OfDQZB&>HocH~Sx!k6h>0Jas~nH4Cvi~$bP?D|xU z;-m#sDvk^|R1y%ZG%c5?{l>|Tb+3DgUiGf!q?G*i3$=)*_k9ZM+}Fj9={$xqv23I* zwpshO zA@Lo)&O%5N52qF>g zE#+9xr$(%8ZW_3@)E@|RDmQ@lP$5C@qVi~m+KaOo3A}I-tcik4n8R%0jhuF?j?AhR zZDEY|`uz|%X)#3B2&ph`>~p)CVR(=cr((OugeqkqlNqV6q++KV`Vgb8EoMjRwqcQnOO<@buP|8BV6NdOLBGs?7N)brNq}T|g zO-EVQNGdlyzdVtFv(FzMW$bVtONYselpX~0lB&E1&b654OZ#3Bt;pm~In3NLT7kxz zI746q>=CR!`^8F9ih#=;k$C-#v$D`Hn&II2KVR#C@BmlVM-0?_E5y{aX+~m&ec7T*8%=iTXQEIQC$H7SNwaA|a{6706l(0DUrCWZyNq^cp2_)`*^}~Z zVc8|G!@pGt_CZkR@(@ZC6Tm3Q>I?|Zk_=1qj@ctEYA60_*v_skycY#Y5-A|gxg$PK z>!xFmX&1)%+RIHC@L4Aqp7~v4T(uiLmb`AZw8##}&ACJfn%4rZr%qql#5o*$Ld6K6C!6*>LbIiDtO(PwIJi}LoB0T6A&?^y zww-S|fq%D*mt)30{Xl&QVb^&lH*?NE_cM6BPACzKh9V=*J&y#cYjyU@Gt~%O_kZ<+ z-JppLX=+I66#n7!b-vb&Wpyso5^r(5Wexfl-T4s;d2y75OkCKd{d$<2Uo6m#4jT$2 z{1V~m4J>g(FY2~DaqyEz!#Y<4Jxo}~#)WG}diMQhx!nDghefTE^Y-dt4ieZ>KXt}pWdw;z#57yfa zvJ!pW)tGw~_(EddLOPB25q7vdBG7m>f-%LSpQ&xgO8Me{{z{Qyy|{Umk8FO z5_<*C^|1W43#Sv`T==I6{!`y*!;7DR)nt5^Qx^=Iy*7|~v@i0qXKO9SUaD>P*ZK2G zlf!u|!vVXQcXXeVHT~#X|EdVfnj}`!V7^7=dNB~G`A!S#?>q!W)8=!s(CL0#63G%A zGcl6!kg4uZeSJqG;Eu`b7EeU&GQM(r8_YM|i(nUS$P)e=gN@X`-8^Qvq@QG&{l4V1 zat`5)N^kQo?HF{PQz^Gj7$48k#bR%2mol2UX0Nk7gaq+T7;vBP*Qu$Ov4_FU&e&X` z6II?p_;gqkQqmx?c!n@P+75$POZvr{i{x)E$HjffolgwZCPxm{Zf-Yl`@tM3LY83+ zqke?9I#P_;p@Q?#%dVFQE}$THK+Eg zRsIzyHL~v^?K!6l>ZD8t+KLgGd!dlJZTNO}bE0gRL<Z9C~W9d@u|+eU{S+qOFC*iJgO z{q269^Pcm5`LVBAwQ8-ZD?gG^d)#9#H!Q>G_YQ-7ReuYvyYL)#WyI*9Q=_g_ypPrN z*<=9Hj`slTk-V*37n|1MgaUH>i{!xQ%J%yyeSPKIj}l*_+QvLbU8IkDEHf6lx=wKo z?V_8G(k}^Kk1ekqLZA_}=4k~0Nc1$u2B0niYGI=PIN;)7%-m^tTcGUVT+BTGSf7Gi zKo{XZ)&&>Ke>6QS2^Y{p`1d>;u>OyxX9w2*(exa^I?YK5?6BpC3``CNjGZmXsgnko zhx32?*syVM{41}{^?-eBxX?bTjrttzot6$>xOV;xYxgwd$e%7&ZVz!K@rpkQERrklFC>wa^ah zmo75*{{$heMG4_tjmefp;Xj$TD-q7ZnK7(;;wY?<+myMh61)}cuB#>eXW51`BHH`Bf!IoX#ELcMEi#S3}HnZWEEF8`^8wAKNQh~rC975RKD*c-c4`LI^NN_#?v&K>?w_6=0qn%!$=Vmj7hMeIQgtaH! z6BLm~IM{R|Y(YfReC>LQaX7x7>*8uos6u<+n{-<@P8Pe*E1CkS@lA}Knf7nlq2YQA zehvb-c^uS~z0l6Do|#k*u}}60aF}YcPg#i~_cPYJQopQ|+W!PIEAPUW?POp5OT zU)XI(bS^Uq-eabV)8Fho87YgeTIggrv0|DW9*HIl2Ivw+fIC}yFhOrtkqah5&n?xg zN$_Pg%3YI5Jj*KX7ub1Gjcx72>Q@|OV_Q6T=#Libk2R!aCAi2KP~<7ZZAL$;E8Yl7 zDhO^U34DDvS5lzPyDW|9CXUm(ED1XY_`PWR+%S9b3~kXU?PvMbcIw}ll5aU^xLI*# zAzLjJ9-nc^hd=Mu8gy>k6dH|R9*B8eh71RN=Sfsr8-ugQ6~|n3Q3xlVMBVQR{Z@e# zE}E0?A+_Gku+K*N$pR3>z7h6$|Nh;z**a_N$(18#I@3w6H`(-8fai{Su8-&k;O6oZ zrZTP1jL{f3Hzy~%vr~Q=WpxNFN~21J&()1tLAd)d-6@#9q0m$whXVf6w6J#d^C#<~ zK1lK~NzU2)K%?5`+5Db{2{Ff{uTn=Aq_U0O^6Z2yk@qp^?>Nn$uS38u5yz9Ep$JA# z4?txGLtlE2D*(y_hD~6D0h;%H0B4j`=umEHxi=8}eI}vKmz04Bd(Wp()a;9`_ttc! z+$I)ult;h6W4B%j{3s1ep(>A8zv^R`SM2sO5V19ItJ$L%AT z6h{Go)WkvpGhL9*7@lpCn?G!P4yME|T_hKXT1Tf%()3;WrM)}}$ZT>73 zs88P%n{E%CnWJp5K{;4cv*l)E%u~Q;L#h4!>{{%FI@#uhIxqDricy7RY#$M9t^YOX z!eOFI&)M_a?~T(2CXX+V%76=lJV72(5dsQ|puqt?Vp0AZDx~e!9R&i3kYEfZdFiC% za(h2+ohhrxlB6Ne^!RGa7|21B#!bBee|jG(vp^|J(MWM8sZA6TPhZouGT3BBu0MHu z?rrlY8&CJUFVQoxVI-ARq)XPD*`IlpE5R&=W~iZND9JIR<-J(-eE=-9IdYD%5cn#c z+%DbS5d;&{!kQT@3Z$VdBNA9*uUohy1%$LZXqd(|tZ%-}+~D&;kW*C17^d}z5guES zTHal2Sl+(P)^=>_H~p+=W@Qm=MJOz(Nxg!5yVcJ6DA@k0@BmH~=G@*U>FCd$=JxM>V9)%ToG$lry2Hx!KIOP$YOL$L|1=6nw| zWAqVqLCjWS8q7~^%K-LWaj?++gQwA|S`u@}X8*P?kKfF?-zC9kxx0HhvbS(N=Htfd zOSx%k%6W0Q>)FI>;750m^`XILM6fa5#m%49nAO88;KN`TLk;L@Y8X%*s8SW^-!<<1 zIH9;y?2n7*y z{XsxFux>~ch?qDMyWcbHxEggT3F&d09_iTFzj=WlO1vCwI%iVpyJC~S7e#w&yfey& z(3G0r|4>_#mH|*(-v_umw6okF+_>`F)NzihxgW^9eqWG@I-X%6I6b%yo7-~_Jvksg zH)T9*(5&A4g$iE({%+?JXdd1sE3%mcebWu2DTooUPyUQUN(Q8g8N;m)*q-%^NJhwt zbJ6Q=tiMe#S-CJOEv<+9&~34l(g^KypUBjS4&>baSp^VpY#RtZQ12B|w)ezgU(iz% z?2S<%7_ABTn9-YDjg)S+cx9sy_EZjqRa}p`x>&ip&fe@bXuSTR#v+Q_IwWF_W?6XQ zJBq#F_lWaA$?=R=0^RbV1cK0I$*PewQ&u>yv<{fbEkLFT4syT zOLm56M|(oov3~^EOeyXk_tJl4no&mI9Cp$Z1LS+Vd^FJ#6rLtYy(qy_ozdf;SsZU* zfqV8gbW?6@)Mc5y`!X&bM4gtUO?yQmMj&BhpoW9;an$=bZIkZZ@JRfLstvjGCq|uP z;69SX$+z=3e8j>Iq|#10H8%`2)f#?W$K|AO%Nb+mXqlFReyVybpYI#tD@g)XQ3!v& z0gNj9DD@qcjep8z+ItPy_9n7($bv584qV&MpA6cC##Z{M z#!UI^eGCq4OM zxM}f6N8QvVu%Q5w8WU15Bh-|USEbq{3xK8btNc9Oh-^f}dDQths~=aVi$2YRTtonT zHAHyQp6F{##jto+yEY9=otuTx(qqs>=~P8-z>E>-^%dxWl?4B0C>=@eM0^bJ-~Xy+ zHxxu_O{t?^TXuKa#DhIw5>Ma63PxKbX>7R2hY!;Hol^;44^BVso$A=5p7HS76X3u< zL+VITrdtT!XqqvAJ^LadlucmPsaXoIIxv>8PU|E~z`qpD<_v@1UIe)%l*j>5z{iHa zW5Rnw49O8HeqfEr#dFCF_R^bv=jRAocVku%Xk4+*AT-e|)D+3W9zuD1&;VSV*s_T2 zvWk+U3idOREec{CR0w{ha}b9^EnpaNad{X|%X|-^!GYid5nyFmS zo{{llY-q@yF&58#lu-a*A<1XG>To8k^>F4o-feAvFI0Rjj|iMR`sdrp4*m!0xomWH z4YYx+c_AwmB4FJ;52jTqB z!3u(0uM4YDV}~?%E;u0~^jHq{?mltWQB$qD5e()b-JCn}j~eyt8u>NfkNSL7=WbSe zkggOP@9ZSAg55G!dnJ-g*&!8+)m$-GOcFJVRVtL9VCLoYdhjerC@dPW=P+tU8c%X5 zW_)Atq6KSZhsz}G91q30W`H2=wkCp5Pb5qbwS$G!xBDR!5Vh$l=ij?3$fV5oZ+PN- z!M*CZ&GO`0vFGy22g^`>vMF}n@GP2~vEyMe!lT&%e8Jg5%X&c;iuYW`&rtMR{s;KA zosg*k=)TYXR@j0Y^LsdIh~D3b`FZ@~4+DN!Qjb*li+F|fXgx&6=!iEROeB9Wojj$M33XGR#5qR1?CJgZ`2P;eU->{J zWCfHF1d?P6tW;_5PyQB=7nQ z6))ccO0y-KW9@j{9Eev~!D!j(hB(HfZIg9+%xG#^?X$O4Pn4W~I<&!6RvsSUYHAVy zQc2}P;xR|SMKuXNNe{c=Na3d*wK3o zP<~Wnao;e64 zW%|1vk()eWjdWad{PExG0;xJBfYK5^Ex6&cZ6x}FdIxLWbxPm{UD@hU>2ai8(u4FJ z`GpM-h;rxV6IdJd-gRUKQCTP)oAIaX4nFucJ^QobfwGMM=z}l#6AV(EK>J^!F3k!B z3^9%F^}n2%2{4xbM#BC<&Va9+|78LFh0MT!Z`UjOx%RvR+4G7Vq0Pltlyz(DY#UBHB5(v=(2`n#6;7Op9MERG%5=%qG0VKV; zzZd<5X8*yc`EY@&{L9sHvA0}HgNcIzH{JbE>~}rjVYdF?qX$sx;Ux4SV^yICT7H&gmBZ<858jW1X@2%@c6@fi&=?GO}oS9Ux>k zZk|-C)4F!f`S|OPQC|*Uwv=~=!rqtgIiU@Q23Kq!qE*M1F~-`pt_-`N6$-esIsVM= z?qW>qQfs+X87HAOSY%3ptSgI)4Mw_g1MK#v0S|BPS=a%%Imfni4Lv#MM`swjXY_D> zSiBD}{CZ1kD(R~`?okU(HXE0rA%LgH_pO3Q&e(x3(-IklqygnLIQFGs30N^GhvfF1 z6@g-WX9}l0EzNE@r!ikcpYcvQgV@O-_r_{E09q9YtN)DL}$qeuN{F5acFB^N?Af(2f1iYKXITs(4k!<($ z1iSf_8C6pWU~*k>Gq&~IRV?HihM7=4`?wx63C2zdnf9T$OF6?KUL6&#>1R-a7=^c7R8(Gq^y(Mq6_6e-*0i&H#Bveat|c0-syai_q0~tl^^P%>m?^MbA^+{XD+=!9D!80$bacOCZgbmxqNvi}M|GU-DoUaM5g z?v0)xG+Tv#ZTT>J&aZo*A7%c-qqzijy)lbdAeGTS?o=aWQ_!$7FOc;o;Z@Yqd8g5iAtsL zgKjK1^KxU-0>P^;cSsnFX1}gQeRQstUZ;saetNr>YMMfhJj+48%Oy+Y*{$L6sVq(3sZ8Hjx;!*}~rLA8!)@sx~!=ix3W zTW1q&{A<4qVaAi_h%4x%#P?%Ebd0}*ekF$l86e@p(0K(rvm`ujpc27{)})DETZ$e4 z76?7sK#i+{l|mQ~`2D_5DTp;|E90q0m@p}u%BkQXxR(-@2zTNt7=evwy7}lK(=9LN ztP(ovmO$XlL@&K)p`C*IZQmq?5(T1FY-fHBu9WNy$KYgOP#p_o(S!$OQSCL^{o0D4e@vbaOC^RmBl)QA@$ zMF4KP^3DX2t5)5sgjkYE*hXW<@Z z6q#<1+|NDP0P+`Caryb=_9NTI!?E$$xY)1s=sEMeQwWXXeVY%I%=3tR?ZjXXwDo~<~9UBo<8Da_C8%eBKP=r1N$G-EOfLr$0pzjs-&$E z_Z;j{J&UB%t2us?AhoJ0yCs4N`PoCy$@e48<*iAUD9p9#jNNkIL9@8K--l-xhDgK1 zl)Pbc1H|mq$&}Bj?|(&C46ccP@IqtA2n$aidd%+9CBVKd!6QueAzMncrMFzEPu)pW zVhyuzKlAH9#4fRb9%a*e^3esSNkg(_J2lUq+flw&Qlw~A)39{@c_MbAl_|hg8J^G% zT_u>1A+3|2(`0vqg+m1wGb^tUThrYD|C6e?0~m9o4{#vM`trSK$Zkj+JPxY+2F~99 zI|wdJ7pn}dw*w-(~vF z$FLLO=w?%UbUy1kgX#<~QiNTFzrv{mzGcDZM?k_zE(DRH%lJdyoT7*t+|oIf_d96l zSVLFL5T?f0v2F-b3=P`mTFHwfUV^o^d`hJW@#aW!`|(eN-uYbWkZ)V3&29^5XjcIA z=>9F~b({S#McgpzBEm@tqq76DU*`kq-!+>(xKnC}jHqXJI*5 zx*e>)1mK@Z>^)FVXB{J>y&r0tN*MbEJKo}q&E7_8Q3oihQd?0M8q%a@v42F2u-~Y( zAZ^X@**~h@;nWyHhX!fzhkPi1`=+b^Iy&(!<&w090pgnWZ7=u-rA}U@>cz4vNvz3; zVJ(`!*LiLx69g=8jHeyObvVB3qczOqnFd4MF3f#;hdZZ+S%H!G}ZCO3*TW{EX zQn?{%CMaOQ5Z(W6Z18WKWnU4D5lH+1i7yUtE+DxBM82?*xj6ri`QqYYZgExuKeSY149G|D)SW!Mz_QY+biw{+8DLs^he63f)5`ULuN<2IV0I0dcUu4hPWhYk{8yfXbMbJs zkcxwagQmp?0Rg1Hay+d}ANU+VH7=E=U;w<)KUzG%5bQsZMn@yyFpz25PkS%|4g=pV zDF0?5B+}B2fdl^}9NSEQ)jtVGAjb7S3C99+VD&cxkw#<*{B;2ZIXr0EpbZ!nI14ur z9s@Sv%h8ehwkCpW7?yNbxda!y1N*1jc;gm2t z5D#DUr4d#(!5`$k{)k8B>Np8Eu*H=mH&?XpkT40XvKN9fukXPUY7)TmVwlhvGFrCJ zTIsoTWDJaIWA($Z^jYl;rj#!?=4wq5Zw{;nQ8ZlEu(b%LJD8}|+}IW&Aj;q0ypZ_{ z7#OQ<+bhpnd-IyK<*Rva)tH!7=>A%P*K&U%ds?6(kMiOSmsPB=c@t05E&WChYb}0q zI^U~foKA2+%zrZ3?pM|y)mJ9>J=)G*XR$r%f==LtcJkWOqwQn(`R`W-0L+q5e|K_5A4z(Y}_wL9wnZ6V@4=}ZqAW+q8u`gt0AuP8L^?7*{5 zCx8bvbX^it=3m8WTIHkdSM61|1J$JL`3ib^NXDn*3~{_Ufm?tY9L#fqcV>~p*p)UduvekD ze8sh^EA)C0rsa>w&o8Lz{AC*pi;B;d8Z~1x{e$tM{S**x_Hs)^OKd|_!QkScl^x$g z4idV0ripK$P{ZfW%;XluG9Z5zVDKX?cT zO5J-X2SPm!z1(-qKa}rGn1-~2a(;06tAaT`!c@E=^M*}2R8&FE&pYih&mxc{uSqrX z;2~_a(}Y3|JaX}59!G$0cShWVai|azy%4+B}@j7km#trMPZp2UMTQtB4g! zy;2e}?_HHAH5w7GG0_M27lb%nmo!0Nc)2udH!xelo}AbS4pO;QYc3@G8XrJmdpf)Q z4O@;bgbd9mo)%p8aY*{h%-6?imN zeE?%O%}sa`lqCG)jRH=}c}%A9P#e17BbwLPsFe83Z`+#wMFjTLsx}mqE#Mwsah%z- zzqxafCWnh3Ta}rsR~!23wQ2eV1g7jamr11xu|K>tp$&=8(V~ODHK4cuSMrTMO#lyoK{w<8Qing(Aa0{=P%JIR7M>^EZ(&jHL8Nqce@op5GaNqow>Dz)Q z2b7vo#pP7Lz;HL``Pyl;3dNlTvuB8cGNV6lHqp1!Y(rS93hpmUZLXDX{%9k6+Er*8 z_?>*CBX;%hSd9|B!~j5)eY#!t0M9tA-Mh}ScvHH0+jcUmuQcFuA{mu0vfsu8w?CDC zWii$j{_M_`@R!l&gu|fpfU&?l!Pq)pTW;n1-HK;|37L)?;fLbXK`C|UBloo3C}47j z<0EnGfE{jV+=0PW4z`VW`Q`oxP9CmgK|~To0CDlVNP22;fd`;V-*~_?&r)Wxf@59G zD=e$_Jx7AKDN(SQ1?j6qJvRZ|HfTN~?;wS%o86mynAHgPzTOK(wy?md{Alu+snJii zSPzdf(o1DY(bAV8KZ~tbR=Ga6Qz7x{`bpPpdFJ92$G~*0wtjW3LrRwm?km4Wi3D&z zl+;xxraAKyK@kA{`Gf{o^VZfDLu!rJWFRr0vK*V06>Q1-XdWx#5pt_rP1++?pBn0X zGg6yzd7mE1VKa*8)dCFlB1%Z#SBU-v2gb}GZBr7(ICd>flw7B-Qn^2V%&0uH;hKDT zKergVR|b*~R1q|1emmt`zU!etlD?^-DZ1r19tlMG#Pk84^}Zwb8(uzP!T!jvb0siv z(W~7)T<64LlTY17GjSw1I*kE8SD>z>i#<)DXNblsyV&8Qg2^X2Kh2|?N7{dA^2d!W zwTP0en;qlFLYQLJa&MCPL-!49NV=hx?oCONy}&f-*~F)02ZsYeF@V>vD%Zqd=5DuD zfU_!{R2dc!%5k;hb`UQRoB$19L8DpI2z$hIMnD$0j-SUf*ngN0uJN>2U;&JoV-~xs;6&v`ibsu}ukp{F33!mPf{-*G?xjXGNjdntQ-f zF3~E*HB|2p$3RDvy3D*pIgFOVNb2)p`)>MFw;6s^>LP)&u+P!SD`HOra+!QHa?G2* znek{LIATQn-JjKJ&E0H~=?>&5%9deDb{OeCx-U3a)d%g_s%|*KeC#=bew0iFqhguO zH%i_B+g|A6Sm_(gP@gLi^w@I>4QPm7kIPMyiQY6ly|hL)MqYO928gLaB3fcH9&FK< zV(?i}dCYu#I|A>K=2edrackDgm-BPeS(Sl#WTgxYDKU0FV}|~F*lHpiWU{^nmKn+l zIcO29V}}6JZ|D466w?|a4<}g9DRa{@l-um7XB*`9xS2wSkb_OnIIFmuFh6TSlod*$MlF7-lvdPXE33+fLk#kNhuB3j zvS_M_MYF!h%`aKzn!8W9xlgASsSIaD_<{BL{5i~H2$y9Hd?C`bB{AbGT zjgJSdnj&`kG6yT+g9o;EBZ{OD0i+Gzr=?5+S4?su<0lnyIBVI+i>uEba*|ji&Tlh> z-&KTdsHM@48G6f0=erJxB)06~JX}7a?84gqqwGDR=9$a(%D;5smbebTL@h#Xh#%E2QmJcl@LAeYV7if_t}b zDQ8?SR7r6JWJ_JJr{usU`9s)+0Ag)3XJ6V`b~`+iZ;IhyV8900OfE4~w81qaM7!DG z3oMl$#k9zYGav7@~sOOTd?;}Rxg4^-nF<>Jgp28Di`IKcD16rEN-l$4mgh3(U zD{s+Msb&R=5IjGX$b!ZNm{=m`YH$z_w9iWU;JL4HduvaV91qQ`Os*o4+e^HLld zt2r#(!9KwD<-UMCB=t#x2Pi3~ArOwUDg;31K_uEmj@+qkhx#1$a%@m82`+K9B+;m_ zsJo8E4{jsH^h*x}NLD=Q0LXoJ8dF6rmA_X~kQF}^2+k_GfuX+VjK4~iEnZb?Sq;Co z?eaP1jJbiq0i4N9x=+vWZtmGj;|AEID60_qK{grg9yvts;IWv-DwePSceXSVU$uu) z=sajfmD&lyVyXuvt5T6J!KlT!P@aV!wb%teXKRCz^|zv?k1*7&0mEP3ny{=u54wIm z!lZ?*R<-2NF=D4NfxRSK3Mo57y1}#mPKR~cH889@gEz2A);l&%4I^~)^f zgqpn{M$2|?Dx7>aCN`jc+kGisb|QI|S9Y>!x#2T9fz{LhM*5gnU4eYRwHuT?+!PDl z6Z*BR?Dn(d0;AbCbXyKlDR>ztp(NMq7+zyS43ezA@|VxvL3%#E~~GlxKkY;_KtD`I%Yq1*LkVQX=mC2_r5x2 zCH1ma`ziJmTa70j3E5{p`09i_>x?%ReLn1m?jDHuC3^quAsNXhT$&b5WB>K`N1dvj zEnZZFR;EnGnATHrlB`QEWxB@D$!5+rjm5SSj3E(V%T&d2${|&T89gIa|JFP*WkNi4 zg+7&4MuL-)8`#%Ets?c@lAT1^#ErlY>)VQiY87Vv9o! znYDGm2r?xbQEv}gZnvr>1s~W5T)r>IBZV-LDPXcee8R;jU!vz0A}+Hx=+mob zQS{OqyE@%P-Tb}|OWb^d$w-1cCFKEa-UahQ+&rYFw^N5^l(cuK}drL&`6B&Mgj?Fr|34rEB$#Xm^2_%!l-pjh6Rov=jV8 z+KS!PSDscgv*86XfbMI+GS`d3+v^lZ3Zi^dkzg4(aZ|zKP$Y&@(Pv?QsEXQOQ+Mw z*{MvZY|n?Qut3FHdV9~p$!Irq03A|k!2}siH3uf43vQ?fRWQonwcb(m6FedlMgMRQ zP~aki8L4fC3QJ=xm>qSzjPmn$#B2s&@O%#pNd=~tM=p7iy0csw_F?({$=ktxL))h@ z*?cd}YFn7PRUVVUsCuWYE?5iUwVU#XDSb4tOgFw=3^|e)5|fraAmPu=A*&*~!niPo zEU`6DDq(38R|V=ONj;qBUhf+95j_Rg9a(`VxKHoNhO$=+A&Xn2SagXu!Kksonaz;I z8o5Bfgu__3G^r?#r?B z!WF_^DEdnVb=W$2AZ`kS$8^||^brO^BVS-qv~~c0PWMK;4%aU~D>f^tPd3d~@xE2D zEIG)kQffe%pzD#x2Uo?QgTs@vF$t?1ibsXu_D)U?k4{cT3d{V2a<2z_ABh$I3F_hm zv9@~kK_@y73gP;_Ap$f9unBfxZx6ycr3r$?2?9^e1dq+c#^#@rk#Q&#(2Udx!jcca z3_&st6JOT^%0s3cxw_iM=l^RmXLIp+n%sXi9jdo~U_j#2idT3UZy$scY87NZK=BXB zX$xjdfF_8Bo*DD#*gHU0`8JD>XXToerLDc46|9O7*Pd_^!sZARP;E^8%^z+Qb$=U- z74&U}RT$J7@uh=95<=ELlV|ywDXhHeXA<3SPzX;p?SL2&&R9p?mmU$h{u9O^EhA{<={)M-vtj*H{`s@?MyUL)2k!loHPNZL{$)<-U90yqj@TNp+2xaO zSD|f6(NT@W@s$&v^OH**{chL9Q`Oy($ECpMOKPnD;W^VV9 zrvFi2@yTMXX^bDASVjI6R{`1E+dugR@Nt~8uzPm*!5r}x)CwwZ`YEB$4?;EcN#?)_l5`>zPS{)YU^F-YX$np!f5pTZQ=*+h@=CgXw8;xhH5#Tl*cpd#3gSy89P=(yyLv ze8ja+(TA4h7GU=2f{V=kvvuoX@8Sr_scRti>{>k(t`D@4MDkgKUXIl@n6wueQ z@$CcKhy3COI5K>1q<1qs|E}~TRL<<~?&R5l|CznUHTDMm>4h33>_B1`{EVw-)-4=W z-utHm&O}rz^c*!nX59W41s>G2SJ>7RGR-Br_4r(OCGR>6^_@pPgMFl$5kQv&;Pt?7 zSLQ`Lk5jsScXV%#Qpno95zNdLI>(mjO{2e|0Pz_hay}Qk)XM;~dch<=4ts`zMU2RZsEXOE_YC>bYdzTNX}M z0`PvJHE@$3+i(#ldN5~^IjIZ1)VC`A-(cv?QKavaY=?@hC!9DG-D+oh@e`TYI98J=@)OY{GeJ=D}CjNx;|tGf^3wCUs9sB z-N4*r6z6i#FHVpmFV5_0o!dL?T(rLR%UOl1v_11@VGqK}-TuWwy@=i1%3FOa{M|-V zA2oSz*Y!d$qe$bA4ZZCMGT=lx(`+1>N>{3gc(@}(nJRBiFE%O|D@BPpb~#Sui-{^~ z`1hoO=rQ+hD6;|L;Mup9Rwciy)r;H33Uuzn$RV3kZR%6Ddr({IGvzm`(oRV7)SSLyY~hi$rZPXIics}=DAaVd{} zlz>R6oJQ0I>UE)kuM;m{WO9bMrHgL1A}7qX1WK+@t7F){JP}~M*vM-x4~&id#*H4( zkzceU;qLNrPso|3dPbae3zbXdQ)`afUkXpb%6*n~a+(IW^K-1dNjMP}t<055)GwsH z{78zjuBxEt`E}$cb1SDk>k!p`czp&o(LnPdA(vU_ zoY?Nij+>cSM`%4~l4dgCX7Ewg4g$448kAJN$D!jE#Z>}iK3p7j(l}GUDlj*W04BwT z@>d^P`K}Ks@v*in7=6R>Ec_`C)h2=;o+gqLvXF^|5g5|DR)AfpY@^0lKJQU<`u#EI-BBuBi|<>yVHn$Qot0Kjkcdt6+y!-ZnQWopVh zL;7DDXkY7sPs{=oXuGRTQgU6ijX^Gn#)nph5&~>^)%s3;%5bFiKC@j#b2uLx zSkqC`6T0A|nVCF8Lz^iExs|QkYNCNE4lP%CP4R|7xc49udr4PkWHiun{tCM@C z`>f=Hvikd$GqLSjrR2@VIn{~3($7Ld;HK$FVW?jg84|q$Ih{I=>0k0wjyM+NvE

=6gtUF+o$x zk@b#$519{z2t8|OX1C16?0g`j;2-P!1CLXZ{a+@M0NxDzZzEMaz>dD<4O69%m-k&> z^%)?+e(1+I&bpr8{UuIgHx*mp%{r3wzzN(*-vBn1#h$NL6=yejn^Ypv2qd_J8z-B# zGe^OX-9nJka28z7Ux(ru?10_x*XtSsVG>dYPdYEkG8+Q5zGm!qUAP+#3cA;#ZyL5C)9gC#Z>r9&|DkM3CQ_qZeM~*}(Uh0f-at*NrMpZZUFS z$Q#B`>gjHL8!ktxdGTDKgNI|cjo%(v$cwF!DOrFJX(HOPab59h$#(J}Gr3 zO4z7PGn%;Pu&-ETKn>3*&fVq+XjW-W!;vXBOsFDg}sQ z?88HwYw!P)n$j%eW>ITvZL`iyahacJqNrrE)%1W8LL-e%)3JYBE9S-C6{Xj9 zyRu^p>tT!MjX|12p0xor(T%usumg}#OQH$Xh0$dLAnlq2Aokc{;F{t5S#MU7_l9v) z1z9`dYKX9REyNRzCVFka(swk|f?(TRiF-`BbDWbIb{ZrG;p4^KW7+qnIr_J;^4%vr zkIRZGwcuQyFGmTQKM?1v5Xe`OvRdcOD@%IH%-fx%KnW}4Q~m07)b;_Y<(?Qu%i|z&C+5zd2_(i zyt+wjU7CY-H8~mTe7z`>6puyK2WgcTa)Ttq{*t_$iioM%Y4a2nyfC2SqIEvsdS-0V z1{v^?X?VK2*HA)&)-b5CmO^Q+Dof@DR@rQM8{gSq zLV5Dj73B2ZaKKK|&DKKLT~NTd%aY-_g)DbU+vzMkpjx@8WR3)|rA5^p3R9$8Pnd#S zyf{H4TUzpQG{6xWT|Ux{B|I;*W`b(ml7^;V4~vPs4k0Rfi)tMX5w zwNlm@X;0Da`|=C(7B_b0K`;b4HJlA+K(DPC1vv2=$=5R>$KLkuV8Bk+@L7` zhYCYbyWTitzhOss^Uojry2MqzZ|h0h>xb-nuQ{HmR5)o}hg!>2JpvgeN#Tq}sZM=_ zm78jcNc7GN90jz7Jrx}tX&9QRhkaab!~}j7i=^98Z#<}WXlUY5#4izhyLJQXc;$Vb z-pIe~SzeYMWc5 z%!^CQ|CZYB{316#L_-5pJ4YID6n$2POf|43^mJmlho?Yngue~W^gR{(w4q=Y-F8`C z>B&w6OPFg*i_8``pmH(*KarD!P}!X2iQ?mYT{`9uL=ypkBZ+=jugSRT^rL>l?7kfv zl9BvXgy6hXMyfyp;>zHvj8HsA9+-e9J;!-Z$2sw5b-9qfmM zLm5rwCGo|^0M3Ru^&fB6vhK!mYzoimQ&~rJ2)_6tWPXJ0@pM$O;+Cr03;Iad9aIb? z5YsKSQbQC#ehZtQ5ZP|{Z&eXib6uY&gYDK(27B-34pbBmf}xd`d(ymsM=z01M`(OYihc5zyF=>tHk?qi z5U;P76l9Kr$K1mcI0{ZIoXj3%@yZ~x93)0ZVk`mE%9)((-mu&IMGxwr_S(N=93hK| zNw=uEf2Gr^eRXV1kL7j=R~`J`6B}TQ0DBnr74G!-mTUFa;rhu?&)c+nar?MLrG)Tq zRB{R&kOM}+)0lzIzGieDeE(G%Th1v&2aWVvBM|JD_2IX5E4KoS86j5r=7F-&44Gm3 z%iWx8x35$wVPQl=3*It9+iu7wiIw7frtOhEhMOtL)5Ol4ShiD=Bz^>#-u6WTn1*86LeWkt8#AOdTd@CK2-v#GseIc9`N1e$m$+Pfj`Tix&rV#& zY?U6RZBzP1{2Bg?1IPVxAF=@4Bg$+LpfpO!|!@&@!gRx9Jv5VjJR;p&+fJHS`mw*In8XwL}lERYjdfrdEVJsr{ra8qU4 zEV;0xW|wmsCu{*X3s5wpNc7Z?oDPv6%MXrDI~%kgthX*G4dm`qDaBJ^pf!~gkfuUl zQdDIi!55@2n3_Y(2Gb$OOTclcPg<(nYsJ-vUnFZcFP8pC_1 z!-LhCpW=@(Pds?Cp*(nDJ7H`Tovp=p9#NqN&%j9NZyYT9cn&Qs>8u?od0TFU!o8|A zeh}ZUhj!H>5|^MS@Cl3_2qMx79b-2eb*FQ_)eAA)Br(OD-}(3^wmq*2+5;q8sOuIE zwAt+%N}zoUB-ulhu~@+uV?ODjh~X-65bsL8fLq@hMdR zKTypu@NxsvcWe}yxGc2VOc;1$2$sHDVc9m;*U5!&o7qb#@h(v!8fw0==2=!w z?}j^k$%@6Ol>SM5IM3@c#jAK$5@V zJEFtWYMsXi6@26njp6`B8UZ>QKH{r!)1NpASW*Z`8cNoW9GYIr>3S_kb$-+a7EPrMN zM>&q`d5Dqy7&($l=TL@7NX{8E1D6LV1i2mCJn`~hJ=s3eG&QoMY+C0duD>x5A>@>A zw=q0#+moC|K=F)(H^x1>41aL>!WqIz?H?i7hgQYJZK~sr%82!HdP+ zV3Nvg9slVj;9{s@8qR^KzPKGX)$D!yk~`7nifj%&c65g=7Kf@7GP!I9Dy|L{(rgLd z&XsXDQYJp^1s{K^NdpNQOlQ^VMvw6P$9=jF+@IXtl~oU&2hdOBN3}d&epv6%v$@S) zg@9#ABT5~e!^UDw!hfpg1sw21E473!t(pT8hBSONP286kIb=|ytH<{&mkyZ^$L|nT z8=K5kmt`BaB4~bL!}<~X%{~+nge25j{W4m2JR_`l@q|3&mG-PLqynhgy-ZIbRY7Ja z#gu(sG0TS*+HoVTY*VMx*J9Qp+2L?>2^L!&ojzQc-Ofl^q!7J+x%cxx`vhh5PP3&&S69eeqzR zmj56TpsKD9H4+wOYj=fK^J+@Q@kuxgK6~ff$R6teQt!h}i{=cihGG=4e5upI487`^ znE{-EUTr4x*MHEm0|vODG1uUNP&Q-fFsJ#opH#Z{pFVp^nGbiOtGv|g>e zP0ni~oC|e@SQS&v)qAXrQ-=buykPuL&Q$r1P{l#5>Z?W{X-Ym!3 zXD!9BN}Dx&Z+$G-D-3qbb4yspI8j;UE*Ht(#)NtWb$>C@75HjG_lP3D9=_Nc)-fo0nCn|z@RH)z?)XN8@t#)t~ zMfbH(MJL|K-Tx_Gtdx ztBjYo9)C>(Rv}tMv0dE*rGH7v=nN=XE+&OieoVnh!R{p2T#HsNV+2`?&@6qTAdM$F zlV)EFWRy)tr|&6667&;|bw{vDfaCi3!`d_sk*daafTerAkoW5j_+{d2A^Ns6Q5CXv z`!Yyj)DJQv8R`=YA3#Lp@d*3GTbnv-3YSm`lYgxZQqVMH3(m0U%G&kO9eS>$YOPf- z&RdQd&fa!iX7;!jkbE_Nx`xlbwX7j3BH~{txBKWe%;IQJSb|Tj%Q~>Bz15=4IJtx% zDRjHMLFj(~B1jLfajvW5-bY4dTeJKA#EmXyPaoIQLUp%{s>3FabhYmIuFGkL33Ifl z{ePDl65sAg>|-6OC?9sbo|ssrGxIXk`y8a{T;(Sn0S~{Ifjp%wT3Jzb`&i3Ni1>g_ z@=+|IUCV|FL}VIy`19jO$qy>T6}_6$$RuPcpSjNRHD8*RCLkscW_l_PLr#-7ndv@_ zR8OldE2#AfUEzl3E}r-Un`DaJ+%k_SO$2FN9A(+n%0-w# zZ&WJPI=U9W{UnKZ)bq1bzmiDJURZK#bg$twSKbX|UN=JuREVjniB zXYL(ahMMpFL(8)vli?XQ#E85=_$?+oLFY6V840>8!)hqpJtXDw%WByO@ZPmEk34 zyl^F-&pTB!t`Mi4~7*{;7`>(tP;{n{4%}j{cI_~Z8o@F_bFW(dViF&(?dKYlhRJP zTM}nN42k}VipuzaN-1`Km&5b317{)hF-O@vrO%G*`E}?7pT$BK62u1LO7GJ|@~y(t z#WNaXlete}k`ej}j=&7JE23Up>R6gfvDa+V1%(0{o`JP{*E|tbnvDz-(65n9k!`|Ciu}y|8 z0VL2er;a{cjW&|4B9B{cKt7*S(@;KeH8)OpeCSIAv>-v%N2bFL2ip9WoDKU`L28pF zzk)wbM2I;y75ux7c*}qx9L9`NKXi35OfG+T*~+eaa+tNpDQ&o-r>NJI?@hkSYVGG?du4}llM@J)v#S+72K z$?1)RXwSjB4u4f_Nf}%OQOuRq>4lXS(AoYn0MuvntpVWotMm4Hqh*ZsdX{44Hd>S9 z{E&gZ%Uuh{YPTMf3r%T#8g*BThQW5cP4(e!WA?0LmLiLNl|bf|el6eL(p5T*Hq(;R zTtGrjniHOo@RlvTMssc2PTB1~24u+$q8Oqqw!L);ZGZmM!C~OOi>Pqf1AG;D03Anx zrlVqZD_f`{-dvPvB>RZD$*uf4!!iE#rfx80>ORN*Xuo35hWdpPt34$eQGpx)E!Lb8 zPH6qJYl`F-uPnsW3~uUBuaYM{8MqbHF|>09o9ZH0yzzw}vEYDPvM1SMuq@t{whQBK3S*ff%BKMm9D&gm_0TrHiIl9+HYb@Sxf6Q*5esTYTO}_`X zE8wpWc}nI%ZwkGpyL~1;G+UlmmAxUV^pl8Tl?oZ+1=R^x)9?ih#eNSsFu6a4+QKgP zm`my(%0ruq?>n1fjcxr!XG&Jw#z%+&%==Eb2Y-pht!JsSG2~%Iyv96A(@@bzU;S$j zCC~_Fp;|9l`r+OJm{VX?Oh(iDVzelxKEdx1V>=qZSWZSLu$|5QkDdpfG|L1*A z(o6CZmLxuzmCE zDO$)1#WDb%VDAvgw~j4nYZB%sbt|qFuA{2iJ5IPG<0)LckUST~D1;^BWUHQ9NC%3A zo)rp3Z-t1gC)7_5)Dt-$SFbVY+J9fMT1RzDeWH!6Z=$T%_rurc#Ic*B5j^;C9dR|* zh`C-GH_ylpilHjnkXkoey8Wo<=WKk;^uLjKPor9`ho|?9l@lqg1V*D1`z{~Fmf@Sl zR>dTinq2IXuaB&^-Zq=du^xKTHeE6n-vZjL5ddx61glaTKw|8LTI5ny`G1hxcNLKI zR@ZoK1cP&Z4Dr_XCy?2GE)T(c3@i8VRzl5#Mou)Xg)=0>i?0I!O9-1i(#XqGloQ@z zJTQ;nhXr-x2iXNe9b4%lGHV;L3`R}*mKu;qzuh1U?>aC_`i7@R1h8|@=7~n|p?;NJ z?UFtolt5&`8I$}-q9Zj*gMa=A7I<_s&wm2$l+wPJCL4y|wJ0pQz9VyJG5MmIQrwUC z5Hs`2DCjm0x7FK+tNVqk`MPE}2inYsdTKYsKPu3vq|L|Y8>2$2$HJVSF?05g+WDGl z?%64WiW@?}*2?Jgrtm$LRIRla`1iRlAh9J4V?JvN=0T(Q^fD7y`F}yMddYM0o;S{p zV^JD#_G@RQr5NY?+D1E`_4}mu&K&%~Ofk~Q<_J~3KA84C*ktPB4RNt6Z1BP%-4mY{ z=Ct?p#`KH0D%vfNBiSR=b{}hhiR7YTq>p#S;W)NAL&;w;*MK&Tb-W3-3`Z)2x^f|r8a za+#pK2A>qm)7K{llRFoPT0;UIkzp{gc4}*mo$eC}yUft3pHsTTQai-XyMI*CHA??~L$00e%>_wxQ!r7i3z*AWt@k zUzqaUagiGV<2PO?g!bQDP@_X|Rj*WXh?R0*txq_n0gE=H>HfOda?)2Y(ifdxd#`un z>wAb4P{NhLT?4=(AX)$Bl6w)x@v_Fus6IXN403-d2Y->NK3UfN+Q=?RA9A zJ7q0&wDzPP0@g*8Sd*cJynDa#+NXu;I=P>sXMa0hbjA9_vP_{>W=_dw#(BQ1@qAgF z<{X}apJVb(ZGJ5KS;X>_u9rO}h|u{e?BYvwf2<(l91YkqHb7FXLsfu*zx>Hekf|@2 z3ZEr}J+LJ!Ovmn?v2evYV1By$Guq&{ATN>d^2cvtotZL_yBIv}sxn39zV085WU|D+ z6o2h755)fb9i1Ua3X<^c+#}HI7NBGoxngr?KT zj?J<&4NS;eP>A8Qsc%(zePNwtBA|QAEDnqDi(XwGmQo5&ETYDR1q<0a=LoEkQGpdkvvzh5m*ngoU4uBv&t0uU;x^vz}BiP#K4d{ozY8tMM z&%J2yd_)U=UDVR5MLS^gZyH7>=w$@U>qf#U6kWo~;2>4GAu8v(d7sQxvi_MDwXeBAi@_6#4wv31&(P0B3Zezl~?^c>GM8ID6I*Tp%B)a!%ZTlTw zI|15D7J?>;qRxhh!x@#@^?qEHWRLy5xNka8e|pB3|3|(l!AW>AB5^J={C~{$H~y*0 zx`5xyxj2>?8dX=@$RDK7t}eIDPnh#&rY_>je`?*hK?ucfWk8!W#zf-5lG64PUL^Tc zuiTj=e5yw^(1dQtUPoHOAw&a_qY*IL))IVQ|MFa3@yRXIg!Jlt@e%*#@)XQ;)M$a%8s z(-NU&HThh%VuR}uHGlH?p|b`8d@4r<)tU+sgeY{Off+GdeeGU3e#I>Ev}s#ZM$5ZgE732L`lK z!$7$!3(_(cr?g~2(aRLfhzr!y%s7v|4V0Z^0=}=d*43GG{(q;53Kf2b@NysNxGr2n zCnUmlxqk|{^MqYXj~H zQQ&{Uh?mulB!4q{M52?oq9#ItV{$0H-*D~Lx=XN7o<{L#_23OZPO~hi)UN6gTd1JI zp}kCO0So!~lugn&pj?ov5hoN7=Q9ao9i_e7J({7qfJfWb=PVTAA8Hv>uPQb4*thTf zKACB*gbP*o&i$5v5d_<8nX@CIPiZ^;dqs#`RXTT;s(+XY&8DoGptXH)2_s)*9x^UQ z;OW+>(D7Npj5SAWpWZrO8csUfn7=(m`=VoI^L-~(vN$u>;p)L_U!?ChaVcE3tIn$Zz9@Kn2LRpm)73iiDgj6jO zXfV0ELVpQp)zs>oqU9w?SI#M7q$pi$8FXLH)uIU1>5O7+6eTlkbFGJU^yey7{?LR3 z$4!Ybl;WNgInrMnKEkJBoR1Z*IO!W+m~G#DiKidaqo8%?JDB$J?n_nun81`ji-Fv8 z5XNyrbKh}uC9_!3M;F1}RBWUnvFg}d7PE7K(trEJOe=Y0`=-Z7pG4uMPbirsr0bjuh{P7HteS!!P#1>QMI*3$D*f`B1zoWrotvGAZ_CEUD+N**O>{SxY8+WM`Rx zhJO`3=MYjem9N76m#W-zx6tqggn?NpBpFqRbh<;?+`xNUkt|`ln z!!Je+cVAgJx}UGh@Z6}sx0aYoBhC%o&dy0C#wNA)V(r5vUgMj?t-SYW`vhmI0)IRf zsMsP%@M2vAoIILRNHw5&9ABvTca;W1he07`ZuWqMO}aL;;A@AcqlI=rn3&g*6LZCc zlps-p2~tz;x!h%j+ePlAYX&IkfSM&D?m61fv)4Jr_xG+#8Jr{cgT9a_U;N7K06T0V z+idJ3d1&^uyGfV6tQ=qV_($xA`hP!TzT;rPt1T@O{njd66iGO&LaWcrxCwu+gAw9Z z+^GdCF2rFZ#<|*sSEyL*Gi@V_Hf4O%`bmcsInh;t<#&Qv5MfNDGB6i)hkx6VC;Dn= zpY)~HEsJB1`*BG{^ekOn#1eYYyvByiQyP=wboXhIS%UhebReAhYwN{2R~Y(DMK-2_ z+CAIM$TOBzAVIM^?iNp<3UDAtKTW?Tif%o!-dc~7>gh6$`h-aWBGO8vv7Z&?1oWFU zlI>b~H!UL3~rG%{trT!heRI`pUlq^#f)U5-)f#gga@Eu??~bg-1Z87O|M!c1F<6 zndqe(cJ@n`S_sIJwpNk?*~;vNUjj#rdLKHWqbt4Hud0uT<&I-|yN>ebhT*TUr}GtF zo`H^-q8|!hJJ8(Dz2{l%S3*iHZ1r0eb7LD(;1u0|PNmLK@Mb7DcYk5}=xbzr!I@~P zn!xh+>f4fmhv|=_OB%AJ$!7LgHR?HtS$DoxX~6YBAliqhLiHM>A>;XYR8iu&GRWOt zyMB4ehoqTvQmzTvgmVMefF)~gN0g3W^mY6Do$XWbT>`057gA)g3|a|dU)e)XbAVVg zd?T4TKTD^wEIsB3Ie#YuUS>Jdj!L-@3yA?uq_%sF$f$iziGJjWIqtoztx?T0iHU{)4HQ-} zh8)R4laD>Fn+w|VSPfZe;yithnSQJk-slqDs!568^$ry7L@RPGbIQCRD5iSqM9cNQj^-Q&DPEIyj%(hKD)K}0Or$NK&T#QxB6E7n!1B=#y zfVEeeBovzp%YRws`6F(X(3)QWxZLRB~R6eX=NsWP#3 zPh++sEkFXp>o<}_IXl{C>h}T1o^*M*;W`mXs&a_h#`KfK@3@{W$zX9zw8>bX6h#!w{w| z8|<#UHGlfP`j;#IVaxw%no9E$R8$5+W{z734Y1D_WNd0S4aNgV_o zm&-nF{XThx5e#lHRKuD`nC-SDUMCK|RIN%NW`FmcViBat11^ve;O$hxPP3awYeS!` z1wY}aQ7Ai^_xc$Kgj6qfY6e)J=$y>?3^2e5NZ>i(=D3d6%D3+&I!BfK4#D5#k!lMs z*5|+pn8Nd@>%9Fzw)$9A1o9omBhN&**SPn*d2gkwgTeQan%0x%gFI7b7PX%g6>WKe zCVy|*r-LpQh8Zz-1)Fgftu2kJ4FlXO8pChIP=h@%bPK8nL|ey$?e{)>6OKLd#D4M; ztXhKu>uyuoU2(uf_0(?5l6w+~ls z2IBpQrdL{4gG{;1Ni@kfL` z?p2DKIqA#gQnp$z7b=0oi9PIL=BAnrE(f2FoUd5=$tuChxO|vi3jT}5MN^>NHLLV)UXNnE?-3mFd3g;irLVp`Wc?=q4 z#I%iD+Ttb3Vmu;|cDUHv!{{&{$_CI=tTE5lc4!kPRKTY!^RfChEN4dXHL4JHR}Bg8 zdVnbmuRrgxMcv1mRbxMG5uSzkV7Q7vtI|d>>gf$3;@kpFxU#$5OOe3Z2^RoXN< zmfJKbEw-m=mr&0oFPWEhUVrIxSJU$&8;nCIZ%E54^lX`~7yAH647%04wW+w%=o2`d zN&Hf`kD1Ol%5$Tp8$2$7VNPtYDl&LlyRYgwVp`Pc1};*jC_kY7<^7=Zhst{o~~dN4os1W zq)A0AtM|_*b+DMO^g+G>wR8QF*(6x9(bwa)+*_#7=+Nh@Ki*>NAWLU;)$B4{2$U(I z#PywsIyeZmbQ%~97wmNMmhi1f+Vc-Z*9w{)H3jy-@x~2Dx3NRvV1Y8w&HWoqI>q3o z({qxHztEgb%4vw!rYrVpLT>1w$RH?5oXR5QmY9jwow5vfgAUTE!&DbqV|4B4S5 z#t8-gG#R1V@S|`PPwG1@uHhpiKTNpUf7R<(i^-^!yiUSFtCs{pBC!yB6l@;LJl!)W z8X%3#FM@jzujazX_f69`4C(CCJoqRjPW=6956`Dv0}6XTdw*P_O+~P7@dK?+rsajN zH8UA<)^O)q&|cC9tM?_?x0t)_%ZI;Ru8lxm?3jdGfM1__1yG#Z(gq3>2n6>KoI!)TySqEVWpEf|aCdiig1fsr1PBC8 za3@%B*Gu-^XXl*n|Eun;shWA8mZ!T{cdvSfoLEtXPRImg1QZ9^g6Wv(8My%>a&l5k zi~vSP7J5cTW_WUPRSU2+@IP{Ra&@4CqXo#8`@bwi9Ds)4SDAmPA^6o$4rB|EcCrRA zu>hFZxtTb)85sf0jEr3WF$6hq14Ip-EldD%^Z;p)Ezl93Tm)q2=3rrF4t|aEpGN?t zF%^J`i;IKyFL!{D4bZ{D*w7XrX9zY2+Pp?IHnaw)fQ&7GV7LFFpyV|NgYCE(7+hRj z=nZWg=|K)={8WFm02d3eIY1fc2y}1;ngD*643Iap0sd1OJv=!;)!f4IZ-olT6zpQ? z00g`WtSyXzwvMkZPPQgM2f%A|fQpnXK*0`Z`?s;|-v+dRe+~!0M9=gu-9O&Hi7agY zayB$J2HDsd+PYcTngL8LtbqUpaanq>E0`8wXlwG@(9nO{5%lVB=xk_VZD{mr@K@@F z0C6EDfZ=O}|J3Jb>|kLBcBFT-u>M^m!*80`V-~YD5dqoQ0BymJ@W1mDwQv9$zn;4r z!#~ZnvIV)=di)2OTG*PH{w~AB$&NwI*23NiC?)!j&8rChkIW1R2Cy-5aQ{)@V{j8px4m_0x17Xx(*{7qw(t()Bopr|I6k7-aXx@E>zuh)p<>umn5GIV@hIq+YN{EdOHOZC5bh}jy0Onz@4GaEa=(80mb z4gR(HuZRuc!SuSOCP3G}rW?ROZwmsyx&VJ(YxV+|f*jy~H=3Otz##lv^f%%HFo^w& zI9LD-QhyLDfI<2X;s7wn{Xv`n2Kj#xCo_OS`43_PFsS`Oua=sB&}%%ce-YQK&gc(% z)fxYbSeRasxy8Sj?YH*zW-$C$^7}LyO#YPenuOW!OZv6He@tGpw)!vlN@DXT#A|=K zARD0Be^D~MlGy!;`I?{I>m-BzL}7Vlurs${`d7gGTCJVMe=)q0+W!}PO~C07WPVNA z^)L88O*M9MaCq(dU)%WF@&Dkz?pGkt6=)2sfZo3)|mjuYSMq*sdpPaAUouBNE>;BQlDe zf4P1$o8WPSPco0v0`XZRS(uQ!*kKStkst!K2Ts7mY*2+9#q(ob|BnP03d|C54(Xr{ z`L3Rtl1y1Fd@l8)O=WPa(TM5}+a>nLoK2gUfUQWKuoU@p5*gmEJNS5)YSe%A;n9(0 zv;l(N2tR3O|D98^U@)2(&j`LK>$__85w29x5e51sr5%EnG`AQ$)SHhN?N&izUPYVBd+HfltHr^%-Wo(<{hg1Max`)ZN8dlEG$UQ7O7Qg$PA4?hu;-yU3<8*KIdI@ zbqP}}+E+)|MxjT#uh%borWbs^KVf3{(qNoc8!6)MVzY7WS?#)^D?5K|11j{YbnmcX z`?dZZEjkj!4Is)cJ?IV(jKZdG3nQsq+8PMGBCLRnHGwFR&n>^d^uzi(1nPibfp;$P zi@ZN{e>#Lr2gt+QHMm2UDZb}XpYAqeAI=*@faG7GeL3TAOHuHZX0;Jw9Dh<~X_{}P z#vJkJqRGQ*+eYU?+X#QMaN3!aOWalvL^1cG!&st>M)Jp08VT5skBRIMTEA?~iJ+RP z#hd+w*ipjg2TRXY`ZM$JlEn-U_ac)InMk`!pXkNt1*HG}R2W~qVC{a$f9ze;xdsW* zFC572rmT#`pQ-}PN|0f?nT)zxGo{N6Jq^0dql%4usCr$r0#1yzDHtsiPwO-xINWZ{;4xCo zaa5Xv@+hEvywL5Q>81}%=k)-F5A*u)gLu}g?&|v&d$!6K>)izUQ9!}!dTK~_&*Zoy z4Ga2au5qg9;k17Y;b4{MHAj}om>8>ETD?f4`1Divu~t|^gs~u2ePNib0}N>N<%gk( zd!`ebsYSGzHz-FMjdjeUcA!krhs^RYs4iFjQPb~|_4nFDx~gK=y_V_9BjMf*G!F>d z+gJyH^iFn4+ZaTPI{tDS`xm-{x-O_(Bg% zTbp=KEoB~~XUMEttglze^)GG6bWzi|w&(@|a(6yh8Oo0N;4a^#s!l30d3^K3z{Rx9 z4U3-37GHn#FjDOt?=Xc4-u#tY=@BM7eMk}7(*r-MnZ>m=TC{$DbKJPbFW`rUA#UDV7AXd~h9J+}u3 zuAAO_^`P%gB~sM{bG}tkp3zKl`+&}y>Da(*nWTT9*Rc`MhDzRp7^9Ze7PRicKO4o6 zTTxvqVgp*+VVoeZ@cL}G^ugq(hdCB2e>i&hJ3SZCqEkVj(xnOV0Mvn@g^AXb-nw9S zqX4WOq6G^Nex0B2V5<-T@Zo`Q`0@%7YKo*%#&~~MA0Gaa|MAPCDrkzYfEpj8<;&Q; zTY-P?0;wGa3|X4m1ioRBZ=G)zn-cRU7H;gUX1ozzEr}@)rrQ@|bt#-0D0WJH2RV}4 zFmRBGuW!Ignfzfev#zm);l?%V#S7mF!B>a0c4xPxYI8m6UP+mST2GzJA6j897>&4c zhxshD)Qtn-&TL-vWrbWtA8K+)*bO@x(2#$DTKnlA&#i>xLx-NNkNI8VS2YiKHzl>AYKGprI-_@Dc=>LN(~)J6WEf!*Q#QI= zi7F`@fqCkOk@qbNS_ZPL5VqxUu30N*U|8?cF4yXpUo3^FGYrh8LzK#D>)PsSyQ=*ct78738_?7lGgc?o)_sQ%1n&JqF#y-W3T5g&bCN9c~A-;;Dn(Yel%XGE}na<-->({MG|hJ#GD$FU}G>n0~aLE@RZb>gGq7s zM6#kTU$q|$GLTT#-%Z(F?bmY&;N0NrT)b-iB_$c^smbq`jFPMpsvos#-9Ue?-r^^Zp>*6Dscb(8v}LRB`Aaw95Z=Mi5RKqj83yHQW4SMno2J(KqNjW}m7-qJ zHpStCltag2nV}-@I4i9}O|UPkYEqzt?$)9EL>!4jn0+YS4=+iD@1S%Y+eo0qcAf8| ziftt8#lSzoW`%x)eZ!~ZlBa+0%z?%B7)pxAo%EeHPfZ_7R#70Xad`BDyhzoqirn>_ z#mOAfB7YJx+R)@p=nmq}84LAyOHz&gEYSnby$G`N8PD@<;%4#iwbAkLmS^1kMcD)% zeIIxerDSO-vZl7=eytJ8AJ|wn%JzF0H~G@q*zw+`^Qcfv=^U~fOyV`YK zjn8u|22akp&vv#B0cwbH>KbJk*YrOzwCKQlX{q})m37SSS#xJ`frStu@VqMQV5Uav zffa*xqx9Wyh@3VEsY9$O0)48iPiYsk`ao1MWEC({p_(z<(N}+w4Z#S1&>$P?u&b=- z*KVQI@Ft(9LHQzrZ_2O$*@$16rbDi~%%YUZ{^Pc}b&Kk%tFSdtgcoAkrF2jgPt8YH$a?`Le(s&gJ24Jb&?pD%(`1FhWeBp64B@dqxm$#> zt^o6^-zj`0@UnlWCzzbr8Fd{E{NUp+lRVSg5-4l2Saa5jDfdr>>z?S)tUB6Tvxkzc z3O6nv+GPl{oKJI?+`P4SkgAPkerVNC$nHANBs*LK1vhyB0tvU@ufYDq| z5PIUY5prL+`kDFGq)VQMWIN3p8)hoLq|0ut<2vPi3yyz?L=m!Yg8a9fn&^QwPac5G zyJL3L9-+0H*&qZX_(m@s1wsC`OXm zL0MM%_6+U2^n-(FEJ{`_stTmbX0w|gX91mRg@a?Kj(b{dS(ZUwdGI=YU`dgKcPFEF zglP=$q8ooZfc8;14-4SH7GfGy1@Gr-ysm@EC(k~5j}+sY5bImU==@O1Vys0U5!h6k z(^v1Rp^IHu}y$2TNeGQ*PqT;-*jdq>m6hWvsbIySz>R!pE;nq42* zkn!EMx4yk%2O&l$5ws#z_80vW!B3hPhf?_&L$j%G9XfTEn)>{|ylg%w13?DP@f&Rp zCLe$71db+WtEw|i=R_vn!_=0}w`xFN+Xc^FSi$54OpFNS5}{Hq=*n&5d`ClpL&dya zj@9$4oSIWes_2AwYn5@#N+sMbrc>w?(!AKg5h18E z)BsxgYr?ZtL`UnmgqZm(#h$?XfFM9V#(IAhom%8^xjVG8+YzlWLC;`;2YP7l1&9+_L-2K?eoY=)*ek9{+&(dGG{zV^LOi-Dz zAN$R7O5;0uC}aLO->z7kV0Bv}{Ry+)x-cMc_iB!2~PZ&7i4rGA#D`sT;*_s@TU zUN#z;`*dfGavMSu?v4hIMqaVmkqb}#jxB`VtwT)*2fX6 z<~kAvMsKbS2{{YWo5?6w&qwssSTL&X(;H^5PPQ&Yph?PKoVz1ht}LI?Afg0PbMBYN zga~GuciHGm9J#x6hw*qMnX7_2>jZzSyBq3^G10f5AruR5E{TD#`AY|MV5aCF47d!# zaYnqsNeRnORu2q29&0fBQ;DFAiCm1pn6E=nTStYQ669!Mb`u?64u_iM&bVii?rop? z$c$Bd5AoQD%i^=!7?Z*`7X^celbgJ^Md4;hIe8F$KA$(dTsXcZ$k98f;WK{|In9e} z@LLhM+dKU3{*EU~UpJw{!Ta@(wq!ze7z6kbq5oo!U8Iyl!YsNq_3jHEH_Dwb9~arx zyR+d#Y_bgMX7;$N`w?>olq=!@I3i#L&)yia@3h7seTj+pjl?sfSn9?E97MsYAk%hJ zVU(*yO}KiQJ!0H=OLci-CF*~?-A}Uu`8O_Zx@+?~nahsM_BO}Q0@?IG3T2w^uX#MK zu2frD{ZWH^a{6M5d=3PaweJs%8e!_}m~&&3-%J-M~2Df?NiL&d(nku;8m;gx@X_3I7}^z6`7 zoXu759HiWLU!6Lz@o?^p?w1Es=Zv4F8>2#qrqzz)#v|zSfURa%=`ykoSP96Bi<_Xu zOYTn6a1d`-e%0Z=ff7>4p{xpa{9;;5PPzPGHzB$tNy1D4ol0jHjv#a5T@z-sb;&}^ z=OlKaw4ay)OL-{D%Ts@ESu-%&e809JwR6Yph)IywwDus>U=}Qq@Ks)AINW%MdG@jG zy8}9X@X8j)oJh2uh;Z&k#9j?1--<)*ltJ=2W~Q}$B_*@&N_Uz(5HCw+FOjjH;7Fi& z+Kwst<_tkED)k&0^F5k@qPNNm5ueP;i-6eOt_)sA21Py1MOc5ngAN%p9GUj_NCww= zJC-hp!%Z!<&lUCo(2dlP2DuJ^(iOZWBs($gE|<})>?tfUV|0Xs zoc@Y_KB=qyuwsAdVT02ziJDZ(t|zPU`>{|1u5fHq^o!;tq_AzGk~jxB3ydR>#*N;+ ztyt29h+DxeCw_(8_HVIY9dr!mH#}@xSCCt~Uoxf}dOQA15LFbBXO+=uS~-8;6%ZpmQ?{MHNg_Geup(W_ zxr`T7$-VcKMxc7Rl+<~P2ZQNFn>g*PCLqd7ViDu;@L9Yt^*S(w$;_E*6z*v6vN2tzsF(7xmk zn53h1K+lKNOQY&d!ZZX#uxtqDR4rr5XsGAp%t4m|A=R4ww;fdRBrsgELJnj;pKD!V z+aPqrBGQi{{oO&nmju)&nw08k1+JZ7A+K@l&pLky8*X|iw0y4mk-g<=(CsljYoFN_ zU_&g07q>VCf&>D8?ubISM?u8lYe!$Yi6$;|zq8RO(kG2KiZFah_H>~_lQLLGsqD8f zH1sqaa_pp|m(EhPBVid45~SF56YTtjwK?O@00R>Q*^>-nxQ+o&;Uc&qBwbw5jAK!A zG@XA)PU_z(@m^vxIXf!&wg#xasb8|1V@om7bi7ZNjIIqZvC^>P*s*t0p5`4U+;BzU zyQIr>4t@J5F^TC_qt$xsZk#rISv^TdWdV6+qdvbzSs|OAyrp3lQTpcDVS+`MLs6MW)YG|7G$5iKPf(HR5H+akSpl{g)8;L%>2&tZQHO8{2Zv!tI zRNtcI9J_muprJu#zTnB;;|6og7FJ5oeCip?5ss`~3-3PQYk{Sv823}b6em<0N|DL{vA}*PG0Zfbc=MTvnkYsbC*VAVuB3md{tnH@9mEzeQn*}RZ&Cq;D&~{$FiO#n z>Hh;}sJP(PN4Aw-fU#kPZfQm(kr-m%{ zg?RY#(qT;(wyz8%V;i1UX(g0E95M#%Rq66B351sQ1j6B~-fVnExhoKWO=}>5`)nX10G&^NzifHcu&fHm6<#CB^)kd4DQ{v(gkLrQxQ1%Exy% ztO;z`N%eZg0jq)jm~v~?pilx>HVJA2fv?KqawSOX{l3q0<7QjY2X;NCi))a!P|pxu zY(q>aCKUy(ald2+4$-w`;oVy7;TnW{n#lSEKjMUrvhNdX9InGp#NL04y>A+lYCU1U zrG1c6?IjC|dY*90SO_^zcq5r?XVJR*qHb)St&43f0unUrFC-ng#iR^mL1$vYD8@XAzt#9F(`o zpND*{M^R6PrgXexQVXj8Bi>TQMQi z$$!Q)+Px6%?WjjXkMKEB&1UItY{7jL+0TdI;5jsq*jSwwg zyf*i}>*6%Nc&;!nuD{go@eI*zk;eIa0vH@>LoU<0)jofm@#+XN4k+-O_6j-t)WldL zHNk1_(?^-0H`}cY_qqvCjtc!V^+@ z+*+!@47GoJFduy-xkbYli3O3xw3x?Ckq)EXVTD3ysk1ldDm>IyRqVcAEt%e!DD*KD zo++P}rmyj}$(PdwgcRN7^lQ`@X1c`fjNmz4n`s+WCus zUwibb;U_FMkK51{h%sX)&0Es|$zf9EL@Jz*}kIkU)Hw;QnD%wmr!n{}wR4J+L&;BuKlN|WC?@HDE zxKw{&%0vTyou!cKl0zo8RiE4L$wULKPZnRO%2U7oznJLBxGQ@?!MAw7#O!}xIdpVcS&_fp0t=mi@QJeC#R zWs_y^exYde^Z2>lcnc&z>P2Vv=fVq^r0+Lk(yIN}85RBO%_=bs-PdmCrq*=sJGZn0QXy zmM1RKXt|afRtiCPHxDEDms5vK)lZ*;U(0;OdnRypjn(?|BiAO6LycD$+lvd{I(hdz_0bON!)=tk)+iKxSDDRp{!E4V5))?kZw z1>!+2D;=re(qJKb7`Mu?t}YaR;{(P(mFaNof_3_Fg1e+ELdNPAq8I0uFk|V{4SROJ zp`J>^)%HHEila)qkdMn1N4y$kkSOy}KVCi_xPO3{6^DlW=n=;Pa-x-=p_}!%_&A&e z4j{>L-4snLdx8rRv;3-e7{tYH(pS6;FIgQ(I-pg#y+e|?B>fUld|{`5ND^79gtbmo zcpH^nI4PL0-Ia!2*Z9TK{JtD}@2S?0=u3$DN^%Fm5qG+^-Ltw_v`Iss`9TW%SW3W6 z<;gi7U-5WtRfgjOr;vs#aAJ9$uc5iOmCXqzjXI-)vtKyh7x^W{x6C~8$ z&O{U{;;6Ta1^sS8M%Cx1zXxsYqB!*g)#;eafQiMxW7u81#NmE`7bS;0A#HLn@`nTh zWH;cRYTj*K6q}Tb-j4y?-`kjL|$wLs=-edymnEJ6s|1R$LK~D|&YZ7LcM1`Qk*hDH zLZBR~CCQRwj3glTnB1@bJ167NUFNC?vNKDbZ}c(}=Zz+Rn>pM2YHQo=BFXe#p^dk5 zNe&s*bL8__!g7{9+qRu#j_s_UqFXKy#e`fxr{S|n_C40+#f6+|)i7iFJalOICBIe6 zw9XmVAq*$N2=jiP>(ClE=~c+F+!QivrFhw`nMrKVGnxb&>*+QWrzw5ajfyb15MfT| z2@}1glljhnE!B#4(SlpL#S*=rC7~i-iicL?9Lg7-oa8(?@fpF`d;p#|nm)1s*CLgSlzI>VdsA>zW+6y4NBWA0dgJ4E`XAcHWA7Ve+{!6N(Ep_E7I zj<&o?O{dJkgi*h1XOtMwV;6-X8!e0nSk<7qYDAirgi!kW9;s@c2xt&IH$^igap-po z`Sg%M97=PU&i9k&a^0h?r?lrAY!UR{6mE$LSDO#ROUVNpaXwh(aDSupG~w1MX@pS` z5_q3~e-AaS5^D#^k?8s!Q#EQ z_`8pc`cQ8%6R6%o*Vj?9r2uRsn>JS*uR;!tji{Y=%jL&VdkWY%&P!W=#%EByRPpU_ zc9TT$qPb?!N|ovM>FzQaJhiibMG;lJZMr>w!eY_Y5qaai#9DdTUl!zC4GCM%9U8*< z_4+1Ln(zyU@Uuy4s?X;aUb-K$(5oVh&dXva^kUcag`5p_jGrKnb+O|T?Pp}iW72=r z&cwMYOGV!orm*XLvg;z}m4oG^nP1p#&<&C=D0_@mj{e>NGgA6popw}!#x}cYEXWXl zM+$&qZxoU=31oY(v?-4qp6y<|?ub9%Ni}H6VZE^B4#yT!oF+2v1&tgzx6EXeC0LMx z<>+*txO8C@>V<5au0Ic@Kr7LO#JthW>X%VgSf`6|$Q^h5P54WFPfL|XGJfpc@s1TE zo2hMVU>;5($MEOuuSrlfq~^N%%~aTb-SyJehhbi|nOpA=7mW~YN}k%&oWCNW1k%oG zX}=MJ^b+C`r1*(`YKH+iT<~aYfIzBw_m0`4XS;7mbzfrTjIaaW0IrK;*y{1QenS3~ zYEUDxPufIy&BxP^m;;$$YcuGatoH4!-aV&1RS$%j6{bn4Xwmt6sjllB$6Nn@nq0?F zoHPqWUBn~A=y!YW=&J+WPKw1cr1@929Y5&%-VYIoaX8d>Z0IcG^`gm|4vt)t?HzfT zpSgJ!2E~iIRDe*4nhniEke-n>k?dv5y*pwwE7OdT+hnmFq@oIPg81FKY5Ye-GK`Q^ z1WPA(n)k+(9;t2YCYB)2D3nQmxU}O@2$diAIJKg)6UmM0&y5VuA_}ocZ!ru?+0mag za@@|HxH2!e89fE>K`1ZS*begZmP;a7L{_cRuUv6|b; z?#=A|Lw8mcwjgDH5mSqEl=sGpF$Y}9hlsQgHB^w;J zGGQk!`g*g9O#&#^Pl0}lEmC})pKTVl3=A;w4it!%?(a_Laj^D|NzSk-Kx&)nytKNPxxcQY=H1IeZ8D&Q4hMUpeoGaAlkO@n{)y&<1ZsB7HMY+h? z=&r5iEZpOQ`dOZL=I5mgyT#_*`|dYP4J@@$TV?ZqM@!M)utmk#66W4?3)-qK*ISS% zTZJ0>YfgLOYKSf|9N9SEA64dSpW%LKK8CQ)&&LZi0EnQaS%zqW!XL+dAs2vRcA_4IdokdhRpk$d_P*ZJ+zZU%1OZO4JZze#~7_=gk#Sv?s`v{v1MW$w!1%E=RLx=#f;&c9vmhv)Vp+WKU; zZL{MxS@9PVDg~6(b**HEbu38lLc!X9BX6L@vKpC;N>Jn6#J78jwUoPC#ZX{B^58_} zBn5q3Uo%gME8+;_y{M=dWy!~Xe~Fsnnh2f?^+sv;e2Oj-kZRSfw|>K%gpcvGx{vRH zSlMF(@uYuI1u0RSRuAj`K=Bj&25S+BhhgB{#Klup!0}8o?HX)A-QeXxI$FDB0&dor``lB2*ER_UvgmJd%XOSSX;H#Tt`-s ze3M>C9`)@~t`oIFxMumd>!ag;qvg+w{R9|iU(WaKzSi!;I5$pZOW1Yt(%kBK3KJdo zyYgceyLs>STV?DmRo}PE>pO{`YURMWOnSQG&dCQ^-#ZyBhD%+2_4%%U@02@ax-A~OAKFs>1fp|jNs1Z zdHLMyQLBPK<9>@j!k%0!q0lp?2bsMec$>)5iM$Eh_GkwIR3lT zl;c7T(s*TUnyhv@-Eb9G+qHHd5gSH70GvLOl+oZrCC8WbFqBGV2=x_ti3?S#*&WDj z`ho%j@=6J%q1YHS2SPu884cLsw_Gec@rJ+Hwjc8q&Ql?HY= zncYWb)IhkJEUtx!{wynWSgcD-Bp|$Fmd%WqCJGw6vE!>BXRvF3^XaoQzEf(}rhxy} z4KnFSYLJJED3@B>!NvaAknkuE9uF;1TgucY{fW>Hxog`GA{2I<5?_c5ZWfU&h+9!; zM<;%+#bBFTt!nDsq*q2nyMoi>*1#7dc9LM8G^rn^W?B5?xoYNKdv}JAo)bTDfDhhZ zjqcG!qZnt!%8x#O^LwL1ew?-LYM>v3-CMFAyNM5{%_Kb$8>buxY`#1-W`#$rC}(?pOQym z)Sw2Mqdk55jd29OSItlxqO6}0eu0;`@4Oep<%{Gc_;3V&+-mhy4J(VjT3$yzlrHS% zbzrQ#n1tR*;Bl+iq^lA*Mu9vvj}dwpBWjCMI$q2XJ;Z#Iw&5jP^8RC*@%vPF&#z^{ z6UpCo1k0q|mK6+=RJ0P{xas+KYwc%wKKTQrcz5{vQ_}Ah5R7UUuS}`j=f3-+d+GTz zYL2dYuLRbA2FSCFzfjMJ_8pmd=w8LNyE%D(RdfEZ?tb5Bt%9ioy&1$X{1F9Rw$peg z>&tE5RYG~&Ke(z1nQ`a(3#LZZCV>W$)}NVY4h5frGYO|$C30Rh6QF>*^QKQ;jTr)ZxZ!s9X(~RoV1-7K?`fq;_XjI`N4> zw}oh>q&*Y6EgMB{5KUaqd@z*!NM4BPOVU?=0jw=-YJ`&sJ#x!Q%Yn$m511{Ram$7> zOQv$=!QUC2=<#~RQaA4MtPZ5H$Vjy?0@r{Q#|kBMJ_e)Kc$cce31%T#{HIl+4rlH_ z2~^06jx|icXGVim3&U?!xX`oYl0W7BCC{pNKHn9s&3f`Q^X}w?4EG~x1^XSQSjXjI zYZYdy;hYE5Rwq%h3E9X1?mne?f60yacy3W0=;msVImzn8KjZ7m_$K9Co@0v>zfs8k zMZ=y~;tk^FL>RUF21Gj=G!eIzb9xjk5Ag7_BA^?Cud|V(9FFq5KJ`~{y`Rm4K zGK9FgLE$jb{{@hLbA^BrD4#qSfx>CPVSuW;Bf!H4@Cb_X2#JC~051q6@-HCVRTPj1 zdq8af4K6?x4uiPiGs(f7yrLtt*G40o6f#1%jt4(O?<16s}y z*dMU^9{>mN_ig|lE}nmv`DJj=x6a{#6Eb%L*_X zIk=M(1cq?K|J9#7)D>clx^{2wKbv)c!98KVe+^qG%*OWD5H{}4+y*eHi#tR`{x1aO z!vBxY4uSv#K*Bu%{o4iTKdCA(TR6Z2`qM4yn*Pj=#gKzvKT$80-Xf^!^J#k=7l75`YFAB?H)hLyaJR zM5_U@fx0{WcT@!dMhQU%W``m(Cl5ati2sj&AL^zE^@7-FLlM^Ye<<_EZ}3ZMj!+mx z8}0`E^=(0Afk6KiL+Q)f0rmZGL-F!Y2<(Ou8{+pGf7uX}oc`H|0?Zn2^GkQU0)hb8 z)fMcGk6Jy-5&(R8Py)4qc>QKJz|94NBTy*-YG!}H7Ve7wYt1}7`~bJ>FCYFt>RP*h zySkzd{!Iteq5rafiyH#*f>`6vOv0_jLY`KKyhm2aPE*nbReP;C)5)V~@${pntPAqx!qhk4wHmrwZ~ik*I>jwJI;(`qn=|zBWZ!cd zhDqW^v^=9USz6H&*Df^e2hk*-@T6>i?7H-ri2YcqJEoI8neUY<3aN&^*ZlCQs`Q0A zIgNUEn(DczOcwdpEfWJ^OQP^panUbVCE z+t<;Ub^gQiwsH5ov+}8v1JT!p^WzJ*B11yr8iKTxu34S>N#k)cYfAYFD+^Aakw&Gv zgkeXGg+unXH{am8&X$j_IvyE+Nvs+@?UG0;;6DO0pWWGswF=-ZNh#_^eu*mY=%|xP zb){zeyd-pa={M?ZW+W!(r?vD3E+|cgJF_w8PqGEP{8IYFrGlB96HYVfQP}8$Zyn>ThE@py%@{TIV9%V+C zaL2v-I0fIEJc__7KlLKZ>Fh=Qy)ZGF7Ts2eow0h0tsPN2(T?2A{9h z#XIgLU7~NLMUoGi4nI99jUPPIAHt`8FPj|~Geay&ME*r#-;ru~sG zQU6Tr40nOp$2QYt73ob`aaklOOjyW6`l>6&l&$eSd6hc7BMxnU)$I4|MQRyhgP+n> zq3Yw4GhZykdRs5~ys>1qh=~-!EQ6FhSZ-xk4&E7382FsAkrvjsXm^+gR2vY`#ah>T z;;PY|f+FvB^9GDvW2gP;WUG4t!#0P}rng*}7uIGq75)Qplu0uC5OoMpJ4H zzvrbUk05`V^f*L+k?G+3HJ7>{mG!odQPCX;3ENL5Jn!gR7Uz>02x9_?Q6fVrA5uca zgu$+s_Pg@h$c_+&x9Y-$w5{sLQLJU_246&JIm=ry>EyN5{rvY}t~Yj%AmQVSC?yLyGFZG%m8)#XYaX8^xAH zwh|1oXGW>E(z~3j-H;Y&R|e);)}3!|CtHNvmQz8$BwU$o9~}1Iqy!7Rro-akJZ@O% z6l?xT{jexOZnmrANBcp+w7ZeH3zupjx?M4oq3JRjJ$(dv?>nX(a(#2#el##XTS*Yf z>UGg50S^p+x8(hl;y19oWtBKt$h}Y8)EKP2M-?-QNNP0?oK(IMIfAh1;A`us&<66C z{%?Qmi*lgbzWY(m|1&6?;a*s&@a@WJObasGJ+wBQ>9vAdBe&F-&$W^U_jF!%7T4}{ zfzVDHOuL!nOvECOc8ZT1!#x9Ug>t+Scf!tp!{&~EW9J)_pq>c!eWo{zVa=#RFR3LNavckj{3lHTMOd%~R6Jv)3%D!seehD4pfjFk=V?AdM zP2!@ir5B#wM}B4JA|y{Za_qzWC-NB2UNiO@?F%8#t~Y8tj<1GTmYV0?ChJ_=gImg` zZaA-hk1s3}-&2M7^)bDp^rI&G*^yHa$u7hcJM1jt5aH=YZ7QSx_=hHCk=Q(QuR{^& zMwsovdR6HRpB_e}e31a2O8Im>)@ry#Q$EFu&fuQzr5-_QTvlm*6%qqPz65q$ z4Y6T3Jd(X3gI+rLbEK(KSQ4%=+UY7tfdQX?X$7vDe-_XH;URl~9G9_bCF)-~S7>}A z)ESKDOnZz`W-#|W(CAzfi_M4X(azZfbLQRjh{sk$n(fVzZ5GI~_kk}0tr)pJ>c0!^J-w}*%{qZ5H+(ucg2xTR#o4f|e{TK0M0jf^zWYGRg~w(PP$wvV z)w4?%e0R}YWi@ESg$%eCj?h^r#rFs zG!bdL$YNlFs12oo>&?5WWGInjllS0>gcLU_`)dh1&+B+A3?^(Sx3xssgV&|6E~ZQ~ z)U@&H20U(mU~`sjm!7whA+;lL=8J%TZ(I>YcGvdC>nwgtl(^k?spQ<-zca5ECL)Oa zslL-bxX&QPU7oc5ijVfx$!~I0>BkyZ8YH+qNu(5M#UION`OY&#%^~%fn?&uXJGx=w z%ssi5cjBC7mg)KFe1p{?vd9;qB_(ovF*#!`odsh% ztQN_FoPD%v$qYSz5NHpR4G__P;otO`>n3eZe52-rAw(~3In0ruXZ#r_l@U|^N?bet z(YTsHHI`D6cCPkmJDuLl#rBc)n-62Lh|8E1PJ2_D zW=-{s(8e?6ku`uQD?IeY8+WEA7ilin#4IGr)-NeUDhyg9BY1XyXf-N@_%+4z8}u6+ zoh-dNwGveLTGwT$9uQ6H4`bOdBbF?s+VE9ft481Kyu=T-xz;9B_Jg>uTD6$Z0dV{oMh{h61K;nf+}opp+d1L`M1k#x(I00l(es(F_uWVjYwH7K)eL;X-MsTm z`}DntZ;uYV!a{4R$;qH`Fkt`5bZewqkn%^?#`Hb$srykOLH#m+jzd;WN&EqP{@Nze zUM^y-iR*f%6LCiZw5@}P7wsCVW4SSVQG-mEPZtm*ihC@F6(#MzPrTENpu}ieCE@hYaY9} z|N1+mQzS#&Aw)R$yjV`&>O(`7{|B{ZaK(7>ZG*Z`uh&_B7K9&M_i;H?&c*Uz+U(VG zRGvR76TjuljWN>a$N$!EPSMMUh*3RytBlnLF0p_q{9}T*ECLoMz|?3ymTXgwxu;Gz zYTo8Oa6giIg?BZ4%cv)qcbeZWF?E@k);GK%&8eW8FDVelPV{venc&CKx0J$uq&O}aqf%#P21@vY0umBjj5R1Of_a`{d=r#qjRck zxQv%RLKO8`{`<{u2X1+*B(tz?WgqmFJy@;GK5}mQ1UmQ;gKy9)9P^qRn=H{RVRXog0r=zwBS3cWL z!8P1?$wy7K0qK$0>@LG*DhV-j4`%PHT}IxUTAdo7VkaY>yqN|`=B$_bxHRH6ww}CI zg!6nf_feHc-T}3&)Eef~ubi_-8zZkv$LONaOiX9Qa#e=sBnE~a+2LVXp7FBKxEQs6 zwjY_cBXTFKu2}8a!B2HZ>OJ%qy&6J9U$#H>U)d#(4_CozPc%)}Q{&XgMU)wddOqOK z_3bs-I#02pK6|4?J;48r^YjcjZO2;`RsTp^YO)h9pH$)|JI{9re)3IPXwtIb?q^&t zrvwIU>L6Wa{l_c?>?2j?5RLkcQE=^lRwW+a8#?0Q9)On0k6I@4*s>$cgT6d}{&=X~ zpk|MkdFdTPI&3F1-bYvF$ZB16WN~tzS?P0@+)MmzeKPDs?=Zi4DdKaTZ};xveJ4UI z?r9I zguTto^d3WT3?uH#w>L);`!*rd9Wr6G$oik+ri&)M0-S}*qO_nd{Vq!h+rv%e9F<>w zN!UM5jH}kxp1<|QAXPg_uyW;pp{0vAT&?=1u=v>w#pY9z-26Fq(3JeEtPQ;q<+hRd zI;PZV&G6&4O9yUV+kh2JW)52`pTq01q-tUC`YvO1?fwwn>~gnhWn0GJNUgc-;Dsc4 zOVHSpAljEIx1Oav{ZU=6n-m{ADUcb0L)YO`ta}-(inrdHEc#;^e2)l!(XB@-BN^Xv zCHrx!(58X*-E?1>7~j|gR8Oas}uNz{DYa+jabh&t~#F_TC(Udv0g^7^c|fz z9P*tR7AG*8A9OPg=w$r}T3}y>H|2T}PffEC77}DzsvZi~vHhf!71^A?2ERhEj>hTK z87La#Q|*j5oV+WKF->59X#0V=DitrC{Vm`aMt zfelx*yW!(QQ{M}~>(SuPR9EE%W|$XVO_#bx9ppv_%G&AzW?RYE;s(5kZkey0XjO5ngi+=a80R$+&%R$g0Lu#EO-CI3{GKO&=)#spPtvV3qfE2^ zHO7p|qbO_NX8XyrFS2jnazA@saa%ghSfYcluY-So`+#MJw<#WraBd`ZlFSfi9uQ6^ zY6zk)Q`c?PBC3EKUy-cOmWfj^!v)Bped}=9`WPqlIJK*9!4KEZFcW1RP04O3r{HYNj|eL!?SpjNBZ;* z2azdag~1V`!4uv+JRRsw5roA!E7`X28iVNIg!Q(3o-W=2w^W;_y*nsoXDrlZ^J7FV z>obLvbgE!W3j!JFc)sLjf{rfZV)#RB&Dk03Q*X*Ef^MyUG#xdy^SSJjmmcB_pFJpl_*qC9PAN!Vf6Tt!%u|E z{RLajz^ZMez0*?X+$yt*ilBD$eN`*muAO@4cg|8A&L4@6RzGl8l_Wj9(Ht6ds1c5F zx)tU_WFgUiBu>q(sLr^i!Na>bjtdhrem5eeva95}uoyR|WywpyDAn+xO`O#xF01H) z-Z5QcT5xXq+xZCo_eJ7W7*yMI)7utY$X6+NqNj#U*16hI(qyt#_VhP7%OwieSzUdD z7I7qciT7l$$olm7+^IgUbW@DQ=gsjwy8f=Z4xO`qrb*t@pJXNrE>1lyNDA{YI?YDV zUX9LO_jj4o7M<{TpnqQ6-XGafv?94F!!AXdPDE#9Qtv!o92wj<%f@w*9oXQVoxSHR zljs|sD6&LeHNP98*o+>~dtf4eH|uYbOekcav%n>I+tDpgZZSMB2m3VmLz8=NN4?+f&PtzMJ9W!rk?(%WvuYDdAoR*jDJz}Y+IZWy+C=)Ax!>y3Y(FZ;198||*O^>>~wgy2Tir>f7 z$4!Aw)%VfuET5D-ood*M@!7PGGmcN}bZLbY$!tvzOx!|jaW?1j-Mla_x~ z2S;|Fpj-Jt1rtl1z66|_fqvGUGd^E>VHx<-FEPl2OB;QaST~=1sex95Q`zb&tq~MRnq>0_^Ao@-@txs&@~udM)1$Gt#!0 zh@CnOOl)$m)z7nSr9mm}OBQ5+H@7N(jHC>48|AZwH)&q&n$1e3JPg|LcC#gQMn33` z)t@&_;+0ZF@-3Dakvw~O#;!D={UfhFZbG1AX&Fa=_m#z%NbeMZScXktRP!L?>(uR^ zg%bMRPwk$(LM#+gMZsl=c`Pp zZMgvPEJbAHbWm8OSifvjaM=0#dukX9jVXjcam_96+p_XI@3oWo5^iZd!0?H#=vYu7 zgBhx(a8idKca}I1YS^Q{_2%e*TSd!0(X+3iembE9Zxy>qH$GI9Jl%{VY4~V^X3GA7 zDB^A^K5kxMXn0v18vU1fcd7}pEtYsH9OEtXC|vo3mMSD*6Y^S6IGW_HjRa4I03J?+ zQtMmXO?c5qNl~{B#vwe3fqQY{80`zR%%3$(r1yex_o}$h=dt!ku=8Jk%^}9u!;kSL zzo~4op5=~3T5;b-Ow88oJAS@!#;q7ad9y*3+oDa5PR8j$W5LbN*Jo05+TP%IBE~u zBx9AI_bf)u-Q9gPovv_ynA`w{bqN@vwGckC#xE}zW>c*EN$|*3^XMcv`P;%zLTZH9@vnfk6 zTv<|ORDW8EPS2z%AMnm37K13=DOA>@DU>nrS#yWaMND1s{v9tB>(wQTlyox^lZ0ba zPX=Ma^-2@DLII6s!N^k_^kX_O9;gvm3=b;e|>IbbNz`UsMC_`!7k^C^rYL z3BmP2r>#1(LUZbWc!$KKKWO#R!r;z2TP3N7f$}MOp_c$d;#@pc@p}6&9oO`5k-;Q~+3NSHNm*$mUcb|gchRv9y z3-}n{=ZRigMXJj3xQ?YAsyILJgtx3EM!eXPJcU>CN}R1$g{*z2+aUJck?tSszboY^mv00?`i4PGu;0H{NRn&3T19& zb98cLVQmVRe0Tx~0yQ$1p-u)Bw;9j_<{<$!mhuA@5HdCjFHB`_XLM*XAT~EMHkV=I z0u%%{H!(1mVX^}+eoU-~Il3*SdGjTJN0a*>Uzh=h=tpv5r2MtPR{6q6CK_xPaWeVgPwfO;uq4 zFE2kgFE1Ys6O#cH;RN}M#$hsoxVb~&FtPvUAnyhNA&{H`e+Yr}(}cqSY93AiAU^;o zBnA`~8Ms z1m=#6@POGs+yKbU0s5*M0Bsit?2og?9|umrUuOdVas&UJ?yu-yiJ-9G!5}ag?(71B z`9NWI09&XN1fZ>?!Hw`nZ~{Oun_rF~CwDk99^?sve>#Dzkq*Br2LY61bpaq`gMYQ> z4t9gOAl$j#p-#VAE4_h_3*@&E z_=`q%e-Pm30(Sw}BAb8&Ky4w&KO8@IkS7FyaPxo!`2BaoKM@WP2(W>I5ddq59TbN1 zcXlKVvHgRQm+uDk2AJ_8wFd<7{`&oU^%N;D8#v6#=WqAl_se6bub`&$gyT=g|F+4= z!My=~TtEO9pCB&)2oweagprGYe`e7ELI0|PfA{ZDRhTUt0Ob8sE%KQDRk7z^0$}}X zIM@LHOr`}#suluZ{afVbyn?)7YdG33wCYC>$F9?t)1RYic1gCGmDLyDOTD8S7t@P~)G ze=9+~AvQWt1lazMWd87mzeddo3WMmt-J!qU7GxAJ?|;~k^96Q9z8~&LUH&nF+>yhE z_t^sK!yO2 zJqG}6;chs;u31P3z$5pI`i+En0X$0oe?}rmr1Ll82k_|sM*k=P?BV8ytnjyPkk$PQ z|9%A^5N`+=XMP3_77ul(4Q;=umZkRM+8C3-JV?7R;o}-Bu)s$2D^6N|Nz~8IT2Ozh zG~WkQvT*3ql5@Ryy*zv3w_ZnA?;~)=MW^)5j?Ow^=I#u2D#`DhhJJ>y870>^e?{(* zSg~6_iVkhegLn6(ZS4B>nF#$^YJ2CByqHN!l!Vp7+O<00RhMLGkkN=5?XBq{TC4{R zHUv*8SaQ~!U%V&CVfXEI zmh9)ydRieumnuOGdm()(_?uIDPgYUJ+SMndqyneJ-aIDhKOH<|4S4IFZ zT%(cHzk&h9PBZS$()k+l#XT;c9je0F7-^v$KrP%O5?VT7-Zyz{^UCb)f3uigyQI(6 zlb40jsdl?hZVhb6rRxLODWc@A9Y2)}GD!tZ$Pa_VMz|tn^E5T*S_?$(S;msI@Q8}) zU}ozz(cwBB+2+@9o!UGNA-G?Dvr?gG*iU`aXE{Os%=R-~_AdLC!#PRC^oS zE!z&QyyJG(f{^@SQS43hYc^|RUwZfJCnus+gTe{S=ek&pq*Tmkx0~ahG#A%AmPveQ zem`mW7lKOnhd(z(e}xlqv-Dae!bKuR@t^N^-I=pV9DR8h?f;hlSOG&!V9n@fb*~rW zqHDHJjyt%iXL~z4qBw_1v82q7M%(|pFQ40ITHTrTPjbEBE4#Ew$=8W@lrmqFYLMTbH`p=tPkv^ZHojLl2_lCK*_c<~Lk{84(Izj{U%t)kB zu8FezKRAm^tZ4Eq%-Dfm?j7L6?Xz&w#f&{i>OU;e-<8)AvN@#XPU^OA$6l9Cc{OC@ zK8CbJ#faBof6XcBkO-;NYGTDYD?c&06V>%ZvvIxM5|%eB6&TEVZTyrz&pHVhodwpq zj#jRmfmr6r zzaDf0pQzF=FbKLhg)nAFIPSx4NF` ziyvLrqzoS6-;-N6-h3Sn=&%BE4(||O3?{-aZ<=kS2<~}f{qwe6->cL%Vb|$+6 z_^mxRf8}%A8F5k4e^+H&jE8ofH^oX&TvZ}yEf6No*BZchL_y1v|}>{;U~qKSmQ4XyJ*F&z%lQ=Q`jXe z{RrJ;Am1U1NV*yi=Xhq+QtcHfzA=e??n4kE**{KEz1jj7r4UZjQ;245XVj?N0Ddj_166bbOj zMM@E%^_NVJoVb=V9X<%WZ-n~AF^ zeQqyW3&Dm=f9{vE2*e#O$5dQ#TvXY!t`mZ<76SNfoaAX^ z^q~xCu*VG@KMIEpTva>e8QE(@2!wCkF6f3^sG7)xD8h^iWSRpsubp`%c4>FC0qT$q zmSSi{K+FM^8ZEz$c8d0EIes{4_WK=UYu7stK?3j3Xg-Ey^X^izBrDq7Xx5F*e^GLe zZ8S-HJJi)@(Q_Zy>&;x6=RM#$6Wt}t6sHX z^r9IOqPfQw$#A6Jf1}LVeN*i1W+)nOhM^%jddEN*4R=dowEv>4MJtRf z3{?V){M-$D4Os0%KggU^1+Kk69fBMm%iUG;~v4x)8VCP98$r(Z4koL4=(N_pPTCnTY=8ID7(YGI) zBu>yA@pESN2nP?v_S=%afz%u%o5IGj=j4f;C#Y>QM^tpMry8BX&x?%CZ*;#Ng@{8@ z-$Ly<``jKNvf39{Bn(8@wntOSP^-?|rQVDsb)S_y1JlH;@A5v`f16`yvrdn>a;b5n zwBrwTc%+s3h$WarqDwr*AbVl0FNym3Ypw~CBE(JLjMC#5VVx)oIMVlr^UV0@-Uo1S z>EP1+{IR{Ku_&sv`RG0Rnyu02xbuQef%hMd1pp?2T?y4}bsvv7uHrp~(PGTMnJrI zce;r#M!{q*%)(}(u8TyvaMkZO*9}G~81b5XPeFb0mw;|o6uOG*FF`l{HMa9SYfABM zZ!fW55$YLvUcaNK{P?`m6E5@$NcaF@d zwj?Ry;&6xa%?9;Y9Yb?bMvH8tyi!GaimCJKFbmv0nHSu|MRV>mtqBKG)V7bG(#*}O z5xtrGB>zD9rrLv|b$eQuEN;?AKEA!u*nOVtD}HbF8go=_u&Mzykm7NMg|+?YC%i=-HQm6cA}kU8PZ{HN8>*+?RO zh$;4h_wdO2MkJ39rR~#0oE@nPR9A})tHk5rtJ)qEqRnS4b=d*vRww+o7~R{)Q>>fo zz_OV|x@SGxzEgS*vR)S+l^_uYgw{~CYwiK&1VM2~e*xnI)aB&oBro-~vp#B*=IsD~ zK!Cr=ECPB zk(D>EUzs=Q7=IX>2e7mX61?Ae02o-1&+*NUhe#Z-wtOaihe_k^m{;%(euPyo`Z)Ar zPMX9!bRu<4vEfz2g9@`Q)ZVqk*JsUYQp~ILQF0+i_bK$j8MD!+l#hl20tFRqEy zr$%(OFTJE~jQAkmP~!wRT?Iigm>pSoI}XwsQupxU52`&)BjJvs%tLehXLTf%f_!r( z10rtMqk-E`g|>j~isWc1==l*Qj-hxj7YA(aS#h}=f31IMwT)pu8N>4ac6)fgq3DZ>Pc@67#bTXz+>T(mz(#7(q@g?$c4|ENxLH>k^Oh*z*aI7oJn2d`yX+@~Np z|E6yOLglNZk>U8Uc#=)gsrPe}rTOs*R7$yZNMp1`4#Tmm+XW8ZHjAfS?aU_AV zMGYI~nm*A(k-_$%Ck&I}%it=6^HfF_fF;`OJw6Df*tRXSYn$>Z!Ur(Q7P# z&HTU`tQ#r;(OAZg=~z+~Y=sZJraty;tV3JkM`q$FC21|y6W3EjTRxnMt4Eis(?&o0 zKMtw|MiGpj_n%;0t!r~FaX^`!?jasQ5%G+3wPUwo_o*pz$)-3X12&IpC04J@#(&ot zeP{=A7D_o{*jN)Wy@_uVW_%yu9uqTV1flM;&B=^yYQLU}ZUlPYE&4tupN z{J6w{e4rKPu)&})rhAt6!~SK9&9=0kavaibg{!|+Fp_?FNF2la=_y43pz0? zzftL;JGm~ypIEb4%(<^tl@H9ba;7qX1LEMM3R0hYF3j1(fm| z@ANJNJ=HfAub@WDkFT1yE?eqr#9fmK6CV*`Zz2+|wV8yCeUna7_Z^mQ53{is_sUmp^$TM$|Ukv2%f!?cf>dn=C=Bm<~UF}h`pXt!0Qv+nilgDet zr9a&7$Klwn)p%P#TV|R7e*>LTcWo~}>l6kj_#}y1m42*DIwxNebSSeFUT^b$NRcKW zGgc=`mtBvYadrw^e%-w=k5AO28Zn2*mC%l7HZRV7$KsH@W<8yY+zB-~e}G?BU&H@(j>{Y> zNbgis-3OX2d;w+g)$GZX-p9Ul>^J9i*L>(t3-gMZAD&W_mcD2Z@r%!7{~XpEZGvB$ zT||=lYLf~W!nvZ>b6gs!eWh1leiGYM*j~W=idILkw(G?U`sff5 z>SAU#)rFlznZ)upFA8y-StU!%1O!~00$rax@)+9S)v@GxIbXahy+H4g)UqGe*ij%Z z^P(P5H8wrBnST?V5=Cz<#Htl{7hq$=3_YX%LdC?+Bv?k0&&j>96&O=8Y?KJMJqrVK zix+f%{N5amO9Q&(iK%j78r%wWDtU9ac%R*aoQ(msU%sx z2=+c6u7B^mB@qdUJmh4^G(T3Z9GL?O;zVpLNiuK|Y*mKzvhmF;_hD`~5=-w-Ka=((09-H-MU9zuUao)=7uutn}M$(g^ww0!)7L zyMAaVcKvU4C|aO1;tvgSHR&xS(708!43*O6k|K`ABm4Rylb3k4(lt1EoLU}!)g9ie zaDVMIA(_RgJ;?Mrofx$+-u3FcK76aI@RTC6_nC~yGuBu1w@)T-46{iEyED}3Q6~iz z3~o8o4kfArO(=A2z2(2QC!2`jo@6n7atccR(B?YaJbyc}2g`ks zghRd4+1v#>maysSvl!oVWyGQ+Y;CruG=J-lOG^_@_Q$?LA#09fGR^xoAM~Yg*9Y%J z`+6YAh!}0`IK+Cg47fj!{!}y||7Qf|Q6O$O-x=9dS%QHqaYcS%``FMW-lH50n6I=( z3YM-^INp=zk?-_1x7WHr-!Cpj`f2*<9n-gAXtM zZdbtfwB7xCx1|bCIgyd=UsqEt6o19`HJwfLg=q#*Pz;$XX^1z1iZjvogc|JEFM4dB zCq!L#P{}y=*Lgt9s(T5dfPvg5RdySZGKX)rzLhxYs!VDT8@2E0UUj_y84OvApl)b3 zSEvQJ(7FT;JZRhH;Giiahi>bycj-G^$%xLRn}4<=IT2n=Rg1hjkeVUSkbj~^3x9(D za~PzMkajRv(=Zh$<2#3u={m*taqhC_MM~FHs;HmQxnnn<71!BNoy!2icyQSiGR~;Og4<-7ZA(v!GdB6-P`>5fLOzb^Yx)WprUr?ERk5)szLbJ6HYU zhAD-pA=ld2Sgm*7E&lwmT7NaE_*8hVj)oaY7p3H%i_ew~UlY$LyA^h2W5l4;4Rubo zwoi^&e2x8{RzpyuqX|VpCynT#Vhg*S$2AH@fz(0QsmB(GM6NkY`RcNaYCVPW%e)ng zh;n(3npgoRRuv?|M-3rk-5>l+GKS0C36=8@uov;qcOTRfyy9pY4}V&GiRB{D^Zwa4 zzj_=I#pcwdVy=s$vb6l9o0D8x97#&=Ky-Mko0UU1E!KIPTpj9swnt4G`wZ!n)| z1^OxDK1Zl3o9qWfw?UbtS`>kUf(hC}TVQO1AGN7=`kyv44csXFzxL362-2 zlc09pcc=aiAw02q7EWs0$=!I|aY}0F;%>Cq=#I`Pxfy4!S106|qY>$3j#&21$TFbIXcu9Ate$?;Dt11c810m?NuLtLCCMyE5+*PoR&ZQ4=2vZecrL}~j8*-eh6 ztXa%!a2oON1xWIMp%R6&wNHIR+gxNkBp{!O36vXm99VIsG7mL2v?lrjTu7wSUK96L z<&k5sIDewN4;6mYzTsFf0@{$*d4E^ZRE9Ooog%HcoRj=KZWP9nV7+xrv>d;Sy_U)2 z+u$C%M!=HilW6+>*7jV-L9u69rN^JHo7q_h(lpDLorDnF|eWCl$r zaK0)|v5l0%?hE10589t=EoxO}FG-N4kEhNKQGZ$cJorqSv7d)7E7?0Va+!&X|I(&5 z>5Exi9VA4)EMK>qTN%Xo`o1MDa)Wc)zDi8$%!Ai%{eG~MO-$^`C`&-**^gs!>2uWr{8GOzowWLulNgtB zAW__UIKN4L*er$Wt0aGeP5w82$scJ;geDS)be}w@G_snW^pSH1xQ&MRpTMu8+xhHA z6Se3Et0+$a#?ucg86~E{BmV{AN#p^Sad-j~mt~d$6PF-31OyN^ISMaK zWo~D5Xfhx;H8?ewVd4T51UWV{F_&So11W#E1yq!47dDI_AR(!Qgabo&4Gq#rcS^(1 z%m6cVcZ+m)3epG&NJ)ou3P?*M-SDBF_nh;-|G(Dvtyyd4zIHu(@B6x*wT7BPS&doL z3~B?~~j0C5Ec8D0Pz8z&1J8wWZywYnAD7W|hPomvy@2(yAh`2Q6k?g)Q2 zhCkROjNuP)3Q!0@*2xyY&Iw@W=4a>OXJZ3!u(9#|ClKn$50Ef+wlV`KumEJC5HJj# zS{!Qc=4fSM34eIZe~th;Q+fb9A0H3X?{t8u9oW&z)EEL#Fos)#?H-J2wVMiK+mM9|rtuJeaAYl|3BB0<*IHH6rV;G7nppgqVp#?d-r1 zI1K$)e-c)XVAF@SyRrVcSsMt{1>*4+Ft>u3ng1HX%*mcr17hXi1eTHbE9Ak1{*TQ9 z3)=6~?RAQ&+dtvI@0V3qQbtx?j`7dLfBVG5psoN9W)3a@GY5zbz|Mcp&IaIlIC%Yc z8D(RuzuI8?Cszhy4h1~K|8DnTPycDz`7Z|0{iP0iz<(E0gg(#~450gm<$7!&Hq(bM z_Wx(D|4#Y;qxi2X|2LNZZ$nZ}wzj|Bbie)oAGficm95)f0S~NofXFWcR;b8MuG(gAzm`77uJ@X6IsIUhM@M5f^oOf|Kp=nz`-4Kwz^=ck4Pa$~K;aK5fQOmA0Oo&CNAzFU%*_X2mHcJ; zjd-{Ktg?S2-Upw~--wSFz-sajdhnV4jX=N9gG7!0w)~on)$Cu88^CJ)FUSL6wfU#m zgVXkp`2PucAR{Z}Uyu{P>hLf4P{8Ro{I7MGIypK%?CUp+A9nR0{QIQ@2D^ey(PyWi zrUHT1)q%|ym7;$nF3js+1(6SuFSI$Bzvde}fp9IZq#a{eO6E(B$=2%I*w zS7sJnYSh@CwAEi`;#_E+6-)8R1~n_Tv{e?T%M+0DY3_fnsKP&)^s29ePKao;R_vk! zRwMPok`z-ZYD>UbGv2L=8 zoOe?3JWQnV#R=3Dawt@Z(0j#m<3Ak`>D>TPwXM^`EaT93h_FBBrv50fg!(33a)LSn zc$2awC_{fN!ad9c7o=2uTRu&P^p6pq&mu4Nui0X>jWp4v13fK26d(C`4~VKoSSOd8 z>N2xvWrL^ib2{-DTuj+8&Ob@BCkeV{cI6)>w*>KPSOU&@g;cJ&<&%!wjL2O`i&3Jn znMs^vY&LL3owM4boTAhsmxru^bGVg@NuOw1Mv#9#Uky1a!6OfwS|#SEk({QT5~V8& z;hih?s89@#@$SN$Ks_xZf5!I`h9&em(~Qi)!(>I| zJ7kji!Hee??;2I&3oKLhJZ_Sa`O$bvigj(F()~xfwi^O zs7ikv_Z=tCiKZ=Ozwg}EyR%CZEFYnXD7@PAZAtl!%Zqd2)A(Vu-=b^j1hV z0__Fi>hZk!aBV~xC3x)=L_vRKMTDRDLY6=MC#MS)&LY`W0TwJIVPj+a2NtzwzVAuq z=*N`F66*V>X-YVh6}v8)F4b(ZDR&uqPYmZOC7YK?>h{f#0=u!5anZJb{VH&Wwt6RF zQ#MAbe$y=ey-6dgIVBi{0IkglKCWguZpQUW5>rzCjvIZ#|Y$2tyLK zEvh6bPUNUAvG_5XjBKyI(JJypfz{(plgYjuyP{U+?PoHQD}!k`zOO_PSs#DZwQ;=FzU){c397=Cc1b>LZSvQ>O+s;@tCMpC*uq;jox- zGQ$D#goj3Kb97n&9&=B_0-}F(Zg44kyF5u4NTW@PZR>h0Pz0rmAiY3q1PRC14dQg$E zQFmrbmR*P!YTvpY=iGl%kEBp|n3s6_(Yd_P@KWdwMXqk|q~A zpin8sCW+vJK={G+^;<(CYSvfvQ(q!XL67@fk7TcqMu%iZ)Ncj6;{|AN^{!&*&=gSI z=WW#JLLXf=gv;iQvKwevubFIu1GqW-$rvm6Uo{**t?1>XxnF-{{weuc`-t^T^KG7U zdzyQ_h}>aIq&aZA>DCAJWS$Ww^-f^Wi>+8rC96V@sC7P97bl&BVo=A;Ip|3FWjJZ ziw|#p{P4!|Tdsd;T6v8`@3p5k9x%1HH$mdYklQT}5NucL8|fwWq&M>IvXx%ep1JH> zt3Erb&0_ItXZ3iYpZ{*kmZ-cAjc~LGmy&==#aVJ}T=O&OQnyZ)$iQ9);twxUMryvx z@mmdCwj<*1?~C^erf6SQI-3GNvm4x2U{2#sn3a<15P5&n2E<(klnUOQ=-_4%Na85v z3yLyRJ+6L7+qV$ej-#YUP<+`UCL{iM&EKce(0R+yL;rttLW}GLC-HzDtypc#*InTsQMT}|d>+E(z&>R`X~jGcRl-dGBfOB``ennqL*;|BC&!-vRgF-saP#EQ6{d59xe_D`P`>tUSv#I+>8v-C`_~-fOoXBUHo6Qu;6fMKHQS59UQtj|< zTJ7!p%$TMha)_Oh3P{tuW6SIC)2V?_x*LClEEUd|HoC$D*nYYpwcwhPGE&Z&Ra zv(21B;}JG}&u}dPmMkFmL^Hps%zh;8jKz(wha4C(g4M3UyF>Z8Gh>9@j{Vffc$4kc z@*6l>wBB62cajk?{UG-pXlZw#2ZWjp-TI=~lIVgrWDsGK-pr5xUHa*@pqd)+wM&jO zcMtkN4{CK|Er31bi62JfL35Ne#vy-r0XXEp!vv6d*kWU)@;iPO zO5zWJO*I9s=%nE`x-BPFOEc8e2>6Cl_OeCFLM2F_dTmRwL+1UKc4+6iiOphg8Na`& z2`aiR3E&qvM(7%NrPSyS+IV)3qclPfdrj1hsWM_uu#R$PaNb!D`6^#Sfl!cRM%3<3 zDj3iCvg7THDNn%9mLJqu=;D8BZ^8~|OCiJ(J7`A{*Bm@EG#no&-PQR#t*hh*>VDW0 z=wGSMRSgs6NXsu)u|)8W*y+aoG`tNFt@mPfpFesUJ!f_xAmI8S`4s!4o+AN(_f)dr z*zhiO>q@YrE6Yp^Um@dyx?kyi@owRqhiEqf7xB4!6n&Oyf^mUQusnajnwq~6i7CYF zRWSmTc{&+c2GaM^jh9l#0Ww8-|K$6~#YH`d#K=^_MU#Tcq%~G^$bC1FHOt$?tMoIG z^n@5Mm7jM#jCNU4FZm`VCUXYf|14iadm3enoZCu3@qTVyN3G^I7@~+&u;w4Rv62X6 zccEh8u9b03!$lf2dFg*U$Uh*_H!~XeUZ{DS_FjcxZ#UTV$rOXSp^Xp6cldVY9JrF& z)5rRCU_PZ=40x7}DF!sERrK_nW#ITyV=&_?Iz2=%N)M}0j%%~4Pv+>^BTc!uvyBiuN^>K{eXf~KQZWZq9 zN}XS^zkYMBVq0Z5zto*%mKrfsUXm*a>ywuQi1<@!bf8FolBHP4R6uGwkJ`Y@$0{OR zDmrzdZTxCia{Yg3-2zdkmXu}7sV`6Ag)^CMWZ`as`5=wr^?ZMzbj^hu0;0&){40s; zLrw3z3}R|%g+u;+A{Qa7e=%iTCGl!~M8vtJCxXhJVxo*t&7T)~HI_hK%kj$iyY)Ep z)H0$szh!(%>LvRSem$4mKpu_64=3Mm6J#r>35djM;W~dyI7`@;9@CjY!_=)ut}*%n z&M^#v@n8*c2a&EwnypoFmTOvwR(`;XBTZpF!fQ5TAOcC|)6mv%;(afD*BgIlRr7j! zcpgq3O#bU;{`G=5EF;QLOT-7*x%n}N$4V)&rL|wXXm%+cPUC^?yBv@~?MEJ{)@!=Q zw%jD0o4dg>H@+e8P3U|-e!G(Q4Cc1eT1R`VtB)hpK%toY;8YZJ>WF#u%^Q20OIpOsV;wnC=iP4AU9fwtXCji8ACiCa#0B+cEGJdYU`lc1 z?R|;KVFLY9YxJf{GBlwdRDH6l;giARzp;OMk24U;Ff1xv%+!dm zk#7Mqg2y-vnq@+C1H8ExK*kHkbvK@^SCCgD)Doh;umb6_#bg1_%;(E@AS43@>)!O& zJC_>a?5GG3@-Eh7oJtqO8Y8v3v{;K05fbAMw6HPK*UrtZXp$RWn&%AY6B_OPACG@U zj~}Q1ET*TrN~-B1Bizz;&XE#pl*f`z;&tXIZ3P;Gw9$VI_i)VxW}fg}m?`#&aHi?; zX~8q2Q!A#_<A7i&{H^BeagdqcCNniaL4HIDV~HpZWo-$Lo#jlF_}edc}yCfi6K%y>&AgIW(k z6HsA95q(ja7CXbSy0{N$2c7$*75OEy`IY|A-Ef1)eX(}+!@=axh?WRJ`vZSeKUpo2 zPvwIM)Llsn3z;?u&}UBS!E5v5QNAR|r-4@Un5B}ey|v*D>!;;h){ym3l~#D?=NTob z8(|(F^tF@wu?I;7~x1Q9F<6)=1ZoABUu`{Kf8emvWg)!HWW z_9;iEsWmeM^5v+b!FkH6z@2{shtC&`$*`MO7?Av8ywBc|y_XWPxXJR76-Q|9vEs9U zvh;}SmDsnDZpGq~19ykA-*ab1Tua9)Qe|Q1X%t0An>TbLWC;_=!YgwYF#YqdyktfK zX?Q3TWdxcCLJbSimNwNv8FA6-sInJl+6s6K3A}>_v+g^l;FKu5>d}87N%|7i1k6^7 zB<{yuE_H`FK`VzZNzx`b6LCM&(sEP6`daL^0?1^HgxE}}Ek<0g0?dCB#&FPCuB>xt^l zC9ySf!VO@J*oa4lHaQ6!&eW(Q(i^BDk1~@7L0r6UnJ_|i6&oa^7WD<9=K z5`87{lf+PQxed5rKL!dzNeP~N$s##J@jQ8(dH|8**=Kia`_iqgSJXS@wxsg44z#sfVt8v$ zqYCN>Qau{qX%Fg!pdQ{77pB*hzpNy#?>Krg66ol3CIgA%>^# zkyhBqv4d5coGcaRqbA)R5)4{`6eJzkp;~|tbl89PWD-nU+p%($ozIk+?7;mN%#T3; zvR%5q8&%%_+%bqnlfV;p$@;uJowz#nY!_WJ&XqwY4G;DFpqOfAy`yWPux&YNJhw1= zFY|ccrzH4*Jsx!5OO&oB{Je1d%(4==!9FTA7^RnKBwA*J+N1W$y5aRo;tW5d8m2@& zzdnEC>jL#I5aF|q2=nJLdYaMvdi@q~1dmasS4{AK7VKlj^GAaTr6>^?>kEl*80&d#9YB2hS4!_Y;K! zKDA)HAO&(Kcj^h{$x3ZmU6m1K|6+{0&{^e!Yvp(@9!#h2xt@j`hfn)o47G5sBONP@ z6I;X`$B&?Lc}Ti2TGvJk;=V$$=HP!Y7NApY)%b9?PAx2vMa$r5bx=IUGQO#j%{?-q zWVWZsdNIA|D}q(pl5wJ)U|)rqe1X$RC^KbEFw*?p7qx7@6Rg!ab8wv6m_2^)H_2hh zYV+z&HYFoV;rU%VgDQ{DjjBY}(7p#pADFhqvXID#G8J>$EXT#}#~hLTOA>#cKuj5| z22c1w;LnAQuOvtzVwUXR+s_~V{Gwseeak#hVue+H6=BMO2uUO0{ur)GIgbWlPqt>b zv&5eg!Wk+h+m-P72s+GV746E%Qw3wjL!-MhwOS{hhn~1t$rdo99B>osz?kSpORZP- z#b$3|$1`uUt}LI33H8MFw)20!m1NBjXnIRp`=m+gU?7;YLC zyo7YS_ur2QvxEdu`8JCSHHb(a~pR4%IJOe|(y5RtC#(_xYOgg>A$qzf%fhiZ8FnXGwGh zuv>DQc6B!dpl|kDVd1xk`W|k!BId;q5h@lm0kWjzgu#YM*$KcsPk|)D> zJFX$yGU?8hI3w%i4N)&EOU6APEr}nc#C^&_={l}C^WnRTuSb8Fa`>#Ev z{7hlc7$-9_-Enu~-NTJFkFF7Iu;)cWhJYz*+&Pi{;POey7d=?uV2W}a66briD(q1C zR+WWs$MVuV$3MdSifV{dPDDAa-)s^a?}Rt-EZA;yDd;0P+p{-KNsouv zB(vSx`V3AB%V&QGvT>F#4vJ{CM5wz~2t9YXy&n>@`2e~wEV%LE8Lm;~V@GH7Vra)C zjjysr!Gsnb@LUSYt}Io4(8?cf z(nD?q&3k`V4Y>}zSJs_QIpAKo=2wbq)eQ4UK4~Nlu($rC!c*6^xGR)YSr#3M^f(9MTlzgkATRH< z@OXa+2f1QiaEh!bicl=Nqc^|0Sd3+K@|pmV3-;7wwGnskM;e?zvzjK#n1B}!Nwdg2 z7<9q>DoW=cLmWZ;))}X5zIx~-W$=l#o+~SpIgCaQQHfJk4pQqX=BF#B3swJ ziAUGwTz#W5pn(KAlH^>z!+ci&4I|2i?Zc}j zE#agK#dE%9&d89MU;!G0%VOl#HvL0#Pf$a+uZ@ABCEWosLSxUa@pRs6H|})Qb5q|c z8D(2T`StaIh9;>o+ohfD#TPz3VKH9VdWgl<0lbSw9tVIeC@}(Xz%t0!O;H)lsXBkV z?@LL0r)cCego5=0A(@bBHcd`q*Ik`niyIYGLFuyjRo;D)XkSfcrj|vcRHPfmE(4~ zOmA2DoA-`I?nZ3fj%O1339>zKuo(H=0rUVEG!R)Lq&{J}N6pMg3()%5DXATkFr=eJh3H>k5@=qO9b&+O zR(rWy7bmYTpPEY|+*OuJvFM&Nv{ID~1#((%o`(3$tZFAv`G6s*!(_rF!Cg#z@_IEL9t5dZU+H>o3E$|=9qajfY_5$@l~($emjLk*I(&P6p^36 zk8N2=B)TCpS1QRjYxbL+caKrWIKyb~pQDA=Z+p#msJ;G>4(yCnI_RpZbR5OFz!WlZ% z2uB=>c5Kznhz3mw8Mhl+rzN>yWGKxy^aIq%yw*N-Vd8{6hGMg=&vB-%R!=#~{nTBa zj?=lU>c6C&6Q&H*$8Ue`FDJ(VzK>KZ*8rV52u?;YQTb6f-6(CEm3fb8m64PwEnGW$ zOd&-$5bq^$86+clLv4kr4E$p@=Kl@BfBp1WDhIA;4zr23}&!6laPT=j~OjCO= zr<{;QvvSCPL5`@ljCgGZ+PIl)=WD9NE53kN0mXr659%s%cMpN5VmJ_DH8Fi_Cq#F{cS@GFFcsrb(Mh;g z=+>!TLM{rE=3#%m%PhKRH38Z*b4m6bHOV`Z#|;$nZ&N&bwqI-~eti1v?h%J^oIyE- zGIefJAI%+pfh_+nz#nf>uAQs@ZV!0fcK+dN;mfx;==GWn6ZzAk>~FyNq>AO+pPLuJ z12@xWptMb{9AQST@Se2BN~xCYiFf;NxLmzaK3b*ibt-?Ee$LLl<(z0vaM9kHj0@A5 zMmS8^p@^hl!Z5n=*2ywC12|$MU1qGp3%O=VoFeNnqR3CmkT6*f!=A&Y_g@e}`;OTi zF>uu9zG|Oa9?N`_(4y0fjTbzi&0v;V%$H5hwYonia5N3t3$@XkE1(;JsqeindfDN% ze24Mzb7yD8Fk5As$h6|)=bs$IyBuY)-xjs@_R{R0%XvgVwF~wdXaF*LHRF2j`LV#eAxu*eQGcqQ&(Zqs?+lyp{5^k&my*t z{|}sr$E=recmfjwH8z(4@&gqRI5r9|Ol59obZ9alH#IXdm$4-S6#_Lgmte93Dt~kZ zRMcDdHZ9#LHKZUtfOL0*bSMnN07J~cFqD9_AYIZS3P?#KDBTE1BS^;}DF{l}AN9WX z{_p#JYkl9EwSIG+y`R0$-se2~aIokb@+sKCZ6T^~7?MwjUr-XDq@$xD0T2`v<`)zM z;&X5qL6I(yzs&d?CJ=-N6b_U8Uw;H81O$Y%v<44~=h0uT}g2tAM#5|b1Z z1ONpECH_N%BP0RJATOvLK!+co35P*E@Hv#=ZoUYpgCp{GoBu2UTwrd1kc5O7@9%Jc zf-3|81%qG!9T3tH;(EIy7~}#lgoB|Fr0>5{a7jBNk#3R#0^Z)<{2*5ket$T^L6(~r z;0;AO0vR3sxQ+0H z*+CG1+sy%n8rlFoHwf$xS^E!x7x35F0EGC3{!aH-^shuv*zaHv7z}rH1HpWuFb9A= z)CB_2Q`P22`XG4$Aeh}RB7exm1AZG1@&Z9!K(@Dp-<5*^stN`G&~1Z%wdVmwK;4iY z{2ox3Uo8s!N^^V4Dlj`GxT`A!hV;PyRi82x0Ri70yRX2Xn{|f4yu zcAjnm#xSV6CqzT}FUqY6{~wzJ1PKro6c-Z~7Xd)r0T3Usqrk89Mt{C;kl#+BU*_8m z0{q5pzeGv4oG6esL)qvTI1RUha$m_e>C&QZv1Q3T%a(BKHLNP>v6e_5)}L|-|c{boo^oyk6U5>ae+K;rw#f0 z8h>HP?L7Uv4iy*}Zue{OfT9loAOr&Bi+_9dw@4J=Cv-cZb`YQ6(gq0d!{Er<5WsEE z0RVeA0{_=FKYw@t5K#PO`h&y(0!sfN34nmg-$)z?5P0}Ek`M<7*#3iVnc%;Xu+S}X zg#L|%gl^M%{)Ydm9qfrf+&1@Ha<`5B2mgLSAP^r282`&>I9MvosV1!Xv`T^An{Rzs z8hbze)C|ZsT<{nd*`qRUy^>^@lRc|ds`{l{NcFK(n}4pN`)Tgt^bbE&Epwf($T1(Y z>ZSv;ZNlf9WAw>nzY_-5&m@g#`KGCgOpKY%q7Gw21O*fNOOS<(8Kgqk2 zbh&S!e}A5=o3SH0Sko(H{X6?JB${Jlvwp6(du(~1ZZsqqOg`wGfMEHikf|Ao0-FdMaT4m zUI#-fZq*ro&c4Uj7>^BgxVd>>Mu&{c;2ECehU$whR7@>yY2)Rh;V?ue=qqgF2ilg~ z<4l&&sG#W`9-`9jmn^@V4!OV<;j#0G{PvMihZ=r@m zXs`}Vdl$+AzZ`<%Z!&O^={49U#&~~EQ5dajA6de@x#(BT)!A~%OOYIAa)J_ZHCO0SpgS^*k=X8 z>E1HlqsdVHJ+0DGut(fzzZe&)fzMHrwp`e}_KZH#+Ux6H+C(wMA!yT!;_d(q<=30c zo#o+{~(EE`U}-+y(-;7eA+ z2j7W~D^gffl$ylA^YRUPGq!@C5mxbXsmy&9Z!teo*Lh`Txoh4XZplyc%_7| z7A5N0>HKyQ5c}Sb=$dsuqwhv#%ymvPfVkC?F&n0lL)n?X-+zYFvyg<8FKbaCQ$*Jq z)>OhCYV@vxS7c11lD?82(zCGbYKDrJLI0U^1-oE9M7uUtyzKb$uo? z3b(A}P`;k-G;To`Tt^LT0pRx}W9ypwNzP{kR{<(wt^2UM8|aDX^MC1~Op*rh-Ge?> zG}0uKAsq~cH zEV`x`pSSXChG!?Vb#RFKhPzzjveoxmvdp$4HOURb^(Ty)w}ZHrYrf~Q6bQ(#>kM{1 z((UErM>u0b@7l={KYv^BrmlsQkdT||7n2RknuX;KBj-p6s!L`B!z@-aSkT2xXtd%+ zKK6+N)a)N32Fv34Q9_?a7ZdSmt)Dn88|FB&_HSw0=XsnNI*5DrIx#uzIm|Dp3^^~# z=H`3Kd&#fx3{!`V2!FBmrsLk44ZjpC4+yi~ zh=Bx?TpxNab9Bokq?ds?KQ}+_@8RWqoq!JA^<6z7qdG8`=Ms_mdh&=+7TcFUQCjUi zKpVCxQhO8F)VEH4B7VUyV@-4(FdI;yrE&cx&n=IIyF)GbPQRT+2b03b&)9{mKR}*= zOWLZ9PUgWDOMhGNY=a2Vx_JT<7Dt9bcjH(R{q$0d=O#IiUgPWsRj$`;IBh_M=BvHV zY$mfcR*uvw2P3|gNpEeK=?{6kyiHumj^!%UubVuA>+S}7@g%c@&^r~XY}})I$`)5s z)ua6KK5gk72ulPjMOG=IW=X?7%U6taHYYY+DTM%mKz_eTl@fp6Dd2PT%R3Ej?6b$D z8Z5>;e`@zZAUtP{qf2mkTQ(?k$27GVo#neW<-U)ZwS#Z&Hwp28!cG3w@w{gzL6`uyAquE2kv=z4RYjoU(iBBwj6TUELX|bC7Zw7b1Z|%K3|0iT;X_WSic1LB$M2{qS45r=oR}NF1wdJ$%4|spuov>)B$oXOHMZkl8yC%d8XUaa zsu-SLn*r;lfZqk!GpH5$NC+PC88}d%?9Fv~?cs$)ct-N>V}Ek%#l$^H1l;JxPKmD4 zL!Xx#sOx`$of6l6p3>(|w^Sb8DaH>!k^evgl<>g_4Ml+ZYSSgNn8~P(LfCP3bS}O< z4&=;k@z+02e>Ze`iY3c{MK^x=BsdO^=i>3*W&2UT8{toR1Mz~E`o+Br$Ni<7h?%4pNABzy-Hj`v zYr&iZvE$bX$^IOh&*pwD9~e8#5E{+Cb*GE5?MU|#>w6F z{tJKA1D@$`KRz7UXyxq^2iZ%%bS@BG0>~uQJpCy1$&z1KFs)<^xZSXj_z_N9TA6MQ zQ7(5NZVOfh7|V8mO9BtsCakIWsIEMY$#@C{aQZY0V=t=tsW+1SunMv-1Vyl!7@ufK z-r1mSDZBU53B#lhVvk~vYX+P4y^nV=1HXU$qP1&UKUqA@EZQWVWJvxYXl=}Q_JtE& zD{-$wZh?A1G{H}1b`OCzUEQe(xgzeYBuV+wAv&tcMY1z@t=Mx)Fx|d=7IEESCf)KW zIGL08ef>E3H~9qT@|y$^?0wzUybY;bYim5H#p|;Z$ETC>Ym(=l2R~yqBi)DNB?W)5 zdDN4S$iAr#aYQ;6HpV!H2>2=9}#>}7f@yS>^mLW})QcJteI%D4))P_~e8 zX~~(wbL}C850^A^?vYdsRnn;q$7++P4uc)tcKtInnD~g|Okz`M^kty2MaWf8l)c|M z|9dNq&!Mks`R{qeV|9GWr~Fig#*cqj7RDk?u!kES@1;UD|K^z&ddvDFLg)FR_RokA zd9%1MY$xN92#xXl)JR*d!-j_J1jEDT(r%RvBls$cDl3q$VaX^8)b*aKQ63NGtAvMfweerGI?s#(IA!hjo0}RVvmK|W z3w=K0?Z%u3t$33JSKF);N8Y5ZHG1#`%6S8=1&J;>&Su_166#yj>`%W{XbUS}EQMJc z8Qr&DW;Ya=kdDI%Eyu43rw2LUU?^!VUV4zrz+>+sQ4+Rhe+zPCrRXr%h(>HwI%Q?6h9{-_Snr zoUks=iY!+yl&+L_dug`fOu?z|`#@}PjknU%&Pc;}WV+~yW<=(_i5`F3D0@fL#Te#t zHKmfmh0!r8*&vvhKiB+WJz27U8u5z{3|uz;~#Kt zSX+iLC6?I4XV6C72xE;*FIle?kVR7F!PVWK+{++5)-eYSgRg%(Qy>g6K1)g!(y#C2 zOCD3%2&^ffv@|sep7zU`KBH=7s8rBKQ2xX{_e+89$1}#h0G&HhsZ|$3=|a4RPAZmN zL6qk4u3iRlBe1sh6W1J-f`~`0?q*JlrWn2}LrYjunbQ;Ywn}It7`kTW((%(!llv?O zX91u+F^SPn-+O-sO2S3>(pV;rY02CpAD;J2!Jh+MiAD*Wd&KJbg4zcJvDJ+~rj%R@ z_fEHdieI{*WRHcGrg(H=8wv0+*m<;^W9g^1-7U(5Cv_||6cGBjW$eE>|3OhwxBFQV zxR$F_PC|q+fMD%-#h7n2cHVVnS=JZx5)>UxH=uSETtI)`oZNZ!d0ZkVt+G~Bes^Cw z+)HCMO&b3`T=XXveVJ+~5#-fD1sT&j+H~qD6y1zWY7oAB4KSIlma8~gZMCg1jhHCd z@dPrl(4x7BByM^W%W46rK-yRN+MvZ_4TlBKE#qCe8uc!0pnFI&Obv++D9yO19x93H{mWyrGd6uTB{OiO8SYCK#VHVHEoh zybbBkDhW;H`trFE0CYJp)7d1~<4YFIxN}2GLKlDSY(!(V?HP1(O)MKEnI2W#Nu|Z1 za)t|C(AaxUI;Vb+_4bSA@T+l)6JylYAm-HR%liY6#|1GzvD#bZdR^HbwJ}HxJR_U< z5C!ZXmQiRnHhj^6EqjL$qus|IOhpq=uTX);Sr-lS@R(Y8f$Ee|cVFyqnd6RmQL(W@ z#L%S zP-`MQoA(`KIMIC+kz2j56CxHUAK0JgO0XWSWwaHE!Jj08pwv<3egHf5!P1`T9l@Tv z7(MXQM`Z$3D9lJF)o>nlXIR+meHo4;pu7;rI&dn)?u!`P4&)t4;3}#3xT-S3*(85! zzj#mhYCtL{t*elQKvl0nV}V$9n~-K)+wIxvH0+9z+tVi4*z`LHE-Z3^{|S@jQdD9u z!m;y=Xm!m1A3K91R`zVzXIv8)W~5!ea9CLd51*gjlYEZxzU1|Q?1>V`MMqw*Ww&eV z*9UJk=~TZAQ>c$xsw%oq5x_0*O)r1XP{*I+sye1H_r!$)TA6YPE7oqL-<1Gw-ePKW zR;i=hkx|%>Vp57!sEQV7Ijqt{>~h%$+tRW*_&Gv6OAMi;bY;x+hAQYoM>*4Bg3@4h zjDmz~l6APkm7hmg;t9eqKoLK8lcp4DpH#r5x;1U-mNXIF%#rT$6`YT%C-Q%w7)ce^ z!oqx=TgEqQoApS+LVUepSCiGs{GucCdu(B~U0`*J5Fm?D%O4B!V*FEU==_{n@ds!2 zp*Ae(jKCNJVU!w}Eyi0~yfj4Tn;usaryOFS+ewSSMR5`UA)-M}O@u>7uXZyrFXtHW z;r`kLyVWnA>n#^=RzDm|(gA-4k>21NK`7TVz}6}CHz_+EMnlgrGfCPA_RW!R#zlTM zXIf2C+ccg(hb1nLviODVKi^nFk;nNcJ`z;gJBVg^FOWOn=k;#rX*hXC6)SZ~s*1fz z$;qR}qPj}W4VkeVcMqIQSx<4T-I1c z#|JMtOVyN{eCv1$`{ys&(tHUSydNa>8YF~*mN~O_Xh`4_OHUT042~DDL+!G-YM%Bv zt367P=w(%M+>DQRN)WGmV&F~ev#GSSa%d{(K48_wsh;gYL2K2zRnOONrmu{C5b@*v z{A@etk$eTLZI(TBtki$xb6v$XJ{RHm5AKzEpYwYzn>8T|_hmm$rPj#l?BKmhdEc}U zBHb_};rLeYm_amI;y`-_RaHW;T<|lu?x9j7?tK>=8N^jwAvz};8577n{VtWD@$gL% zWHs?gz+D$xF{D!qrN)gkoyDB|M4L<JFoIAUJ!~RitWkkEh50PcZ6B zw)=LlUbxPL-@3EhN7WcZeD#ij-Rb;J+dGqVPMv?lPFXf;t3C%f3e7}4CKV4uDYZ!s zF1-Xb?j8!F??{_DL0o{8CZcJtm37Js!VgNxTB}!#$+6 z&A0j*anq_zsJ9`|cwdkvFU6MVsVw%XPM*at#{L#cu>9^s)-Ms<{RDmB0DA0wNMO`+jDPwiuqmm z`B#R35+e&=7R2Qf?BSSb@JA?fYE(V%a;I)A##&vDeUIJ2hQ%8$jG2@tia>`p#D)cM z#ghJt-psXJG5tLFiN`VpF2=;;`6hoC_VJg;=^dnS?g|mRGnwEn#M*E>Jqam}oK-A< zq0QST3jb9K0@vnc_p&|tp3(|tq8|U(ob#O5)uR`k1^Bij@iTVmAE^#L(jVmqcYjGV zO6y-8$(F#SsP$lzSz8E&1(La>ONBixg6{QBnx9bIkN4_y^YtJS`>EpVkko&&LrW=9 zX{sfq;Pm0sQRPGax23O6fD3`2kGv|z6Y?Xv zd|1cCK#Yja4-FZB!5lnOJyL(6$S+Ye6Gt<+3Jv1hUb80hmKh zZMQgpv;)&s%1ly$E$mBcPX#BBssy8IzPatXc1p?WeFtllp+(LcgxG(r5g8a@Q}s61 zj9&P0r0G&=4iUfGa?eo91Izj_9Ef3XOlnSV;gPy)&WSJPS_-7JXUS_~oq^USWyEdA zJTIvWnY5lI!BuOB8Q6OiFG|_xkY1w4*e}ly}LT@9=Q4BOozG+nsYpcs9A{ zINerOTAE|IKQ_&mcAkF%+XqwMJ1HH#LkBZ1>!E8f*BC?1_jw?uFweRYeMzRa8?z>4 zDQg%ih3`f|?hP+WHk~cw!nywRX<5XW*IPkZLXMJ^sm_bJ?WCvjDnK0v>aRhr!T6}1 zST{NmZO5AARfl zh`}hz8mpi03fap`DuhV?@Nrjq7$>lWLE5WTj&G;hYvc66fzLbikSl-27QJz#4p{)K-J#Z=r3{shc%u&1<4#3Ju2 zQ70y%gIeiZv(_uuoFj5`#Iu4hY!lz!)H%Z@bB&Kcr|}=~@g3Wz8bn$xIrju0EEcX1 z_4HNF)j9|MK}TzPoHwH*6E(Qj!iIw|uIJ_pjr&(p33I-FOFDa$$H3!0^Cnh4=EvY1 zobz@NPE>!1M#AIJWDU0iiBkTt;#xc1WE3A8ftCX{xs*|P!`1z--WX_TfeL4O!i@1- zK?aQO1R*lnOKX#7ez_&D37;2pGO1CA50YPx-(jr|sNyZ&#y7{KBk`$i?!#UmbtsVX z>oQHzWUcX7tXzTbx40nOoP1RF;XI;YdE-)m>4-L=eyDN~NO zp7(#g)|QT-On#`SHmxU8|1P>rHu+6kfi!K9d89;1j5<5I7lv_}PJH*zXR3kRXu5te z{4Wh$8rAz0aC*6A&X^eTlZGjPjG8N<&x)32dfd1t-=>x_-Mq7QZ+?#%YnjwjT48vo zjyUxtO?yZwJnlfW%Ir1q$^Ws$82w|Ws-S;vjiuo;#B1i7{`AR$owuWx!&k!SmWo$w zPgmm$4cJ zEPqv7*ES(3(t`A%LFxd~AR!?ojY!u44si~gpc|C#PLT#dO1is2kPaz9N|Y|a@2K~^ z_q*@^kMaLwkFocf&x|$an$KKgvodPx@W@(2EkTM<2!e;77bp&RqOL6j00IShfj|L# zR#sgw!V&Zb#b?zA!QfyhMErm0pTIyC2!9kNZ-GFWsY4+E6{I78Ul71AEY2??4g>-O zfIzYT7(!v<0C@{nur)xP7oY-#fZ+J7PoT~oFtDv10=3J3mH-YbP5{4{mS)7m0&CQM1!U@g`h1ovlSfUJmCvE{yl+^-Qpz8apI=B@K?2Lf( z!oiNeD&+eW26e~^5bGyUCnpdD0muK9pF9`_vO=A@2jB0uIzXUq5U)RL8!*J$=2r>U zNM}Ah2-pP)QkMVA0tMm!gV}-*03jd{C?YBf0J#7_?pAhuzk=&}ID>vG`G0@GsQi7r zoT1JD8&nA(AFvGw^}+XoTeyM%2pAIN{5y)K1%LRjEP(&`Dno3b0I@&GqE6{Q3A_H)eU85dgA?%YSkIs+ z#)1GG{}9|5Cg|HkfLQT`tU|L=Shk&cePwH&|H|A*GX3GC?cmmbAe zBm%{Kbtq~AApdRp9Q0>g)j`%^q|<+El@S)G8IXn8I{tl#V7MaK9e-r42}W4i{h`Vq zT<_O_If5Y|O(-1v>p}sb8U*|=9crqq98i}A9L2}qDiCUD{=KCF#0qNtYq|u4gaH;X zn1u&Es>LWt2;jw!8bfQ4`)>vV_;?{u1j+?~D$fUC1BK!L>Zgz(fX@buqAUvi0|=l1 zC=&KJ@JI~6hq}1_F@F#O@WDZ@s0-n5?7&x@t+JTaa{O5`%!`gUWTgz(U;Sn z%VoL(@D3^#Du2TVbeN~4BNJ?1a@)x&l(SyN1xtN%?v0WK46pBTr!4Uh^KJ`dRDiW3 zAoblfBka=OawxFkJ{S2$>dS9y=$?>AzTOulpo|tK7 z`rkNIOPwfu`JQKqEL&7QseR(g0l0dTMt|2+TPt;rwsUu&6z`Gt(P3-pv}8<1xCGSA zVZ3NdQ3klG&NfJ^a;<$ zK72!-K}oupQDMXSQX-GnwiTEuIOE|@Xkv`lYk~wP!hea> zMo+m`apt(#F^5}~?ma4G$lxiwjVWz!=@N}1aN?TR+Uz*%`_xL6SN!u}%SWPXcI6Z4 zC*{W#E22l+D+Zle_vTD}Sn5s0z8Lcy*maK7xo#C441FaV8=i^W0rYBE#c%fFN;xGm zpI@nIvrwvGs3cmDX?hxmH~$d7;(waCN42h*1fh<8C92(?Az+s}ir%FG5U!B-G|NXNoha%31Hkpm~>O&iy ziYTEBU-WxnCn5)%5<82Wc$(+aQT(H2twzdi$<^+@YBz4ix)k>p@Wei0>oR|wy`uD| zqP->LwuV_GbE4N}dO}!MJAa?j-;`XISjn^D3Psc$*;3l&C2cCTpC=O^F%D9(6S~v_l(Z(8|cg3iCGofLH$Z4^IqEKcbY#<#m$PX zZpGQbzY4jf->_5YLO$G%9diG9;YzR^(@A*auB&5`&AR`9SuM+$`G1vJl*6OD&!I-{ z!3IRa_DPwcY_P?B20Zjvq~?j^!Ua?r?=f zzKU`$n^5IrIf2*p#_a0Ll@^3rVPNOHll5_f|uX_2#? zTR3HcBR664+Mac_mg++4Cr4fA zmfqQg(mD@}h89>t3{T@zMe8aXF{fsP!#C`hyZ{7~l7DeruPrGP_8#4Eeno1jy5Rd> znhi3YT&S_ekZ^peg^;RhRc9zckAB!l3LSya^~=oZG@3playK+O*(%??+Io5GykYn; zWcq&HD?+0%Q*`4Zr$e(#bP&y&!$is^87Uqv^i9gzGUHmZT|h`&Zp$?lP3aKvieLse zp#g*-%m+LOzK(eN$DT%vZuyq1WzP zKRta%nN~dbk@s*rE=LL&4tX)+?9Sq#(x~brKM=_2%4F0{KS4|^LZ`xLca{K5Jec{C zG`rKE*!y*DnES-F=qJYZ)N#AfK%jq4E|llGq6j?g?z(^Q^MUh$dVEgSiC%W36@TC4SK-0$jt8o@F)sT*<~}I*ozhe;Q#nQO zq)MJ|@5P82uq<9r_&bAbzE{qMu0C zmZaH?uWQJ)w`anqwD1$%q(P0nwSU(GN5wkR)7#onD!zC?+x!c`=5cnu=PO-?Pk461 zKY)+w;&L;hlI5?NxGY@8axnaMg;OO*U3OhfT0I$xtWK}UQl2{CXBw7S#XemmxAD(i ztADUg>mWLQy-4q;WKeZSF%Aa@9*>+R!Ep7|fC)n*u9|-%fp{=Y3vPCit+pSP*f}`+asg=H2eaQyVhR?=5P6 zZc2g5m&HHF!IXU1U4^X=p!8P~Z*ad#XB6Xvz7 z71-WuKcb(!{e*ATv#!Nx6+O1lg3Uo*m{vFU`R71mOZ|N*=`_v_&*Zxc9<;r*&u&l^vxdkxKt{4(dh1JlctS&&duYk$90ZsYhf3Vv3Z zhuL1blu*;8ryG<_(*_!O<}!u8P7Q*o-rsGJ9RbHfxgzQV>>Dd7XDM*OgHr4)(pCGD41U{Ks0~mY7)~ z`eIlQ-sdWwJFEAM$A2yyn4RV=31cC>z46wWj#lLIsWxvSZ=5Z7n?7~v^t0B4=^0P= z+Oro)n_r{blr5?rF#6kSa~E1O+eQy_}F&(K8{Ho z^_QK(yUEfA08U)KFcL4l^B@lUNE-LnL>Xej1LMvSyB?KdLZK1qaQX2MJ2i8Ol@CU_ z(X8w0cxw`2Q-7@4O0k8zQ2p?pPVrZEYqaDI+cjOv_Cf_Y<`ru70uF_!FJhaHS%}V}rjx-!b z?r6h`ceR$OGTDiCPjR7+uNoS5e25R8>ZDL|j9T_0s(&Ad6ND_@>3!*rx8NNXhEIkz zA5apfmh>p?Lo9jOn9WzGpBIT~mdji3MO{+*@}^%@U=mtsZ7wgUDp6I zM3CNQ#w}gpxPn3lb=-h=!3McH^#zURB0L=q%}zDMSOls+sksIHd^@Z(rOzGXhnD2u z5cKjJuz!=@)hWN&CY*Vl>$OrjYJU(aqLtVC zBkLy-POEZaV=d&HFJbA*{N#Y<#*RA-W>_3vy>n%;M(<+rqcq&^Y zcz+1a&Ml8t*!)7|RL_(VjHf$yqo$G6Sa+ zXA#CmCKDw4l`bw9t@#WKO0o)(f|wg!YEwEx#XP>$RYtp4A4!1AUD;I4knyVr4pcIt zOujC2$#!gPZ}h)Mh&X@><&N?@+#oNh%70a?#bzo}HCPNd#|hZ?pNVdW8gbRrRUg~*!X&`8 z`EaoJG!j$x^;vC7SHlN3vC^+G!F3%OVFMCYI5gc;11lmznUaLHXkumcUcvF67< z7sscp-YS2u2uesVFb7e6bUFo6%zrF=(2VEo_rstFDnEwDstU>(ogUuXto|ymrk=Cb z$LIoH@GQ6HTJ>v>rZjnT9mLf3sJVQhdr#bi*F<+Wh%!#_R z<0)))pOdTXN%Uy6d?i&}TQa;KO#SYi2bjR2E+2hj8au2QQnuge3=`%V zc#&H$&gYUhQ^yXiXj7ch*4@n>>k$JS=GC}Gx~FwiwWaE|X@AvRwoRlEv*Fnnh5Nr7 zXq7t;H8~_FEP6Uyaly+{w{@h&2K&|e*PJccBPCad0fThi zMYznC!~H22aDn;TlPW$Pq)qFK18*{pRfoc3nO*V?b-e2JBxHx;MCDytUJ7c8m~_1B z6aGHn2L)XvLE!B2|%pGP`5 zLzha>4Ck|H;E6)Pvv09;Cn?+PUnC0JmFTIOmxjr8yt^V}T38@c-tVa>GdwMHqa*)X z!+*GQrnhia%8%89+?;}ss>|$xGFkBaL)&s4PK#Kl&{MJEL=NIg&NvcRD=O0Vt^pqm zCik*gq%4w88py8?UG5h%%E{IlOdadEQHoG6hSLTOXm+S}o|pF+j4N}bdX!*BjEw=i z#v27h_MN^~m`}hudrizZD)aH_xr)dAi+@#g5KQieNlrjRb6fUA(n)03IImwC#r;LzxLX}vJ)qX{Rz>z zp!|fFx;<~5>#Lh`=TJ=wR{07pAr{>y zs=Yn^MV)6a2DO9HY*`y0^>jFYGd*Y_`rOb!?neO0o2E;Z$oFhW&*Me&&dPMGmI_lS z=xfFcol7dPs525&aemvXm3N2a$$wbD7}ZPCd`)low?Ixr_xgI;YRCEEhk?iRyGtt; zoz0<^Zx#SS0+b&Yw#1F#wD6uj!GQ~?u7H93ZPkWB4fjgWY8n^*!xW{$OrDnrPMpZT zh!0dxOWX1U3<7ST-2$4y<#QZ0u#d_+88FG{(%W(ZGR%t3#NJP~8|t~Xet(62IWf@d zV1~~d6sd(l)yNy?RuA@m_1w^JLk(#!HgEv}Z2$%VULz`%JdfQF2(vPLfQuSa*| zf3j!Zf*_`!9 zR#dgQtC?Q-W?}@%r7j#~yCNCc;cg^S)fUL3a;wmdb~AV(|=`_Fy7Nj?o3Ur zCd_@#3ny2Tp_6+>KF9jhvs(3?9m{>K6O!q?(|sC67ht`b8lyt=$SlE=uSr6F)cUEE z0#c`b6bGvu6F0cHDI7=dk%9tYR=8_~s*JG74y9evo;Rw}C$kqe&pB3OiU||dwu!aj zss}e0rY}x4vFS#5UVq62M^R>eFX))`CqB@hIL=UtPh42mMe3`V`zr+1zDl3*ySDns zVzym`JGy0calG_pqy!Pf_)fd(hP-HhyScyox)t+s zDev-fXKp~ zSk-$qOTn#V9)AjGKlg!g)g@%1SZlj-6pl3fypaIz6}`t)b(oCL8sF|nwARxvES;QW ze8U)dy+K`l7=dw}Jg1(bJ1^(_P<0(Wj^steg?iG>^DbA42l7P$zWhG1=82c+yySM8 zIY14LhmK3SxSJ`@u;vz>M2&k}{GlmH0?%$%_m?M&<8NB<2I3h=sdL+COwq``c^vkc zN%rc9ZUK}7jycBTeg^9{`$b292Fuk~WJW6WwhE;$uo)b8HNV{G?XOCp2iAnVZpuu$ z=u?m5X-q6%y_`AoTmAAd*~4lYepf`N6vFtU(Bf7DYX9+n08P)Jsh4qh0uuo?mhuA@ zw|YDUd>;ciHZ+%^P6ibaHZ%$^Ol59obZ9alH#jvpm$4-S7XdeyVX^}$f3^iw6lxbP zOi2tK(#lZM%nS`mhje!jFf=oC4IrR&ONWF=BO)as4bq`BNVlX2NOMuoch32~|6l9g zHEYeh&#rgJv)?t$^y*q%l2!-{m>dG`&IREHivXonGzEcRFfTV4%mZL%*0ytZg#D2M zm~~;UZgvQ`$iMW`t}v+kf1OMQ>V9XYf`9`RJsg1$ULZt31R^K`1_OD(VB!B5B3wm) zGEh%DE1(KDP!R!#xdE7^5zaoYb~d)|ceniK2xPTn144v_1v!7a10|hcu6CACI8X)Z zZVPj|yU`Nr2-HGY+QHm?{woCQ6I*w8XAuy{%gc)!>g2|aaJ3O*f8zvt*}2;SHDPWr zS5KG~@K?D&Rj3o}cVXNBW}vpMo!cL=7Q))y3+f63-U%G-EMaiBI|mQA70eZQcQ;T= zK^ds#41@nMR{mqa3H+-yKnOSF?{I&4{|aOW|LqL5v_v>LL*YJla2uetog)mWCa28p z?(NPAgu<xinZGRVM1X%}HZXS}KNt)a6b1ufE+3fB!p*I@Ip3EWrQxD!{D~K;b{h-gW6e348uEeb&DggAMrKu~ZRvjD-PN z{~@?Bm>+C;_XYWXrulD||37yBit>LU`2Xf3=i%u1Tg&=O{r}NIo$MTa{?gy^)x-Uc z`znaL4S@fzsUGalx~jme>^z+QSF7L-z1smvxQ*lAe@(P=le6=NS*hE(TiX7i${)GT zuLX0ogTvGjZg#&O6d)G_4E`V8-BwvT+&vm@cYOS@+@h#QV@zjFcJmFEw%Mz{ig%~Mzi2(tJk`h$dlAj`ke zuY5pOfB%9IAPDv^CW8}i*na=v?G;EphB_kX02zodUC@{cbs z5ajYN$Oib-gq;F64}Bf3wF00ah~GyR6_v*Hg*lz7C?VtFo*o z60>yI$eo57tgyyJjiyV#E3*X6&+AQq=~41eBX4#jtGgfI&~j-@Z1`Qf_~`~Ypf{kl zDl+G~cnA@wza~BN>U!#3-Ca627&^JGvGGno3HPe>3s;Ozv~f_;ICGxGs|iX5On0sa zf7t9Khu(zaC#Pd1IU~1piU}M5|J@kg0;J&*Pwe@G?|iv7k6RlR6O|$51N0M;!OxG7 zQd=pC6jR9Jf`$BXV~@fJ-mh&aCQkzURc zoAPGknzQU#g)p& zyzcxf9IHf5Mbom{5E?2B&chLtVAIzC-%Sb%>M!gxI7hV{;SRPXV`%njUR%vye_eLb za1I?FaVBniAK4eIQi=P$_Pw0gwvSlZxOhnO0Tf0_}fe~zcSzg|o}9pC0`=a5iuZhtUwxMtp#S=%mKro)E7 z-v3sscZh2*rD`43KG#0q1aEq$5LVA^5SRJ^Cves(U57HFDrTa%MQtc6k`gR4PwkRS6lvLf6oBZEOYDH z>9=ep0r!~{n1^p&mR_nWFjjM^kR*<5>3Ta16LffY?@BCu9G}Y~HC$8_unjzTyD}?k zD>+-aI6R0cLe$C_kFc2ZY+N7%!&;25>5d8W_E0kHmi!-AQC+HZ5)j@#wbI zQ?S*yP`~>2rMqX1b@6b|>7bFyx{(U&9to{xEDxB{d?Dh4wzAVP2=#PLgEUt8Wj}2& zzOT}>$^)nObVCL23$hNcrg1n-x9cZ8C96LI5V8X|Prd0%J!yCMfAl{ncuS)7{m`q) zd4tt^F(KwXE8S7ry2Jk&<9X8Y0lin=nCW&R-Z|NHSHZMr5-a-gXFg7@{9ste_m5*u z`Pkwh&4|_ARPk7uY8RMGdrAlKtC%uc>}syO++u8R*}Z)r)5+Jg81nen?7WDN%N1$C z2ICxHB!?>Z#dU39f4A63csPq_ZqSDw1;tC+PJp$^V3;(6n=?GPGM6V9f`jC}5S6`} zwXfJg<2xBQRPE;hpu9U#3SjpNY81agJtlv%wa=JRlN*X5TuS};7*K;Dd5yEX|0n7jog0LbPvx(WL{EvrFVdnKnLa%T~j4Tbh=?*f898rpA~NyWDA4{pAwzr zZFH}7edubD3b$`2*!&pTsg-6PZ){3PeVcK~QDBnI1nt&mQJ1z)nth5T3F80=8!%B> zT$a{N4UZUqk^CY5i zei#uvoj38$fA8fNuF9zMw{tFn9%EhRo&_-Uw*qHLt-5iD%}laC!;+D&wUf=l=d6cm zsm+ED6AA?$wdr$FAGoeYydO?J6I&}Iq~m*p{j^)$wZPaUC*u#c3^zqj->*(JbhRww#J zXPWD0b9>U*b`p`bZtq05oQ#8mf|FZ4h#gIz+N$=_O=C)2?kus=rpCMBdt)?R2;5Jc zp?!~GaiJ0x#D7A<{tdg11--PeTVP#$ZG8vcDw*4W%*w7zr{io&hlC?DWlzI*xhFNf zomBa#8XXolSjkYlNHZH8dBG~@M5XAhIddD!#29f4ATAR2sQ>+N+9Maze&%>+t0>xUV(Nim+@CQfKc{CInt>HdEJsrt$n&S|y zEYFQ@6By$(KH@}nXZ}E4X zsPkzs2*}N^p|qZ@Z62LqzTf-&%$M#Yjetop!#%!nh(+OaaRwsVicCuhag zQ#`70Gs^{yS0ek1DE5iltHp~V6BoeYvh3UlqOAdAei31PozFn~NHopNMH@zw12jFC z+JCGA!}{Wc)uzCV_5t|VSgthstE~echU^IJoho}qj-HjCUgPvhWa3cLGoR$m(qxm- zWW1QM9YSit|F5}h2KHc!{$(mXk7Mh z#ndgCK3<39*F?m4N;!lh^hd8J2*4FvJAb@q=q{cZsoZiEW)JiwQ}X2ePowztq4=jK7Z`*{u7qnc7sldHa>g%L3socu=6NU z*~)Op|ClFK??)yv_YPlC>~rq@CR64i_JYv|)#L**Gkyn#;?;XE1YgAJK@L&h;<4k) zJW*eT4A`5TM=as`Dz=cGCFjm#et&x@_TW3240VpUy4mf4`zRuB=!a5da=daRi)Cr# z$%h9hCkr@VX&1wCqns$ov@pfU+PPjuPc!-@#Ns`EHoRh_2|-_Ju_Ps4qN!EnMK{%lBPBf}x7hVt<9u3tbtR zZHW>p7pVFc1!dVDnfkZ3a|yh3FiO@qsB5O;l4JUTU`oFk zZj;7OY~SaaT@m;rly))*sh3%ze!01DCUhQ)`?{T(EqZjv2eo9HhaQI+rn?O$HG({h zp>JEm4$A@Ff@JF-v}DPf_$%|1)v~8Y4|MuP#1U^@@T!UQj0tc0?|*+^r^|7PL@T7A zP+vspcYktn-xhVXwxefgS(DTAonRE9tOZJN_eP^3Kba`?iCAamc`8==VfSPf*;zj0 z{U%#25>3hKT```n1rIBjkal!IW<&1BOaHnj#h7+k453P(p+cdzDP}1eI@5S!=(v zI>>JcxpqIJ*p&uFllNenVTY7$e_o|0#cO^M3bE<5F$aG5Vt?`dUY$n@PTl2-t`$PN z!K_S{DYPgQ_?bl6P! zPo5dpe1H&?AD<y6T7QEFArxOp-WKD)GEl;zkv1d?VJ=N_BV%*^GV*i5`|$KuUX4OVbISIG z@+DeCbl4p6N=b=0K#ud7)TN3IoSZvxU-Sn5+os4Pe7n-N2>p!voR|Yk!*iIn%s4u)=H&0sEI&9z^>Q z^tJd2h3?PR4U{<&j7;KpTE`hU9j`gTfhmXKg}dqL0e9$vDCC9MY0 z>&pqvShB+SP3>qiDSMI8kL5-mKAkN3&T`%IK%}a>B;V@(F1dc# z2;5KMoalW?;Xp<6x9d^~|W>=`nWZ|3=_{I6d6CH~aFk@driM-s-;dwPn&sS6f zihsCwy`!8(19|yfy&#m+O4}obD1mULAVd3ZM1S> z-ulS^8=q&9RWV)sLTkGmX7o(z?xE4%VT<_;V2O9av+XSU@pEL#E)8V>L;8;0_|F;3 zg`FWvc?X;2wC{7Gpn+u>e1ruOh3S!-DZ5$h`BpV3%686pp8SA`!s(Hrt!fa~V}Gpb zI>s8wrvg&qb#&c5Ad*{{DLvVvLiDR+jtH}o-H}v+8OdhUcKO2geeGw2M?j)3xoY#H z;Kt+%XW*nuKHdXWw5j z{FzY2Rvsth99(D=M&PwwKg7;j#?WN+sLbQFNFO`;E7uH>Qqi^HrTo3XPIcvVTMtncg-i>l!=DDDp*-?6iaRzV5CaPb`ZYN?VKF1Xgc&}OM3ax;KfDHuAPh6m1Hh)Is3X>9q6yD?K zEu7UDzBeKKW*O@U3004;wYW#2L;q-Hz=dr5k=_N7f$Dr%jrbZaP)>soV8 zuo9XMhR)_i+!4{&PJgJS!ikZVKdk#K{6fOS7xC7U>i`B1G%zLFo}-y$p43pO^Vk-E zru24#+4R4A&b1~Q0Q#=bk7hX95+B2rvKEEwm4n(zqbu0S%FG+NVjy^d9PiQFk5V%a zC@bu{M+fKRkACR68%O`#|1^5^v`z83wIkK;ddrSv`jPdqwSO3tUq+gUsYIY*#nC3d z_c3L{tp|H_{deYd$c_{Pdc) za{{zvxy?5-S-O{iqO@@J&b0a&?lP~%0kagf1XHPsRoyO=5bKUxVw8Hno@JrI?V$)y z@@LgYM}IEF7(-wA(oW);@&LuU2A8z{7Z!BkIOaXG}}%1Q+K*2GrakcW>x zRFp{I>-!SptzA|zu6dKl%X7#uM|&Cu=&8ks>tgeE^P;Qb%7u&tWeJa>V&wvi81NXH zYF(YmVOim+J81*R>G2z0WjboXxJ{d^S3T9KAAff=G0ZiTgx=E`pB?VcCI?!BZBKIF z0|TE_+zOH9h2Z-GnNhI39)=W2mxhh?2GIPlg*JeO zxHxv#$a`=OJr0C{=Ht8yNbtt#~^riCdCzO?LwD_S63XIoSKO6#;%RC(*G4{m zs%R~)P93s7A__C_478?MyKBv$IONz)!R(mh&Cv643?7QCN8KHHzpW%$ELZhvXIdPiha ziS{v?%17p#MO^2$WlfeyEl06E zz(Ihak7w$!P0m#wF7ah7&=NtVQ#0c-r8XF;1BF?X&OxBxp)G%beAq)3=ZT0`+v2WJ&Q%ArgEut|Ros6?bITUM{gwu%WQqzha=a_U3K;EHGk{vu|E=W)?hpFqb^NVher1CKchdWdo=DW>mCAhbx^)ZdU+iy zG!i^qRjQxU9VlSK;qA0|u)3m6!}D?zEgL;|Lla(`(?8Vw<8Du>G{P)M!`;lNfyLx9_r_87%(Y!vIDfP4vEyspFP1GvNr%%O z=lAZu4WfE7^l`8ET>5K&5ksLx_kEhASk0VTi?tU|WTVELj$P{CGs0+Po6B?GOt8SK z!2QdP7ZBd-PqinUxKlhrDb&Fv<-N=kr{kg#x{CNctV`@JoV8R77EoB24K>31H~pgs+6P5z)V_HuKkg%HlE zQ6nR8Rm*PUe8%xdg6w{yLY(>jrmy2eB1lx~miq3}q<@p-QJqVwuT+&m@5oPx?#YL1 zU6}FVPLg9VDW!iVKlw%}RrOre%hMPG(7f_JC~<_$UU#`NSaD0kJhw;YVHDNrLcnpc z!TVIQ>5z!<)|PMdKcM>aUKQ~4bhYrNA*%XW_-$|fBu*EbqJjDw>*0XV?QNW&dWzZK zS&&mx2Y;A*v*?Y%pb5;%6q{4I1O3>X`RKfOo{t(V1q~T^4UzqEA78RRX{v?Zzo9K> zp3K8l6jgpiyu85qwqg^0KV0u9)(r2BFSPLTa`HOdQ$* zS!c>g*Zjuf1Iuizft`?$wo4{{)pBTiu%(5kzn6stV7a@8t z@tK7SN2CG4U}9O$I~wen6Vk&lai(VrxWbX<1>;h6>&wMR^xZQJd*(q&ZyOZIdAQM9 zMKFDCC4oghM~loVvlHYbw~4An!ezDqOn*D5rp=JyXHao|KtCS*s+pcyK*9gv14auI zDb8VnXl8h&aR~GYBPw~3fClto+3=NO*rHlg`_Mr+L#S|{by>@IuY#%%S(0{0orVhK z>CLd^5S09I-}P&nxmtHR%AW#k710bUTWd1zfwfXqYzl$tD75$&2H-_0d#YsNFMl@j zeS*3irb93Jj`wd4zY2A!g^7Ph|K8osWbe~LC-o}LidcTCYm;)s0e3b=mDR=5e&yvs zT|r;niOuU`&wD>*5F#NtL#S*>Cv6Y+uDUDg@%F?|r_423hq~x#4?VWR=myBslo8%~ zDdARB5-VfXA+k|@+Y034=?($>MSqbCOTC6L;_;gZnuM6Puv)oEJ>oDU6vBoUeyN|X z$jy|S^+SG(I1#xQo$133Eg`D4;kWk)x)%mj6G*mFrutOcCUTR-K7Ge$ES`5ZTo&1J ziWU7bbMHbPpVCTyxW0Tnqn^!CD!An!SS2azC8bwx*oXJB25GJ6pHOsfPJf$8^(;_k zGD~dQ78k^egYlxTR;>h4XR&-!WBG!VK{Mk8Ze@jF)ZDMpwi)L#?*{csV-yGaMLnkt z-?C0(09v{BYthIFgMCZG>#tzfuMR$eHa(oV|>C#vr+yvpYXIJxaYt zxWG}HZ4!Fc!~u_ysxycVP5R{F2R(`w_IH}rjkLsJKb1l`k+AY1%73?}`%g58@zP@Z z*e}bHy5t7Rt;1Vv>#necBy=g=cibMm~(Cu{>G5B8~FcUw_XjvZpzcMjpq) z4K5Hs&8}t_$zrisb*j5ZQHM@-QO8bao>S*j?t;yo4#s!EsZPg`KxlAiuqe|RQN z8Jz=&*coF%Xq;o%ioP>e^M(cCe?bJaaWR7cYw)RKmnLS^ppiA6gz2nvBy49Biikm6 zR;cl=^U5c5>^pBTTnr$r*SHlr?=qQV=L3a6?>dUTgGcmnjJ4GB*IJXD7^Xce9BG*uT-e;BGRS+iwK z01*RjL5Gw^8wimhi3U$piv1W65J^@*L8FP2){bI;$A~4U$IcF$?UARQ%*rgarq%J!L zC79ghlu&Ik6D10=FbtI}f9o&>l|3ojX>BtpOjKufWIZ+JscfjjgpfP7($=D{go&U5 zr%cmx7Hgkqa*ldW4*hwRFe7T&J4Xs_J$rQ=BPeh?E)SO4ZzZq9fMIt5qXiGyjMRC@ z#Xx@{QVy6ODBLkniVhj}WE}g;5wbwx;9w64e9sa(%N=0YA~f1lKWk3iOe!E5WlCm`#< zC&w7U)}c?i(<(VTo1Z``TL=FIWE~ko*gEJrcVs1Jzfv4m2R@(wj*B|<`Qh~Z11{_E z=cm)X8Mkn`T!5?sEIypgc&7@n_zjY}D!~QFD#35u_J#ZdWR>8*9j&>Lvoo~xWq2&d zTev~>mmU@yf7B^#)KIoO9d?GeF~R8J*(^LD53kC7@>^^qIYaa0-{c^#6_=EjhZjdh zL9i1;0%L~1#4d;DN5p{h<3W#+y&QqDh29JshMJD>djTO$&b$vR30jLmvCmBJpGqCi zG8qbz%Vany9)XbrZM|2u5AZS~k%kePnB?$?PCRFLe+bqGJ@C-uXhcFNCL6hjKqvm6 zXE_*vsv>w6WpivQs4fJ@^z@jj3N{?vzGW0%s94vJQ)||dhaZl*X3MS$0Rc-F44G0< zv@@8&b<5`49vs{=r!BS+^s1<=6l22Shq5#P^?l*_eWmR$h zsR=B1kB?6l@ZuNm7IOV$e*B-U{@%&i{_N~6J&FFQf7n0j@4uxZQHU5XW_ye7tu=b$ z0aO4zCPWK};}eGv=CYe$8jLL6S6_AgZr6W(fAaFA>$kfv-p>y%&SsOn>FHvAay-%Y z%MO02MvBiA$GZul`zTHb6DZ+Rq;a<=jW=lmDAYNe6QuD@O)`+3!`Vl-kvRVL!~wFL zC_)iuCm#FQC^N~#j^0nqhT?=)obB#yR1&Vb{>=|R68ZyyPZB`X@x|fcPiy%MBl(2e zf9GR-z$p{&Kh9^enE=bJ@)7pPjCOP;C@n2^5F~+1>jhDH3E{W^8qr!JGiTYqdG_vS zYK~nzI+D#4mN&mUJK5WvL9Jc?-S$q`znuNP=zdyVsqdx-Gax940XzkO5NeozF*^r< z*_)k9t|3)VXZ!Q1Ks2r(cW&ekMHgqpe`0{^g-;g$9HTNZqAbjd%GsB5sAnJQIo5Nk z=Un*&AdDj4KbuVfD!VV9P8X+#CyT@RyY5#z$rJZK-G{~E^!#6af3&Kw*Lj|LmV~6Ac64ej&lD{>K|XOf9j75 z2+N+H&txgD1-bLH^TquS(=%evC(}y9q_-}CWl1tch0Be@LF`t)9zcH-Hj@JrKbw;W zyGzNA8!50*9@@&eB)1~KgX6uE{rT}hH_mjZf^pB^zn@{vX&rBY-YZ0Ou|P+`bA+mb z2)!v#*gHX)KJ*2j2amlRVt*fde#e0lKxa{Q*i3B#o>NAX;nHANMCf#ag@mtUvD;{YC#P&?nN~{*V5@Vnw|G|8q&+ zE86`3pSs-bnEcAR-Is_jB-9$~j(h^Lf^ld$RxtjI`Sdd5NfnImf*g~de>5gPX-t07 znEa$VT9G`amFy?gK@UKViBB36pRAVIPS(q8Cz~eQ$#$9TWVcLdvR|e&IW##;jw?A# zPAfS~&O;89lp2$kr1X%qBvr?5EH9}l!ml9RkkcgPhnyy}+9_Ht(l< z2y>qU-Y*Fi4M2q-h01=Cbogt9f-z3AvrD0t3C_oa+O9(B`2Kitd-6mL9U<$ZZj3xr zpIA+urAf5^=hA2sCsFB99FJU?+2~&*4s+s++{ZYiUWxt)z}!S&f8{(0>4wGHIh&o& zl%MaNO>fb3G%|IhEK6x@oMa?9e~mQNZ~!PLhA$zEJT{q1_Dt}UrK58HhQh!AAt9%4)dSXnzna{Zi-+*{$CJx|z6JD3p z#Ba#z{Di=0BVMg0$!^4IVJkUq)~$vAgeErPMYNgl72QU>I9t70zZ$+fBkkCT*Fj#j znI5z@lK_~t$zEulO0AgxrH!%rSc~se^XF}ZaAhNC_op|4f8TH;_$#W4h~hqP#2NsS zatxdC8auHc6M=gX{@0p~7OGMD%5vPi0&iW86KL-(a*YXK!CS!T3Bf%|)*>L{3cK8w zuQGtSn63d^@a^cNZdGI}8f6GTU`!A|LoiFGkl8@9gW64G7s$fE>XV!Bg91QYzSa~0 zY+$!QPe5^ee~mw}wM37mbj%aiJ}MbP%EA+DLboX=NL|W|G?PaR2}2>7U5Hb*vQcc@4*4VWQrSjCc< zE7#JCe%rg2=2+=+_jAhHXH%B3TAor9os|h%&RKI6fB6)bT7ho7;gUqlTH&)v)|p>u z1kNMK{8Mgvl3q*uI)VYn>wMr!))5M)lsPBS_E-~ST?S1!v~9K0&Z*S!c?Xa2s_J`L z*S29T-!|~;6l%Q4)#^q1GkUpV)(VFmT8BWH_*Q`LoY<4_ai199{e7%GprHgj=a}Sk zXA14Df9$y{^d_ZNL41ic`_#r8bzM*E@3dpD-dSn7S{EGMNhxn=WKt66B2`hzj*>Dv zI-gR~1B%zKW#K3S#Sqa=DcdQOkrPVDk{x$apf^oo^&bA4A8?5Wu<)JA(f(oS{02;M z<&^YmmAL3YF;ZZNNKP-ecM1#-8JiAn0yS9Pe?USBAh5c$P;hV z%=T*8>W>d4%r#}ZFb*EY)Uw!Kd$;r>G%U2`ZB44Q8CC0K2Wj_QkI&S zMK|!rdRWim!wuIhAjoQoeZF$q#Cq?%7?bCki(WI)N#&_Mo3ipkCoW&LqhdQ{TqzN9 zfAva5QCzExtMrPhq~p3g4Q-8>V8c_DUFyXgt9lZrQq6tj=dy{p)>4bBF6BD&NVL&X zw)Iv3gqHx}qXdXj5+KzwA{6LadLwsB+4R|#{0^!;v~o^-f}CRJGMBP#RY1(uGARjO zS4wR}(0VH7QA;E{JVFW0HX1jTXKO4zDSG72I0SV0?P!vjT$HQI?+FBg3ur(z^0562}pvL{b|&Sf72`F zYK-C6s=h!O!LpPL3nZ}DWg{R}i8G=OiQO$<6Y#F#%)Muy79a}hvswIs>{o3iE;`OO zmUUyGaajw1w2}#UNjGA%N>QMGsE|>>VpCHrs_>W6iWTx*M7b_}Wg%<(Qs1^@J+lkG z4wG!ehtDlbKecq?Ok=?Xrk1idemr`?_RvYb%Xb)LBmA61V z7kKV$g$-V6hxtpbywN#1#I}*}Ie|b3Nq?M5e z{)__>kt7)no_B*0D-S{LYT1WLKt5!v7{rz2O|vz5WqMp< z0T(Z7Ct;pGg4SRJEor`L7q2D&#&XHM?9)`h5A1^ByudLD{AEs#4?>iHs$7#PBN;Z| z!I@>0D*J>Q@#2kw+zoYCf3@YPl@d|;MOhFZ0Ka0TM>sEPT2i4T)*HD-bXQhDs>2>E zd;yU>iMNt>rtBk$*HE0Zb3yzOcZ~~lZuB@P)e_rbsx^-4Jmn&~x zH*dB8h!2r>yeM-j zLkS)Wl7I*%{Ron3e^gfB$klSte!J6F{Y`0K{2r4uH^fG-R#kR|t|+omd5e(BD7MV_ z8vn)qM;Y7Rd7YIJ^U(6VsM!Id@MV~hYPs6!`o@IhUL)S0b-3+rY+-#>4^>z4$TBT? zhErT=eb!Z64EUq--C*8WE zwq8n6rIk=!f67u*X2&q2hj}5ZX236YAz8RQQOOLc#b%^smLwvS;G^V3mLx_>G@vV; z3X-bXpc32|>%dwU&s(IBGK#*6Z#u+IEeDJmM)exjr?L zmP_u!;UuGRUP@V;_HNNtp`~O3#-C!Ar!RcRTcE{ff0XQHIAY+l4i}6(%QfRs*ebU{z}W*w*Vl7nW1lTS$SO$mKR>| z(Kz8%YP@1M4p782l*xk1miMKF)Oj7mD;RmHCM}j+<(`#H!zMv(LXY=~xP_LIIh3MV z8z<`Zf9W&J(ob7Poh36UxvD$@l^QON73|KKELacb!niHiS;-?ZBTpKIldo`zNOkRj zW{gcqM}TMF{R9c!rK}jxcysAT&3HZ(z8?YETN%+q&VY-r?xHi zvdgP(qLJVvZQDMDM}C2VvTRW|a;Ab^L?1#+fBDl!Ur0ZGxbx!C5C6RX^xhk-hOeVt z`*HLgAG$m8+g2U;Fhq?XMgzaJpF)Qen(w4FZ(jR7wAOC?Xd3aSe96vNm|ygF`+NO% z|E%BbU-r}fUHNRhf8W2K_Xqule%>GUNAkTmzf(W0KcMV?X+IqA|M;@Vzca_Ess2`S zf5R`vcXxO0KEGG=VbhzaclHqMf?*3I0;cNIutS z*~Lc5R<}xicgCNTEDmSy7w_f=2gCIld8OjRbn)AKf7Z{B7qf%2>EZtT{Pb}8M}Nw% z5^A%Ri}q?U(u>nV4?VA5tz0ge3pSHq!z_k@FOKIY$Ms@$72Kz+!n6C&ckVxse^p3p z79nyGy!k4Ayvz-GkCV@n z8w0~dJ2|-=e*uCv>*nV^I;Hd}3-tKa?zgX=ViHdut=lHnRQIf0`iMKSH@Txb^vZP> zX6-87gD0XFq7Qn}zv|!gKNQdNe_;;qb96L?_c`G2v1Vs*GDrQ%(d=M4`j*oVbKRfL z;jl0I-&ggLmrK36IQrqCVxoBPIVw}FExg_7tr4743BN|++&TZ-DfBRRv+uwZm zqlg+en%hc)YmIrBn~t|Ow@c=`gTT4FI-^heN!gDN9)0ujvCJXe5VvF!THV%$Olvpf z18l~+1?%?vnbEz7jtKwD<@H+zi2lj*uU|cTDO1_ZrLHu%e(rg2M)Jd;+gQL=mr6AB z0G?;?IhQ6k#*4@Ix4(Pwe?4S<0mr$Kt8E)xJ2@c9Iyv=OUSt_9LS7H`9*UcN47m4X zdh~98x`X8}rr+XKRS%U%xa~QDT>}a1q@|+!)(=Qj(L*hgJ z&3pMHQaro{EdIO(E)J-sK`Ki>e|T{Y)BELOcFtesf;d^s_TL=}fBSGzTF6x)3-Uag zmkEp*wER4EV^aO4)S6%n9=fIAH4<#VU@cT2a#4B#F)!*otqSG z*cPi39Ru~w_xE1zh>358L0bOn-TW|7E&m$r7A9&xW1@CMBtPDJ^_p<`#fE^S;a{Kr z$V82~m5Iic6&-AsJNV>!hq`>Uu{!5v6#rkGxu!RSQqJ-P^jC?QC6A$spbFF_DQ^cvqJIp;m!dGB58-Zg9e=h?qqp1q&_+nbe1 zN1s>D7G@1nhCva$Kt2IUfP$u;I6y!^h)+O3kbsrd0E~cu{-6Y`Mj*Hw7zUO6UwQ>N zf5-}f!W69#C^JnM6rk=70RV*nKv7Acn52LJKu|zH;%`G3ToRyYTfnb!0a{khpx=e@ z5wHRb9KddWV11Y!!qW;40-yj0*aif3LpiuZZ9#AV>TZC(ng&4I1qA(LtntTy2k_U^ z0DyeJ|AhO?`&S?^^tZE>jSbA%#R}>LhS~${zz`5XTUmn-fkf~Ctf02P46Pt;e=wB4 zm4_7=Vr7jo_?@^FKv_-~V1=shuj<@v;9wVo8=o5(@~cArUtv&>tOT`HfH^yZpa?gD zU->D5;UF8-t9$YPZmSa%<_Y!rbG8FRZS8)QVC(L}ZwLjux`Wgd|FS?q1pi?6AOt`} zKtMoD0tf)P0zgO`2mW8d4ZK`Hf4`N#VO0KpJ}xj9fE}s?kRR9%g!&`!akKIO0T6I^ zke|>0R{UEc00IHFU>gL$8e|WK68sY#1%vGV$f(Z4!AO9q0E&1(fWWWce@az3PC?#CTZj91!T(Xo%fpZWA6_9*0I#5k001Z;CIApa9sK?se?`X%{8ttN z|M;pw?O*_jKgptA>FcnV0LMQBeSeE@zouH;=U#fH3887Hhlv6Gp?E-Td=$H ze{0ncR;U?}gW5y>^N3(Ke`PQdWUB*4*f{*5${*bD*MLF5P>>GH4g71N0C<4{0{^8$ zO_hxkYH7Hk`1o4|LJiHouT+BCz-)g_m!OC!zzPnx@*+UB7$u1Se1NDiv;`r5GZ?_n z2ZbR}E&x<{egHcdoZweKCBy*yR==R%k|+?s4{~)!_26$rSOUP0e_C7rk%2%#0KdyW zY5|ml+8s~`$PV!j3j7QG)B3+*R1N$HPuM?Z;sAbc5d07Duc~a^;V5s!Z`Pqo{#*XN zKtLcQ$cA8c8fGIE;#eKhd|o9-=gGSq;(keto61?4{d^gIDwo># z>F&Z8C5{u>ImR2Ge{T)7xZ#b-x=mNU*A|I-V;fBbpGT>>M+(2m)pRl7)AJh0Zu;K1 z`Wgi}VK$(DRA{LP4bd}BzhD~qiZdQsuzH?nV&KqkO^DL-%lJ%8! z&J+zZ4uY2fkBjU8NiunIIzjeww6I*m1*^kwvx44N)ZKi(GNej$L ztF5o_Ly#eBe|g%}Jk+CvI*rkCcl*oCa1IHsq!;%5OFuAXP=3u(U4uiURPiMTIgp7u z{5pMCDYqIKbca1dvHIs~>~7XebWH^_{sC!pIKDa`F)%$$4Hci9ypyjo z>i*Kf%xU0|STtg;KuUtdctOLV_r)ufr_GI%TXi{Ff9i`f+9xh*nXivjvs;+M2U)dZ zo210qt&isLRB*^+O*&HBlC67eSBT8PyALYr4;qgX!1t`~f=*N1^6EO5R)du}A(DRg zZ!3k?pAsZu6ESFdoMV=-s%Raw&U8`pj2E@=`&*7io-t?bVya``P0$t;5}!)|;{alK z&D2z$f7`6L*om!A1{Mt-3eF7OOPnk4GXN0({Mt?QrbG4!pAAV#!9cZKLniJ(5JEZY zV{cU}LcgpL*fZtH?vEv{-EgcyV`G1=v-WPsBT?d=@<5jNB_-?K=cVVQAt2wI2<pdYMoxxwKh4N2oua-id%@9a2+%%ua83DScsrB$ z`%=COQJN82o!?=M&xhiNrlgegB4BlGEjYeW}`ucm462GY~K3Rx;RdDuahzozg~G;Q_G%1A3bUf5H2&x ziM87(Bh@UcNj_MxC$F_!uG0GSBwi6rf3gE3!h{kM>AaoQZ~mnJbY2nL)al!4OuT)M z={_R6z2k`douN6cOyWU*-l2~n+c+~yY6uq z7%d!Qfea;U-mGvy~WL1-!+_T4(SMX<^C$E~50^C{mEvhq>e~HZRG-65@ ztfM7vQKU}h^oA*f*|nsz^3KfHeXP-Y)Vvm@i-|Ezf{;BP=;?ge5Uv2Py{1{&_b%96 zPgWcYP3Is#1^HF(NYdabjiAXW1%|es*i#WolODCtZ82D%3NVL`R=FBzqnl~qJPT|k zppYBPIv*>?8Sm5_NQ;p>~(9G+T0_-%vnOtZ+X{^Z{AXWd|lh+?;VYd z5&c*c;G7&vh5PhW*(fUIR6$7_sUCJo;Hd0e6ym^1`?RkG^A-Kne`t8L_=n&ghUmHN z7d~IyaXW~jLv0GUHl#`hKr(aI8_PXt5To*+zGuUvvW1;vyrlW`j^E_$)+FAy8eLl- zzpB9}6UQ*PnzyZXq!DJ?HfnB6Uk6p6z@tn&CQW!iMn&UcSTX_xCK!u*Pr6hJaV|V= z=OMM^{@eTAvk_IMe=f(GA)6UQNFs4J)fN`<%?^mf3vIQEWpfe_N^F!w4rMg99tyz`-8RwXZ;lV3|cWMFlB z{*H;4;PqOc_|vQ*ZWlJ;Q^yR-b=nW7+UCu`cdrdxJYp3?&C?PnIy-S0V>0K7j*$=2 z-|unTL5|mve@Th7uQtWnE2YA4=nmkNmzs3p-T>j1WdXBWqO^jcrx~FNMN0z< zjO07*_=2@r`L@oyYKu2kn+xb2rG#n^;Z%^c*^cr6zb$+Nmj z?slxmPg@+$%y{VN@^?6_;jYH6wC?C;!)2-r_C2$me`qv?E@FAf`4y7yv}SeXC~eW3 z_rj*8j8lIEeb;s3@TDC6WN{XtU%=lxa3*e*Y;@7f$_|_JU^WztV=CV*c4BZ4(Uplm zdR5A~8I@|!rvB=|K4UQjY2f4l&q~j{qrMp>TR(7D*>!Y~t9OTMzVB%!S6n=}6cT=@ zZ>N<)f1c*!YC?}+$&M-8vto;N4uvq(``j=;?o>R^N5AdL#Ge*M%o`ZTlTb@!-ahpc zb^z%TLfS3FWK&2@=nXsHwDP}}vuWfSB}aQB*ZxeHK}u`Frxu4%_;&BrHI~Rp`Ffj1 zW&5l&laUDDoz@&bIQrw&D+a39uFu!?GcdW>fAubi@K`Dm zf9fR_&aMSQJ*SM)wI`z;SN%BmRf>~)ue?_^3wLSN8=&g0hSfLgevLRl%0^^H=8xc$ zjqW>7tQo7!ICW!5XB_RIxbXun4ncP}5EU6x!_N{HVot>+cX)gvs;i}MFx5$vf(1>V zyj5)UQS1_1Xkw6PKc!<=4_wMU8{N2Ke*qqk03FjL$DrIN*edxvGhHJ*sgxV!0T8#J zLd}cMmDO$yR9E6v=|e4(&`vWwvRhNXz1fgvo#3_WoprPck=RJ z7I`qUZKAGGkH$vGiEW~JRy{9|P}q5xf9S~c zbDL>$uY>Qf8ACR?$oldifrR>p-q?owy(d%C69fVk#8Y2h+8?gdwp$R;dqP(~`fNAr z%GF^*F^k_csMsf~slJFY!&M@>s3JZ}gavdN<=ob71U3sxa)jdzJo{o$Xv~P~_V8m( zUj5384y^{66#~tdy@Y#2+w4{Se-AG6p7XMad@Oz=y2v50lHO3dE z;+=X?iASju*Ck@AVfW3}_Ybxagc3BridRe_!6Qv(J@M z``NPGo+^{ioG~vyF+HK^HCj!mv8(xrKxvVuOW3Apy4`o1;GSP1aRf2;hVVtOtBItU8#e|MoOFhK3lTcX< zWs=EEH8x6H-^NsK)Izg1e-Gqk)C93ex`UhLmL$mOjI7&mYnqrrwVTJM?<270a4P%mxZlu<+s26?t9K(O~VOUvKo4!Q!B+jZ^ofLJSC zP0^_m&r-kd$bM?h`pSqgw|~LW6+!>OJSLM~i2-Z0=7zQY9S5PEx_9K@7xVjfvTE5= zYpU@u4(f>X0JVZc@nKdW%~U$UqH&B@~y%hIX=_fK)yb7KHZ{?lytOHV5$ zL~L#|fCa)7==c06q3q7;O>P5v%yp>a=kT!X2&!UsE|8wX1}{l0-+c#)5~)}R9L?9T z?$6~mmGLAar(MWP4u8f2a2rjO=bd`W3$4L=_qEi|M5p%+_D}Ef&)Yh3pPl9s>+9nw6%cE{4xG05ZX!Czv~uZU*<>xz?~dzd#z>ri3Im3`3rb_#eYJZcR6|e|y$-UD9B|MHoZ$)oy*=J_pI{8_G=}p0*#gRMQaaD?$VY#2l zL5kBVB?oI36YTC`;hQ>r z_puCqGH^Z9xIsiGYQ;7ZO-;3JhxqBitW2dN{@s@%i5t_~Un{6}o?BWzAX1Zx^vu)l z829Xv$bZ%9&+r&ghUKyVxw%X=^=S5ZA6_{~^#cc~@6Ie0y7l)(7;S9@?zszbmoiQ( z*aVfHm`o6lMNj$yKgxHSNo|sRSj{6ch`3+XIOf+Hy%^NIbL7Kyobd7k6Rx&-pU5_m zR8gDga`$AX+CXAVhBI$BQuYXAV!l7#ZQS&uAb(nOBz}w*eZ0b~^^0`w0`O))Q&v8A zU(9*g9F)}EZzbnt%-e&QeMd+$MM{d|d+9z4%v?Ob$k~PkE?|_9%$mfTKDfyEL1pqo zeXsY=tPT52F?Yc_t=%SVI-=fjb^3YZs$YY)z|qSsg#yROx4sDmr=7GDEW^F?F|)e; z^naBy765nkqAv=EMfIZ22bPB-h%r$7CHb>>I;IaFtInE#9yjCb2H#TBYD3B+A~rg$ z3)QrHE6GO}IX^pr9GwK@#O^`9-xc%WpANY*N}rmH3(a28c{ttC4#}@Lj%L>1IyD!J zee4nzn-8ZV zJs;2xvGXO`TgzCLe~^R5X@;FmhPCyv!nCHMWlLJ*(fYIg*YCo5(dF}R=_8i~h5MMl zE3*_XJ6^?%Ut zVp-zSj`ZE?<3hPdagQBKSzEe$SEsLLwmRUh8!y$Xa)Lf4R6nmGX%AW_?mwg5z&%sl zO?w+;xqw5e@0)tUZbiu?W_mhp!WPIU@9|h7SlGvZsFGbNg&MMcTC}`)AumBFYX2z; zs!zh^w>PM)ktG5L`aRvsX_Ao|QGe~JTxQVG=28-7wU`*f3exq8BgAe-s zmV!>ChK8T%r$Zhq$(HxCQsZM~E_t}h+!u^K5Jy@@Q3j%&=K3>)8U@Y-XFkP@IO zcC_Ss!&sNP!*L-|y|8v|i_cV?A|MqX|AOBXy)*jg5sNEq%{I;~NBdD5j(@Z_FK5|p z*#}#O^CJ5v5MO8@p2k!){*N!p@k*-WS~y!p;~_}{6b-9Cz7KCCxLbeftS9vSn3ayL(^jLE+GUr;G;VLE*bbP&tof|k2l=!W~NX7xCC*l<%vzXzL*I94! zQn0fQ$LOLXbKC#u_F^?lG zqlmrry6R-BFMmexD!kT%yTIe=4te7@cLl*qOtrUp#Jf2DFOTop2Y+WIxk;ZhbGU5i zHW#1fG3)8JZ5Qji0+Eq}MLb`(fp&cnrYg@{&5&%2L#dAo;zd!13FEj64N=l?^lxDcw{5A+wR?$eC0HnPeYp}8~~#|XxF** zpUfvL+j{pBBDEHMwtrZ&_;Uc*Ygu#br6!vh6~|DH1XvOSD%PWfLk!IV+iduG|d5o3o0ipukfx;|JY@*30HNq0hZwDuSo(!#! zeR-<#R@?AaztSjJ;!Q4lCYy2$%Yos@s;p7WaZ5WK>jI?3xr8Xr?0;H1GNL2IiK{`dz8Id9>&-0C3Jn8TGy~Ap;D7Rza77<^*u8&1zGc4iwe;aT zXh5cOT%UjB-m?jBGYXohBCoa2s(u-DqkBKI{ZxZKTu%yM5 zz9zg+zcT+69K$t7@63E;{(_>H&}+f9yrIVNCI68Wk>nO9&FM+8(Wl{9W~Xq4T@5na z9xSQ=AAg|$%r}Kc&e`E6HZ0j$9D)K{H_#9nV$Jd}bPt=g?}!_)%V+qfptfsL)~K_j zuR^ZL(V+=rCsMCDu{@(@Po4{nO>nXJvdrGNo(D8%ebkx@#2A+>q_z<`$QXVY{m@%Bjeo{oFfyoQk9-Pi6MF$`%2?VH z`+wH5HZ|yeyTy)QWiSyMgM)a)41TH~$#5j>`RLY*b#0@q{^EB%fy}kAu!tTHsh-5E zkW0zu^{?xXJcQoYP#)X~czAq`Zynp{`gfc5no>iX~CvTuGhAe~)-TH$z5tLxN z_(1`XaN$TYotpaNG_3z-Bu(!&=8^Ex2H|l|+~ScU)6~x(ao0kROe%vobgyfDKW(yc zY7c|yLE_u|)`JL%Lq&*`x3+*ita8D;RV1ec3x_KY77_2n;VMcz1g$W zn;n5w8RWf%L8EH#tb)V3R5pltvtktHv7l7Nq=@iUnUjQ z8TI^7&feO7t7WF>i2qX6>rSTU;@jci2Z?sZbSs7Tn2!aUx27py5#m%pVmZ`LnU$pQ zDDvHoyiUW=N0l98xB(b4soSSv$`a%5&dq$EBA$E>X^lS)+FA&Hu>ilSzO?PKRCLce_e9|S{?Q19&kP*x(un%BrnG-_CBIs zT&tw2I9cB%CEIh1X2$u`3)%t(k|R^}O4?vEajgkUktb&!tX`_`aeoEl^&aSY3@s)d zR=qOuH49aSS5)y;f=$zshVvHV3&8JhyI(l2j|^1^JuDrwK`pDCP!l9?rjDvQg zY^`2V%O zZ_QfI+}G}X?`z*oblQ4cGB$84up%6W_7B!2rvkFe=m~$%=yP1Amao^K&?SAfCdO@ z2X?y8Xbo}%=)tX_V5HZ7gon7U=;(fC2XcN2oOz=6dho2D1Sp0Qb28dMfGw zEoU(7FJtw;3^)OQUk!kloA;k^e|!H91cm)^23cFfot!~1FDMKGu!TB;0a}Xc+(=I( zCjbPq`E3YtbcNshe}mjXP)Cr}y}_TtK>$S=9RTRQzrVY4wMIalk*?gXP{-dL^85~S zf5{3k8#%a>6Bvec#ra*IJQM-8zQ1)Zo= z1Ae~&u>UnR0{^wH8eki!o74YlRgj?j9gu-R9RImQf2gY>)Dvu@4Mkep{Y90(2!Q~3 z;oOh-9ti?`c<80}S>ATjMOu!mXc$+Si7*UslUddT?!zN=z|r8@*=Z@>xK1xc$V( zOku0a3|>Wimq{7ye!R4)zvBj_-|&uVIh_YRkh;Ri<1QHxYd8eBw)wUM0`EzOv85;j`O1J5@qzkA9U+ za>W_Mz6dIwX3De5njxphKyp!Iu@jwm5=>uwpCZZ`yQ5W2o#F%%NUAX*te>nxJ9$!ZajuKz1sFB*QU)xd`{UWzDtM8J!xv=Ri;YeAEQO?ND{PFjh)&WKrngN;Qkj zCF+4BYQd?j`P&Iwd=_!O_lZ`CTS-)U6&T*6S!j|xEe@+YppK2f_u3Wo_NU!Je@RQ^ z$TdGxqD6)$X{OFQiQ5(g7LPEGPV zGv%PoJXOtTpZ`MetIlniTTm~ynoAR-c=3ZbFbeW|5b7yGTye#X4 z3KcV^bT?tn&gRG#tzQ(^`fD+tZ7-PzjLlABmuSIJET8;}rizK}&0p-_^|nfGy58)9 zQwJb@>)z;eoJ$SMJg?kNny9!QiZ;6WB^81b8&tf|$DF4cT^Xt4e{FWD2j(<&c*dth z%f+d3@Fy+5e!#P^41MGDY*E1NCCHi_%@a{U*SU|nrk0h>+kTq3`NmL4=&QF=VfGS|RJ=6-uT-2w zf6`fAn=t1Y2Y18G?few+Cvm=Q_XO0+os+0XH=nQeubPr#o)}dzv;M^UPA8 zbY2=H30A!;lQ=FAn?#%8Dy3YW_NJi~B1p_4M}sU8G3#tro2ZyJh#RF?N;NX}JDe|Vz##m&T|Q7Vf-UDsLX z=v(_+yUWTT%1`#swhye&&A_Zn4I^O`+m+bYD37g{DZ)T)SRC@hWg0gN=FgZHVQvt^ zwUXtxm#7l1IqX#hLN96q^7kKxRAp0PoY`KlzDaG*{opjXMyC71L)9I7OxO8)_31XN zfB08`gV>|If5yEM9d~=tFFI9r(OEDo7JFJv{%{u5G`(fl^>R&n#dsiQ#dB0A z4KRKq^GWR|8nKUU$-=7tYvIZ%+8@|gSnHCRY#&Nlf9D?#Vh;&jKAG`5PMVC8&F=@iqr4RK&+4(b`am#nve=-fSa2v-ff~`Zvqo?qklm?PGnhN6%aG$|g`YHxJIvcqtV~ zA15MHf728GFh2JEirOuaoke}M(e#qb&PewXt5NAbH2q=oQ-K_G*941|_gU}g%X#(( ztvEL)mPpGmHothMXCG|uyf+N)hP-ubxTN?jV$p)GRAO&G<|(JBU*7xHh`ycIohpkt zE!mJv+D}&Gl~HkVe(NAI7hTjA3j+Ct@ndBZf75jids&Uzi8|qtpQq_XKOMJ;9AsH0 z=jwAg?eGQaxwxqN7>zvZgpHl(7$;2(Tx~*NJW#6hIoOmt@qdMhqvY z&J_8OWVZTUNoEGkuOpnO!Lt%HU)DX;G(O2SN;>wqpddq>KJY*LporbSZ1AV3MaLR&35(~(|BZM>7ZB68OTzEBQYX@`;e=N$tta{OxrSav3tyOf%{Y;hhG zk_+5GMc_GBj=V zLAj!j1BFv_#{&N#jMtZ_J37p@wkG&9kXwInrGH%*`b4|q{98g~s>3eg_H8C~XeVPT z?Uror8S1+QOF46*5$J%;g+mt}7nhb-tT}%sMUG~$Ib5OX1HpBv&SUdMPvHyx;0`G> zzEGL*_6#vht4{?kmCqKke{USazx8yw_tP3iMnrEV+|-w><2^~<9r-F~M=~{qmdj}T zc=6y!Z!Jh^4kZNOs(0=GRGzr7k|%^gwP`60+feMINT9pTW`z|-*E*HmUKX7~6l%G=A1$PxDEnA? z2JJph@I0%=v4GS{F{ zusX3zn)Y5QiGHcCKK@|MZ6&OLz7U4uSMk1rMDH7`Lcz?4f2#kud;q?#RhTEXr4=lo zf&C=1I;9S~Nr~`)It?z%R+~c-i7)(wE=ezBf4XS&cGVJ&D}^a~RT))m=d-IA=O8Le zh@;M1`QxC%3(l%Tu9V0Kd^1;V#$Um(kHV>?S|sA@zkW;~`*rNNWv0JJs}>Gn?QQe? zvLUw$IeOKGe<9$fO#^;Jzzlb6CkG~d`oYqL*TfWHEctWPuuT(w7}P%>6MF9WaTy=W zK3n3M=hxWV-iq^#Pu=_k+iVyMbV_H)+O~OHRWph(R;-Ipd_GHTPy}zB2v4d_rg7hZ zF|Q0n+~8{N)v(>3!L8roC{## zf7ac9^fEDNC|h?&6UhpDDTzZsUxttS3FoO6!Ck8*kxW_)oY2#1@T&se`DA*A7OQIf za`SmDe{v90DJ8Vu4rFb`1wA`>=uxjHI@V~G&ML*w)Pa7$Fj9VU`9OH&b2zd5j2$N@ zL*~otOn9nq<=CC;akj6@o*{9=!X$PlEFmqX4@1 z!8X1_sFlMBmAh1=s=k6ZaP_$bM2~(&f4NiP{dDq(?J~`;`q##3kErxWk1a(rAEzzW z6}X~c#^5>MU0RFxeJYuklAj2gJ~ykn`kuaxz1>Ngeka?nBt=>)LSIiGP=cHke^t2D zBWD{Rn(UL^@)U!E*7w6~zhG6x$TO!|P>SEO;t5~eWoV|Vv$QfzS@2$W>Z7h#3W=h6 zIV(mtf9sW8dwlX@l|{}I)n8q+jcu~;tKklM!pf_Qy00`^z-9XD>b&&xs3{5=z>Ac= z(i4J!fnJaF+mSu53vW$&{^XFve>@J5@mCdkdTi6EQiJy%0!rO;5vi=B>+9Kd^Ht;* z0w^}(MjdF-dS`R=aKT?-JC|#GPcp6+58U$MswL3*$+;v3Vln)VxNNb67L@UgJrbWp zmxROSOBbg{N^bv#VX;$geS&}cnasrPG~3aougaEJW??{6I;AujPX5a~e;KB@bRf(g zj1|!+9?vgNX+}_nPZ=XYt#&e9X5z;t3*Bb$`eBWx%6#Ck?l!yc8gL7lH$q>2s$fd1 zOHJm1O7v`+t$^&OzM}DJ&}hg9pd05SGWAGI{j`;#_`~=g)ID^LLe8jTtd}o!Rhb2% zCX2U6BfRBVe~5sME?(}Xe<(C-0a7uJT3D@=HARp13y4%6jGo8wxeRI~WYb5gk~;sO zT&*K&hYlxntIv6g9`Le0vJds~G}o5Kx|sVqJ^6eYqQ_2kr2IVfhgCP2Il7b(t?|Fe0h#K+qO>twl`^8_5rATQ0V8L^wr4R!#%s*Y5Xvxiwnrs$C%{}K zFV=Aj;1R{&5zqM?e`>Ax7|)z6LgnK*2dHNB6>8gk29Zz z7${bcAFVc&&bJ9!BYRoTx`t@F>M(Si_WanK?6BL2>-UITJD`och_&U1up|^(woIMu zuK`hn^Yxuwb))YOJa}ID?6;j2B>q~fc@n9@|7=Vk9^LO99P^T)O;0or@_9R^O z+__gd_EfIEe+lm9^XQ10sNhzc*N=1-8%oZskLU0qpYFuL1l&IS2?mV@UIm_sgn^t~ z0`TV@(_83b2>90OPi_;b`ihM+h|-CJ+gvgI(yA5WNY&-5l*aVf*`zf^q6FFGK7QuR zAosYqY?w?Jkm#5eqSx?7#%G&-mQiIhQ%}ysKm^3Hf2+V!t8(PbcXjAgI*5wNNOcU8 zGOJJCL~qBM)czu}j^%CykO?pD3)w&S|`4u)v4l4RZ61Bc>oz2?0HT@nhJFi znv6QYJoX}yy*oG~6wbYu`r@bF@%s0t+Y4w3#wu=yUgXbRE2M}Y(G2ruQ+IWqjVFi| zD4|!{e^l+dJS;iaWK@Neq5p)byKec&x)^^lv!_UDu)Q^wT|^wjM<0b=e1pCxA377P zb=Hf;c=tiBt~S?23?~>>RMZn}jbWxc<>M_^gBsB)<)ziCH_N@lv8K;p`Ae0(KA63v zQVTIMC-#V!tF~PU^q5}pxm7zR-|IdtMGkSmecQZlFs$Ixa?@BjQVplhF)>A)wGA-T;=6=Ghy{Dnf-dqTpN ze=uqm7G1SR3^`A0)9GW3E2lN~64-|#46)uuYzj71gjZT?pY6iK^eFBVk+YUeg^Pcz&*3DWAWPn{cZIP^KRioT4gp+%8duX|_e{1$% z;yXO>w2sbtb7%N=`h#e>a<_{}HQ!*t7$N^@{^+-Fa{)6M=lLPrL3-&J90O$1%mf|L zi7$F5%(}9yj8^mL@-fdX9lfwh8Ty3CpmyDI5j)INW+?%r9~XvD4}^YQpX5 zL!HNH5^uL2Bz_^;7|t?kphP7VfAOJ7bdoceZ+h0GgS@5O%rdQvHd!qrBDDXQUhiv+ zsv|%!UU&X;3W0Bom81AFB75c{b3zV7bSbipVm(^nNh4)kDT6}e?veLu=m40 zm!tZ+A4$DsRp;wT zZ*sjbL~V9!j1Zk>Kuw8C6p1R=dD5Zf{BL@>hhMuVcb!(h&k@B3u3Qle#{O7t;`avP zzRlZf5DeSm-NQQo`Og&8yr&}Izuq8~OwT>a8Dh52h(P@~6z%R`e{_p2DJmX6T6fI0 z=&4BA+$2}_?TGs2%@zCLH*L33KX)MqQ`R!u(I(Y*o?iYfA{5HC>wAl}qu$>G78{9B zz9B+2t~k5n5-I{KbZ8Y-r^2t{CG%CBu`?{}RWB4u87VT*{mM8ogj=Egsb*dCm(8|G z(>mdznm9zCRex=Of8pjQmR@sisr7XY_WBeotF_DYk_^VcA}mElU)*@z2nH?eo?lVS z`B7*GT*l!I9TDbxfoq}y=-+uj;Z=i-Uv#_=31vchLgHRMWX3@X&rtG@=*l*rBCu+P z1`keyQ01MGdkG_p$pMxg3r3{dtB|GYYBbJzP{Th+8HG9iKN zUcb~=IG1}aa>E@pYnn4+CrMp(cUrj?2sTn8Nj@>NusWoyQ60EFe*mO1J=+)>06bCa zVe^%KX3m1bf6uGI(kqVD)Wp!zuGuuG7tIr8q;&h!%lMEWpi=1~S3bTfME0W}og&Ra zILUIsIN@eUv-`n%k_dThW*gT-_4F2{U4sL(9Xs*Ei@KBgr9|b^6j8 zKM~6>)67YWm2=pJHfglT@ZE0JhlD;_^|zT5e|$|KCH>)6^6Gek#UO2HS>wUO4D5pL z_MKQOc;@CrX z^DL)ut=h{*kr0-d&Z4mbZhTsALn@s+ocdZ!u3nfse~4MG&|eGIgf@yfSOJ>oe^ zf1B7zMQK_GiAf2hJ7J9Y!I_w+dJ3n#gPNSo`9`jIrIk+-UfXk^ zk(ClNZE(@c2GxeJmb#`c2;sDMk2ba%Tn4ValZ`QTM!4^&70}`GSO;mzb`&=@H0(S* z+1i@+cG7!h-rNLG2=uaB5c`^k3~Ck_e~vt)M`sMJT^P34U&Cmuna(-qN9FwFLcDg6 z`)2fR@r1r$k+N@bq-hw=5I359)I>SExCOc3^UlkA5J~9g8ssoioxw3rOcB(r+J^Wh zq!lk9lG7pk!%il7;JY#^g&TO)p<4O8u||tvBUe8VLD_#Zg}P~c-6-eUa|5s~f5|c0 zIiLSXGD&L2pFN1T_u8h7D&uQ?g!Q~=8ZU!*p)N_vAaj$8630q+ty6QQUzB1dyP=Gf z$HAQ_PBYVCOo1`pl)-I@#JkMzmKtsPx;a);$EK=$)$OGuKlqZ3y^-oGcAHp*xF*CQ z?Jjxn2!}k%MJudE^)d*N-!@}Se;&!Bu+qk~H5G%HnJqoVJNnWkEVg6o>UJv^k*g3r z;OmO8A2OZVMvPuNgOC>o2~dqY%PHjeX85|8uIcBXBaz0Kw@d;GG4qqLrxI?bPxW=> zW-wBh+Jh)i;Ib*0WZ^fMQLc<0h%>L@q0c;drR&(%^TfPxhgToCl-C&*e^FDV*q3a= zhzbeA>_Q{%cBjL_9BGt|D*-RUEM^T#9d`Qa#uGEY)5yz}CNM3bP2l*PV|sGuF%C`k z1Xn#L4>fwTcB_ulO=fIJx8BEA1<%b+m8Z0?)tsRF?rjC|WJL)16KW&VDeWE>i z=b|oP=tlfWw({8-p1tLPf0{zHlH*7lbE&y*OVD>eH5swv3fBYxyCB|%P*s_H%ET_C zxO%HlIx@Kt%ImwPM?TD(pv__uF-7jbWitB7RJxwBwk6gr2rc4;5YgpCBr}YndRAQ_im6l>oqR{9!lWK-s#4*-2{?M><^T#VrZgZ7 zIMpI^eP`E$)wzwrz*~l%5uyTJ=)N8G(7hI^#6F-)&<|>?_LrG^D}eO~h5RrZ=>vTw zcl{+l2KGF!a=?+%f1mgBHN8!|6DYAW@1^x@QRYh>(@$kW*pQa?wf&92Z}Y7|9&0us zJ!CCrw5*o!O1nuaPQ!A_orR`7(g04Gv3wJUviGFF_!Om*Ah>2DIWJUnMC85IJ-;jK zrM9AkJT+NW7on*hEKD$#seOuymO0@DaYyqW?el)3^S-rpfBG!7t>ZPFxOeEeA)76a z7@70H;vAtAL8+~wDNSrSVTs1ARAwMzy6ZYfSbf-6#Wvp02*Kd2eDz{?)@)ES%?JBa zdRDdTRT>74h#@PEe}s<-C0+CnS7C3u|<+KrA5lxFc|liRnWH&6@lQ54 zgE;p?G6u?DQ<3NcUyoa_OYyDqH*ArJVOm(J0At8rT07e2u@o0E7Et^jYpSs`sc~`iD8ydM~K(I=6{TsLt9%BgfabP;X00OMZ^!UXv5SZdHG=7Ir? z{}TN*Cm$#1>5c3EneKnM{Qt51ca;At(f>Cic{d2;4?W|b2LB(uxq~gl>o1EZ=DNY2 zwm=p7v_1?hzu-R!_&5I4 zK#nKN-#5pAlJgFPkhCU82$Wv9~%{v423CYX*0{p7bB^_h0?IeIbSm7le;m`*WFn`YblDkFgUsXE$K71 zyrJ)x-PT}AODL)JxIk*;7Vc@h1_id65uy=8qTby78-X64-H$s34;`+%hC+t`2SCvc z4s{9{?449j$07V%18Uk0*s#HCf1DUR7o#*cZ6%%Y2l%(PF}Kof(Inr!wv1xZhgVkz zvp)By@?7LA_g3*&hT)SCc)y~~8A%u*A&k#@)#wUGFU@x&Q<@w{LsIAvM!$w&Cb0H% zI{$NP`~Z(zy|tQ5&~tVF(FV6#DBqk|PS4r}x#@PM_ID1<7flI~HmudDf3(tcRhDo! z!)d2gJdoU8L?TK6a&5=*FV$&iamlTL3j9(-G>U%+kIBx&i#xM-8Sz})#>rw3!GW(I zr1^mmN~aMky`_86WB@)X9X?PAL5QdSO7U^2f`9bASa6eAvS1*m|MJAyGg*zJSe%-z z=NdiVkxb$&T+TSSQB9O{I}B~iiq#li!Fc0r8xG^{_oNM`g3biyf7WuPA9Vsu@k{() z=UTn{8FRgRRezeRFI5|12#HMUoC?@7{V+<=ZumKdJgsZusJERVdDm01{>KgC8NS7^ zg75%MXd$G$A(pR2X7w{+q>j;NbCtHMCRCT6QLBcl?-*Q0w<5gTK~5%n^=hY1Kg*n@ zWdV5D3=40Bc(y84e*@`-d=N1rbOU5DuLbci%_r)Ex#t|&;cToL(6=EH%1cD~heot- zo1$=Qe<(Pe-Sm>L;p7Fj z2CFtBM;P#~7hi@o;pQ8}&W`5m1Le+C9=NwmxtpI?HkU#bf0KRCxrjZdNC<`w7&_bB zNPJtNn0Gfn^wg**G&AIqE{cxRn`5WpuYS@eZKXk|2CIOliJH}-W zVcR$}w#A{!e`V@JQ!&&^&!az0fBL!m;#w2;(G)hVCz9SddY(4mCdv4+48}ZKj6eNc z=Y5us@7DFThMzglH~A6>LUPBYpeJGl8A`zvEJ0CEs-&lKQ>2!9Nq24H5mTmRm>@(K zTARA;-jZ{aAkkBsL?x1xRUHPu!^3rPG zCw#&LSJr0bN_0ElCp~>rI(g(^&hJOp=fxaXe{L%VnM<#=&1%zukJBF|jX{)xi8YR- z0?rH}BsDSQKV3T>;M*8S)mlwvkf{^6c?MByT`q0pBj=0TD6Q&Gm?Qea7=9ri88x<#u ze-pJEL_zIZGHN}SxXbzOj?3xVTd0-ku{GmuG;bzvOYx04 zkiW16`1wRkejbv{olaqSOP*ni_3WV(WIpEPIJCS~H~n?irwmiAG#KvGhR*eS+5TA$ z0Iqp{L#==)c>7z0?$Y+yKuD)~X@>FDf1boFD+c`Wg#|1Rl9*lP`jHB8y-{JibHKq+L8;e{JRRIixeWquiC;Fa9}rL{0O^BFq6 zsp@F-gBhD-Eea=|F7g8z!&TOJf6c^ADNL(mr~uniVzow}5D}j-#31BN->toxUcEur zvHXJQp0r> zPCUFw@5^1m&;7ogh2oaK?7Xxy-Uap6>pBeVq;8Nn7mr%Y43orPf5x9KbhTtW6Y@rC z{iYouvlhV72lH=ru9 zRXz9V9HUn$6C$f}s$q!06Li}EWOIaGwOzC`h)x)^uOoxmj<`7Pu%dGXf})w__+F-3 zhMyNeV^VyK0A)a$zh%nAX@4IPX)70f;t6_GvGb6A6+q8sUdHTdiP&H6@Bo={u>dQx_^BwYh?Yv{SqJJApF6G>O`||S9 zD7)2w@_bY>M^10zGKG&68&uAbjj@O3rFt6sbl#!UFJ66WUeGTf&F|rXDS2`Bb$nn) zoPHVEZBiiwB?wifaCK5+$jVrp%CUOvLk)r z>yBOVfwl}`<}Yh16n|FmU)~Y+3MJ5+C)kOwQ1}qGa)zTZO)NozcWFB)EsN>MB^p*f!1j6biP)ox3|?M;tcRvBBzdUbeuv2P-4Tk>F3bSCU7n!VD* z-9vp&u%;9K!#5Ky)=pA^tktaDV!n3e+*RvQ2rzutSsSD&d0qpx6@+D+s zL(L;^b90v`(_RW-}$|m+9Go)KmaZ z@umjhey230?thg(?U|5VehX2Yof!ICV+la{Ubc@1Qk5w-AJ1)}{E78+XDx5Gbo$1YTK&2FS6gjJ9%p>h(?8qFu9>{%>nu0Bil8cLPGrTcDP3@AsYV=ADsX413#Pz8M z9g@N4!;)hVA}qaMG*h}VihFn2f;0BSv++oxUUyk)ZkXmtCxGu(qD;jlMf z+|xG>`HHTO^%tbxc2G`|9#`Z2I#?`YNdjS21~!Q1`Fk-q9Jz|7>+A;!IZ>N-z!z(@ zEnROj6sct@)SYf1rHNy~_m_O>vNNv3bG+oy7k_`1=Pj`)dmJdHcK7C4yM-er#XBEo zVhaOCahgRz=DoKaLtpGmym;=Qn^AXgD}cbuNX4xl%vf2E&E`AffC5&7D+bJaoK4JbvJfxNMTtw-uATi_O!;lhgF1#XCSMlydPCKtulyuDUuf> zmw!KbvTstIs300u?-Mn4(jyTqHcALNoGzc$U%n^TPIT^&pA(eo&%)6$tNJOD z_mZaX7v_k_Sbo?@LmF~%YA31YBCvbNmB%H;>5KrqaixGIA1g52Zpyq)X>npgtbb&> zL4M3KrOLp~XR4WHZ2pm1SpQsAwFSMtHWbtOvpao5)$py%`ZpdmxCRwN*IEy4pqo!T zk!xGac=a7H=Pe6cc4cXv&fC-)`D>j!AWf_CSXdZKdE1mh2Uq}Kg0q}4`3BY2l8h`v zrB1}!9!01dkI_JhEiM{j_VM~e#D8p-aCb*)0##AC?&JFn14Rl8uEhGyR>c9ICXbK- zO%sF33=%9>^!K##B{M0CvWpkGq!LaSC|;AP%>=+TI(f0y;GTic(&5NAi#K@+$_qf7 zT7R`Vqb5Y9Vbg<%KpE6CZ6fcrDJ!&HG|}mlr0DygXJ))l-^y}abFUcM9)C7gY0dmJ z(U7r&QI-N;mjvQ&s&U&}<(pqZ-ChasWC!3J)Lpo59CTgrNH-1}6n}>a zzkK%k>UJS_h+HKI{xBpDm`E=GgJHwpxG8vxC|mO`T~5BE6lrv0qS>z%`LUvvoYLdo zK5}+{E#qG+(fKN*l_No(hF^!hnp1oi8UBi8MOkAyl#_&Jc)EO2?0+!m+;xBLIK&hB z%6MbGjC$1Lo?m^H-S2HqAnb4?fDiX9Uw3n)w3ej;x3ICIvg@8gAgWf!H8|trT>!Ee516n;i=K|zSXhyol&U%$*T%w+Y5p@sRx*ORmiID z-_{xJh+)McTk8PK^MCPt$MfS%<1yoY4fs*L7jM)T;z=VMu-KzN#8jT4X&QA9PozQB zMD1SgpguAL@AkEERpKvTb&2> z+`4N)>Mjjp36Se#k-!+@D~h0p2wmwn1H~sCt*_9OSLhKSa#ep z4n~Dv%hd(MgY5Nw*caxPw!@F;S22WqI-w{c%EBh>5!EUFG_STSr~fOsI zM=XHR?s_{y}Yx|h6qWT4Qj{ZlrTCRL0&pho`WmiyVBrnrzgqI_%EF3zeQAp8cCJq1=FoEohKvZO zRibQi;bRQ&2y2-ZpnL-MgzJxqFX;kM6cb*%i?$k6zP>NIA|ZYUMSa$cYgelW&vXt(_l*IBTrrJ~N6q(TF_`TY=`;Gwl^zk7s2@ z4uiI$(A2-5ADZC}qZT_Qr1>r+Yt7Jp)c8p`DWh_g ze}5U@MC6&~f%dhdh~kZW(^@7HJ*GcR=(b#<_?Ix>1`#tv?0yXQpLBOrOI6xN$Dlc6 zg!>uwIt$!swjID}v(?@!Y4g&lSqq*e2?^Bv!OYyi@ zpbc!QXSz>SkvDKZbH_mU{_#z_Y3;`d=i(}X#mk$_XGWRcUgHU~w1{A?ie>v*zEn$1 zsUtJS{x_07abiebdg7gD5!>QF;;VMOBzO9MHS28rK>gz{gBpPY5?hU zn9P1mdcicC&gRpo9@|{4KKFwgN3*1-4%>5Z?+}$LLZct`%0t?EB7U>&LF=J4CzEEr z43cSacH=G5T$85cHTzm_9;tieAb--yrNmwpqfruBvIk7x^`0j=4bnRt3DdgW>7%0v zI%eAAaMB#OTU+cZqj|wy?}nZx2TtI-W9eJ0b}cr%U?4>$sA(>~PW!rR5ux#k^y;iy z3xbzx*M9?uBO&!haVLSpSqt3sr(?%g_I|BKkQWuYd%tx{BzJ(qx&_wdo`1p>QzeGt zGZC-_y#fvBek~B5BGp;so@^2y;)<9bOr*i?)X-~rAEN$nJsHo-tnU4@g&ov%X$MLw zH=w^?Us+ff$B#Wa5IYpWOEP$oUUzdhcy_=l#pgJzv@Rc&%#kH=KN^+3foW{+%3i0& z@dIs_RTTvOne3rgo6kA*vVX~Vc(H8up2s80I4UcKJF&bge$Hy7u&2p z)X^ID8dCFxXQa}YIc0QYBXctQAERExvP8chCwbnq5JBRwhjus+L3~I}aYo*HW-h+g zEJ9{%+dbP;wvLs8q&fA-u&ar`)$C~q@x!sJ%OB<0=8;bf^6YHdY_l3glu_7HD`xHp z{U#&%7~J@^hz7qA41bK-e|znI%0;&70*V=o((73w=g~;%yVmf)U_`+lxcBC{VUyT? zj})Jd0iY^ay~^2j63c$%yqCb8){D7|QAKB%Su?D?QoRQ7Hk{!jC4&#_T44-DKBhdmLc}`!fH26dgiKD5 z{s%qzPX*-O%7HJc4JEWkj(R!qu>>I4M;D9xP}9*{lx^Iz;Z}*k{cWje7B$}cA;VCW z1_;qRetxbP(SOrJwD(BJ%GMOz+W^rz?<3lBH*V^_0h9D1?pmHPnv|6qDUTg7XWAi+ zAJ?e~!vJ1-N8g;~u}RkEY6mWwVu8-HTMwH)xFr3NXuSKgPB)`ARy4sLYKA5GcU>1? z^|%t!z(eS$Vuf9UK7C`#O61$)5MP`~K?Mv-ieh|>aDQ<|(+uy@4^aYdQdAw16=u2c z2_!$nYU>AdoR5dbjg%+^EE&|GXysFIaAiDnsK0IMr(4x!vgf4zE9c_2rs?A}Eo6la1 zC|wup*`BS_|L9Yn2XSt=3=wd#YBpF=<+l6|m2+pXsh3R6)|;r-rR^1sk@Ul16yw>ng#ox&bg{g1W_1>GjSo&0r>ak!5bS z^gn>aO}@;!`@^k=-JP9i2I5)a4utM47sPK)I2xbdx#khYl3BGR3*2m4<)R0!80sW8 zaDQ%Uo?VFb=FuOXSXXbQi}JV>?tm~dkTekj>Y;r>caRVd*g9j8xb+s5SkbRaGs|^6 zXVR^>;a_~`qbiImd^6HhL{{50rilj&7T%6?U#>^N%(}!EvFf}a>=<+TPr<(Bd8^Yl z8rm-mMr9en3KPLKt#+?Uy7l58<<4vylYc(=Gns+eg&20LysZvR36Q7&qr58QC|f8& zknM{Vv;1UNMtJqTPrYx^g^k#By0&Om=q$x~_HmbRr+DWeZr|dct*0=oQLzh=7oyRb z9lQJdtVUC$o375uXEGVmqS=vBImSptq@0gZ*(K7f3jwz(Sza*+?0r4%CpDWvIe)iY zKwC)YB~m;H>8$70(`{lk+Zv=}e(xn3rOo{~1V4a6U(LyHsYf~0E%M2O+- zv)+ce-FYAA2lSV^D~%b#yb;vKN1a)vY=(Erd96#i&2#9H1L#=@M5^we)(5&G3?)BC z734q!;H|GQ`-f0%*(FlE6C4w1o_`md`Kj00zBshk_m}aWFOU|vbZq0qHu_1=gWZom zsPlQy<`-To0nn5AJ@D#=(M4wHg;Y-)p%rjoz08|QLyXJ5p7;#~P$&CBV*#Z3(XB%K z%GiO?!xGjqy`|rvf$^rwsilN3%QTJtGW7rhnx_O>zOJx&QkmLb`iu$w|30LznarLBbirkqj~NvZ=E} zK=|s3)u+l9bp~Q?>1?cZ{M*zZWmHDq#Ru%KV8k?>m6Ht|L)#>k>}-5UErrZc+&1{6 zXPMQB&3Ms`nADl2J_BdOQV-tG>z&=>YNizM=aDSic0y}PmFJAbG=EnAeE53POgVEp zFqHzZ+a*dx}6pt7IFkeS$iPY zWq&894qJa#ilpGO9Z>X&NqCAuH`v5%?W<3W?{x!|XJudWa zR;1@y35h0Wv(KT4&Jj`~MsE3wXH%|Q(UcPD^@_hBy!$`;#J=MU)5{V#Nq!Fg>5DU{ zMnjWLwhlA@}`_ymr&i4KZF!<8iBFYx$8nHpgO(S&mK|oq;(121AQewA5=Ph zjuF55aNFnj@)Vc?GoSIbrmEgOwqRwlu_x*@p(&;$ce!S2CKK>Cj?1PQoD3r$ts
    3V)RyG&H9*&=+dc33%IAV!;W^ z4Wmvu^44n5wJZuv3Kg25gh7($4M0Y2&h2QBrb0y^AvINI+RN9BVFY`rY_ETsbzgbd zL15oVoFm6AR>cHU0xHR#F2U}|<^Zw4t#qE!Qc(nm`pDe+7> zcn$)rB7f}+py$)LxY%?ZC@ponL$Nwn)IGRuZXy;Ruq44Gc6 zga`!o?RrQJU=#}s9CBH+TxQ9eNbt7_uzztQE+q)OPx-!iubpoEIDyCC;1n?-1M^s41?{td=lx`v7f4(3}qnS?&DvT9pBtZ zX(g#Q*6h)9&iez$33|fmzDaD~F|v5IN#t=xX(ov*;MK{dW4E{LD^AR3%8m;het-Sw zMB6h)kc{KOx0KD6LxU>NE;FUs`HosH>Op-!Q{#=?=RMdgxj3IzH!$`ZGr5uC4P5_G z$Hz8vEBTGrxN`nTsar4waHj?lQ%Xwx7qD&Nwfy+UcD#veFHoVsJ4}&RH1U z4?n}iE+4dv=xpfWoySgAinkJnSAX}|h$SYGSd17OsQcSXjsAwh(qbWK8;mUd=sdYo zi4f;u|JfjGUfW5wM6uwW4t2M@jkV{i&m>>r0+E~@|y6gZZNswSKWX6UI z)76m2_1k<7L-c-`NRCc0$Sly8KMW;cs=E7*s;g9jSe0lYfX>Oh$`& zB|&q3I^zT^d<&xksWU1F1Vx^L{ictA+r|3>U$b6p_RTA&cZALF=(u-x$I|5!p1&zo z#_~(T{hqfXS(b_-Ov}@XF@OA^Ssi|#7-P`r+j!9{yXuwS9(+c(62@q}mpNG-uJKG( z=6%Eh?eQ;0cz3~8D+{qncz+R<7sQ)U1qj522>#(%qOi{_5Q5Js~K zFBbEf^Mf=!kLqSkR&Bt;E6ph;h1P+GXqj6s<FtvVwcA z`~5c=y_b}xsx^>!-hYz=M-kQ+^=>wf_u>0 zBLZ?9WrNeBxQmM=B%J5FlmLx*r<^$W>jyy{#ON4trEBm++TMjkRZ$LglY8(hx0#h8VJAdrmHlcExT{LqX%S|4<#M4cog_47Ato}bcL<4rh<>zHb$*OghM5i&H zeVkNo@VNH6Pv4rr>UMea{_B-5aG!2RNC!c0lH#lTI~+3sOq`Ok^WPUQbFdvpsziI>$xw6aDa7?i*ryV1}$H93pEH5v4-au-#Z!oX|y< z(ChC!Z}F9#rX3chr#Hu;?zQeZd_N{i7Z>N4#tPPX-|MW5_Mx5$5cuD?dvdSS8Ciac z$nrdgZ+~+JKFjGSwos*lf2%~!$U$`OlU}acvgewwE}oT>Q{=Si@y)zJmAJ3I-^+O@ zXL>iW?0J&Vw=_TS`}|=Q=*#@ z=@Xu#oJ2vy>kOpdgGM5TZKefL&orRjj4R7`)*HBk}k%fH9w+o5bRqmbgg?PIkO42y)CPoR7 zOs&M?r&lb;W=RKE((dMmsxaXNFIQuCzErp2)j=kN)a;mtDpEUAv)u57Oy*LY=^9-O z=M0j2a+w#H{vVBLjhvUEB?lCjg3|#Kx4IMtxf}yHH!_z2@&gr@z7z%y0x>n0Vd4T5 z12-`^m!UibDt~kbR8!s7Exn_3q#6{EA|wFLV!>b2%-1hks`f`R27gW zMSAZYQF`wkMFbW8Snj?5ci$W1y^%3a&Yo+owb$Bv&cnr_r7Iv~iL!tzqL3H?upmeR zAg8WtBnAM1gatt$Au=v5Jp{%c{ud_W(ubp+5h$d@|9>LLq2W*r7L$i!usn4X5}@j0 z4*&}Tz@idhF$oX|AOr&4`xg;~mH@~@T@jW5bwPkC3JG^63HW=(S|9S=R zz<2@Rd-ufd{!RzTIKa^e7!(Omhhl8t4%i)GP87@dmI2wT69H6VB2GDebBma=q{t)g0{+U z`n#|~AT6za4Poix2z-o0IJv-8WM0ltS2zHJc7gkN{qMj(S7cx?z!Cw&04(6v z2qf8ms$*fe)t@!?^3e!)fC&hzJum?D>-X=sCs=t|qLB6;|DpfBU!bOr)?-a|{y!7{ zJ0>fOatC+`fFS^Zdk`=HEQEcCi3 zfak9{cme;crGdh#77pO~kH}3y5D*Oe0RMkW{dda$P2s<){J%v0-wi3c*xUaO^Zbtg zA7Q8i!rtRA0V`S;4AubZD69>T|4lW3|1qsP+!Ep9@ZV7t3>0ew8KgB<%mQE$L4T0Q z9~|MVh;WBnY9TN%n?I8IgFpUdHG2dSu7z?&{Q9%eD;$F1{`kVnMvXXKY1~Qnsb%Sn zffTJzuR_PByjl1Tz74yZwq*t^BrE4&a1^>$Wsd}M`_4bNS;N^aQOwpOVt*+StJH__ z+HBXKnh==WNi>-H5hB(uyjix9|FhY7)A-&lzyVPBm5L*o1rsBa-MotzWyHa`jOjNr zrHZ9No20tvsXQL}i5G>4J(F#WW;*v+HHl5@pP%o|?CwetK6&}5h>Jn7}#&;k;_>yjB+|szNVph5xKP4mKNvOAcYuya(`313?e^fJfl0S zR!QNlEjka6&i`QZdBaqW=@|{p4Y^zP$A%jp)0K{QH*o`|WZePO&xu)g4KfJd-oa7W zG+9!>UACBU%w9CMs8JZDZt=?^JRC4X&55j4Zx8pspomr~*Ife5 znO>R!=RS{~D6%lWRDa9#MFELJ?+dZO-b;sz32yAmS~TlK<5hSqtiSeGz^x?LrRx-| zzQ;)5N7FwKj3IWbJ7Eb|8k1zcU9+7HG?_>f`P5Kk>)GV#v^2(kmqCRnsi0;ca3+tz zbLXx5@+B#*MXJDe4drJvjEM~WhcwWl2h?(W1yNMyQH3E zTsdKv?xa;UAx`)bTjR)AfV~HY{R2x@W z^b1a}^D6gMeLHo6Cb6VGXvJ^8|B>`&Y+Rvj9bV3{Nm4B?xjvH?R^si}snK@49ijHI@co%*5m(P6)unJ=6o%8gpC zc_acy`X)R~TTro{1&9?qS#2_AwxU7E+}(N;7HU?k_J6^9!JJe~7Pi+E0M1?PyyI{l zdt)-N>jP;Sn*mvF6$;>Q@kp!X)vQ%NyNu>s{8Jfs76Kv9i2-|xwmH!kbHVOD8gmsr z*}F4?$uL)wO|#JB5W$mMc;}Ze0#{fa=fdr@tBk3``{__>PT`BD(<1K}8j%$DrPIYG zimL&f*MDS1!PKvK3S&~ALm$HSbp~gVqK-D7(v6v{JUveyL_X?gA*Y*Wy5I~qIdg{ zMR2dNlzvKbQsK(b>s7H@1wTo+m$%7#Fudae(0{w)uQ{f@vQYTW^mTYBQDRSbmhIDZ-OO*|Yuly#rxf{Rh5l zVkAzFfSs>n?vo!8WK;9R3($p%3rpaNN=gEQJJZ^YZf2kVY?7#CB&gbzN1iHTByJP- zhkth6tIy(Y&0&@uljw7!Ak)jMk2HwgXYM9^bxy1R5mQ^TT}ihXe_`gmig;i(w$1gN zqZB-`_HEJV&XIgR!_9c62a_w;Y9R0A`%&Gap~T;>oO$epwIlu3h}~-qt;CQsOG<$w zH-{YQhS0%a@T@*nrTBEDL)K!e;DU*dBUK@xDf;z0s>$n4cY|Udmwy^} z1kamfsD5bDe#Ar?oz16~BK~$Iq-r9M=^-elJh_+t`{m56HL-VZxnjjrz2$Yg!z9{g z$wH}F;~5PfW4gnRN^eKr9AwYx+jh6;dKzRD@R0OPUp5lul|4DZ(7gsdbNz0Jh^q*( z?_8V-IKCWfCJk7k?Stsr5D= z+Z2b;<-Eun9No0_TP3vay6Pu|N&}WGd0ztC_`^RoUVC0=$t)NHLT9M!-;kZL(e@l| z#=9?ey0MRAILx$%|IR`wqQ@UDg1T@&J#yiEvOo}hrxZT*I2c0V`X&cK@faB*lpb!{ zL0{e?C3<8SG|0Fdr?}7MH-BS!b1S2&M3H0U;o>1Pv5!x2q>}=}^&ys|5)X^~P^iHY z2jarhx%tu8Zdu@4UMn zIg#;$g|P?MathP^grGb*#E1GqGmRP~5NY`@YTqmw2VBxM#6k!pe7Sm_d5c_1k>~(F zEE+EGa^h~Od`MXlAV)D8C)oLBaVb#7OMD-ap`v++SGYF9#lgLoGxjz)BuUsxJZH-O zV%sw4hq_LN!1i6xD}TjvBpw@mCe9tBuS#xXyDkSEMCN=kR~BpRRfdFRZlzK(Mo!W{ zP4CO*O?M4aRmV~Cjc7S0!(i3iwJNPp^j+*Zk(cE_OjQRX)f zzf9fOkVS<`DKy@6)V~Rt?8c_X-(a{h7~+LP(@RjXS|7KMkTk2>8i~ z2kr)CtSb@XveSPt+clm{zPnakZa=e(x#ifw$VBJF5eYMkr%M6(c z92`ETiDe}6>!ZKnLM$|sShsTIH< zhUiL5hSvm| zb0g;Ddg*LbCL|#I!NAlOv#L=FQYIh&0m(CdhzB=ub@VcUvMBgHClRaX%cu*Wr-WU- zz}FiUlz$AO(pClll{Fz54V`0Ka5{ zPk-lwRa@^ulKU%}nw~dVTdU2U+jMoWv__>B#19F7YTy)26^~T(wSHhuFaGty>&vN& z%_n!Ragq2HZ~qozcG>xjurEZ*GKes>vsaY(eI?=w4$ z65XuZWH{}Kkmeg<(i5hFEvp*|hD`6?sehj?E`BG9SJ2GIE%B$0Ev_ODTZq=0B}{x1 z7^RGBasLj4?ZeUO+xHW+`;!!qb{X}{+Z~IecyC8_admClms9g96G{NCQ4LN4^2iZZ z)4GxuY!t%wR21A8cktdpi5=uf0haS<=WlkkLg!2nW z_n1Y92*=rY?3xK>KVL+e)uMF9zklv844MFaD_G_HgytzKPqy&)x$H>QYl4=%Vrv|O zKH=P84KDfMw+VR&cdLzNeQ?g!c$P7(>0MWOe=VRnxwR*B$wP5=ZwGwzn({~k_>twr zrqIwfaM#|(Esq6$Oo1GhB z)JuYRx;^cQR_ySyRZ=iBP>y;n7QmBl?GvXyK0V2xFHrfG@7uYh6Wwry$xdX4*$8F$ z$8f5(MjYU@2P0!=Jmu^iy@U!xxuj7s5@Z(}7t@cGAkEBm}A0 z&bZYNk$9NNmf(nw$bX<>vB;R_s2_r7*9+NsaTq+!GeT~BZ<8)=s*?EOk)TG6*nz9O zW1d&Ma(C1|O}blyP}e9v-n@jpNT)j)V6ir+TBUuIAjy77b=>swYUgohsV16jYh55x z;M?I#3|Tg;o9kJC0lv-yF)eMHpvHBPpK0%O2%|{V&qV|Cn}4R+Cp~dOZUj|Lni23k zXj^%w!K8|ybqhWG@iulG_)d4@baBm!FpK2mBUN!3*&em;M*QiW96Il%+9VCgE!sn0 zie7*a6Me$F6Xk$VdcNuN+|}515+H>y@XDfFsvTI!Yzvn5r6ZEJ9^)B^xG^wjR`3*l z|?r}+&xkC_R`VnkhUYRf0-wf zV0-&T)YDVBi=4}LbvrBVdrVaI7Cvg+()odeKGBB(?tejMxQ$f-7Uj^`zEAjLX`nrQ zO=XFwTC-?d)!ep7iWV`uF}L{SQ2oGNI(ez7^P-!SxM%Gu1FyZihJ!n)YWqG0%XWI7 zABVmF-i2H6oGOvB<4fV&6!?zn+-5yLW7aN{SWKXOoN=!D_~(L|Dlr+6HoZixOvm!f zZ1v$+kAHPq%ac2a{jK)GiD&s6lH!}A!RtvaJ$wyr!*2oyJgyD7eYCnwP*gb_%DYVA zqlZi_%jQ%wTz~^Ozhv^DMqlz->jqG1$xR`if0}WinSZ19C!J~G;oVo}wU*jy^IH5i_AaOX z$pZynJ-?a~p3}?YX~S@uJJpd-^)6agmitqR^KNyJ_R2hDf{Od=a_Vj_3#>lQZ|vYA z+l@eQthHX`X$9$fq!`oDQEwAEPthj0Q0pwWM*93bJfG&FWy8e1XWA)zkQ|OM- z!fdN4paCg4C&bmSP*iGO&1y<&*}E)CisbWqH2b|XFU+*ZZcVU!|CDl>%|73-N*A{3 zjlO(l@`P$A_29cUcUVaj#|-pkuVERcG=KB7>DUCF{)km4px#`hX1YsfoZKrfk>lnl zmoUvdgCJv&&m!4J0oi{3;K7cCw5!$U-@6erKLgnPI($C_)k~_2z4M-sOY-=*UX7)La3U0j(;5f zw`ASsPSM=d9krTN))_-xZDZS7Vb!FUtSlrHIqb6fC7EsamTVIku3aShBgB|r?L*kb z{pm8$vTL15#1A#u3k;op6&h5p>eNF`6)y zeec_tR7Bt-f+n&>;DPYN8kte=Dm*3r1wGlQ?JS**qmMz9!kSaZGOMz6_U&U{8_xE( zXoru%XJUZWVY~iuX7hOX+L!>%Rh)LHMv0~jIrNE?GSbUwLY5+g3%oJ1y*R+$8$)41nIU&8;6w-E?t%Ep4x6;8wt@rQwvduCx&2BJ_py z^7+A)oNNVqYYd-xpIGc&|)X@Y!h!fyU*3>k@-qi>$#-B zQt7N+omb$7f8Kq6f!$90!dF%^IY+SuIgAdSr@h64)zwTQqex9YZe412YLfVPFJ7s+ zvNe;Grstfb?Q+_Kl6CmkoxoNvf`eMGOhCrBK-Jcw34eKxcZHW82N-}7qVIDbysbFN zr3kLL&{-znM zELIy|j|{i#%*UpBTs2WNl@S6SiqE=7PEOtG=?9EqUhkG&i`3seBne#nsoHk&cy_d$ z)LnxtqrL6*aPB^8REFQTy>KJ1c;LzCRiItn-G8U{C{_m=7mbj*-3)@}Aj#plH8 zQUL-5}6P-lL3@5!ZcWmBOf&xuH}^ zOH$Z&U!C${04loH<@*p5+g&l-*iFRv(Jo-f&wMatv(_VWN`o_&&>fKgCz{h>2@S8# zE=BS@dS+QdeL&P-dcDN`$gAL!Z=BF7WnGEE&2UyE!R|zF%6`fbIghd(9FfCWqOESHJ4%H0u%!_IWm`_JOwI$R0mX3+qR_&1dt}Z1p!4bCG;v?kPgy2Aqfx&Nk~F3 zf(X*9bfx!Rq^LA0A|PEwMd`grkuJ!O<-Pmw`+to8N5(igd#<_GUTg0;4?mBgv5*QB zda1_H_ci-^L=0oB1?a41ku7^sax!mt2-H5A$x z19x`8;kWtMD^LJ(11KshD=qjd9jM|C!@wb6Bv22GbAh?zcZ7fuKw}gH4#WBWqlAEh z3l4{t6A|(D_7(=aV}((F7-z*BfzFwz%}bOt)X5ip>EhORKq2PX&wBcVTuU<4L_h0h0jf#C?SBcAZ9 zb1+at#Rv$-5BO(1ECd5b@ zzi-wJiSkDJ|5-S}kx-|fLqI*zBBn^VhbK%+{SO5X0sh9EVK|^9NLETp5(I>K0AW55 z7m=UkO?=U?UqR7-pD=!cKz}p}4Rpc}0SkmX!SH_oe=OJw2E<`JVS)btJ@C&JKvWb6 zg+p*aN0>7l3HZA@9)>ynUgIwx1NQ-1gYeoD1%iJ5{{3c)mlqU;MEL$q|8>728oI`M z`Wk=zp7`G}RaKM^&|gSQ7APbuDFYN0m5>5TOG^U-|5?U=5Dfp*2I%ixEu<3)DEqrx z{4xEjW3N8~5cp$`8^C|o(nsM{3j+%LEpi)>BnX0ki2lE&{ww8wQ~1v+|Ch-Bvmp&n z1mag%;8*;Agu(7`gzp~$UbLP#yaDu3cpD)9lWGq8ZCX7T6z=K%pHVFw7;gj>q%&U3 zLZTAFAc^09I2@}1_klqT;W&uPZ^`_|O@CSq0Y}0NQCRrTZwo#P1p1E{-d_+m{PzQk z*X6Ge3~!%*?t2>vK|z1|OiWS=2*zN*z5ozjPGXXhKz~uZA)zpzUrGjw2qRHAdt9}m!F*s4z{mF}i2MWB`UkDY zwJPl1LQ6xJX6D)>6D)fpByra!bNyX($uc#^Jyac_RV;&Ph9Anp$KD69-~4(!>|^ut zamaM)og5s&?cN2|9ihDblW#AbVO&rYoAZctTI2%VcA^m{je|9b_4Q=)_h(_!UE(X% z%Z2BE?bsD7*$tpOu=tRcCzTx+tCHQmK@@Gt!#9T;u(Y9#qsLgMdzxsOj+_%k!{d%r zTVq&Hd>5?aG6ueUdHwiRZ<_dCzD{?IR8=?w>lHt3p6tP-K32xW$J)(Uf@`XhhiYXh z30GN*+{3R;6FW#xf1k*I^&+uP+_TYHUoC`x(je$flV<}WDoaW@5T%^UBEa2D+%?f~ zUGq_Ss#jRg9%HlVMuLV=%|*Z3?0`+M9OjH>G08lgm4A1TFGDvc_J&|VtU>UHt{~ya zgIOn%@xz??h8Yp?ah11RtMkF!$sD=9#7=!uTW)dXrbJDkl?(z?aZh?7z|Wtv@o zKa_m?`dz5|%I63cjkpcf#pXnT-Su=fKYv+=lyX%9z|~9oq(Zf#)J*Xswx%-!!xK%u z6LxfjHPKzYbc{0}n{`JPl}*bB59?oW8@y4W-TNvb?w+0!@Yk0YeU38xqOMPTxugQ_ zaSSzw64uu4Rcg+Z(cMtOrX(bqF1m$%Q*@@m5^c~r zU++t=s$Sn({Z{?$s@;1FOjuy%RgDyFD9`WZ*c`MND=0Zs$r0{cxO3`UQ9Tmua@Oj` z5m~$ZY5`X`By)64b+*}G9ZM*-w;v&d233{x9yPWTo~PCogtonMcX413;VkJ(1yEYE z`F1SiCGGr@XpBS6cmgT7^Pj%lh(a9U%mJB>3($)>M^A~KRewAln_EcJ+oHu8G~uC} z1v@e<3aGy;=Xk|J1SYpGY(C>H*DR8^4*PVYF4r74Z`)z_HmdV-f6ly${+rb}g2C&e z6ftVi`0{7@lzBNSxBBaVn#jX;4>;+JW4rHXZeuqkuOBr`>rFq4kKI z=l&=fr-KN)Fvc|CijDh}JY?8Npyu&kr50+Ql0b&1ZCIjFB2(3ODh$DIV=TJiV+bmOR~pqEDt`Pn(|9m?okw)7nD~6z9ataXyQfGEWu`R7)WqLmQFc_Ea*Y z?{S+@z~v7zb@~WqgZ^m~0&wSYw^%b1sSfD~DN@5{;UF-u)^JK&YfraJxJtelzS*~k z?8Vy~R*3m+(Df%4{;;NCnu;hI9{qP@8h!J^wphYdYD$Co2!%D0+emFAz_=7&fO51G zO!J5a&!B;Y=c?PjWs29#)QKj~YV4O18tTVjBaZ&5&>Wriw5Z|&IUseR?C5FSn-1f; zZZ0C9t@Ul7tNF+aG`Y3(8AfeYJsgySwv!|T+P1vhHk^rNosl`3gOcrTj;kdH z`oiWu1w$VCzbt%<(!;icjLj#psS{&Fa;nj|EkZKO^?F&Hq@cM{QFNVIFSSQllC%#} z88hon9M%9}yp15-37`rUM(xe#kNrn!wm@qk(K^T3@p2LP;?YZdkp<1y%>EzxkufcW zNW6;NB5VK|e5$cAPN2^-{!mMoz@RU+pz+DSgb^n_2|JhBKC+Cg0t-I+5TWKBoll8L zTRC~F@oEOxlUk@}-u zE1k>w28F1zgtyTepetegK98AYuGDjzx<^xwEO>O=p*9v^UAv}fy!Kbs{D2{IoW{_+ z=*9eOi)~uC$NEeG`1p+nf(Gi%j5LImbCIHm^;S0qr!*-6k4{Fqe0?T|78eNCmXr0Z zM;^Dh-{yy>8Gzlm6IG#tvdiC96gu{Qvc1R^_2XT$hy6RA%-%rCEKg=;tcE5zy`P#i zH4LED?XYI9ARV>RDx@{PYZSH;`RwtG=?r{8fA}8kMuH!W6V5 zb@Is>jVW1h{8Yz4B=7o0Bp;StLp|Kz1e;hxs}{>?3Kjg*PsI{w-3>f-$Id& ze&t<(K?|tZkh1oe_+)vpYio8c$->J+bgLnBa2+6rxp8D{9~$|B5U=x#Ep5Y_+W6$)Ti1awka3KtGGU&-js5T937^# zk|_rkV}M(#Gt9Nf-kUf7P+^hfH%*v0+fOLwJV<~rD>Q7^6`7RyQ`v$?4V`{;?CljG zXnl3T$&GwKtVnl?9l1xxS?(Cuv1>YvBZDRVCRnP@W#v!;V>{|E{d)^6tQU`9 zO=zE*MW$qth)Tzq58Q?(YXTHfs!wBh=dBtS9cOy^B9#@G_ztm+@K>Q-PzQuO5OdkM z4IePk-oPHD8Kkh`@h4&bEL`lajG$PJr<#2w$nvs$7dp3QE_Qe7s2)Q~iBm|WxZBmq z&HlKzYiIVXz2ir5v7+NYO692!r|IZuF1t|G?OFH4_~LzF?xfEJO-m^Z4Oq+$&e>h9)t-q_!#l63;%ZngZZ_k3jsATjcb^BXapF%Mik@bx`6a{43YE zFtLx0bJB%l*tScJ4F0B@%+y^bccptsH1Dk1BR9vZpgyzfs9-I5FobFfOTRmHwA^@)LGQ71*a&*W;N0v2vi8P>OZ z#wgY*&X~ghk*nt=Od>wh@5b6V#N~FfVTfThES6D6@hVIem5)Zt;aPz0Esyt?x>dK1Rvw5h?Lmim!t?>nGC8_fw0O@R~zHW0kFA zYxa%H>cj}&me%oOs%bF6qRu8HS6#^H5=!re@*DfzaVQxB^DkIB&UF~`Bj$i%q>-Se zF%c)Vy|R~Colds>ZwF(=b9$%CZF9VX2XnL4xVRCgdPK!iv=Qsj?W}L<$q0lk0XA)(GD>m#mek#PnglB&BX-1DZX6 zzD(O3Bu-cl*~KJ5b2#UErp5mUSp+XtVj}YCO5C^fK4Y$5nwZP4IX@%ITXI{ttkP4v0zT_$`MW-q#-) z*+B@QD*UaQb94~s#TUt{0Qn%qQb7`bGtu;6+Seh2wpQcRY!K}9>5pHi$9-n!Sdanv z?aPQhV&3&OgnzJ3keUb>RqJ_rByX8QrnxC;TodCjFZ(8uKbl32)0=-xg~@p+vN`>s z?T4OyWKTF4Iso)D?z^{)M4x$OY8OAE)=E>&yM$2lC{I!==s}LGK3d}JO&V6)&o)C0 zJb9MqRdaKhjasR7UB?W)zq}USo*`9BTQyGDS);k8Jb`=O9@0oiN}^OC3~Xn>ee=A? zi|mexnSX%u-vU(>wz3f|yR2U(n8r`c{f0C?MkL#3c>%H|&^Ll&jbn`TiiH@tB4o9< zRONPggjSGWMYuK0`EPiuzu6oOcD2+hN|Ib`3;u*F8;|!YtVE$Ywy@-P^Za9lZO}h? zHV=~w{3V9+VOAPcM=|Nr782Uu7L((E1H;3U2n=d&l;Sr&I>Hd-O4}_Z>2^@nAp_AO zCNCv>egf=I@vgrOres=RIasYh{o`K3YLPf6b_*iub1pF@v@aq5p?j7lVXoZy^p4mk zpJFaPeeAeZF$9c_f1CgcoPZVFMZ7ikdHTFYL?AL)?dRG&1)k|HimSCQBz(IDE;uq? zPTdeYd!|<+G>eZL6Zucpj583Ef0Yy0rX**g;{X~DpDRh{D9y8(4(M{@vK3<7144Ju zL{tHHTGXs$6`pEtlSHpszE0{km#(`OE?ZAPdx*lM?9UbQ_@+`=BBR}{%p$lE33~ML zR7GprsNG1U6d=~_;BDq%pUF+y!EM2MHtf{S%?kM&-!77!gH0VCV6JQFG8hoDTUo&99aRDEGzG=WP{IM{tG*q8} z_hc?>p`pF!@dRAD|5tK&VGfPiK22@jkswn8f5M^fb#B@XSXef1r~YCs6}t|{Y8r20 zKd6u*2L=&`jHM&MTW!^GT6e4SV(Onei)o{n@NkM;~mVIp3Lf_!6c2QeU#T_TW2C z7kdqCOZ|JqC~+dsP5IpY9CK)i36P=wTh2(XYn61HdjSwvJiQy9@0k2ohh;kd;cFS} zKdxCH(e(X{Kk`?jyvB3_oSjS#xgZGMFUrKM&s_he5Vw$wVca(ldqr?o?6ea3?XoD? zwklU=S_b?}3{`6!*yKt9Lcst-_k{#AAPQtYtm4s2;xvTHFVTCQlZT6mp8%c3?6h;4 z&i2_LzQ8M+HZdk2iYryIai}*d3cJ!hLY7ff>9n+pY+J8iVzum^m(L6#GE(7Xsmg9t z>7z4x`Ehp2GoCp>`bP?Ds&paeMRSIY%n$}UC3g4opwt+je}v_c$L9Cgu3HDPms)?f|98sZFYGTcCcPKPQ2e&a{fl`ne=7RtT>UvSC72hjk*tnBQ%}Y zFZmpPSj!c+_SNdwN0`q-?cHmHx^ZwP;2+%t7*Xsxr_`7qGgmb2O1BjBRCWQje6R|~+m$n^?*{v{W>o;4fDCM?d1)OWo==?dFO!CO z({YMYahmL8GOi|?%3aAaM>)k-yLXTOp)GB5p&PGJ{u;VE=)NWc$8WKeGFEdpu9isK5554qBGZ=5H+6^`l-6!$-7ZZIm} zPa5GFE2&Gl(|5q^kG9n~g>ph}>o|M7P9>UE@I)OQYPf#95)XYU2?4WkSj1mH_k`P) zPc21LxXX`mKv^T;AvMWU#epkenQ_10J?B)a>*pHVrp(7WkO6*NHUQ%>gRC}S-qVz- z`T=T$EMn=ZvXYFD2FKNOIiETQyV~KjnVS8A(D_t1#Gt3v&4U)V87H0)!^$G7asK_^ zJlWx(Hl#(NGT zi~hYI&8~R#zarI?ia73V-o2TLM8tH+hqWhawzJGe^KMK2ehA@AJAA0h?Rjr;qQW&x z$S!PBb(eO1>@qjaG3W}k5&t>yXD-y+o2o(gc}UH;d;mFi5&Z$8CIrJsT+-@x8Mt`< z=t~%B5`>V*Rdu0sc|6QBm3;V>TGg5%-|OGBALLE$`EtvS#>jas%la_$Tqp7R8!{7j zpA5)4hBLHN)mse|%_?$w`PecYyHGM^Rq6%2ze-*|e-*Rt|82ehD2&(mJ=ugxg7*@+ zihC?E+YAWt**Bm`8A3_C*xyQN&9faW$IuO(k=RR!ml~rlixF>8T$Vu;WUl3)3*2=w zDVBK3@hQq2O|cuZh%F;c#{;uhs|&G>i7FWPPeTZea@Xl77*ST%S7uiK$)P76ePMU# zhy;UlxW+l#hgYorvn^5BY(cc6Z&w*l=hh{FM;SnEotcZ_tw{%-Kch|a>4pTZJXT^7 z6!RlxVnU$&p1DT)J@^@42pF68ZZ*`xK z4{6XDvcHtYQ{r*~+cgbJt+T}}l)~I2Pk(_Sw|p&bk00I#qq}_jK02Ts9~ORLqix=HR$>v|x52EbNX+67C;FZa1HWlZ@{9CG0uWf>sXtGAyTHnROdrcZOtUGE% z0k!>eg%Rw&Mt5+q>%kf{aO>wf;jnVZhb;g#=QWzxEdL}_Z2wik;Wea#N%A09SF(&P zsI-rQ+*`efVEtMOWlSGOx)*I{nM|l}DX|%1Tw~W|)r^!Y($4L}=I0Fp8ZX73gcJB> zzY_81%lL@8ti~+06DhZ$StIj09mR<8?v%x=R<0>JBe?NnG|0;w--DHfs|2z0FKfV& zR*tnUoMosRg{Q$yiwnicTG@_9^Nh_hU9DZOl~Uy4SsHM(ac^UdlhHoQhMmiEb7W~S zn?T^lQA-^AX7Oy^S&+E)qmDI=))Mgb6DGr=EfdysVJ~SPfv;6|uj_jUmL@vW-nb)O@VmzNn?yBT1$|!mbQF zhb$2iI6O~ql)rcwmjST1+O;-&o8_$GI;qU%GUVk|c=8ocKHUG*OV>;3YOw9YIZ3TU zenxQZK~a~%8zEmgE24sN=0rJgH=}(Nxn(WAAmp|lbw;1b2ZR6zNM*T}PXU!2KVDC? zvHQ-tiV5c+bq{-^5T5hW?rQUBs>V)4_mWo&%8{5D8SA{vyAc?90tUMOEOtL7qh7Ua zcOzqev$DjcJ+n`}Vd~ZnvVXfr8nCR|-PbuA^@t=N6HB9P3*KvSZamU}i)>2z1T9A_ z#{(%|@?z@eg|E^Tih})(ZUm8g1#Y8eR{OdKUF$FZBK*;siQUbke>lTw_Tze5i<*5c zVQe3)D0Lo77ok&u>!DK?4qee>{sCwH1!;C`^YY)B8z{$rW^HIK<}pxx;-FlKH|c0V zVlD`X7QqFmacZD>85mXz@h8+AERbst46_9W2D*X(sNn#G2;Aj_c7tYPVPR%rX9wzY zLF50wB!CM#8k~!RGtsdV50{$-j#0wW$=QXNi}^eJzvDb&RyG!n#P~fbK-Dj8)y-j4 zKfxZ6*u&!Ma~*XWb$^nd{*&gSnYTec$hrGAvnX|027nGpcrr^Drj0j4*;DQIo*M6V z9UiSJv~&jxR0c@hUHy|m+;k~ylyr)eJ29$ktvoby`F<)nQz-kSfHW2(UHH^J)Z*YQ zmr#fpeg@~j~kx@u}V)i;O3unhdONuCXo)Sq!u2vL=-1k5d2n^~6bOY~vn zxc%On9ispi7@^_5qL}c?9#C(uFXgT*EzGbrvfKX<$sBEq%>BA>*yIsWl z&-c4vT|WaeSZ*zban4n*U;7nK+H&uA9WIDuyxtu|+c}?&?oM{Xe6m+d5tYO4?!fH? z!R9{xb>vs<(%$U+97vtAHU>hVrk7;+E5=Em74@*j|7 z|IfQ!HrO>IIa!P8Ngh_=d4B^!Cy}s=r{}}jDk5<^;5loS>u30`Z3%PcwGs|{c$0s(@aqJPU zP3^ci6wv&4-5U~f&Eaqo|#c=bppSDH>zequo3>0uHc4?d031hHo<5e2xNxo8oY- z2$ihpA5ALzUid$av5=7$P?Kz;w`}heDvx->I zMtoOd)YWHWpLButp?xatY5M<_#6P^JSt}lC}DI`GH^=8*2!-W!Lm7hAyn6Q4O zEE{IzQZRnW1-Ok{@^;dbwTCa8<0)rZPb=37_j=XBUAWh*CZoC}Khnb8QN_04Ru9h? z!otj?_nsp;fPl7)#2t6+>M$tjCnuu zvFVQChK*RC&*0RmvlmwV}^le@UKvtU-xZn4x;;3=iNBjk$hX9XJWy~rhvg4VErS}Krqwu z!n{wfFw$~(fC=;IwsjE8B|A=vvZF3sRcgHI?!;O?d%K06#@oC$^ z`xId_=@1)!y4|b$acf;)liSbZ+yv<^6TxTd06xLy$+q(9UN~XVN36{w;CAb;YL45> zK;s=&(vqLW_OgIK!?~6v;DGVktB3Kj!X0mODiwaAhj{wo8`gU9O0o0EHE^8M>MQAm z`I;Gg<<4OZf|!guCQJdr|5i@xqhLbfq00b$RAIPD2-7dEw71rp4~D4P$V-hk(im)RQ`g5 z$v!PFpH_*e<{25}s}hYmVQR16X8C2XsOoJLQjXa$F8&Dww>RucD|7O-Pkcf;pflJJ z5Fk!iL;Mj|$Xq@L(zj7LA?qVux*n2M=%?cWp&FZsxhg1q)l~XxJiX{a$Iz#&{Lg&H zxsJ7*Mb6K}UV-`sfMUa({ruaxS{3?*3{Q9cXSxo~j5qhw`a%w=QATl`L`(cG2a2_e zY|$ZJb6y`u7t-V+2YuDJL`#{5M7SD#yo{X_3=#qA(&Z8t5f{6<>yAxDc72MsI44yi z$qS80x6K&PYhHllji$fbW)+wLrX9Rv7VNh=$Jl<)Nn2qHAe9o6?TMRBPM#W-Mx_TD zqX8=$6tzC^ylF-jX>dnws#&&Br#gZgkcndlvFxc2eFnyvdOd@Uwpb?4pE>BF9#h#X zi!#QJITpuZHoqg=eBLNs6t}c0+w2QmeDXU?&eDRDerMAP6L;k5&s)TG8 z`?Jmg>epaD4kjdtH=^Tgsd$yJ-R~JT#)jpNhHp%qnL2gbL&V}gZcX{z$GK|r-6kBH zxBw%V)Mjcm*gx}ZXR=CHIAYS`R9xHGiG-u9wS)2w~L|fDx<%P^qlUZP3?Xa2o!EEOVt z69*fHlFLaPr_=TF4`knZD!#;T#~**bvrv>9Dkf@Tq}S2+=Yn-iz`uQ^m``^rbP0f& zw*3$nGWKwm_()oSuHg7B)?q%}NUPg& zo9W}1;gH(H`}+H3-l)Ffyn5nv>i!LhjYw2XEQtm!r=bWLSp`(cmGC4YCYP8v?C?f&T;v<{KI=MVqm2({v zZ%wmGuuSPqo?wVPRcQhs$_UTL7Q0gdm#$QO;XsZg!_oAZ0PM|CV&)XeOX(qT1Q64JtoMntTeH4|D4U4Sv9BC;Eb8R6V3#weoa$>DVel`LXH2-cGfX^11P&NaP)_W0fNQjQJIQ(o}-)p~^4c z8>^y+B4ILs{aLrwc*4}{f)NiescmOAc~~-hoY`~0zsm^!-S^A}-gY0Ogu?v@EsBnL zRFR5*ct&!-|MyjvL%6P0C?lN4f3B0qZC{Jdit50(nXbIWiDUz+p)CRF883FRO-_agPL>*t3s88+Wn&$NIH?)Ga8LwGxw+-JlxPq5V(_N(cQ)6dEVvp>t zYix;WvToFV*xNE~D#bnVlrwnbTX@+3JP=7tKws}}7yc-R&YtDgD2xBo<=QWq-i@z$ zusMhG3*KTrWFOAV&eR!b&J2b0jRF4(K$8HNIrZQeRV}^Dh`E_L;TScEb(o1+iJ8AQ zRqX9uzBk#3nTS>37^UsZ?Y}ej|7BvtI(%YWY!bq3Of1aYEbQNykXuBAS%jHgLX?|@ zRf0o|l~sWF|NjZ%_d)-Ihb*kjT>piK6f2$%>Wc)uH_n&do^;w{{V5@ILMy<1VHj;# z!*{zaCN$&?`j2EB}+|X#XoZ4E2{<8wSEYB3T(hICTXeW?ZCZ zLM%d;qXoN2!jz;%U-zOG*5_a>8-bx39l~WPkS=6Hxac88oT5+}ZbeFtLQBp8JcW_^ zSv;K~$_}X#(S-6xMLsAV)!8H*LxljcAi^>SzBDGFZZI-@vN#w0%9PE28XH7&HaykSgHc11z}GKWHkIPm+pJLYTb)qM+mBH&l~vY`Y>3CUI1Bj;L|a?FI4=QH z`97ZL_+EWZUY!9&u!P0LN^x|Z z#DCNIM;^AcnegC<;hYT_qJnUGE%CAtxtS2|#pbpYL-@+qHmR8iU6Rm9h<-Xo#5l1O z)v_bSF4!%IpiML!_Toe@3iGoGk4qw5Z1fW`lmV>F9QnlihI zwdqSLngZ`Hi^^Z-6qECKe3_Ay=4^gROFP?Q6luu>C22vH$g_0BbUJ}5<|Q(SMZ7o{ zCYeO*4g#R+bRJ?zg!;KP7VAc1*xmR4e6yC@*-PwChhE)&er0wiN+Xxp8_)G0h!EDk z#w@zOp5)g_=fW#WaH&kkd&Mj`hafi{ZcdjZlDkyaWLQmFhv1S?Zt_7Dv@B|6ytLN2 zH7puv`?jFVRJPqm4v!*8l5)@WCu=(w$N`AS@BuixG!&1`=WB|Oa5;onpWbTE1_Yf{ zJ{m|@vZ6nwYd1w4^k94y!85UUf)VyElyub^N|fK?>e%fp2LBSp@Jmdav8|KV|rzUT6mMVlQn;ZiajMl;N6z2L``sKSN()5+?c7 zAt9h4-gb&!!5{&^tKnj6sbYtFNp|a&Lq>RmDQQA->e0i}@&@?sE#QO6$Tt!dVF8N1 z((E_UC*>cbvcZgIz=af(-K+ru zdRNCmemj-USxec(CWk;)=5JZWQzGJUSUkYJAj|1&p zMSEC_Y1ktUaM9;GU`S6PT+I}UK7g0DbBpo)q4S#a^20mide}V#@UGA*B#Je9&e;NL z?dh295V7c0fyn@8ZvpDt{T}K-A?m?N+WBO%`yuxndEJM)D|-3-JJNw2EAu*sVRudL zxvEb1fqEeLq}8M{lUVo_WK;l-#SSLz32;gf8PYrK zavn!i4=41Kax^6dn)?a9jS=3HCD<^qP>9J97$=B<2%jjk!);VwDZ(WFlQcC2qP{Bd zgeCu5BTt!0br^4AjSSs1h};309%^;3FB83$7~NMVl~NTS{ci;N1W+AD=CB|3!VZdD z6t1ve3LCP(=toqDBeF%%9Dvr#o~O`p>kQhGk9;N9HIuKKUX@Wgm>kI zl8DB}(3q2@B*UZk5Q>Z1hnlDwRwwnSDuh@Y-=+eJdnD-M-d-}}5#R@9x^8&nR(0tA z3Cja*zGkRd_sImGFBcr+&VU}!{Wnrr5b*Fzajb*VMT|rBI4O$L<)HI( z#&TfH={2|@fnwJ?3NW0qel1(kv|uryd9WWV9d8*+on(vAP$nhl5FOpA%CN|*05AE* zj#LaG~ ze-#z8&v-`A6exsnEQoR{^cAg)gpdoMVhH;A8|s5sNU{gw;S2A(&b~fu|F_U`IBDy* z#^XsJei@OjoBsC~&c(^h$o4;xy|ERXvx||Fi-(h$IUE~12RA1N90i5Aq6FOk0Rrf? ADF6Tf From 99d17cab31fcaf65a4acdb38c8e6a9845ecfe3cf Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 27 Mar 2026 11:22:19 -0400 Subject: [PATCH 12/12] One more test + comments --- doc/CovarianceRecovery.pdf | Bin 477500 -> 478155 bytes gtsam/nonlinear/Marginals.cpp | 23 ++++++++++++++++++++--- tests/testGaussianBayesTreeB.cpp | 18 ++++++++---------- 3 files changed, 28 insertions(+), 13 deletions(-) diff --git a/doc/CovarianceRecovery.pdf b/doc/CovarianceRecovery.pdf index 078acf2a351f36ebb5721207fefcc422fb820b9e..d61938f3a5642d1af89f17cc4dc73821f5c0ffd8 100644 GIT binary patch delta 9833 zcmajjRZJWVur^@at+-2B+!nV&ahKxmvN($rC{Px6cZwEwcXxMpcXx;W-^rhIeJ-BK zOfuJ#$=e=JHkLwGUFrqL#mUK;5VuPYxgfQT*=xM<@)>wcC*Wh+O&{O!rIoCbQOQAa z7NL;!v$4OZtTeQxUTbOle4UIiOc{;)mhn!%wKJ9V$qBL$$$!xe>F{y}?>p&*AL1g%`x(mjjY+oF(@JR;<%lpLx%8a?u3=RKqZtxyn!Tb7r5LT-z|6u`CJ>;RLBLh`eLOx z%zyu&CyF#hCMXo1iLw6k%5Dura4XXg3hr-gnGcH-Nn!pQ-s1FKq7e@KHyDO&uQbcC zJ%)MM*Yj7$b~;x$3Q7?ogtQj0K#sH}t(h36V1Y>S$%y1bZH%i=D}Sg!-zM1Y0Mcsp zBHLuAnqz+Nu(F=t%%n<0ly)m!{Q+$lwO!X|0-o zSzLNL3o?;2;%VOQLd1>eL1!SMT-uPNlhc=LI znIo=YckQvOOgR0^aPCWOqW#K9o^|db%OP-~^bOJlkrPQJe$pIwh3GdWj&hYO;ZlsX79mi-<{ zhwS~LCj$;fc08Aoc`T-oq@~21ZJ_PaiL{+u#;&+f%|FS!y_L&za*=70nl-I~ z(W_pDtYy7tvdU39edm;_3e^PGPh2|auK=sO{5-37AvvT%I!h%DuGaX$TdiN6>sl`R zof%Y*2M}e*c|w{gB#W2_@c7U$;A5mjY%O34A)!Xa3K$Knr5}y)#XU*%Ac|${u!qhU zCw}ii-XM&i=9r0}{AzD%pYWqZ(y0}o?z>9<`>&;v*Rt4aU~fjvO2e!bZR!e zC?={mXVeCW(jYAqv)7t)7UYxDjZq)m3E8j-$ejbV893yN?2*+%0>e0mTG;df(=W#G z6AuvJ9HOClvl+#`Gpw!uoWE$5M9ADH%b;}+29(gXf|7g)Uj<^Xi@78;W7UcA4gj`H z*(G_7cCZ>pduNS)!dl7Fo{16aRSE@^Y5%MCU04ZMb@Wav3qb}~4;!~m${;cm+Kz5P z{}~zY@Hlz)<_wp+S_TDQ{VYICVV29(*bh=DpIU;>Y_>)NX3m zWXe4fMX}Ue0-n@GN18Xe+TYKwA~ahH88S_1vrO7kTDQ5@cF0V#ph>}_Uv9Li#Djon zJQY%w;V!GH35NAou zU-hwm<;sS5k_uM5!t1Hi-L3^9xA`--Fz<4m=$eN@*rju^|Sq1 zFzU8_o|ErQ&%_tHmF?`dB$EiinaN|Z70pdDUfH`g!k#>!oi|!+G*_U(lg7)w&t4SC^gPlsMRF2?I#x4p zvvscAvd?H~h^cQn7RoBcoREXF>om_Nw|pMO?w7mwYBJQ_pWf^f6U@rakOniaf~vi| zF8O(_#B{^yuynH`0{^yyl{WfR?i#^AL-j%n74P)e$G&J>lJY%(3y5Jj^%4yfQn}$| z)zIqHilz|*4-ln;ds-)kc0 zjuaTmipMzFXX3520*Sl}h>6in%bXdcXZd#`n~=B_jJrE=Gsqcs|%iW4bHO}mU2%)@>T&bt~{T2o+ey@A9t-P>a5-b}LG;-{O8zi_*`mufB&0%~5 z{RgeSE+1DrGj3U?et*xi#YeVp#~U^^qpPCRkTvNTH;p4--f8-&|i zGMj&ai(&!fxZx`}GnQ^dqT1oQ#8DSaExrIk>hD&5h}dt-N_M*5Rn>vzRV_M?nOMzk z#XlPQ7~tSBRaeF}HZq9eF9;9mf5K+UR(KTJjj!-pJ&KX)m^be8`@%Ct9ACFS@0`p% zZxI#Xa5|ZYnLt&|KQ2I=#yuZ=@23T1@IPh_lK??}g;#C@`A}(_-juyVaRqK;1}3GI zYP^8Der8=G8E2$XyBp3%2c2Dyb_D+>r(aGB85?~DI*gpvbX`1y_Us4=3^!92=Cqos zH5M<6A9D7pR_AAYnjh(pr5hgWtm>A9ERzi21+)%!e!+tJ$F=kDe>L_}2)FtP&&uJO z;4VTwE+-2{U;nOF6rYD*=Xt8s(Koe_Oh3uKQ3N^le=@2(OA1jal9BJ0?6}bbg>Y3P_tURUk zUBy*geJc_^bd22*FrvJ}t?&#X%Jb%n=HWYpfrn|{e&Ipy4;Qzh*pL8ZxQUk5P~rhmEM(=IdW%%NpGStAm-oX!m&BL{x31dNLEvs3r0n zVjPXDKjgAcU)M{nh22k2)}b3=^e8{Z=Uow=r*wE|pVx zKS=f>-s}!?GweHQfMIm^ah1}h`vZ`^9t0hJ9i(^Allj%yq|l-h#1s_=Oqv|u;{L?b zdg=WA{NKCT=Qb?^NBC6^|^Yl+!BwrdR+qT(U6Wlp@bMATjJN@3e*i zdEIbAz@?NaXd&)SzV3N3V8dcn*A6=67hc7pYv)jXnVj1Lx1<@=F@ZRvO)q4klV}=4 zFYukUmT+01@QevmN4hps*V66JMfSq$DuJy=*;aNcQS$@h&ACl-WWRaTPxK+-{T^An zvrD>Pu=llMMXxKOeZmJq?&bKkN{c^o$cLc&&5Nuz zO`oEN&ls=iI7}s!;F#|v+cE?_xr2y4dfOgv`Q=-XI~3(0tk^9eYgc+qZM?LH|5xOX zsfIE!VH&m0=Q=ti%N#(~HkeLz+lDwLU(7YTb7A%623;z`t0qRCQ^8LuSQt_)=6PVV(HCV}8u z$Ji!QaXtF5IN&6wAVW@7tFD?_0E3oi?19IRj2lz%*7-bR`0q+{Fs-tzcYoj$c3?{h z4y9shWQ;QGEq{SA&P_|teoIqXNY~h`-QmorRet|4&MgaTv);72gxg&i^;jB!h7Nly zM|ddOrRvK@l;05lxh$kch7paKHOUa(UUsDsK?2(SDFg)dJi*($6HRe- zhbJ`NUcz*-_KHmg1PP<#+a;HV)~aFS!mxKLh>9oW3G3jTR>`}K@>IU?=hVo z=#%U-T35UK8<%B2fWxw{)8ysf>F-flWr@f0-R2vopVQ7*KhaR1I?W$_%$Nt4%izF< zfUm`5iFuHQ0Cntbxa=~wYf=|u%K8P)byjBfZ;r|dqp&^qxFrTb#o|&s?58N>H;|~y zRsnjIE3!)E$(*PIxmlA~5yE{npbFoj?v zHJ2K9gkXPTSPeNdbGW6=@yXqPlKdC@$S<30IYV<)LRk~Dd&+uty`UwAoLWt-1kB*% zv@z>rZL^^fLgTo{7xyqSiLw!7g}e3Wh7((oW& zCp>5q0J~|5tf?*o<_FEh6?ZfA#{Q^MW<>Buk#&UE%l#|nQCb6&`11BZ)=*=Vsjq}s zd;N6~oEh13z+NuPF%+%Twpoqh{5KSl$%9aa7#z95#F#<742o~jb#a-I7?Y@-gjZno z>u{wW8SvnnZ^W+{B?NFck7n>@8 zC{7(QnO$cat#?p;hMv|ENN4<{P0HS1DrPDLGChc*7kKbDE_`UuN!=e_>{jZz{hWd4OR}C|n`QpZxyS|(s8YBuu>_QVNyBxE`%RrC=uOb^12%GK1Ac#Vfc8&v4 z>UG5j5(7B+QLOP4l;8o~hb`9}#0>UsM!dJ7~N}}h_O8245%BLvmGr-WdT!LTA?;j zjF{tLn^=#1UJ~D9C{s>5Oed+&84Q8PJ}W066Z*wr69efwRe0-rR^+wGR%9dCI55Sq zzMCE-$a|FJ&Gt#n{CQUj^Yi%a(woCa;KNFZFV9ia?c3(<@_vj1JhZ?{9uxy-w?}>ru+Ho+1ntG98)M*@b){w~w7Mf%=!dh(J z48Df<)2NE@Kt|hoCCZrZd|f+(B>ehzvi5|uac_yCw0~}aIM^FTCKR%8EX+FoXTQ>m zmyKj|;tjR~LIT@^SM?}za}RAE98aHt8b)j^i>s0s^zX)j;3o2H_oUBZmp?FKQ>Q*bUeSmyLZG=E`sP3nRzEY_$ip z2mv2#mSl5DLi=IG_KU^iJp{WYFfkYRps8xn*u!oR;_RCGPiy^T)T-+V!n6O=+Q8;h zHG`*D|7*CJjf$Qp*piCekV3P+Zld#M%;)<@tXm7nK4s`W=FbA0y*~qyAMLKeR(A^L zR0+cmMtT1EN_H*Y7>VxL* z#oDs?(AlSqT5rsY+8NrfwM2DNk)Ak-zxJyQ{_>A~YmY$E48_8U`!k4em=Vu}hKkas$z1)k`Vpmeoa2oc(opl0!E3XTbC3y{4G32`f&@Q6^N$~f~3>yUT>&7M<5WK%OXJ@Y-ac|qCh0aH|MRV3XB`faFb4Q&Y1-S6UR7pR6)-%RU?F&sFKWHZ3m60B=X{z$#DmBMySwKs&0!2F? zd-}<}uHJImVpLi=nM_WOs(x<;V)wdccYAnY+JvG4zF1j9cG$>L-0Gs3t7)Wg*9+&~ zcq<#Yash}kG#WK2n^>+=Sa+{3)!pbkRkms0cZ6fDY<7}gX}4nA7p0JyX1i^EtQuTK z&TcNrR9^VJ0DYQBT%9hqnl`~h=_`-nvIYkFUP8ZKNtzk>`(A?dITPZ~F1U1;)-I~rhwx9brBE3|mTRx4_2V2-SD z(lhotz|i<)2s;jZG2%F?q*XNxm!Ew?+{>dK;Ap>~iKjjtO+-xkasK9uoF~l_Ok`9jg(w7<0)7O){ zwW2E%FAKDqe;#hVNX1e^g8chr22J%tZ~f%%Ub`D^t4Dep(~@(L@B8iPYWjX{eGC{o z-@bd?N^>ei=b*d81{C#D^igWZIc`&IMLT8uCK z+KxK(pee&0ZJ5(6T=Yt@Inh>94>@)IzL-_ydl)x9f7`zK|H#^&^wWPNsAqzGI zW3UPsPeZ#HCEFN~?|c%xA^`GpxB;?lxCT2KSphy)tfCmL?t(bMdDL)sUPG{s|M-&R zMCVYi*ayvi(Mo5a&QRb&@n@!Fl=hJ$<=d~-FEz~m^YJD>t9oI?OSuPewM&fcu~-*u zHcCIm23)?~b4Tg!=v8o63VQ-x-F|re{vo)2_YZIFpXz`c3d^bh*$3jzY%@~8!cfS< z5cGdw{sa3Txc|U6Ees*}gAsYz+1WWcxKj-I5J~@cX!7GjEJRQNN=orb@p6lEafypc zNQiStinH^u^YU>@0J$WAyj=Xkl;8f(6$2DD1q%m|s}&^&7ck}TH+TjJ&9WCbX@F?x z#{CJvzwbi_pu!Rp>!m@K#ef#0^n;6sf{urx+KG?VjuZXz6&^P>qM`!NzG2ncK2uFs zr6eLK8NYO|ypfuPZx+U%n9u_T=b$vFUK-q>{H`&D6!*up?Beh+ai$KUbe!wsMfc=sR(*VRP>~T%C@Tb(E z>%_1G^OCtuh{DzLko++wR`A20p1Y6Koj$SN>pANEW)-qh4TbM4MLizOKW*;cYyV0( zF^zyuE90$f>tX^S*K$Cxx2}NK4NLS%5O#bE-#R2_DY;1Zq zQnHj0uapgEK3j)>?u~=imE%4qnTtI4%{HG)hPVVx_s?IqR${EEsjsa90e?s{S83*h z=T379MlSQY!!-#ikkK~0t^6cuwY_48t{J*tudTaVveLaEi~dtEn!ZQ3St0k-zV&b4 zDEE8-VBV>OS24=&PNcynh3LY#59$fsHBPLE(!Zu-}zU^y<+Jd~$}RBklTqB|{c)aMou>9jh7E2B|$ z?*4#&%iJD8bnrT%wTZI|c69!y{A`*QoyW@&&n*)})T6G-Xq7AcOI(=0Sijf4NS`1N)F0P2kady{^k+cP}iF&ayK-W>~`B zge)!8p)`%s>n)h7f<~P2So04CkyJc3_|m%-0UOdS_AStuuwR6^UvwERhHRDz1p8(V z7=sfeUn16X03a?~QMbenMY(q0{@sLAHk!p;>LH~E_I%#y&Y3vo6o9O3c_RH!fW(EO zR1}pt+<1c`EVw_%4o(9UzL?-~rK+Vr&cgackZ6~< zm*Tazgzb2anHbsK8Ma?yv-#wLik_@iksBUM=E*|6>+aI@EbxA2*7v?om(W)f<9H*I z{ljP;pYuXh5&Y_Nfh{z&)JUDF)Kwl91DUI`y4}5xNNaEYhSUDwC=?auJl;uS?H{4n zFsLt3xX3;itpyJ3i9_dwJvE_?rIHTL@R4Tssq{_W3|(=56`J_!B+>nabtte^%-Dyl z#kqexj!7Dhw8a_Fizkk(HKR4XB_q(EKN3efq~D4x6047cg&>VV`UR}eo^Iyf1=&B= z!$w#_8SgZE%=Fo_idu1xSXM_4rPgUfG@6%r5590xT!`r0;*~%?=EF3+yin%>ReP@D?;rN_D|b z^^qTY^EXxlu?n@%F$99lFSt`03t6MzPeOem>n=bUM9$mYb`&$I0n$p+d+NqUDL+U3 zh-ZnE4~7-9PWX{bC&7ahQ){#mOc)ApfCW1knf(`WS43-+l7)XS`k{9aF-VXCi${pg zP8gT)O(HwXq+4t_^{<7q>+w^sfma|)Hi{loko`yR;}z0N<10)X&t zq05E^9h+(-6(k&o`F)H9^S9cwDEc~9R^D0j)ehscj7QcbX4)8a`(m7JuS)B8PxWV~ z7DHhoRZ0yTg=2Qs2b{vUB1rp-Q}D^N&W;2xxQXC4h`{lSAxcl5zcQ|27DIcj%JYlL z4uSsFLKP}qSog>kQkS`<&rfZ>1=@^F#BAiM4+D?P623m9%$;1&C)N9FAUGK}`>he2 zb=DCFoqr-$26o~i#o62}s!FmwU%nLai6v`iK;SJosY;iP1)ax}KwevBVy(y13F^}^ z;bY-f2K5gg*o?kx{+94?47wJcx)r{13yN!BrS_h#ARxrx2ll4gqD?k{0x|zldb{d2 zPZk@1UN)LFp7{))&Hb-W7KozxK4i20XvUqp??*8)=s0-MR7E3gbPv874an5Jll z|I~!lZO6xEAm5JjKn~EUSjdF&In0mkED_eJ%ok8sGUBNBK+^lZl85qCuV`K>f)v={D#Z3tWEX@sLbSLW`GOgYcmc7Ou3vkm^J=%4+7> zCtDaFY50~)t*ye;wyZR=UsqO()LIf`5v&^F;Is2Zr0=-DHop=WmDH3G$k;2UFW$3t z-T-@+g;`hWNb(Hy=+W|hnYjh|G@2#F%)ZkJW*7{WZ4R21cQM;-_cdXnkQDXk^%i;s zO_W^Im{>)CAt}tVZ9zcqEa^2y)ES38822so+T{x&gWl+`CPxA$S`@=Rj#o(^qnDE~ zS&mcWzh99Q{B%iU^JS5t}`cPtRHQs#^srS#do6-Sey`N)}J4*+Q|lXJDqL zCJqCt`z{vyxwo@z;|D8*yQK3H%DR9AZP@&eE@a=aa4a0vLhW__` z;8Z5e2Z5?kKM|?^l>b1na4>gqb+$0EMad9un&MxmjR IRF*>de?!0OKmY&$ delta 9182 zcmai(MNk|Jux^99yZhko4uiV}4=#ff+y{3jNN@>mgS!k4!QCwoT!ID&@cvt`?)olH z*ZHb@+trKynMKi)Mgge~faew97s!&9L|_76niwYk>c9!!HJkVIfOD+#O&2Am?v@59 zVpAh~hmd!}&~Bc&sBP&fH2K)xp6keI<1*+p1>RGm9hRwS;U`xg=o78)_J5q^`V4QS z@^M$u_*_$6;rHrPDQRPBtw`MjDWXt(}{SQ>bvI!+!dD3Msh}$l$`QqBWoY`$_y1vsuB>_@O0UOE4Sh8+D zDMFj-C!BL-eXWZdi$Z;@^{!Lu-PPTf z@9_mGZcL8B?bbZ|ThmvftC|qe4C0IpZxOACPp!CREsQIaQLf<9Uum+~ z^K-u%QgJ?)c!GyN*V3U};O)Cf;*19Qbj>Q*ig`-6O}FU)E>y8w)h0jE}njg&RMED>(p!!!n6?$xWY@oymFsXK z#k#$VPVQeu?u(ORIUaX?P?^bva;t3dM#;G=d!$*8!dvnyS}``PpI$zk;qx46IXp1} zWN&}(wNe+CnVe*4E2zl!I$UY6-BWm2L_2mguAU$aP&QvDCrit4T4xC+DCO7qv=k=4 zJ4&dmlalxC0lAJ0xC=95-~MT@O|kc+r=2v4cerfLGF#cV#&~oO1R&C88RVy)Iv9_s zdxVqsuaRD}px6>c=%|gym@y!M*OxbTOT>tsq-F@+DNSSZUiZMPuB6x?)GKO~dKF%d z{)~^jP}x*Fsrj%GCAkYmn;ZR{TG!@xNou>vGAqzGmc`QG5&e>MhJS%#scO~>U4r>- zQ)+C5j>OI|Zs@N%V8SNac#Pxio~>Fz*|4bx+tyFXgFi-T!Q=$mp}hh$tUkM>3sd^n zyDQte5y)zLlMxWK9I)%>{&9u@852C)u4i*4ad8$DCW(_yiF1K_{4ZbtKSL%Gh+Y4f zpOSnJsJu)!U3#_b_Tn_M!a1+$Nrgv0F7 zvF~lj+sR7zH=6-#zTWfTHWvz9k-ykxcJ(gZ4g4K3(%F< zl7cn-QE~q>CX7TCjfrA%FIoM3lq+dmRz*amCH6rrEK0AC1BGCZ-vGl=1mmZ+jhq$O*?Si>3+WDXU4aj?tinpakA2*3rFYHdkXkqU+NKh>_F=M}3{Wn| z>5($Iee>>-KKiHSL`(duN45dohOma*?0^Lve3!h$~?IBGN@ zPSaqMni*yEY>r0c74Vw*FVy__kY?kJ<+Mm@pJqIeaKma541qZmm*3l36!43mEbP! zratEENo&pN5}pED;8tA9VhL%*l~HI%RK7f=%jx~Q8GI5)QT-ZkGR zX^-^KBth%ZCQCMT#mXH$_$k@z6z^s6b-*~%0+I{$MDdZYOpGF09xHjYvfBe0X@H4` zUd+D%ya~(=$OMp&`iE9eR@{$*42|75xTac6qACw|N-lzu$exKK9Hl>I={9w;^{97} z3~XfE5T9gJQv!_dc5wpW*qE2`U~sXvnB`?~eBnef+YD_EE{M#GE=g9VidUG;=S<)E8+mh(Hi88lcjMpz)NnHM%3MmXx!?mPcNBQo zimc{M=~sqD(v4xn9E8P}knh?O<)0F;8#CwVFZ0udf-X4SDv>Uzr^ViZ(mG@uw1Q$Qd03Wbh7rP)`Z-{@`)7peOaEft7A> z_B6bagYokP@g>{c=vdj-YJg235-mp|QuhB|*J2fmr#>NLW-gmi<0`n4|LeG5J@*7>2rmEsdT13^)+1XOvdb_??CM zZ3$=kDm?kLX3&zb{KCDh(*=i@P2dGnL`3n1&Dssy%NMdcVT-I2Jg|4HgiTiE8i?*c zp%|bMgk$j%E#hGmyk$j*orSXyXl?WDAn_6G7TfrTdUw942QXUI#%kVCuCo(*3?GlDVD*Ue|bokE?Pvts4^j9ZI=M?jKB?TOV&-BKV@8a|GW0b_T27lTtyS$J6Naq7U5rqX9D4pG+f^9WY<%gG zZ?d>$c_Heny|PtB9Q-UX8u~!F_o~VuLcAIU9i+9#*Qt@ld7b*KSC*#-wd~Hn8d0g5 ztDhV1=&s&UHWyyj9G&cRs&8(KYYX}j%p`2K6S~|4f|n_Nk(a9{^SJ3c?#2tmzcANa zFllyjU~w9Q4d@EA`5jX29RJ-+@ZTG1G$HerTyiV2$nR_4Ju3**=k+6ubLB6 zKT<_1_3pDg9$6(-g#=7#KgZJ<40_1@eKlF>vsT!L+S3?d5^aq1LnJ=d-OFEkd<0dU zw%cZMXSW+vbj<~$iNN7MZt2#RWZhazga?N==~N-$QfETmrWDfAt=}?L-1x+%uiC#$ z*dAlbb8Bkaf%c@u5pino+1Kvm+v2a0%jz9PC7tFnVwc6$R++sK>22#CzQ>|~Ub^9{ z>Fj|qc#fL8QamHIu7-8F@NSl$no&9NoIi(V>fsBWGl@kC6mJQVk#ZRhtZ8ndOW@c1 zR<9btN+!4g5Yo+kHR7i$XgSiC+l}|%g-ypqx#))&6rCDM3X5U72Zq=p`GnS*_>1<^ zh=?e{-wB--9STd13z+ckfTn!7w{c!d$kZ&?4^`z_rqgQZ2i~cpqfDLRl@{%MO=x?U z=O@m*M2$+Xs2vSQ_zc{r=&l~j)kEuj6k65bFH>iNsq+J}d~euvxdd1V95W1PGn*MOQ>m%13wW0F#;4!U{^MK!WPzpdC<~PWi zo%LRo$)&cbx%4Ybouc6l zAw7!~80rIYX1PLR-sF)4E9W{pKQt)QmufJyLs-7wjuiHI`fFvzJHJDGJ{Nl@eqo0T z;8Q{p{90bmr{w&COVUMRj%3WR)=A=&2}gLY!l*in%q6WA77im3pSl=r9L9CDY;=K7 zHY*W_>m&8hW32RXJi$tV)nunpI_5+IR`NWC(I{vZpP=}o@_Xj{r|EjQJ{lhfH?>ZC z%&*^X#JD9APmaFwmKyF-M(J!f@ddp`me@C*Nj>uLddS{@(I(Ya!Z{uy%C3vhb75yAhb30vo)^ zX<}4qX%qymAGRQE}OqygMd!=;-?%*H@h?RusC4JSyY=Yit!9GzI=HTTX{-_EU zER3aTzFN+oV0z!kPFyXslM+zT_7@%33wnJ5wi~IE3bV|gCMM*WeNy?oJ z0HjY_kf`5Yc=7dWsv4$H&nw^Pu{5SF<~Mh>$_zi*8Go31bWrq_DS87D{F{X%I}z>T zvJ7wf^RXqvucm0%W>$e=oxpDc7j`)eQvt%D;Lq6J}4QX0(e zhpYOtt=}K?u?&WB6tw@|3{8mTf#J!Ll0;wzUm6*^l8q4rA2(#TuSqp~2z#(6d}Q0(qAco*GkTRxqk`!IY$x@APG9xS>Ba>7M ztk*M!U$Aa9zE=0qq+F6tbeLir@L%E>$ zbSvnn%^T4=KoudOv&`@q#EDivK-POUM>>$}#Quu3wP<4^EB43?qr2BX(P8Um5=$3$ ztlSehZa-+=z!VZo_(LVsRXHvrbWeE)?3PTtMq{qKlNQX)$_d;H!_-262Eu-4F!c0= z=O9ttL(ay5GE$P4Ak0v+X#z+MBjMAKuc&ycV5%b%E*T66;)YK9igY-UZAteLdgE5o zkuUJsvT93^-3X&GCmf-FmCskW9`vb@D z^;q-@8RYc<65K-?7wrUPm>-$6EOMx_fADz*zJ(-V1DfDu(T*Ah&HXrjK*H%s&Cwsr zfg~e-RZBAAlTjDrB~ASFF49P=L^q7ad$jA77v!RZ6tsxgaos;+)MMbVLZ?Ijg=$;V zo)i-Zk^O@);r3!-ofBfl0un8Nmt_Xx#@@u~+d?|xXiagGZn3EyO;VuEc5p%WuQoOJ z=ljv#MP}-wciv)!(i`M0f2O7S?d{TQPVGf&STv)9oo3~Sh|)RFvf<`$->1 z*m4EFiR2_;McwI%3;*TCC&9H&pGb-STlZ&|_zq()I4^G-$(@hF)U?e`nF>>K#_f1j zVYlBAvq2&_P?9`3_UHTvsQhMi|DN$7*;{02UYYdV0**Z5%6N6y(Rz7ySgV&b$ffvU z=KY`Uo4atH+0;hyOOF95n9Tn0^r2NWjw);g?(OmHt*6g@4)cB=B$C_TL#$3S0r%$M z`<90IQdr7+VWehW#wjQSva48}XJED|cJ%r;;Hph*<)lRj2lcCs!;=mg3`%hAOzJIGH99%Ct6lJb+w@eNze z4us1+5+(-PgM3Y7;PlN0(B(_3&`hMxgFq#yDG^9X13ihE%G>zbU|Ej6o4A2)VGkHtm+-`EE03b2vQZA#Z^2Iug>I}J=}Xp%8^n4?)^y}xlk|89&5>z`rh7Vdh0h>O z%s_F9+rS{n4hAa;x%nqLwba*;FEDOVSPo%k(rqjRRbI#hE%`@dXxYwn#y#eVmo53c zZsIF!rr2p~Gf_7Pp`R<_eQ}~(x6#!XuHPTucdaQkUiR^T?e4rtjP5UO2v+;Un3xv) z8=M}kw4F8Jo#|)(>)%@iJBgutY5D<0z9KN+i|M&Y6F_wXY1BOKy0p3NII|Fz0`)e$ zSqT%jsIyOG$Zc8d7Bpd)9KY4gkEsJ<_JKDTw5Q#nIHdwn^XTvyjjP)O^8)-1NFwMY zKAB54`xigy28}nLzx1WBp6ZcAfoz*OhO#Z394YC+EomzedV_sH*7vV6+y;2RQW>^z z;_AZxSpXYbXz=5MKRT>nn(=6N?r|E$Wd|=~;0nb$Gs(jX63Y|D8)58Rm?ICTs!~lZ*Opq5QXfE*X#(la77-n1F!xl zMFSZyz1TPUaw3SC9deB}?n3pqAN(UIem<(hE|%(P7&*-Vz-n4hxDsE0Ijy+rj|!m) zS95hEtC^f0j#`yzizfC&I|-Z~8-K0MY_(}waxux;7^_^9UxaTiFEp2yvl|>qr5`I;a=mk0_Y!(=UQ$Z`a1*BGjHr<;uJ`;4w%@xE85>p| zJGYXJH2D~)E#S+*{VQ}eq3*X`Z=R-&+1KG2DY819^}kWYjWn1AtLWS-KS_5=uMAOn zFfu68q2K)0M~qY^zk)Rz)7U;qtbA^JG=y*qar>0<+9nZuDWiH!1b54NWcvFOT{jMb z11t}M)NCUCDl`ZXl@N?|W=q%xF8Eu+hH+3p2-0@iBPn|GBvN%qv zqGd16pLZ+;O0+tbTb(~E*kRg0tTm9fI0Ta02dL1^ODf(kepSe$%7V{uU2~Z`XH6O} zGle3YBN_@20i_mqHQ#(y`TmD_OsoRfU^PG2FI0OxFb~Sr=tip$XI!tX8jE-*tymi_ zNmqyJYGNW@qFtiP;pE_l^ggDj+|W)z&?WGRq#Yzae_f4OfP^Z?e5_ck(xZ+U`qW%- zJ5g<>DBEMuCbi=1*d62 z@6A0!e&X{e%CjbH4cCeduw3(VsRMhZiN0N&$fF=zwRT*De5G%dh*8Ek!!4zqr~f(8 z-B0q94Vw)wD`u_Nk{jE3o%r;n4XmFFY_hqNYznc~Wz4!Nhykc9G-|Mt%!5^= z%OixLJ_(w9PWja(dI(c}xN}}$AKn(*Ih#oZg-rHIWm&#iM^uBxyy&_a1Msw(=jcaOJxi(G{0tkAXW6EI{k-V9Bkf zz@zwr1mj@||CL~uG2_yfJN}a8%Le_S_hQioRNU;*(%7GeNsKnbPk! z2uTM|8ei@xs~q2YJYUDkaUVa{z75gY&NEyU%5iG9Z#%FDr5#GhExeaynot_tPxNZ5 zboMUM+GOx+PqNUKWpxF=-8??zuBnsAoJbT=@WNKl|Ix$rQ(3(PKg@G9j%^qCcISIP zo38rI-(xX5ALD23UAe^t35_KeJP2a@0?Dor5jDiY*x@Fzh4t4%1OBqz0N0}l|314B zGxq0>BmXyT25{AAzwQL%=uul!@T^k3Xb-Y03)WZPo!X$BTiaa?ot?F@59r88EuP79 z{*YShg6Mkpw~Ht6f5E+Vp_~%%`fBC+RJHdgDFnYMLw|7z-@848lG&3=|Mj|KVDr`& z!GyFksJF=HaTJY1Ipwsga{a-;pt3*epU7qg*Lk)be|3PJ7TwY_*|{TcPaBVSNCRc&1CJVDev zd^}wL|2IUj=I55NOfvT8DK8*BH%Ma~F+vJi1=*S*LW&y2ng%6;0=TB2r3V9pAnWK{ zgYTJVWW4D=hG_sT4GYs&4uBXG*CX?+%z$dVH`L=Z6N>&Qpgbaf9BW*K?63d?U~S?bH^Sxnv^Jis0Ey z6Ky2k`t12C&C#mvaCh=sTB7xI>GuMA2+%>La=Lhv3UO^fK)!OiTogO5l0Z9G&IcP` z2TUgA4A_QpMQji|h(Np)3-Fo1!#p1fc+ocNW<#%9WrjiaGw^QzWfIH_9pI=pw~V)DZlV zFRhlOeu?fN+~N7;jt>i3_nJe%1bf0g z$FxBlDc*%x)>}ldc6TOKoUpJL@fHx2jrNoEs892EGR{=aWu^&h$VOoIf`)}UgKkvfGj^MdU5{!4)9f(Um$&ToA3HfJDYbxn; z=9xURbct|SPdgSo&`uQEef}#CHn;c9jI#TmvRV;|SyKP$zwIFqStIqMXpI#M<71&8 z{5dtn=TCJwn=YyGF7|wGVC_A7#rII}368R5*)L@_)^h;02nzq|a6j}g2mhvaquIIQxkhGx zO1Y7P4rfk|9wEYXFm%*1I!Ij^X;~Qx)x?nb>&9Hi!W61Zj7m^s91V3NhEkS-5+iu# zT!hIy+vm9ue-FT>9D_ITvhHndhfK1O*tyWk2UN3B#ph6YixP*<2~?xK=VEgZ^XCv= zbV+Q(N&|#)<3svnh;sJUqgzMOMF30O{Tw)ou`0G^6s@LRBCYYDQ`M*Wg;+CHl_5w( zCZaVnTlf(q48vc*N_BU)bwssW7ccKU+B>%3SL>x>#bOr!AMn?gH~^=*+0^04QSM$T z$97_@`&1t*AM_ckWzB5mpG2z8VRKO(1 zaZ~Maol@eKBI_^zUWyUk|hROZ6amL%5Qsr@R%1-Pf6`4@-XY!>4jv5TBKaU)10A+LBs zh$~5y)`l`+hEi1q+z6z3vjfU^raZT$ETd4Ntb0U&^C}{O10uJGBE>K>K7xw(^ok*B zCm$hP=DnKup+|#7sKvhVT)z1OPT4fC5owpe5#vER6c{UlDB?MU#;xpP$yJQTB32s& z_Vr(nf)UF^k^CRHD-0;-c(7Jfl2rl35bQJz&Yvq77&ozyuZ@sX9E-b}!AuC`L1w=m zD8vBX+J--lyj+Z+ph6by$GP$|S@Y8C;3TO>dy-@e^a;5c;2nGdx~cz#BJM*=2W4ha zx+~Bm$*WhhFiBF(rwa7y%A{%ONt*jLBzg*UB;HzYYN$|V?_sy$@}Ble2ba92m zf3+19B6*s1u#j)mL~BIhEAs#5!t>9T=^X}pQti(qbEzt@?q}cd*ag@`yIo)n{>iwB zbhAvn*<_5|?PblI!Ztnf?f=jgl7m+dV(l57>M4Llid-y2vCBjTI}z=ev+P($>>L)k zdLg?Wqg(NVjY}=?b%Cjke!skAgioHj)Q!T6*49!#H@O-jC=y>Vb*dQm zDHBuFbYmdCIe(_*_X}I&W(ST?7RMnNv!5@l)Dk#gp;+1EId9_)c8H}MuDyUQEqcVn zoWiXa)YlkPt+Pox@8k^=z1?}nc_7nGq|WiR@}hEjrTIpvx1KF^;=o+%Y47oNPSHAa z;yiUf%Z+;fUX!;GeTNGmW9v@1(V|)4kVQmeyb!2RjQH~4HG<(>Iy2|X3!cUIh^Rv9 z(fUI@*L@zBe45&Wq4r)t?K`*%Vw(ne3-||*$U;#nH0CkZ0Va$pbX%W@-M~8P} zR`nudW$QsIV4+iu&wa|1P00x=7Bb&xVtMGbqUa}6WJ%JPWN?o-Q$XayGO+YO+?#2h zNlDRpT}8O}>{weVfVH&1p_Jr!q}bjQu;mk~nsx0D4xT@%HymInOd~z2jf=I1r@M`X j^Z%Hur30#mr-i$xue*&cDxV;q5Dy dimsForKeys(const KeyVector& keys, const Values& values) { std::vector dims; dims.reserve(keys.size()); @@ -63,6 +66,7 @@ std::vector dimsForKeys(const KeyVector& keys, const Values& values) { } /* ************************************************************************* */ +// Convert per-variable dimensions into cumulative block offsets. std::vector blockOffsets(const std::vector& dims) { std::vector offsets(dims.size() + 1, 0); for (size_t i = 0; i < dims.size(); ++i) { @@ -72,6 +76,7 @@ std::vector blockOffsets(const std::vector& dims) { } /* ************************************************************************* */ +// Recover a covariance matrix from a symmetric information matrix. Matrix informationToCovariance(const Matrix& information) { if (!information.allFinite()) { return Matrix::Zero(information.rows(), information.cols()); @@ -83,6 +88,7 @@ Matrix informationToCovariance(const Matrix& information) { return covariance; } +// Build the reduced joint factor graph for the requested variable set. GaussianFactorGraph reducedJointFactorGraph( const GaussianBayesTree& bayesTree, Marginals::Factorization factorization, const KeyVector& variables) { @@ -96,6 +102,7 @@ GaussianFactorGraph reducedJointFactorGraph( } /* ************************************************************************* */ +// Eliminate a reduced factor graph into a Bayes net ordered by the query keys. GaussianBayesNet queryBayesNet(const GaussianFactorGraph& factorGraph, Marginals::Factorization factorization, const KeyVector& variables) { @@ -110,6 +117,7 @@ GaussianBayesNet queryBayesNet(const GaussianFactorGraph& factorGraph, } /* ************************************************************************* */ +// Recover only the covariance columns associated with selected variable blocks. Matrix covarianceColumns(const GaussianBayesNet& bayesNet, const KeyVector& orderedKeys, const std::vector& dims, @@ -140,6 +148,7 @@ Matrix covarianceColumns(const GaussianBayesNet& bayesNet, } /* ************************************************************************* */ +// Assemble a left-by-right block from packed selected covariance columns. Matrix assembleCrossBlock(const Matrix& selectedColumns, const KeyVector& orderedKeys, const std::vector& dims, @@ -304,6 +313,7 @@ Matrix Marginals::marginalCovariance(Key variable) const { /* ************************************************************************* */ JointMarginal Marginals::jointMarginalCovariance( const KeyVector& variables) const { + // Normalize the query key set so block order is deterministic. const KeyVector variablesSorted = uniqueSortedKeys(variables); if (variablesSorted.size() == 1) { Matrix covariance = marginalCovariance(variablesSorted.front()); @@ -311,12 +321,14 @@ JointMarginal Marginals::jointMarginalCovariance( variablesSorted); } + // Reduce the Bayes tree query to a Bayes net on just the requested variables. const GaussianFactorGraph jointFG = reducedJointFactorGraph(bayesTree_, factorization_, variablesSorted); const GaussianBayesNet bayesNet = queryBayesNet(jointFG, factorization_, variablesSorted); const std::vector dims = dimsForKeys(variablesSorted, values_); + // Recover every covariance block by selecting every column block. std::vector allBlocks(variablesSorted.size()); std::iota(allBlocks.begin(), allBlocks.end(), 0); Matrix covariance = @@ -327,19 +339,20 @@ JointMarginal Marginals::jointMarginalCovariance( /* ************************************************************************* */ JointMarginal Marginals::jointMarginalInformation( const KeyVector& variables) const { + // Normalize the query key set so the returned block layout is stable. const KeyVector variablesSorted = uniqueSortedKeys(variables); if (variablesSorted.empty()) { return JointMarginal(Matrix(), std::vector(), variablesSorted); } - // If 2 variables, we can use the BayesTree::joint function, otherwise we - // have to use sequential elimination. + // A single-variable query can reuse the existing marginal-factor path. if (variablesSorted.size() == 1) { Matrix info = marginalInformation(variablesSorted.front()); std::vector dims; dims.push_back(info.rows()); return JointMarginal(info, dims, variablesSorted); } else { + // Reduce the Bayes tree query and then materialize the reduced Hessian. GaussianFactorGraph jointFG = reducedJointFactorGraph(bayesTree_, factorization_, variablesSorted); GaussianBayesNet bayesNet = @@ -350,7 +363,7 @@ JointMarginal Marginals::jointMarginalInformation( (void)rhs; Matrix info = R.transpose() * R; - // Get dimensions from factor graph + // Record block dimensions in the same key order used for the Hessian. std::vector dims; dims.reserve(variablesSorted.size()); for (const auto& key : variablesSorted) { @@ -364,6 +377,7 @@ JointMarginal Marginals::jointMarginalInformation( /* ************************************************************************* */ Matrix Marginals::crossCovariance(const KeyVector& left, const KeyVector& right) const { + // Preserve the requested left/right block order while removing duplicates. const KeyVector leftUnique = uniqueStableKeys(left); const KeyVector rightUnique = uniqueStableKeys(right); KeyVector unionKeys = leftUnique; @@ -378,6 +392,7 @@ Matrix Marginals::crossCovariance(const KeyVector& left, return marginalCovariance(unionKeys.front()); } + // Reduce to the union query once, then recover only the requested RHS blocks. const GaussianFactorGraph jointFG = reducedJointFactorGraph(bayesTree_, factorization_, unionKeys); const GaussianBayesNet bayesNet = @@ -385,12 +400,14 @@ Matrix Marginals::crossCovariance(const KeyVector& left, const std::vector dims = dimsForKeys(unionKeys, values_); FastMap keyIndex = Ordering(unionKeys).invert(); + // Map each requested right-hand variable to its block in the reduced system. std::vector rightBlocks; rightBlocks.reserve(rightUnique.size()); for (Key key : rightUnique) { rightBlocks.push_back(keyIndex.at(key)); } + // Recover the selected columns and pack them back into the requested block layout. const Matrix selectedColumns = covarianceColumns(bayesNet, unionKeys, dims, rightBlocks); return assembleCrossBlock(selectedColumns, unionKeys, dims, leftUnique, diff --git a/tests/testGaussianBayesTreeB.cpp b/tests/testGaussianBayesTreeB.cpp index d02eec64be..83920762a7 100644 --- a/tests/testGaussianBayesTreeB.cpp +++ b/tests/testGaussianBayesTreeB.cpp @@ -259,16 +259,14 @@ TEST( GaussianBayesTree, balanced_smoother_joint ) GaussianBayesNet actual3 = *bayesTree.jointBayesNet(X(1),X(4)); EXPECT(assert_equal(expected3,actual3,tol)); - // // Check the joint density P(x4,x1), i.e. with a root variable, factored the other way - // GaussianBayesNet expected4; - // GaussianConditional::shared_ptr - // parent4(new GaussianConditional(X(1), Z_2x1, -1.0*I/sigmax1, ones(2))); - // expected4.push_front(parent4); - // double sig41 = 0.668096; - // Matrix A41 = -0.055794*I; - // push_front(expected4,X(4), Z_2x1, I/sig41, X(1), A41/sig41, sigma); - // GaussianBayesNet actual4 = *bayesTree.jointBayesNet(X(4),X(1)); - // EXPECT(assert_equal(expected4,actual4,tol)); + // Check the joint density P(x4,x1), i.e. when the first queried clique is the ancestor + double sig41 = 0.668096; + Matrix A41 = -0.055794*I; + GaussianBayesNet expected4; + expected4.emplace_shared(X(4), Z_2x1, I/sig41, X(1), A41/sig41); + expected4.emplace_shared(X(1), Z_2x1, -1.0*I/sigmax1); + GaussianBayesNet actual4 = *bayesTree.jointBayesNet(X(4),X(1)); + EXPECT(assert_equal(expected4, actual4, tol)); } /* ************************************************************************* */