From f340e6260ee053d4b47ebfbbb32aa42970b35286 Mon Sep 17 00:00:00 2001 From: Yun Chang Date: Thu, 23 Dec 2021 20:44:03 -0500 Subject: [PATCH 001/116] correctly parse optimizer params for base optimizer in gnc --- gtsam/nonlinear/GncOptimizer.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/gtsam/nonlinear/GncOptimizer.h b/gtsam/nonlinear/GncOptimizer.h index 3ddaf4820..0cd9629e7 100644 --- a/gtsam/nonlinear/GncOptimizer.h +++ b/gtsam/nonlinear/GncOptimizer.h @@ -183,7 +183,8 @@ class GTSAM_EXPORT GncOptimizer { /// Compute optimal solution using graduated non-convexity. Values optimize() { NonlinearFactorGraph graph_initial = this->makeWeightedGraph(weights_); - BaseOptimizer baseOptimizer(graph_initial, state_); + BaseOptimizer baseOptimizer( + graph_initial, state_, params_.baseOptimizerParams); Values result = baseOptimizer.optimize(); double mu = initializeMu(); double prev_cost = graph_initial.error(result); @@ -227,7 +228,8 @@ class GTSAM_EXPORT GncOptimizer { // variable/values update NonlinearFactorGraph graph_iter = this->makeWeightedGraph(weights_); - BaseOptimizer baseOptimizer_iter(graph_iter, state_); + BaseOptimizer baseOptimizer_iter( + graph_iter, state_, params_.baseOptimizerParams); result = baseOptimizer_iter.optimize(); // stopping condition From b687317ccbf2ff007d3c1c7831e0ac4e53fe5a90 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Sun, 13 Feb 2022 16:47:12 -0800 Subject: [PATCH 002/116] EXPORT statements to help Windows build. In Constraint.h, there was a GTSAM_EXPORT that should have been GTSAM_UNSTABLE_EXPORT, and in DiscreteKey.h, there should be a GTSAM_EXPORT in front of an operator definition for a class that is being exported. --- gtsam/discrete/DiscreteKey.h | 2 +- gtsam_unstable/discrete/Constraint.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/discrete/DiscreteKey.h b/gtsam/discrete/DiscreteKey.h index ce0c56dbe..dea00074d 100644 --- a/gtsam/discrete/DiscreteKey.h +++ b/gtsam/discrete/DiscreteKey.h @@ -72,5 +72,5 @@ namespace gtsam { }; // DiscreteKeys /// Create a list from two keys - DiscreteKeys operator&(const DiscreteKey& key1, const DiscreteKey& key2); + GTSAM_EXPORT DiscreteKeys operator&(const DiscreteKey& key1, const DiscreteKey& key2); } diff --git a/gtsam_unstable/discrete/Constraint.h b/gtsam_unstable/discrete/Constraint.h index 4ee7b85eb..168891e6f 100644 --- a/gtsam_unstable/discrete/Constraint.h +++ b/gtsam_unstable/discrete/Constraint.h @@ -34,7 +34,7 @@ using Domains = std::map; * Base class for constraint factors * Derived classes include SingleValue, BinaryAllDiff, and AllDiff. */ -class GTSAM_EXPORT Constraint : public DiscreteFactor { +class GTSAM_UNSTABLE_EXPORT Constraint : public DiscreteFactor { public: typedef boost::shared_ptr shared_ptr; From ac01db4f4d1af145d09094047629f9d7271ec803 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Tue, 15 Feb 2022 00:19:54 -0800 Subject: [PATCH 003/116] Per https://github.com/borglab/gtsam/blob/develop/Using-GTSAM-EXPORT.md , classes with no methods defined in a .cpp file shouldn't have the GTSAM_EXPORT or GTSAM_UNSTABLE_EXPORT modifier. This was causing problems with the building of gtsam_unstable on MSVC / Windows. --- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 2 +- gtsam/nonlinear/NonlinearFactor.h | 12 ++++++------ gtsam/slam/SmartFactorBase.h | 2 +- gtsam_unstable/slam/SmartStereoProjectionFactor.h | 2 +- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 61e9f0909..dcb830f24 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -30,7 +30,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeCamera: public PinholeBaseK { +class PinholeCamera: public PinholeBaseK { public: diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index b4999af7c..7b92be5d5 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -31,7 +31,7 @@ namespace gtsam { * \nosubgrouping */ template -class GTSAM_EXPORT PinholeBaseK: public PinholeBase { +class PinholeBaseK: public PinholeBase { private: diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 38d831e15..7fafd95df 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -282,7 +282,7 @@ public: * which are objects in non-linear manifolds (Lie groups). */ template -class GTSAM_EXPORT NoiseModelFactor1: public NoiseModelFactor { +class NoiseModelFactor1: public NoiseModelFactor { public: @@ -366,7 +366,7 @@ private: /** A convenient base class for creating your own NoiseModelFactor with 2 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor2: public NoiseModelFactor { +class NoiseModelFactor2: public NoiseModelFactor { public: @@ -441,7 +441,7 @@ private: /** A convenient base class for creating your own NoiseModelFactor with 3 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor3: public NoiseModelFactor { +class NoiseModelFactor3: public NoiseModelFactor { public: @@ -518,7 +518,7 @@ private: /** A convenient base class for creating your own NoiseModelFactor with 4 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor4: public NoiseModelFactor { +class NoiseModelFactor4: public NoiseModelFactor { public: @@ -599,7 +599,7 @@ private: /** A convenient base class for creating your own NoiseModelFactor with 5 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor5: public NoiseModelFactor { +class NoiseModelFactor5: public NoiseModelFactor { public: @@ -684,7 +684,7 @@ private: /** A convenient base class for creating your own NoiseModelFactor with 6 * variables. To derive from this class, implement evaluateError(). */ template -class GTSAM_EXPORT NoiseModelFactor6: public NoiseModelFactor { +class NoiseModelFactor6: public NoiseModelFactor { public: diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 16712c429..ca158cc1d 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -47,7 +47,7 @@ namespace gtsam { * @tparam CAMERA should behave like a PinholeCamera. */ template -class GTSAM_EXPORT SmartFactorBase: public NonlinearFactor { +class SmartFactorBase: public NonlinearFactor { private: typedef NonlinearFactor Base; diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index 5cdfb2ab7..61f110d3a 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -49,7 +49,7 @@ typedef SmartProjectionParams SmartStereoProjectionParams; * If you'd like to store poses in values instead of cameras, use * SmartStereoProjectionPoseFactor instead */ -class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactor +class SmartStereoProjectionFactor : public SmartFactorBase { private: From 3a49c79ee86921b11819cfa754fdfa07a44ac935 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 08:25:10 -0500 Subject: [PATCH 004/116] Fix check.geometry --- gtsam/base/serializationTestHelpers.h | 2 +- gtsam/geometry/tests/testCal3Bundler.cpp | 2 +- gtsam/geometry/tests/testPose2.cpp | 49 +++++++++++---------- gtsam/geometry/tests/testQuaternion.cpp | 26 +++++++---- gtsam/geometry/tests/testRot2.cpp | 52 +++++++++++----------- gtsam/geometry/tests/testRot3.cpp | 56 +++++++++++++----------- gtsam/geometry/tests/testSO3.cpp | 18 +++++++- gtsam/geometry/tests/testSO4.cpp | 42 +++++++++++++----- 8 files changed, 145 insertions(+), 102 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 5994a5e51..bb8574245 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -42,7 +42,7 @@ T create() { } // Creates or empties a folder in the build folder and returns the relative path -boost::filesystem::path resetFilesystem( +inline boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { boost::filesystem::remove_all(folder); boost::filesystem::create_directory(folder); diff --git a/gtsam/geometry/tests/testCal3Bundler.cpp b/gtsam/geometry/tests/testCal3Bundler.cpp index cd576f900..020cab2f9 100644 --- a/gtsam/geometry/tests/testCal3Bundler.cpp +++ b/gtsam/geometry/tests/testCal3Bundler.cpp @@ -160,7 +160,7 @@ TEST(Cal3Bundler, retract) { } /* ************************************************************************* */ -TEST(Cal3_S2, Print) { +TEST(Cal3Bundler, Print) { Cal3Bundler cal(1, 2, 3, 4, 5); std::stringstream os; os << "f: " << cal.fx() << ", k1: " << cal.k1() << ", k2: " << cal.k2() diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index d17dc7689..c199a7af0 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -796,44 +796,45 @@ TEST(Pose2, align_4) { } //****************************************************************************** +namespace pose2_example { +Pose2 id; Pose2 T1(M_PI / 4.0, Point2(sqrt(0.5), sqrt(0.5))); Pose2 T2(M_PI / 2.0, Point2(0.0, 2.0)); +} // namespace pose2_example //****************************************************************************** -TEST(Pose2 , Invariants) { - Pose2 id; +TEST(Pose2, Invariants) { + using namespace pose2_example; - EXPECT(check_group_invariants(id,id)); - EXPECT(check_group_invariants(id,T1)); - EXPECT(check_group_invariants(T2,id)); - EXPECT(check_group_invariants(T2,T1)); - - EXPECT(check_manifold_invariants(id,id)); - EXPECT(check_manifold_invariants(id,T1)); - EXPECT(check_manifold_invariants(T2,id)); - EXPECT(check_manifold_invariants(T2,T1)); + EXPECT(check_group_invariants(id, id)); + EXPECT(check_group_invariants(id, T1)); + EXPECT(check_group_invariants(T2, id)); + EXPECT(check_group_invariants(T2, T1)); + EXPECT(check_manifold_invariants(id, id)); + EXPECT(check_manifold_invariants(id, T1)); + EXPECT(check_manifold_invariants(T2, id)); + EXPECT(check_manifold_invariants(T2, T1)); } //****************************************************************************** -TEST(Pose2 , LieGroupDerivatives) { - Pose2 id; - - CHECK_LIE_GROUP_DERIVATIVES(id,id); - CHECK_LIE_GROUP_DERIVATIVES(id,T2); - CHECK_LIE_GROUP_DERIVATIVES(T2,id); - CHECK_LIE_GROUP_DERIVATIVES(T2,T1); +TEST(Pose2, LieGroupDerivatives) { + using namespace pose2_example; + CHECK_LIE_GROUP_DERIVATIVES(id, id); + CHECK_LIE_GROUP_DERIVATIVES(id, T2); + CHECK_LIE_GROUP_DERIVATIVES(T2, id); + CHECK_LIE_GROUP_DERIVATIVES(T2, T1); } //****************************************************************************** -TEST(Pose2 , ChartDerivatives) { - Pose2 id; +TEST(Pose2, ChartDerivatives) { + using namespace pose2_example; - CHECK_CHART_DERIVATIVES(id,id); - CHECK_CHART_DERIVATIVES(id,T2); - CHECK_CHART_DERIVATIVES(T2,id); - CHECK_CHART_DERIVATIVES(T2,T1); + CHECK_CHART_DERIVATIVES(id, id); + CHECK_CHART_DERIVATIVES(id, T2); + CHECK_CHART_DERIVATIVES(T2, id); + CHECK_CHART_DERIVATIVES(T2, T1); } //****************************************************************************** diff --git a/gtsam/geometry/tests/testQuaternion.cpp b/gtsam/geometry/tests/testQuaternion.cpp index e862b94ad..88548d15e 100644 --- a/gtsam/geometry/tests/testQuaternion.cpp +++ b/gtsam/geometry/tests/testQuaternion.cpp @@ -80,12 +80,6 @@ TEST(Quaternion , Compose) { EXPECT(traits::Equals(expected, actual)); } -//****************************************************************************** -Vector3 Q_z_axis(0, 0, 1); -Q id(Eigen::AngleAxisd(0, Q_z_axis)); -Q R1(Eigen::AngleAxisd(1, Q_z_axis)); -Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0))); - //****************************************************************************** TEST(Quaternion , Between) { Vector3 z_axis(0, 0, 1); @@ -108,7 +102,17 @@ TEST(Quaternion , Inverse) { } //****************************************************************************** -TEST(Quaternion , Invariants) { +namespace q_example { +Vector3 Q_z_axis(0, 0, 1); +Q id(Eigen::AngleAxisd(0, Q_z_axis)); +Q R1(Eigen::AngleAxisd(1, Q_z_axis)); +Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0))); +} // namespace q_example + +//****************************************************************************** +TEST(Quaternion, Invariants) { + using namespace q_example; + EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -121,7 +125,9 @@ TEST(Quaternion , Invariants) { } //****************************************************************************** -TEST(Quaternion , LieGroupDerivatives) { +TEST(Quaternion, LieGroupDerivatives) { + using namespace q_example; + CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -129,7 +135,9 @@ TEST(Quaternion , LieGroupDerivatives) { } //****************************************************************************** -TEST(Quaternion , ChartDerivatives) { +TEST(Quaternion, ChartDerivatives) { + using namespace q_example; + CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); diff --git a/gtsam/geometry/tests/testRot2.cpp b/gtsam/geometry/tests/testRot2.cpp index 7cd27a9da..f08f3e2a5 100644 --- a/gtsam/geometry/tests/testRot2.cpp +++ b/gtsam/geometry/tests/testRot2.cpp @@ -156,44 +156,42 @@ TEST( Rot2, relativeBearing ) } //****************************************************************************** +namespace rot2_example { +Rot2 id; Rot2 T1(0.1); Rot2 T2(0.2); +} // namespace rot2_example //****************************************************************************** -TEST(Rot2 , Invariants) { - Rot2 id; - - EXPECT(check_group_invariants(id,id)); - EXPECT(check_group_invariants(id,T1)); - EXPECT(check_group_invariants(T2,id)); - EXPECT(check_group_invariants(T2,T1)); - - EXPECT(check_manifold_invariants(id,id)); - EXPECT(check_manifold_invariants(id,T1)); - EXPECT(check_manifold_invariants(T2,id)); - EXPECT(check_manifold_invariants(T2,T1)); +TEST(Rot2, Invariants) { + using namespace rot2_example; + EXPECT(check_group_invariants(id, id)); + EXPECT(check_group_invariants(id, T1)); + EXPECT(check_group_invariants(T2, id)); + EXPECT(check_group_invariants(T2, T1)); + EXPECT(check_manifold_invariants(id, id)); + EXPECT(check_manifold_invariants(id, T1)); + EXPECT(check_manifold_invariants(T2, id)); + EXPECT(check_manifold_invariants(T2, T1)); } //****************************************************************************** -TEST(Rot2 , LieGroupDerivatives) { - Rot2 id; - - CHECK_LIE_GROUP_DERIVATIVES(id,id); - CHECK_LIE_GROUP_DERIVATIVES(id,T2); - CHECK_LIE_GROUP_DERIVATIVES(T2,id); - CHECK_LIE_GROUP_DERIVATIVES(T2,T1); - +TEST(Rot2, LieGroupDerivatives) { + using namespace rot2_example; + CHECK_LIE_GROUP_DERIVATIVES(id, id); + CHECK_LIE_GROUP_DERIVATIVES(id, T2); + CHECK_LIE_GROUP_DERIVATIVES(T2, id); + CHECK_LIE_GROUP_DERIVATIVES(T2, T1); } //****************************************************************************** -TEST(Rot2 , ChartDerivatives) { - Rot2 id; - - CHECK_CHART_DERIVATIVES(id,id); - CHECK_CHART_DERIVATIVES(id,T2); - CHECK_CHART_DERIVATIVES(T2,id); - CHECK_CHART_DERIVATIVES(T2,T1); +TEST(Rot2, ChartDerivatives) { + using namespace rot2_example; + CHECK_CHART_DERIVATIVES(id, id); + CHECK_CHART_DERIVATIVES(id, T2); + CHECK_CHART_DERIVATIVES(T2, id); + CHECK_CHART_DERIVATIVES(T2, T1); } /* ************************************************************************* */ diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index dc4b888b3..537ec8f4f 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -640,46 +640,50 @@ TEST( Rot3, slerp) } //****************************************************************************** +namespace rot3_example { +Rot3 id; Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1)); Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2)); +} // namespace rot3_example //****************************************************************************** -TEST(Rot3 , Invariants) { - Rot3 id; +TEST(Rot3, Invariants) { + using namespace rot3_example; - EXPECT(check_group_invariants(id,id)); - EXPECT(check_group_invariants(id,T1)); - EXPECT(check_group_invariants(T2,id)); - EXPECT(check_group_invariants(T2,T1)); - EXPECT(check_group_invariants(T1,T2)); + EXPECT(check_group_invariants(id, id)); + EXPECT(check_group_invariants(id, T1)); + EXPECT(check_group_invariants(T2, id)); + EXPECT(check_group_invariants(T2, T1)); + EXPECT(check_group_invariants(T1, T2)); - EXPECT(check_manifold_invariants(id,id)); - EXPECT(check_manifold_invariants(id,T1)); - EXPECT(check_manifold_invariants(T2,id)); - EXPECT(check_manifold_invariants(T2,T1)); - EXPECT(check_manifold_invariants(T1,T2)); + EXPECT(check_manifold_invariants(id, id)); + EXPECT(check_manifold_invariants(id, T1)); + EXPECT(check_manifold_invariants(T2, id)); + EXPECT(check_manifold_invariants(T2, T1)); + EXPECT(check_manifold_invariants(T1, T2)); } //****************************************************************************** -TEST(Rot3 , LieGroupDerivatives) { - Rot3 id; +TEST(Rot3, LieGroupDerivatives) { + using namespace rot3_example; - CHECK_LIE_GROUP_DERIVATIVES(id,id); - CHECK_LIE_GROUP_DERIVATIVES(id,T2); - CHECK_LIE_GROUP_DERIVATIVES(T2,id); - CHECK_LIE_GROUP_DERIVATIVES(T1,T2); - CHECK_LIE_GROUP_DERIVATIVES(T2,T1); + CHECK_LIE_GROUP_DERIVATIVES(id, id); + CHECK_LIE_GROUP_DERIVATIVES(id, T2); + CHECK_LIE_GROUP_DERIVATIVES(T2, id); + CHECK_LIE_GROUP_DERIVATIVES(T1, T2); + CHECK_LIE_GROUP_DERIVATIVES(T2, T1); } //****************************************************************************** -TEST(Rot3 , ChartDerivatives) { - Rot3 id; +TEST(Rot3, ChartDerivatives) { + using namespace rot3_example; + if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) { - CHECK_CHART_DERIVATIVES(id,id); - CHECK_CHART_DERIVATIVES(id,T2); - CHECK_CHART_DERIVATIVES(T2,id); - CHECK_CHART_DERIVATIVES(T1,T2); - CHECK_CHART_DERIVATIVES(T2,T1); + CHECK_CHART_DERIVATIVES(id, id); + CHECK_CHART_DERIVATIVES(id, T2); + CHECK_CHART_DERIVATIVES(T2, id); + CHECK_CHART_DERIVATIVES(T1, T2); + CHECK_CHART_DERIVATIVES(T2, T1); } } diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 910d482b0..64d3e681d 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -67,28 +67,33 @@ TEST(SO3, ClosestTo) { } //****************************************************************************** +namespace so3_example { SO3 id; Vector3 z_axis(0, 0, 1), v2(1, 2, 0), v3(1, 2, 3); SO3 R1(Eigen::AngleAxisd(0.1, z_axis)); SO3 R2(Eigen::AngleAxisd(0.2, z_axis)); +} // namespace so3_example /* ************************************************************************* */ TEST(SO3, ChordalMean) { + using namespace so3_example; std::vector rotations = {R1, R1.inverse()}; EXPECT(assert_equal(SO3(), SO3::ChordalMean(rotations))); } //****************************************************************************** +// Check that Hat specialization is equal to dynamic version TEST(SO3, Hat) { - // Check that Hat specialization is equal to dynamic version + using namespace so3_example; EXPECT(assert_equal(SO3::Hat(z_axis), SOn::Hat(z_axis))); EXPECT(assert_equal(SO3::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO3::Hat(v3), SOn::Hat(v3))); } //****************************************************************************** +// Check that Hat specialization is equal to dynamic version TEST(SO3, Vee) { - // Check that Hat specialization is equal to dynamic version + using namespace so3_example; auto X1 = SOn::Hat(z_axis), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO3::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO3::Vee(X2), SOn::Vee(X2))); @@ -97,6 +102,7 @@ TEST(SO3, Vee) { //****************************************************************************** TEST(SO3, Local) { + using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = traits::Local(R1, R2); EXPECT(assert_equal((Vector)expected, actual)); @@ -104,6 +110,7 @@ TEST(SO3, Local) { //****************************************************************************** TEST(SO3, Retract) { + using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = traits::Retract(R1, v); EXPECT(assert_equal(R2, actual)); @@ -111,6 +118,7 @@ TEST(SO3, Retract) { //****************************************************************************** TEST(SO3, Logmap) { + using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = SO3::Logmap(R1.between(R2)); EXPECT(assert_equal((Vector)expected, actual)); @@ -118,6 +126,7 @@ TEST(SO3, Logmap) { //****************************************************************************** TEST(SO3, Expmap) { + using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = R1 * SO3::Expmap(v); EXPECT(assert_equal(R2, actual)); @@ -125,6 +134,8 @@ TEST(SO3, Expmap) { //****************************************************************************** TEST(SO3, Invariants) { + using namespace so3_example; + EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -138,6 +149,7 @@ TEST(SO3, Invariants) { //****************************************************************************** TEST(SO3, LieGroupDerivatives) { + using namespace so3_example; CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -146,6 +158,7 @@ TEST(SO3, LieGroupDerivatives) { //****************************************************************************** TEST(SO3, ChartDerivatives) { + using namespace so3_example; CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); @@ -350,6 +363,7 @@ TEST(SO3, ApplyInvDexp) { //****************************************************************************** TEST(SO3, vec) { + using namespace so3_example; const Vector9 expected = Eigen::Map(R2.matrix().data()); Matrix actualH; const Vector9 actual = R2.vec(actualH); diff --git a/gtsam/geometry/tests/testSO4.cpp b/gtsam/geometry/tests/testSO4.cpp index 5486755f7..7379049c3 100644 --- a/gtsam/geometry/tests/testSO4.cpp +++ b/gtsam/geometry/tests/testSO4.cpp @@ -48,6 +48,14 @@ TEST(SO4, Concept) { } //****************************************************************************** +TEST(SO4, Random) { + std::mt19937 rng(42); + auto Q = SO4::Random(rng); + EXPECT_LONGS_EQUAL(4, Q.matrix().rows()); +} + +//****************************************************************************** +namespace so4_example { SO4 id; Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); SO4 Q1 = SO4::Expmap(v1); @@ -55,15 +63,12 @@ Vector6 v2 = (Vector(6) << 0.00, 0.00, 0.00, 0.01, 0.02, 0.03).finished(); SO4 Q2 = SO4::Expmap(v2); Vector6 v3 = (Vector(6) << 1, 2, 3, 4, 5, 6).finished(); SO4 Q3 = SO4::Expmap(v3); +} // namespace so4_example -//****************************************************************************** -TEST(SO4, Random) { - std::mt19937 rng(42); - auto Q = SO4::Random(rng); - EXPECT_LONGS_EQUAL(4, Q.matrix().rows()); -} //****************************************************************************** TEST(SO4, Expmap) { + using namespace so4_example; + // If we do exponential map in SO(3) subgroup, topleft should be equal to R1. auto R1 = SO3::Expmap(v1.tail<3>()).matrix(); EXPECT((Q1.matrix().topLeftCorner<3, 3>().isApprox(R1))); @@ -84,16 +89,18 @@ TEST(SO4, Expmap) { } //****************************************************************************** +// Check that Hat specialization is equal to dynamic version TEST(SO4, Hat) { - // Check that Hat specialization is equal to dynamic version + using namespace so4_example; EXPECT(assert_equal(SO4::Hat(v1), SOn::Hat(v1))); EXPECT(assert_equal(SO4::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO4::Hat(v3), SOn::Hat(v3))); } //****************************************************************************** +// Check that Hat specialization is equal to dynamic version TEST(SO4, Vee) { - // Check that Hat specialization is equal to dynamic version + using namespace so4_example; auto X1 = SOn::Hat(v1), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO4::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO4::Vee(X2), SOn::Vee(X2))); @@ -102,6 +109,8 @@ TEST(SO4, Vee) { //****************************************************************************** TEST(SO4, Retract) { + using namespace so4_example; + // Check that Cayley yields the same as Expmap for small values EXPECT(assert_equal(id.retract(v1 / 100), SO4::Expmap(v1 / 100))); EXPECT(assert_equal(id.retract(v2 / 100), SO4::Expmap(v2 / 100))); @@ -116,8 +125,9 @@ TEST(SO4, Retract) { } //****************************************************************************** +// Check that Cayley is identical to dynamic version TEST(SO4, Local) { - // Check that Cayley is identical to dynamic version + using namespace so4_example; EXPECT( assert_equal(id.localCoordinates(Q1), SOn(4).localCoordinates(SOn(Q1)))); EXPECT( @@ -130,6 +140,8 @@ TEST(SO4, Local) { //****************************************************************************** TEST(SO4, Invariants) { + using namespace so4_example; + EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, Q1)); EXPECT(check_group_invariants(Q2, id)); @@ -145,6 +157,8 @@ TEST(SO4, Invariants) { //****************************************************************************** TEST(SO4, compose) { + using namespace so4_example; + SO4 expected = Q1 * Q2; Matrix actualH1, actualH2; SO4 actual = Q1.compose(Q2, actualH1, actualH2); @@ -161,20 +175,22 @@ TEST(SO4, compose) { //****************************************************************************** TEST(SO4, vec) { + using namespace so4_example; + using Vector16 = SO4::VectorN2; const Vector16 expected = Eigen::Map(Q2.matrix().data()); Matrix actualH; const Vector16 actual = Q2.vec(actualH); EXPECT(assert_equal(expected, actual)); - std::function f = [](const SO4& Q) { - return Q.vec(); - }; + std::function f = [](const SO4& Q) { return Q.vec(); }; const Matrix numericalH = numericalDerivative11(f, Q2, 1e-5); EXPECT(assert_equal(numericalH, actualH)); } //****************************************************************************** TEST(SO4, topLeft) { + using namespace so4_example; + const Matrix3 expected = Q3.matrix().topLeftCorner<3, 3>(); Matrix actualH; const Matrix3 actual = topLeft(Q3, actualH); @@ -188,6 +204,8 @@ TEST(SO4, topLeft) { //****************************************************************************** TEST(SO4, stiefel) { + using namespace so4_example; + const Matrix43 expected = Q3.matrix().leftCols<3>(); Matrix actualH; const Matrix43 actual = stiefel(Q3, actualH); From 10bf3a0199f0d630c5d08ec050c1cf27b7d8ddb5 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 08:54:36 -0500 Subject: [PATCH 005/116] fix check.sam --- gtsam/nonlinear/factorTesting.h | 39 +++--- gtsam/sam/tests/testBearingFactor.cpp | 32 +---- gtsam/sam/tests/testBearingRangeFactor.cpp | 32 +---- gtsam/sam/tests/testRangeFactor.cpp | 68 ++-------- gtsam/sam/tests/testSerializationSam.cpp | 140 +++++++++++++++++++++ 5 files changed, 179 insertions(+), 132 deletions(-) create mode 100644 gtsam/sam/tests/testSerializationSam.cpp diff --git a/gtsam/nonlinear/factorTesting.h b/gtsam/nonlinear/factorTesting.h index 3a9b6fb11..266aa841c 100644 --- a/gtsam/nonlinear/factorTesting.h +++ b/gtsam/nonlinear/factorTesting.h @@ -21,6 +21,8 @@ #include #include +#include +#include namespace gtsam { @@ -34,13 +36,14 @@ namespace gtsam { * This is fixable but expensive, and does not matter in practice as most factors will sit near * zero errors anyway. However, it means that below will only be exact for the correct measurement. */ -JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, - const Values& values, double delta = 1e-5) { +inline JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, + const Values& values, + double delta = 1e-5) { // We will fill a vector of key/Jacobians pairs (a map would sort) std::vector > jacobians; // Get size - const Eigen::VectorXd e = factor.whitenedError(values); + const Vector e = factor.whitenedError(values); const size_t rows = e.size(); // Loop over all variables @@ -51,18 +54,18 @@ JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, const size_t cols = dX.dim(key); Matrix J = Matrix::Zero(rows, cols); for (size_t col = 0; col < cols; ++col) { - Eigen::VectorXd dx = Eigen::VectorXd::Zero(cols); + Vector dx = Vector::Zero(cols); dx(col) = delta; dX[key] = dx; Values eval_values = values.retract(dX); - const Eigen::VectorXd left = factor.whitenedError(eval_values); + const Vector left = factor.whitenedError(eval_values); dx(col) = -delta; dX[key] = dx; eval_values = values.retract(dX); - const Eigen::VectorXd right = factor.whitenedError(eval_values); + const Vector right = factor.whitenedError(eval_values); J.col(col) = (left - right) * one_over_2delta; } - jacobians.push_back(std::make_pair(key, J)); + jacobians.emplace_back(key, J); } // Next step...return JacobianFactor @@ -71,15 +74,15 @@ JacobianFactor linearizeNumerically(const NoiseModelFactor& factor, namespace internal { // CPPUnitLite-style test for linearization of a factor -bool testFactorJacobians(const std::string& name_, - const NoiseModelFactor& factor, const gtsam::Values& values, double delta, - double tolerance) { - +inline bool testFactorJacobians(const std::string& name_, + const NoiseModelFactor& factor, + const gtsam::Values& values, double delta, + double tolerance) { // Create expected value by numerical differentiation JacobianFactor expected = linearizeNumerically(factor, values, delta); // Create actual value by linearize - boost::shared_ptr actual = // + auto actual = boost::dynamic_pointer_cast(factor.linearize(values)); if (!actual) return false; @@ -89,17 +92,19 @@ bool testFactorJacobians(const std::string& name_, // if not equal, test individual jacobians: if (!equal) { for (size_t i = 0; i < actual->size(); i++) { - bool i_good = assert_equal((Matrix) (expected.getA(expected.begin() + i)), - (Matrix) (actual->getA(actual->begin() + i)), tolerance); + bool i_good = + assert_equal((Matrix)(expected.getA(expected.begin() + i)), + (Matrix)(actual->getA(actual->begin() + i)), tolerance); if (!i_good) { - std::cout << "Mismatch in Jacobian " << i+1 << " (base 1), as shown above" << std::endl; + std::cout << "Mismatch in Jacobian " << i + 1 + << " (base 1), as shown above" << std::endl; } } } return equal; } -} +} // namespace internal /// \brief Check the Jacobians produced by a factor against finite differences. /// \param factor The factor to test. @@ -109,4 +114,4 @@ bool testFactorJacobians(const std::string& name_, #define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance) \ { EXPECT(gtsam::internal::testFactorJacobians(name_, factor, values, numerical_derivative_step, tolerance)); } -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/sam/tests/testBearingFactor.cpp b/gtsam/sam/tests/testBearingFactor.cpp index 17a049a1d..904bdba31 100644 --- a/gtsam/sam/tests/testBearingFactor.cpp +++ b/gtsam/sam/tests/testBearingFactor.cpp @@ -21,14 +21,13 @@ #include #include #include -#include -#include #include using namespace std; using namespace gtsam; +namespace { Key poseKey(1); Key pointKey(2); @@ -41,43 +40,18 @@ typedef BearingFactor BearingFactor3D; Unit3 measurement3D = Pose3().bearing(Point3(1, 0, 0)); // has to match values! static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5)); BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D); - -/* ************************************************************************* */ -// Export Noisemodels -// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html -BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); - -/* ************************************************************************* */ -TEST(BearingFactor, Serialization2D) { - EXPECT(serializationTestHelpers::equalsObj(factor2D)); - EXPECT(serializationTestHelpers::equalsXML(factor2D)); - EXPECT(serializationTestHelpers::equalsBinary(factor2D)); } /* ************************************************************************* */ TEST(BearingFactor, 2D) { - // Serialize the factor - std::string serialized = serializeXML(factor2D); - - // And de-serialize it - BearingFactor2D factor; - deserializeXML(serialized, factor); - // Set the linearization point Values values; values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); values.insert(pointKey, Point2(-4.0, 11.0)); - EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor2D.expression({poseKey, pointKey}), values, 1e-7, 1e-5); - EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); -} - -/* ************************************************************************* */ -TEST(BearingFactor, Serialization3D) { - EXPECT(serializationTestHelpers::equalsObj(factor3D)); - EXPECT(serializationTestHelpers::equalsXML(factor3D)); - EXPECT(serializationTestHelpers::equalsBinary(factor3D)); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor2D, values, 1e-7, 1e-5); } /* ************************************************************************* */ diff --git a/gtsam/sam/tests/testBearingRangeFactor.cpp b/gtsam/sam/tests/testBearingRangeFactor.cpp index 735358d89..0dcc227c7 100644 --- a/gtsam/sam/tests/testBearingRangeFactor.cpp +++ b/gtsam/sam/tests/testBearingRangeFactor.cpp @@ -21,14 +21,13 @@ #include #include #include -#include -#include #include using namespace std; using namespace gtsam; +namespace { Key poseKey(1); Key pointKey(2); @@ -40,43 +39,18 @@ typedef BearingRangeFactor BearingRangeFactor3D; static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(3, 0.5)); BearingRangeFactor3D factor3D(poseKey, pointKey, Pose3().bearing(Point3(1, 0, 0)), 1, model3D); - -/* ************************************************************************* */ -// Export Noisemodels -// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html -BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); - -/* ************************************************************************* */ -TEST(BearingRangeFactor, Serialization2D) { - EXPECT(serializationTestHelpers::equalsObj(factor2D)); - EXPECT(serializationTestHelpers::equalsXML(factor2D)); - EXPECT(serializationTestHelpers::equalsBinary(factor2D)); } /* ************************************************************************* */ TEST(BearingRangeFactor, 2D) { - // Serialize the factor - std::string serialized = serializeXML(factor2D); - - // And de-serialize it - BearingRangeFactor2D factor; - deserializeXML(serialized, factor); - // Set the linearization point Values values; values.insert(poseKey, Pose2(1.0, 2.0, 0.57)); values.insert(pointKey, Point2(-4.0, 11.0)); - EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor.expression({poseKey, pointKey}), + EXPECT_CORRECT_EXPRESSION_JACOBIANS(factor2D.expression({poseKey, pointKey}), values, 1e-7, 1e-5); - EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); -} - -/* ************************************************************************* */ -TEST(BearingRangeFactor, Serialization3D) { - EXPECT(serializationTestHelpers::equalsObj(factor3D)); - EXPECT(serializationTestHelpers::equalsXML(factor3D)); - EXPECT(serializationTestHelpers::equalsBinary(factor3D)); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor2D, values, 1e-7, 1e-5); } /* ************************************************************************* */ diff --git a/gtsam/sam/tests/testRangeFactor.cpp b/gtsam/sam/tests/testRangeFactor.cpp index 5f5d4f4dd..200e1236a 100644 --- a/gtsam/sam/tests/testRangeFactor.cpp +++ b/gtsam/sam/tests/testRangeFactor.cpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -32,42 +31,40 @@ using namespace std::placeholders; using namespace std; using namespace gtsam; -// Create a noise model for the pixel error -static SharedNoiseModel model(noiseModel::Unit::Create(1)); - typedef RangeFactor RangeFactor2D; typedef RangeFactor RangeFactor3D; typedef RangeFactorWithTransform RangeFactorWithTransform2D; typedef RangeFactorWithTransform RangeFactorWithTransform3D; // Keys are deliberately *not* in sorted order to test that case. +namespace { +// Create a noise model for the pixel error +static SharedNoiseModel model(noiseModel::Unit::Create(1)); + constexpr Key poseKey(2); constexpr Key pointKey(1); constexpr double measurement(10.0); -/* ************************************************************************* */ Vector factorError2D(const Pose2& pose, const Point2& point, - const RangeFactor2D& factor) { + const RangeFactor2D& factor) { return factor.evaluateError(pose, point); } -/* ************************************************************************* */ Vector factorError3D(const Pose3& pose, const Point3& point, - const RangeFactor3D& factor) { + const RangeFactor3D& factor) { return factor.evaluateError(pose, point); } -/* ************************************************************************* */ Vector factorErrorWithTransform2D(const Pose2& pose, const Point2& point, - const RangeFactorWithTransform2D& factor) { + const RangeFactorWithTransform2D& factor) { return factor.evaluateError(pose, point); } -/* ************************************************************************* */ Vector factorErrorWithTransform3D(const Pose3& pose, const Point3& point, - const RangeFactorWithTransform3D& factor) { + const RangeFactorWithTransform3D& factor) { return factor.evaluateError(pose, point); } +} // namespace /* ************************************************************************* */ TEST( RangeFactor, Constructor) { @@ -75,27 +72,6 @@ TEST( RangeFactor, Constructor) { RangeFactor3D factor3D(poseKey, pointKey, measurement, model); } -/* ************************************************************************* */ -// Export Noisemodels -// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html -BOOST_CLASS_EXPORT(gtsam::noiseModel::Unit); - -/* ************************************************************************* */ -TEST(RangeFactor, Serialization2D) { - RangeFactor2D factor2D(poseKey, pointKey, measurement, model); - EXPECT(serializationTestHelpers::equalsObj(factor2D)); - EXPECT(serializationTestHelpers::equalsXML(factor2D)); - EXPECT(serializationTestHelpers::equalsBinary(factor2D)); -} - -/* ************************************************************************* */ -TEST(RangeFactor, Serialization3D) { - RangeFactor3D factor3D(poseKey, pointKey, measurement, model); - EXPECT(serializationTestHelpers::equalsObj(factor3D)); - EXPECT(serializationTestHelpers::equalsXML(factor3D)); - EXPECT(serializationTestHelpers::equalsBinary(factor3D)); -} - /* ************************************************************************* */ TEST( RangeFactor, ConstructorWithTransform) { Pose2 body_P_sensor_2D(0.25, -0.10, -M_PI_2); @@ -142,28 +118,6 @@ TEST( RangeFactor, EqualsWithTransform ) { body_P_sensor_3D); CHECK(assert_equal(factor3D_1, factor3D_2)); } -/* ************************************************************************* */ -TEST( RangeFactor, EqualsAfterDeserializing) { - // Check that the same results are obtained after deserializing: - Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), - Point3(0.25, -0.10, 1.0)); - - RangeFactorWithTransform3D factor3D_1(poseKey, pointKey, measurement, model, - body_P_sensor_3D), factor3D_2; - - // check with Equal() trait: - gtsam::serializationTestHelpers::roundtripXML(factor3D_1, factor3D_2); - CHECK(assert_equal(factor3D_1, factor3D_2)); - - const Pose3 pose(Rot3::RzRyRx(0.2, -0.3, 1.75), Point3(1.0, 2.0, -3.0)); - const Point3 point(-2.0, 11.0, 1.0); - const Values values = {{poseKey, genericValue(pose)}, {pointKey, genericValue(point)}}; - - const Vector error_1 = factor3D_1.unwhitenedError(values); - const Vector error_2 = factor3D_2.unwhitenedError(values); - CHECK(assert_equal(error_1, error_2)); -} - /* ************************************************************************* */ TEST( RangeFactor, Error2D ) { // Create a factor @@ -411,7 +365,7 @@ TEST( RangeFactor, Camera) { /* ************************************************************************* */ // Do a test with non GTSAM types -namespace gtsam{ +namespace gtsam { template <> struct Range { typedef double result_type; @@ -421,7 +375,7 @@ struct Range { // derivatives not implemented } }; -} +} // namespace gtsam TEST(RangeFactor, NonGTSAM) { // Create a factor diff --git a/gtsam/sam/tests/testSerializationSam.cpp b/gtsam/sam/tests/testSerializationSam.cpp new file mode 100644 index 000000000..8fdd8f37e --- /dev/null +++ b/gtsam/sam/tests/testSerializationSam.cpp @@ -0,0 +1,140 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSerializationSam.cpp + * @brief All serialization test in this directory + * @author Frank Dellaert + * @date February 2022 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + +namespace { +Key poseKey(1); +Key pointKey(2); +constexpr double rangeMmeasurement(10.0); +} // namespace + +/* ************************************************************************* */ +// Export Noisemodels +// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html +BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic); +BOOST_CLASS_EXPORT(gtsam::noiseModel::Unit); + +/* ************************************************************************* */ +TEST(SerializationSam, BearingFactor2D) { + using BearingFactor2D = BearingFactor; + double measurement2D(10.0); + static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(1, 0.5)); + BearingFactor2D factor2D(poseKey, pointKey, measurement2D, model2D); + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(SerializationSam, BearingFactor3D) { + using BearingFactor3D = BearingFactor; + Unit3 measurement3D = + Pose3().bearing(Point3(1, 0, 0)); // has to match values! + static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(2, 0.5)); + BearingFactor3D factor3D(poseKey, pointKey, measurement3D, model3D); + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +namespace { +static SharedNoiseModel rangeNoiseModel(noiseModel::Unit::Create(1)); +} + +TEST(SerializationSam, RangeFactor2D) { + using RangeFactor2D = RangeFactor; + RangeFactor2D factor2D(poseKey, pointKey, rangeMmeasurement, rangeNoiseModel); + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(SerializationSam, RangeFactor3D) { + using RangeFactor3D = RangeFactor; + RangeFactor3D factor3D(poseKey, pointKey, rangeMmeasurement, rangeNoiseModel); + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +TEST(RangeFactor, EqualsAfterDeserializing) { + // Check that the same results are obtained after deserializing: + Pose3 body_P_sensor_3D(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), + Point3(0.25, -0.10, 1.0)); + RangeFactorWithTransform factor3D_1( + poseKey, pointKey, rangeMmeasurement, rangeNoiseModel, body_P_sensor_3D), + factor3D_2; + + // check with Equal() trait: + gtsam::serializationTestHelpers::roundtripXML(factor3D_1, factor3D_2); + CHECK(assert_equal(factor3D_1, factor3D_2)); + + const Pose3 pose(Rot3::RzRyRx(0.2, -0.3, 1.75), Point3(1.0, 2.0, -3.0)); + const Point3 point(-2.0, 11.0, 1.0); + const Values values = {{poseKey, genericValue(pose)}, + {pointKey, genericValue(point)}}; + + const Vector error_1 = factor3D_1.unwhitenedError(values); + const Vector error_2 = factor3D_2.unwhitenedError(values); + CHECK(assert_equal(error_1, error_2)); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization2D) { + using BearingRangeFactor2D = BearingRangeFactor; + static SharedNoiseModel model2D(noiseModel::Isotropic::Sigma(2, 0.5)); + BearingRangeFactor2D factor2D(poseKey, pointKey, 1, 2, model2D); + + EXPECT(serializationTestHelpers::equalsObj(factor2D)); + EXPECT(serializationTestHelpers::equalsXML(factor2D)); + EXPECT(serializationTestHelpers::equalsBinary(factor2D)); +} + +/* ************************************************************************* */ +TEST(BearingRangeFactor, Serialization3D) { + using BearingRangeFactor3D = BearingRangeFactor; + static SharedNoiseModel model3D(noiseModel::Isotropic::Sigma(3, 0.5)); + BearingRangeFactor3D factor3D(poseKey, pointKey, + Pose3().bearing(Point3(1, 0, 0)), 1, model3D); + EXPECT(serializationTestHelpers::equalsObj(factor3D)); + EXPECT(serializationTestHelpers::equalsXML(factor3D)); + EXPECT(serializationTestHelpers::equalsBinary(factor3D)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 1aedbf76a2b33c38b450d8c3283eb1fabc340736 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 08:57:23 -0500 Subject: [PATCH 006/116] fix check.discrete --- gtsam/discrete/tests/testDecisionTreeFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/discrete/tests/testDecisionTreeFactor.cpp b/gtsam/discrete/tests/testDecisionTreeFactor.cpp index 92145b8b7..846653c38 100644 --- a/gtsam/discrete/tests/testDecisionTreeFactor.cpp +++ b/gtsam/discrete/tests/testDecisionTreeFactor.cpp @@ -107,7 +107,7 @@ TEST(DecisionTreeFactor, enumerate) { } /* ************************************************************************* */ -TEST(DiscreteFactorGraph, DotWithNames) { +TEST(DecisionTreeFactor, DotWithNames) { DiscreteKey A(12, 3), B(5, 2); DecisionTreeFactor f(A & B, "1 2 3 4 5 6"); auto formatter = [](Key key) { return key == 12 ? "A" : "B"; }; From 8e33e96efaab9885f9b11b3be10adee8d2b2e6ab Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 09:30:59 -0500 Subject: [PATCH 007/116] Fix check.slam --- gtsam/slam/tests/PinholeFactor.h | 52 +++++++++ gtsam/slam/tests/smartFactorScenarios.h | 88 +++++++-------- gtsam/slam/tests/testSerializationSlam.cpp | 104 ++++++++++++++++++ gtsam/slam/tests/testSmartFactorBase.cpp | 91 ++++----------- .../slam/tests/testSmartProjectionFactor.cpp | 32 ++---- .../tests/testSmartProjectionPoseFactor.cpp | 44 +------- 6 files changed, 235 insertions(+), 176 deletions(-) create mode 100644 gtsam/slam/tests/PinholeFactor.h create mode 100644 gtsam/slam/tests/testSerializationSlam.cpp diff --git a/gtsam/slam/tests/PinholeFactor.h b/gtsam/slam/tests/PinholeFactor.h new file mode 100644 index 000000000..35500ca35 --- /dev/null +++ b/gtsam/slam/tests/PinholeFactor.h @@ -0,0 +1,52 @@ +/* ---------------------------------------------------------------------------- + + * 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 PinholeFactor.h + * @brief helper class for tests + * @author Frank Dellaert + * @date February 2022 + */ + +#pragma once + +namespace gtsam { +template +struct traits; +} + +#include +#include +#include +#include + +namespace gtsam { + +class PinholeFactor : public SmartFactorBase > { + public: + typedef SmartFactorBase > Base; + PinholeFactor() {} + PinholeFactor(const SharedNoiseModel& sharedNoiseModel, + boost::optional body_P_sensor = boost::none, + size_t expectedNumberCameras = 10) + : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} + double error(const Values& values) const override { return 0.0; } + boost::shared_ptr linearize( + const Values& values) const override { + return boost::shared_ptr(new JacobianFactor()); + } +}; + +/// traits +template <> +struct traits : public Testable {}; + +} // namespace gtsam diff --git a/gtsam/slam/tests/smartFactorScenarios.h b/gtsam/slam/tests/smartFactorScenarios.h index 66be08c67..eff942799 100644 --- a/gtsam/slam/tests/smartFactorScenarios.h +++ b/gtsam/slam/tests/smartFactorScenarios.h @@ -29,6 +29,7 @@ using namespace std; using namespace gtsam; +namespace { // three landmarks ~5 meters infront of camera Point3 landmark1(5, 0.5, 1.2); Point3 landmark2(5, -0.5, 1.2); @@ -48,23 +49,24 @@ static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); static double fov = 60; // degrees static size_t w = 640, h = 480; +} /* ************************************************************************* */ // default Cal3_S2 cameras namespace vanilla { typedef PinholeCamera Camera; typedef SmartProjectionFactor SmartFactor; -static Cal3_S2 K(fov, w, h); -static Cal3_S2 K2(1500, 1200, 0, w, h); -Camera level_camera(level_pose, K2); -Camera level_camera_right(pose_right, K2); -Point2 level_uv = level_camera.project(landmark1); -Point2 level_uv_right = level_camera_right.project(landmark1); -Camera cam1(level_pose, K2); -Camera cam2(pose_right, K2); -Camera cam3(pose_above, K2); +static const Cal3_S2 K(fov, w, h); +static const Cal3_S2 K2(1500, 1200, 0, w, h); +static const Camera level_camera(level_pose, K2); +static const Camera level_camera_right(pose_right, K2); +static const Point2 level_uv = level_camera.project(landmark1); +static const Point2 level_uv_right = level_camera_right.project(landmark1); +static const Camera cam1(level_pose, K2); +static const Camera cam2(pose_right, K2); +static const Camera cam3(pose_above, K2); typedef GeneralSFMFactor SFMFactor; -SmartProjectionParams params; +static const SmartProjectionParams params; } // namespace vanilla /* ************************************************************************* */ @@ -74,12 +76,12 @@ typedef PinholePose Camera; typedef CameraSet Cameras; typedef SmartProjectionPoseFactor SmartFactor; typedef SmartProjectionRigFactor SmartRigFactor; -static Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); -Camera level_camera(level_pose, sharedK); -Camera level_camera_right(pose_right, sharedK); -Camera cam1(level_pose, sharedK); -Camera cam2(pose_right, sharedK); -Camera cam3(pose_above, sharedK); +static const Cal3_S2::shared_ptr sharedK(new Cal3_S2(fov, w, h)); +static const Camera level_camera(level_pose, sharedK); +static const Camera level_camera_right(pose_right, sharedK); +static const Camera cam1(level_pose, sharedK); +static const Camera cam2(pose_right, sharedK); +static const Camera cam3(pose_above, sharedK); } // namespace vanillaPose /* ************************************************************************* */ @@ -89,12 +91,12 @@ typedef PinholePose Camera; typedef CameraSet Cameras; typedef SmartProjectionPoseFactor SmartFactor; typedef SmartProjectionRigFactor SmartRigFactor; -static Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); -Camera level_camera(level_pose, sharedK2); -Camera level_camera_right(pose_right, sharedK2); -Camera cam1(level_pose, sharedK2); -Camera cam2(pose_right, sharedK2); -Camera cam3(pose_above, sharedK2); +static const Cal3_S2::shared_ptr sharedK2(new Cal3_S2(1500, 1200, 0, 640, 480)); +static const Camera level_camera(level_pose, sharedK2); +static const Camera level_camera_right(pose_right, sharedK2); +static const Camera cam1(level_pose, sharedK2); +static const Camera cam2(pose_right, sharedK2); +static const Camera cam3(pose_above, sharedK2); } // namespace vanillaPose2 /* *************************************************************************/ @@ -103,15 +105,15 @@ namespace bundler { typedef PinholeCamera Camera; typedef CameraSet Cameras; typedef SmartProjectionFactor SmartFactor; -static Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); -Camera level_camera(level_pose, K); -Camera level_camera_right(pose_right, K); -Point2 level_uv = level_camera.project(landmark1); -Point2 level_uv_right = level_camera_right.project(landmark1); -Pose3 pose1 = level_pose; -Camera cam1(level_pose, K); -Camera cam2(pose_right, K); -Camera cam3(pose_above, K); +static const Cal3Bundler K(500, 1e-3, 1e-3, 0, 0); +static const Camera level_camera(level_pose, K); +static const Camera level_camera_right(pose_right, K); +static const Point2 level_uv = level_camera.project(landmark1); +static const Point2 level_uv_right = level_camera_right.project(landmark1); +static const Pose3 pose1 = level_pose; +static const Camera cam1(level_pose, K); +static const Camera cam2(pose_right, K); +static const Camera cam3(pose_above, K); typedef GeneralSFMFactor SFMFactor; } // namespace bundler @@ -122,14 +124,14 @@ typedef PinholePose Camera; typedef CameraSet Cameras; typedef SmartProjectionPoseFactor SmartFactor; typedef SmartProjectionRigFactor SmartRigFactor; -static boost::shared_ptr sharedBundlerK(new Cal3Bundler(500, 1e-3, +static const boost::shared_ptr sharedBundlerK(new Cal3Bundler(500, 1e-3, 1e-3, 1000, 2000)); -Camera level_camera(level_pose, sharedBundlerK); -Camera level_camera_right(pose_right, sharedBundlerK); -Camera cam1(level_pose, sharedBundlerK); -Camera cam2(pose_right, sharedBundlerK); -Camera cam3(pose_above, sharedBundlerK); +static const Camera level_camera(level_pose, sharedBundlerK); +static const Camera level_camera_right(pose_right, sharedBundlerK); +static const Camera cam1(level_pose, sharedBundlerK); +static const Camera cam2(pose_right, sharedBundlerK); +static const Camera cam3(pose_above, sharedBundlerK); } // namespace bundlerPose /* ************************************************************************* */ @@ -138,12 +140,12 @@ namespace sphericalCamera { typedef SphericalCamera Camera; typedef CameraSet Cameras; typedef SmartProjectionRigFactor SmartFactorP; -static EmptyCal::shared_ptr emptyK(new EmptyCal()); -Camera level_camera(level_pose); -Camera level_camera_right(pose_right); -Camera cam1(level_pose); -Camera cam2(pose_right); -Camera cam3(pose_above); +static const EmptyCal::shared_ptr emptyK(new EmptyCal()); +static const Camera level_camera(level_pose); +static const Camera level_camera_right(pose_right); +static const Camera cam1(level_pose); +static const Camera cam2(pose_right); +static const Camera cam3(pose_above); } // namespace sphericalCamera /* *************************************************************************/ diff --git a/gtsam/slam/tests/testSerializationSlam.cpp b/gtsam/slam/tests/testSerializationSlam.cpp new file mode 100644 index 000000000..02b0e3191 --- /dev/null +++ b/gtsam/slam/tests/testSerializationSlam.cpp @@ -0,0 +1,104 @@ +/* ---------------------------------------------------------------------------- + + * 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 testSerializationSlam.cpp + * @brief all serialization tests in this directory + * @author Frank Dellaert + * @date February 2022 + */ + +#include +#include +#include +#include + +#include +#include + +#include "smartFactorScenarios.h" +#include "PinholeFactor.h" + +namespace { +static const double rankTol = 1.0; +static const double sigma = 0.1; +static SharedIsotropic model(noiseModel::Isotropic::Sigma(2, sigma)); +} // namespace + +/* ************************************************************************* */ +BOOST_CLASS_EXPORT_GUID(noiseModel::Constrained, "gtsam_noiseModel_Constrained") +BOOST_CLASS_EXPORT_GUID(noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") +BOOST_CLASS_EXPORT_GUID(noiseModel::Gaussian, "gtsam_noiseModel_Gaussian") +BOOST_CLASS_EXPORT_GUID(noiseModel::Unit, "gtsam_noiseModel_Unit") +BOOST_CLASS_EXPORT_GUID(noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") +BOOST_CLASS_EXPORT_GUID(SharedNoiseModel, "gtsam_SharedNoiseModel") +BOOST_CLASS_EXPORT_GUID(SharedDiagonal, "gtsam_SharedDiagonal") + +/* ************************************************************************* */ +TEST(SmartFactorBase, serialize) { + using namespace serializationTestHelpers; + PinholeFactor factor(unit2); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +/* ************************************************************************* */ +TEST(SerializationSlam, SmartProjectionFactor) { + using namespace vanilla; + using namespace serializationTestHelpers; + SmartFactor factor(unit2); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +/* ************************************************************************* */ +TEST(SerializationSlam, SmartProjectionPoseFactor) { + using namespace vanillaPose; + using namespace serializationTestHelpers; + SmartProjectionParams params; + params.setRankTolerance(rankTol); + SmartFactor factor(model, sharedK, params); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +TEST(SerializationSlam, SmartProjectionPoseFactor2) { + using namespace vanillaPose; + using namespace serializationTestHelpers; + SmartProjectionParams params; + params.setRankTolerance(rankTol); + Pose3 bts; + SmartFactor factor(model, sharedK, bts, params); + + // insert some measurments + KeyVector key_view; + Point2Vector meas_view; + key_view.push_back(Symbol('x', 1)); + meas_view.push_back(Point2(10, 10)); + factor.add(meas_view, key_view); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index ba46dce8d..544fd3264 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -16,47 +16,29 @@ * @date Feb 2015 */ -#include -#include -#include #include +#include +#include +#include +#include +#include -using namespace std; +#include "PinholeFactor.h" + +namespace { using namespace gtsam; - static SharedNoiseModel unit2(noiseModel::Unit::Create(2)); static SharedNoiseModel unit3(noiseModel::Unit::Create(3)); +} // namespace -/* ************************************************************************* */ -#include -#include +using namespace std; namespace gtsam { -class PinholeFactor: public SmartFactorBase > { -public: - typedef SmartFactorBase > Base; - PinholeFactor() {} - PinholeFactor(const SharedNoiseModel& sharedNoiseModel, - boost::optional body_P_sensor = boost::none, - size_t expectedNumberCameras = 10) - : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} - double error(const Values& values) const override { return 0.0; } - boost::shared_ptr linearize( - const Values& values) const override { - return boost::shared_ptr(new JacobianFactor()); - } -}; - -/// traits -template<> -struct traits : public Testable {}; -} - TEST(SmartFactorBase, Pinhole) { - PinholeFactor f= PinholeFactor(unit2); - f.add(Point2(0,0), 1); - f.add(Point2(0,0), 2); + PinholeFactor f = PinholeFactor(unit2); + f.add(Point2(0, 0), 1); + f.add(Point2(0, 0), 2); EXPECT_LONGS_EQUAL(2 * 2, f.dim()); } @@ -71,7 +53,7 @@ TEST(SmartFactorBase, PinholeWithSensor) { // Camera coordinates in world frame. Pose3 wTc = world_P_body * body_P_sensor; cameras.push_back(PinholeCamera(wTc)); - + // Simple point to project slightly off image center Point3 p(0, 0, 10); Point2 measurement = cameras[0].project(p); @@ -81,9 +63,10 @@ TEST(SmartFactorBase, PinholeWithSensor) { Matrix E; Vector error = f.unwhitenedError(cameras, p, Fs, E); - Vector expectedError = Vector::Zero(2); + Vector expectedError = Vector::Zero(2); Matrix29 expectedFs; - expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, 0, 0, 0, 0; + expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, + 0, 0, 0, 0; Matrix23 expectedE; expectedE << 0.1, 0, 0.01, 0, 0.1, 0; @@ -94,20 +77,13 @@ TEST(SmartFactorBase, PinholeWithSensor) { EXPECT(assert_equal(expectedE, E)); } -/* ************************************************************************* */ -#include - -namespace gtsam { - -class StereoFactor: public SmartFactorBase { -public: +class StereoFactor : public SmartFactorBase { + public: typedef SmartFactorBase Base; StereoFactor() {} - StereoFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { - } - double error(const Values& values) const override { - return 0.0; - } + StereoFactor(const SharedNoiseModel& sharedNoiseModel) + : Base(sharedNoiseModel) {} + double error(const Values& values) const override { return 0.0; } boost::shared_ptr linearize( const Values& values) const override { return boost::shared_ptr(new JacobianFactor()); @@ -115,9 +91,8 @@ public: }; /// traits -template<> +template <> struct traits : public Testable {}; -} TEST(SmartFactorBase, Stereo) { StereoFactor f(unit3); @@ -125,24 +100,7 @@ TEST(SmartFactorBase, Stereo) { f.add(StereoPoint2(), 2); EXPECT_LONGS_EQUAL(2 * 3, f.dim()); } - -/* ************************************************************************* */ -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal") - -TEST(SmartFactorBase, serialize) { - using namespace gtsam::serializationTestHelpers; - PinholeFactor factor(unit2); - - EXPECT(equalsObj(factor)); - EXPECT(equalsXML(factor)); - EXPECT(equalsBinary(factor)); -} +} // namespace gtsam /* ************************************************************************* */ int main() { @@ -150,4 +108,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - diff --git a/gtsam/slam/tests/testSmartProjectionFactor.cpp b/gtsam/slam/tests/testSmartProjectionFactor.cpp index 133f81511..ecdb5287f 100644 --- a/gtsam/slam/tests/testSmartProjectionFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionFactor.cpp @@ -22,18 +22,19 @@ #include "smartFactorScenarios.h" #include #include -#include #include #include #include using namespace boost::assign; +namespace { static const bool isDebugTest = false; static const Symbol l1('l', 1), l2('l', 2), l3('l', 3); static const Key c1 = 1, c2 = 2, c3 = 3; static const Point2 measurement1(323.0, 240.0); static const double rankTol = 1.0; +} template PinholeCamera perturbCameraPoseAndCalibration( @@ -70,8 +71,9 @@ TEST(SmartProjectionFactor, Constructor) { /* ************************************************************************* */ TEST(SmartProjectionFactor, Constructor2) { using namespace vanilla; - params.setRankTolerance(rankTol); - SmartFactor factor1(unit2, params); + auto myParams = params; + myParams.setRankTolerance(rankTol); + SmartFactor factor1(unit2, myParams); } /* ************************************************************************* */ @@ -84,8 +86,9 @@ TEST(SmartProjectionFactor, Constructor3) { /* ************************************************************************* */ TEST(SmartProjectionFactor, Constructor4) { using namespace vanilla; - params.setRankTolerance(rankTol); - SmartFactor factor1(unit2, params); + auto myParams = params; + myParams.setRankTolerance(rankTol); + SmartFactor factor1(unit2, myParams); factor1.add(measurement1, c1); } @@ -810,25 +813,6 @@ TEST(SmartProjectionFactor, implicitJacobianFactor ) { EXPECT(assert_equal(yActual, yExpected, 1e-7)); } -/* ************************************************************************* */ -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal") - -TEST(SmartProjectionFactor, serialize) { - using namespace vanilla; - using namespace gtsam::serializationTestHelpers; - SmartFactor factor(unit2); - - EXPECT(equalsObj(factor)); - EXPECT(equalsXML(factor)); - EXPECT(equalsBinary(factor)); -} - /* ************************************************************************* */ int main() { TestResult tr; diff --git a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp index f3706fa02..5c38233c1 100644 --- a/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp +++ b/gtsam/slam/tests/testSmartProjectionPoseFactor.cpp @@ -24,7 +24,6 @@ #include #include #include -#include #include #include #include @@ -32,6 +31,7 @@ using namespace boost::assign; using namespace std::placeholders; +namespace { static const double rankTol = 1.0; // Create a noise model for the pixel error static const double sigma = 0.1; @@ -51,6 +51,7 @@ static Point2 measurement1(323.0, 240.0); LevenbergMarquardtParams lmParams; // Make more verbose like so (in tests): // lmParams.verbosityLM = LevenbergMarquardtParams::SUMMARY; +} /* ************************************************************************* */ TEST( SmartProjectionPoseFactor, Constructor) { @@ -1332,47 +1333,6 @@ TEST( SmartProjectionPoseFactor, Cal3BundlerRotationOnly ) { values.at(x3))); } -/* ************************************************************************* */ -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal") - -TEST(SmartProjectionPoseFactor, serialize) { - using namespace vanillaPose; - using namespace gtsam::serializationTestHelpers; - SmartProjectionParams params; - params.setRankTolerance(rankTol); - SmartFactor factor(model, sharedK, params); - - EXPECT(equalsObj(factor)); - EXPECT(equalsXML(factor)); - EXPECT(equalsBinary(factor)); -} - -TEST(SmartProjectionPoseFactor, serialize2) { - using namespace vanillaPose; - using namespace gtsam::serializationTestHelpers; - SmartProjectionParams params; - params.setRankTolerance(rankTol); - Pose3 bts; - SmartFactor factor(model, sharedK, bts, params); - - // insert some measurments - KeyVector key_view; - Point2Vector meas_view; - key_view.push_back(Symbol('x', 1)); - meas_view.push_back(Point2(10, 10)); - factor.add(meas_view, key_view); - - EXPECT(equalsObj(factor)); - EXPECT(equalsXML(factor)); - EXPECT(equalsBinary(factor)); -} - /* ************************************************************************* */ int main() { TestResult tr; From f71f12498db60837eda7bb1e76d01e846273b393 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 09:39:22 -0500 Subject: [PATCH 008/116] fixed check.navigation --- gtsam/navigation/tests/testAttitudeFactor.cpp | 29 ----------- gtsam/navigation/tests/testMagFactor.cpp | 5 +- gtsam/navigation/tests/testMagPoseFactor.cpp | 7 +-- ...on.cpp => testSerializationNavigation.cpp} | 49 ++++++++++++++----- 4 files changed, 43 insertions(+), 47 deletions(-) rename gtsam/navigation/tests/{testImuFactorSerialization.cpp => testSerializationNavigation.cpp} (63%) diff --git a/gtsam/navigation/tests/testAttitudeFactor.cpp b/gtsam/navigation/tests/testAttitudeFactor.cpp index 9304e8412..26d793528 100644 --- a/gtsam/navigation/tests/testAttitudeFactor.cpp +++ b/gtsam/navigation/tests/testAttitudeFactor.cpp @@ -19,8 +19,6 @@ #include #include #include -#include -#include #include #include @@ -63,22 +61,6 @@ TEST( Rot3AttitudeFactor, Constructor ) { EXPECT(assert_equal(expectedH, actualH, 1e-8)); } -/* ************************************************************************* */ -// Export Noisemodels -// See http://www.boost.org/doc/libs/1_32_0/libs/serialization/doc/special.html -BOOST_CLASS_EXPORT(gtsam::noiseModel::Isotropic) - -/* ************************************************************************* */ -TEST(Rot3AttitudeFactor, Serialization) { - Unit3 nDown(0, 0, -1); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); - Rot3AttitudeFactor factor(0, nDown, model); - - EXPECT(serializationTestHelpers::equalsObj(factor)); - EXPECT(serializationTestHelpers::equalsXML(factor)); - EXPECT(serializationTestHelpers::equalsBinary(factor)); -} - /* ************************************************************************* */ TEST(Rot3AttitudeFactor, CopyAndMove) { Unit3 nDown(0, 0, -1); @@ -129,17 +111,6 @@ TEST( Pose3AttitudeFactor, Constructor ) { EXPECT(assert_equal(expectedH, actualH, 1e-8)); } -/* ************************************************************************* */ -TEST(Pose3AttitudeFactor, Serialization) { - Unit3 nDown(0, 0, -1); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); - Pose3AttitudeFactor factor(0, nDown, model); - - EXPECT(serializationTestHelpers::equalsObj(factor)); - EXPECT(serializationTestHelpers::equalsXML(factor)); - EXPECT(serializationTestHelpers::equalsBinary(factor)); -} - /* ************************************************************************* */ TEST(Pose3AttitudeFactor, CopyAndMove) { Unit3 nDown(0, 0, -1); diff --git a/gtsam/navigation/tests/testMagFactor.cpp b/gtsam/navigation/tests/testMagFactor.cpp index 85447facd..e2a623710 100644 --- a/gtsam/navigation/tests/testMagFactor.cpp +++ b/gtsam/navigation/tests/testMagFactor.cpp @@ -31,7 +31,7 @@ using namespace std; using namespace gtsam; using namespace GeographicLib; -// ************************************************************************* +namespace { // Convert from Mag to ENU // ENU Origin is where the plane was in hold next to runway // const double lat0 = 33.86998, lon0 = -84.30626, h0 = 274; @@ -51,10 +51,11 @@ Point3 bias(10, -10, 50); Point3 scaled = scale * nM; Point3 measured = nRb.inverse() * (scale * nM) + bias; -double s(scale * nM.norm()); +double s(scale* nM.norm()); Unit3 dir(nM); SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25); +} // namespace using boost::none; diff --git a/gtsam/navigation/tests/testMagPoseFactor.cpp b/gtsam/navigation/tests/testMagPoseFactor.cpp index 204c1d38f..e10409f4c 100644 --- a/gtsam/navigation/tests/testMagPoseFactor.cpp +++ b/gtsam/navigation/tests/testMagPoseFactor.cpp @@ -20,7 +20,7 @@ using namespace std::placeholders; using namespace gtsam; -// ***************************************************************************** +namespace { // Magnetic field in the nav frame (NED), with units of nT. Point3 nM(22653.29982, -1956.83010, 44202.47862); @@ -51,8 +51,9 @@ SharedNoiseModel model3 = noiseModel::Isotropic::Sigma(3, 0.25); // Make up a rotation and offset of the sensor in the body frame. Pose2 body_P2_sensor(Rot2(-0.30), Point2(1.0, -2.0)); -Pose3 body_P3_sensor(Rot3::RzRyRx(Vector3(1.5, 0.9, -1.15)), Point3(-0.1, 0.2, 0.3)); -// ***************************************************************************** +Pose3 body_P3_sensor(Rot3::RzRyRx(Vector3(1.5, 0.9, -1.15)), + Point3(-0.1, 0.2, 0.3)); +} // namespace // ***************************************************************************** TEST(MagPoseFactor, Constructors) { diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testSerializationNavigation.cpp similarity index 63% rename from gtsam/navigation/tests/testImuFactorSerialization.cpp rename to gtsam/navigation/tests/testSerializationNavigation.cpp index e72b1fb5b..63d2606a1 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testSerializationNavigation.cpp @@ -10,17 +10,19 @@ * -------------------------------------------------------------------------- */ /** - * @file testImuFactor.cpp - * @brief Unit test for ImuFactor + * @file testSerializationNavigation.cpp + * @brief serialization tests for navigation * @author Luca Carlone * @author Frank Dellaert * @author Richard Roberts * @author Stephen Williams * @author Varun Agrawal + * @date February 2022 */ #include #include +#include #include #include @@ -30,17 +32,13 @@ using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, - "gtsam_noiseModel_Constrained") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, - "gtsam_noiseModel_Diagonal") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, - "gtsam_noiseModel_Gaussian") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit") -BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, - "gtsam_noiseModel_Isotropic") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel") -BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal") +BOOST_CLASS_EXPORT_GUID(noiseModel::Constrained, "gtsam_noiseModel_Constrained") +BOOST_CLASS_EXPORT_GUID(noiseModel::Diagonal, "gtsam_noiseModel_Diagonal") +BOOST_CLASS_EXPORT_GUID(noiseModel::Gaussian, "gtsam_noiseModel_Gaussian") +BOOST_CLASS_EXPORT_GUID(noiseModel::Unit, "gtsam_noiseModel_Unit") +BOOST_CLASS_EXPORT_GUID(noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") +BOOST_CLASS_EXPORT_GUID(SharedNoiseModel, "gtsam_SharedNoiseModel") +BOOST_CLASS_EXPORT_GUID(SharedDiagonal, "gtsam_SharedDiagonal") template P getPreintegratedMeasurements() { @@ -69,6 +67,7 @@ P getPreintegratedMeasurements() { return pim; } +/* ************************************************************************* */ TEST(ImuFactor, serialization) { auto pim = getPreintegratedMeasurements(); @@ -83,6 +82,7 @@ TEST(ImuFactor, serialization) { EXPECT(equalsBinary(factor)); } +/* ************************************************************************* */ TEST(ImuFactor2, serialization) { auto pim = getPreintegratedMeasurements(); @@ -93,6 +93,7 @@ TEST(ImuFactor2, serialization) { EXPECT(equalsBinary(factor)); } +/* ************************************************************************* */ TEST(CombinedImuFactor, Serialization) { auto pim = getPreintegratedMeasurements(); @@ -107,6 +108,28 @@ TEST(CombinedImuFactor, Serialization) { EXPECT(equalsBinary(factor)); } +/* ************************************************************************* */ +TEST(Rot3AttitudeFactor, Serialization) { + Unit3 nDown(0, 0, -1); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); + Rot3AttitudeFactor factor(0, nDown, model); + + EXPECT(serializationTestHelpers::equalsObj(factor)); + EXPECT(serializationTestHelpers::equalsXML(factor)); + EXPECT(serializationTestHelpers::equalsBinary(factor)); +} + +/* ************************************************************************* */ +TEST(Pose3AttitudeFactor, Serialization) { + Unit3 nDown(0, 0, -1); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(2, 0.25); + Pose3AttitudeFactor factor(0, nDown, model); + + EXPECT(serializationTestHelpers::equalsObj(factor)); + EXPECT(serializationTestHelpers::equalsXML(factor)); + EXPECT(serializationTestHelpers::equalsBinary(factor)); +} + /* ************************************************************************* */ int main() { TestResult tr; From 65a3928d0ae47443e548941ec67217a8b051aa1d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 09:40:41 -0500 Subject: [PATCH 009/116] fixed check.basis --- gtsam/basis/tests/testChebyshev.cpp | 3 ++- gtsam/basis/tests/testChebyshev2.cpp | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/basis/tests/testChebyshev.cpp b/gtsam/basis/tests/testChebyshev.cpp index 64c925886..7d7f9323d 100644 --- a/gtsam/basis/tests/testChebyshev.cpp +++ b/gtsam/basis/tests/testChebyshev.cpp @@ -25,9 +25,10 @@ using namespace std; using namespace gtsam; +namespace { auto model = noiseModel::Unit::Create(1); - const size_t N = 3; +} // namespace //****************************************************************************** TEST(Chebyshev, Chebyshev1) { diff --git a/gtsam/basis/tests/testChebyshev2.cpp b/gtsam/basis/tests/testChebyshev2.cpp index 4cee70daf..6fafc0ccf 100644 --- a/gtsam/basis/tests/testChebyshev2.cpp +++ b/gtsam/basis/tests/testChebyshev2.cpp @@ -27,9 +27,11 @@ using namespace std; using namespace gtsam; using namespace boost::placeholders; +namespace { noiseModel::Diagonal::shared_ptr model = noiseModel::Unit::Create(1); const size_t N = 32; +} // namespace //****************************************************************************** TEST(Chebyshev2, Point) { From 3d6a7bf970a1e1a28f269a80ad86449ed0bd7604 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 09:43:12 -0500 Subject: [PATCH 010/116] Fix more stuff in check.slam --- .../testSmartStereoProjectionFactorPP.cpp | 21 ++++++++++++------- .../testSmartStereoProjectionPoseFactor.cpp | 19 ++++++++++------- 2 files changed, 24 insertions(+), 16 deletions(-) diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionFactorPP.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionFactorPP.cpp index 61836d098..c71c19038 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionFactorPP.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionFactorPP.cpp @@ -31,12 +31,13 @@ using namespace std; using namespace boost::assign; using namespace gtsam; +namespace { // make a realistic calibration matrix static double b = 1; static Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fov, w, h, b)); -static Cal3_S2Stereo::shared_ptr K2( - new Cal3_S2Stereo(1500, 1200, 0, 640, 480, b)); +static Cal3_S2Stereo::shared_ptr K2(new Cal3_S2Stereo(1500, 1200, 0, 640, 480, + b)); static SmartStereoProjectionParams params; @@ -45,8 +46,8 @@ static SmartStereoProjectionParams params; static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1)); // Convenience for named keys -using symbol_shorthand::X; using symbol_shorthand::L; +using symbol_shorthand::X; // tests data static Symbol x1('X', 1); @@ -59,16 +60,19 @@ static Symbol body_P_cam3_key('P', 3); static Key poseKey1(x1); static Key poseExtrinsicKey1(body_P_cam1_key); static Key poseExtrinsicKey2(body_P_cam2_key); -static StereoPoint2 measurement1(323.0, 300.0, 240.0); //potentially use more reasonable measurement value? -static StereoPoint2 measurement2(350.0, 200.0, 240.0); //potentially use more reasonable measurement value? +static StereoPoint2 measurement1( + 323.0, 300.0, 240.0); // potentially use more reasonable measurement value? +static StereoPoint2 measurement2( + 350.0, 200.0, 240.0); // potentially use more reasonable measurement value? static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), - Point3(0.25, -0.10, 1.0)); + Point3(0.25, -0.10, 1.0)); static double missing_uR = std::numeric_limits::quiet_NaN(); vector stereo_projectToMultipleCameras(const StereoCamera& cam1, - const StereoCamera& cam2, const StereoCamera& cam3, Point3 landmark) { - + const StereoCamera& cam2, + const StereoCamera& cam3, + Point3 landmark) { vector measurements_cam; StereoPoint2 cam1_uv1 = cam1.project(landmark); @@ -82,6 +86,7 @@ vector stereo_projectToMultipleCameras(const StereoCamera& cam1, } LevenbergMarquardtParams lm_params; +} // namespace /* ************************************************************************* */ TEST( SmartStereoProjectionFactorPP, params) { diff --git a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp index a0bfc3649..fc56b1a9f 100644 --- a/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartStereoProjectionPoseFactor.cpp @@ -32,13 +32,13 @@ using namespace std; using namespace boost::assign; using namespace gtsam; +namespace { // make a realistic calibration matrix static double b = 1; static Cal3_S2Stereo::shared_ptr K(new Cal3_S2Stereo(fov, w, h, b)); -static Cal3_S2Stereo::shared_ptr K2( - new Cal3_S2Stereo(1500, 1200, 0, 640, 480, b)); - +static Cal3_S2Stereo::shared_ptr K2(new Cal3_S2Stereo(1500, 1200, 0, 640, 480, + b)); static SmartStereoProjectionParams params; @@ -47,8 +47,8 @@ static SmartStereoProjectionParams params; static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.1)); // Convenience for named keys -using symbol_shorthand::X; using symbol_shorthand::L; +using symbol_shorthand::X; // tests data static Symbol x1('X', 1); @@ -56,15 +56,17 @@ static Symbol x2('X', 2); static Symbol x3('X', 3); static Key poseKey1(x1); -static StereoPoint2 measurement1(323.0, 300.0, 240.0); //potentially use more reasonable measurement value? +static StereoPoint2 measurement1( + 323.0, 300.0, 240.0); // potentially use more reasonable measurement value? static Pose3 body_P_sensor1(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), - Point3(0.25, -0.10, 1.0)); + Point3(0.25, -0.10, 1.0)); static double missing_uR = std::numeric_limits::quiet_NaN(); vector stereo_projectToMultipleCameras(const StereoCamera& cam1, - const StereoCamera& cam2, const StereoCamera& cam3, Point3 landmark) { - + const StereoCamera& cam2, + const StereoCamera& cam3, + Point3 landmark) { vector measurements_cam; StereoPoint2 cam1_uv1 = cam1.project(landmark); @@ -78,6 +80,7 @@ vector stereo_projectToMultipleCameras(const StereoCamera& cam1, } LevenbergMarquardtParams lm_params; +} // namespace /* ************************************************************************* */ TEST( SmartStereoProjectionPoseFactor, params) { From c979a6f1364aeeac43c559bed956f6bcfdbb7199 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 13:07:26 -0500 Subject: [PATCH 011/116] use anonymous namespace --- gtsam/geometry/tests/testPose2.cpp | 10 ++-------- gtsam/geometry/tests/testQuaternion.cpp | 10 ++-------- gtsam/geometry/tests/testRot2.cpp | 7 ++----- gtsam/geometry/tests/testRot3.cpp | 10 ++-------- gtsam/geometry/tests/testSO3.cpp | 16 ++-------------- gtsam/geometry/tests/testSO4.cpp | 21 ++------------------- 6 files changed, 12 insertions(+), 62 deletions(-) diff --git a/gtsam/geometry/tests/testPose2.cpp b/gtsam/geometry/tests/testPose2.cpp index c199a7af0..0df858aa8 100644 --- a/gtsam/geometry/tests/testPose2.cpp +++ b/gtsam/geometry/tests/testPose2.cpp @@ -796,16 +796,14 @@ TEST(Pose2, align_4) { } //****************************************************************************** -namespace pose2_example { +namespace { Pose2 id; Pose2 T1(M_PI / 4.0, Point2(sqrt(0.5), sqrt(0.5))); Pose2 T2(M_PI / 2.0, Point2(0.0, 2.0)); -} // namespace pose2_example +} // namespace //****************************************************************************** TEST(Pose2, Invariants) { - using namespace pose2_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -819,8 +817,6 @@ TEST(Pose2, Invariants) { //****************************************************************************** TEST(Pose2, LieGroupDerivatives) { - using namespace pose2_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -829,8 +825,6 @@ TEST(Pose2, LieGroupDerivatives) { //****************************************************************************** TEST(Pose2, ChartDerivatives) { - using namespace pose2_example; - CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); CHECK_CHART_DERIVATIVES(T2, id); diff --git a/gtsam/geometry/tests/testQuaternion.cpp b/gtsam/geometry/tests/testQuaternion.cpp index 88548d15e..281c71f7c 100644 --- a/gtsam/geometry/tests/testQuaternion.cpp +++ b/gtsam/geometry/tests/testQuaternion.cpp @@ -102,17 +102,15 @@ TEST(Quaternion , Inverse) { } //****************************************************************************** -namespace q_example { +namespace { Vector3 Q_z_axis(0, 0, 1); Q id(Eigen::AngleAxisd(0, Q_z_axis)); Q R1(Eigen::AngleAxisd(1, Q_z_axis)); Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0))); -} // namespace q_example +} // namespace //****************************************************************************** TEST(Quaternion, Invariants) { - using namespace q_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -126,8 +124,6 @@ TEST(Quaternion, Invariants) { //****************************************************************************** TEST(Quaternion, LieGroupDerivatives) { - using namespace q_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -136,8 +132,6 @@ TEST(Quaternion, LieGroupDerivatives) { //****************************************************************************** TEST(Quaternion, ChartDerivatives) { - using namespace q_example; - CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); diff --git a/gtsam/geometry/tests/testRot2.cpp b/gtsam/geometry/tests/testRot2.cpp index f08f3e2a5..5a087edcd 100644 --- a/gtsam/geometry/tests/testRot2.cpp +++ b/gtsam/geometry/tests/testRot2.cpp @@ -156,15 +156,14 @@ TEST( Rot2, relativeBearing ) } //****************************************************************************** -namespace rot2_example { +namespace { Rot2 id; Rot2 T1(0.1); Rot2 T2(0.2); -} // namespace rot2_example +} // namespace //****************************************************************************** TEST(Rot2, Invariants) { - using namespace rot2_example; EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -178,7 +177,6 @@ TEST(Rot2, Invariants) { //****************************************************************************** TEST(Rot2, LieGroupDerivatives) { - using namespace rot2_example; CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -187,7 +185,6 @@ TEST(Rot2, LieGroupDerivatives) { //****************************************************************************** TEST(Rot2, ChartDerivatives) { - using namespace rot2_example; CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); CHECK_CHART_DERIVATIVES(T2, id); diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 537ec8f4f..1df342d57 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -640,16 +640,14 @@ TEST( Rot3, slerp) } //****************************************************************************** -namespace rot3_example { +namespace { Rot3 id; Rot3 T1(Rot3::AxisAngle(Vector3(0, 0, 1), 1)); Rot3 T2(Rot3::AxisAngle(Vector3(0, 1, 0), 2)); -} // namespace rot3_example +} // namespace //****************************************************************************** TEST(Rot3, Invariants) { - using namespace rot3_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, T1)); EXPECT(check_group_invariants(T2, id)); @@ -665,8 +663,6 @@ TEST(Rot3, Invariants) { //****************************************************************************** TEST(Rot3, LieGroupDerivatives) { - using namespace rot3_example; - CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, T2); CHECK_LIE_GROUP_DERIVATIVES(T2, id); @@ -676,8 +672,6 @@ TEST(Rot3, LieGroupDerivatives) { //****************************************************************************** TEST(Rot3, ChartDerivatives) { - using namespace rot3_example; - if (ROT3_DEFAULT_COORDINATES_MODE == Rot3::EXPMAP) { CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, T2); diff --git a/gtsam/geometry/tests/testSO3.cpp b/gtsam/geometry/tests/testSO3.cpp index 64d3e681d..96c1cce32 100644 --- a/gtsam/geometry/tests/testSO3.cpp +++ b/gtsam/geometry/tests/testSO3.cpp @@ -67,16 +67,15 @@ TEST(SO3, ClosestTo) { } //****************************************************************************** -namespace so3_example { +namespace { SO3 id; Vector3 z_axis(0, 0, 1), v2(1, 2, 0), v3(1, 2, 3); SO3 R1(Eigen::AngleAxisd(0.1, z_axis)); SO3 R2(Eigen::AngleAxisd(0.2, z_axis)); -} // namespace so3_example +} // namespace /* ************************************************************************* */ TEST(SO3, ChordalMean) { - using namespace so3_example; std::vector rotations = {R1, R1.inverse()}; EXPECT(assert_equal(SO3(), SO3::ChordalMean(rotations))); } @@ -84,7 +83,6 @@ TEST(SO3, ChordalMean) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO3, Hat) { - using namespace so3_example; EXPECT(assert_equal(SO3::Hat(z_axis), SOn::Hat(z_axis))); EXPECT(assert_equal(SO3::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO3::Hat(v3), SOn::Hat(v3))); @@ -93,7 +91,6 @@ TEST(SO3, Hat) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO3, Vee) { - using namespace so3_example; auto X1 = SOn::Hat(z_axis), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO3::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO3::Vee(X2), SOn::Vee(X2))); @@ -102,7 +99,6 @@ TEST(SO3, Vee) { //****************************************************************************** TEST(SO3, Local) { - using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = traits::Local(R1, R2); EXPECT(assert_equal((Vector)expected, actual)); @@ -110,7 +106,6 @@ TEST(SO3, Local) { //****************************************************************************** TEST(SO3, Retract) { - using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = traits::Retract(R1, v); EXPECT(assert_equal(R2, actual)); @@ -118,7 +113,6 @@ TEST(SO3, Retract) { //****************************************************************************** TEST(SO3, Logmap) { - using namespace so3_example; Vector3 expected(0, 0, 0.1); Vector3 actual = SO3::Logmap(R1.between(R2)); EXPECT(assert_equal((Vector)expected, actual)); @@ -126,7 +120,6 @@ TEST(SO3, Logmap) { //****************************************************************************** TEST(SO3, Expmap) { - using namespace so3_example; Vector3 v(0, 0, 0.1); SO3 actual = R1 * SO3::Expmap(v); EXPECT(assert_equal(R2, actual)); @@ -134,8 +127,6 @@ TEST(SO3, Expmap) { //****************************************************************************** TEST(SO3, Invariants) { - using namespace so3_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, R1)); EXPECT(check_group_invariants(R2, id)); @@ -149,7 +140,6 @@ TEST(SO3, Invariants) { //****************************************************************************** TEST(SO3, LieGroupDerivatives) { - using namespace so3_example; CHECK_LIE_GROUP_DERIVATIVES(id, id); CHECK_LIE_GROUP_DERIVATIVES(id, R2); CHECK_LIE_GROUP_DERIVATIVES(R2, id); @@ -158,7 +148,6 @@ TEST(SO3, LieGroupDerivatives) { //****************************************************************************** TEST(SO3, ChartDerivatives) { - using namespace so3_example; CHECK_CHART_DERIVATIVES(id, id); CHECK_CHART_DERIVATIVES(id, R2); CHECK_CHART_DERIVATIVES(R2, id); @@ -363,7 +352,6 @@ TEST(SO3, ApplyInvDexp) { //****************************************************************************** TEST(SO3, vec) { - using namespace so3_example; const Vector9 expected = Eigen::Map(R2.matrix().data()); Matrix actualH; const Vector9 actual = R2.vec(actualH); diff --git a/gtsam/geometry/tests/testSO4.cpp b/gtsam/geometry/tests/testSO4.cpp index 7379049c3..fa550723a 100644 --- a/gtsam/geometry/tests/testSO4.cpp +++ b/gtsam/geometry/tests/testSO4.cpp @@ -55,7 +55,7 @@ TEST(SO4, Random) { } //****************************************************************************** -namespace so4_example { +namespace { SO4 id; Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); SO4 Q1 = SO4::Expmap(v1); @@ -63,12 +63,10 @@ Vector6 v2 = (Vector(6) << 0.00, 0.00, 0.00, 0.01, 0.02, 0.03).finished(); SO4 Q2 = SO4::Expmap(v2); Vector6 v3 = (Vector(6) << 1, 2, 3, 4, 5, 6).finished(); SO4 Q3 = SO4::Expmap(v3); -} // namespace so4_example +} // namespace //****************************************************************************** TEST(SO4, Expmap) { - using namespace so4_example; - // If we do exponential map in SO(3) subgroup, topleft should be equal to R1. auto R1 = SO3::Expmap(v1.tail<3>()).matrix(); EXPECT((Q1.matrix().topLeftCorner<3, 3>().isApprox(R1))); @@ -91,7 +89,6 @@ TEST(SO4, Expmap) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO4, Hat) { - using namespace so4_example; EXPECT(assert_equal(SO4::Hat(v1), SOn::Hat(v1))); EXPECT(assert_equal(SO4::Hat(v2), SOn::Hat(v2))); EXPECT(assert_equal(SO4::Hat(v3), SOn::Hat(v3))); @@ -100,7 +97,6 @@ TEST(SO4, Hat) { //****************************************************************************** // Check that Hat specialization is equal to dynamic version TEST(SO4, Vee) { - using namespace so4_example; auto X1 = SOn::Hat(v1), X2 = SOn::Hat(v2), X3 = SOn::Hat(v3); EXPECT(assert_equal(SO4::Vee(X1), SOn::Vee(X1))); EXPECT(assert_equal(SO4::Vee(X2), SOn::Vee(X2))); @@ -109,8 +105,6 @@ TEST(SO4, Vee) { //****************************************************************************** TEST(SO4, Retract) { - using namespace so4_example; - // Check that Cayley yields the same as Expmap for small values EXPECT(assert_equal(id.retract(v1 / 100), SO4::Expmap(v1 / 100))); EXPECT(assert_equal(id.retract(v2 / 100), SO4::Expmap(v2 / 100))); @@ -127,7 +121,6 @@ TEST(SO4, Retract) { //****************************************************************************** // Check that Cayley is identical to dynamic version TEST(SO4, Local) { - using namespace so4_example; EXPECT( assert_equal(id.localCoordinates(Q1), SOn(4).localCoordinates(SOn(Q1)))); EXPECT( @@ -140,8 +133,6 @@ TEST(SO4, Local) { //****************************************************************************** TEST(SO4, Invariants) { - using namespace so4_example; - EXPECT(check_group_invariants(id, id)); EXPECT(check_group_invariants(id, Q1)); EXPECT(check_group_invariants(Q2, id)); @@ -157,8 +148,6 @@ TEST(SO4, Invariants) { //****************************************************************************** TEST(SO4, compose) { - using namespace so4_example; - SO4 expected = Q1 * Q2; Matrix actualH1, actualH2; SO4 actual = Q1.compose(Q2, actualH1, actualH2); @@ -175,8 +164,6 @@ TEST(SO4, compose) { //****************************************************************************** TEST(SO4, vec) { - using namespace so4_example; - using Vector16 = SO4::VectorN2; const Vector16 expected = Eigen::Map(Q2.matrix().data()); Matrix actualH; @@ -189,8 +176,6 @@ TEST(SO4, vec) { //****************************************************************************** TEST(SO4, topLeft) { - using namespace so4_example; - const Matrix3 expected = Q3.matrix().topLeftCorner<3, 3>(); Matrix actualH; const Matrix3 actual = topLeft(Q3, actualH); @@ -204,8 +189,6 @@ TEST(SO4, topLeft) { //****************************************************************************** TEST(SO4, stiefel) { - using namespace so4_example; - const Matrix43 expected = Q3.matrix().leftCols<3>(); Matrix actualH; const Matrix43 actual = stiefel(Q3, actualH); From 67c1b26f2b9e40c08b5596bd3ce257260cd9f005 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 13:07:38 -0500 Subject: [PATCH 012/116] Try if combined tests are faster --- .github/scripts/unix.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index d890577b6..5bca4dca4 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -91,6 +91,7 @@ function build () { export GTSAM_BUILD_EXAMPLES_ALWAYS=ON export GTSAM_BUILD_TESTS=OFF + export GTSAM_SINGLE_TEST_EXE=ON configure @@ -108,6 +109,7 @@ function test () { export GTSAM_BUILD_EXAMPLES_ALWAYS=OFF export GTSAM_BUILD_TESTS=ON + export GTSAM_SINGLE_TEST_EXE=ON configure From 7b124f4953c3de8364e1d9d1c94169d6740649cd Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 13:24:54 -0500 Subject: [PATCH 013/116] Try grouped tests - again --- .github/scripts/unix.sh | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index 5bca4dca4..3091531ea 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -71,6 +71,7 @@ function configure() -DGTSAM_USE_SYSTEM_EIGEN=${GTSAM_USE_SYSTEM_EIGEN:-OFF} \ -DGTSAM_USE_SYSTEM_METIS=${GTSAM_USE_SYSTEM_METIS:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ + -DGTSAM_SINGLE_TEST_EXE=ON \ -DBOOST_ROOT=$BOOST_ROOT \ -DBoost_NO_SYSTEM_PATHS=ON \ -DBoost_ARCHITECTURE=-x64 @@ -91,7 +92,6 @@ function build () { export GTSAM_BUILD_EXAMPLES_ALWAYS=ON export GTSAM_BUILD_TESTS=OFF - export GTSAM_SINGLE_TEST_EXE=ON configure @@ -109,7 +109,6 @@ function test () { export GTSAM_BUILD_EXAMPLES_ALWAYS=OFF export GTSAM_BUILD_TESTS=ON - export GTSAM_SINGLE_TEST_EXE=ON configure From 311325cc2f4a9e10d138438bfddb4f9dfb89e968 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 14:06:58 -0500 Subject: [PATCH 014/116] Fixed another serialization clash --- tests/testSerializationSLAM.cpp | 70 +++++++++++++++++++++++++++ tests/testSubgraphPreconditioner.cpp | 71 ---------------------------- 2 files changed, 70 insertions(+), 71 deletions(-) diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSLAM.cpp index 496122419..3f030cdff 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSLAM.cpp @@ -592,6 +592,76 @@ TEST (testSerializationSLAM, factors) { EXPECT(equalsBinary(genericStereoFactor3D)); } +/* ************************************************************************* */ +// Read from XML file +namespace { +static GaussianFactorGraph read(const string& name) { + auto inputFile = findExampleDataFile(name); + ifstream is(inputFile); + if (!is.is_open()) throw runtime_error("Cannot find file " + inputFile); + boost::archive::xml_iarchive in_archive(is); + GaussianFactorGraph Ab; + in_archive >> boost::serialization::make_nvp("graph", Ab); + return Ab; +} +} // namespace + +/* ************************************************************************* */ +// Read from XML file +TEST(SubgraphSolver, Solves) { + // Create preconditioner + SubgraphPreconditioner system; + + // We test on three different graphs + const auto Ab1 = planarGraph(3).first; + const auto Ab2 = read("toy3D"); + const auto Ab3 = read("randomGrid3D"); + + // For all graphs, test solve and solveTranspose + for (const auto& Ab : {Ab1, Ab2, Ab3}) { + // Call build, a non-const method needed to make solve work :-( + KeyInfo keyInfo(Ab); + std::map lambda; + system.build(Ab, keyInfo, lambda); + + // Create a perturbed (non-zero) RHS + const auto xbar = system.Rc1().optimize(); // merely for use in zero below + auto values_y = VectorValues::Zero(xbar); + auto it = values_y.begin(); + it->second.setConstant(100); + ++it; + it->second.setConstant(-100); + + // Solve the VectorValues way + auto values_x = system.Rc1().backSubstitute(values_y); + + // Solve the matrix way, this really just checks BN::backSubstitute + // This only works with Rc1 ordering, not with keyInfo ! + // TODO(frank): why does this not work with an arbitrary ordering? + const auto ord = system.Rc1().ordering(); + const Matrix R1 = system.Rc1().matrix(ord).first; + auto ord_y = values_y.vector(ord); + auto vector_x = R1.inverse() * ord_y; + EXPECT(assert_equal(vector_x, values_x.vector(ord))); + + // Test that 'solve' does implement x = R^{-1} y + // We do this by asserting it gives same answer as backSubstitute + // Only works with keyInfo ordering: + const auto ordering = keyInfo.ordering(); + auto vector_y = values_y.vector(ordering); + const size_t N = R1.cols(); + Vector solve_x = Vector::Zero(N); + system.solve(vector_y, solve_x); + EXPECT(assert_equal(values_x.vector(ordering), solve_x)); + + // Test that transposeSolve does implement x = R^{-T} y + // We do this by asserting it gives same answer as backSubstituteTranspose + auto values_x2 = system.Rc1().backSubstituteTranspose(values_y); + Vector solveT_x = Vector::Zero(N); + system.transposeSolve(vector_y, solveT_x); + EXPECT(assert_equal(values_x2.vector(ordering), solveT_x)); + } +} /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } diff --git a/tests/testSubgraphPreconditioner.cpp b/tests/testSubgraphPreconditioner.cpp index eeba38b68..c5b4e42ec 100644 --- a/tests/testSubgraphPreconditioner.cpp +++ b/tests/testSubgraphPreconditioner.cpp @@ -29,10 +29,8 @@ #include -#include #include #include -#include #include using namespace boost::assign; @@ -197,75 +195,6 @@ TEST(SubgraphPreconditioner, system) { EXPECT(assert_equal(expected_g, vec(g))); } -/* ************************************************************************* */ -BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "JacobianFactor") - -// Read from XML file -static GaussianFactorGraph read(const string& name) { - auto inputFile = findExampleDataFile(name); - ifstream is(inputFile); - if (!is.is_open()) throw runtime_error("Cannot find file " + inputFile); - boost::archive::xml_iarchive in_archive(is); - GaussianFactorGraph Ab; - in_archive >> boost::serialization::make_nvp("graph", Ab); - return Ab; -} - -TEST(SubgraphSolver, Solves) { - // Create preconditioner - SubgraphPreconditioner system; - - // We test on three different graphs - const auto Ab1 = planarGraph(3).first; - const auto Ab2 = read("toy3D"); - const auto Ab3 = read("randomGrid3D"); - - // For all graphs, test solve and solveTranspose - for (const auto& Ab : {Ab1, Ab2, Ab3}) { - // Call build, a non-const method needed to make solve work :-( - KeyInfo keyInfo(Ab); - std::map lambda; - system.build(Ab, keyInfo, lambda); - - // Create a perturbed (non-zero) RHS - const auto xbar = system.Rc1().optimize(); // merely for use in zero below - auto values_y = VectorValues::Zero(xbar); - auto it = values_y.begin(); - it->second.setConstant(100); - ++it; - it->second.setConstant(-100); - - // Solve the VectorValues way - auto values_x = system.Rc1().backSubstitute(values_y); - - // Solve the matrix way, this really just checks BN::backSubstitute - // This only works with Rc1 ordering, not with keyInfo ! - // TODO(frank): why does this not work with an arbitrary ordering? - const auto ord = system.Rc1().ordering(); - const Matrix R1 = system.Rc1().matrix(ord).first; - auto ord_y = values_y.vector(ord); - auto vector_x = R1.inverse() * ord_y; - EXPECT(assert_equal(vector_x, values_x.vector(ord))); - - // Test that 'solve' does implement x = R^{-1} y - // We do this by asserting it gives same answer as backSubstitute - // Only works with keyInfo ordering: - const auto ordering = keyInfo.ordering(); - auto vector_y = values_y.vector(ordering); - const size_t N = R1.cols(); - Vector solve_x = Vector::Zero(N); - system.solve(vector_y, solve_x); - EXPECT(assert_equal(values_x.vector(ordering), solve_x)); - - // Test that transposeSolve does implement x = R^{-T} y - // We do this by asserting it gives same answer as backSubstituteTranspose - auto values_x2 = system.Rc1().backSubstituteTranspose(values_y); - Vector solveT_x = Vector::Zero(N); - system.transposeSolve(vector_y, solveT_x); - EXPECT(assert_equal(values_x2.vector(ordering), solveT_x)); - } -} - /* ************************************************************************* */ TEST(SubgraphPreconditioner, conjugateGradients) { // Build a planar graph From e4cbd9cea80464450256291a10924f78ef294345 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 15:07:05 -0500 Subject: [PATCH 015/116] Move Vector serialization to separate file --- gtsam/base/Vector.h | 44 +-------------------- gtsam/base/VectorSerialization.h | 65 ++++++++++++++++++++++++++++++++ 2 files changed, 66 insertions(+), 43 deletions(-) create mode 100644 gtsam/base/VectorSerialization.h diff --git a/gtsam/base/Vector.h b/gtsam/base/Vector.h index 36dc2288d..9cb2aa165 100644 --- a/gtsam/base/Vector.h +++ b/gtsam/base/Vector.h @@ -264,46 +264,4 @@ GTSAM_EXPORT Vector concatVectors(const std::list& vs); * concatenate Vectors */ GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...); -} // namespace gtsam - -#include -#include -#include - -namespace boost { - namespace serialization { - - // split version - copies into an STL vector for serialization - template - void save(Archive & ar, const gtsam::Vector & v, unsigned int /*version*/) { - const size_t size = v.size(); - ar << BOOST_SERIALIZATION_NVP(size); - ar << make_nvp("data", make_array(v.data(), v.size())); - } - - template - void load(Archive & ar, gtsam::Vector & v, unsigned int /*version*/) { - size_t size; - ar >> BOOST_SERIALIZATION_NVP(size); - v.resize(size); - ar >> make_nvp("data", make_array(v.data(), v.size())); - } - - // split version - copies into an STL vector for serialization - template - void save(Archive & ar, const Eigen::Matrix & v, unsigned int /*version*/) { - ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); - } - - template - void load(Archive & ar, Eigen::Matrix & v, unsigned int /*version*/) { - ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); - } - - } // namespace serialization -} // namespace boost - -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector) -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2) -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3) -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6) +} // namespace gtsam diff --git a/gtsam/base/VectorSerialization.h b/gtsam/base/VectorSerialization.h new file mode 100644 index 000000000..97df02a75 --- /dev/null +++ b/gtsam/base/VectorSerialization.h @@ -0,0 +1,65 @@ +/* ---------------------------------------------------------------------------- + + * 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 VectorSerialization.h + * @brief serialization for Vectors + * @author Frank Dellaert + * @date February 2022 + */ + +#pragma once + +#include + +#include +#include +#include + +namespace boost { +namespace serialization { + +// split version - copies into an STL vector for serialization +template +void save(Archive& ar, const gtsam::Vector& v, unsigned int /*version*/) { + const size_t size = v.size(); + ar << BOOST_SERIALIZATION_NVP(size); + ar << make_nvp("data", make_array(v.data(), v.size())); +} + +template +void load(Archive& ar, gtsam::Vector& v, unsigned int /*version*/) { + size_t size; + ar >> BOOST_SERIALIZATION_NVP(size); + v.resize(size); + ar >> make_nvp("data", make_array(v.data(), v.size())); +} + +// split version - copies into an STL vector for serialization +template +void save(Archive& ar, const Eigen::Matrix& v, + unsigned int /*version*/) { + ar << make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); +} + +template +void load(Archive& ar, Eigen::Matrix& v, + unsigned int /*version*/) { + ar >> make_nvp("data", make_array(v.data(), v.RowsAtCompileTime)); +} + +} // namespace serialization +} // namespace boost + +BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector) +BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector2) +BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector3) +BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector6) From a97eae628c9628def89fbf42eec810ecf7cc60ba Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 15:07:29 -0500 Subject: [PATCH 016/116] Move Matrix serialization to separate file and remove spurious headers --- gtsam/base/Matrix.cpp | 1 + gtsam/base/Matrix.h | 85 +----------------------------- gtsam/base/MatrixSerialization.h | 89 ++++++++++++++++++++++++++++++++ 3 files changed, 91 insertions(+), 84 deletions(-) create mode 100644 gtsam/base/MatrixSerialization.h diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 41a80629b..5b8a021d4 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -25,6 +25,7 @@ #include #include +#include #include #include diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 61c61a5af..c9625b895 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -26,12 +26,7 @@ #include #include -#include - -#include -#include #include -#include /** * Matrix is a typedef in the gtsam namespace @@ -523,82 +518,4 @@ GTSAM_EXPORT Matrix LLt(const Matrix& A); GTSAM_EXPORT Matrix RtR(const Matrix& A); GTSAM_EXPORT Vector columnNormSquare(const Matrix &A); -} // namespace gtsam - -#include -#include -#include - -namespace boost { - namespace serialization { - - /** - * Ref. https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063 - * - * Eigen supports calling resize() on both static and dynamic matrices. - * This allows for a uniform API, with resize having no effect if the static matrix - * is already the correct size. - * https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing - * - * We use all the Matrix template parameters to ensure wide compatibility. - * - * eigen_typekit in ROS uses the same code - * http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html - */ - - // split version - sends sizes ahead - template - void save(Archive & ar, - const Eigen::Matrix & m, - const unsigned int /*version*/) { - const size_t rows = m.rows(), cols = m.cols(); - ar << BOOST_SERIALIZATION_NVP(rows); - ar << BOOST_SERIALIZATION_NVP(cols); - ar << make_nvp("data", make_array(m.data(), m.size())); - } - - template - void load(Archive & ar, - Eigen::Matrix & m, - const unsigned int /*version*/) { - size_t rows, cols; - ar >> BOOST_SERIALIZATION_NVP(rows); - ar >> BOOST_SERIALIZATION_NVP(cols); - m.resize(rows, cols); - ar >> make_nvp("data", make_array(m.data(), m.size())); - } - - // templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix); - template - void serialize(Archive & ar, - Eigen::Matrix & m, - const unsigned int version) { - split_free(ar, m, version); - } - - // specialized to Matrix for MATLAB wrapper - template - void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { - split_free(ar, m, version); - } - - } // namespace serialization -} // namespace boost +} // namespace gtsam diff --git a/gtsam/base/MatrixSerialization.h b/gtsam/base/MatrixSerialization.h new file mode 100644 index 000000000..f79d7b27f --- /dev/null +++ b/gtsam/base/MatrixSerialization.h @@ -0,0 +1,89 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file MatrixSerialization.h + * @brief Serialization for matrices + * @author Frank Dellaert + * @date February 2022 + */ + +// \callgraph + +#pragma once + +#include + +#include +#include +#include + +namespace boost { +namespace serialization { + +/** + * Ref. + * https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063 + * + * Eigen supports calling resize() on both static and dynamic matrices. + * This allows for a uniform API, with resize having no effect if the static + * matrix is already the correct size. + * https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing + * + * We use all the Matrix template parameters to ensure wide compatibility. + * + * eigen_typekit in ROS uses the same code + * http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html + */ + +// split version - sends sizes ahead +template +void save( + Archive& ar, + const Eigen::Matrix& m, + const unsigned int /*version*/) { + const size_t rows = m.rows(), cols = m.cols(); + ar << BOOST_SERIALIZATION_NVP(rows); + ar << BOOST_SERIALIZATION_NVP(cols); + ar << make_nvp("data", make_array(m.data(), m.size())); +} + +template +void load(Archive& ar, + Eigen::Matrix& m, + const unsigned int /*version*/) { + size_t rows, cols; + ar >> BOOST_SERIALIZATION_NVP(rows); + ar >> BOOST_SERIALIZATION_NVP(cols); + m.resize(rows, cols); + ar >> make_nvp("data", make_array(m.data(), m.size())); +} + +// templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix); +template +void serialize( + Archive& ar, + Eigen::Matrix& m, + const unsigned int version) { + split_free(ar, m, version); +} + +// specialized to Matrix for MATLAB wrapper +template +void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { + split_free(ar, m, version); +} + +} // namespace serialization +} // namespace boost From d2f8041e13e8558352c938e457ea83338ff239f3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 15:15:14 -0500 Subject: [PATCH 017/116] rename --- ...alizationSLAM.cpp => testSerializationSam.cpp} | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) rename tests/{testSerializationSLAM.cpp => testSerializationSam.cpp} (99%) diff --git a/tests/testSerializationSLAM.cpp b/tests/testSerializationSam.cpp similarity index 99% rename from tests/testSerializationSLAM.cpp rename to tests/testSerializationSam.cpp index 3f030cdff..bc2f5e864 100644 --- a/tests/testSerializationSLAM.cpp +++ b/tests/testSerializationSam.cpp @@ -19,16 +19,16 @@ #include #include + +#include #include + #include #include -#include #include -#include +#include #include -#include -#include -#include + #include #include #include @@ -44,6 +44,11 @@ #include #include +#include +#include +#include +#include +#include #include using namespace std; From 63b643e0bf908d8acb6766469c4c0840742d463f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 15:16:05 -0500 Subject: [PATCH 018/116] rename again --- tests/{testSerializationSam.cpp => testSerializationSlam.cpp} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename tests/{testSerializationSam.cpp => testSerializationSlam.cpp} (100%) diff --git a/tests/testSerializationSam.cpp b/tests/testSerializationSlam.cpp similarity index 100% rename from tests/testSerializationSam.cpp rename to tests/testSerializationSlam.cpp From bd487ac1f6461d770354a97808b22d821b790345 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 16:12:47 -0500 Subject: [PATCH 019/116] add using... --- tests/testSerializationSlam.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tests/testSerializationSlam.cpp b/tests/testSerializationSlam.cpp index bc2f5e864..3a1798f5e 100644 --- a/tests/testSerializationSlam.cpp +++ b/tests/testSerializationSlam.cpp @@ -614,6 +614,8 @@ static GaussianFactorGraph read(const string& name) { /* ************************************************************************* */ // Read from XML file TEST(SubgraphSolver, Solves) { + using gtsam::example::planarGraph; + // Create preconditioner SubgraphPreconditioner system; From b975cdcc3d3beea4b58a285c9fdf5b5543cc07aa Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 20:58:20 -0500 Subject: [PATCH 020/116] Compilation issues with linux system --- gtsam/base/FastSet.h | 1 + gtsam/discrete/tests/testDecisionTree.cpp | 22 ++++++++++--------- ...onSlam.cpp => testSerializationInSlam.cpp} | 0 3 files changed, 13 insertions(+), 10 deletions(-) rename gtsam/slam/tests/{testSerializationSlam.cpp => testSerializationInSlam.cpp} (100%) diff --git a/gtsam/base/FastSet.h b/gtsam/base/FastSet.h index a5ee77495..6fe2d06e3 100644 --- a/gtsam/base/FastSet.h +++ b/gtsam/base/FastSet.h @@ -18,6 +18,7 @@ #pragma once +#include #if BOOST_VERSION >= 107400 #include #endif diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index dbfb2dc40..967023eeb 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -17,17 +17,19 @@ * @date Jan 30, 2012 */ -#include -using namespace boost::assign; - -#include -#include -#include - // #define DT_DEBUG_MEMORY // #define DT_NO_PRUNING #define DISABLE_DOT #include + +#include +#include + +#include + +#include +using namespace boost::assign; + using namespace std; using namespace gtsam; @@ -148,9 +150,9 @@ TEST(DecisionTree, example) { DOT(notb); // Check supplying empty trees yields an exception - CHECK_EXCEPTION(apply(empty, &Ring::id), std::runtime_error); - CHECK_EXCEPTION(apply(empty, a, &Ring::mul), std::runtime_error); - CHECK_EXCEPTION(apply(a, empty, &Ring::mul), std::runtime_error); + CHECK_EXCEPTION(gtsam::apply(empty, &Ring::id), std::runtime_error); + CHECK_EXCEPTION(gtsam::apply(empty, a, &Ring::mul), std::runtime_error); + CHECK_EXCEPTION(gtsam::apply(a, empty, &Ring::mul), std::runtime_error); // apply, two nodes, in natural order DT anotb = apply(a, notb, &Ring::mul); diff --git a/gtsam/slam/tests/testSerializationSlam.cpp b/gtsam/slam/tests/testSerializationInSlam.cpp similarity index 100% rename from gtsam/slam/tests/testSerializationSlam.cpp rename to gtsam/slam/tests/testSerializationInSlam.cpp From 2f53a67b4f936bc53c2d205f07823146888087f4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 20:58:57 -0500 Subject: [PATCH 021/116] rename to avoid conflict with tests --- gtsam/slam/tests/testSerializationInSlam.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/tests/testSerializationInSlam.cpp b/gtsam/slam/tests/testSerializationInSlam.cpp index 02b0e3191..6aec8ecb0 100644 --- a/gtsam/slam/tests/testSerializationInSlam.cpp +++ b/gtsam/slam/tests/testSerializationInSlam.cpp @@ -16,17 +16,18 @@ * @date February 2022 */ -#include -#include -#include +#include "smartFactorScenarios.h" +#include "PinholeFactor.h" + #include +#include +#include + +#include #include #include -#include "smartFactorScenarios.h" -#include "PinholeFactor.h" - namespace { static const double rankTol = 1.0; static const double sigma = 0.1; From bac5d4f1209f26f939dec6099028dccade4f96e6 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 20:59:26 -0500 Subject: [PATCH 022/116] Fix serialization class name --- examples/Data/randomGrid3D.xml | 2 +- examples/Data/toy3D.xml | 2 +- tests/testSerializationSlam.cpp | 5 ++++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/examples/Data/randomGrid3D.xml b/examples/Data/randomGrid3D.xml index 6a82ce31c..42eb473be 100644 --- a/examples/Data/randomGrid3D.xml +++ b/examples/Data/randomGrid3D.xml @@ -7,7 +7,7 @@ 32 1 - + diff --git a/examples/Data/toy3D.xml b/examples/Data/toy3D.xml index 13dbcbe6c..26bd231ca 100644 --- a/examples/Data/toy3D.xml +++ b/examples/Data/toy3D.xml @@ -7,7 +7,7 @@ 2 1 - + diff --git a/tests/testSerializationSlam.cpp b/tests/testSerializationSlam.cpp index 3a1798f5e..ea7038635 100644 --- a/tests/testSerializationSlam.cpp +++ b/tests/testSerializationSlam.cpp @@ -51,6 +51,9 @@ #include #include +#include +#include + using namespace std; using namespace gtsam; using namespace gtsam::serializationTestHelpers; @@ -615,7 +618,7 @@ static GaussianFactorGraph read(const string& name) { // Read from XML file TEST(SubgraphSolver, Solves) { using gtsam::example::planarGraph; - + // Create preconditioner SubgraphPreconditioner system; From 0167716037cc1b6463b43346aed71f038a05ecd2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 21:27:28 -0500 Subject: [PATCH 023/116] avoid more warnings on Linux --- gtsam/geometry/PinholeCamera.h | 14 ++++++++------ gtsam/nonlinear/tests/testCallRecord.cpp | 3 +-- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 61e9f0909..339e95e70 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -230,13 +230,15 @@ public: Point2 _project2(const POINT& pw, OptionalJacobian<2, dimension> Dcamera, OptionalJacobian<2, FixedDimension::value> Dpoint) const { // We just call 3-derivative version in Base - Matrix26 Dpose; - Eigen::Matrix Dcal; - Point2 pi = Base::project(pw, Dcamera ? &Dpose : 0, Dpoint, - Dcamera ? &Dcal : 0); - if (Dcamera) + if (Dcamera){ + Matrix26 Dpose; + Eigen::Matrix Dcal; + const Point2 pi = Base::project(pw, Dpose, Dpoint, Dcal); *Dcamera << Dpose, Dcal; - return pi; + return pi; + } else { + return Base::project(pw, boost::none, Dpoint, boost::none); + } } /// project a 3D point from world coordinates into the image diff --git a/gtsam/nonlinear/tests/testCallRecord.cpp b/gtsam/nonlinear/tests/testCallRecord.cpp index 5d0d5d5f2..419172f74 100644 --- a/gtsam/nonlinear/tests/testCallRecord.cpp +++ b/gtsam/nonlinear/tests/testCallRecord.cpp @@ -153,7 +153,7 @@ TEST(CallRecord, virtualReverseAdDispatching) { } { const int Rows = 6; - record.CallRecord::reverseAD2(Eigen::Matrix(), NJM); + record.CallRecord::reverseAD2(Eigen::Matrix::Zero(), NJM); EXPECT((assert_equal(record.cc, CallConfig(Rows, Cols)))); record.CallRecord::reverseAD2(DynRowMat(Rows, Cols), NJM); EXPECT((assert_equal(record.cc, CallConfig(Eigen::Dynamic, Cols, Rows, Cols)))); @@ -168,4 +168,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - From 59fbdf9cff4dc55671adfaa8cb93d420d4c1f6bc Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 21:29:59 -0500 Subject: [PATCH 024/116] use anonymous namespace --- gtsam/navigation/tests/imuFactorTesting.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/navigation/tests/imuFactorTesting.h b/gtsam/navigation/tests/imuFactorTesting.h index 5aa83e87e..6160db2a1 100644 --- a/gtsam/navigation/tests/imuFactorTesting.h +++ b/gtsam/navigation/tests/imuFactorTesting.h @@ -28,6 +28,7 @@ using symbol_shorthand::X; using symbol_shorthand::V; using symbol_shorthand::B; +namespace { static const Vector3 kZero = Z_3x1; typedef imuBias::ConstantBias Bias; static const Bias kZeroBiasHat, kZeroBias; @@ -43,6 +44,7 @@ static const Vector3 kGravityAlongNavZDown(0, 0, kGravity); auto radians = [](double t) { return t * M_PI / 180; }; static const double kGyroSigma = radians(0.5) / 60; // 0.5 degree ARW static const double kAccelSigma = 0.1 / 60; // 10 cm VRW +} namespace testing { From c78af4d3ea892044567feb7c0b7e20f1cb5a7bc4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 15:08:28 -0500 Subject: [PATCH 025/116] Add headers in the place they are needed --- examples/SFMExampleExpressions_bal.cpp | 6 +- examples/SFMExample_bal.cpp | 10 +-- examples/SFMExample_bal_COLAMD_METIS.cpp | 10 +-- gtsam/base/Value.h | 1 + gtsam/base/VerticalBlockMatrix.h | 1 + gtsam/base/cholesky.h | 1 - gtsam/base/tests/testSerializationBase.cpp | 1 + gtsam/geometry/BearingRange.h | 1 + gtsam/geometry/Cal3DS2.h | 1 + gtsam/geometry/Cal3DS2_Base.h | 1 + gtsam/geometry/Cal3Fisheye.h | 2 + gtsam/geometry/Point3.cpp | 1 + gtsam/geometry/SOn.h | 2 + gtsam/geometry/Unit3.h | 3 +- gtsam/linear/GaussianDensity.cpp | 61 +++++++++---------- gtsam/linear/LossFunctions.cpp | 1 + gtsam_unstable/nonlinear/LinearizedFactor.cpp | 1 + .../slam/tests/testSerialization.cpp | 13 ++-- 18 files changed, 67 insertions(+), 50 deletions(-) diff --git a/examples/SFMExampleExpressions_bal.cpp b/examples/SFMExampleExpressions_bal.cpp index 3a02e6cab..8a5a12e56 100644 --- a/examples/SFMExampleExpressions_bal.cpp +++ b/examples/SFMExampleExpressions_bal.cpp @@ -26,10 +26,12 @@ #include // Header order is close to far -#include -#include #include // for loading BAL datasets ! #include +#include +#include + +#include #include using namespace std; diff --git a/examples/SFMExample_bal.cpp b/examples/SFMExample_bal.cpp index 6944177c1..10563760d 100644 --- a/examples/SFMExample_bal.cpp +++ b/examples/SFMExample_bal.cpp @@ -16,12 +16,14 @@ */ // For an explanation of headers, see SFMExample.cpp -#include +#include // for loading BAL datasets ! +#include +#include #include #include -#include -#include // for loading BAL datasets ! -#include +#include + +#include #include using namespace std; diff --git a/examples/SFMExample_bal_COLAMD_METIS.cpp b/examples/SFMExample_bal_COLAMD_METIS.cpp index 4d04dd16e..92d779a56 100644 --- a/examples/SFMExample_bal_COLAMD_METIS.cpp +++ b/examples/SFMExample_bal_COLAMD_METIS.cpp @@ -17,16 +17,16 @@ */ // For an explanation of headers, see SFMExample.cpp -#include -#include -#include -#include #include #include // for loading BAL datasets ! #include - +#include +#include +#include +#include #include +#include #include using namespace std; diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index a19fbe176..697c4f3be 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -21,6 +21,7 @@ #include // Configuration from CMake #include +#include #include #include diff --git a/gtsam/base/VerticalBlockMatrix.h b/gtsam/base/VerticalBlockMatrix.h index 92031db2b..0d8d69df8 100644 --- a/gtsam/base/VerticalBlockMatrix.h +++ b/gtsam/base/VerticalBlockMatrix.h @@ -18,6 +18,7 @@ #pragma once #include +#include #include namespace gtsam { diff --git a/gtsam/base/cholesky.h b/gtsam/base/cholesky.h index 5e3276ff0..bf7d18a1d 100644 --- a/gtsam/base/cholesky.h +++ b/gtsam/base/cholesky.h @@ -18,7 +18,6 @@ #pragma once #include -#include namespace gtsam { diff --git a/gtsam/base/tests/testSerializationBase.cpp b/gtsam/base/tests/testSerializationBase.cpp index d863eaba3..f7aa97b31 100644 --- a/gtsam/base/tests/testSerializationBase.cpp +++ b/gtsam/base/tests/testSerializationBase.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 8db7abffe..95b0232f0 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -22,6 +22,7 @@ #include #include #include +#include #include namespace gtsam { diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index affce0819..039497cc9 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -21,6 +21,7 @@ #pragma once #include +#include namespace gtsam { diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index b583234fd..1b2291e07 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -21,6 +21,7 @@ #include #include +#include namespace gtsam { diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index a8c9fa182..c0caecaa1 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -22,6 +22,8 @@ #include #include +#include + #include namespace gtsam { diff --git a/gtsam/geometry/Point3.cpp b/gtsam/geometry/Point3.cpp index a565ac140..ef91108eb 100644 --- a/gtsam/geometry/Point3.cpp +++ b/gtsam/geometry/Point3.cpp @@ -17,6 +17,7 @@ #include #include #include +#include using namespace std; diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 86b6019e1..3af118134 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -24,6 +24,8 @@ #include #include +#include + #include // TODO(frank): how to avoid? #include #include diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index 27d41a014..c9a67dbb1 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -23,11 +23,12 @@ #include #include #include +#include +#include #include #include #include -#include #include #include diff --git a/gtsam/linear/GaussianDensity.cpp b/gtsam/linear/GaussianDensity.cpp index 2f7aa312b..343396c0a 100644 --- a/gtsam/linear/GaussianDensity.cpp +++ b/gtsam/linear/GaussianDensity.cpp @@ -17,42 +17,41 @@ */ #include +#include +#include -using namespace std; +using std::cout; +using std::endl; +using std::string; namespace gtsam { - /* ************************************************************************* */ - GaussianDensity GaussianDensity::FromMeanAndStddev(Key key, - const Vector& mean, - double sigma) { - return GaussianDensity(key, mean, - Matrix::Identity(mean.size(), mean.size()), - noiseModel::Isotropic::Sigma(mean.size(), sigma)); - } +/* ************************************************************************* */ +GaussianDensity GaussianDensity::FromMeanAndStddev(Key key, const Vector& mean, + double sigma) { + return GaussianDensity(key, mean, Matrix::Identity(mean.size(), mean.size()), + noiseModel::Isotropic::Sigma(mean.size(), sigma)); +} - /* ************************************************************************* */ - void GaussianDensity::print(const string &s, const KeyFormatter& formatter) const - { - cout << s << ": density on "; - for(const_iterator it = beginFrontals(); it != endFrontals(); ++it) - cout << (boost::format("[%1%]")%(formatter(*it))).str() << " "; - cout << endl; - gtsam::print(mean(), "mean: "); - gtsam::print(covariance(), "covariance: "); - if(model_) - model_->print("Noise model: "); - } +/* ************************************************************************* */ +void GaussianDensity::print(const string& s, + const KeyFormatter& formatter) const { + cout << s << ": density on "; + for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) + cout << (boost::format("[%1%]") % (formatter(*it))).str() << " "; + cout << endl; + gtsam::print(mean(), "mean: "); + gtsam::print(covariance(), "covariance: "); + if (model_) model_->print("Noise model: "); +} - /* ************************************************************************* */ - Vector GaussianDensity::mean() const { - VectorValues soln = this->solve(VectorValues()); - return soln[firstFrontalKey()]; - } +/* ************************************************************************* */ +Vector GaussianDensity::mean() const { + VectorValues soln = this->solve(VectorValues()); + return soln[firstFrontalKey()]; +} - /* ************************************************************************* */ - Matrix GaussianDensity::covariance() const { - return information().inverse(); - } +/* ************************************************************************* */ +Matrix GaussianDensity::covariance() const { return information().inverse(); } -} // gtsam +} // namespace gtsam diff --git a/gtsam/linear/LossFunctions.cpp b/gtsam/linear/LossFunctions.cpp index bf799a2ba..7307c4a68 100644 --- a/gtsam/linear/LossFunctions.cpp +++ b/gtsam/linear/LossFunctions.cpp @@ -19,6 +19,7 @@ #include #include +#include using namespace std; diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.cpp b/gtsam_unstable/nonlinear/LinearizedFactor.cpp index 1a86adbfa..0c821b872 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.cpp +++ b/gtsam_unstable/nonlinear/LinearizedFactor.cpp @@ -16,6 +16,7 @@ */ #include +#include #include namespace gtsam { diff --git a/gtsam_unstable/slam/tests/testSerialization.cpp b/gtsam_unstable/slam/tests/testSerialization.cpp index e9157317e..362cf3778 100644 --- a/gtsam_unstable/slam/tests/testSerialization.cpp +++ b/gtsam_unstable/slam/tests/testSerialization.cpp @@ -7,9 +7,6 @@ * @author Alex Cunningham */ -#include -#include - #include #include @@ -18,12 +15,16 @@ #include #include -#include -#include -#include +#include + #include #include +#include +#include +#include +#include + using namespace std; using namespace gtsam; using namespace boost::assign; From d6ebc21634f374a10d649c9fd25bdec3c024e58e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 23:11:00 -0500 Subject: [PATCH 026/116] Base wrapper needs Matrix serialization --- gtsam/base/base.i | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/base/base.i b/gtsam/base/base.i index 9838f97d3..9b9f351ce 100644 --- a/gtsam/base/base.i +++ b/gtsam/base/base.i @@ -82,6 +82,7 @@ class IndexPairSetMap { }; #include +#include bool linear_independent(Matrix A, Matrix B, double tol); #include From c4ebc71c5891c228bbb7ace96bd63b058b3a9e9c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 23:23:50 -0500 Subject: [PATCH 027/116] Add missing header --- gtsam/base/Matrix.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 5b8a021d4..75cb8e294 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -34,6 +34,8 @@ #include #include #include +#include +#include using namespace std; From ba8da3c573856b0ae30e8b249a83ed260dbef80d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Feb 2022 23:35:44 -0500 Subject: [PATCH 028/116] Added missing header in header --- gtsam/base/Matrix.cpp | 1 - gtsam/base/Matrix.h | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index 75cb8e294..f71f6fce8 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -35,7 +35,6 @@ #include #include #include -#include using namespace std; diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index c9625b895..cfedf6d8c 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -28,6 +28,8 @@ #include #include +#include + /** * Matrix is a typedef in the gtsam namespace * TODO: make a version to work with matlab wrapping From 5905110342561f02e6a367c77cac540f39c7357d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 17 Feb 2022 00:09:55 -0500 Subject: [PATCH 029/116] Remove duplicate header --- gtsam/base/Matrix.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/base/Matrix.cpp b/gtsam/base/Matrix.cpp index f71f6fce8..5b8a021d4 100644 --- a/gtsam/base/Matrix.cpp +++ b/gtsam/base/Matrix.cpp @@ -34,7 +34,6 @@ #include #include #include -#include using namespace std; From b65c89c159aeb87cf5c0f66894e862473a688b7b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 17 Feb 2022 00:10:04 -0500 Subject: [PATCH 030/116] Use at least 2 cores --- .github/scripts/unix.sh | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/.github/scripts/unix.sh b/.github/scripts/unix.sh index d890577b6..c2ecad735 100644 --- a/.github/scripts/unix.sh +++ b/.github/scripts/unix.sh @@ -95,7 +95,11 @@ function build () configure if [ "$(uname)" == "Linux" ]; then - make -j$(nproc) + if (($(nproc) > 2)); then + make -j$(nproc) + else + make -j2 + fi elif [ "$(uname)" == "Darwin" ]; then make -j$(sysctl -n hw.physicalcpu) fi @@ -113,7 +117,11 @@ function test () # Actual testing if [ "$(uname)" == "Linux" ]; then - make -j$(nproc) check + if (($(nproc) > 2)); then + make -j$(nproc) check + else + make -j2 check + fi elif [ "$(uname)" == "Darwin" ]; then make -j$(sysctl -n hw.physicalcpu) check fi From 6e6c64749d9a319aa20840a03c0e4c0af1ca2c7b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 01:52:12 -0500 Subject: [PATCH 031/116] basis module tests pass --- gtsam/basis/Basis.h | 7 +------ gtsam/basis/BasisFactors.h | 14 +++++++------- gtsam/basis/Chebyshev.h | 4 ++-- gtsam/basis/Fourier.h | 2 +- gtsam/basis/basis.i | 3 --- 5 files changed, 11 insertions(+), 19 deletions(-) diff --git a/gtsam/basis/Basis.h b/gtsam/basis/Basis.h index d8bd28c1a..765a2f645 100644 --- a/gtsam/basis/Basis.h +++ b/gtsam/basis/Basis.h @@ -92,7 +92,7 @@ Matrix kroneckerProductIdentity(const Weights& w) { /// CRTP Base class for function bases template -class GTSAM_EXPORT Basis { +class Basis { public: /** * Calculate weights for all x in vector X. @@ -497,11 +497,6 @@ class GTSAM_EXPORT Basis { } }; - // Vector version for MATLAB :-( - static double Derivative(double x, const Vector& p, // - OptionalJacobian H = boost::none) { - return DerivativeFunctor(x)(p.transpose(), H); - } }; } // namespace gtsam diff --git a/gtsam/basis/BasisFactors.h b/gtsam/basis/BasisFactors.h index 0b3d4c1a0..3d1a12f19 100644 --- a/gtsam/basis/BasisFactors.h +++ b/gtsam/basis/BasisFactors.h @@ -31,7 +31,7 @@ namespace gtsam { * @tparam BASIS The basis class to use e.g. Chebyshev2 */ template -class GTSAM_EXPORT EvaluationFactor : public FunctorizedFactor { +class EvaluationFactor : public FunctorizedFactor { private: using Base = FunctorizedFactor; @@ -85,7 +85,7 @@ class GTSAM_EXPORT EvaluationFactor : public FunctorizedFactor { * @param M: Size of the evaluated state vector. */ template -class GTSAM_EXPORT VectorEvaluationFactor +class VectorEvaluationFactor : public FunctorizedFactor> { private: using Base = FunctorizedFactor>; @@ -148,7 +148,7 @@ class GTSAM_EXPORT VectorEvaluationFactor * where N is the degree and i is the component index. */ template -class GTSAM_EXPORT VectorComponentFactor +class VectorComponentFactor : public FunctorizedFactor> { private: using Base = FunctorizedFactor>; @@ -217,7 +217,7 @@ class GTSAM_EXPORT VectorComponentFactor * where `x` is the value (e.g. timestep) at which the rotation was evaluated. */ template -class GTSAM_EXPORT ManifoldEvaluationFactor +class ManifoldEvaluationFactor : public FunctorizedFactor::dimension>> { private: using Base = FunctorizedFactor::dimension>>; @@ -269,7 +269,7 @@ class GTSAM_EXPORT ManifoldEvaluationFactor * @param BASIS: The basis class to use e.g. Chebyshev2 */ template -class GTSAM_EXPORT DerivativeFactor +class DerivativeFactor : public FunctorizedFactor { private: using Base = FunctorizedFactor; @@ -318,7 +318,7 @@ class GTSAM_EXPORT DerivativeFactor * @param M: Size of the evaluated state vector derivative. */ template -class GTSAM_EXPORT VectorDerivativeFactor +class VectorDerivativeFactor : public FunctorizedFactor> { private: using Base = FunctorizedFactor>; @@ -371,7 +371,7 @@ class GTSAM_EXPORT VectorDerivativeFactor * @param P: Size of the control component derivative. */ template -class GTSAM_EXPORT ComponentDerivativeFactor +class ComponentDerivativeFactor : public FunctorizedFactor> { private: using Base = FunctorizedFactor>; diff --git a/gtsam/basis/Chebyshev.h b/gtsam/basis/Chebyshev.h index d16ccfaac..7d37ccd8c 100644 --- a/gtsam/basis/Chebyshev.h +++ b/gtsam/basis/Chebyshev.h @@ -31,7 +31,7 @@ namespace gtsam { * These are typically denoted with the symbol T_n, where n is the degree. * The parameter N is the number of coefficients, i.e., N = n+1. */ -struct Chebyshev1Basis : Basis { +struct GTSAM_EXPORT Chebyshev1Basis : Basis { using Parameters = Eigen::Matrix; Parameters parameters_; @@ -79,7 +79,7 @@ struct Chebyshev1Basis : Basis { * functions. In this sense, they are like the sines and cosines of the Fourier * basis. */ -struct Chebyshev2Basis : Basis { +struct GTSAM_EXPORT Chebyshev2Basis : Basis { using Parameters = Eigen::Matrix; /** diff --git a/gtsam/basis/Fourier.h b/gtsam/basis/Fourier.h index d264e182d..eb259bd8a 100644 --- a/gtsam/basis/Fourier.h +++ b/gtsam/basis/Fourier.h @@ -24,7 +24,7 @@ namespace gtsam { /// Fourier basis -class GTSAM_EXPORT FourierBasis : public Basis { +class FourierBasis : public Basis { public: using Parameters = Eigen::Matrix; using DiffMatrix = Eigen::Matrix; diff --git a/gtsam/basis/basis.i b/gtsam/basis/basis.i index c9c027438..a6c9d87ee 100644 --- a/gtsam/basis/basis.i +++ b/gtsam/basis/basis.i @@ -44,9 +44,6 @@ class Chebyshev2 { static Matrix DerivativeWeights(size_t N, double x, double a, double b); static Matrix IntegrationWeights(size_t N, double a, double b); static Matrix DifferentiationMatrix(size_t N, double a, double b); - - // TODO Needs OptionalJacobian - // static double Derivative(double x, Vector f); }; #include From b13a219a3b9857ce7e0ac4f3e5cd140fd554c963 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 02:40:44 -0500 Subject: [PATCH 032/116] update METIS test for _WIN32 --- gtsam/inference/tests/testOrdering.cpp | 32 +++++++++++++++++--------- 1 file changed, 21 insertions(+), 11 deletions(-) diff --git a/gtsam/inference/tests/testOrdering.cpp b/gtsam/inference/tests/testOrdering.cpp index 0305218af..6fdca0d89 100644 --- a/gtsam/inference/tests/testOrdering.cpp +++ b/gtsam/inference/tests/testOrdering.cpp @@ -270,17 +270,7 @@ TEST(Ordering, MetisLoop) { symbolicGraph.push_factor(0, 5); // METIS -#if !defined(__APPLE__) - { - Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph); - // - P( 0 4 1) - // | - P( 2 | 4 1) - // | | - P( 3 | 4 2) - // | - P( 5 | 0 1) - Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1)); - EXPECT(assert_equal(expected, actual)); - } -#else +#if defined(__APPLE__) { Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph); // - P( 1 0 3) @@ -290,6 +280,26 @@ TEST(Ordering, MetisLoop) { Ordering expected = Ordering(list_of(5)(4)(2)(1)(0)(3)); EXPECT(assert_equal(expected, actual)); } +#elif defined(_WIN32) + { + Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph); + // - P( 0 5 2) + // | - P( 3 | 5 2) + // | | - P( 4 | 5 3) + // | - P( 1 | 0 2) + Ordering expected = Ordering(list_of(4)(3)(1)(0)(5)(2)); + EXPECT(assert_equal(expected, actual)); + } +#else + { + Ordering actual = Ordering::Create(Ordering::METIS, symbolicGraph); + // - P( 0 4 1) + // | - P( 2 | 4 1) + // | | - P( 3 | 4 2) + // | - P( 5 | 0 1) + Ordering expected = Ordering(list_of(3)(2)(5)(0)(4)(1)); + EXPECT(assert_equal(expected, actual)); + } #endif } #endif From 7712158bf2bf42b96b30d2a47fac151b7cd06d58 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 03:01:18 -0500 Subject: [PATCH 033/116] sfm tests pass --- gtsam/slam/dataset.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index a2b96efab..0b352900f 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -384,6 +384,7 @@ boost::shared_ptr createSampler(const SharedNoiseModel &model) { /* ************************************************************************* */ // Implementation of parseMeasurements for Pose2 template <> +GTSAM_EXPORT std::vector> parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, @@ -411,6 +412,7 @@ static BinaryMeasurement convert(const BinaryMeasurement &p) { } template <> +GTSAM_EXPORT std::vector> parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, @@ -868,6 +870,7 @@ template <> struct ParseMeasurement { /* ************************************************************************* */ // Implementation of parseMeasurements for Pose3 template <> +GTSAM_EXPORT std::vector> parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, @@ -895,6 +898,7 @@ static BinaryMeasurement convert(const BinaryMeasurement &p) { } template <> +GTSAM_EXPORT std::vector> parseMeasurements(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, From beeb91a26ce9a9f54e7592090281c56cf946b2b2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 03:07:26 -0500 Subject: [PATCH 034/116] symbolic tests pass --- .../symbolic/tests/testSymbolicBayesTree.cpp | 31 ++++++++++++------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp index 33fc3243b..ee9b41a5a 100644 --- a/gtsam/symbolic/tests/testSymbolicBayesTree.cpp +++ b/gtsam/symbolic/tests/testSymbolicBayesTree.cpp @@ -731,10 +731,12 @@ TEST(SymbolicBayesTree, COLAMDvsMETIS) { { Ordering ordering = Ordering::Create(Ordering::METIS, sfg); // Linux and Mac split differently when using mettis -#if !defined(__APPLE__) - EXPECT(assert_equal(Ordering(list_of(3)(2)(5)(0)(4)(1)), ordering)); -#else +#if defined(__APPLE__) EXPECT(assert_equal(Ordering(list_of(5)(4)(2)(1)(0)(3)), ordering)); +#elif defined(_WIN32) + EXPECT(assert_equal(Ordering(list_of(4)(3)(1)(0)(5)(2)), ordering)); +#else + EXPECT(assert_equal(Ordering(list_of(3)(2)(5)(0)(4)(1)), ordering)); #endif // - P( 1 0 3) @@ -742,20 +744,27 @@ TEST(SymbolicBayesTree, COLAMDvsMETIS) { // | | - P( 5 | 0 4) // | - P( 2 | 1 3) SymbolicBayesTree expected; -#if !defined(__APPLE__) - expected.insertRoot( - MakeClique(list_of(2)(4)(1), 3, - list_of( - MakeClique(list_of(0)(1)(4), 1, - list_of(MakeClique(list_of(5)(0)(4), 1))))( - MakeClique(list_of(3)(2)(4), 1)))); -#else +#if defined(__APPLE__) expected.insertRoot( MakeClique(list_of(1)(0)(3), 3, list_of( MakeClique(list_of(4)(0)(3), 1, list_of(MakeClique(list_of(5)(0)(4), 1))))( MakeClique(list_of(2)(1)(3), 1)))); +#elif defined(_WIN32) + expected.insertRoot( + MakeClique(list_of(3)(5)(2), 3, + list_of( + MakeClique(list_of(4)(3)(5), 1, + list_of(MakeClique(list_of(0)(2)(5), 1))))( + MakeClique(list_of(1)(0)(2), 1)))); +#else + expected.insertRoot( + MakeClique(list_of(2)(4)(1), 3, + list_of( + MakeClique(list_of(0)(1)(4), 1, + list_of(MakeClique(list_of(5)(0)(4), 1))))( + MakeClique(list_of(3)(2)(4), 1)))); #endif SymbolicBayesTree actual = *sfg.eliminateMultifrontal(ordering); EXPECT(assert_equal(expected, actual)); From 865a7bac77d4588d1df0268e93883a3a67abdf71 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 09:37:17 -0500 Subject: [PATCH 035/116] navigation tests passing --- gtsam/navigation/CombinedImuFactor.cpp | 3 --- gtsam/navigation/CombinedImuFactor.h | 3 --- gtsam/navigation/tests/testSerializationNavigation.cpp | 3 +++ 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 7d086eb57..3fe2cf4d1 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -256,6 +256,3 @@ std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) { } /// namespace gtsam -/// Boost serialization export definition for derived class -BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams) - diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 89e8b574f..068a17ca4 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -351,6 +351,3 @@ template <> struct traits : public Testable {}; } // namespace gtsam - -/// Add Boost serialization export key (declaration) for derived class -BOOST_CLASS_EXPORT_KEY(gtsam::PreintegrationCombinedParams) diff --git a/gtsam/navigation/tests/testSerializationNavigation.cpp b/gtsam/navigation/tests/testSerializationNavigation.cpp index 63d2606a1..6a2155875 100644 --- a/gtsam/navigation/tests/testSerializationNavigation.cpp +++ b/gtsam/navigation/tests/testSerializationNavigation.cpp @@ -39,6 +39,9 @@ BOOST_CLASS_EXPORT_GUID(noiseModel::Unit, "gtsam_noiseModel_Unit") BOOST_CLASS_EXPORT_GUID(noiseModel::Isotropic, "gtsam_noiseModel_Isotropic") BOOST_CLASS_EXPORT_GUID(SharedNoiseModel, "gtsam_SharedNoiseModel") BOOST_CLASS_EXPORT_GUID(SharedDiagonal, "gtsam_SharedDiagonal") +BOOST_CLASS_EXPORT_GUID(PreintegratedImuMeasurements, "gtsam_PreintegratedImuMeasurements") +BOOST_CLASS_EXPORT_GUID(PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams") +BOOST_CLASS_EXPORT_GUID(PreintegratedCombinedMeasurements, "gtsam_PreintegratedCombinedMeasurements") template P getPreintegratedMeasurements() { From 2e5bdcd5e715078bb2f345c5fbee6cbb3ce6e0ee Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 09:56:32 -0500 Subject: [PATCH 036/116] fixed dllexport issues in nonlinear, only tests failing --- gtsam/nonlinear/FunctorizedFactor.h | 4 +-- gtsam/nonlinear/LinearContainerFactor.h | 35 ++++++++++++------------- 2 files changed, 19 insertions(+), 20 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index e1f8ece8d..394b22b6b 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -56,7 +56,7 @@ namespace gtsam { * MultiplyFunctor(multiplier)); */ template -class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { +class FunctorizedFactor : public NoiseModelFactor1 { private: using Base = NoiseModelFactor1; @@ -155,7 +155,7 @@ FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, * @param T2: The second argument type for the functor. */ template -class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2 { +class FunctorizedFactor2 : public NoiseModelFactor2 { private: using Base = NoiseModelFactor2; diff --git a/gtsam/nonlinear/LinearContainerFactor.h b/gtsam/nonlinear/LinearContainerFactor.h index efc095775..16094b67a 100644 --- a/gtsam/nonlinear/LinearContainerFactor.h +++ b/gtsam/nonlinear/LinearContainerFactor.h @@ -23,14 +23,14 @@ namespace gtsam { * This factor does have the ability to perform relinearization under small-angle and * linearity assumptions if a linearization point is added. */ -class LinearContainerFactor : public NonlinearFactor { +class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor { protected: GaussianFactor::shared_ptr factor_; boost::optional linearizationPoint_; /** direct copy constructor */ - GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional& linearizationPoint); + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional& linearizationPoint); // Some handy typedefs typedef NonlinearFactor Base; @@ -44,13 +44,13 @@ public: LinearContainerFactor() {} /** Primary constructor: store a linear factor with optional linearization point */ - GTSAM_EXPORT LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values()); + LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values()); /** Primary constructor: store a linear factor with optional linearization point */ - GTSAM_EXPORT LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values()); + LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values()); /** Constructor from shared_ptr */ - GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values()); + LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values()); // Access @@ -59,10 +59,10 @@ public: // Testable /** print */ - GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override; + void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const override; /** Check if two factors are equal */ - GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const override; + bool equals(const NonlinearFactor& f, double tol = 1e-9) const override; // NonlinearFactor @@ -74,10 +74,10 @@ public: * * @return nonlinear error if linearizationPoint present, zero otherwise */ - GTSAM_EXPORT double error(const Values& c) const override; + double error(const Values& c) const override; /** get the dimension of the factor: rows of linear factor */ - GTSAM_EXPORT size_t dim() const override; + size_t dim() const override; /** Extract the linearization point used in recalculating error */ const boost::optional& linearizationPoint() const { return linearizationPoint_; } @@ -98,17 +98,17 @@ public: * TODO: better approximation of relinearization * TODO: switchable modes for approximation technique */ - GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const override; + GaussianFactor::shared_ptr linearize(const Values& c) const override; /** * Creates an anti-factor directly */ - GTSAM_EXPORT GaussianFactor::shared_ptr negateToGaussian() const; + GaussianFactor::shared_ptr negateToGaussian() const; /** * Creates the equivalent anti-factor as another LinearContainerFactor. */ - GTSAM_EXPORT NonlinearFactor::shared_ptr negateToNonlinear() const; + NonlinearFactor::shared_ptr negateToNonlinear() const; /** * Creates a shared_ptr clone of the factor - needs to be specialized to allow @@ -140,25 +140,24 @@ public: /** * Simple checks whether this is a Jacobian or Hessian factor */ - GTSAM_EXPORT bool isJacobian() const; - GTSAM_EXPORT bool isHessian() const; + bool isJacobian() const; + bool isHessian() const; /** Casts to JacobianFactor */ - GTSAM_EXPORT boost::shared_ptr toJacobian() const; + boost::shared_ptr toJacobian() const; /** Casts to HessianFactor */ - GTSAM_EXPORT boost::shared_ptr toHessian() const; + boost::shared_ptr toHessian() const; /** * Utility function for converting linear graphs to nonlinear graphs * consisting of LinearContainerFactors. */ - GTSAM_EXPORT static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph, const Values& linearizationPoint = Values()); protected: - GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint); + void initializeLinearizationPoint(const Values& linearizationPoint); private: /** Serialization function */ From 38425f1164c41d67821227261549701a9df2de5f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 10:44:28 -0500 Subject: [PATCH 037/116] fixed dllexport issues in slam, only tests failing --- gtsam/slam/FrobeniusFactor.h | 6 +++--- gtsam/slam/OrientedPlane3Factor.h | 4 ++-- gtsam/slam/SmartProjectionPoseFactor.h | 2 +- gtsam/slam/dataset.cpp | 22 ++++++++++++++-------- 4 files changed, 20 insertions(+), 14 deletions(-) diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 4a60c8ba0..05e23ce6d 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -48,7 +48,7 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t n, * element of SO(3) or SO(4). */ template -class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1 { +class FrobeniusPrior : public NoiseModelFactor1 { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; using MatrixNN = typename Rot::MatrixNN; Eigen::Matrix vecM_; ///< vectorized matrix to approximate @@ -75,7 +75,7 @@ class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1 { * The template argument can be any fixed-size SO. */ template -class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2 { +class FrobeniusFactor : public NoiseModelFactor2 { enum { Dim = Rot::VectorN2::RowsAtCompileTime }; public: @@ -101,7 +101,7 @@ class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2 { * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. */ template -class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2 { +class FrobeniusBetweenFactor : public NoiseModelFactor2 { Rot R12_; ///< measured rotation between R1 and R2 Eigen::Matrix R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index d7b836dec..81bb790de 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -15,7 +15,7 @@ namespace gtsam { /** * Factor to measure a planar landmark from a given pose */ -class OrientedPlane3Factor: public NoiseModelFactor2 { +class GTSAM_EXPORT OrientedPlane3Factor: public NoiseModelFactor2 { protected: OrientedPlane3 measured_p_; typedef NoiseModelFactor2 Base; @@ -49,7 +49,7 @@ class OrientedPlane3Factor: public NoiseModelFactor2 { }; // TODO: Convert this factor to dimension two, three dimensions is redundant for direction prior -class OrientedPlane3DirectionPrior : public NoiseModelFactor1 { +class GTSAM_EXPORT OrientedPlane3DirectionPrior : public NoiseModelFactor1 { protected: OrientedPlane3 measured_p_; /// measured plane parameters typedef NoiseModelFactor1 Base; diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index 3cd69c46f..f4c0c73aa 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -42,7 +42,7 @@ namespace gtsam { * @addtogroup SLAM */ template -class GTSAM_EXPORT SmartProjectionPoseFactor +class SmartProjectionPoseFactor : public SmartProjectionFactor > { private: typedef PinholePose Camera; diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 0b352900f..6c8e43108 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -177,8 +177,9 @@ boost::optional parseVertexPose(istream &is, const string &tag) { } template <> -std::map parseVariables(const std::string &filename, - size_t maxIndex) { +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + size_t maxIndex) +{ return parseToMap(filename, parseVertexPose, maxIndex); } @@ -199,8 +200,9 @@ boost::optional parseVertexLandmark(istream &is, } template <> -std::map parseVariables(const std::string &filename, - size_t maxIndex) { +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + size_t maxIndex) +{ return parseToMap(filename, parseVertexLandmark, maxIndex); } @@ -428,6 +430,7 @@ parseMeasurements(const std::string &filename, /* ************************************************************************* */ // Implementation of parseFactors for Pose2 template <> +GTSAM_EXPORT std::vector::shared_ptr> parseFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, @@ -777,8 +780,9 @@ boost::optional> parseVertexPose3(istream &is, } template <> -std::map parseVariables(const std::string &filename, - size_t maxIndex) { +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + size_t maxIndex) +{ return parseToMap(filename, parseVertexPose3, maxIndex); } @@ -795,8 +799,9 @@ boost::optional> parseVertexPoint3(istream &is, } template <> -std::map parseVariables(const std::string &filename, - size_t maxIndex) { +GTSAM_EXPORT std::map parseVariables(const std::string &filename, + size_t maxIndex) +{ return parseToMap(filename, parseVertexPoint3, maxIndex); } @@ -914,6 +919,7 @@ parseMeasurements(const std::string &filename, /* ************************************************************************* */ // Implementation of parseFactors for Pose3 template <> +GTSAM_EXPORT std::vector::shared_ptr> parseFactors(const std::string &filename, const noiseModel::Diagonal::shared_ptr &model, From 1e1e2c26ee5b98f7fea8a56fba6928c73c31782b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:13:40 -0500 Subject: [PATCH 038/116] move Line3 transformTo definition to header to resolve ambiguity --- gtsam/geometry/Line3.cpp | 28 +--------------------------- gtsam/geometry/Line3.h | 27 +++++++++++++++++++++++++-- 2 files changed, 26 insertions(+), 29 deletions(-) diff --git a/gtsam/geometry/Line3.cpp b/gtsam/geometry/Line3.cpp index e3b4841e0..747a58d2f 100644 --- a/gtsam/geometry/Line3.cpp +++ b/gtsam/geometry/Line3.cpp @@ -91,30 +91,4 @@ Point3 Line3::point(double distance) const { return rotated_center + distance * R_.r3(); } -Line3 transformTo(const Pose3 &wTc, const Line3 &wL, - OptionalJacobian<4, 6> Dpose, OptionalJacobian<4, 4> Dline) { - Rot3 wRc = wTc.rotation(); - Rot3 cRw = wRc.inverse(); - Rot3 cRl = cRw * wL.R_; - - Vector2 w_ab; - Vector3 t = ((wL.R_).transpose() * wTc.translation()); - Vector2 c_ab(wL.a_ - t[0], wL.b_ - t[1]); - - if (Dpose) { - Matrix3 lRc = (cRl.matrix()).transpose(); - Dpose->setZero(); - // rotation - Dpose->block<2, 3>(0, 0) = -lRc.block<2, 3>(0, 0); - // translation - Dpose->block<2, 3>(2, 3) = -lRc.block<2, 3>(0, 0); - } - if (Dline) { - Dline->setIdentity(); - (*Dline)(0, 3) = -t[2]; - (*Dline)(1, 2) = t[2]; - } - return Line3(cRl, c_ab[0], c_ab[1]); -} - -} \ No newline at end of file +} // namespace gtsam diff --git a/gtsam/geometry/Line3.h b/gtsam/geometry/Line3.h index f70e13ca7..6dd7bf85a 100644 --- a/gtsam/geometry/Line3.h +++ b/gtsam/geometry/Line3.h @@ -26,7 +26,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class Line3 { +class GTSAM_EXPORT Line3 { private: Rot3 R_; // Rotation of line about x and y in world frame double a_, b_; // Intersection of line with the world x-y plane rotated by R_ @@ -146,7 +146,30 @@ class Line3 { */ Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian<4, 6> Dpose = boost::none, - OptionalJacobian<4, 4> Dline = boost::none); + OptionalJacobian<4, 4> Dline = boost::none) { + Rot3 wRc = wTc.rotation(); + Rot3 cRw = wRc.inverse(); + Rot3 cRl = cRw * wL.R_; + + Vector2 w_ab; + Vector3 t = ((wL.R_).transpose() * wTc.translation()); + Vector2 c_ab(wL.a_ - t[0], wL.b_ - t[1]); + + if (Dpose) { + Matrix3 lRc = (cRl.matrix()).transpose(); + Dpose->setZero(); + // rotation + Dpose->block<2, 3>(0, 0) = -lRc.block<2, 3>(0, 0); + // translation + Dpose->block<2, 3>(2, 3) = -lRc.block<2, 3>(0, 0); + } + if (Dline) { + Dline->setIdentity(); + (*Dline)(0, 3) = -t[2]; + (*Dline)(1, 2) = t[2]; + } + return Line3(cRl, c_ab[0], c_ab[1]); +} template<> struct traits : public internal::Manifold {}; From fcd418a673ef59191c6a766b2f6e446a3a540084 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:14:09 -0500 Subject: [PATCH 039/116] fixed dllexport issues in geometry, only tests failing --- gtsam/geometry/SOn.cpp | 9 +++++---- gtsam/geometry/SOn.h | 6 +++++- gtsam/geometry/Unit3.h | 28 ++++++++++++++-------------- 3 files changed, 24 insertions(+), 19 deletions(-) diff --git a/gtsam/geometry/SOn.cpp b/gtsam/geometry/SOn.cpp index c6cff4214..7088513d5 100644 --- a/gtsam/geometry/SOn.cpp +++ b/gtsam/geometry/SOn.cpp @@ -22,7 +22,7 @@ namespace gtsam { template <> -GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref X) { +void SOn::Hat(const Vector &xi, Eigen::Ref X) { size_t n = AmbientDim(xi.size()); if (n < 2) throw std::invalid_argument("SO::Hat: n<2 not supported"); @@ -48,7 +48,7 @@ GTSAM_EXPORT void SOn::Hat(const Vector &xi, Eigen::Ref X) { } } -template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) { +template <> Matrix SOn::Hat(const Vector &xi) { size_t n = AmbientDim(xi.size()); Matrix X(n, n); // allocate space for n*n skew-symmetric matrix SOn::Hat(xi, X); @@ -56,7 +56,6 @@ template <> GTSAM_EXPORT Matrix SOn::Hat(const Vector &xi) { } template <> -GTSAM_EXPORT Vector SOn::Vee(const Matrix& X) { const size_t n = X.rows(); if (n < 2) throw std::invalid_argument("SO::Hat: n<2 not supported"); @@ -104,7 +103,9 @@ SOn LieGroup::between(const SOn& g, DynamicJacobian H1, } // Dynamic version of vec -template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const { +template <> +typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const +{ const size_t n = rows(), n2 = n * n; // Vectorize diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 3af118134..af0e7a3cf 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -358,17 +358,21 @@ Vector SOn::Vee(const Matrix& X); using DynamicJacobian = OptionalJacobian; template <> +GTSAM_EXPORT SOn LieGroup::compose(const SOn& g, DynamicJacobian H1, DynamicJacobian H2) const; template <> +GTSAM_EXPORT SOn LieGroup::between(const SOn& g, DynamicJacobian H1, DynamicJacobian H2) const; /* * Specialize dynamic vec. */ -template <> typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; +template <> +GTSAM_EXPORT +typename SOn::VectorN2 SOn::vec(DynamicJacobian H) const; /** Serialization function */ template diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index c9a67dbb1..ebd5c63c9 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -40,7 +40,7 @@ namespace gtsam { /// Represents a 3D point on a unit sphere. -class Unit3 { +class GTSAM_EXPORT Unit3 { private: @@ -97,7 +97,7 @@ public: } /// Named constructor from Point3 with optional Jacobian - GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, // + static Unit3 FromPoint3(const Point3& point, // OptionalJacobian<2, 3> H = boost::none); /** @@ -106,7 +106,7 @@ public: * std::mt19937 engine(42); * Unit3 unit = Unit3::Random(engine); */ - GTSAM_EXPORT static Unit3 Random(std::mt19937 & rng); + static Unit3 Random(std::mt19937 & rng); /// @} @@ -116,7 +116,7 @@ public: friend std::ostream& operator<<(std::ostream& os, const Unit3& pair); /// The print fuction - GTSAM_EXPORT void print(const std::string& s = std::string()) const; + void print(const std::string& s = std::string()) const; /// The equals function with tolerance bool equals(const Unit3& s, double tol = 1e-9) const { @@ -133,16 +133,16 @@ public: * tangent to the sphere at the current direction. * Provides derivatives of the basis with the two basis vectors stacked up as a 6x1. */ - GTSAM_EXPORT const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const; + const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const; /// Return skew-symmetric associated with 3D point on unit sphere - GTSAM_EXPORT Matrix3 skew() const; + Matrix3 skew() const; /// Return unit-norm Point3 - GTSAM_EXPORT Point3 point3(OptionalJacobian<3, 2> H = boost::none) const; + Point3 point3(OptionalJacobian<3, 2> H = boost::none) const; /// Return unit-norm Vector - GTSAM_EXPORT Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const; + Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const; /// Return scaled direction as Point3 friend Point3 operator*(double s, const Unit3& d) { @@ -150,20 +150,20 @@ public: } /// Return dot product with q - GTSAM_EXPORT double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, // + double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, // OptionalJacobian<1,2> H2 = boost::none) const; /// Signed, vector-valued error between two directions /// @deprecated, errorVector has the proper derivatives, this confusingly has only the second. - GTSAM_EXPORT Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const; + Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const; /// Signed, vector-valued error between two directions /// NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal. - GTSAM_EXPORT Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, // + Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, // OptionalJacobian<2, 2> H_q = boost::none) const; /// Distance between two directions - GTSAM_EXPORT double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const; + double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const; /// Cross-product between two Unit3s Unit3 cross(const Unit3& q) const { @@ -196,10 +196,10 @@ public: }; /// The retract function - GTSAM_EXPORT Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const; + Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const; /// The local coordinates function - GTSAM_EXPORT Vector2 localCoordinates(const Unit3& s) const; + Vector2 localCoordinates(const Unit3& s) const; /// @} From 566c7b9cb81c9e53fb8c727ceb5b95b1829eebdd Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:15:02 -0500 Subject: [PATCH 040/116] Fix discrete module --- gtsam/discrete/AlgebraicDecisionTree.h | 4 ++-- gtsam/discrete/DiscreteLookupDAG.h | 2 +- gtsam/discrete/DiscreteMarginals.h | 2 +- gtsam/discrete/DiscreteValues.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/gtsam/discrete/AlgebraicDecisionTree.h b/gtsam/discrete/AlgebraicDecisionTree.h index 828f0b1a2..f2266c758 100644 --- a/gtsam/discrete/AlgebraicDecisionTree.h +++ b/gtsam/discrete/AlgebraicDecisionTree.h @@ -33,7 +33,7 @@ namespace gtsam { * TODO: consider eliminating this class altogether? */ template - class GTSAM_EXPORT AlgebraicDecisionTree : public DecisionTree { + class AlgebraicDecisionTree : public DecisionTree { /** * @brief Default method used by `labelFormatter` or `valueFormatter` when * printing. @@ -127,7 +127,7 @@ namespace gtsam { return map.at(label); }; std::function op = Ring::id; - this->root_ = this->template convertFrom(other.root_, L_of_M, op); + this->root_ = DecisionTree::convertFrom(other.root_, L_of_M, op); } /** sum */ diff --git a/gtsam/discrete/DiscreteLookupDAG.h b/gtsam/discrete/DiscreteLookupDAG.h index 8cb651f28..38a846f1f 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -36,7 +36,7 @@ class DiscreteBayesNet; * Inherits from discrete conditional for convenience, but is not normalized. * Is used in the max-product algorithm. */ -class DiscreteLookupTable : public DiscreteConditional { +class GTSAM_EXPORT DiscreteLookupTable : public DiscreteConditional { public: using This = DiscreteLookupTable; using shared_ptr = boost::shared_ptr; diff --git a/gtsam/discrete/DiscreteMarginals.h b/gtsam/discrete/DiscreteMarginals.h index a2207a10b..dc87f665e 100644 --- a/gtsam/discrete/DiscreteMarginals.h +++ b/gtsam/discrete/DiscreteMarginals.h @@ -29,7 +29,7 @@ namespace gtsam { /** * A class for computing marginals of variables in a DiscreteFactorGraph */ -class GTSAM_EXPORT DiscreteMarginals { +class DiscreteMarginals { protected: diff --git a/gtsam/discrete/DiscreteValues.h b/gtsam/discrete/DiscreteValues.h index 81997a783..cb17bf833 100644 --- a/gtsam/discrete/DiscreteValues.h +++ b/gtsam/discrete/DiscreteValues.h @@ -37,7 +37,7 @@ namespace gtsam { * stores cardinality of a Discrete variable. It should be handled naturally in * the new class DiscreteValue, as the variable's type (domain) */ -class DiscreteValues : public Assignment { +class GTSAM_EXPORT DiscreteValues : public Assignment { public: using Base = Assignment; // base class From 770587ddafb180aa1250215b3d1f8a08ce9fe216 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:15:15 -0500 Subject: [PATCH 041/116] documentation updates --- DEVELOP.md | 2 +- Using-GTSAM-EXPORT.md | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/DEVELOP.md b/DEVELOP.md index 8604afe0f..7cd303373 100644 --- a/DEVELOP.md +++ b/DEVELOP.md @@ -15,7 +15,7 @@ For example: ```cpp class GTSAM_EXPORT MyClass { ... }; -GTSAM_EXPORT myFunction(); +GTSAM_EXPORT return_type myFunction(); ``` More details [here](Using-GTSAM-EXPORT.md). diff --git a/Using-GTSAM-EXPORT.md b/Using-GTSAM-EXPORT.md index faeebc97f..24a29f96b 100644 --- a/Using-GTSAM-EXPORT.md +++ b/Using-GTSAM-EXPORT.md @@ -8,6 +8,7 @@ To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and need * At least one of the functions inside that class is declared in a .cpp file and not just the .h file. * You can `GTSAM_EXPORT` any class it inherits from as well. (Note that this implictly requires the class does not derive from a "header-only" class. Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!) 3. If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations. (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.) +4. For template specializations, you need to add `GTSAM_EXPORT` to each individual specialization. ## When is GTSAM_EXPORT being used incorrectly Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library. For example, an error in `gtsam/base` will often show up when compiling the `check_base_program` or the MATLAB wrapper, but not when compiling/linking gtsam itself. The most common errors will say something like: From d860e39561e7da0e34c8c2aa77ab45c76fdc47b7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:16:13 -0500 Subject: [PATCH 042/116] suppress spurious warnings --- cmake/GtsamBuildTypes.cmake | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 4b179d128..fac2bdba5 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -93,6 +93,10 @@ if(MSVC) /wd4267 # warning C4267: 'initializing': conversion from 'size_t' to 'int', possible loss of data ) + add_compile_options(/wd4005) + add_compile_options(/wd4101) + add_compile_options(/wd4834) + endif() # Other (non-preprocessor macros) compiler flags: From 9a234a2830f256b31c04419568169e825eba757a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:16:35 -0500 Subject: [PATCH 043/116] build (almost) all GTSAM test targets in CI --- .github/workflows/build-windows.yml | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index a9e794b3f..9785eb7d7 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -106,6 +106,21 @@ jobs: cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam_unstable cmake --build build -j 4 --config ${{ matrix.build_type }} --target wrap + + # Run GTSAM tests cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.basis + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.discrete + #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.geometry + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.inference cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.navigation + #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.nonlinear + #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sam + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sfm + #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.slam + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.symbolic + + # Run GTSAM_UNSTABLE tests + cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable + From 12d1d21e28d1fa8c29f1ea8710d16b2e8c7129b0 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 11:21:51 -0500 Subject: [PATCH 044/116] formatting updates --- gtsam/slam/dataset.cpp | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 6c8e43108..71dd64dbb 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -177,9 +177,8 @@ boost::optional parseVertexPose(istream &is, const string &tag) { } template <> -GTSAM_EXPORT std::map parseVariables(const std::string &filename, - size_t maxIndex) -{ +GTSAM_EXPORT std::map parseVariables( + const std::string &filename, size_t maxIndex) { return parseToMap(filename, parseVertexPose, maxIndex); } @@ -200,9 +199,8 @@ boost::optional parseVertexLandmark(istream &is, } template <> -GTSAM_EXPORT std::map parseVariables(const std::string &filename, - size_t maxIndex) -{ +GTSAM_EXPORT std::map parseVariables( + const std::string &filename, size_t maxIndex) { return parseToMap(filename, parseVertexLandmark, maxIndex); } @@ -780,9 +778,8 @@ boost::optional> parseVertexPose3(istream &is, } template <> -GTSAM_EXPORT std::map parseVariables(const std::string &filename, - size_t maxIndex) -{ +GTSAM_EXPORT std::map parseVariables( + const std::string &filename, size_t maxIndex) { return parseToMap(filename, parseVertexPose3, maxIndex); } @@ -799,9 +796,8 @@ boost::optional> parseVertexPoint3(istream &is, } template <> -GTSAM_EXPORT std::map parseVariables(const std::string &filename, - size_t maxIndex) -{ +GTSAM_EXPORT std::map parseVariables( + const std::string &filename, size_t maxIndex) { return parseToMap(filename, parseVertexPoint3, maxIndex); } From 6fe55af512e6293a6e4801bb4d17b9c7782e6397 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 14:45:34 -0500 Subject: [PATCH 045/116] comment out gtsam_unstable test target --- .github/workflows/build-windows.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index 9785eb7d7..0cc67ad5a 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -122,5 +122,5 @@ jobs: cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.symbolic # Run GTSAM_UNSTABLE tests - cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable + #cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable From 1545d9007b3d7bc9e35d163e30547c131accd047 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 17 Feb 2022 15:27:01 -0500 Subject: [PATCH 046/116] Move transformTo declaration to the top to avoid ambiguous linkage --- gtsam/geometry/Line3.cpp | 26 +++++++++++++++++++++ gtsam/geometry/Line3.h | 50 ++++++++++++---------------------------- 2 files changed, 41 insertions(+), 35 deletions(-) diff --git a/gtsam/geometry/Line3.cpp b/gtsam/geometry/Line3.cpp index 747a58d2f..9e7b2e13e 100644 --- a/gtsam/geometry/Line3.cpp +++ b/gtsam/geometry/Line3.cpp @@ -91,4 +91,30 @@ Point3 Line3::point(double distance) const { return rotated_center + distance * R_.r3(); } +Line3 transformTo(const Pose3 &wTc, const Line3 &wL, + OptionalJacobian<4, 6> Dpose, OptionalJacobian<4, 4> Dline) { + Rot3 wRc = wTc.rotation(); + Rot3 cRw = wRc.inverse(); + Rot3 cRl = cRw * wL.R_; + + Vector2 w_ab; + Vector3 t = ((wL.R_).transpose() * wTc.translation()); + Vector2 c_ab(wL.a_ - t[0], wL.b_ - t[1]); + + if (Dpose) { + Matrix3 lRc = (cRl.matrix()).transpose(); + Dpose->setZero(); + // rotation + Dpose->block<2, 3>(0, 0) = -lRc.block<2, 3>(0, 0); + // translation + Dpose->block<2, 3>(2, 3) = -lRc.block<2, 3>(0, 0); + } + if (Dline) { + Dline->setIdentity(); + (*Dline)(0, 3) = -t[2]; + (*Dline)(1, 2) = t[2]; + } + return Line3(cRl, c_ab[0], c_ab[1]); +} + } // namespace gtsam diff --git a/gtsam/geometry/Line3.h b/gtsam/geometry/Line3.h index 6dd7bf85a..78827274a 100644 --- a/gtsam/geometry/Line3.h +++ b/gtsam/geometry/Line3.h @@ -21,6 +21,21 @@ namespace gtsam { +class Line3; + +/** + * Transform a line from world to camera frame + * @param wTc - Pose3 of camera in world frame + * @param wL - Line3 in world frame + * @param Dpose - OptionalJacobian of transformed line with respect to p + * @param Dline - OptionalJacobian of transformed line with respect to l + * @return Transformed line in camera frame + */ +GTSAM_EXPORT Line3 transformTo(const Pose3 &wTc, const Line3 &wL, + OptionalJacobian<4, 6> Dpose = boost::none, + OptionalJacobian<4, 4> Dline = boost::none); + + /** * A 3D line (R,a,b) : (Rot3,Scalar,Scalar) * @addtogroup geometry @@ -136,41 +151,6 @@ class GTSAM_EXPORT Line3 { OptionalJacobian<4, 4> Dline); }; -/** - * Transform a line from world to camera frame - * @param wTc - Pose3 of camera in world frame - * @param wL - Line3 in world frame - * @param Dpose - OptionalJacobian of transformed line with respect to p - * @param Dline - OptionalJacobian of transformed line with respect to l - * @return Transformed line in camera frame - */ -Line3 transformTo(const Pose3 &wTc, const Line3 &wL, - OptionalJacobian<4, 6> Dpose = boost::none, - OptionalJacobian<4, 4> Dline = boost::none) { - Rot3 wRc = wTc.rotation(); - Rot3 cRw = wRc.inverse(); - Rot3 cRl = cRw * wL.R_; - - Vector2 w_ab; - Vector3 t = ((wL.R_).transpose() * wTc.translation()); - Vector2 c_ab(wL.a_ - t[0], wL.b_ - t[1]); - - if (Dpose) { - Matrix3 lRc = (cRl.matrix()).transpose(); - Dpose->setZero(); - // rotation - Dpose->block<2, 3>(0, 0) = -lRc.block<2, 3>(0, 0); - // translation - Dpose->block<2, 3>(2, 3) = -lRc.block<2, 3>(0, 0); - } - if (Dline) { - Dline->setIdentity(); - (*Dline)(0, 3) = -t[2]; - (*Dline)(1, 2) = t[2]; - } - return Line3(cRl, c_ab[0], c_ab[1]); -} - template<> struct traits : public internal::Manifold {}; From ac9eed6444c053b583ee40a9f85bd0e8e0971d4f Mon Sep 17 00:00:00 2001 From: Andre Nguyen Date: Thu, 17 Feb 2022 23:21:57 -0500 Subject: [PATCH 047/116] fix: typo --- tests/testExpressionFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/testExpressionFactor.cpp b/tests/testExpressionFactor.cpp index 75425a0cd..6d23144aa 100644 --- a/tests/testExpressionFactor.cpp +++ b/tests/testExpressionFactor.cpp @@ -231,7 +231,7 @@ TEST(ExpressionFactor, Shallow) { Pose3_ x_(1); Point3_ p_(2); - // Construct expression, concise evrsion + // Construct expression, concise version Point2_ expression = project(transformTo(x_, p_)); // Get and check keys and dims From 57a51a7c07caedb8ddf49de02a940154ff1041ff Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Fri, 18 Feb 2022 00:04:51 -0800 Subject: [PATCH 048/116] Assignment accidentally used in place of equality --- gtsam/discrete/tests/testAlgebraicDecisionTree.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index 9d130a1f6..56cdf7524 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -318,7 +318,7 @@ TEST(ADT, factor_graph) { dot(fg, "Marginalized-3E"); fg = fg.combine(L, &add_); dot(fg, "Marginalized-2L"); - EXPECT(adds = 54); + EXPECT(adds == 54); gttoc_(marg); tictoc_getNode(margNode, marg); elapsed = margNode->secs() + margNode->wall(); From 31e1a713fc0a4a3fa3fe3751369c5bcf5ea26755 Mon Sep 17 00:00:00 2001 From: lcarlone Date: Fri, 18 Feb 2022 20:23:45 -0500 Subject: [PATCH 049/116] added unit test on params --- tests/testGncOptimizer.cpp | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/tests/testGncOptimizer.cpp b/tests/testGncOptimizer.cpp index a3d1e4e9b..c3335ce20 100644 --- a/tests/testGncOptimizer.cpp +++ b/tests/testGncOptimizer.cpp @@ -98,6 +98,30 @@ TEST(GncOptimizer, gncConstructor) { CHECK(gnc.equals(gnc2)); } +/* ************************************************************************* */ +TEST(GncOptimizer, solverParameterParsing) { + // has to have Gaussian noise models ! + auto fg = example::createReallyNonlinearFactorGraph(); // just a unary factor + // on a 2D point + + Point2 p0(3, 3); + Values initial; + initial.insert(X(1), p0); + + LevenbergMarquardtParams lmParams; + lmParams.setMaxIterations(0); // forces not to perform optimization + GncParams gncParams(lmParams); + auto gnc = GncOptimizer>(fg, initial, + gncParams); + Values result = gnc.optimize(); + + // check that LM did not perform optimization and result is the same as the initial guess + DOUBLES_EQUAL(fg.error(initial), fg.error(result), tol); + + // also check the params: + DOUBLES_EQUAL(0.0, gncParams.baseOptimizerParams.maxIterations, tol); +} + /* ************************************************************************* */ TEST(GncOptimizer, gncConstructorWithRobustGraphAsInput) { auto fg = example::sharedNonRobustFactorGraphWithOutliers(); From 3e003bdf46b4f0dafb3aca36bf18338bbb11b3ab Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 19 Feb 2022 11:09:42 -0500 Subject: [PATCH 050/116] Add missing header for timing target --- timing/timeSFMBAL.h | 1 + 1 file changed, 1 insertion(+) diff --git a/timing/timeSFMBAL.h b/timing/timeSFMBAL.h index 79d7432c8..e24b50089 100644 --- a/timing/timeSFMBAL.h +++ b/timing/timeSFMBAL.h @@ -17,6 +17,7 @@ */ #include +#include #include #include #include From 5f48ac5bbf48e45da14acf91cd45f76f5a5e54d2 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 19 Feb 2022 16:36:15 -0500 Subject: [PATCH 051/116] removed obsolete header --- gtsam/basis/Chebyshev.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/gtsam/basis/Chebyshev.h b/gtsam/basis/Chebyshev.h index d16ccfaac..87599acdc 100644 --- a/gtsam/basis/Chebyshev.h +++ b/gtsam/basis/Chebyshev.h @@ -21,8 +21,6 @@ #include #include -#include - namespace gtsam { /** From 026cfca0d96085b9bfed154266ee534a0309fd0d Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Sun, 20 Feb 2022 02:53:15 -0500 Subject: [PATCH 052/116] replace ifndefs with pragma once --- gtsam_unstable/slam/AHRS.h | 4 +--- wrap/pybind11/tests/object.h | 5 +---- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/gtsam_unstable/slam/AHRS.h b/gtsam_unstable/slam/AHRS.h index 35b4677d5..714e62288 100644 --- a/gtsam_unstable/slam/AHRS.h +++ b/gtsam_unstable/slam/AHRS.h @@ -5,8 +5,7 @@ * Author: cbeall3 */ -#ifndef AHRS_H_ -#define AHRS_H_ +#pragma once #include "Mechanization_bRn2.h" #include @@ -82,4 +81,3 @@ public: }; } /* namespace gtsam */ -#endif /* AHRS_H_ */ diff --git a/wrap/pybind11/tests/object.h b/wrap/pybind11/tests/object.h index 9235f19c2..9fbbc69f0 100644 --- a/wrap/pybind11/tests/object.h +++ b/wrap/pybind11/tests/object.h @@ -1,5 +1,4 @@ -#if !defined(__OBJECT_H) -#define __OBJECT_H +#pragma once #include #include "constructor_stats.h" @@ -171,5 +170,3 @@ public: private: T *m_ptr; }; - -#endif /* __OBJECT_H */ From e4733e720f758f1e158cd51731075efdc0124516 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Mon, 21 Feb 2022 02:49:54 -0800 Subject: [PATCH 053/116] * Repaired actual test (needs '49', not '54'?) and LONGS_EQUAL instead of EQUAL -- Please review * Added GTSAM_EXPORT back to to AlgebraicDecisionTree.h and added a .cpp file to accompany the .h. The only contents of the file are the specialization AlgebraicDecisionTree. This seems to make the linker happy enough to include the symbols that allow the above test to run. --- gtsam/discrete/AlgebraicDecisionTree.cpp | 28 +++++++++++++++++++ gtsam/discrete/AlgebraicDecisionTree.h | 2 +- .../tests/testAlgebraicDecisionTree.cpp | 2 +- 3 files changed, 30 insertions(+), 2 deletions(-) create mode 100644 gtsam/discrete/AlgebraicDecisionTree.cpp diff --git a/gtsam/discrete/AlgebraicDecisionTree.cpp b/gtsam/discrete/AlgebraicDecisionTree.cpp new file mode 100644 index 000000000..83ee4051a --- /dev/null +++ b/gtsam/discrete/AlgebraicDecisionTree.cpp @@ -0,0 +1,28 @@ +/* ---------------------------------------------------------------------------- + + * 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 AlgebraicDecisionTree.cpp + * @date Feb 20, 2022 + * @author Mike Sheffler + * @author Duy-Nguyen Ta + * @author Frank Dellaert + */ + +#include "AlgebraicDecisionTree.h" + +#include + +namespace gtsam { + + template class AlgebraicDecisionTree; + +} // namespace gtsam diff --git a/gtsam/discrete/AlgebraicDecisionTree.h b/gtsam/discrete/AlgebraicDecisionTree.h index f2266c758..a2ceac834 100644 --- a/gtsam/discrete/AlgebraicDecisionTree.h +++ b/gtsam/discrete/AlgebraicDecisionTree.h @@ -33,7 +33,7 @@ namespace gtsam { * TODO: consider eliminating this class altogether? */ template - class AlgebraicDecisionTree : public DecisionTree { + class GTSAM_EXPORT AlgebraicDecisionTree : public DecisionTree { /** * @brief Default method used by `labelFormatter` or `valueFormatter` when * printing. diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index 56cdf7524..c800321d6 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -318,7 +318,7 @@ TEST(ADT, factor_graph) { dot(fg, "Marginalized-3E"); fg = fg.combine(L, &add_); dot(fg, "Marginalized-2L"); - EXPECT(adds == 54); + LONGS_EQUAL(49, adds); gttoc_(marg); tictoc_getNode(margNode, marg); elapsed = margNode->secs() + margNode->wall(); From 3f4decb77b5b837e3a3852146e525be796675b32 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 21 Feb 2022 08:00:15 -0500 Subject: [PATCH 054/116] fix incorrect filename warning --- tests/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 068b39eca..5eaad45dc 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -3,14 +3,14 @@ set (tests_exclude "") if (${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang") # might not be best test - Richard & Jason & Frank - # clang linker segfaults on large testSerializationSLAM - list (APPEND tests_exclude "testSerializationSLAM.cpp") + # clang linker segfaults on large testSerializationSlam + list (APPEND tests_exclude "testSerializationSlam.cpp") endif() # Build tests gtsamAddTestsGlob(tests "test*.cpp" "${tests_exclude}" "gtsam") if(MSVC) - set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSLAM.cpp" + set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSlam.cpp" APPEND PROPERTY COMPILE_FLAGS "/bigobj") endif() From b72b65ddf26f39f356edecb5e155483d04785f6d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 21 Feb 2022 08:00:27 -0500 Subject: [PATCH 055/116] properly set project version --- CMakeLists.txt | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c637796cf..b86598663 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,3 @@ -project(GTSAM CXX C) cmake_minimum_required(VERSION 3.0) # new feature to Cmake Version > 2.8.12 @@ -19,6 +18,11 @@ if (${GTSAM_VERSION_PATCH} EQUAL 0) else() set (GTSAM_VERSION_STRING "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}${GTSAM_PRERELEASE_VERSION}") endif() + +project(GTSAM + LANGUAGES CXX C + VERSION "${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}") + message(STATUS "GTSAM Version: ${GTSAM_VERSION_STRING}") set (CMAKE_PROJECT_VERSION_MAJOR ${GTSAM_VERSION_MAJOR}) From 6ae319e4010282e81cc6f9734f62541e127c4191 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 11:49:17 -0500 Subject: [PATCH 056/116] add missing header guards under gtsam/ --- gtsam/discrete/DiscreteJunctionTree.h | 2 ++ gtsam/geometry/Cyclic.h | 2 ++ gtsam/linear/GaussianJunctionTree.h | 2 ++ gtsam/linear/linearAlgorithms-inst.h | 2 ++ gtsam/linear/tests/powerMethodExample.h | 2 ++ gtsam/navigation/ConstantVelocityFactor.h | 2 ++ gtsam/navigation/MagFactor.h | 2 ++ gtsam/nonlinear/WhiteNoiseFactor.h | 2 ++ gtsam/nonlinear/internal/LevenbergMarquardtState.h | 2 ++ gtsam/sfm/TranslationRecovery.h | 2 ++ gtsam/slam/TriangulationFactor.h | 2 ++ gtsam/symbolic/SymbolicJunctionTree.h | 2 ++ 12 files changed, 24 insertions(+) diff --git a/gtsam/discrete/DiscreteJunctionTree.h b/gtsam/discrete/DiscreteJunctionTree.h index f5bc9be1d..c74ad3cc2 100644 --- a/gtsam/discrete/DiscreteJunctionTree.h +++ b/gtsam/discrete/DiscreteJunctionTree.h @@ -16,6 +16,8 @@ * @author Richard Roberts */ +#pragma once + #include #include #include diff --git a/gtsam/geometry/Cyclic.h b/gtsam/geometry/Cyclic.h index 35578ffe0..065cd0140 100644 --- a/gtsam/geometry/Cyclic.h +++ b/gtsam/geometry/Cyclic.h @@ -15,6 +15,8 @@ * @author Frank Dellaert **/ +#pragma once + #include #include diff --git a/gtsam/linear/GaussianJunctionTree.h b/gtsam/linear/GaussianJunctionTree.h index 67e5a374b..c7f13ea5c 100644 --- a/gtsam/linear/GaussianJunctionTree.h +++ b/gtsam/linear/GaussianJunctionTree.h @@ -16,6 +16,8 @@ * @author Richard Roberts */ +#pragma once + #include #include #include diff --git a/gtsam/linear/linearAlgorithms-inst.h b/gtsam/linear/linearAlgorithms-inst.h index 811e07121..d19ac6de5 100644 --- a/gtsam/linear/linearAlgorithms-inst.h +++ b/gtsam/linear/linearAlgorithms-inst.h @@ -15,6 +15,8 @@ * @author Richard Roberts */ +#pragma once + #include #include #include diff --git a/gtsam/linear/tests/powerMethodExample.h b/gtsam/linear/tests/powerMethodExample.h index f80299386..994fcc640 100644 --- a/gtsam/linear/tests/powerMethodExample.h +++ b/gtsam/linear/tests/powerMethodExample.h @@ -19,6 +19,8 @@ * PowerMethod/AcceleratedPowerMethod */ +#pragma once + #include #include diff --git a/gtsam/navigation/ConstantVelocityFactor.h b/gtsam/navigation/ConstantVelocityFactor.h index ed68ac077..6ab4c2f02 100644 --- a/gtsam/navigation/ConstantVelocityFactor.h +++ b/gtsam/navigation/ConstantVelocityFactor.h @@ -15,6 +15,8 @@ * @author Asa Hammond */ +#pragma once + #include #include diff --git a/gtsam/navigation/MagFactor.h b/gtsam/navigation/MagFactor.h index 74e9177d5..895ac6512 100644 --- a/gtsam/navigation/MagFactor.h +++ b/gtsam/navigation/MagFactor.h @@ -16,6 +16,8 @@ * @date January 29, 2014 */ +#pragma once + #include #include #include diff --git a/gtsam/nonlinear/WhiteNoiseFactor.h b/gtsam/nonlinear/WhiteNoiseFactor.h index 95f46ab6c..1cd117437 100644 --- a/gtsam/nonlinear/WhiteNoiseFactor.h +++ b/gtsam/nonlinear/WhiteNoiseFactor.h @@ -17,6 +17,8 @@ * @date September 2011 */ +#pragma once + #include #include #include diff --git a/gtsam/nonlinear/internal/LevenbergMarquardtState.h b/gtsam/nonlinear/internal/LevenbergMarquardtState.h index cee839540..75e5a5135 100644 --- a/gtsam/nonlinear/internal/LevenbergMarquardtState.h +++ b/gtsam/nonlinear/internal/LevenbergMarquardtState.h @@ -16,6 +16,8 @@ * @date April 2016 */ +#pragma once + #include "NonlinearOptimizerState.h" #include diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index c99836853..620a1c130 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -16,6 +16,8 @@ * @brief Recovering translations in an epipolar graph when rotations are given. */ +#pragma once + #include #include #include diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 40e9538e2..b6da02d55 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -15,6 +15,8 @@ * @author Frank Dellaert */ +#pragma once + #include #include #include diff --git a/gtsam/symbolic/SymbolicJunctionTree.h b/gtsam/symbolic/SymbolicJunctionTree.h index 7a152e532..0dcfae541 100644 --- a/gtsam/symbolic/SymbolicJunctionTree.h +++ b/gtsam/symbolic/SymbolicJunctionTree.h @@ -16,6 +16,8 @@ * @author Richard Roberts */ +#pragma once + #include #include #include From 6d1e7ebce41f19be4c0fafb53f72337df5ecda7f Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 11:56:12 -0500 Subject: [PATCH 057/116] add missing header guards under gtsam_unstable/ --- gtsam_unstable/base/BTree.h | 2 ++ gtsam_unstable/base/Dummy.h | 2 ++ gtsam_unstable/linear/ActiveSetSolver-inl.h | 2 ++ gtsam_unstable/linear/LPSolver.h | 2 ++ gtsam_unstable/linear/QPSolver.h | 2 ++ gtsam_unstable/partition/FindSeparator.h | 2 ++ 6 files changed, 12 insertions(+) diff --git a/gtsam_unstable/base/BTree.h b/gtsam_unstable/base/BTree.h index 9d854a169..94e27d6c4 100644 --- a/gtsam_unstable/base/BTree.h +++ b/gtsam_unstable/base/BTree.h @@ -17,6 +17,8 @@ * @date Feb 3, 2010 */ +#pragma once + #include #include #include diff --git a/gtsam_unstable/base/Dummy.h b/gtsam_unstable/base/Dummy.h index a2f544de5..548bce344 100644 --- a/gtsam_unstable/base/Dummy.h +++ b/gtsam_unstable/base/Dummy.h @@ -17,6 +17,8 @@ * @date June 14, 2012 */ +#pragma once + #include #include #include diff --git a/gtsam_unstable/linear/ActiveSetSolver-inl.h b/gtsam_unstable/linear/ActiveSetSolver-inl.h index 12374ac76..a0f7e5337 100644 --- a/gtsam_unstable/linear/ActiveSetSolver-inl.h +++ b/gtsam_unstable/linear/ActiveSetSolver-inl.h @@ -17,6 +17,8 @@ * @date 2/11/16 */ +#pragma once + #include /******************************************************************************/ diff --git a/gtsam_unstable/linear/LPSolver.h b/gtsam_unstable/linear/LPSolver.h index 460b4b7ee..f36462bda 100644 --- a/gtsam_unstable/linear/LPSolver.h +++ b/gtsam_unstable/linear/LPSolver.h @@ -17,6 +17,8 @@ * @date 6/16/16 */ +#pragma once + #include #include #include diff --git a/gtsam_unstable/linear/QPSolver.h b/gtsam_unstable/linear/QPSolver.h index 3854d2a15..86cf51f1c 100644 --- a/gtsam_unstable/linear/QPSolver.h +++ b/gtsam_unstable/linear/QPSolver.h @@ -17,6 +17,8 @@ * @date 6/16/16 */ +#pragma once + #include #include #include diff --git a/gtsam_unstable/partition/FindSeparator.h b/gtsam_unstable/partition/FindSeparator.h index 42d971a82..f4342695b 100644 --- a/gtsam_unstable/partition/FindSeparator.h +++ b/gtsam_unstable/partition/FindSeparator.h @@ -6,6 +6,8 @@ * Description: find the separator of bisectioning for a given graph */ +#pragma once + #include #include #include From 2ba86834547cfadc852eb72e32dcaeccf0c81c2f Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 11:56:32 -0500 Subject: [PATCH 058/116] add newline at end of file --- gtsam_unstable/linear/ActiveSetSolver-inl.h | 2 +- gtsam_unstable/linear/QPSolver.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/linear/ActiveSetSolver-inl.h b/gtsam_unstable/linear/ActiveSetSolver-inl.h index a0f7e5337..350985cf4 100644 --- a/gtsam_unstable/linear/ActiveSetSolver-inl.h +++ b/gtsam_unstable/linear/ActiveSetSolver-inl.h @@ -285,4 +285,4 @@ Template std::pair This::optimize() const { } #undef Template -#undef This \ No newline at end of file +#undef This diff --git a/gtsam_unstable/linear/QPSolver.h b/gtsam_unstable/linear/QPSolver.h index 86cf51f1c..ae87b3ab7 100644 --- a/gtsam_unstable/linear/QPSolver.h +++ b/gtsam_unstable/linear/QPSolver.h @@ -47,4 +47,4 @@ struct QPPolicy { using QPSolver = ActiveSetSolver; -} \ No newline at end of file +} From 1bf53fc414c662bdc42ddf9d780d5556bb4e1a0f Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 11:59:01 -0500 Subject: [PATCH 059/116] add missing header guards under timing/ and examples/ --- examples/SFMdata.h | 2 ++ timing/timeSFMBAL.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/examples/SFMdata.h b/examples/SFMdata.h index 04d3c9e47..95f129da9 100644 --- a/examples/SFMdata.h +++ b/examples/SFMdata.h @@ -22,6 +22,8 @@ * Passing function argument allows to specificy an initial position, a pose increment and step count. */ +#pragma once + // As this is a full 3D problem, we will use Pose3 variables to represent the camera // positions and Point3 variables (x, y, z) to represent the landmark coordinates. // Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y). diff --git a/timing/timeSFMBAL.h b/timing/timeSFMBAL.h index e24b50089..7af798887 100644 --- a/timing/timeSFMBAL.h +++ b/timing/timeSFMBAL.h @@ -16,6 +16,8 @@ * @date July 5, 2015 */ +#pragma once + #include #include #include From 67fc9a93e2d7073a480b0cb8339e94c1dbee5d6b Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 11:59:26 -0500 Subject: [PATCH 060/116] add newline at end of file --- examples/SFMdata.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/SFMdata.h b/examples/SFMdata.h index 95f129da9..3031828f1 100644 --- a/examples/SFMdata.h +++ b/examples/SFMdata.h @@ -68,4 +68,4 @@ std::vector createPoses( } return poses; -} \ No newline at end of file +} From 5d3b0bf1c1407c8b3a56e4a70fb382080422ea17 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 17:22:39 -0500 Subject: [PATCH 061/116] only metis.h is needed to include both system and local metis.h file metislib.h can be changed to <> due to cmake changes --- gtsam/inference/Ordering.cpp | 4 ---- gtsam_unstable/partition/FindSeparator-inl.h | 2 +- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/gtsam/inference/Ordering.cpp b/gtsam/inference/Ordering.cpp index 440d2b828..2ac2c0dde 100644 --- a/gtsam/inference/Ordering.cpp +++ b/gtsam/inference/Ordering.cpp @@ -25,11 +25,7 @@ #include #ifdef GTSAM_SUPPORT_NESTED_DISSECTION -#ifdef GTSAM_USE_SYSTEM_METIS #include -#else -#include -#endif #endif using namespace std; diff --git a/gtsam_unstable/partition/FindSeparator-inl.h b/gtsam_unstable/partition/FindSeparator-inl.h index 2e48b0d45..5ec8813b9 100644 --- a/gtsam_unstable/partition/FindSeparator-inl.h +++ b/gtsam_unstable/partition/FindSeparator-inl.h @@ -24,7 +24,7 @@ extern "C" { #include -#include "metislib.h" +#include } From c7374307f4dfdbddec241fb527dfc559d89c1244 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Mon, 21 Feb 2022 18:14:49 -0500 Subject: [PATCH 062/116] use internal metislib.h; extern C for system&local --- cmake/HandleMetis.cmake | 11 +++++++++-- gtsam_unstable/partition/FindSeparator-inl.h | 5 +---- gtsam_unstable/partition/tests/testFindSeparator.cpp | 4 ---- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/cmake/HandleMetis.cmake b/cmake/HandleMetis.cmake index 9c29e5776..d74621654 100644 --- a/cmake/HandleMetis.cmake +++ b/cmake/HandleMetis.cmake @@ -21,7 +21,12 @@ if(GTSAM_USE_SYSTEM_METIS) mark_as_advanced(METIS_LIBRARY) add_library(metis-gtsam-if INTERFACE) - target_include_directories(metis-gtsam-if BEFORE INTERFACE ${METIS_INCLUDE_DIR}) + target_include_directories(metis-gtsam-if BEFORE INTERFACE ${METIS_INCLUDE_DIR} + # gtsam_unstable/partition/FindSeparator-inl.h uses internel metislib.h API + # via extern "C" + $ + $ + ) target_link_libraries(metis-gtsam-if INTERFACE ${METIS_LIBRARY}) endif() else() @@ -30,10 +35,12 @@ else() add_subdirectory(${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis) target_include_directories(metis-gtsam BEFORE PUBLIC + $ $ + # gtsam_unstable/partition/FindSeparator-inl.h uses internel metislib.h API + # via extern "C" $ $ - $ ) add_library(metis-gtsam-if INTERFACE) diff --git a/gtsam_unstable/partition/FindSeparator-inl.h b/gtsam_unstable/partition/FindSeparator-inl.h index 5ec8813b9..0e4950b79 100644 --- a/gtsam_unstable/partition/FindSeparator-inl.h +++ b/gtsam_unstable/partition/FindSeparator-inl.h @@ -20,10 +20,9 @@ #include "FindSeparator.h" -#ifndef GTSAM_USE_SYSTEM_METIS +#include extern "C" { -#include #include } @@ -566,5 +565,3 @@ namespace gtsam { namespace partition { } }} //namespace - -#endif diff --git a/gtsam_unstable/partition/tests/testFindSeparator.cpp b/gtsam_unstable/partition/tests/testFindSeparator.cpp index 63acc8f18..fe49de928 100644 --- a/gtsam_unstable/partition/tests/testFindSeparator.cpp +++ b/gtsam_unstable/partition/tests/testFindSeparator.cpp @@ -20,8 +20,6 @@ using namespace std; using namespace gtsam; using namespace gtsam::partition; -#ifndef GTSAM_USE_SYSTEM_METIS - /* ************************************************************************* */ // x0 - x1 - x2 // l3 l4 @@ -229,8 +227,6 @@ TEST ( Partition, findSeparator3_with_reduced_camera ) LONGS_EQUAL(2, partitionTable[28]); } -#endif - /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr);} /* ************************************************************************* */ From c10f1954921bea36baf0fda3ebc6b10e0ca0e5da Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Tue, 22 Feb 2022 22:42:14 -0800 Subject: [PATCH 063/116] use rng in TA initialization --- gtsam/sfm/TranslationRecovery.cpp | 17 +++++++++++++---- gtsam/sfm/TranslationRecovery.h | 12 ++++++++++-- 2 files changed, 23 insertions(+), 6 deletions(-) diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index f38c14ba7..aa7b14709 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -35,6 +35,9 @@ using namespace gtsam; using namespace std; +// In Wrappers we have no access to this so have a default ready. +static std::mt19937 kRandomNumberGenerator(42); + TranslationRecovery::TranslationRecovery( const TranslationRecovery::TranslationEdges &relativeTranslations, const LevenbergMarquardtParams &lmParams) @@ -88,13 +91,15 @@ void TranslationRecovery::addPrior( edge->key2(), scale * edge->measured().point3(), edge->noiseModel()); } -Values TranslationRecovery::initalizeRandomly() const { +Values TranslationRecovery::initializeRandomly(std::mt19937 &rng) const { + uniform_real_distribution randomVal(-1, 1); // Create a lambda expression that checks whether value exists and randomly // initializes if not. Values initial; - auto insert = [&initial](Key j) { + auto insert = [&initial, &rng, &randomVal](Key j) { if (!initial.exists(j)) { - initial.insert(j, Vector3::Random()); + initial.insert( + j, Point3(randomVal(rng), randomVal(rng), randomVal(rng))); } }; @@ -115,10 +120,14 @@ Values TranslationRecovery::initalizeRandomly() const { return initial; } +Values TranslationRecovery::initializeRandomly() const { + return initializeRandomly(kRandomNumberGenerator); +} + Values TranslationRecovery::run(const double scale) const { auto graph = buildGraph(); addPrior(scale, &graph); - const Values initial = initalizeRandomly(); + const Values initial = initializeRandomly(); LevenbergMarquardtOptimizer lm(graph, initial, params_); Values result = lm.optimize(); diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index c99836853..430b54d1d 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -99,10 +99,18 @@ class TranslationRecovery { /** * @brief Create random initial translations. - * + * + * @param rng random number generator * @return Values */ - Values initalizeRandomly() const; + Values initializeRandomly(std::mt19937 &rng) const; + + /** + * @brief Version of initializeRandomly with a fixed seed. + * + * @return Values + */ + Values initializeRandomly() const; /** * @brief Build and optimize factor graph. From 24173ab025badc7a01d4828a76280d580145ae85 Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Tue, 22 Feb 2022 22:42:42 -0800 Subject: [PATCH 064/116] update comment in shonan --- gtsam/sfm/ShonanAveraging.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/sfm/ShonanAveraging.h b/gtsam/sfm/ShonanAveraging.h index de12de478..8be16e204 100644 --- a/gtsam/sfm/ShonanAveraging.h +++ b/gtsam/sfm/ShonanAveraging.h @@ -300,6 +300,7 @@ class GTSAM_EXPORT ShonanAveraging { /** * Create initial Values of type SO(p) * @param p the dimensionality of the rotation manifold + * @param rng random number generator */ Values initializeRandomlyAt(size_t p, std::mt19937 &rng) const; From 93519e4ccaca89081e20380bdcebf0fe3ff05a32 Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Thu, 24 Feb 2022 23:22:05 -0800 Subject: [PATCH 065/116] updating tolerance in tests --- tests/testTranslationRecovery.cpp | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 2915a375e..090f2e1cb 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -116,8 +116,8 @@ TEST(TranslationRecovery, TwoPoseTest) { const auto result = algorithm.run(/*scale=*/3.0); // Check result for first two translations, determined by prior - EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(3, 0, 0), result.at(1))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0), 1e-8)); + EXPECT(assert_equal(Point3(3, 0, 0), result.at(1), 1e-8)); } TEST(TranslationRecovery, ThreePoseTest) { @@ -153,9 +153,9 @@ TEST(TranslationRecovery, ThreePoseTest) { const auto result = algorithm.run(/*scale=*/3.0); // Check result - EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(3, 0, 0), result.at(1))); - EXPECT(assert_equal(Point3(1.5, -1.5, 0), result.at(3))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0), 1e-8)); + EXPECT(assert_equal(Point3(3, 0, 0), result.at(1), 1e-8)); + EXPECT(assert_equal(Point3(1.5, -1.5, 0), result.at(3), 1e-8)); } TEST(TranslationRecovery, ThreePosesIncludingZeroTranslation) { @@ -190,9 +190,9 @@ TEST(TranslationRecovery, ThreePosesIncludingZeroTranslation) { const auto result = algorithm.run(/*scale=*/3.0); // Check result - EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(3, 0, 0), result.at(1))); - EXPECT(assert_equal(Point3(3, 0, 0), result.at(2))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0), 1e-8)); + EXPECT(assert_equal(Point3(3, 0, 0), result.at(1), 1e-8)); + EXPECT(assert_equal(Point3(3, 0, 0), result.at(2), 1e-8)); } TEST(TranslationRecovery, FourPosesIncludingZeroTranslation) { @@ -231,10 +231,10 @@ TEST(TranslationRecovery, FourPosesIncludingZeroTranslation) { const auto result = algorithm.run(/*scale=*/4.0); // Check result - EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(4, 0, 0), result.at(1))); - EXPECT(assert_equal(Point3(4, 0, 0), result.at(2))); - EXPECT(assert_equal(Point3(2, -2, 0), result.at(3))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0), 1e-8)); + EXPECT(assert_equal(Point3(4, 0, 0), result.at(1), 1e-8)); + EXPECT(assert_equal(Point3(4, 0, 0), result.at(2), 1e-8)); + EXPECT(assert_equal(Point3(2, -2, 0), result.at(3), 1e-8)); } TEST(TranslationRecovery, ThreePosesWithZeroTranslation) { @@ -261,9 +261,9 @@ TEST(TranslationRecovery, ThreePosesWithZeroTranslation) { const auto result = algorithm.run(/*scale=*/4.0); // Check result - EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); - EXPECT(assert_equal(Point3(0, 0, 0), result.at(1))); - EXPECT(assert_equal(Point3(0, 0, 0), result.at(2))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0), 1e-8)); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(1), 1e-8)); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(2), 1e-8)); } /* ************************************************************************* */ From 5f9082b5367ce793c44b535ad4dc31f0de593157 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Feb 2022 22:43:37 -0500 Subject: [PATCH 066/116] docs --- gtsam/basis/Chebyshev2.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/basis/Chebyshev2.h b/gtsam/basis/Chebyshev2.h index 28590961d..e306c93d5 100644 --- a/gtsam/basis/Chebyshev2.h +++ b/gtsam/basis/Chebyshev2.h @@ -22,8 +22,7 @@ * * This is different from Chebyshev.h since it leverage ideas from * pseudo-spectral optimization, i.e. we don't decompose into basis functions, - * rather estimate function parameters that enforce function nodes at Chebyshev - * points. + * rather estimate function values at the Chebyshev points. * * Please refer to Agrawal21icra for more details. * From a16f588317d975c47732a7b157ac1d74d8dedbfe Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Feb 2022 22:43:55 -0500 Subject: [PATCH 067/116] Add test for ManifoldEvaluationFunctor --- gtsam/basis/tests/testChebyshev2.cpp | 36 +++++++++++++++++++++------- 1 file changed, 28 insertions(+), 8 deletions(-) diff --git a/gtsam/basis/tests/testChebyshev2.cpp b/gtsam/basis/tests/testChebyshev2.cpp index 6fafc0ccf..9090757f4 100644 --- a/gtsam/basis/tests/testChebyshev2.cpp +++ b/gtsam/basis/tests/testChebyshev2.cpp @@ -10,18 +10,20 @@ * -------------------------------------------------------------------------- */ /** - * @file testChebyshev.cpp + * @file testChebyshev2.cpp * @date July 4, 2020 * @author Varun Agrawal * @brief Unit tests for Chebyshev Basis Decompositions via pseudo-spectral * methods */ -#include -#include #include #include +#include #include +#include + +#include using namespace std; using namespace gtsam; @@ -123,12 +125,30 @@ TEST(Chebyshev2, InterpolateVector) { EXPECT(assert_equal(numericalH, actualH, 1e-9)); } +//****************************************************************************** +// Interpolating poses using the exponential map +TEST(Chebyshev2, InterpolatePose2) { + double t = 30, a = 0, b = 100; + + ParameterMatrix<3> X(N); + X.row(0) = Chebyshev2::Points(N, a, b); // slope 1 ramp + X.row(1) = Vector::Zero(N); + X.row(2) = 0.1 * Vector::Ones(N); + + Vector xi(3); + xi << t, 0, 0.1; + Chebyshev2::ManifoldEvaluationFunctor fx(N, t, a, b); + // We use xi as canonical coordinates via exponential map + Pose2 expected = Pose2::ChartAtOrigin::Retract(xi); + EXPECT(assert_equal(expected, fx(X))); +} + //****************************************************************************** TEST(Chebyshev2, Decomposition) { // Create example sequence Sequence sequence; for (size_t i = 0; i < 16; i++) { - double x = (double)i / 16. - 0.99, y = x; + double x = (1.0/ 16)*i - 0.99, y = x; sequence[x] = y; } @@ -146,11 +166,11 @@ TEST(Chebyshev2, DifferentiationMatrix3) { // Trefethen00book, p.55 const size_t N = 3; Matrix expected(N, N); - // Differentiation matrix computed from Chebfun + // Differentiation matrix computed from chebfun expected << 1.5000, -2.0000, 0.5000, // 0.5000, -0.0000, -0.5000, // -0.5000, 2.0000, -1.5000; - // multiply by -1 since the cheb points have a phase shift wrt Trefethen + // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen // This was verified with chebfun expected = -expected; @@ -169,7 +189,7 @@ TEST(Chebyshev2, DerivativeMatrix6) { 0.3820, -0.8944, 1.6180, 0.1708, -2.0000, 0.7236, // -0.2764, 0.6180, -0.8944, 2.0000, 1.1708, -2.6180, // 0.5000, -1.1056, 1.5279, -2.8944, 10.4721, -8.5000; - // multiply by -1 since the cheb points have a phase shift wrt Trefethen + // multiply by -1 since the chebyshev points have a phase shift wrt Trefethen // This was verified with chebfun expected = -expected; @@ -254,7 +274,7 @@ TEST(Chebyshev2, DerivativeWeights2) { Weights dWeights2 = Chebyshev2::DerivativeWeights(N, x2, a, b); EXPECT_DOUBLES_EQUAL(fprime(x2), dWeights2 * fvals, 1e-8); - // test if derivative calculation and cheb point is correct + // test if derivative calculation and Chebyshev point is correct double x3 = Chebyshev2::Point(N, 3, a, b); Weights dWeights3 = Chebyshev2::DerivativeWeights(N, x3, a, b); EXPECT_DOUBLES_EQUAL(fprime(x3), dWeights3 * fvals, 1e-8); From c85b6496855ca701c8969dac6f4c64359a5860a3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Feb 2022 22:44:17 -0500 Subject: [PATCH 068/116] Move BasisFactors tests to correct place --- gtsam/basis/tests/testBasisFactors.cpp | 185 ++++++++++++++++++ .../nonlinear/tests/testFunctorizedFactor.cpp | 141 +------------ 2 files changed, 190 insertions(+), 136 deletions(-) create mode 100644 gtsam/basis/tests/testBasisFactors.cpp diff --git a/gtsam/basis/tests/testBasisFactors.cpp b/gtsam/basis/tests/testBasisFactors.cpp new file mode 100644 index 000000000..b0e1e91cb --- /dev/null +++ b/gtsam/basis/tests/testBasisFactors.cpp @@ -0,0 +1,185 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------1------------------------------------------- + */ + +/** + * @file testBasisFactors.cpp + * @date May 31, 2020 + * @author Varun Agrawal + * @brief unit tests for factors in BasisFactors.h + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using gtsam::noiseModel::Isotropic; +using gtsam::Vector; +using gtsam::Values; +using gtsam::Chebyshev2; +using gtsam::ParameterMatrix; +using gtsam::LevenbergMarquardtParams; +using gtsam::LevenbergMarquardtOptimizer; +using gtsam::NonlinearFactorGraph; +using gtsam::NonlinearOptimizerParams; + +const size_t N = 2; + +// Key for FunctorizedFactor +gtsam::Key key = gtsam::Symbol('X', 0); + +//****************************************************************************** +TEST(FunctorizedFactor, Print2) { + using gtsam::VectorEvaluationFactor; + const size_t M = 1; + + Vector measured = Vector::Ones(M) * 42; + + auto model = Isotropic::Sigma(M, 1.0); + VectorEvaluationFactor priorFactor(key, measured, model, N, 0); + + std::string expected = + " keys = { X0 }\n" + " noise model: unit (1) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 42\n" + "]\n" + " noise model sigmas: 1\n"; + + EXPECT(assert_print_equal(expected, priorFactor)); +} + +//****************************************************************************** +TEST(FunctorizedFactor, VectorEvaluationFactor) { + using gtsam::VectorEvaluationFactor; + const size_t M = 4; + + Vector measured = Vector::Zero(M); + + auto model = Isotropic::Sigma(M, 1.0); + VectorEvaluationFactor priorFactor(key, measured, model, N, 0); + + NonlinearFactorGraph graph; + graph.add(priorFactor); + + ParameterMatrix stateMatrix(N); + + Values initial; + initial.insert>(key, stateMatrix); + + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::SILENT; + parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); +} + +//****************************************************************************** +TEST(FunctorizedFactor, VectorComponentFactor) { + using gtsam::VectorComponentFactor; + const int P = 4; + const size_t i = 2; + const double measured = 0.0, t = 3.0, a = 2.0, b = 4.0; + auto model = Isotropic::Sigma(1, 1.0); + VectorComponentFactor controlPrior(key, measured, model, N, i, + t, a, b); + + NonlinearFactorGraph graph; + graph.add(controlPrior); + + ParameterMatrix

stateMatrix(N); + + Values initial; + initial.insert>(key, stateMatrix); + + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::SILENT; + parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); +} + +//****************************************************************************** +TEST(FunctorizedFactor, VecDerivativePrior) { + using gtsam::VectorDerivativeFactor; + const size_t M = 4; + + Vector measured = Vector::Zero(M); + auto model = Isotropic::Sigma(M, 1.0); + VectorDerivativeFactor vecDPrior(key, measured, model, N, 0); + + NonlinearFactorGraph graph; + graph.add(vecDPrior); + + ParameterMatrix stateMatrix(N); + + Values initial; + initial.insert>(key, stateMatrix); + + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::SILENT; + parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); +} + +//****************************************************************************** +TEST(FunctorizedFactor, ComponentDerivativeFactor) { + using gtsam::ComponentDerivativeFactor; + const size_t M = 4; + + double measured = 0; + auto model = Isotropic::Sigma(1, 1.0); + ComponentDerivativeFactor controlDPrior(key, measured, model, + N, 0, 0); + + NonlinearFactorGraph graph; + graph.add(controlDPrior); + + Values initial; + ParameterMatrix stateMatrix(N); + initial.insert>(key, stateMatrix); + + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::SILENT; + parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 14a14fc19..214c5efa7 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -17,16 +17,14 @@ * @brief unit tests for FunctorizedFactor class */ -#include -#include -#include -#include -#include -#include -#include #include #include #include +#include +#include +#include + +#include using namespace std; using namespace gtsam; @@ -272,135 +270,6 @@ TEST(FunctorizedFactor, Lambda2) { EXPECT(assert_equal(Vector::Zero(3), error, 1e-9)); } -const size_t N = 2; - -//****************************************************************************** -TEST(FunctorizedFactor, Print2) { - const size_t M = 1; - - Vector measured = Vector::Ones(M) * 42; - - auto model = noiseModel::Isotropic::Sigma(M, 1.0); - VectorEvaluationFactor priorFactor(key, measured, model, N, 0); - - string expected = - " keys = { X0 }\n" - " noise model: unit (1) \n" - "FunctorizedFactor(X0)\n" - " measurement: [\n" - " 42\n" - "]\n" - " noise model sigmas: 1\n"; - - EXPECT(assert_print_equal(expected, priorFactor)); -} - -//****************************************************************************** -TEST(FunctorizedFactor, VectorEvaluationFactor) { - const size_t M = 4; - - Vector measured = Vector::Zero(M); - - auto model = noiseModel::Isotropic::Sigma(M, 1.0); - VectorEvaluationFactor priorFactor(key, measured, model, N, 0); - - NonlinearFactorGraph graph; - graph.add(priorFactor); - - ParameterMatrix stateMatrix(N); - - Values initial; - initial.insert>(key, stateMatrix); - - LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; - parameters.setMaxIterations(20); - Values result = - LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); - - EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); -} - -//****************************************************************************** -TEST(FunctorizedFactor, VectorComponentFactor) { - const int P = 4; - const size_t i = 2; - const double measured = 0.0, t = 3.0, a = 2.0, b = 4.0; - auto model = noiseModel::Isotropic::Sigma(1, 1.0); - VectorComponentFactor controlPrior(key, measured, model, N, i, - t, a, b); - - NonlinearFactorGraph graph; - graph.add(controlPrior); - - ParameterMatrix

stateMatrix(N); - - Values initial; - initial.insert>(key, stateMatrix); - - LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; - parameters.setMaxIterations(20); - Values result = - LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); - - EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); -} - -//****************************************************************************** -TEST(FunctorizedFactor, VecDerivativePrior) { - const size_t M = 4; - - Vector measured = Vector::Zero(M); - auto model = noiseModel::Isotropic::Sigma(M, 1.0); - VectorDerivativeFactor vecDPrior(key, measured, model, N, 0); - - NonlinearFactorGraph graph; - graph.add(vecDPrior); - - ParameterMatrix stateMatrix(N); - - Values initial; - initial.insert>(key, stateMatrix); - - LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; - parameters.setMaxIterations(20); - Values result = - LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); - - EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); -} - -//****************************************************************************** -TEST(FunctorizedFactor, ComponentDerivativeFactor) { - const size_t M = 4; - - double measured = 0; - auto model = noiseModel::Isotropic::Sigma(1, 1.0); - ComponentDerivativeFactor controlDPrior(key, measured, model, - N, 0, 0); - - NonlinearFactorGraph graph; - graph.add(controlDPrior); - - Values initial; - ParameterMatrix stateMatrix(N); - initial.insert>(key, stateMatrix); - - LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; - parameters.setMaxIterations(20); - Values result = - LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); - - EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); -} - /* ************************************************************************* */ int main() { TestResult tr; From 3d8c7b9fdfed5c4bc5ced72d27ccedde48968693 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Feb 2022 22:56:46 -0500 Subject: [PATCH 069/116] Add EvaluationFactor test --- gtsam/basis/BasisFactors.h | 7 ++- gtsam/basis/tests/testBasisFactors.cpp | 80 +++++++++++++++++--------- 2 files changed, 59 insertions(+), 28 deletions(-) diff --git a/gtsam/basis/BasisFactors.h b/gtsam/basis/BasisFactors.h index 3d1a12f19..648bcd510 100644 --- a/gtsam/basis/BasisFactors.h +++ b/gtsam/basis/BasisFactors.h @@ -29,6 +29,9 @@ namespace gtsam { * pseudo-spectral parameterization. * * @tparam BASIS The basis class to use e.g. Chebyshev2 + * + * Example, degree 8 Chebyshev polynomial measured at x=0.5: + * EvaluationFactor factor(key, measured, model, 8, 0.5); */ template class EvaluationFactor : public FunctorizedFactor { @@ -47,7 +50,7 @@ class EvaluationFactor : public FunctorizedFactor { * @param N The degree of the polynomial. * @param x The point at which to evaluate the polynomial. */ - EvaluationFactor(Key key, const double &z, const SharedNoiseModel &model, + EvaluationFactor(Key key, double z, const SharedNoiseModel &model, const size_t N, double x) : Base(key, z, model, typename BASIS::EvaluationFunctor(N, x)) {} @@ -62,7 +65,7 @@ class EvaluationFactor : public FunctorizedFactor { * @param a Lower bound for the polynomial. * @param b Upper bound for the polynomial. */ - EvaluationFactor(Key key, const double &z, const SharedNoiseModel &model, + EvaluationFactor(Key key, double z, const SharedNoiseModel &model, const size_t N, double x, double a, double b) : Base(key, z, model, typename BASIS::EvaluationFunctor(N, x, a, b)) {} diff --git a/gtsam/basis/tests/testBasisFactors.cpp b/gtsam/basis/tests/testBasisFactors.cpp index b0e1e91cb..ec3c53152 100644 --- a/gtsam/basis/tests/testBasisFactors.cpp +++ b/gtsam/basis/tests/testBasisFactors.cpp @@ -40,45 +40,51 @@ using gtsam::LevenbergMarquardtOptimizer; using gtsam::NonlinearFactorGraph; using gtsam::NonlinearOptimizerParams; -const size_t N = 2; +constexpr size_t N = 2; -// Key for FunctorizedFactor -gtsam::Key key = gtsam::Symbol('X', 0); +// Key used in all tests +const gtsam::Symbol key('X', 0); //****************************************************************************** -TEST(FunctorizedFactor, Print2) { - using gtsam::VectorEvaluationFactor; - const size_t M = 1; +TEST(BasisFactors, EvaluationFactor) { + using gtsam::EvaluationFactor; - Vector measured = Vector::Ones(M) * 42; + double measured = 0; - auto model = Isotropic::Sigma(M, 1.0); - VectorEvaluationFactor priorFactor(key, measured, model, N, 0); + auto model = Isotropic::Sigma(1, 1.0); + EvaluationFactor factor(key, measured, model, N, 0); - std::string expected = - " keys = { X0 }\n" - " noise model: unit (1) \n" - "FunctorizedFactor(X0)\n" - " measurement: [\n" - " 42\n" - "]\n" - " noise model sigmas: 1\n"; + NonlinearFactorGraph graph; + graph.add(factor); - EXPECT(assert_print_equal(expected, priorFactor)); + Vector functionValues(N); + functionValues.setZero(); + + Values initial; + initial.insert(key, functionValues); + + LevenbergMarquardtParams parameters; + parameters.verbosity = NonlinearOptimizerParams::SILENT; + parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); } //****************************************************************************** -TEST(FunctorizedFactor, VectorEvaluationFactor) { +TEST(BasisFactors, VectorEvaluationFactor) { using gtsam::VectorEvaluationFactor; const size_t M = 4; - Vector measured = Vector::Zero(M); + const Vector measured = Vector::Zero(M); auto model = Isotropic::Sigma(M, 1.0); - VectorEvaluationFactor priorFactor(key, measured, model, N, 0); + VectorEvaluationFactor factor(key, measured, model, N, 0); NonlinearFactorGraph graph; - graph.add(priorFactor); + graph.add(factor); ParameterMatrix stateMatrix(N); @@ -96,7 +102,29 @@ TEST(FunctorizedFactor, VectorEvaluationFactor) { } //****************************************************************************** -TEST(FunctorizedFactor, VectorComponentFactor) { +TEST(BasisFactors, Print) { + using gtsam::VectorEvaluationFactor; + const size_t M = 1; + + const Vector measured = Vector::Ones(M) * 42; + + auto model = Isotropic::Sigma(M, 1.0); + VectorEvaluationFactor factor(key, measured, model, N, 0); + + std::string expected = + " keys = { X0 }\n" + " noise model: unit (1) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 42\n" + "]\n" + " noise model sigmas: 1\n"; + + EXPECT(assert_print_equal(expected, factor)); +} + +//****************************************************************************** +TEST(BasisFactors, VectorComponentFactor) { using gtsam::VectorComponentFactor; const int P = 4; const size_t i = 2; @@ -124,11 +152,11 @@ TEST(FunctorizedFactor, VectorComponentFactor) { } //****************************************************************************** -TEST(FunctorizedFactor, VecDerivativePrior) { +TEST(BasisFactors, VecDerivativePrior) { using gtsam::VectorDerivativeFactor; const size_t M = 4; - Vector measured = Vector::Zero(M); + const Vector measured = Vector::Zero(M); auto model = Isotropic::Sigma(M, 1.0); VectorDerivativeFactor vecDPrior(key, measured, model, N, 0); @@ -151,7 +179,7 @@ TEST(FunctorizedFactor, VecDerivativePrior) { } //****************************************************************************** -TEST(FunctorizedFactor, ComponentDerivativeFactor) { +TEST(BasisFactors, ComponentDerivativeFactor) { using gtsam::ComponentDerivativeFactor; const size_t M = 4; From 6fb38aa8d7f009aefe42c88e5ca7b5eca6fb287d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Feb 2022 23:05:49 -0500 Subject: [PATCH 070/116] Add test for ManifoldEvaluationFactor --- gtsam/basis/tests/testBasisFactors.cpp | 41 ++++++++++++++++++-------- 1 file changed, 29 insertions(+), 12 deletions(-) diff --git a/gtsam/basis/tests/testBasisFactors.cpp b/gtsam/basis/tests/testBasisFactors.cpp index ec3c53152..18a389da5 100644 --- a/gtsam/basis/tests/testBasisFactors.cpp +++ b/gtsam/basis/tests/testBasisFactors.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include #include @@ -31,6 +32,7 @@ #include using gtsam::noiseModel::Isotropic; +using gtsam::Pose2; using gtsam::Vector; using gtsam::Values; using gtsam::Chebyshev2; @@ -64,8 +66,6 @@ TEST(BasisFactors, EvaluationFactor) { initial.insert(key, functionValues); LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; parameters.setMaxIterations(20); Values result = LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); @@ -92,8 +92,6 @@ TEST(BasisFactors, VectorEvaluationFactor) { initial.insert>(key, stateMatrix); LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; parameters.setMaxIterations(20); Values result = LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); @@ -130,11 +128,11 @@ TEST(BasisFactors, VectorComponentFactor) { const size_t i = 2; const double measured = 0.0, t = 3.0, a = 2.0, b = 4.0; auto model = Isotropic::Sigma(1, 1.0); - VectorComponentFactor controlPrior(key, measured, model, N, i, + VectorComponentFactor factor(key, measured, model, N, i, t, a, b); NonlinearFactorGraph graph; - graph.add(controlPrior); + graph.add(factor); ParameterMatrix

stateMatrix(N); @@ -142,8 +140,31 @@ TEST(BasisFactors, VectorComponentFactor) { initial.insert>(key, stateMatrix); LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; + parameters.setMaxIterations(20); + Values result = + LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); + + EXPECT_DOUBLES_EQUAL(0, graph.error(result), 1e-9); +} + +//****************************************************************************** +TEST(BasisFactors, ManifoldEvaluationFactor) { + using gtsam::ManifoldEvaluationFactor; + const Pose2 measured; + const double t = 3.0, a = 2.0, b = 4.0; + auto model = Isotropic::Sigma(3, 1.0); + ManifoldEvaluationFactor factor(key, measured, model, N, + t, a, b); + + NonlinearFactorGraph graph; + graph.add(factor); + + ParameterMatrix<3> stateMatrix(N); + + Values initial; + initial.insert>(key, stateMatrix); + + LevenbergMarquardtParams parameters; parameters.setMaxIterations(20); Values result = LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); @@ -169,8 +190,6 @@ TEST(BasisFactors, VecDerivativePrior) { initial.insert>(key, stateMatrix); LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; parameters.setMaxIterations(20); Values result = LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); @@ -196,8 +215,6 @@ TEST(BasisFactors, ComponentDerivativeFactor) { initial.insert>(key, stateMatrix); LevenbergMarquardtParams parameters; - parameters.verbosity = NonlinearOptimizerParams::SILENT; - parameters.verbosityLM = LevenbergMarquardtParams::SILENT; parameters.setMaxIterations(20); Values result = LevenbergMarquardtOptimizer(graph, initial, parameters).optimize(); From eadfabc51d46c0c7ddc33b66462270655fb00b2c Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Sun, 27 Feb 2022 15:06:56 -0500 Subject: [PATCH 071/116] filename in repo is w10000 not w10000-odom --- timing/timeBatch.cpp | 2 +- timing/timeIncremental.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/timing/timeBatch.cpp b/timing/timeBatch.cpp index 4ed1a4555..f59039fa7 100644 --- a/timing/timeBatch.cpp +++ b/timing/timeBatch.cpp @@ -28,7 +28,7 @@ int main(int argc, char *argv[]) { cout << "Loading data..." << endl; - string datasetFile = findExampleDataFile("w10000-odom"); + string datasetFile = findExampleDataFile("w10000"); std::pair data = load2D(datasetFile); diff --git a/timing/timeIncremental.cpp b/timing/timeIncremental.cpp index 6e0f4ccdf..5e3fc9189 100644 --- a/timing/timeIncremental.cpp +++ b/timing/timeIncremental.cpp @@ -72,7 +72,7 @@ int main(int argc, char *argv[]) { cout << "Loading data..." << endl; gttic_(Find_datafile); - //string datasetFile = findExampleDataFile("w10000-odom"); + //string datasetFile = findExampleDataFile("w10000"); string datasetFile = findExampleDataFile("victoria_park"); std::pair data = load2D(datasetFile); From 1a2eb9a1018c5c060f1fbb051ff2f149d91101d2 Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Mon, 28 Feb 2022 22:21:59 -0800 Subject: [PATCH 072/116] change to pointer --- gtsam/sfm/TranslationRecovery.cpp | 4 ++-- gtsam/sfm/TranslationRecovery.h | 16 ++++++++-------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index aa7b14709..9d72f56da 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -91,7 +91,7 @@ void TranslationRecovery::addPrior( edge->key2(), scale * edge->measured().point3(), edge->noiseModel()); } -Values TranslationRecovery::initializeRandomly(std::mt19937 &rng) const { +Values TranslationRecovery::initializeRandomly(std::mt19937 *rng) const { uniform_real_distribution randomVal(-1, 1); // Create a lambda expression that checks whether value exists and randomly // initializes if not. @@ -121,7 +121,7 @@ Values TranslationRecovery::initializeRandomly(std::mt19937 &rng) const { } Values TranslationRecovery::initializeRandomly() const { - return initializeRandomly(kRandomNumberGenerator); + return initializeRandomly(&kRandomNumberGenerator); } Values TranslationRecovery::run(const double scale) const { diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 430b54d1d..30c9a14e3 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -16,16 +16,16 @@ * @brief Recovering translations in an epipolar graph when rotations are given. */ -#include -#include -#include -#include - #include #include #include #include +#include +#include +#include +#include + namespace gtsam { // Set up an optimization problem for the unknown translations Ti in the world @@ -99,15 +99,15 @@ class TranslationRecovery { /** * @brief Create random initial translations. - * + * * @param rng random number generator * @return Values */ - Values initializeRandomly(std::mt19937 &rng) const; + Values initializeRandomly(std::mt19937 *rng) const; /** * @brief Version of initializeRandomly with a fixed seed. - * + * * @return Values */ Values initializeRandomly() const; From 42bee1ab0baf3a303576dd44286104b2a3103917 Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Mon, 28 Feb 2022 22:23:41 -0800 Subject: [PATCH 073/116] lamda capture all variables --- gtsam/sfm/TranslationRecovery.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index 9d72f56da..64953d2a5 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -96,7 +96,7 @@ Values TranslationRecovery::initializeRandomly(std::mt19937 *rng) const { // Create a lambda expression that checks whether value exists and randomly // initializes if not. Values initial; - auto insert = [&initial, &rng, &randomVal](Key j) { + auto insert = [&](Key j) { if (!initial.exists(j)) { initial.insert( j, Point3(randomVal(rng), randomVal(rng), randomVal(rng))); From 97ee1268a28cd82811d9acd660544b43a4edd24b Mon Sep 17 00:00:00 2001 From: Akshay Krishnan Date: Mon, 28 Feb 2022 22:27:28 -0800 Subject: [PATCH 074/116] update pointer usage --- gtsam/sfm/TranslationRecovery.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index 64953d2a5..2e81c2d56 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -99,7 +99,7 @@ Values TranslationRecovery::initializeRandomly(std::mt19937 *rng) const { auto insert = [&](Key j) { if (!initial.exists(j)) { initial.insert( - j, Point3(randomVal(rng), randomVal(rng), randomVal(rng))); + j, Point3(randomVal(*rng), randomVal(*rng), randomVal(*rng))); } }; From ba32a0de85c94eebae4d27116cec3885db9f66bc Mon Sep 17 00:00:00 2001 From: Thomas Sayre-McCord Date: Tue, 8 Mar 2022 16:34:09 +0100 Subject: [PATCH 075/116] fix triangulatePoint3 for calibrations with distortion Prior implementation only used the K() portion of all Cal3 calibrations for the linear triangulation of points with triangulatePoint3. - Added tests for triangulation with non-Cal3_S2 calibrations. - Added skew to the test Cal3_S2 calibration. - Added an undistortMeasurements step to triangulatePoint3 so that linear triangulation works for calibrations with distortion coefficients. --- gtsam/geometry/tests/testTriangulation.cpp | 109 ++++++++++++++++++++- gtsam/geometry/triangulation.h | 34 ++++++- 2 files changed, 139 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index 3a09f49bc..95c41fb99 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include @@ -38,7 +39,7 @@ using namespace boost::assign; // Some common constants static const boost::shared_ptr sharedCal = // - boost::make_shared(1500, 1200, 0, 640, 480); + boost::make_shared(1500, 1200, 0.1, 640, 480); // Looking along X-axis, 1 meter above ground plane (x-y) static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2); @@ -95,11 +96,113 @@ TEST(triangulation, twoPoses) { EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-4)); } +//****************************************************************************** +// Simple test with a well-behaved two camera situation with Cal3S2 calibration. +TEST(triangulation, twoPosesCal3S2) { + static const boost::shared_ptr sharedDistortedCal = // + boost::make_shared(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003); + + PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); + + PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); + +// 1. Project two landmarks into two cameras and triangulate + Point2 z1Distorted = camera1Distorted.project(landmark); + Point2 z2Distorted = camera2Distorted.project(landmark); + + vector poses; + Point2Vector measurements; + + poses += pose1, pose2; + measurements += z1Distorted, z2Distorted; + + double rank_tol = 1e-9; + + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); + + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); + + // 3. Add some noise and try again: result should be ~ (4.995, + // 0.499167, 1.19814) + measurements.at(0) += Point2(0.1, 0.5); + measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); + + // 4. Now with optimization on + optimize = true; + boost::optional actual4 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); +} + +//****************************************************************************** +// Simple test with a well-behaved two camera situation with Fisheye calibration. +TEST(triangulation, twoPosesFisheye) { + using Calibration = Cal3Fisheye; + static const boost::shared_ptr sharedDistortedCal = // + boost::make_shared(1500, 1200, .1, 640, 480, -.3, 0.1, 0.0001, -0.0003); + + PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); + + PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); + +// 1. Project two landmarks into two cameras and triangulate + Point2 z1Distorted = camera1Distorted.project(landmark); + Point2 z2Distorted = camera2Distorted.project(landmark); + + vector poses; + Point2Vector measurements; + + poses += pose1, pose2; + measurements += z1Distorted, z2Distorted; + + double rank_tol = 1e-9; + + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); + + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); + + // 3. Add some noise and try again: result should be ~ (4.995, + // 0.499167, 1.19814) + measurements.at(0) += Point2(0.1, 0.5); + measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); + + // 4. Now with optimization on + optimize = true; + boost::optional actual4 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); +} + + //****************************************************************************** // Similar, but now with Bundler calibration TEST(triangulation, twoPosesBundler) { boost::shared_ptr bundlerCal = // - boost::make_shared(1500, 0, 0, 640, 480); + boost::make_shared(1500, 0.1, 0.2, 640, 480); PinholeCamera camera1(pose1, *bundlerCal); PinholeCamera camera2(pose2, *bundlerCal); @@ -126,7 +229,7 @@ TEST(triangulation, twoPosesBundler) { boost::optional actual2 = // triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-4)); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-3)); } //****************************************************************************** diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index af01d3a36..fce7ca89b 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -227,6 +227,35 @@ std::vector> projectionMatricesFrom return projection_matrices; } +/** Remove distortion for measurements so as if the measurements came from a pinhole camera. + * + * Removes distortion but maintains the K matrix of the initial sharedCal. Operates by calibrating using + * full calibration and uncalibrating with only the pinhole component of the calibration. + * @tparam CALIBRATION Calibration type to use. + * @param sharedCal Calibration with which measurements were taken. + * @param measurements Vector of measurements to undistort. + * @return measurements with the effect of the distortion of sharedCal removed. + */ +template +Point2Vector undistortMeasurements(boost::shared_ptr sharedCal, const Point2Vector& measurements) { + const auto& K = sharedCal->K(); + Cal3_S2 pinholeCalibration(K(0,0), K(1,1), K(0,1), K(0,2), K(1,2)); + Point2Vector undistortedMeasurements; + // Calibrate with sharedCal and uncalibrate with pinhole version of sharedCal so that measurements are undistorted. + std::transform(measurements.begin(), measurements.end(), std::back_inserter(undistortedMeasurements), [&sharedCal, &pinholeCalibration](auto& measurement) { + return pinholeCalibration.uncalibrate(sharedCal->calibrate(measurement)); + }); + + return undistortedMeasurements; +} + +/** Specialization for Cal3_S2 as it doesn't need to be undistorted. */ +template <> +Point2Vector undistortMeasurements(boost::shared_ptr sharedCal, const Point2Vector& measurements) { + return measurements; +} + + /** * Function to triangulate 3D landmark point from an arbitrary number * of poses (at least 2) using the DLT. The function checks that the @@ -253,8 +282,11 @@ Point3 triangulatePoint3(const std::vector& poses, // construct projection matrices from poses & calibration auto projection_matrices = projectionMatricesFromPoses(poses, sharedCal); + // Undistort the measurements, leaving only the pinhole elements in effect. + auto undistortedMeasurements = undistortMeasurements(sharedCal, measurements); + // Triangulate linearly - Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); + Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); // Then refine using non-linear optimization if (optimize) From afc406162b4b0a427c473de117ab380c1e9dd780 Mon Sep 17 00:00:00 2001 From: Thomas Sayre-McCord Date: Wed, 9 Mar 2022 11:39:07 +0100 Subject: [PATCH 076/116] add support for second version of triangulatePoint3 - added undistort for cameras version of triangulatePoint3 - changed to 2 space indent - changed to calibration from shared calibration --- gtsam/geometry/tests/testTriangulation.cpp | 163 ++++++++++++--------- gtsam/geometry/triangulation.h | 98 +++++++++++-- 2 files changed, 177 insertions(+), 84 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index 95c41fb99..0e30acaae 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -99,102 +99,102 @@ TEST(triangulation, twoPoses) { //****************************************************************************** // Simple test with a well-behaved two camera situation with Cal3S2 calibration. TEST(triangulation, twoPosesCal3S2) { - static const boost::shared_ptr sharedDistortedCal = // - boost::make_shared(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003); + static const boost::shared_ptr sharedDistortedCal = // + boost::make_shared(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003); - PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); + PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); - PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); + PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); // 1. Project two landmarks into two cameras and triangulate - Point2 z1Distorted = camera1Distorted.project(landmark); - Point2 z2Distorted = camera2Distorted.project(landmark); + Point2 z1Distorted = camera1Distorted.project(landmark); + Point2 z2Distorted = camera2Distorted.project(landmark); - vector poses; - Point2Vector measurements; + vector poses; + Point2Vector measurements; - poses += pose1, pose2; - measurements += z1Distorted, z2Distorted; + poses += pose1, pose2; + measurements += z1Distorted, z2Distorted; - double rank_tol = 1e-9; + double rank_tol = 1e-9; - // 1. Test simple DLT, perfect in no noise situation - bool optimize = false; - boost::optional actual1 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *actual1, 1e-7)); + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); - // 2. test with optimization on, same answer - optimize = true; - boost::optional actual2 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *actual2, 1e-7)); + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); - // 3. Add some noise and try again: result should be ~ (4.995, - // 0.499167, 1.19814) - measurements.at(0) += Point2(0.1, 0.5); - measurements.at(1) += Point2(-0.2, 0.3); - optimize = false; - boost::optional actual3 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); + // 3. Add some noise and try again: result should be ~ (4.995, + // 0.499167, 1.19814) + measurements.at(0) += Point2(0.1, 0.5); + measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); - // 4. Now with optimization on - optimize = true; - boost::optional actual4 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); + // 4. Now with optimization on + optimize = true; + boost::optional actual4 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); } //****************************************************************************** // Simple test with a well-behaved two camera situation with Fisheye calibration. TEST(triangulation, twoPosesFisheye) { - using Calibration = Cal3Fisheye; - static const boost::shared_ptr sharedDistortedCal = // - boost::make_shared(1500, 1200, .1, 640, 480, -.3, 0.1, 0.0001, -0.0003); + using Calibration = Cal3Fisheye; + static const boost::shared_ptr sharedDistortedCal = // + boost::make_shared(1500, 1200, .1, 640, 480, -.3, 0.1, 0.0001, -0.0003); - PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); + PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); - PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); + PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); // 1. Project two landmarks into two cameras and triangulate - Point2 z1Distorted = camera1Distorted.project(landmark); - Point2 z2Distorted = camera2Distorted.project(landmark); + Point2 z1Distorted = camera1Distorted.project(landmark); + Point2 z2Distorted = camera2Distorted.project(landmark); - vector poses; - Point2Vector measurements; + vector poses; + Point2Vector measurements; - poses += pose1, pose2; - measurements += z1Distorted, z2Distorted; + poses += pose1, pose2; + measurements += z1Distorted, z2Distorted; - double rank_tol = 1e-9; + double rank_tol = 1e-9; - // 1. Test simple DLT, perfect in no noise situation - bool optimize = false; - boost::optional actual1 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *actual1, 1e-7)); + // 1. Test simple DLT, perfect in no noise situation + bool optimize = false; + boost::optional actual1 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual1, 1e-7)); - // 2. test with optimization on, same answer - optimize = true; - boost::optional actual2 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(landmark, *actual2, 1e-7)); + // 2. test with optimization on, same answer + optimize = true; + boost::optional actual2 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(landmark, *actual2, 1e-7)); - // 3. Add some noise and try again: result should be ~ (4.995, - // 0.499167, 1.19814) - measurements.at(0) += Point2(0.1, 0.5); - measurements.at(1) += Point2(-0.2, 0.3); - optimize = false; - boost::optional actual3 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); + // 3. Add some noise and try again: result should be ~ (4.995, + // 0.499167, 1.19814) + measurements.at(0) += Point2(0.1, 0.5); + measurements.at(1) += Point2(-0.2, 0.3); + optimize = false; + boost::optional actual3 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); - // 4. Now with optimization on - optimize = true; - boost::optional actual4 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); - EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); + // 4. Now with optimization on + optimize = true; + boost::optional actual4 = // + triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); } @@ -439,6 +439,31 @@ TEST(triangulation, fourPoses_distinct_Ks) { #endif } +//****************************************************************************** +TEST(triangulation, fourPoses_distinct_Ks_distortion) { + Cal3DS2 K1(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003); + // create first camera. Looking along X-axis, 1 meter above ground plane (x-y) + PinholeCamera camera1(pose1, K1); + + // create second camera 1 meter to the right of first camera + Cal3DS2 K2(1600, 1300, 0, 650, 440, -.2, 0.05, 0.0002, -0.0001); + PinholeCamera camera2(pose2, K2); + + // 1. Project two landmarks into two cameras and triangulate + Point2 z1 = camera1.project(landmark); + Point2 z2 = camera2.project(landmark); + + CameraSet> cameras; + Point2Vector measurements; + + cameras += camera1, camera2; + measurements += z1, z2; + + boost::optional actual = // + triangulatePoint3(cameras, measurements); + EXPECT(assert_equal(landmark, *actual, 1e-2)); +} + //****************************************************************************** TEST(triangulation, outliersAndFarLandmarks) { Cal3_S2 K1(1500, 1200, 0, 640, 480); diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index fce7ca89b..0df569608 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -227,35 +227,99 @@ std::vector> projectionMatricesFrom return projection_matrices; } +/** Create a pinhole calibration from a different Cal3 object, removing distortion. + * + * @tparam CALIBRATION Original calibration object. + * @param cal Input calibration object. + * @return Cal3_S2 with only the pinhole elements of cal. + */ +template +Cal3_S2 createPinholeCalibration(const CALIBRATION& cal) { + const auto& K = cal.K(); + return Cal3_S2(K(0,0), K(1,1), K(0,1), K(0,2), K(1,2)); +} + +/** Internal undistortMeasurement to be used by undistortMeasurement and undistortMeasurements */ +template +MEASUREMENT undistortMeasurementInternal(const CALIBRATION& cal, + const MEASUREMENT& measurement, + boost::optional pinholeCal = boost::none) { + if (!pinholeCal) { + pinholeCal = createPinholeCalibration(cal); + } + return pinholeCal->uncalibrate(cal.calibrate(measurement)); +} + /** Remove distortion for measurements so as if the measurements came from a pinhole camera. * - * Removes distortion but maintains the K matrix of the initial sharedCal. Operates by calibrating using + * Removes distortion but maintains the K matrix of the initial cal. Operates by calibrating using * full calibration and uncalibrating with only the pinhole component of the calibration. * @tparam CALIBRATION Calibration type to use. - * @param sharedCal Calibration with which measurements were taken. + * @param cal Calibration with which measurements were taken. * @param measurements Vector of measurements to undistort. * @return measurements with the effect of the distortion of sharedCal removed. */ template -Point2Vector undistortMeasurements(boost::shared_ptr sharedCal, const Point2Vector& measurements) { - const auto& K = sharedCal->K(); - Cal3_S2 pinholeCalibration(K(0,0), K(1,1), K(0,1), K(0,2), K(1,2)); - Point2Vector undistortedMeasurements; - // Calibrate with sharedCal and uncalibrate with pinhole version of sharedCal so that measurements are undistorted. - std::transform(measurements.begin(), measurements.end(), std::back_inserter(undistortedMeasurements), [&sharedCal, &pinholeCalibration](auto& measurement) { - return pinholeCalibration.uncalibrate(sharedCal->calibrate(measurement)); - }); - - return undistortedMeasurements; +Point2Vector undistortMeasurements(const CALIBRATION& cal, + const Point2Vector& measurements) { + Cal3_S2 pinholeCalibration = createPinholeCalibration(cal); + Point2Vector undistortedMeasurements; + // Calibrate with cal and uncalibrate with pinhole version of cal so that measurements are undistorted. + std::transform(measurements.begin(), measurements.end(), std::back_inserter(undistortedMeasurements), + [&cal, &pinholeCalibration](const Point2& measurement) { + return undistortMeasurementInternal(cal, measurement, pinholeCalibration); + }); + return undistortedMeasurements; } /** Specialization for Cal3_S2 as it doesn't need to be undistorted. */ template <> -Point2Vector undistortMeasurements(boost::shared_ptr sharedCal, const Point2Vector& measurements) { +inline Point2Vector undistortMeasurements(const Cal3_S2& cal, + const Point2Vector& measurements) { return measurements; } +/** Remove distortion for measurements so as if the measurements came from a pinhole camera. + * + * Removes distortion but maintains the K matrix of the initial calibrations. Operates by calibrating using + * full calibration and uncalibrating with only the pinhole component of the calibration. + * @tparam CAMERA Camera type to use. + * @param cameras Cameras corresponding to each measurement. + * @param measurements Vector of measurements to undistort. + * @return measurements with the effect of the distortion of the camera removed. + */ +template +typename CAMERA::MeasurementVector undistortMeasurements(const CameraSet& cameras, + const typename CAMERA::MeasurementVector& measurements) { + + const size_t num_meas = cameras.size(); + assert(num_meas == measurements.size()); + typename CAMERA::MeasurementVector undistortedMeasurements(num_meas); + for (size_t ii = 0; ii < num_meas; ++ii) { + // Calibrate with cal and uncalibrate with pinhole version of cal so that measurements are undistorted. + undistortedMeasurements[ii] = + undistortMeasurementInternal(cameras[ii].calibration(), measurements[ii]); + } + return undistortedMeasurements; +} + +/** Specialize for Cal3_S2 to do nothing. */ +template > +inline PinholeCamera::MeasurementVector undistortMeasurements( + const CameraSet>& cameras, + const PinholeCamera::MeasurementVector& measurements) { + return measurements; +} + +/** Specialize for SphericalCamera to do nothing. */ +template +inline SphericalCamera::MeasurementVector undistortMeasurements( + const CameraSet& cameras, + const SphericalCamera::MeasurementVector& measurements) { + return measurements; +} + /** * Function to triangulate 3D landmark point from an arbitrary number * of poses (at least 2) using the DLT. The function checks that the @@ -283,7 +347,7 @@ Point3 triangulatePoint3(const std::vector& poses, auto projection_matrices = projectionMatricesFromPoses(poses, sharedCal); // Undistort the measurements, leaving only the pinhole elements in effect. - auto undistortedMeasurements = undistortMeasurements(sharedCal, measurements); + auto undistortedMeasurements = undistortMeasurements(*sharedCal, measurements); // Triangulate linearly Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); @@ -332,7 +396,11 @@ Point3 triangulatePoint3( // construct projection matrices from poses & calibration auto projection_matrices = projectionMatricesFromCameras(cameras); - Point3 point = triangulateDLT(projection_matrices, measurements, rank_tol); + + // Undistort the measurements, leaving only the pinhole elements in effect. + auto undistortedMeasurements = undistortMeasurements(cameras, measurements); + + Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); // The n refine using non-linear optimization if (optimize) From 98efc464dc81560394e033a75db1e9c31f109d0a Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 10 Mar 2022 16:51:19 -0500 Subject: [PATCH 077/116] Fixed all lint errors, formatting --- examples/RangeISAMExample_plaza2.cpp | 169 +++++++++++++++------------ 1 file changed, 94 insertions(+), 75 deletions(-) diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp index c8e31e1c5..898460b49 100644 --- a/examples/RangeISAMExample_plaza2.cpp +++ b/examples/RangeISAMExample_plaza2.cpp @@ -10,62 +10,80 @@ * -------------------------------------------------------------------------- */ /** - * @file RangeISAMExample_plaza1.cpp + * @file RangeISAMExample_plaza2.cpp * @brief A 2D Range SLAM example * @date June 20, 2013 - * @author FRank Dellaert + * @author Frank Dellaert */ -// Both relative poses and recovered trajectory poses will be stored as Pose2 objects +// Both relative poses and recovered trajectory poses will be stored as Pose2. #include +using gtsam::Pose2; -// Each variable in the system (poses and landmarks) must be identified with a unique key. -// We can either use simple integer keys (1, 2, 3, ...) or symbols (X1, X2, L1). -// Here we will use Symbols +// gtsam::Vectors are dynamic Eigen vectors, Vector3 is statically sized. +#include +using gtsam::Vector; +using gtsam::Vector3; + +// Unknown landmarks are of type Point2 (which is just a 2D Eigen vector). +#include +using gtsam::Point2; + +// Each variable in the system (poses and landmarks) must be identified with a +// unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols +// (X1, X2, L1). Here we will use Symbols. #include +using gtsam::Symbol; -// We want to use iSAM2 to solve the range-SLAM problem incrementally +// We want to use iSAM2 to solve the range-SLAM problem incrementally. #include -// iSAM2 requires as input a set set of new factors to be added stored in a factor graph, -// and initial guesses for any new variables used in the added factors +// iSAM2 requires as input a set set of new factors to be added stored in a +// factor graph, and initial guesses for any new variables in the added factors. #include #include -// We will use a non-liear solver to batch-inituialize from the first 150 frames +// We will use a non-linear solver to batch-initialize from the first 150 frames #include -// In GTSAM, measurement functions are represented as 'factors'. Several common factors -// have been provided with the library for solving robotics SLAM problems. -#include +// Measurement functions are represented as 'factors'. Several common factors +// have been provided with the library for solving robotics SLAM problems: #include +#include #include -// Standard headers, added last, so we know headers above work on their own +// Timing, with functions below, provides nice facilities to benchmark. +#include +using gtsam::tictoc_print_; + + +// Standard headers, added last, so we know headers above work on their own. #include #include +#include +#include +#include -using namespace std; -using namespace gtsam; namespace NM = gtsam::noiseModel; -// data available at http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/ -// Datafile format (from http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html) +// data available at +// http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/ Datafile +// format (from +// http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html) // load the odometry // DR: Odometry Input (delta distance traveled and delta heading change) // Time (sec) Delta Dist. Trav. (m) Delta Heading (rad) -typedef pair TimedOdometry; -list readOdometry() { - list odometryList; - string data_file = findExampleDataFile("Plaza2_DR.txt"); - ifstream is(data_file.c_str()); +using TimedOdometry = std::pair; +std::list readOdometry() { + std::list odometryList; + std::string data_file = gtsam::findExampleDataFile("Plaza2_DR.txt"); + std::ifstream is(data_file.c_str()); while (is) { double t, distance_traveled, delta_heading; is >> t >> distance_traveled >> delta_heading; - odometryList.push_back( - TimedOdometry(t, Pose2(distance_traveled, 0, delta_heading))); + odometryList.emplace_back(t, Pose2(distance_traveled, 0, delta_heading)); } is.clear(); /* clears the end-of-file and error flags */ return odometryList; @@ -73,90 +91,91 @@ list readOdometry() { // load the ranges from TD // Time (sec) Sender / Antenna ID Receiver Node ID Range (m) -typedef boost::tuple RangeTriple; -vector readTriples() { - vector triples; - string data_file = findExampleDataFile("Plaza2_TD.txt"); - ifstream is(data_file.c_str()); +using RangeTriple = boost::tuple; +std::vector readTriples() { + std::vector triples; + std::string data_file = gtsam::findExampleDataFile("Plaza2_TD.txt"); + std::ifstream is(data_file.c_str()); while (is) { double t, sender, range; size_t receiver; is >> t >> sender >> receiver >> range; - triples.push_back(RangeTriple(t, receiver, range)); + triples.emplace_back(t, receiver, range); } is.clear(); /* clears the end-of-file and error flags */ return triples; } // main -int main (int argc, char** argv) { - +int main(int argc, char** argv) { // load Plaza2 data - list odometry = readOdometry(); -// size_t M = odometry.size(); + std::list odometry = readOdometry(); + // size_t M = odometry.size(); - vector triples = readTriples(); + std::vector triples = readTriples(); size_t K = triples.size(); // parameters - size_t minK = 150; // minimum number of range measurements to process initially - size_t incK = 25; // minimum number of range measurements to process after + size_t minK = + 150; // minimum number of range measurements to process initially + size_t incK = 25; // minimum number of range measurements to process after bool groundTruth = false; bool robust = true; // Set Noise parameters - Vector priorSigmas = Vector3(1,1,M_PI); + Vector priorSigmas = Vector3(1, 1, M_PI); Vector odoSigmas = Vector3(0.05, 0.01, 0.1); - double sigmaR = 100; // range standard deviation - const NM::Base::shared_ptr // all same type - priorNoise = NM::Diagonal::Sigmas(priorSigmas), //prior - odoNoise = NM::Diagonal::Sigmas(odoSigmas), // odometry - gaussian = NM::Isotropic::Sigma(1, sigmaR), // non-robust - tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), gaussian), //robust - rangeNoise = robust ? tukey : gaussian; + double sigmaR = 100; // range standard deviation + const NM::Base::shared_ptr // all same type + priorNoise = NM::Diagonal::Sigmas(priorSigmas), // prior + odoNoise = NM::Diagonal::Sigmas(odoSigmas), // odometry + gaussian = NM::Isotropic::Sigma(1, sigmaR), // non-robust + tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), + gaussian), // robust + rangeNoise = robust ? tukey : gaussian; // Initialize iSAM - ISAM2 isam; + gtsam::ISAM2 isam; // Add prior on first pose - Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120, - M_PI - 2.02108900000000); - NonlinearFactorGraph newFactors; + Pose2 pose0 = Pose2(-34.2086489999201, 45.3007639991120, M_PI - 2.021089); + gtsam::NonlinearFactorGraph newFactors; newFactors.addPrior(0, pose0, priorNoise); - Values initial; + gtsam::Values initial; initial.insert(0, pose0); // initialize points - if (groundTruth) { // from TL file - initial.insert(symbol('L', 1), Point2(-68.9265, 18.3778)); - initial.insert(symbol('L', 6), Point2(-37.5805, 69.2278)); - initial.insert(symbol('L', 0), Point2(-33.6205, 26.9678)); - initial.insert(symbol('L', 5), Point2(1.7095, -5.8122)); - } else { // drawn from sigma=1 Gaussian in matlab version - initial.insert(symbol('L', 1), Point2(3.5784, 2.76944)); - initial.insert(symbol('L', 6), Point2(-1.34989, 3.03492)); - initial.insert(symbol('L', 0), Point2(0.725404, -0.0630549)); - initial.insert(symbol('L', 5), Point2(0.714743, -0.204966)); + if (groundTruth) { // from TL file + initial.insert(Symbol('L', 1), Point2(-68.9265, 18.3778)); + initial.insert(Symbol('L', 6), Point2(-37.5805, 69.2278)); + initial.insert(Symbol('L', 0), Point2(-33.6205, 26.9678)); + initial.insert(Symbol('L', 5), Point2(1.7095, -5.8122)); + } else { // drawn from sigma=1 Gaussian in matlab version + initial.insert(Symbol('L', 1), Point2(3.5784, 2.76944)); + initial.insert(Symbol('L', 6), Point2(-1.34989, 3.03492)); + initial.insert(Symbol('L', 0), Point2(0.725404, -0.0630549)); + initial.insert(Symbol('L', 5), Point2(0.714743, -0.204966)); } // set some loop variables - size_t i = 1; // step counter - size_t k = 0; // range measurement counter + size_t i = 1; // step counter + size_t k = 0; // range measurement counter bool initialized = false; Pose2 lastPose = pose0; size_t countK = 0; // Loop over odometry gttic_(iSAM); - for(const TimedOdometry& timedOdometry: odometry) { - //--------------------------------- odometry loop ----------------------------------------- + for (const TimedOdometry& timedOdometry : odometry) { + //--------------------------------- odometry loop -------------------------- double t; Pose2 odometry; boost::tie(t, odometry) = timedOdometry; // add odometry factor - newFactors.push_back(BetweenFactor(i-1, i, odometry, odoNoise)); + newFactors.emplace_shared>(i - 1, i, odometry, + odoNoise); // predict pose and add as initial estimate Pose2 predictedPose = lastPose.compose(odometry); @@ -167,16 +186,17 @@ int main (int argc, char** argv) { while (k < K && t >= boost::get<0>(triples[k])) { size_t j = boost::get<1>(triples[k]); double range = boost::get<2>(triples[k]); - newFactors.push_back(RangeFactor(i, symbol('L', j), range,rangeNoise)); + newFactors.emplace_shared>( + i, Symbol('L', j), range, rangeNoise); k = k + 1; countK = countK + 1; } // Check whether to update iSAM 2 if ((k > minK) && (countK > incK)) { - if (!initialized) { // Do a full optimize for first minK ranges + if (!initialized) { // Do a full optimize for first minK ranges gttic_(batchInitialization); - LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial); + gtsam::LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial); initial = batchOptimizer.optimize(); gttoc_(batchInitialization); initialized = true; @@ -185,16 +205,16 @@ int main (int argc, char** argv) { isam.update(newFactors, initial); gttoc_(update); gttic_(calculateEstimate); - Values result = isam.calculateEstimate(); + gtsam::Values result = isam.calculateEstimate(); gttoc_(calculateEstimate); lastPose = result.at(i); - newFactors = NonlinearFactorGraph(); - initial = Values(); + newFactors = gtsam::NonlinearFactorGraph(); + initial = gtsam::Values(); countK = 0; } i += 1; - //--------------------------------- odometry loop ----------------------------------------- - } // end for + //--------------------------------- odometry loop -------------------------- + } // end for gttoc_(iSAM); // Print timings @@ -202,4 +222,3 @@ int main (int argc, char** argv) { exit(0); } - From f7af2c09e7a94cc43d7be1678ae6f0dc4de0ddd9 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 10 Mar 2022 17:28:18 -0500 Subject: [PATCH 078/116] Now initializing randomly --- examples/RangeISAMExample_plaza2.cpp | 43 +++++++++++++++++----------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp index 898460b49..bf30cfbb7 100644 --- a/examples/RangeISAMExample_plaza2.cpp +++ b/examples/RangeISAMExample_plaza2.cpp @@ -56,10 +56,11 @@ using gtsam::Symbol; #include using gtsam::tictoc_print_; - // Standard headers, added last, so we know headers above work on their own. #include #include +#include +#include #include #include #include @@ -73,7 +74,7 @@ namespace NM = gtsam::noiseModel; // load the odometry // DR: Odometry Input (delta distance traveled and delta heading change) -// Time (sec) Delta Dist. Trav. (m) Delta Heading (rad) +// Time (sec) Delta Distance Traveled (m) Delta Heading (rad) using TimedOdometry = std::pair; std::list readOdometry() { std::list odometryList; @@ -120,7 +121,6 @@ int main(int argc, char** argv) { size_t minK = 150; // minimum number of range measurements to process initially size_t incK = 25; // minimum number of range measurements to process after - bool groundTruth = false; bool robust = true; // Set Noise parameters @@ -129,6 +129,7 @@ int main(int argc, char** argv) { double sigmaR = 100; // range standard deviation const NM::Base::shared_ptr // all same type priorNoise = NM::Diagonal::Sigmas(priorSigmas), // prior + looseNoise = NM::Isotropic::Sigma(2, 1000), // loose LM prior odoNoise = NM::Diagonal::Sigmas(odoSigmas), // odometry gaussian = NM::Isotropic::Sigma(1, sigmaR), // non-robust tukey = NM::Robust::Create(NM::mEstimator::Tukey::Create(15), @@ -145,18 +146,11 @@ int main(int argc, char** argv) { gtsam::Values initial; initial.insert(0, pose0); - // initialize points - if (groundTruth) { // from TL file - initial.insert(Symbol('L', 1), Point2(-68.9265, 18.3778)); - initial.insert(Symbol('L', 6), Point2(-37.5805, 69.2278)); - initial.insert(Symbol('L', 0), Point2(-33.6205, 26.9678)); - initial.insert(Symbol('L', 5), Point2(1.7095, -5.8122)); - } else { // drawn from sigma=1 Gaussian in matlab version - initial.insert(Symbol('L', 1), Point2(3.5784, 2.76944)); - initial.insert(Symbol('L', 6), Point2(-1.34989, 3.03492)); - initial.insert(Symbol('L', 0), Point2(0.725404, -0.0630549)); - initial.insert(Symbol('L', 5), Point2(0.714743, -0.204966)); - } + // We will initialize landmarks randomly, and keep track of which landmarks we + // already added with a set. + std::mt19937_64 rng; + std::normal_distribution normal(0.0, 1.0); + std::set initializedLandmarks; // set some loop variables size_t i = 1; // step counter @@ -185,9 +179,19 @@ int main(int argc, char** argv) { // Check if there are range factors to be added while (k < K && t >= boost::get<0>(triples[k])) { size_t j = boost::get<1>(triples[k]); + Symbol landmark_key('L', j); double range = boost::get<2>(triples[k]); newFactors.emplace_shared>( - i, Symbol('L', j), range, rangeNoise); + i, landmark_key, range, rangeNoise); + if (initializedLandmarks.count(landmark_key) == 0) { + double x = normal(rng), y = normal(rng); + initial.insert(landmark_key, Point2(x, y)); + initializedLandmarks.insert(landmark_key); + // We also add a very loose prior on the landmark in case there is only + // one sighting, which cannot fully determine the landmark. + newFactors.emplace_shared>( + landmark_key, Point2(0, 0), looseNoise); + } k = k + 1; countK = countK + 1; } @@ -220,5 +224,12 @@ int main(int argc, char** argv) { // Print timings tictoc_print_(); + // Print optimized landmarks: + gtsam::Values finalResult = isam.calculateEstimate(); + for (auto&& landmark_key : initializedLandmarks) { + Point2 p = finalResult.at(landmark_key); + std::cout << landmark_key << ":" << p.transpose() << "\n"; + } + exit(0); } From 8496565d9d4fa6ef4a73ab1479111f48d881d4a9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 11 Mar 2022 08:41:24 -0500 Subject: [PATCH 079/116] documentation updates --- gtsam/discrete/DiscreteLookupDAG.h | 2 +- gtsam/geometry/Pose3.cpp | 2 +- gtsam/inference/BayesTree.h | 2 +- gtsam/nonlinear/ISAM2.h | 11 +++++++++++ 4 files changed, 14 insertions(+), 3 deletions(-) diff --git a/gtsam/discrete/DiscreteLookupDAG.h b/gtsam/discrete/DiscreteLookupDAG.h index 38a846f1f..15169a1dc 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -46,7 +46,7 @@ class GTSAM_EXPORT DiscreteLookupTable : public DiscreteConditional { * @brief Construct a new Discrete Lookup Table object * * @param nFrontals number of frontal variables - * @param keys a orted list of gtsam::Keys + * @param keys a sorted list of gtsam::Keys * @param potentials the algebraic decision tree with lookup values */ DiscreteLookupTable(size_t nFrontals, const DiscreteKeys& keys, diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 1e399ad18..88f128191 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -59,7 +59,7 @@ Matrix6 Pose3::AdjointMap() const { const Matrix3 R = R_.matrix(); Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R; Matrix6 adj; - adj << R, Z_3x3, A, R; + adj << R, Z_3x3, A, R; // Gives [R 0; A R] return adj; } diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h index a32b3ce22..5b053ebee 100644 --- a/gtsam/inference/BayesTree.h +++ b/gtsam/inference/BayesTree.h @@ -139,7 +139,7 @@ namespace gtsam { return nodes_.empty(); } - /** return nodes */ + /** Return nodes. Each node is a clique of variables obtained after elimination. */ const Nodes& nodes() const { return nodes_; } /** Access node by variable */ diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h index 92c2142a7..37feee837 100644 --- a/gtsam/nonlinear/ISAM2.h +++ b/gtsam/nonlinear/ISAM2.h @@ -295,6 +295,17 @@ class GTSAM_EXPORT ISAM2 : public BayesTree { const ISAM2UpdateParams& updateParams, const FastList& affectedKeys, const KeySet& relinKeys); + /** + * @brief Perform an incremental update of the factor graph to return a new + * Bayes Tree with affected keys. + * + * @param updateParams Parameters for the ISAM2 update. + * @param relinKeys Keys of variables to relinearize. + * @param affectedKeys The set of keys which are affected in the update. + * @param affectedKeysSet [output] Affected and contaminated keys. + * @param orphans [output] List of orphanes cliques after elimination. + * @param result [output] The result of the incremental update step. + */ void recalculateIncremental(const ISAM2UpdateParams& updateParams, const KeySet& relinKeys, const FastList& affectedKeys, From b9f6d67fc71617fe1b38aed967d3b9b6d31c2133 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 11 Mar 2022 08:42:08 -0500 Subject: [PATCH 080/116] printing updates --- gtsam/navigation/PreintegrationParams.cpp | 1 - gtsam/slam/BetweenFactor.h | 4 +++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/PreintegrationParams.cpp b/gtsam/navigation/PreintegrationParams.cpp index 2298bb696..2548f95a6 100644 --- a/gtsam/navigation/PreintegrationParams.cpp +++ b/gtsam/navigation/PreintegrationParams.cpp @@ -34,7 +34,6 @@ void PreintegrationParams::print(const string& s) const { << endl; if (omegaCoriolis && use2ndOrderCoriolis) cout << "Using 2nd-order Coriolis" << endl; - if (body_P_sensor) body_P_sensor->print(" "); cout << "n_gravity = (" << n_gravity.transpose() << ")" << endl; } diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 8a1ffdd72..f80462847 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -80,7 +80,9 @@ namespace gtsam { /// @{ /// print with optional string - void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { + void print( + const std::string& s = "", + const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override { std::cout << s << "BetweenFactor(" << keyFormatter(this->key1()) << "," << keyFormatter(this->key2()) << ")\n"; From ebc75e3a8dac9bf9218a2e4ca0240a95082260e6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 11 Mar 2022 08:42:40 -0500 Subject: [PATCH 081/116] added test for ordering in Python --- .../gtsam/tests/test_GaussianFactorGraph.py | 27 +++++++++++++++---- 1 file changed, 22 insertions(+), 5 deletions(-) diff --git a/python/gtsam/tests/test_GaussianFactorGraph.py b/python/gtsam/tests/test_GaussianFactorGraph.py index a29b0f263..26a8be1a6 100644 --- a/python/gtsam/tests/test_GaussianFactorGraph.py +++ b/python/gtsam/tests/test_GaussianFactorGraph.py @@ -23,23 +23,23 @@ from gtsam.utils.test_case import GtsamTestCase def create_graph(): """Create a basic linear factor graph for testing""" graph = gtsam.GaussianFactorGraph() - + x0 = X(0) x1 = X(1) x2 = X(2) - + BETWEEN_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(np.ones(1)) 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(x2, np.eye(1), x1, -np.eye(1), 2 * np.ones(1), BETWEEN_NOISE) graph.add(x0, np.eye(1), np.zeros(1), PRIOR_NOISE) return graph, (x0, x1, x2) + class TestGaussianFactorGraph(GtsamTestCase): """Tests for Gaussian Factor Graphs.""" - def test_fg(self): """Test solving a linear factor graph""" graph, X = create_graph() @@ -71,7 +71,7 @@ class TestGaussianFactorGraph(GtsamTestCase): self.assertAlmostEqual(EXPECTEDM[0], m[0], delta=1e-8) self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8) self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8) - + def test_linearMarginalization(self): """Marginalize a linear factor graph""" graph, X = create_graph() @@ -88,5 +88,22 @@ class TestGaussianFactorGraph(GtsamTestCase): self.assertAlmostEqual(EXPECTEDM[1], m[1], delta=1e-8) self.assertAlmostEqual(EXPECTEDM[2], m[2], delta=1e-8) + def test_ordering(self): + """Test ordering""" + gfg, keys = create_graph() + ordering = gtsam.Ordering() + for key in keys[::-1]: + ordering.push_back(key) + + bn = gfg.eliminateSequential(ordering) + self.assertEqual(bn.size(), 3) + + keyVector = gtsam.KeyVector() + keyVector.append(keys[2]) + ordering = gtsam.Ordering.ColamdConstrainedLastGaussianFactorGraph(gfg, keyVector) + bn = gfg.eliminateSequential(ordering) + self.assertEqual(bn.size(), 3) + + if __name__ == '__main__': unittest.main() From 23c6a7e39265156ba2b3d3d6f4b93179fd34a093 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 11 Mar 2022 12:32:54 -0500 Subject: [PATCH 082/116] comment out failing python code since it is out of scope --- python/gtsam/tests/test_GaussianFactorGraph.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/python/gtsam/tests/test_GaussianFactorGraph.py b/python/gtsam/tests/test_GaussianFactorGraph.py index 26a8be1a6..09ac4c564 100644 --- a/python/gtsam/tests/test_GaussianFactorGraph.py +++ b/python/gtsam/tests/test_GaussianFactorGraph.py @@ -100,9 +100,10 @@ class TestGaussianFactorGraph(GtsamTestCase): keyVector = gtsam.KeyVector() keyVector.append(keys[2]) - ordering = gtsam.Ordering.ColamdConstrainedLastGaussianFactorGraph(gfg, keyVector) - bn = gfg.eliminateSequential(ordering) - self.assertEqual(bn.size(), 3) + #TODO(Varun) Below code causes segfault in Debug config + # ordering = gtsam.Ordering.ColamdConstrainedLastGaussianFactorGraph(gfg, keyVector) + # bn = gfg.eliminateSequential(ordering) + # self.assertEqual(bn.size(), 3) if __name__ == '__main__': From b7932957dad145f12370188a7a5abdbcd85c5dd3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 11 Mar 2022 12:33:53 -0500 Subject: [PATCH 083/116] update scoop installation for Windows CI --- .github/workflows/build-windows.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build-windows.yml b/.github/workflows/build-windows.yml index 0cc67ad5a..ef2500b46 100644 --- a/.github/workflows/build-windows.yml +++ b/.github/workflows/build-windows.yml @@ -48,7 +48,9 @@ jobs: - name: Install Dependencies shell: powershell run: | - Invoke-Expression (New-Object System.Net.WebClient).DownloadString('https://get.scoop.sh') + iwr -useb get.scoop.sh -outfile 'install_scoop.ps1' + .\install_scoop.ps1 -RunAsAdmin + scoop install cmake --global # So we don't get issues with CMP0074 policy scoop install ninja --global From bcf49e6243b67d237aa14b9a52728ed674f2453e Mon Sep 17 00:00:00 2001 From: Thomas Sayre-McCord Date: Mon, 14 Mar 2022 09:19:19 +0100 Subject: [PATCH 084/116] set new code to google style and fix doc - new code in triangulation and testTriangulation - clean up doc number and typos --- gtsam/geometry/tests/testTriangulation.cpp | 48 +++++++++------ gtsam/geometry/triangulation.h | 70 +++++++++++++--------- 2 files changed, 72 insertions(+), 46 deletions(-) diff --git a/gtsam/geometry/tests/testTriangulation.cpp b/gtsam/geometry/tests/testTriangulation.cpp index 0e30acaae..fb66fb6a2 100644 --- a/gtsam/geometry/tests/testTriangulation.cpp +++ b/gtsam/geometry/tests/testTriangulation.cpp @@ -97,16 +97,17 @@ TEST(triangulation, twoPoses) { } //****************************************************************************** -// Simple test with a well-behaved two camera situation with Cal3S2 calibration. -TEST(triangulation, twoPosesCal3S2) { +// Simple test with a well-behaved two camera situation with Cal3DS2 calibration. +TEST(triangulation, twoPosesCal3DS2) { static const boost::shared_ptr sharedDistortedCal = // - boost::make_shared(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, -0.0003); + boost::make_shared(1500, 1200, 0, 640, 480, -.3, 0.1, 0.0001, + -0.0003); PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); -// 1. Project two landmarks into two cameras and triangulate + // 0. Project two landmarks into two cameras and triangulate Point2 z1Distorted = camera1Distorted.project(landmark); Point2 z2Distorted = camera2Distorted.project(landmark); @@ -121,13 +122,15 @@ TEST(triangulation, twoPosesCal3S2) { // 1. Test simple DLT, perfect in no noise situation bool optimize = false; boost::optional actual1 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(landmark, *actual1, 1e-7)); // 2. test with optimization on, same answer optimize = true; boost::optional actual2 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(landmark, *actual2, 1e-7)); // 3. Add some noise and try again: result should be ~ (4.995, @@ -136,28 +139,32 @@ TEST(triangulation, twoPosesCal3S2) { measurements.at(1) += Point2(-0.2, 0.3); optimize = false; boost::optional actual3 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); // 4. Now with optimization on optimize = true; boost::optional actual4 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); } //****************************************************************************** -// Simple test with a well-behaved two camera situation with Fisheye calibration. +// Simple test with a well-behaved two camera situation with Fisheye +// calibration. TEST(triangulation, twoPosesFisheye) { using Calibration = Cal3Fisheye; static const boost::shared_ptr sharedDistortedCal = // - boost::make_shared(1500, 1200, .1, 640, 480, -.3, 0.1, 0.0001, -0.0003); + boost::make_shared(1500, 1200, .1, 640, 480, -.3, 0.1, + 0.0001, -0.0003); PinholeCamera camera1Distorted(pose1, *sharedDistortedCal); PinholeCamera camera2Distorted(pose2, *sharedDistortedCal); -// 1. Project two landmarks into two cameras and triangulate + // 0. Project two landmarks into two cameras and triangulate Point2 z1Distorted = camera1Distorted.project(landmark); Point2 z2Distorted = camera2Distorted.project(landmark); @@ -172,13 +179,15 @@ TEST(triangulation, twoPosesFisheye) { // 1. Test simple DLT, perfect in no noise situation bool optimize = false; boost::optional actual1 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(landmark, *actual1, 1e-7)); // 2. test with optimization on, same answer optimize = true; boost::optional actual2 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(landmark, *actual2, 1e-7)); // 3. Add some noise and try again: result should be ~ (4.995, @@ -187,17 +196,18 @@ TEST(triangulation, twoPosesFisheye) { measurements.at(1) += Point2(-0.2, 0.3); optimize = false; boost::optional actual3 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual3, 1e-3)); // 4. Now with optimization on optimize = true; boost::optional actual4 = // - triangulatePoint3(poses, sharedDistortedCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, sharedDistortedCal, measurements, + rank_tol, optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19814), *actual4, 1e-3)); } - //****************************************************************************** // Similar, but now with Bundler calibration TEST(triangulation, twoPosesBundler) { @@ -220,7 +230,8 @@ TEST(triangulation, twoPosesBundler) { double rank_tol = 1e-9; boost::optional actual = // - triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, + optimize); EXPECT(assert_equal(landmark, *actual, 1e-7)); // Add some noise and try again @@ -228,7 +239,8 @@ TEST(triangulation, twoPosesBundler) { measurements.at(1) += Point2(-0.2, 0.3); boost::optional actual2 = // - triangulatePoint3(poses, bundlerCal, measurements, rank_tol, optimize); + triangulatePoint3(poses, bundlerCal, measurements, rank_tol, + optimize); EXPECT(assert_equal(Point3(4.995, 0.499167, 1.19847), *actual2, 1e-3)); } diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 0df569608..49b5aef04 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -227,7 +227,8 @@ std::vector> projectionMatricesFrom return projection_matrices; } -/** Create a pinhole calibration from a different Cal3 object, removing distortion. +/** Create a pinhole calibration from a different Cal3 object, removing + * distortion. * * @tparam CALIBRATION Original calibration object. * @param cal Input calibration object. @@ -236,13 +237,14 @@ std::vector> projectionMatricesFrom template Cal3_S2 createPinholeCalibration(const CALIBRATION& cal) { const auto& K = cal.K(); - return Cal3_S2(K(0,0), K(1,1), K(0,1), K(0,2), K(1,2)); + return Cal3_S2(K(0, 0), K(1, 1), K(0, 1), K(0, 2), K(1, 2)); } -/** Internal undistortMeasurement to be used by undistortMeasurement and undistortMeasurements */ +/** Internal undistortMeasurement to be used by undistortMeasurement and + * undistortMeasurements */ template -MEASUREMENT undistortMeasurementInternal(const CALIBRATION& cal, - const MEASUREMENT& measurement, +MEASUREMENT undistortMeasurementInternal( + const CALIBRATION& cal, const MEASUREMENT& measurement, boost::optional pinholeCal = boost::none) { if (!pinholeCal) { pinholeCal = createPinholeCalibration(cal); @@ -250,10 +252,12 @@ MEASUREMENT undistortMeasurementInternal(const CALIBRATION& cal, return pinholeCal->uncalibrate(cal.calibrate(measurement)); } -/** Remove distortion for measurements so as if the measurements came from a pinhole camera. +/** Remove distortion for measurements so as if the measurements came from a + * pinhole camera. * - * Removes distortion but maintains the K matrix of the initial cal. Operates by calibrating using - * full calibration and uncalibrating with only the pinhole component of the calibration. + * Removes distortion but maintains the K matrix of the initial cal. Operates by + * calibrating using full calibration and uncalibrating with only the pinhole + * component of the calibration. * @tparam CALIBRATION Calibration type to use. * @param cal Calibration with which measurements were taken. * @param measurements Vector of measurements to undistort. @@ -261,14 +265,17 @@ MEASUREMENT undistortMeasurementInternal(const CALIBRATION& cal, */ template Point2Vector undistortMeasurements(const CALIBRATION& cal, - const Point2Vector& measurements) { + const Point2Vector& measurements) { Cal3_S2 pinholeCalibration = createPinholeCalibration(cal); Point2Vector undistortedMeasurements; - // Calibrate with cal and uncalibrate with pinhole version of cal so that measurements are undistorted. - std::transform(measurements.begin(), measurements.end(), std::back_inserter(undistortedMeasurements), + // Calibrate with cal and uncalibrate with pinhole version of cal so that + // measurements are undistorted. + std::transform(measurements.begin(), measurements.end(), + std::back_inserter(undistortedMeasurements), [&cal, &pinholeCalibration](const Point2& measurement) { - return undistortMeasurementInternal(cal, measurement, pinholeCalibration); - }); + return undistortMeasurementInternal( + cal, measurement, pinholeCalibration); + }); return undistortedMeasurements; } @@ -276,30 +283,33 @@ Point2Vector undistortMeasurements(const CALIBRATION& cal, template <> inline Point2Vector undistortMeasurements(const Cal3_S2& cal, const Point2Vector& measurements) { - return measurements; + return measurements; } - -/** Remove distortion for measurements so as if the measurements came from a pinhole camera. +/** Remove distortion for measurements so as if the measurements came from a + * pinhole camera. * - * Removes distortion but maintains the K matrix of the initial calibrations. Operates by calibrating using - * full calibration and uncalibrating with only the pinhole component of the calibration. + * Removes distortion but maintains the K matrix of the initial calibrations. + * Operates by calibrating using full calibration and uncalibrating with only + * the pinhole component of the calibration. * @tparam CAMERA Camera type to use. * @param cameras Cameras corresponding to each measurement. * @param measurements Vector of measurements to undistort. * @return measurements with the effect of the distortion of the camera removed. */ template -typename CAMERA::MeasurementVector undistortMeasurements(const CameraSet& cameras, +typename CAMERA::MeasurementVector undistortMeasurements( + const CameraSet& cameras, const typename CAMERA::MeasurementVector& measurements) { - const size_t num_meas = cameras.size(); assert(num_meas == measurements.size()); typename CAMERA::MeasurementVector undistortedMeasurements(num_meas); for (size_t ii = 0; ii < num_meas; ++ii) { - // Calibrate with cal and uncalibrate with pinhole version of cal so that measurements are undistorted. + // Calibrate with cal and uncalibrate with pinhole version of cal so that + // measurements are undistorted. undistortedMeasurements[ii] = - undistortMeasurementInternal(cameras[ii].calibration(), measurements[ii]); + undistortMeasurementInternal( + cameras[ii].calibration(), measurements[ii]); } return undistortedMeasurements; } @@ -315,8 +325,8 @@ inline PinholeCamera::MeasurementVector undistortMeasurements( /** Specialize for SphericalCamera to do nothing. */ template inline SphericalCamera::MeasurementVector undistortMeasurements( - const CameraSet& cameras, - const SphericalCamera::MeasurementVector& measurements) { + const CameraSet& cameras, + const SphericalCamera::MeasurementVector& measurements) { return measurements; } @@ -347,10 +357,12 @@ Point3 triangulatePoint3(const std::vector& poses, auto projection_matrices = projectionMatricesFromPoses(poses, sharedCal); // Undistort the measurements, leaving only the pinhole elements in effect. - auto undistortedMeasurements = undistortMeasurements(*sharedCal, measurements); + auto undistortedMeasurements = + undistortMeasurements(*sharedCal, measurements); // Triangulate linearly - Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); + Point3 point = + triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); // Then refine using non-linear optimization if (optimize) @@ -398,9 +410,11 @@ Point3 triangulatePoint3( auto projection_matrices = projectionMatricesFromCameras(cameras); // Undistort the measurements, leaving only the pinhole elements in effect. - auto undistortedMeasurements = undistortMeasurements(cameras, measurements); + auto undistortedMeasurements = + undistortMeasurements(cameras, measurements); - Point3 point = triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); + Point3 point = + triangulateDLT(projection_matrices, undistortedMeasurements, rank_tol); // The n refine using non-linear optimization if (optimize) From 5e9020237f8a821a641080911adebeab8da84426 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 18 Mar 2022 00:11:05 -0400 Subject: [PATCH 085/116] add test for visitWith with pruned tree --- gtsam/discrete/tests/testDecisionTree.cpp | 46 ++++++++++++++++++++--- 1 file changed, 41 insertions(+), 5 deletions(-) diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index 967023eeb..ca5daf201 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -20,12 +20,10 @@ // #define DT_DEBUG_MEMORY // #define DT_NO_PRUNING #define DISABLE_DOT -#include - -#include -#include - #include +#include +#include +#include #include using namespace boost::assign; @@ -346,6 +344,44 @@ TEST(DecisionTree, visitWith) { EXPECT_DOUBLES_EQUAL(6.0, sum, 1e-9); } +/* ************************************************************************** */ +// Test visit, with Choices argument. +TEST(DecisionTree, VisitWithPruned) { + // Create pruned tree + std::pair A("A", 2), B("B", 2), C("C", 2); + std::vector> labels = {C, B, A}; + std::vector nodes = {0, 0, 2, 3, 4, 4, 6, 7}; + DT tree(labels, nodes); + + std::vector> choices; + auto func = [&](const Assignment& choice, const int& d) { + choices.push_back(choice); + }; + tree.visitWith(func); + + EXPECT_LONGS_EQUAL(6, choices.size()); + + Assignment expectedAssignment; + + expectedAssignment = {{"B", 0}, {"C", 0}}; + EXPECT(expectedAssignment == choices.at(0)); + + expectedAssignment = {{"A", 0}, {"B", 1}, {"C", 0}}; + EXPECT(expectedAssignment == choices.at(1)); + + expectedAssignment = {{"A", 1}, {"B", 1}, {"C", 0}}; + EXPECT(expectedAssignment == choices.at(2)); + + expectedAssignment = {{"B", 0}, {"C", 1}}; + EXPECT(expectedAssignment == choices.at(3)); + + expectedAssignment = {{"A", 0}, {"B", 1}, {"C", 1}}; + EXPECT(expectedAssignment == choices.at(4)); + + expectedAssignment = {{"A", 1}, {"B", 1}, {"C", 1}}; + EXPECT(expectedAssignment == choices.at(5)); +} + /* ************************************************************************** */ // Test fold. TEST(DecisionTree, fold) { From 13c60990f7336d320cad3ff5a692d25c32db9398 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 18 Mar 2022 00:11:38 -0400 Subject: [PATCH 086/116] fix visitWith operator() to be more functional --- gtsam/discrete/Assignment.h | 2 ++ gtsam/discrete/DecisionTree-inl.h | 7 +++++-- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/gtsam/discrete/Assignment.h b/gtsam/discrete/Assignment.h index cdbf0a2e9..90e2dbdd8 100644 --- a/gtsam/discrete/Assignment.h +++ b/gtsam/discrete/Assignment.h @@ -33,6 +33,8 @@ namespace gtsam { template class Assignment : public std::map { public: + using std::map::operator=; + void print(const std::string& s = "Assignment: ") const { std::cout << s << ": "; for (const typename Assignment::value_type& keyValue : *this) diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 01c7b689c..c616c0269 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -666,8 +666,11 @@ namespace gtsam { if (!choice) throw std::invalid_argument("DecisionTree::VisitWith: Invalid NodePtr"); for (size_t i = 0; i < choice->nrChoices(); i++) { - choices[choice->label()] = i; // Set assignment for label to i - (*this)(choice->branches()[i]); // recurse! + choices[choice->label()] = i; // Set assignment for label to i + + VisitWith visit(f); + visit.choices = choices; + visit(choice->branches()[i]); // recurse! } } }; From fa542a20384435c88eaf3cf2b460a2c645908812 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 18 Mar 2022 08:19:01 -0400 Subject: [PATCH 087/116] address review comments --- gtsam/discrete/DecisionTree-inl.h | 8 +++++--- gtsam/discrete/tests/testDecisionTree.cpp | 6 ++++-- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index c616c0269..627c1a5aa 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -668,9 +668,11 @@ namespace gtsam { for (size_t i = 0; i < choice->nrChoices(); i++) { choices[choice->label()] = i; // Set assignment for label to i - VisitWith visit(f); - visit.choices = choices; - visit(choice->branches()[i]); // recurse! + (*this)(choice->branches()[i]); // recurse! + + // Remove the choice so we are backtracking + auto choice_it = choices.find(choice->label()); + choices.erase(choice_it); } } }; diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index ca5daf201..91deed625 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -20,11 +20,13 @@ // #define DT_DEBUG_MEMORY // #define DT_NO_PRUNING #define DISABLE_DOT -#include -#include #include + +#include #include +#include + #include using namespace boost::assign; From e271a8a81e861433502a200dfa8690e80c280bed Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 19 Mar 2022 00:22:30 -0400 Subject: [PATCH 088/116] wrap ParameterMatrix as argument for Values --- gtsam/nonlinear/nonlinear.i | 63 ++++++++++++++++++++++++++++++++++++- 1 file changed, 62 insertions(+), 1 deletion(-) diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index da5e8b29c..800208c33 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -25,6 +25,7 @@ namespace gtsam { #include #include #include +#include #include class GraphvizFormatting : gtsam::DotWriter { @@ -228,6 +229,21 @@ class Values { void insert(size_t j, const gtsam::imuBias::ConstantBias& constant_bias); void insert(size_t j, const gtsam::NavState& nav_state); void insert(size_t j, double c); + void insert(size_t j, const gtsam::ParameterMatrix<1>& X); + void insert(size_t j, const gtsam::ParameterMatrix<2>& X); + void insert(size_t j, const gtsam::ParameterMatrix<3>& X); + void insert(size_t j, const gtsam::ParameterMatrix<4>& X); + void insert(size_t j, const gtsam::ParameterMatrix<5>& X); + void insert(size_t j, const gtsam::ParameterMatrix<6>& X); + void insert(size_t j, const gtsam::ParameterMatrix<7>& X); + void insert(size_t j, const gtsam::ParameterMatrix<8>& X); + void insert(size_t j, const gtsam::ParameterMatrix<9>& X); + void insert(size_t j, const gtsam::ParameterMatrix<10>& X); + void insert(size_t j, const gtsam::ParameterMatrix<11>& X); + void insert(size_t j, const gtsam::ParameterMatrix<12>& X); + void insert(size_t j, const gtsam::ParameterMatrix<13>& X); + void insert(size_t j, const gtsam::ParameterMatrix<14>& X); + void insert(size_t j, const gtsam::ParameterMatrix<15>& X); void update(size_t j, const gtsam::Point2& point2); void update(size_t j, const gtsam::Point3& point3); @@ -254,6 +270,21 @@ class Values { void update(size_t j, Vector vector); void update(size_t j, Matrix matrix); void update(size_t j, double c); + void update(size_t j, const gtsam::ParameterMatrix<1>& X); + void update(size_t j, const gtsam::ParameterMatrix<2>& X); + void update(size_t j, const gtsam::ParameterMatrix<3>& X); + void update(size_t j, const gtsam::ParameterMatrix<4>& X); + void update(size_t j, const gtsam::ParameterMatrix<5>& X); + void update(size_t j, const gtsam::ParameterMatrix<6>& X); + void update(size_t j, const gtsam::ParameterMatrix<7>& X); + void update(size_t j, const gtsam::ParameterMatrix<8>& X); + void update(size_t j, const gtsam::ParameterMatrix<9>& X); + void update(size_t j, const gtsam::ParameterMatrix<10>& X); + void update(size_t j, const gtsam::ParameterMatrix<11>& X); + void update(size_t j, const gtsam::ParameterMatrix<12>& X); + void update(size_t j, const gtsam::ParameterMatrix<13>& X); + void update(size_t j, const gtsam::ParameterMatrix<14>& X); + void update(size_t j, const gtsam::ParameterMatrix<15>& X); void insert_or_assign(size_t j, const gtsam::Point2& point2); void insert_or_assign(size_t j, const gtsam::Point3& point3); @@ -280,6 +311,21 @@ class Values { void insert_or_assign(size_t j, Vector vector); void insert_or_assign(size_t j, Matrix matrix); void insert_or_assign(size_t j, double c); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<1>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<2>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<3>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<4>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<5>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<6>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<7>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<8>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<9>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<10>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<11>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<12>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<13>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<14>& X); + void insert_or_assign(size_t j, const gtsam::ParameterMatrix<15>& X); template + double, + gtsam::ParameterMatrix<1>, + gtsam::ParameterMatrix<2>, + gtsam::ParameterMatrix<3>, + gtsam::ParameterMatrix<4>, + gtsam::ParameterMatrix<5>, + gtsam::ParameterMatrix<6>, + gtsam::ParameterMatrix<7>, + gtsam::ParameterMatrix<8>, + gtsam::ParameterMatrix<9>, + gtsam::ParameterMatrix<10>, + gtsam::ParameterMatrix<11>, + gtsam::ParameterMatrix<12>, + gtsam::ParameterMatrix<13>, + gtsam::ParameterMatrix<14>, + gtsam::ParameterMatrix<15>}> T at(size_t j); }; From a7f65c21bba108f6bb027278646d4d384374f9a6 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 19 Mar 2022 12:56:06 -0400 Subject: [PATCH 089/116] New apply method which takes op with Assignment --- gtsam/discrete/DecisionTree-inl.h | 57 +++++++++++++++++++++++ gtsam/discrete/DecisionTree.h | 20 ++++++++ gtsam/discrete/tests/testDecisionTree.cpp | 28 +++++++++++ 3 files changed, 105 insertions(+) diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 627c1a5aa..3f82ce9a6 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -112,6 +112,13 @@ namespace gtsam { return f; } + /// Apply unary operator with assignment + NodePtr apply(const UnaryAssignment& op, + const Assignment& choices) const override { + NodePtr f(new Leaf(op(choices, constant_))); + return f; + } + // Apply binary operator "h = f op g" on Leaf node // Note op is not assumed commutative so we need to keep track of order // Simply calls apply on argument to call correct virtual method: @@ -322,12 +329,48 @@ namespace gtsam { for (const NodePtr& branch : f.branches_) push_back(branch->apply(op)); } + /** + * @brief Constructor which accepts a UnaryAssignment op and the + * corresponding assignment. + * + * @param label The label for this node. + * @param f The original choice node to apply the op on. + * @param op Function to apply on the choice node. Takes Assignment and + * value as arguments. + * @param choices The Assignment that will go to op. + */ + Choice(const L& label, const Choice& f, const UnaryAssignment& op, + const Assignment& choices) + : label_(label), allSame_(true) { + branches_.reserve(f.branches_.size()); // reserve space + + Assignment choices_ = choices; + + for (size_t i = 0; i < f.branches_.size(); i++) { + choices_[label_] = i; // Set assignment for label to i + + const NodePtr branch = f.branches_[i]; + push_back(branch->apply(op, choices_)); + + // Remove the choice so we are backtracking + auto choice_it = choices_.find(label_); + choices_.erase(choice_it); + } + } + /** apply unary operator */ NodePtr apply(const Unary& op) const override { auto r = boost::make_shared(label_, *this, op); return Unique(r); } + /// Apply unary operator with assignment + NodePtr apply(const UnaryAssignment& op, + const Assignment& choices) const override { + auto r = boost::make_shared(label_, *this, op, choices); + return Unique(r); + } + // Apply binary operator "h = f op g" on Choice node // Note op is not assumed commutative so we need to keep track of order // Simply calls apply on argument to call correct virtual method: @@ -739,6 +782,20 @@ namespace gtsam { return DecisionTree(root_->apply(op)); } + /// Apply unary operator with assignment + template + DecisionTree DecisionTree::apply( + const UnaryAssignment& op) const { + std::cout << "Calling the correct apply" << std::endl; + // It is unclear what should happen if tree is empty: + if (empty()) { + throw std::runtime_error( + "DecisionTree::apply(unary op) undefined for empty tree."); + } + Assignment choices; + return DecisionTree(root_->apply(op, choices)); + } + /****************************************************************************/ template DecisionTree DecisionTree::apply(const DecisionTree& g, diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index d655756b8..13ff0a8c6 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -54,6 +54,7 @@ namespace gtsam { /** Handy typedefs for unary and binary function types */ using Unary = std::function; + using UnaryAssignment = std::function&, const Y&)>; using Binary = std::function; /** A label annotated with cardinality */ @@ -103,6 +104,8 @@ namespace gtsam { &DefaultCompare) const = 0; virtual const Y& operator()(const Assignment& x) const = 0; virtual Ptr apply(const Unary& op) const = 0; + virtual Ptr apply(const UnaryAssignment& op, + const Assignment& choices) const = 0; virtual Ptr apply_f_op_g(const Node&, const Binary&) const = 0; virtual Ptr apply_g_op_fL(const Leaf&, const Binary&) const = 0; virtual Ptr apply_g_op_fC(const Choice&, const Binary&) const = 0; @@ -283,6 +286,16 @@ namespace gtsam { /** apply Unary operation "op" to f */ DecisionTree apply(const Unary& op) const; + /** + * @brief Apply Unary operation "op" to f while also providing the + * corresponding assignment. + * + * @param op Function which takes Assignment and Y as input and returns + * object of type Y. + * @return DecisionTree + */ + DecisionTree apply(const UnaryAssignment& op) const; + /** apply binary operation "op" to f and g */ DecisionTree apply(const DecisionTree& g, const Binary& op) const; @@ -337,6 +350,13 @@ namespace gtsam { return f.apply(op); } + /// Apply unary operator `op` with Assignment to DecisionTree `f`. + template + DecisionTree apply(const DecisionTree& f, + const typename DecisionTree::UnaryAssignment& op) { + return f.apply(op); + } + /// Apply binary operator `op` to DecisionTree `f`. template DecisionTree apply(const DecisionTree& f, diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index 91deed625..935d433c6 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -90,6 +90,7 @@ struct DT : public DecisionTree { auto valueFormatter = [](const int& v) { return (boost::format("%d") % v).str(); }; + std::cout << s; Base::print("", keyFormatter, valueFormatter); } /// Equality method customized to int node type @@ -451,6 +452,33 @@ TEST(DecisionTree, threshold) { EXPECT_LONGS_EQUAL(2, thresholded.fold(count, 0)); } +/* ************************************************************************** */ +// Test apply with assignment. +TEST(DecisionTree, ApplyWithAssignment) { + // Create three level tree + vector keys; + keys += DT::LabelC("C", 2), DT::LabelC("B", 2), DT::LabelC("A", 2); + DT tree(keys, "1 2 3 4 5 6 7 8"); + + DecisionTree probTree( + keys, "0.01 0.02 0.03 0.04 0.05 0.06 0.07 0.08"); + double threshold = 0.035; + + // We test pruning one tree by indexing into another. + auto pruner = [&](const Assignment& choices, const int& x) { + // Prune out all the leaves with even numbers + if (probTree(choices) < threshold) { + return 0; + } else { + return x; + } + }; + DT prunedTree = tree.apply(pruner); + + DT expectedTree(keys, "0 0 0 4 5 6 7 8"); + EXPECT(assert_equal(expectedTree, prunedTree)); +} + /* ************************************************************************* */ int main() { TestResult tr; From 383d81298cb14ff9173fa78598a3570cbea5cca4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 19 Mar 2022 14:57:17 -0400 Subject: [PATCH 090/116] Added python notebook --- .../examples/RangeISAMExample_plaza2.ipynb | 9443 +++++++++++++++++ 1 file changed, 9443 insertions(+) create mode 100644 python/gtsam/examples/RangeISAMExample_plaza2.ipynb diff --git a/python/gtsam/examples/RangeISAMExample_plaza2.ipynb b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb new file mode 100644 index 000000000..e62423695 --- /dev/null +++ b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb @@ -0,0 +1,9443 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information\n", + "\n", + "A 2D Range SLAM example, with iSAM and smart range factors\n", + "\n", + "Author: Frank Dellaert" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "# pylint: disable=invalid-name, E1101\n", + "\n", + "from gtsam import Point2, Pose2\n", + "import plotly.express as px\n", + "import numpy as np\n", + "import gtsam\n", + "import math\n", + "\n", + "import matplotlib.pyplot as plt\n", + "from gtsam.utils import plot\n", + "from numpy.random import default_rng\n", + "\n", + "rng = default_rng()\n", + "\n", + "NM = gtsam.noiseModel" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Read 4090 odometry entries.\n" + ] + } + ], + "source": [ + "# load the odometry\n", + "# DR: Odometry Input (delta distance traveled and delta heading change)\n", + "# Time (sec) Delta Distance Traveled (m) Delta Heading (rad)\n", + "odometry = {}\n", + "data_file = gtsam.findExampleDataFile(\"Plaza2_DR.txt\")\n", + "for row in np.loadtxt(data_file):\n", + " t, distance_traveled, delta_heading = row\n", + " odometry[t] = Pose2(distance_traveled, 0, delta_heading)\n", + "M = len(odometry)\n", + "print(f\"Read {M} odometry entries.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Read 1816 range triples.\n" + ] + } + ], + "source": [ + "# load the ranges from TD\n", + "# Time (sec) Sender / Antenna ID Receiver Node ID Range (m)\n", + "triples = []\n", + "data_file = gtsam.findExampleDataFile(\"Plaza2_TD.txt\")\n", + "for row in np.loadtxt(data_file):\n", + " t, sender, receiver, _range = row\n", + " triples.append((t, int(receiver), _range))\n", + "K = len(triples)\n", + "print(f\"Read {K} range triples.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "# parameters\n", + "minK = 150 # minimum number of range measurements to process initially\n", + "incK = 25 # minimum number of range measurements to process after\n", + "robust = True" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "# Set Noise parameters\n", + "priorSigmas = gtsam.Point3(1, 1, math.pi)\n", + "odoSigmas = gtsam.Point3(0.05, 0.01, 0.1)\n", + "sigmaR = 100.0 # range standard deviation\n", + "\n", + "priorNoise = NM.Diagonal.Sigmas(priorSigmas) # prior\n", + "looseNoise = NM.Isotropic.Sigma(2, 1000) # loose LM prior\n", + "odoNoise = NM.Diagonal.Sigmas(odoSigmas) # odometry\n", + "gaussian = NM.Isotropic.Sigma(1, sigmaR) # non-robust\n", + "tukey = NM.Robust.Create(NM.mEstimator.Tukey.Create(15), gaussian) # robust\n", + "rangeNoise = tukey if robust else gaussian" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + ": cliques: 0, variables: 0\n", + "\n" + ] + } + ], + "source": [ + "# Initialize iSAM\n", + "isam = gtsam.ISAM2()\n", + "print(isam)" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "NonlinearFactorGraph: size: 1\n", + "\n", + "Factor 0: PriorFactor on 0\n", + " prior mean: (-34.2086, 45.3008, 1.1205)\n", + " noise model: diagonal sigmas[1; 1; 3.14159265];\n", + "\n", + " Values with 1 values:\n", + "Value 0: (gtsam::Pose2)\n", + "(-34.208649, 45.300764, 1.12050365)\n", + "\n", + "\n" + ] + } + ], + "source": [ + "# Add prior on first pose\n", + "pose0 = Pose2(-34.2086489999201, 45.3007639991120, math.pi - 2.021089)\n", + "newFactors = gtsam.NonlinearFactorGraph()\n", + "newFactors.addPriorPose2(0, pose0, priorNoise)\n", + "initial = gtsam.Values()\n", + "initial.insert(0, pose0)\n", + "print(newFactors, initial)" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Adding landmark L1\n", + "Adding landmark L6\n", + "Adding landmark L0\n", + "Adding landmark L5\n", + "Initializing at time 151\n" + ] + } + ], + "source": [ + "# set some loop variables\n", + "i = 1 # step counter\n", + "k = 0 # range measurement counter\n", + "initialized = False\n", + "lastPose = pose0\n", + "countK = 0\n", + "\n", + "initializedLandmarks = set()\n", + "\n", + "# Loop over odometry\n", + "for t, relative_pose in odometry.items():\n", + " # add odometry factor\n", + " newFactors.add(gtsam.BetweenFactorPose2(i - 1, i, relative_pose,\n", + " odoNoise))\n", + "\n", + " # predict pose and add as initial estimate\n", + " predictedPose = lastPose.compose(relative_pose)\n", + " lastPose = predictedPose\n", + " initial.insert(i, predictedPose)\n", + "\n", + " # Check if there are range factors to be added\n", + " while (k < K) and (triples[k][0] <= t):\n", + " j = triples[k][1]\n", + " landmark_key = gtsam.symbol('L', j)\n", + " _range = triples[k][2]\n", + " newFactors.add(gtsam.RangeFactor2D(\n", + " i, landmark_key, _range, rangeNoise))\n", + " if landmark_key not in initializedLandmarks:\n", + " p = rng.normal(loc=40,scale=5,size=(2,))\n", + " initial.insert(landmark_key, p)\n", + " print(f\"Adding landmark L{j}\")\n", + " initializedLandmarks.add(landmark_key)\n", + " # We also add a very loose prior on the landmark in case there is only\n", + " # one sighting, which cannot fully determine the landmark.\n", + " newFactors.add(gtsam.PriorFactorPoint2(\n", + " landmark_key, Point2(-40, 40), looseNoise))\n", + " k = k + 1\n", + " countK = countK + 1\n", + "\n", + " # Check whether to update iSAM 2\n", + " if (k > minK) and (countK > incK):\n", + " if not initialized: # Do a full optimize for first minK ranges\n", + " print(f\"Initializing at time {k}\")\n", + " batchOptimizer = gtsam.LevenbergMarquardtOptimizer(\n", + " newFactors, initial)\n", + " initial = batchOptimizer.optimize()\n", + " initialized = True\n", + "\n", + " isam.update(newFactors, initial)\n", + " result = isam.calculateEstimate()\n", + " lastPose = result.atPose2(i)\n", + " newFactors = gtsam.NonlinearFactorGraph()\n", + " initial = gtsam.Values()\n", + " countK = 0\n", + "\n", + " i += 1\n", + "\n", + "finalResult = isam.calculateEstimate()" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "5476377146882523136: [-36.82919593 26.43059833]\n", + "5476377146882523137: [-76.14891175 22.8614804 ]\n", + "5476377146882523141: [ -3.59406453 -13.50748537]\n", + "5476377146882523142: [-34.91205938 72.42462601]\n" + ] + } + ], + "source": [ + "# Print optimized landmarks:\n", + "for j in [0,1,5,6]:\n", + " landmark_key = gtsam.symbol('L', j)\n", + " p = finalResult.atPoint2(landmark_key)\n", + " print(f\"{landmark_key}: {p}\")" + ] + }, + { + "cell_type": "code", + "execution_count": 15, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "(4090, 2)\n" + ] + } + ], + "source": [ + "# plot positions\n", + "poses = gtsam.utilities.allPose2s(finalResult)\n", + "landmarks = gtsam.utilities.extractPoint2(finalResult)\n", + "positions = np.array([poses.atPose2(key).translation()\n", + " for key in poses.keys()])\n", + "print(positions.shape)" + ] + }, + { + "cell_type": "code", + "execution_count": 16, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "hovertemplate": "x=%{x}
y=%{y}", + "legendgroup": "", + "marker": { + "color": "#636efa", + "symbol": "circle" + }, + "mode": "markers", + "name": "", + "showlegend": false, + "type": "scattergl", + "x": [ + -34.20865765277028, + -34.20837627489812, + -34.20804341121378, + -34.20769819900134, + -34.20745791562606, + -34.207262384639584, + -34.20686768496456, + -34.20651586952684, + -34.206068051490725, + -34.20568191285258, + -34.20531779706161, + -34.20487525574619, + -34.20441594634689, + -34.20403934106818, + -34.20366719891563, + -34.20321548065241, + -34.20279758581938, + -34.20236982691178, + -34.20208044779656, + -34.20178452579769, + -34.201476810903344, + -34.201131364439505, + -34.20083959268987, + -34.20050783633701, + -34.20021641568552, + -34.1999036391564, + -34.19960845622661, + -34.19935481630433, + -34.1991197153355, + -34.19886207299627, + -34.19866445873396, + -34.19846692568774, + -34.19824814825021, + -34.19804389331806, + -34.19779278422965, + -34.197561076711025, + -34.19736024057739, + -34.197189125239845, + -34.1969835943833, + -34.19676091619598, + -34.196608333385896, + -34.19640233825663, + -34.196130467067924, + -34.19598494582688, + -34.19585039867902, + -34.195696091766784, + -34.195498091510714, + -34.19535353058579, + -34.19519795908968, + -34.1950071167798, + -34.194831094182135, + -34.19461985854805, + -34.19441132026083, + -34.19424822642422, + -34.194081780417626, + -34.19391357666842, + -34.193711429634185, + -34.19354560895851, + -34.19343110907236, + -34.19325256825953, + -34.19313133842211, + -34.19296665495514, + -34.192788116797225, + -34.19265451354776, + -34.192513435453314, + -34.19234391846579, + -34.19218930175465, + -34.191838323058576, + -34.19136570856127, + -34.190928229906305, + -34.190511990806826, + -34.19000761972925, + -34.18946318971993, + -34.18897791236561, + -34.18851864150678, + -34.18800608441713, + -34.18743169138802, + -34.187036933672935, + -34.18662146295106, + -34.186165007801236, + -34.185817766053745, + -34.185405809463184, + -34.18489058464781, + -34.18448357822621, + -34.18409518154167, + -34.18357571608114, + -34.18309387250541, + -34.18256248424499, + -34.181945835241166, + -34.18134727077619, + -34.18075641955187, + -34.18020608448097, + -34.17963922444816, + -34.179030908528105, + -34.17846295752322, + -34.17789438126163, + -34.17735517301769, + -34.17683902681143, + -34.17646759077013, + -34.17613625869724, + -34.17569496410317, + -34.175274199432124, + -34.174986261943396, + -34.1746536384632, + -34.17437934491031, + -34.17396057959478, + -34.17348400091052, + -34.173132109277056, + -34.172711744705396, + -34.17229359208847, + -34.171889686935685, + -34.171385951929445, + -34.17092532852038, + -34.17054598449141, + -34.17013012377779, + -34.16967802854073, + -34.16919048706976, + -34.168700394094, + -34.16835264800961, + -34.16800957980584, + -34.16756748692532, + -34.167100635865324, + -34.16670327117912, + -34.16635987105999, + -34.165916396897536, + -34.16543888597081, + -34.164981052151965, + -34.16464236988413, + -34.16438165036788, + -34.16395683830689, + -34.163500921448296, + -34.163203159566095, + -34.16283304045582, + -34.16233482182268, + -34.16201880326297, + -34.16150158543522, + -34.16117214943242, + -34.16087247015591, + -34.16069370051231, + -34.160288097838524, + -34.15986460694333, + -34.159654913244964, + -34.159330520615946, + -34.15894290784079, + -34.15854197964232, + -34.15806600534028, + -34.157651010814675, + -34.15733633819677, + -34.15688964504245, + -34.1562164494654, + -34.155904707964396, + -34.1555960279812, + -34.155176861289206, + -34.15470441225209, + -34.15431155084816, + -34.154022421184415, + -34.15379683660929, + -34.153615481685534, + -34.15320786275925, + -34.15285406634137, + -34.1526312702774, + -34.15238434289839, + -34.15197873628081, + -34.151463716790985, + -34.15075297645223, + -34.150422920229474, + -34.150106454424375, + -34.14953083643422, + -34.14865404131877, + -34.147403188210866, + -34.146541461534724, + -34.145832799117535, + -34.14480842908335, + -34.143733929260904, + -34.142752588831556, + -34.14178504499314, + -34.14080054418268, + -34.13987637403273, + -34.138956497883136, + -34.137983706253095, + -34.13707987779172, + -34.13619140755394, + -34.135239035151116, + -34.1342465874728, + -34.13332047604423, + -34.13232866206878, + -34.13133065383901, + -34.13053467472447, + -34.12989457270364, + -34.12914895123361, + -34.12828154203491, + -34.12738571557727, + -34.12655868998526, + -34.12594547630765, + -34.12524399982086, + -34.12438184847555, + -34.12359907359514, + -34.122897400403204, + -34.12237940255494, + -34.121723362493036, + -34.120850538344364, + -34.12029414700698, + -34.119673381183986, + -34.11892484075732, + -34.117959209281125, + -34.11637980957664, + -34.11539288296394, + -34.1139206718875, + -34.112529323577334, + -34.111201361189806, + -34.10715961721005, + -34.099200943828784, + -34.08528778483324, + -34.063537358389006, + -34.0330176108807, + -33.99466330117002, + -33.95228927011852, + -33.91102636757699, + -33.87648411911662, + -33.848949423962125, + -33.82880245368321, + -33.813795371332816, + -33.80302765011269, + -33.79557557067424, + -33.789009500143464, + -33.781028897828314, + -33.769330768968906, + -33.750080307764335, + -33.722410907571, + -33.685802846989034, + -33.63966975965821, + -33.58426987377947, + -33.52025064735403, + -33.44676174131417, + -33.363576136128266, + -33.26935813802871, + -33.163122367170935, + -33.04542280551315, + -32.91817693229932, + -32.78261009875481, + -32.63640547090148, + -32.47640794287209, + -32.306688975113, + -32.12775566866747, + -31.940826864370234, + -31.742477831501663, + -31.53463009871392, + -31.319720548495376, + -31.08998509855075, + -30.8540957508384, + -30.61341296572028, + -30.357335204560368, + -30.094857736558367, + -29.825185182220352, + -29.55171753116922, + -29.269164559501284, + -28.98246080248745, + -28.702613976531723, + -28.41678215375779, + -28.127357109874872, + -27.841149083706476, + -27.55633122678872, + -27.26815228010316, + -26.987175657910743, + -26.71343258961448, + -26.4438583365748, + -26.176709586931796, + -25.9175906251324, + -25.67618980468899, + -25.43181643150372, + -25.19374803478677, + -24.990787477060266, + -24.78739899338199, + -24.589083405331888, + -24.40598476077686, + -24.231696326766766, + -24.06742150344417, + -23.908247046205076, + -23.750254982784725, + -23.609050007658485, + -23.470707450260925, + -23.33088879992566, + -23.20471360256028, + -23.08279521662908, + -22.960770106964247, + -22.846398323856718, + -22.739628244678563, + -22.637878731144024, + -22.538663275812723, + -22.44413423905337, + -22.356602438124526, + -22.273226931552326, + -22.197142974973296, + -22.123574506593187, + -22.05518455320675, + -21.99415465600562, + -21.939564935384716, + -21.88550475592873, + -21.83459698486749, + -21.7858842220242, + -21.73712767832763, + -21.68528019783519, + -21.6341471189187, + -21.58451865634108, + -21.533989778555632, + -21.48224823566605, + -21.434144485609504, + -21.384718433528295, + -21.330711643441262, + -21.278102263962182, + -21.228086229019123, + -21.174898125871866, + -21.1201216471771, + -21.06835717672824, + -21.012090180196257, + -20.958190803479805, + -20.9017989297325, + -20.847027929669178, + -20.791057465910786, + -20.73374607686016, + -20.677984615004902, + -20.62054153562771, + -20.561217397664468, + -20.497570656327234, + -20.436068060400043, + -20.372574664767427, + -20.304225814998883, + -20.234036096947104, + -20.160782558230018, + -20.086083122244485, + -20.00808627936259, + -19.927156617257467, + -19.84457613832099, + -19.75900958016967, + -19.671388081969617, + -19.58207076920672, + -19.490130965447076, + -19.39417286396094, + -19.29683608347038, + -19.19548418857807, + -19.085321208130296, + -18.975105151884314, + -18.86180077327289, + -18.738236649074565, + -18.610154872731925, + -18.480393406542845, + -18.339463266757704, + -18.194233996767583, + -18.044253991578852, + -17.88604692974885, + -17.725857015409737, + -17.557590371526267, + -17.37878631399246, + -17.19776384735875, + -17.01042240300562, + -16.80999598265039, + -16.610564485432956, + -16.405565930644755, + -16.188663405589807, + -15.975014538427745, + -15.759063358341724, + -15.534507995711774, + -15.312377832471743, + -15.091463892047729, + -14.861614635491696, + -14.631523592524267, + -14.408883046579172, + -14.182184206264761, + -13.955999806789674, + -13.73228921372798, + -13.508890099247246, + -13.280310842785969, + -13.051393633045917, + -12.822749073638654, + -12.5947518203909, + -12.363772827011108, + -12.136682714475835, + -11.91104035249452, + -11.682605748870857, + -11.4584028711377, + -11.234707711039341, + -11.007860412464913, + -10.78504111279112, + -10.567121477406495, + -10.348688471478162, + -10.13583488500359, + -9.931177033479994, + -9.7022312235608, + -9.493358327175411, + -9.291263453811862, + -9.090902699597233, + -8.890794589408246, + -8.694020682483048, + -8.502326962491017, + -8.310469169971078, + -8.123326610292315, + -7.939504428022957, + -7.756233922866621, + -7.578392200121858, + -7.398413327196626, + -7.2182629267388325, + -7.041919998827723, + -6.866546197523425, + -6.690360426827359, + -6.5228069558437936, + -6.36347577941645, + -6.200987190064998, + -6.050007480928178, + -5.912232311551511, + -5.7743416728836205, + -5.646420306052364, + -5.5325949134200485, + -5.422918295268944, + -5.323892537691768, + -5.238663186195628, + -5.162665786407667, + -5.101381785082697, + -5.052723869574644, + -5.015244782305614, + -4.9919866108588895, + -4.9825583435547545, + -4.987316861859119, + -5.006256414313346, + -5.04201747568707, + -5.097422039433109, + -5.168815768125782, + -5.25713726768217, + -5.36305329576835, + -5.48888337339212, + -5.639287440052063, + -5.817416709808972, + -6.005550857156813, + -6.2073870642528455, + -6.436954242954809, + -6.674188290893242, + -6.919673867376524, + -7.197024991217148, + -7.481743967619861, + -7.7632116739282, + -8.063956446057551, + -8.375625528507998, + -8.690637452178606, + -9.013983746734263, + -9.339718894808357, + -9.665754291246362, + -9.999708490001447, + -10.331941006221287, + -10.663667670193183, + -10.998085705180765, + -11.331495899154495, + -11.662676948690304, + -11.997659662064569, + -12.326420081367713, + -12.655203291863426, + -12.98587095881301, + -13.310765222518047, + -13.634780920747755, + -13.960896670198567, + -14.284108881408201, + -14.607413513757185, + -14.932899279001981, + -15.262078111243333, + -15.591412638981694, + -15.923511099171229, + -16.258262911703923, + -16.59737276316696, + -16.94018105423836, + -17.2909484860004, + -17.655068612728492, + -18.0207371994716, + -18.38856463954403, + -18.7691510321504, + -19.149187833538363, + -19.52520105852179, + -19.91402415182552, + -20.31591058028569, + -20.70140767958901, + -21.097312765680723, + -21.512012551973932, + -21.9042354163522, + -22.31047375709063, + -22.73151624550871, + -23.133425368061893, + -23.548574543556498, + -23.974953994743817, + -24.377725107507008, + -24.788768501880945, + -25.20780217756491, + -25.596585457089272, + -25.986839797348612, + -26.403570854025947, + -26.80481618663611, + -27.19151604914389, + -27.604095502488054, + -28.013040181107904, + -28.399561120040854, + -28.806305096361402, + -29.21836060889838, + -29.612333991750894, + -30.014839001888117, + -30.42101969427448, + -30.812849563600615, + -31.20975150080373, + -31.607386345888898, + -32.001140911476554, + -32.398511738416815, + -32.795673562184895, + -33.19043549084416, + -33.591818893107636, + -33.99170159046605, + -34.395001772313535, + -34.8007159742122, + -35.21246146096016, + -35.62157246081787, + -36.03028500254523, + -36.43892827784079, + -36.84281499403664, + -37.23936120912264, + -37.6357100863053, + -38.03227527745555, + -38.43341536444668, + -38.842734157084585, + -39.25935801324063, + -39.676612237452915, + -40.09331920677003, + -40.50845440957805, + -40.921070304427836, + -41.34229428167896, + -41.7668309225472, + -42.18790223607136, + -42.59759140395779, + -43.00343010658945, + -43.41118345011088, + -43.818104387761196, + -44.226856572447986, + -44.63207297851732, + -45.04105873294049, + -45.452137717302335, + -45.848582357761366, + -46.246420071019344, + -46.656200074653064, + -47.056121644452084, + -47.45516448410812, + -47.86059878098149, + -48.26812764507053, + -48.66813762511848, + -49.06550271312794, + -49.462743587503844, + -49.85160033511153, + -50.236067455967294, + -50.63236592602849, + -51.0230252239154, + -51.402841949384964, + -51.79340413782777, + -52.1793847503508, + -52.54627719981708, + -52.92818013165972, + -53.30531632375098, + -53.67051783551845, + -54.051273229532896, + -54.432923306503874, + -54.797667966942946, + -55.17853015764748, + -55.55729922853328, + -55.92182316112514, + -56.30369922294296, + -56.68044305487901, + -57.041036489211216, + -57.41233647793287, + -57.7706682135264, + -58.127233440631706, + -58.4924456555522, + -58.852217044817216, + -59.20945677748908, + -59.56867753427188, + -59.92014152015811, + -60.270052574470235, + -60.631476885203405, + -60.98028694706533, + -61.33516553788088, + -61.689908810375684, + -62.02306126130879, + -62.35798184038503, + -62.69004704965884, + -62.99241843758069, + -63.300429779674246, + -63.6044627683144, + -63.883826499514534, + -64.15754939083865, + -64.42281867173546, + -64.67275723743165, + -64.90508952457635, + -65.12955525690963, + -65.34213047273701, + -65.54035548783273, + -65.72858304977794, + -65.90175985054115, + -66.06830228723238, + -66.22920044003294, + -66.37684053648285, + -66.5147227022707, + -66.64282244339906, + -66.76334412013065, + -66.87755657410239, + -66.98131503045009, + -67.08105425508822, + -67.17957589698175, + -67.26732669092793, + -67.34696553722583, + -67.42086056045576, + -67.48424165958828, + -67.53977030995661, + -67.58892626747567, + -67.62521470008504, + -67.6495189664005, + -67.66748200634846, + -67.67350495619027, + -67.66310281912445, + -67.63681921992985, + -67.59625719827237, + -67.54390581011167, + -67.47791181357339, + -67.39699369051641, + -67.30124835953411, + -67.18999145508437, + -67.06654777360508, + -66.93275642679862, + -66.7870188333484, + -66.63200535676094, + -66.46921861044694, + -66.29260496988596, + -66.10287213961468, + -65.90578769689013, + -65.70338794784624, + -65.48873574040499, + -65.26757863662448, + -65.05711231214029, + -64.83312390224027, + -64.59441784791593, + -64.37011538587512, + -64.14028001725154, + -63.885524179488435, + -63.641244695497605, + -63.3985459897878, + -63.13394209674045, + -62.87644812985557, + -62.62080580414671, + -62.352721230763194, + -62.089715954521054, + -61.83156654673461, + -61.56893223476824, + -61.310292262630064, + -61.054001022681945, + -60.79466881062043, + -60.533762342770004, + -60.27561420364428, + -60.01727189473518, + -59.76324569629319, + -59.511562431911166, + -59.26429214368505, + -59.01350129596539, + -58.76796019139932, + -58.52106867458063, + -58.272875656176666, + -58.02981520878215, + -57.79409549812396, + -57.550958925549175, + -57.324053662051085, + -57.1047014444447, + -56.87444734156775, + -56.65463950696342, + -56.433119865646276, + -56.201243660638085, + -55.97842127648121, + -55.75555379279634, + -55.503766595057634, + -55.280159034461285, + -55.059498820467, + -54.83036613495392, + -54.595453683291524, + -54.36695449025803, + -54.13681195180934, + -53.89960604756126, + -53.66668449453342, + -53.43921231795147, + -53.2050036097736, + -52.96975591697278, + -52.738378298576784, + -52.50058143730088, + -52.26149106162401, + -52.03035347222737, + -51.797685452499195, + -51.566514662511324, + -51.344339918580104, + -51.11699128329711, + -50.89267816639776, + -50.66994217142387, + -50.44150315843499, + -50.2078232899057, + -49.968287475176126, + -49.72991752485483, + -49.48660386162624, + -49.232905254156954, + -48.97354091627121, + -48.71138241606341, + -48.447217300053985, + -48.18043385266988, + -47.91202142850183, + -47.64473404164936, + -47.38565772901833, + -47.128686329031105, + -46.86718251551342, + -46.60861341694757, + -46.35334698823539, + -46.092455573640706, + -45.82910723039233, + -45.56767442415841, + -45.30781123187224, + -45.04927088820327, + -44.77723833877998, + -44.511498656988465, + -44.254477628267395, + -43.98023839839559, + -43.706126594039254, + -43.45476071311876, + -43.18497471956452, + -42.901799613816934, + -42.636584261112105, + -42.36457612373446, + -42.071178953831904, + -41.78871608839509, + -41.52471671017607, + -41.23353784019416, + -40.932875163883075, + -40.64906532262748, + -40.34279881141663, + -40.023969009031084, + -39.715363572293434, + -39.393132970570335, + -39.07022363376905, + -38.748440288186494, + -38.419963820390116, + -38.08605157788975, + -37.75877465535211, + -37.421029182409036, + -37.087867531694336, + -36.765705079761084, + -36.42426520040904, + -36.07874871115632, + -35.74587992277794, + -35.40834356887657, + -35.06710994573955, + -34.73199222388137, + -34.40664678937468, + -34.07699779100251, + -33.76136244895746, + -33.46016948598249, + -33.15648449712948, + -32.85592076987152, + -32.57466832758714, + -32.292490123671044, + -32.01020800140973, + -31.741604353620243, + -31.469942663967327, + -31.20847515829357, + -30.956116870204347, + -30.705778329254887, + -30.466686800437184, + -30.23671593374634, + -30.015966086982132, + -29.80404929245738, + -29.60284763420318, + -29.41091369748634, + -29.22475934111039, + -29.047339831863482, + -28.876763478737516, + -28.71320960128329, + -28.558254442726433, + -28.40833616544292, + -28.263854515016146, + -28.12471881580457, + -27.98791269481932, + -27.854024781435854, + -27.727141563221338, + -27.599430483592645, + -27.4711775043917, + -27.35152567991133, + -27.229861756103972, + -27.105764113868315, + -26.985615083763363, + -26.870097430871592, + -26.75168988415617, + -26.63282706372104, + -26.518590899920646, + -26.40292360487485, + -26.286826704518603, + -26.174016289968826, + -26.05961812669295, + -25.944797560137037, + -25.83104325707594, + -25.717249115805537, + -25.599840375010448, + -25.481528577202834, + -25.36496648818335, + -25.24501449406681, + -25.124890260714952, + -25.006158782308173, + -24.886944194957987, + -24.767729947132178, + -24.650078324754315, + -24.530190556934365, + -24.413659275357002, + -24.295336833298865, + -24.17445381450801, + -24.05542934494462, + -23.934421841950442, + -23.812780868032956, + -23.693483309785638, + -23.574794738836673, + -23.456171584759993, + -23.339965689277857, + -23.225990425140644, + -23.111106122208927, + -23.00155994453248, + -22.89556935154261, + -22.789439606384583, + -22.686707513840453, + -22.59111141043223, + -22.497742028538134, + -22.409379353553174, + -22.323477397674704, + -22.239658370541928, + -22.164170884769486, + -22.0918536833376, + -22.020727933566217, + -21.952044764584247, + -21.888064655657626, + -21.821762101566964, + -21.75197916838357, + -21.68501071438019, + -21.619063616663286, + -21.553166711357957, + -21.48504583721297, + -21.420525815700625, + -21.356303702746956, + -21.28685939394922, + -21.218415115716088, + -21.151822514907103, + -21.087634191426336, + -21.02437443552054, + -20.962096986706154, + -20.900119053190263, + -20.838125089802865, + -20.777815917118446, + -20.718057691702477, + -20.660129583277982, + -20.60288567452934, + -20.543722503545894, + -20.487238613238645, + -20.43007415739744, + -20.37141205325075, + -20.3128528281756, + -20.258073694657217, + -20.203510494966917, + -20.14647122632617, + -20.082973993621103, + -20.024612713225867, + -19.963387326162582, + -19.897915978102425, + -19.829622262869968, + -19.757922655086105, + -19.682344784712182, + -19.60327070377297, + -19.52166863863207, + -19.433802043497366, + -19.34062902699642, + -19.2430030185819, + -19.14051075814092, + -19.029890647416014, + -18.913328003639542, + -18.796706146225763, + -18.674022770807362, + -18.54471855578794, + -18.41558776231358, + -18.281870638283987, + -18.13901454597218, + -17.998066271991835, + -17.856675336109355, + -17.703753252988538, + -17.551270708037396, + -17.400445276210593, + -17.237442053139276, + -17.073643356971125, + -16.913527814019, + -16.74041603453929, + -16.565332628964775, + -16.400213935532765, + -16.207552236682343, + -16.021819420661284, + -15.84699159823023, + -15.667092161135956, + -15.472862269674522, + -15.285584644868019, + -15.096443074120153, + -14.898381387044548, + -14.702442507468776, + -14.50569646553477, + -14.304213243436743, + -14.101884043077925, + -13.89790007157055, + -13.6925179574355, + -13.487772380728252, + -13.278775065666851, + -13.066927240203983, + -12.85544049886375, + -12.641558360879957, + -12.425720748674701, + -12.209913136668696, + -12.000315021602171, + -11.78457517923467, + -11.570082369561755, + -11.358789654589712, + -11.142454059079778, + -10.927120137433844, + -10.712321075149939, + -10.498084417658669, + -10.284525097788132, + -10.075458410060298, + -9.867457346567777, + -9.658123727625295, + -9.449737686444529, + -9.24419233451893, + -9.039731972618624, + -8.835429992753749, + -8.63443954140641, + -8.43716601147788, + -8.239300304776066, + -8.047246647206697, + -7.861151680568275, + -7.677379012068177, + -7.495564985735251, + -7.3175797799355005, + -7.145247668396517, + -6.971100946005515, + -6.79818711501, + -6.623724463640425, + -6.452319125855208, + -6.2834299550182875, + -6.092329402049868, + -5.919343678281793, + -5.7553176678986295, + -5.5937185390268285, + -5.43252603328783, + -5.276230407073092, + -5.130505296363279, + -4.98964925773899, + -4.854131605454319, + -4.729948581233919, + -4.611616391338887, + -4.503037179655838, + -4.412044415619663, + -4.3271521731974705, + -4.249017111637989, + -4.185941179324683, + -4.134477041885564, + -4.092668897513787, + -4.063360782544444, + -4.046259142699124, + -4.041987399667728, + -4.051165990521669, + -4.073942925994559, + -4.110904863075316, + -4.162155800894148, + -4.229589187754156, + -4.311708575703241, + -4.408036906953321, + -4.518048653510903, + -4.645305455200856, + -4.797822423005665, + -4.964389803278236, + -5.142189574296227, + -5.3496404030185865, + -5.573421464205477, + -5.8042203754495025, + -6.056196937945198, + -6.3238885381876, + -6.596875542862387, + -6.889274784715866, + -7.191884297538913, + -7.4937589053751275, + -7.810973156955758, + -8.136824574834591, + -8.456284840556274, + -8.7803609463077, + -9.110558869488141, + -9.42884479504251, + -9.754570350900178, + -10.08489775246689, + -10.401053313764542, + -10.720085558570752, + -11.040959627890507, + -11.348055976571189, + -11.654843661604891, + -11.961467456921028, + -12.26110491752206, + -12.557122158412735, + -12.853110392915866, + -13.147070394263933, + -13.437303080943583, + -13.728441347763876, + -14.0200730857591, + -14.312458451202858, + -14.608030522885487, + -14.906012356330399, + -15.210220122427952, + -15.515335418884517, + -15.82269192168044, + -16.133865703043043, + -16.44536785719234, + -16.759637217915845, + -17.0773552923272, + -17.396324436625346, + -17.720947525509334, + -18.045811567461666, + -18.36833981094028, + -18.70341705933958, + -19.034431574137617, + -19.36440746612907, + -19.69380241432439, + -20.03834957779887, + -20.381633972572452, + -20.710868759344486, + -21.061224770465973, + -21.41481077775693, + -21.751772958151705, + -22.100085007084378, + -22.464598463301268, + -22.813701792291237, + -23.16655013515301, + -23.535642575259036, + -23.891293926911082, + -24.243458057965356, + -24.608870430459667, + -24.969477256203113, + -25.322978156143186, + -25.681319764813868, + -26.046168505850687, + -26.406209755560276, + -26.764979695950537, + -27.126126577743964, + -27.492197609902387, + -27.851708092325026, + -28.211751823870774, + -28.582144695012385, + -28.949830327619164, + -29.312297244894527, + -29.680971094527823, + -30.05658799726269, + -30.42076889669658, + -30.782121693656595, + -31.151937148506285, + -31.50868387365998, + -31.864770361874942, + -32.22472307222192, + -32.579652484711154, + -32.935901065223995, + -33.29114491063867, + -33.640503436774694, + -33.994216855514225, + -34.35321090838215, + -34.70674728111639, + -35.06249478488046, + -35.421161482096394, + -35.77562375872252, + -36.12974053530249, + -36.486515097977424, + -36.8370658726633, + -37.18068676390196, + -37.53142686680611, + -37.872407846824466, + -38.21643646462669, + -38.569893577771786, + -38.924134497406854, + -39.27836194064444, + -39.6457889908704, + -40.01213107413774, + -40.371512898998496, + -40.735175913412974, + -41.103419692920994, + -41.46152909375386, + -41.82291452907854, + -42.18912045641845, + -42.543963530852125, + -42.89219062707086, + -43.24495670516598, + -43.596896295463736, + -43.94121527772567, + -44.295846063177855, + -44.65139743521477, + -44.999648750108186, + -45.35302240608575, + -45.70714106778485, + -46.04816524916467, + -46.39334279322935, + -46.74265592846308, + -47.087629640850004, + -47.42769461755935, + -47.7719132994987, + -48.11683068133768, + -48.45966445230252, + -48.79888708358816, + -49.139283764720005, + -49.481140565990195, + -49.820486761193955, + -50.157087057923746, + -50.49979109401643, + -50.84745899871575, + -51.18736165268032, + -51.52598826062575, + -51.87104199378865, + -52.21195432076135, + -52.53979326355826, + -52.87643566540903, + -53.214515952253265, + -53.54183693038462, + -53.87473864666174, + -54.214336495193294, + -54.54753707147511, + -54.877573466675855, + -55.21828555021866, + -55.55193018142669, + -55.87701746527285, + -56.214779429937714, + -56.552187979127204, + -56.87605564387785, + -57.20468550384501, + -57.53744766585467, + -57.85808955993053, + -58.181214786661464, + -58.50953441606787, + -58.82957961496041, + -59.14822813829285, + -59.469528783707865, + -59.78602746488803, + -60.094818935602525, + -60.40350912456221, + -60.71625486364919, + -61.023813147028875, + -61.33148151388015, + -61.64680711051246, + -61.95282404511547, + -62.24773425030408, + -62.549122581110055, + -62.8488991713276, + -63.13099518064569, + -63.41094680154312, + -63.69120627991752, + -63.95643549358305, + -64.21247184750521, + -64.47027285329462, + -64.70957452410602, + -64.94398146032917, + -65.17056064808759, + -65.37618318321724, + -65.57638368642908, + -65.76356719574198, + -65.94007956259367, + -66.11979176972015, + -66.28099245704996, + -66.43312909088498, + -66.59094718720128, + -66.74154073512811, + -66.88413745934777, + -67.02239669463482, + -67.15165902341101, + -67.27978847903408, + -67.40427857430315, + -67.52146269219321, + -67.62924162797573, + -67.73714594390412, + -67.83706817775604, + -67.92215303249631, + -67.99806012379929, + -68.06352660700529, + -68.114528246376, + -68.15650009436126, + -68.18561812245795, + -68.2009157524861, + -68.20975108721088, + -68.21089135487408, + -68.19887332851475, + -68.17239258964494, + -68.13456534354545, + -68.08697910663294, + -68.02953461515013, + -67.96137592236013, + -67.88159070510437, + -67.78414929393003, + -67.6751948052676, + -67.55503541456446, + -67.42371365758812, + -67.28068940289505, + -67.12671078192913, + -66.97141841057255, + -66.80741063558389, + -66.63820417250463, + -66.46100290687446, + -66.27891622921368, + -66.09586409399127, + -65.9043404136652, + -65.71378359831859, + -65.5213950468977, + -65.32249297762922, + -65.11904406686214, + -64.91990933948763, + -64.7129140460563, + -64.50153698206827, + -64.29670270151745, + -64.08743684046358, + -63.87138264015154, + -63.653867546403404, + -63.43370662687731, + -63.20738863236294, + -62.98017210553031, + -62.750438214939905, + -62.51765901233964, + -62.2861672750576, + -62.04696108955838, + -61.8031091077138, + -61.56043092051491, + -61.31142073302581, + -61.05747383135898, + -60.803977918221925, + -60.54889253417473, + -60.29118333843693, + -60.03715104565685, + -59.78084579626353, + -59.52867865538103, + -59.27630899666948, + -59.01770696294031, + -58.76201321053243, + -58.51178548751056, + -58.25464965577174, + -58.004382435736005, + -57.76346431473836, + -57.51193708359743, + -57.26996822146708, + -57.03189888319683, + -56.78509754948844, + -56.54587294641515, + -56.30881746048974, + -56.06256540458002, + -55.82369926153637, + -55.595726809168, + -55.35184090645175, + -55.10661727517301, + -54.872596990014024, + -54.62613911727918, + -54.37486906368861, + -54.13633923490666, + -53.8914630572816, + -53.6410196432496, + -53.3980215009388, + -53.149782734602475, + -52.89496150840424, + -52.651615152303215, + -52.41126251219881, + -52.170185606678025, + -51.93622701981825, + -51.705446999793345, + -51.47966887694434, + -51.24973403092119, + -51.02004229414803, + -50.78523161316766, + -50.54848733851053, + -50.31518575293781, + -50.07665072401502, + -49.83009771395729, + -49.5828132161494, + -49.33715365801616, + -49.082157337157234, + -48.83193333014188, + -48.58873290677186, + -48.34144416320349, + -48.10360173323675, + -47.87009470992484, + -47.622514706473574, + -47.363966739705205, + -47.12013795521646, + -46.87257049162197, + -46.61062913375097, + -46.35200814212822, + -46.097583433824305, + -45.83687587139437, + -45.563170967350636, + -45.29591709740525, + -45.037523455519576, + -44.77131210219301, + -44.49284996858265, + -44.23091373251442, + -43.964006574815805, + -43.672839750953095, + -43.38599077479786, + -43.110946250191546, + -42.816501303423415, + -42.51417479511037, + -42.23818749026477, + -41.9574496142742, + -41.650858897770384, + -41.3528863546484, + -41.05379292343766, + -40.72557625370128, + -40.39969781586623, + -40.07113987252099, + -39.728536258790534, + -39.38724721786888, + -39.04220905850102, + -38.68599662597201, + -38.33535987726679, + -37.974115925958536, + -37.61024733531228, + -37.25587461258331, + -36.88864640813949, + -36.51849771971568, + -36.15724795826422, + -35.79554363469556, + -35.42964631157209, + -35.08112319361428, + -34.73884994084711, + -34.392755894705495, + -34.074077979693655, + -33.76393325300418, + -33.442883513001235, + -33.1489629236288, + -32.85990276701371, + -32.56837015476392, + -32.294684172890086, + -32.028774898971186, + -31.75718767402392, + -31.495730807416944, + -31.24791565919711, + -31.00121962124004, + -30.759627234807496, + -30.530664629688705, + -30.310852079543675, + -30.09607289768241, + -29.883862359017467, + -29.677880790471516, + -29.480891444958747, + -29.289993440013557, + -29.10261107047686, + -28.92364991150457, + -28.748139666612893, + -28.573226178117782, + -28.40592874609806, + -28.245276083201215, + -28.082977954940496, + -27.931234064689665, + -27.789710518065313, + -27.644616675377932, + -27.506947402047835, + -27.378522436375814, + -27.245882670417625, + -27.11663794071789, + -26.99300541098765, + -26.86722145658784, + -26.742737620858613, + -26.620127305638263, + -26.495194364643197, + -26.369159116174483, + -26.245335215615878, + -26.115857229254324, + -25.98389129610689, + -25.85370763143319, + -25.717637410421045, + -25.582103450486787, + -25.44680215508687, + -25.30825672214228, + -25.168758099994903, + -25.029521586542533, + -24.893230068326957, + -24.752276262732824, + -24.610893805664148, + -24.471651749104904, + -24.331871781410168, + -24.194466328335597, + -24.057916487969454, + -23.925633212669805, + -23.796289157373838, + -23.668940136514355, + -23.531217314779276, + -23.415495706932536, + -23.301692937313973, + -23.190532314594886, + -23.0870812858565, + -22.98828267493393, + -22.895022149441242, + -22.80659696819355, + -22.722293959750044, + -22.6447131143414, + -22.572189884252822, + -22.499300442670005, + -22.42756830472304, + -22.35967804104907, + -22.28575079230414, + -22.209094019249193, + -22.136547437571625, + -22.063304942142754, + -21.984911102927903, + -21.910468924042853, + -21.834243310557962, + -21.750318264668973, + -21.669245972574057, + -21.59321120154545, + -21.515850918555735, + -21.44011386348618, + -21.366266375229404, + -21.290963462074345, + -21.21501499338668, + -21.14235551246563, + -21.072393903507383, + -21.002448463060183, + -20.93182383747362, + -20.865088656369338, + -20.797770586972558, + -20.72998308241188, + -20.6655264338563, + -20.602766499874217, + -20.53845797512729, + -20.47269378482167, + -20.40544985601269, + -20.335254295360638, + -20.260348601716093, + -20.18245196414492, + -20.09956836404846, + -20.01167021052066, + -19.921454109351217, + -19.824992540687557, + -19.721312578357868, + -19.611836768816712, + -19.494748073623743, + -19.36847981299224, + -19.236203231070814, + -19.101819824012058, + -18.95885288915273, + -18.811931958697485, + -18.66121378735747, + -18.497255021956903, + -18.330527538292355, + -18.160174752164238, + -17.980221273569583, + -17.797022578069004, + -17.610027628843415, + -17.4166767583467, + -17.22516942646293, + -17.02880138213018, + -16.824918570644137, + -16.632689144140926, + -16.434556785191827, + -16.222013833958925, + -16.022114363750095, + -15.821539263401311, + -15.606529188295276, + -15.395644280380646, + -15.187167820010343, + -14.966706975796223, + -14.754468490541361, + -14.558943657146083, + -14.356619727420545, + -14.154401602462695, + -13.956618199868508, + -13.752031676596259, + -13.543654641602096, + -13.338672335098378, + -13.128921204221147, + -12.919115743911556, + -12.705119718601106, + -12.487170768127378, + -12.26869919382645, + -12.051085271849994, + -11.837548192783965, + -11.623348978756004, + -11.409444851129606, + -11.197392062057354, + -10.988675819087593, + -10.779523375280213, + -10.573066747040784, + -10.367401132602206, + -10.160219747027968, + -9.952428517322884, + -9.747949968604173, + -9.54854295388597, + -9.348898020945425, + -9.153006389797316, + -8.963902231676316, + -8.77758035848527, + -8.595694620894326, + -8.420927563968194, + -8.249744821381304, + -8.081435122747934, + -7.917227007839054, + -7.75070768175025, + -7.586101597221615, + -7.429471770624002, + -7.257298823333568, + -7.104645340776128, + -6.961988780756195, + -6.823759126985268, + -6.687554489360367, + -6.558984384204702, + -6.436291091041718, + -6.312319001932537, + -6.194234905523938, + -6.080969034550201, + -5.967389673532327, + -5.860152286876645, + -5.757794801920761, + -5.6566256628771105, + -5.5658816046674975, + -5.480967770476624, + -5.402178448446612, + -5.335477512080547, + -5.277246076256775, + -5.224878962971179, + -5.182095094719288, + -5.1480953224626065, + -5.123399800086929, + -5.1092777228028465, + -5.104623772748024, + -5.110473145305642, + -5.128940831361704, + -5.161308524207603, + -5.207978306248866, + -5.271269279630029, + -5.346436629042738, + -5.435858600197381, + -5.553335213973659, + -5.684702745226146, + -5.820986069841115, + -5.9746325807390726, + -6.143048938440841, + -6.3218157059790085, + -6.5166538008814605, + -6.727708238719462, + -6.952184410523694, + -7.1909903104453585, + -7.436789430370237, + -7.687500259759616, + -7.9524992732315605, + -8.223955056709887, + -8.498474529811658, + -8.779791223014795, + -9.063252158535997, + -9.372851306698582, + -9.655230219915316, + -9.941506797101145, + -10.225248573353394, + -10.510183968052262, + -10.798768470577533, + -11.084219929884725, + -11.366391943635408, + -11.64959740145844, + -11.928728574571482, + -12.204968161319659, + -12.48090091055975, + -12.75095056671446, + -13.021256515708794, + -13.29636794736704, + -13.567311910690004, + -13.836496873775022, + -14.137436435484469, + -14.411588121872944, + -14.68773255696378, + -14.964013442657567, + -15.240893854913917, + -15.524812012198275, + -15.806282843594758, + -16.088855804412653, + -16.372990571411755, + -16.656715028205927, + -16.948151284131853, + -17.23475908098609, + -17.52405663008479, + -17.821883353352185, + -18.121189083950064, + -18.41457088965136, + -18.7148194283729, + -19.026102464069908, + -19.328581621335758, + -19.637655645853506, + -19.945124335975077, + -20.26227926121529, + -20.587336292560085, + -20.900471973383766, + -21.226886665001466, + -21.56387694747123, + -21.886930643083467, + -22.213782123596182, + -22.55831464687727, + -22.89575416147447, + -23.228296525995525, + -23.578172729600727, + -23.926253247141, + -24.262883026618272, + -24.608882580870766, + -24.992990337304413, + -25.336305299619195, + -25.67942762458503, + -26.02680259945706, + -26.376704909776212, + -26.726666085992726, + -27.074155712129674, + -27.425144936953824, + -27.777110294896342, + -28.128832260266027, + -28.483461804743925, + -28.83945419796568, + -29.197218210322102, + -29.552337395623532, + -29.909835414663057, + -30.263854645961224, + -30.60967243773454, + -30.954746942543842, + -31.30201385584006, + -31.63774173984617, + -31.969276168312284, + -32.309309106966765, + -32.642245420753675, + -32.972022339707046, + -33.305788693989506, + -33.63564342091818, + -33.96360760857367, + -34.292073191653394, + -34.62598433989233, + -34.962465594101225, + -35.28954879153012, + -35.620472907491894, + -35.95672505845251, + -36.28662776203072, + -36.61684557626144, + -36.94621608685265, + -37.26264009973386, + -37.5848620116347, + -37.912084105920485, + -38.22899574176612, + -38.54863505093228, + -38.876444820099465, + -39.20148309022963, + -39.53024159490634, + -39.86651468191604, + -40.20100707177658, + -40.53697160106745, + -40.873887355024635, + -41.21719227675245, + -41.55652242450899, + -41.8924203416051, + -42.23467152791791, + -42.576482252679774, + -42.91109477083226, + -43.24478267401926, + -43.58334279588164, + -43.918646507047164, + -44.253732344290206, + -44.59623954768933, + -44.931913342596864, + -45.264530411590634, + -45.60672172161301, + -45.93795884515952, + -46.269604154834155, + -46.60417550888577, + -46.937858867469686, + -47.26982522955466, + -47.604587474154975, + -47.93592217464142, + -48.26934745159304, + -48.60110561346804, + -48.927175086197344, + -49.254066155153744, + -49.58174814088134, + -49.90660632808245, + -50.23107637867807, + -50.55979378643404, + -50.8917436987979, + -51.220535168451576, + -51.54802249736267, + -51.88062667178284, + -52.209848333029576, + -52.52585866614077, + -52.85119930087964, + -53.18073104114711, + -53.497825215480745, + -53.8227351141769, + -54.15562371428327, + -54.48261674566701, + -54.807288282782686, + -55.14394557857862, + -55.47720722795808, + -55.802191537433224, + -56.14052579619243, + -56.48108908827178, + -56.80918375914819, + -57.14268988422175, + -57.481302985557654, + -57.80399448281153, + -58.13078835801433, + -58.46339988064208, + -58.78884783372682, + -59.11245654910816, + -59.439789331047535, + -59.762743142086926, + -60.07821734342035, + -60.398111042322675, + -60.72434750977929, + -61.04233945739224, + -61.36359753907159, + -61.68552558685144, + -61.98808980267596, + -62.282386413723565, + -62.57122499658275, + -62.85195535224514, + -63.11158079739945, + -63.37237553395694, + -63.63073778922422, + -63.86947022195167, + -64.10925160331492, + -64.34227018456264, + -64.58975127476415, + -64.84543292147062, + -65.08953167538627, + -65.32689911596297, + -65.55733278643139, + -65.77576745875913, + -65.9828568816992, + -66.19225016045954, + -66.3784069843528, + -66.55509949135688, + -66.72186708157075, + -66.86576820382932, + -67.00359969640152, + -67.13642299608212, + -67.25424145811719, + -67.36443358983367, + -67.4697226570013, + -67.55978956201018, + -67.64567135683917, + -67.72916804724449, + -67.79950758673753, + -67.86298358088574, + -67.92219323199015, + -67.972564353899, + -68.01546367063806, + -68.0483974563218, + -68.07040099147785, + -68.08694600942935, + -68.09227031170168, + -68.08075148928833, + -68.05406241329986, + -68.01507570773059, + -67.9664007507879, + -67.90563960681862, + -67.8306438124575, + -67.74177114521864, + -67.63714548533596, + -67.51833295742998, + -67.38874916724625, + -67.24414827629755, + -67.08925912006195, + -66.92560443261574, + -66.75129426201148, + -66.56845577371764, + -66.37778221580734, + -66.17933406941548, + -65.98165946768908, + -65.77904936626595, + -65.56587408067271, + -65.35869392971273, + -65.14959040323969, + -64.92564088737147, + -64.7021476023911, + -64.486095611291, + -64.25295320970861, + -64.01491726958696, + -63.781731700888784, + -63.5409703381668, + -63.28966232614324, + -63.040647788425986, + -62.786962882446886, + -62.52906628303248, + -62.270404792074196, + -62.00692433215578, + -61.74392054616378, + -61.48086048949135, + -61.21250030309478, + -60.94493203647749, + -60.675778946238204, + -60.40437112105071, + -60.1359398044163, + -59.86973634363778, + -59.60021628437911, + -59.33649919844747, + -59.07279114579643, + -58.803107391701985, + -58.54002453020873, + -58.27551531030626, + -58.00572503235222, + -57.74491252097591, + -57.489160350947245, + -57.22613914309932, + -56.97591832788377, + -56.72645975449218, + -56.47386327130982, + -56.22808593385795, + -55.97972758749454, + -55.730354780346225, + -55.48381021687825, + -55.2339933656851, + -54.982163745908096, + -54.74174274868021, + -54.49321718320209, + -54.23834495425245, + -53.99027603454085, + -53.74126329606611, + -53.48407611729288, + -53.234923278913726, + -52.98456172921275, + -52.725766341738286, + -52.46788834710454, + -52.20472972418036, + -51.93819474180007, + -51.67897511484283, + -51.42269666285617, + -51.170692926057846, + -50.923571578648364, + -50.678671852851, + -50.43522112770682, + -50.19153346488385, + -49.93976843551103, + -49.65589603820561, + -49.401811215996666, + -49.143388944656174, + -48.87482302295215, + -48.604484417935886, + -48.33268771624553, + -48.059951800034234, + -47.78568525052522, + -47.51418406991346, + -47.2569113045454, + -47.01017901277052, + -46.76622422855464, + -46.52334558082118, + -46.282048930713934, + -46.03839213126161, + -45.798901053291104, + -45.533075268345726, + -45.28878449528761, + -45.04381906917227, + -44.79269558835044, + -44.531454907327145, + -44.26425464129381, + -44.008788626376884, + -43.753970264792265, + -43.485370298172, + -43.22283533452984, + -42.97348931885159, + -42.70806880953647, + -42.43618369747359, + -42.18888948457328, + -41.939429867018475, + -41.68074324909305, + -41.4255371376996, + -41.16943682462024, + -40.91186907428929, + -40.63815205152, + -40.36003941417462, + -40.07929954669712, + -39.777130073828076, + -39.4570397235451, + -39.13133218251017, + -38.796400427182945, + -38.45948939543574, + -38.115930418119866, + -37.76778565215383, + -37.42206673784064, + -37.06586211795496, + -36.70302579198616, + -36.34792122705641, + -36.03288476294385, + -35.715466802372134, + -35.39327975906087, + -35.075994858784874, + -34.76924621846017, + -34.45205543597953, + -34.148596864654486, + -33.85900809784277, + -33.571580209405624, + -33.281189508290616, + -32.977806838871054, + -32.68122437592948, + -32.3888342647305, + -32.09676660137176, + -31.80632160802792, + -31.52300481168706, + -31.242152314284507, + -30.963346085348668, + -30.691619348407944, + -30.43308620677529, + -30.181230178828628, + -29.930258250525448, + -29.696866478426877, + -29.466847155523265, + -29.239021472583524, + -29.026972166393996, + -28.8237212903129, + -28.621783519943893, + -28.430025531873827, + -28.241866155491973, + -28.054040986262187, + -27.87805176584032, + -27.71021418685295, + -27.539630087736835, + -27.38435680389206, + -27.238892152319405, + -27.08854595439461, + -26.949023332399104, + -26.819225982448028, + -26.682917859090434, + -26.553996079709922, + -26.43164188604073, + -26.30849850592943, + -26.188262287617565, + -26.071176684234214, + -25.95478467593371, + -25.837889211639578, + -25.72565769787192, + -25.6090831455678, + -25.490410760347128, + -25.37187922714603, + -25.25206312999524, + -25.13016530438501, + -25.01009609733855, + -24.8901393943063, + -24.768264223957846, + -24.649552360534514, + -24.529791348565993, + -24.413770288028577, + -24.29357489215293, + -24.17349303794771, + -24.052755247857867, + -23.930564720279055, + -23.809504119812164, + -23.686770507825614, + -23.564303171892195, + -23.442569023961706, + -23.31896576490457, + -23.195598344294645, + -23.07283876649093, + -22.95546625900003, + -22.837554086804055, + -22.722128948949262, + -22.614458107091732, + -22.509820671686885, + -22.410057757095156, + -22.31501803622426, + -22.223569954326916, + -22.138705934772016, + -22.060499210689603, + -21.98384617338542, + -21.908987118375066, + -21.84094153906116, + -21.773424875212275, + -21.701184821441792, + -21.634376703258035, + -21.572484487211174, + -21.5102184136449, + -21.448783042602518, + -21.391561448655736, + -21.3328649170468, + -21.270370983152183, + -21.209024595385703, + -21.148813876046027, + -21.088742584854412, + -21.02744902242941, + -20.964939838097717, + -20.900941901509675, + -20.834707327201077, + -20.76697246412593, + -20.699587458716117, + -20.631934031270504, + -20.559767564483245, + -20.489113801015886, + -20.417698881190578, + -20.344878252095764, + -20.271170893347175, + -20.200973242386176, + -20.132304868802283, + -20.062492769684184, + -19.99404634108976, + -19.924140110056346, + -19.853287205483973, + -19.78095801332462, + -19.707443533284177, + -19.63156149244821, + -19.55245929739752, + -19.47473788950867, + -19.392121425032574, + -19.304250094265583, + -19.216207428785335, + -19.123857039560107, + -19.02650636545839, + -18.922544716211487, + -18.812494535573286, + -18.699170972107435, + -18.58244379245635, + -18.45859968595741, + -18.329501197930224, + -18.193895725187208, + -18.05200564627889, + -17.903262512236594, + -17.747543578216767, + -17.590668064165165, + -17.42615017423268, + -17.25835424182736, + -17.09114063677347, + -16.918762199579422, + -16.736777954421882, + -16.563218495980028, + -16.389427875316613, + -16.197349502565203, + -16.014235854213386, + -15.836343589404848, + -15.644512083276659, + -15.456104541958904, + -15.272143446768258, + -15.083122322955424, + -14.894441617632763, + -14.711319486896373, + -14.52746141925098, + -14.3417640965953, + -14.157278726508983, + -13.967285526208965, + -13.775288452181831, + -13.579680168693109, + -13.38107443699138, + -13.178964650780102, + -12.977252444787776, + -12.771699419863873, + -12.563938401381387, + -12.355934021140786, + -12.142629356441429, + -11.93113366350645, + -11.717669643847204, + -11.501052307978233, + -11.284555626151555, + -11.06844942166838, + -10.852541839399422, + -10.636005026619523, + -10.423527377022992, + -10.213310216982059, + -9.999075763703555, + -9.785930262927305, + -9.577366736144475, + -9.36603030307235, + -9.147755432275234, + -8.939428805736833, + -8.731140399381117, + -8.518671652381668, + -8.31098694241625, + -8.106092132470822, + -7.901629527846874, + -7.6946174871784745, + -7.485699018879198, + -7.281496518549839, + -7.078862784376807, + -6.873897714768329, + -6.676319700273836, + -6.4864640903131745, + -6.289130253810288, + -6.104133571272094, + -5.933536469508783, + -5.757799320920648, + -5.584755887518073, + -5.427087786521035, + -5.268344946207315, + -5.116876057770809, + -4.974848327334748, + -4.832670478293677, + -4.710412238595439, + -4.595053907280515, + -4.480850047095039, + -4.3831196509593315, + -4.298973724467213, + -4.223312224241947, + -4.16251912661842, + -4.115475682752629, + -4.079632921713764, + -4.057683322035281, + -4.0497633088001175, + -4.055863258036774, + -4.076998215256428, + -4.1134502271726925, + -4.164975272496102, + -4.2325182923216325, + -4.318591759797483, + -4.423047853198676, + -4.543722847198863, + -4.684773464165652, + -4.844670432503804, + -5.017705211420784, + -5.217147349040418, + -5.432995513525165, + -5.662264449874713, + -5.909273918413672, + -6.168061038992916, + -6.437447625694629, + -6.719855812733649, + -7.014831557942956, + -7.317825426702909, + -7.622772978317606, + -7.940282393727611, + -8.26320916901528, + -8.586785865539298, + -8.914048899272423, + -9.237595242606512, + -9.556300646951536, + -9.878293249501493, + -10.199021843992485, + -10.513134340491707, + -10.828795519518424, + -11.174391149549265, + -11.481227620596052, + -11.788309280238991, + -12.092349562421603, + -12.39322325232527, + -12.691973430070467, + -12.983382277509811, + -13.274590340662257, + -13.564045654261891, + -13.849703564491298, + -14.136216974038087, + -14.422028737490951, + -14.707283067784356, + -14.99114532930672, + -15.275945174048655, + -15.564766590843552, + -15.852752499044497, + -16.142906850652306, + -17.17314741044977, + -17.478182813658446, + -17.79182832937652, + -18.11079617721354, + -18.42714572180963, + -18.749749002753273, + -19.0816248901036, + -19.40629594972301, + -19.731826082974244, + -20.05841147903698, + -20.401288838203744, + -20.740474809645217, + -21.072438391231586, + -21.42662141925003, + -21.77914286037434, + -22.11837736906065, + -22.471611014192685, + -22.834011270115308, + -23.179721988586955, + -23.53415774461837, + -23.90158646706203, + -24.2544405819262, + -24.610666258146484, + -24.976154241038806, + -25.333454188733036, + -25.689471558670224, + -26.051056875198427, + -26.419257966070656, + -26.786369727597965, + -27.15264842046791, + -27.52334865978693, + -27.894932873525505, + -28.26387342846709, + -28.638491410536695, + -29.015233919415305, + -29.391840090992194, + -29.769291850625944, + -30.15057998175051, + -30.526253229073507, + -30.896677850573962, + -31.26966465648412, + -31.64087742523774, + -32.0007279253995, + -32.36426563289039, + -32.73396917822784, + -33.09182946101586, + -33.45345872141775, + -33.81766227133371, + -34.177694557752176, + -34.53528757347948, + -34.901174909526134, + -35.269196621898715, + -35.62711607127921, + -35.99285285849184, + -36.36277638389323, + -36.725180587024084, + -37.08824653846684, + -37.44433345109259, + -37.78923882709414, + -38.14177079186136, + -38.490278868950035, + -38.83548993586474, + -39.19184373751581, + -39.54921569486623, + -39.90673058848482, + -40.273446003535724, + -40.64015304783525, + -41.00393762273027, + -41.370740488685996, + -41.74091713701195, + -42.09902392828216, + -42.46042622252486, + -42.82537474447516, + -43.179490651063375, + -43.528849507652225, + -43.88205847688059, + -44.232331716935605, + -44.56833052708007, + -44.89985248724656, + -45.2284906256809, + -45.5493857404015, + -45.87614441547058, + -46.22424725687594, + -46.53783796105583, + -46.8537183745384, + -47.165978501112086, + -47.476069407070455, + -47.79506382989975, + -48.11556022545372, + -48.434348355419566, + -48.756109919126644, + -49.06988091178277, + -49.380598624341346, + -49.690779680787195, + -49.997267269464146, + -50.3049975449524, + -50.61072713610734, + -50.911144104523196, + -51.206718908487716, + -51.49952154089539, + -51.79271361906446, + -52.086862643448995, + -52.38092796772231, + -52.666114434227445, + -52.950917199642994, + -53.24378484397096, + -53.53078472662074, + -53.816388825820525, + -54.114016522739774, + -54.41317251061458, + -54.70798654818017, + -55.00045128159819, + -55.2997366557262, + -55.59838606562386, + -55.89137971230882, + -56.188058153598625, + -56.489160884856666, + -56.78881823532458, + -57.08930989206927, + -57.391741350204185, + -57.692745173151515, + -57.99057008646997, + -58.28297681813924, + -58.575543138993766, + -58.86903618089999, + -59.15816470046521, + -59.442831041731225, + -59.729271902696276, + -60.016024283583214, + -60.295415946986914, + -60.57171222326323, + -60.85248685486421, + -61.13238359286206, + -61.40840686037356, + -61.68662383327404, + -61.96647724375321, + -62.23837500263527, + -62.502096957689474, + -62.760493470537035, + -63.01658868620819, + -63.27047895359807, + -63.50826020631331, + -63.751709585442306, + -63.99228771054395, + -64.22153675376323, + -64.45136706449661, + -64.67401691207169, + -64.89087507459233, + -65.106517446601, + -65.31253473777473, + -65.51536748455793, + -65.71155381379072, + -65.89730880834624, + -66.07802958081712, + -66.2568334350681, + -66.41367613797222, + -66.57235287423055, + -66.72910938266696, + -66.87218144916228, + -67.01347147311785, + -67.14473095443732, + -67.26327976348009, + -67.37890441972439, + -67.48361775389816, + -67.5762377628514, + -67.6674938020023, + -67.7491293121327, + -67.81838468367297, + -67.88191109430018, + -67.93618316791971, + -67.98133990499582, + -68.01715817116215, + -68.04118431443811, + -68.05657977150146, + -68.06603921525864, + -68.06342856125076, + -68.04596045508238, + -68.01518506720029, + -67.97347259576468, + -67.92268206371651, + -67.86021994208443, + -67.7861755823915, + -67.69975808599018, + -67.60095100857507, + -67.4934195066361, + -67.37627270805676, + -67.2482438994998, + -67.11073870702361, + -66.96623401873879, + -66.8113376015874, + -66.64647559103149, + -66.47144652637122, + -66.29156644766901, + -66.1108632901167, + -65.92190724816146, + -65.72716727582748, + -65.53873886504608, + -65.34470480409853, + -65.13905019836768, + -64.93716412962752, + -64.73962551762308, + -64.52631575912591, + -64.31077071691386, + -64.10085223510309, + -63.882594558202356, + -63.656813799009974, + -63.43510654249091, + -63.208947542039255, + -62.97752796227855, + -62.74848487076831, + -62.514877330043205, + -62.28154834304957, + -62.05219778968952, + -61.81971488031907, + -61.584094628424914, + -61.351293511264686, + -61.113761592572054, + -60.87427425174988, + -60.636052446036175, + -60.39865609892982, + -60.15902393001214, + -59.924705926141165, + -59.68590459739886, + -59.447092126024984, + -59.211142750873265, + -58.96858000853882, + -58.72783673028705, + -58.49276578472339, + -58.25714823689183, + -58.0182650131093, + -57.794135858412766, + -57.5628600650443, + -57.32908277899748, + -57.10322510004539, + -56.868014170082205, + -56.62955861028737, + -56.39809843734877, + -56.1617801757568, + -55.92196704229794, + -55.68934583397833, + -55.46334633026685, + -55.22719909196398, + -54.992554547595326, + -54.76169334006083, + -54.52965323139209, + -54.29467957012429, + -54.066640298967734, + -53.84073233980438, + -53.610602003022834, + -53.38239275488003, + -53.15383851165397, + -52.92009762022746, + -52.68988001827451, + -52.46368493446851, + -52.23918400016331, + -52.021429454858115, + -51.810113332496485, + -51.594940866430484, + -51.386823461491225, + -51.179549268093474, + -50.96621960282022, + -50.749779523243724, + -50.528890585193665, + -50.3101877073193, + -50.08814360606012, + -49.857553105868305, + -49.62187189069538, + -49.3829594751214, + -49.14177276858828, + -48.900210588080874, + -48.658576175881926, + -48.414857305623684, + -48.178163184624616, + -47.94791360964173, + -47.71489974734685, + -47.47955062429109, + -47.24258062910488, + -47.011546636966834, + -46.77584374169844, + -46.53319506962506, + -46.29080597647534, + -46.04607075076184, + -45.80436712260419, + -45.54888612559069, + -45.29302623879207, + -45.04261198579043, + -44.78852661576912, + -44.51998027688438, + -44.26230853726105, + -44.00935795739714, + -43.73445301016194, + -43.457632107481345, + -43.1939152143408, + -42.91824131676634, + -42.63096257128518, + -42.36365961289818, + -42.10241000710876, + -41.81297046055366, + -41.51796373579707, + -41.23143676531105, + -40.92113763704598, + -40.606892251486805, + -40.30022890223715, + -39.97706596929543, + -39.657648821759686, + -39.33657419881249, + -39.00522352284926, + -38.67613681457556, + -38.34936825255397, + -38.01209357295046, + -37.678517169079996, + -37.34836826179574, + -36.99805686093465, + -36.64505427476551, + -36.29905258356289, + -35.948714717804265, + -35.59390738162773, + -35.24811213806463, + -34.90949555582719, + -34.567481565253374, + -34.24592603650697, + -33.937294662885776, + -33.621962712142306, + -33.315087209689324, + -33.03286414559924, + -32.7438962484879, + -32.46124429651965, + -32.19514194763271, + -31.931629684838693, + -31.66562934275739, + -31.413636124569884, + -31.17015669148171, + -30.925899168706554, + -30.688058667965244, + -30.461262313263457, + -30.241066780068092, + -30.025459427801167, + -29.81439984751964, + -29.614409069979523, + -29.42345523035274, + -29.238179503987503, + -29.055850882559447, + -28.88193772330147, + -28.71080987628412, + -28.541607115220092, + -28.37991731223352, + -28.223646009794745, + -28.06594750115205, + -27.917853390565092, + -27.77809345992737, + -27.63426271065992, + -27.495838170192673, + -27.365493223456493, + -27.23043474407258, + -27.096650196234123, + -26.968707927363088, + -26.83995375834438, + -26.704144730972136, + -26.565968946554342, + -26.427652172387216, + -26.287307899422835, + -26.151541713723248, + -26.011902670125803, + -25.869222456010576, + -25.727646136726076, + -25.586396620153735, + -25.442464723509012, + -25.307541277935947, + -25.177722888531928, + -25.04600908381682, + -24.917121572267266, + -24.788125411527496, + -24.662039297282313, + -24.53182931521357, + -24.399620126439526, + -24.267452661191722, + -24.133540617960936, + -23.995636126760715, + -23.853515305897222, + -23.714171059538444, + -23.578191257976414, + -23.44216862851543, + -23.310895225673786, + -23.183907249776336, + -23.063520810172292, + -22.942438759213363, + -22.824832329508865, + -22.717735109243844, + -22.615610707046123, + -22.517291680403947, + -22.422491462697835, + -22.331134837332154, + -22.248243963609365, + -22.16978687815482, + -22.093176398706508, + -22.01944584829417, + -21.95121705486948, + -21.88579223943143, + -21.821502822345227, + -21.763843742305273, + -21.709343889518678, + -21.652646960406056, + -21.598710947348714, + -21.54846774613765, + -21.493919830806792, + -21.438652213157617, + -21.38442425464531, + -21.326744362612235, + -21.266598716013863, + -21.20500619847264, + -21.142429721477257, + -21.079348065052375, + -21.01472626823717, + -20.94951722524327, + -20.886028908842263, + -20.822940275257913, + -20.75488132953802, + -20.69074946712982, + -20.629465710400524, + -20.567361864538576, + -20.504057880498937, + -20.44361271371172, + -20.38431961969177, + -20.32272947393359, + -20.259079127211745, + -20.190229059079506, + -20.116169726382388, + -20.034808625595353, + -19.94606171186625, + -19.853561276949925, + -19.754038063000156, + -19.650394833854403, + -19.544781420698843, + -19.43262049913946, + -19.314214499500526, + -19.1902777316672, + -19.061786076432135, + -18.933767326625006, + -18.79853376685333, + -18.661247472734505, + -18.52719926587841, + -18.38940716913294, + -18.246644100954516, + -18.106142906429113, + -17.964895443170374, + -17.8159615878383, + -17.664483037358462, + -17.51443774750091, + -17.355682865318865, + -17.197776038334222, + -17.039103784047885, + -16.874082576074187, + -16.702668619872654, + -16.537701235242935, + -16.370540557097137, + -16.18695180139197, + -16.016725783392605, + -15.841114752710066, + -15.6509785869013, + -15.4640804517942, + -15.276518958243155, + -15.083292607797304, + -14.888891144387616, + -14.69838754911703, + -14.50406689039443, + -14.307454029086736, + -14.111003316125702, + -13.912422283353548, + -13.713651235853419, + -13.513900237430422, + -13.314401368792659, + -13.111179904798744, + -12.911452707155615, + -12.709102012793903, + -12.510644090152551, + -12.313918253669252, + -12.114851699028497, + -11.919709982314373, + -11.726520385163177, + -11.529653227947433, + -11.334206437284548, + -11.141027640066572, + -10.947911924409743, + -10.754110868757065, + -10.565428209175893, + -10.377840332203059, + -10.185543787097933, + -9.994676687883254, + -9.8099209645742, + -9.625504437036492, + -9.436851783690933, + -9.258801554602389, + -9.083457851716325, + -8.902209382937015, + -8.727783505526311, + -8.555528958324672, + -8.381863023688284, + -8.207941606531735, + -8.031832381492727, + -7.852682171794043, + -7.677737487619914, + -7.499830232370012, + -7.32343444121509, + -7.15412986713176, + -6.97742937956745, + -6.808263461437903, + -6.645239230553583, + -6.480126330553118, + -6.321610129894153, + -6.171406040112868, + -6.025782510531592, + -5.8840604152574105, + -5.750222640994218, + -5.620357549438017, + -5.499672325962924, + -5.3875974493949625, + -5.27970169969005, + -5.181373672890584, + -5.09244340726824, + -5.010364330417337, + -4.939180123770951, + -4.87932959992753, + -4.83092898776508, + -4.794338018227281, + -4.770845822589469, + -4.761479650395224, + -4.767347263675286, + -4.790003260981669, + -4.83002707553688, + -4.8857563635534556, + -4.962009810454228, + -5.062494608257472, + -5.182496145017407, + -5.319464080856335, + -5.48646447435295, + -5.6781672343620535, + -5.8818786152041165, + -6.1093658639785975, + -6.353615042867167, + -6.607929683684417, + -6.8780239507149, + -7.16209689562419, + -7.456209988506733, + -7.755236388109119, + -8.065939563465781, + -8.383962262434833, + -8.703661947642509, + -9.029328828734164, + -9.351076408907938, + -9.670234092492473, + -9.990746753030484, + -10.310794466310988, + -10.624628182040013, + -10.937141983048106, + -11.246744698762829, + -11.551981303232175, + -11.854876207444745, + -12.152643821505787, + -12.447524421561937, + -12.740226959383119, + -13.025775042882891, + -13.31259659865821, + -13.598497596494655, + -13.878944892651946, + -14.160843513240069, + -14.445097367089, + -14.72880539492346, + -15.012365001907149, + -15.326899446551678, + -15.61753894322012, + -15.907490575849256, + -16.199323265377256, + -16.49399935871493, + -16.792340988507664, + -17.096481318043487, + -17.40324943071121, + -17.71432425738958, + -18.03554537615367, + -18.358983961304972, + -18.682138973977246, + -19.0180636692091, + -19.353281887089786, + -19.6902777995624, + -20.02729388854081, + -20.38171430666889, + -20.732631105220477, + -21.07599373850713, + -21.44454535889323, + -21.81149554677682, + -22.16536606181982, + -22.534285346715343, + -22.91203407012189, + -23.27393526122621, + -23.64896254038367, + -24.031010326557475, + -24.399525504603716, + -24.776205613627123, + -25.156406424881997, + -25.526184129708575, + -25.8994498320983, + -26.283550700911295, + -26.66314143660697, + -27.038982509312035, + -27.423303471452627, + -27.809498058081246, + -28.189723880756414, + -28.57597217680803, + -28.96952099376038, + -29.36163903154931, + -29.754513215060598, + -30.15316752755474, + -30.544086102844883, + -30.929702536223648, + -31.320676052334807, + -31.700346764452423, + -32.07358755573875, + -32.458027951279476, + -32.83454559896451, + -33.205169920591686, + -33.58145862924901, + -33.9576391690854, + -34.32451164127945, + -34.69708534191942, + -35.07466363624796, + -35.44092166896769, + -35.8112400397407, + -36.22187416482816, + -36.58558715914228, + -36.95019923390805, + -37.30722039055362, + -37.66022645519799, + -38.013865676811584, + -38.36429207274727, + -38.71955888602662, + -39.08086347353355, + -39.437007420312284, + -39.80208930662878, + -40.174053129625705, + -40.536293716082035, + -40.894992762822845, + -41.26334274470197, + -41.62206518692534, + -41.973968096581395, + -42.33501311442969, + -42.689788615724005, + -43.02963554909753, + -43.37327266607992, + -43.72533593541936, + -44.06457962885775, + -44.4099779056109, + -44.75767671814547, + -45.09718448453561, + -45.43531725412767, + -45.776304553782836, + -46.108939369182984, + -46.44315197593767, + -46.77671320836342, + -47.1097916500584, + -47.44092674373454, + -47.77223045426809, + -48.10040012601571, + -48.4314894830876, + -48.75754412267551, + -49.078659471510015, + -49.40134906470348, + -49.720839445720365, + -50.040349840036484, + -50.360188312589415, + -50.682491734446636, + -51.0052570146535, + -51.327311560291925, + -51.649295372723095, + -51.974327279246154, + -52.29802564782532, + -52.61238112329573, + -52.93298379299863, + -53.25988223727866, + -53.60583207414197, + -53.92246057642615, + -54.24806808279626, + -54.56842567866411, + -54.88147735525404, + -55.20225750322398, + -55.52506010969101, + -55.8387378677252, + -56.15384444336004, + -56.473451500630524, + -56.78653006164733, + -57.09791242056369, + -57.40896515875888, + -57.71766858472592, + -58.021961041411565, + -58.32165198305714, + -58.62245827442661, + -58.92386458923721, + -59.217323747072484, + -59.50993694388504, + -59.838094191706325, + -60.131659958931856, + -60.41831426312358, + -60.71057614856131, + -61.00365228998208, + -61.293513825360534, + -61.58340389910705, + -61.87590932124566, + -62.16118369846589, + -62.438659026915936, + -62.708841181370545, + -62.98038388744832, + -63.243801013062196, + -63.494203051516244, + -63.751191428207626, + -63.999712028628686, + -64.2406005326087, + -64.47703712670896, + -64.70642542945515, + -64.92931317062418, + -65.16318724935785, + -65.38729506878302, + -65.6060726891053, + -65.81616202686729, + -66.01449779138751, + -66.21162846234624, + -66.38659094581782, + -66.56085536796608, + -66.73244684473043, + -66.89035451771738, + -67.03507457511772, + -67.16900249744889, + -67.29275896729585, + -67.41457951260044, + -67.52543905902068, + -67.62724231781792, + -67.72924406711621, + -67.82068476790911, + -67.89999965240955, + -67.97326809434492, + -68.03443977924331, + -68.08705114968794, + -68.1302694767572, + -68.16066800177673, + -68.18272920647078, + -68.19867952246226, + -68.20181207445387, + -68.18951883961707, + -68.1646274842005, + -68.12918384282501, + -68.08260255189471, + -68.02393911772455, + -67.95286829617942, + -67.86868226662678, + -67.7702939523941, + -67.66037218650199, + -67.53937115307448, + -67.40384807520357, + -67.2596935111753, + -67.10973633176081, + -66.94149530078502, + -66.7680674613186, + -66.59164428152881, + -66.41174341663618, + -66.23469514052006, + -66.0554457105644, + -65.86565807463982, + -65.67983002419086, + -65.49355369495187, + -65.29764628527755, + -65.1033288156557, + -64.91078935487995, + -64.71669034036273, + -64.51016631909441, + -64.30264164333961, + -64.0939707719879, + -63.879767744820796, + -63.66013353700236, + -63.43950714809001, + -63.21546653838599, + -62.989324697392306, + -62.76366186457419, + -62.53377246857059, + -62.30305713381066, + -62.07500725259491, + -61.84397569998243, + -61.61013784941881, + -61.37655537051623, + -61.13853762360535, + -60.89692275488019, + -60.65466443261562, + -60.41124009451162, + -60.16567979786915, + -59.8992134922145, + -59.65392790922492, + -59.41130718281685, + -59.1727282859495, + -58.93186539834098, + -58.69888095003819, + -58.474625899546936, + -58.249619840917575, + -58.02886352448362, + -57.82697080168654, + -57.61986416040366, + -57.412477854243484, + -57.21790629901126, + -57.01417455503435, + -56.80427539332728, + -56.60051983870767, + -56.3909301755096, + -56.17867322852458, + -55.96567590669834, + -55.75002019127368, + -55.53821000436251, + -55.32275563397752, + -55.097034951736006, + -54.874554282590935, + -54.65154556264045, + -54.42015676403187, + -54.1891977712623, + -53.9614974957198, + -53.72591319541674, + -53.48680118342321, + -53.25012897881014, + -53.00595907394144, + -52.75762124270159, + -52.51642386106821, + -52.27492439426055, + -52.03446135545029, + -51.80338771123684, + -51.570131743521394, + -51.339573288905584, + -51.111819435022326, + -50.8786841191399, + -50.640249050916225, + -50.398346501704374, + -50.157928984684986, + -49.91153730186999, + -49.65681732613714, + -49.39851113453391, + -49.138684563959714, + -48.87561029299528, + -48.61332713480645, + -48.351313973049365, + -48.09391763721541, + -47.844131904719525, + -47.5925508667915, + -47.33823620512275, + -47.084624928978656, + -46.837978267530694, + -46.582914096065664, + -46.32267761569632, + -46.06674810210955, + -45.81358593373239, + -45.55259010126162, + -45.28519390370538, + -45.02927634043554, + -44.781689275642115, + -44.52085863738756, + -44.26726591293619, + -44.03319750372196, + -43.783763958900835, + -43.52248442722238, + -43.27260548524963, + -43.02231897415474, + -42.761132332254896, + -42.49383754189107, + -42.23604587339814, + -41.98449023263584, + -41.713577270098575, + -41.43731140915635, + -41.16821530747471, + -40.88274234060668, + -40.584601594446006, + -40.29027130515817, + -39.981488308192475, + -39.66911822323395, + -39.359846685451615, + -39.04055651844393, + -38.71213240045084, + -38.387212631084445, + -38.0545504745387, + -37.71601498515601, + -37.391258543936985, + -37.05362203171195, + -36.700536008170076, + -36.35747655690082, + -36.015072282920364, + -35.66764202829099, + -35.32003928951747, + -34.98211857521233, + -34.64601291789126, + -34.31012468152238, + -33.99917280616775, + -33.69036934635618, + -33.37252637187671, + -33.07801542439387, + -32.793133970565, + -32.49856686616356, + -32.22140147035971, + -31.95255704580614, + -31.68582930214602, + -31.423631772945555, + -31.1739095830452, + -30.930711126470772, + -30.692076432081222, + -30.46416432851567, + -30.244015760179764, + -30.034802928863694, + -29.83187604724801, + -29.632595413163973, + -29.440857524061972, + -29.258080208780836, + -29.079226062327194, + -28.902690554308926, + -28.735352235137242, + -28.570039077963198, + -28.40421427345232, + -28.244859088491445, + -28.092574801800435, + -27.943005642885478, + -27.799709405209214, + -27.664916180262097, + -27.529275668507786, + -27.394708065742588, + -27.26959806318795, + -27.144448935461774, + -27.01768573990916, + -26.89787609366886, + -26.777365424158678, + -26.65398058306212, + -26.53442257492223, + -26.413244125949667, + -26.2905665921127, + -26.16954957018384, + -26.047865366896147, + -25.921803248337532, + -25.795793335642138, + -25.671125904950184, + -25.542272870482364, + -25.416761141290415, + -25.292304464815377, + -25.16654336774769, + -25.041264557897748, + -24.916893199446427, + -24.79358078621804, + -24.672231319722187, + -24.548652199182136, + -24.42655841947077, + -24.305231593550875, + -24.18320677676784, + -24.064023907822595, + -23.945339160114113, + -23.8289148212615, + -23.71282700567663, + -23.597508985821865, + -23.482437735536017, + -23.370468805176095, + -23.251013585785863, + -23.142821782250813, + -23.041046932935984, + -22.942268845593144, + -22.844489189901505, + -22.74958296518811, + -22.655536346114808, + -22.563102470299114, + -22.477491037207717, + -22.393557353489836, + -22.30970519529215, + -22.226692937187224, + -22.14600634224972, + -22.06266736309336, + -21.975538256320444, + -21.896577154454505, + -21.82141801150044, + -21.74538678778868, + -21.671662864113483, + -21.60365542603736, + -21.535091750690743, + -21.464296664202067, + -21.398950542882325, + -21.33559701583881, + -21.27496859266713, + -21.214309574897396, + -21.1521963503551, + -21.091359317870097, + -21.030699439283005, + -20.969579625976433, + -20.9098221161416, + -20.85162585422419, + -20.79021143043873, + -20.72591263963573, + -20.66632930359653, + -20.606756013391703, + -20.54793563100285, + -20.489295377111368, + -20.432874415698684, + -20.378494230646304, + -20.32391958757059, + -20.269627165249354, + -20.213192398605802, + -20.15483064850556, + -20.095594385340217, + -20.033812313778647, + -19.969942780704837, + -19.90350039406957, + -19.833527866239653, + -19.764014785982017, + -19.692108766412368, + -19.61360639638979, + -19.532550458494118, + -19.44773062430693, + -19.355592283156742, + -19.25834594038665, + -19.1534272375535, + -19.043982858127226, + -18.92849206129195, + -18.806684199137845, + -18.67850867398856, + -18.54067541708158, + -18.396960040558653, + -18.249224811303247, + -18.091554930154057, + -17.926856700358016, + -17.761750058542518, + -17.58543179215636, + -17.405605300622042, + -17.22859798607869, + -17.039129325914118, + -16.848666693439938, + -16.6686330336351, + -16.47652264047373, + -16.278866978601055, + -16.09137994161027, + -15.897040527105835, + -15.693751042780153, + -15.4966742148757, + -15.298197050089271, + -15.089348171692212, + -14.885089128457635, + -14.6819258564195, + -14.449113779667437, + -14.238462294996125, + -14.027180938854725, + -13.810463310106211, + -13.59211177590087, + -13.377071793323289, + -13.159329879227819, + -12.947782978232762, + -12.73648038212877, + -12.525048836825933, + -12.315720323875656, + -12.109352970906356, + -11.906677108230163, + -11.705393518953267, + -11.505387198968648, + -11.30924365056562, + -11.114067544486828, + -10.918693505094573, + -10.726333082328877, + -10.539315941056248, + -10.351655575671991, + -10.164587177282716, + -9.97766109026659, + -9.79021576216002, + -9.602406903104615, + -9.415187739159482, + -9.230366463441761, + -9.044213924765177, + -8.862251104887306, + -8.681349789377212, + -8.501347110457658, + -8.321457502881403, + -8.140273101105624, + -7.962422570741458, + -7.7838871558740985, + -7.604338394898698, + -7.425114977611501, + -7.249151616998797, + -7.071273543879868, + -6.899545543739369, + -6.737215706948102, + -6.571567806855794, + -6.399927947089783, + -6.232808456374319, + -6.070741063907515, + -5.902810867076883, + -5.741294598085184, + -5.586845810918248, + -5.426456899643438, + -5.27174834862525, + -5.129183736000645, + -4.9889571805071835, + -4.86339172223333, + -4.750069251820169, + -4.642505876003119, + -4.54585226879615, + -4.460211877510048, + -4.384058913325851, + -4.321146436868113, + -4.27187270826552, + -4.236265106477961, + -4.216005860397327, + -4.210176772519647, + -4.220354095654507, + -4.2473615803990485, + -4.292681161497685, + -4.3587749747053355, + -4.445349518086225, + -4.5524076363952135, + -4.683500954836085, + -4.8432594067400325, + -5.022028914400991, + -5.2191401875980645, + -5.440063084845116, + -5.672922677038756, + -5.922664565901052, + -6.188808705343841, + -6.461947549427972, + -6.754117920110981, + -7.052798465791427, + -7.35059411751251, + -7.661967325805363, + -7.9832890317025464, + -8.297017429364743, + -8.611832612467229, + -8.930462069406301, + -9.240934484010658, + -9.550160389278119, + -9.862375700301817, + -10.168760128912231, + -10.473256055642691, + -10.777581275065579, + -11.075524237624167, + -11.371149705828651, + -11.662907304778852, + -11.952265851473792, + -12.240132377325695, + -12.52370127523571, + -12.808053908403776, + -13.097543095082074, + -13.384641468399407, + -13.669836436712401, + -13.958753857364563, + -14.250420843215275, + -14.541161131699276, + -14.832444982102599, + -15.131949392039019, + -15.431893213659425, + -15.734957774675108, + -16.04875672451202, + -16.36280414491753, + -16.683553232004968, + -17.00699308186, + -17.332747334602168, + -17.667887062929207, + -18.006987923791336, + -18.34423684463063, + -18.695508690381114, + -19.04334643942763, + -19.383285249998647, + -19.72287251600759, + -20.078413829905095, + -20.43400135525887, + -20.776686380526844, + -21.14124394717289, + -21.50906632415472, + -21.86146422365928, + -22.224969733501066, + -22.604764968625048, + -22.966135933097714, + -23.333190888492236, + -23.712322423120806, + -24.07678349836263, + -24.44302401814183, + -24.81916976232616, + -25.184358791921095, + -25.550925890268402, + -25.92440996628066, + -26.299281066303568, + -26.671911481988346, + -27.04590893036592, + -27.42363718412834, + -27.799273898283765, + -28.177081677650502, + -28.555931951833543, + -28.938372998127534, + -29.320798679575173, + -29.703302227329466, + -30.085839146691445, + -30.464179820922475, + -30.838759530642555, + -31.217494140793907, + -31.583673161430763, + -31.94729185703748, + -32.321546013104644, + -32.68507945473096, + -33.047322176730255, + -33.414348603841425, + -33.77725214880683, + -34.13121959916513, + -34.49136493089003, + -34.858149523061954, + -35.21317117890908, + -35.57320167927696, + -35.93912655339301, + -36.297759702010254, + -36.658166114989136, + -37.01584278101903, + -37.363671882451406, + -37.71918818737856, + -38.07009011853977, + -38.4192419354633, + -38.779972176411505, + -39.138676472252456, + -39.49906960422623, + -39.869975854523005, + -40.241600283067065, + -40.60342805716733, + -40.971095771213015, + -41.339607651174774, + -41.69576764207521, + -42.05619454683223, + -42.41976727018062, + -42.7712731748833, + -43.117881304040026, + -43.47096678291186, + -43.81918218196119, + -44.160421813372125, + -44.51270227679648, + -44.863395806909736, + -45.20718075785223, + -45.558118553094246, + -45.899440869304115, + -46.24028870659253, + -46.58268028396712, + -46.922831346866076, + -47.26038864953452, + -47.6007955930503, + -47.938188878742935, + -48.27607148286675, + -48.611115283100666, + -48.94177586453975, + -49.27426430952204, + -49.60512664717823, + -49.93364108685517, + -50.26499397829418, + -50.60010530903664, + -50.93593920746131, + -51.267822894194, + -51.59801866473734, + -51.93094760277337, + -52.26200271980654, + -52.58137243184985, + -52.90707399580594, + -53.23821734458246, + -53.558469572304226, + -53.879483425254215, + -54.2092128421484, + -54.54185155314612, + -54.88932727075317, + -55.24249321569978, + -55.596643036632805, + -55.942674701815115, + -56.290443054981836, + -56.640411972020516, + -56.98408075989082, + -57.325307407783605, + -57.666136180459816, + -57.99724724428649, + -58.310970848072145, + -58.619696760548145, + -58.92702186794036, + -59.236775048101684, + -59.537340151671366, + -59.83459656830051, + -60.13572461652187, + -60.4324845962634, + -60.72202133405235, + -61.00940804596916, + -61.284146701549226, + -61.555728698510464, + -61.82696216986305, + -62.10138520566945, + -62.37045248164464, + -62.63220986432724, + -62.88779565580989, + -63.14171686106158, + -63.42171388515108, + -63.65871347807436, + -63.90220543119827, + -64.14685131473944, + -64.380434954368, + -64.60878200641977, + -64.83653060712273, + -65.05782932678203, + -65.2770852740441, + -65.48701069616845, + -65.6911606816281, + -65.89607652863722, + -66.09474127384375, + -66.31184830494684, + -66.49555014564436, + -66.67650043253545, + -66.87310345199377, + -67.04243044693298, + -67.20109124786681, + -67.34934314279768, + -67.48868190342226, + -67.6152598900484, + -67.72943327169341, + -67.83696138410691, + -67.92957533813689, + -68.00756133962416, + -68.07396299553434, + -68.12490626916019, + -68.16165420916077, + -68.18447059190872, + -68.19471965844453, + -68.19422577114908, + -68.17963605247925, + -68.14973647685582, + -68.10357412857022, + -68.04309324752415, + -67.97207058491907, + -67.88761146640188, + -67.78784341323492, + -67.67681140481433, + -67.55214102633916, + -67.41354055578304, + -67.26579036318951, + -67.10583100720318, + -66.94292764651082, + -66.77491661115016, + -66.60226357385955, + -66.42403430874768, + -66.24711004653231, + -66.07194777803723, + -65.8888736709726, + -65.70669644053216, + -65.52605098415836, + -65.3389185521889, + -65.14908149935475, + -64.96048925841929, + -64.76972608456713, + -64.57381824928201, + -64.3791344660323, + -64.18148199195709, + -63.981151055753415, + -63.77752144969465, + -63.57319723378935, + -63.365163333170734, + -63.15492654382409, + -62.945898469985636, + -62.73241123742727, + -62.51923284037687, + -62.308349848833195, + -62.094569124912574, + -61.876731772078266, + -61.660221863054424, + -61.43827108087202, + -61.21159987807561, + -60.98462798178336, + -60.75627815165769, + -60.52564879010985, + -60.296167193870836, + -60.06459632240016, + -59.82995713548851, + -59.59667484648438, + -59.3579326006824, + -59.11505296780608, + -58.87564497207802, + -58.63757934739215, + -58.392745508136976, + -58.155700546167544, + -57.926264880692045, + -57.68475196623979, + -57.45165653454874, + -57.21967681709609, + -56.976653191345996, + -56.740985283310046, + -56.51031439087568, + -56.27255462907921, + -56.03777018960083, + -55.81333338627688, + -55.587746813302, + -55.351435034574585, + -55.119544184925374, + -54.89091806950956, + -54.65315513065476, + -54.41529335908701, + -54.18454709911138, + -53.94641026415759, + -53.70438234670335, + -53.467279125317376, + -53.22438777065321, + -52.97598323518786, + -52.73635432009008, + -52.49902106545069, + -52.26215693833489, + -52.032434838484114, + -51.80143886598082, + -51.57815664422095, + -51.35058741694427, + -51.12037014615864, + -50.88821687901644, + -50.64957361497919, + -50.41436834867109, + -50.17546861867721, + -49.92890091489961, + -49.6789750660276, + -49.429652796231004, + -49.17569703060559, + -48.9207764239108, + -48.67046159851721, + -48.41863653161014, + -48.17785718793287, + -47.93933897121058, + -47.67281443309361, + -47.42377282292627, + -47.185082938086424, + -46.94882815642885, + -46.700490486465725, + -46.45525309815263, + -46.21177766739795, + -45.97069543633762, + -45.719215041775186, + -45.47124758114668, + -45.22963354800662, + -44.990147497932135, + -44.7387569525379, + -44.48866234233836, + -44.24992910988856, + -43.99863821366199, + -43.732647083377834, + -43.47267251101343, + -43.217003439382125, + -42.95010965130786, + -42.676783674005726, + -42.41717333370034, + -42.164115996782556, + -41.89254509713656, + -41.61708458340238, + -41.34734913493048, + -41.061625157362165, + -40.7652650433777, + -40.47133710313652, + -40.16424603143145, + -39.85368225169909, + -39.54273118661796, + -39.222530030983044, + -38.89157386271389, + -38.563973957574525, + -38.227126143397115, + -37.88248697364101, + -37.55197748559018, + -37.20839009955219, + -36.85044275868542, + -36.50248672176635, + -36.156593284841016, + -35.80565575556108, + -35.457912478486016, + -35.12443794837501, + -34.79063364554585, + -34.46089862331865, + -34.158724860412335, + -33.85711200902962, + -33.54851771848214, + -33.26904674483539, + -32.99048511996118, + -32.70763129128961, + -32.44397959648887, + -32.186520092905944, + -31.92207919171088, + -31.66654454313218, + -31.423143867287802, + -31.180937758785337, + -30.941562837459823, + -30.710265389050218, + -30.48591565277127, + -30.27155217361085, + -30.06044039019869, + -29.852837116124395, + -29.65821965345719, + -29.47374363829907, + -29.289308221845356, + -29.11355146632258, + -28.94326228285456, + -28.771299701455444, + -28.60391715640494, + -28.44478188561241, + -28.287143868490215, + -28.128547136297414, + -27.982156688014772, + -27.84108800553709, + -27.695576842662707, + -27.55768435920355, + -27.427185144312723, + -27.29078783811361, + -27.15701972986323, + -27.02789292391146, + -26.89630659737769, + -26.766524754676166, + -26.63890827340488, + -26.50998986811527, + -26.37930138100591, + -26.252635785012448, + -26.122613742951934, + -25.989233641777307, + -25.85619187003529, + -25.723001737915244, + -25.58702980593626, + -25.45334178306973, + -25.320643132813696, + -25.186769046028385, + -25.056151207291038, + -24.925521577812056, + -24.799887659456303, + -24.67113774492623, + -24.541946985087716, + -24.41353367974446, + -24.284415243938945, + -24.157379816213925, + -24.028791788956305, + -23.90251251487836, + -23.778305565422993, + -23.652621510385604, + -23.52801573154487, + -23.406664723236712, + -23.290583916296562, + -23.17299805591505, + -23.05803106552739, + -22.948452539768354, + -22.840906137286407, + -22.737569530668804, + -22.636938082674405, + -22.538817962300598, + -22.44839958144037, + -22.360081603669116, + -22.271002634935414, + -22.184900618477602, + -22.103239130672712, + -22.014479762357627, + -21.925076219122143, + -21.84358296127434, + -21.762901278132713, + -21.680065064600818, + -21.603796169976505, + -21.5298319625657, + -21.448699523720126, + -21.37053181201758, + -21.29522768411689, + -21.220193220675228, + -21.144932436311436, + -21.069502756738537, + -20.993000401104982, + -20.915139598245805, + -20.836362476713152, + -20.759848821063958, + -20.685694248929767, + -20.607965797768685, + -20.531906658937547, + -20.4582291401625, + -20.38468112958522, + -20.309451168894814, + -20.238488598494687, + -20.169293725160717, + -20.098530092779974, + -20.02660230942389, + -19.9500141454091, + -19.869935506011178, + -19.786749288357925, + -19.70078623204097, + -19.611337121528702, + -19.517673369750533, + -19.42401636348683, + -19.32484162536539, + -19.219512380743346, + -19.11009234439682, + -19.00561746281542, + -18.900630452626732, + -18.789210306109172, + -18.67288115520019, + -18.55344480226453, + -18.4306162347505, + -18.301523436571486, + -18.166633892675442, + -18.030478909515868, + -17.891823566838152, + -17.735483461156054, + -17.573967505978977, + -17.40960829443117, + -17.23748555687319, + -17.068687548978406, + -16.898923225515574, + -16.71677063759025, + -16.541886205758647, + -16.370041594298264, + -16.1794668729959, + -16.002906841016575, + -15.838150680923476, + -15.65541404846038, + -15.470282902125652, + -15.28934621217244, + -15.10011313197145, + -14.904843790414107, + -14.715755247753119, + -14.52645821299971, + -14.332290870385137, + -14.132606731027836, + -13.931727493688731, + -13.72738080668493, + -13.520244894338862, + -13.314763867680039, + -13.10528222978969, + -12.898854902486203, + -12.689737788942864, + -12.483305136228353, + -12.281972521953938, + -12.052623322930717, + -11.817743968530818, + -11.584338453453785, + -11.348256864236905, + -11.114342842430563, + -10.883604701583929, + -10.654761443621585, + -10.42478171950886, + -10.195302979942849, + -9.97475231693026, + -9.769998519232248, + -9.571054807203446, + -9.375417913997303, + -9.184170727774703, + -8.988597397886682, + -8.791890416085007, + -8.602719953838504, + -8.411860111056003, + -8.21997760218974, + -8.031556981128379, + -7.8376941515003775, + -7.643111751732136, + -7.447022164396884, + -7.249836894600815, + -7.05142909650045, + -6.864192343081893, + -6.673116519509215, + -6.480025557699567, + -6.298781596663485, + -6.114105451143301, + -5.937361607614952, + -5.7721289455864175, + -5.607215117982718, + -5.4434819972844135, + -5.288422461368478, + -5.137776625133515, + -4.987381387024947, + -4.846559694129956, + -4.709753934769112, + -4.578624702006177, + -4.457572723125548, + -4.339024241729415, + -4.2294753258954865, + -4.130914987869087, + -4.039879148273867, + -3.95657914556615, + -3.8826764758420067, + -3.8201087528016426, + -3.7672292828033918, + -3.7256977397103426, + -3.6955138118894784, + -3.6770146209065997, + -3.6715946955947816, + -3.6808656487423788, + -3.7055355155165337, + -3.7449386071828585, + -3.802030474497758, + -3.8794570338897474, + -3.97420013018582, + -4.083911746718939, + -4.221500530721805, + -4.387535942198094, + -4.566653020215587, + -4.76113262777675, + -4.976709965202321, + -5.199257730520783, + -5.434835159250235, + -5.685380549926435, + -5.9428732363886, + -6.21238316471042, + -6.50696499359925, + -6.773886359439698, + -7.053750767225963, + -7.33973572622452, + -7.626456913534832, + -7.916782464454037, + -8.205646712319059, + -8.492050094030459, + -8.779053840349983, + -9.064313604001057, + -9.33384660439048, + -9.61646527958896, + -9.900424270673751, + -10.183177791607156, + -10.46027226751575, + -10.739440009601028, + -11.016061103154998, + -11.288266148574056, + -11.56284721691582, + -11.832733983018528, + -12.10052109320295, + -12.373206564594877, + -12.643139739294062, + -12.911854727461288, + -13.185682238104803, + -13.46016140509024, + -13.735541888662391, + -14.012805277113669, + -14.291571137100174, + -14.576080596574343, + -14.861663923350035, + -15.147062863209158, + -15.436449379522982, + -15.729661487595468, + -16.025683577990534, + -16.3259641118826, + -16.628643167328327, + -16.93640083820361, + -17.25237864626378, + -17.56434155192122, + -17.881837796544843, + -18.21125739537088, + -18.535305797214715, + -18.863330300252386, + -19.190294409900005, + -19.531916121181638, + -19.869821903325168, + -20.197928657670445, + -20.5461424621001, + -20.892740304918068, + -21.226708387833042, + -21.570438651134808, + -21.92730913622124, + -22.27337495356273, + -22.619024390057913, + -22.976571053052066, + -23.32787112560278, + -23.673687321816168, + -24.02903025793823, + -24.381686420947037, + -24.726948925539567, + -25.07982105962973, + -25.427353101501105, + -25.781701017069786, + -26.13694409316997, + -26.48784201106306, + -26.84263462170883, + -27.200202960430932, + -27.557248079750657, + -27.912253275792036, + -28.27559316550701, + -28.63439632886228, + -28.991763551401778, + -29.353511115547064, + -29.709783645660497, + -30.01323901761087, + -30.362695436940708, + -30.710804430413184, + -31.048522993817613, + -31.392226461220748, + -31.737511267222768, + -32.072843154855654, + -32.41893289161984, + -32.76050294582449, + -33.093835998479435, + -33.43253142031484, + -33.774557551109254, + -34.11879081435566, + -34.45416380248082, + -34.79214542782523, + -35.13956589482416, + -35.47964635722244, + -35.82015204080372, + -36.15523614887767, + -36.479142864119574, + -36.80674706483185, + -37.1291116637628, + -37.447048364440334, + -37.764806536344665, + -38.08264704370983, + -38.39453813804148, + -38.710798351912224, + -39.02222979718832, + -39.32246295221218, + -39.6186140469893, + -39.90659619198359, + -40.18426418681222, + -40.45012198626207, + -40.74392973947109, + -41.00145920924832, + -41.24388350087197, + -41.48352599803586, + -41.71949558891751, + -41.943007478604, + -42.162533594962134, + -42.3767548274806, + -42.58190509390349, + -42.7769890588805, + -42.96672207836876, + -43.14921278631825, + -43.32522528291063, + -43.49400343403272, + -43.655386636374224, + -43.80946632043466, + -43.95835746958686, + -44.0986616858918, + -44.234111722028814, + -44.362705841581004, + -44.48787799190498, + -44.60818177282764, + -44.726030293359415, + -44.84005633801287, + -44.95205489166338, + -45.05506360824793, + -45.153203812309336, + -45.24850106503814, + -45.337966490095056, + -45.42247563763865, + -45.46732325894877, + -45.545759674876685, + -45.61877177427002, + -45.68643047744021, + -45.747090283895865, + -45.804888994986875, + -45.857196480917096, + -45.90643402647283, + -45.95488229329985, + -46.00148330239156, + -46.04480654641061, + -46.084664143937616, + -46.121982462449786, + -46.156163476189214, + -46.185184775311804, + -46.21000581689569, + -46.231883910132005, + -46.2501290064271, + -46.26582681121732, + -46.27905374974234, + -46.288700712577295, + -46.29704694548059, + -46.30527065409081, + -46.31250846518448, + -46.317928943784885, + -46.32228100271273, + -46.32542482762396, + -46.32747488306811, + -46.328919653780396, + -46.32986608599402, + -46.3304398726619, + -46.33083244968079, + -46.330799733883694, + -46.330557374228555, + -46.330329932323, + -46.330030683635066, + -46.32966117343729, + -46.32929646015045, + -46.32893328567334, + -46.32857092034011, + -46.32817699677578, + -46.32776764111201, + -46.32763750722102, + -46.32752353585319, + -46.32741971950408, + -46.327311341827425, + -46.32721412055969, + -46.32712851929781, + -46.32704343720672, + -46.326961885047375, + -46.326889645591145, + -46.3268292156383, + -46.32625332436312, + -46.32558996719882, + -46.32489536106943, + -46.324172070980374, + -46.32341546088188, + -46.31854893589611, + -46.3177119394207, + -46.31683521102417, + -46.31590373459938, + -46.31493176385335, + -46.31468611420354, + -46.31452037781347, + -46.31434516935154, + -46.31416596403488, + -46.31398190557863, + -46.313789053324385, + -46.31359229044191, + -46.313388579072296, + -46.3131777660119, + -46.3129605319642, + -46.31220793694785, + -46.31137463406303, + -46.31051845738101, + -46.30964367184241, + -46.308749128709785, + -46.30783345566822, + -46.3068996753256, + -46.30594324377183, + -46.30496486113546, + -46.303964665004116, + -46.30360411258737, + -46.30330338414397, + -46.30299313539405, + -46.30268222063515, + -46.30236990386346, + -46.30204335822196, + -46.30171050285596, + -46.30137528525517, + -46.30102610097923, + -46.30067419875487, + -46.298681681678026, + -46.29643981480972, + -46.29415891872216, + -46.29185035169715, + -46.28952100105424, + -46.2871632931724, + -46.28476434163069, + -46.282341589514715, + -46.279900163436906, + -46.277397162465554, + -46.276858249478906, + -46.276545553239885, + -46.276237437701376, + -46.275939097285224, + -46.27563698229068, + -46.27533217631425, + -46.27502008355396, + -46.27466962203694, + -46.274343699054235, + -46.27402063184802, + -46.27393243420421, + -46.27384803666774, + -46.27377608733807, + -46.27370256016782, + -46.27361375448261, + -46.27352735658383, + -46.27344759052145, + -46.27336324828337 + ], + "xaxis": "x", + "y": [ + 45.3008156780876, + 45.30139249659502, + 45.30207388412416, + 45.302779365342516, + 45.30327017525618, + 45.30366755396359, + 45.304470145008935, + 45.30518387263864, + 45.30609090911849, + 45.30687156544467, + 45.307606550331045, + 45.308498081838486, + 45.30942195356706, + 45.310178104221386, + 45.310926488730445, + 45.31182747165074, + 45.31266222320987, + 45.31351501570955, + 45.314094239896505, + 45.31467869635597, + 45.31528909457208, + 45.31597277766448, + 45.31654964174645, + 45.317203857669774, + 45.31777798392741, + 45.31839253279861, + 45.31897215740679, + 45.319468677500254, + 45.31992878987747, + 45.320431444448275, + 45.32081689665318, + 45.32120610300833, + 45.321625721527056, + 45.32202211593169, + 45.32250820449737, + 45.322955418807005, + 45.3233432006593, + 45.3236721494652, + 45.32406768610164, + 45.32449448721753, + 45.324786667993585, + 45.325181078207635, + 45.32569962486422, + 45.325977368459846, + 45.326232633712586, + 45.32652617078259, + 45.32690094971074, + 45.327175032373795, + 45.327468279438456, + 45.32782881931442, + 45.32815955695149, + 45.32855726232112, + 45.3289479042678, + 45.32925402295475, + 45.32957195489748, + 45.32988602204331, + 45.3302553562011, + 45.33056458182725, + 45.33077645486678, + 45.331108311543844, + 45.33133192390389, + 45.33163701185809, + 45.3319656771283, + 45.33221244624497, + 45.33247912474411, + 45.33278226233508, + 45.3330664033172, + 45.33370888493417, + 45.33458040982336, + 45.33537000147783, + 45.33612905222214, + 45.337045324723526, + 45.33803467707128, + 45.33891321918778, + 45.33974516663382, + 45.340669989337506, + 45.341706933303875, + 45.3424165803379, + 45.34316434906252, + 45.343982178039354, + 45.34460533149476, + 45.345352162774525, + 45.34626063496387, + 45.346987307893635, + 45.34767841539286, + 45.34859987931272, + 45.34945584746354, + 45.350395505481366, + 45.35148574922371, + 45.35254371492952, + 45.35358334727091, + 45.35455292738862, + 45.35554700714752, + 45.3566151497575, + 45.35760786605543, + 45.358603163309496, + 45.35954239913033, + 45.36044313293403, + 45.36108732179106, + 45.36166416591801, + 45.36242752377537, + 45.36315745628319, + 45.36366896891568, + 45.36422668083271, + 45.36470075387124, + 45.365418958998745, + 45.36623907015416, + 45.36684004409919, + 45.367561299130706, + 45.36827572050837, + 45.36897988583669, + 45.36982052976597, + 45.37060570595836, + 45.371247589681396, + 45.37195435313954, + 45.37271734665364, + 45.37354313216032, + 45.374367704722154, + 45.374955454021205, + 45.37553003991417, + 45.37627435510372, + 45.37705473867891, + 45.377721903573075, + 45.37831286704026, + 45.379033142782866, + 45.379830947639604, + 45.38059243751599, + 45.38117249069004, + 45.381584204690135, + 45.382289755173126, + 45.38304080280461, + 45.383534270318066, + 45.38414144610749, + 45.384963056608626, + 45.3854795917873, + 45.386329977947234, + 45.38686672616464, + 45.387358926539015, + 45.387647810618766, + 45.38831143294449, + 45.389019970667675, + 45.38933818219206, + 45.38986687054689, + 45.390494593561264, + 45.39114008025351, + 45.39191132113288, + 45.39257737356896, + 45.39308626634105, + 45.39382450230375, + 45.394881821393, + 45.39538367284164, + 45.39587702399459, + 45.39656761866656, + 45.39729705610352, + 45.39792512989577, + 45.39838165972011, + 45.39874233865337, + 45.39902638582274, + 45.39967427948701, + 45.40023006427122, + 45.400584152467445, + 45.40096982891739, + 45.40161061108628, + 45.40241610102564, + 45.40353330610432, + 45.404046616503614, + 45.40454401090433, + 45.40543917032443, + 45.406808970991854, + 45.40875166726319, + 45.41009398234997, + 45.41119017778836, + 45.41277666718019, + 45.414441898035896, + 45.41595401106941, + 45.41744928896387, + 45.41896141057751, + 45.42038195091547, + 45.42179378705188, + 45.42328822555661, + 45.424667636170554, + 45.42602883424413, + 45.42747793039279, + 45.42899354980808, + 45.43039835660806, + 45.43190844253109, + 45.43341773885088, + 45.4346268542106, + 45.43562375873985, + 45.43674924925812, + 45.43805682224895, + 45.439370632660086, + 45.44061735675941, + 45.441537158339806, + 45.44261891673703, + 45.44387328724353, + 45.44504649112133, + 45.446088310458094, + 45.446863676367514, + 45.44783462592337, + 45.44913497438336, + 45.44995477834738, + 45.4508777616672, + 45.45197956661854, + 45.45340942077631, + 45.45573246220501, + 45.45718909584074, + 45.45938684207846, + 45.461389196091126, + 45.46334061612658, + 45.46926139318614, + 45.48089777711856, + 45.501214711717786, + 45.53288822687134, + 45.577290444240646, + 45.633096606635455, + 45.694498226716014, + 45.753903368151434, + 45.80324708003626, + 45.842514531229476, + 45.871001472155704, + 45.89232880537815, + 45.90755927947151, + 45.91810200470127, + 45.92735225768559, + 45.93863367975251, + 45.95510226972569, + 45.98220132377144, + 46.02101755307864, + 46.072201015367, + 46.136281479681884, + 46.21268366519937, + 46.30023381874523, + 46.3987222526035, + 46.50841955536481, + 46.630216313790825, + 46.764829759859204, + 46.91125682816488, + 47.067105943074985, + 47.2301537665803, + 47.40069902256385, + 47.57923186470848, + 47.75964445930259, + 47.93985239218809, + 48.11860858050425, + 48.297836894706336, + 48.472262707350595, + 48.63911928992631, + 48.80357382257347, + 48.95798249389381, + 49.10089279573725, + 49.237599758046144, + 49.362792853770976, + 49.47604431993286, + 49.57548028229101, + 49.66420073780353, + 49.7399837451903, + 49.799237489241285, + 49.84418947149259, + 49.875802185057275, + 49.89222039768281, + 49.89099748302868, + 49.87043247632826, + 49.83138604513381, + 49.77439663659841, + 49.69922220649449, + 49.60464481714886, + 49.493100513352935, + 49.36949924541319, + 49.22537423589797, + 49.06192063745789, + 48.90056135171285, + 48.71326156484875, + 48.50677767207073, + 48.29123013154028, + 48.06217323972727, + 47.8263036719102, + 47.574960042544, + 47.30548547698959, + 47.045676425305, + 46.77277482648385, + 46.47996621724064, + 46.19731751334456, + 45.90729061412997, + 45.598604405795726, + 45.29071891001583, + 44.980974826570744, + 44.66267315736977, + 44.335157104668696, + 44.00718979490236, + 43.67453768698372, + 43.33532658956795, + 43.00035013818195, + 42.66252204416129, + 42.31053292607663, + 41.96500768512144, + 41.61781986964398, + 41.262578113674586, + 40.889098081171305, + 40.53548505220367, + 40.17463957841586, + 39.79404993323112, + 39.4227806618875, + 39.05773260388129, + 38.683176224769205, + 38.29913475580295, + 37.93580532168676, + 37.56441738761964, + 37.17811635258044, + 36.804510099558854, + 36.44113900340817, + 36.064546098911265, + 35.69372087141643, + 35.334615656045194, + 34.9644569027439, + 34.597104208935136, + 34.22727820122309, + 33.86389863684194, + 33.49488431760243, + 33.12181591189096, + 32.759274732150935, + 32.395474510484995, + 32.03804504836804, + 31.66601075130246, + 31.31725611808596, + 30.967690039639177, + 30.601231172111575, + 30.245156493319932, + 29.893627092750066, + 29.540271224832736, + 29.177603179598087, + 28.817969149126267, + 28.467078341879606, + 28.11085186343826, + 27.755593154455127, + 27.402708520690407, + 27.05160239263043, + 26.69603599407251, + 26.34608845173437, + 25.997783470672367, + 25.636561296441418, + 25.292832310208993, + 24.952662739209387, + 24.59828609904642, + 24.24889079335562, + 23.90981742879898, + 23.556238946751584, + 23.208548846812583, + 22.867356255936546, + 22.520619688446672, + 22.1876450455937, + 21.854303830472148, + 21.51917623638629, + 21.19556415285358, + 20.873701750356773, + 20.542221125944344, + 20.2240715322587, + 19.90671534746058, + 19.57797828845812, + 19.263416671605512, + 18.949845388828383, + 18.629574691901183, + 18.31678177799355, + 18.007455306366328, + 17.686616681291696, + 17.36593154591251, + 17.053670632089403, + 16.734225319944265, + 16.41665371576344, + 16.105345159951728, + 15.795884134788553, + 15.482673454930206, + 15.16978272106591, + 14.856165353792097, + 14.542356140388431, + 14.223514689927992, + 13.906649352658695, + 13.589123697081071, + 13.265220477639241, + 12.945816900600125, + 12.62347924681104, + 12.296554103238934, + 11.974138151036009, + 11.655235559168181, + 11.328660914920984, + 11.003878164777806, + 10.689554109617307, + 10.336243739986498, + 10.012882028606871, + 9.70006425773776, + 9.387405783443159, + 9.07221919192586, + 8.76318492149884, + 8.459091266684318, + 8.15366952352691, + 7.851049574429019, + 7.550825329024207, + 7.2475686489489695, + 6.95111250129687, + 6.649122672343673, + 6.3415263993000455, + 6.040796463926234, + 5.735054831825614, + 5.417440985445541, + 5.103882331876352, + 4.796628215343878, + 4.4710126942388495, + 4.154003125172445, + 3.8482676826184345, + 3.520071410336961, + 3.196028968250423, + 2.8827003196684813, + 2.5533895948068066, + 2.2256742525251783, + 1.9065839344434248, + 1.5787089986988987, + 1.2651164732978843, + 0.9526818893866802, + 0.6337693479703133, + 0.3341686963750352, + 0.03254823819888407, + -0.27648412447609516, + -0.5687027525870395, + -0.8635005364573746, + -1.1665914153099537, + -1.454811315170887, + -1.7427599098874327, + -2.0294113008777246, + -2.3085698226508033, + -2.5797839307054833, + -2.8474848989618433, + -3.0857886310911478, + -3.305761264129615, + -3.525632163772129, + -3.722457127936083, + -3.894970666098154, + -4.057218885737025, + -4.194189076241781, + -4.303664293010956, + -4.39493505559735, + -4.463884314162211, + -4.508502390300171, + -4.529686531299095, + -4.528705855772213, + -4.507491266321912, + -4.465671421355342, + -4.405001886944767, + -4.32625764130935, + -4.230554011243292, + -4.119715288476124, + -3.994783832463368, + -3.8540688232855236, + -3.7025005624448304, + -3.5376120998679643, + -3.358881803838362, + -3.171118176019267, + -2.972527316378767, + -2.7633975361435636, + -2.549750915092249, + -2.3316471827646374, + -2.109896765989796, + -1.8863183099210437, + -1.6652110461765917, + -1.4451771478074735, + -1.226889137720352, + -1.011277772934694, + -0.7993051441073634, + -0.5897134119466692, + -0.3830455392882667, + -0.1864948954127271, + 0.0004078606033779599, + 0.1841737451301992, + 0.3581433899216065, + 0.523106531424442, + 0.6856718939917603, + 0.8448896943368465, + 0.9852469551509175, + 1.120574499501041, + 1.2534584683232481, + 1.372300570357847, + 1.4891902499772482, + 1.6025651196027995, + 1.700974297405831, + 1.7950677733487508, + 1.886022272846113, + 1.9685798216488397, + 2.050010889495398, + 2.1279426241905512, + 2.1940161643564493, + 2.2545925319915137, + 2.315099925122909, + 2.369688620213981, + 2.4208469471933536, + 2.4734767901004764, + 2.5217831366172576, + 2.564724544275585, + 2.60865494652897, + 2.652391161093852, + 2.6958755206167906, + 2.743230773389391, + 2.7926624770464876, + 2.8450847000196515, + 2.9027667471179592, + 2.9621795538146714, + 3.0228889257776115, + 3.08511995497618, + 3.147228635069744, + 3.209805052764536, + 3.275428095767219, + 3.3425320247803243, + 3.4132174717170405, + 3.4896686082634463, + 3.5732865496411255, + 3.662835601032349, + 3.7584972016324896, + 3.860760868542198, + 3.970510709658999, + 4.085992883988966, + 4.209555049949327, + 4.340229789785011, + 4.4786732655191575, + 4.62312839460308, + 4.773898205177146, + 4.929969700935827, + 5.092612765295047, + 5.261896756172644, + 5.43572917477412, + 5.61676170286682, + 5.805103169990768, + 5.998199751734249, + 6.194148892434426, + 6.396021645392319, + 6.60351207877032, + 6.812150181151334, + 7.024439891419589, + 7.239593035908757, + 7.461798938328259, + 7.689736019284011, + 7.910876789935185, + 8.134178225766638, + 8.366337537529912, + 8.595205430692014, + 8.828259709925012, + 9.067759325112458, + 9.308143599918386, + 9.544916660600956, + 9.782906022073732, + 10.02445110245041, + 10.266502632981478, + 10.511513709381713, + 10.767614786337361, + 11.021663554114792, + 11.271077075426104, + 11.532421447231798, + 11.794230143723857, + 12.048732529840379, + 12.318792424498856, + 12.587589110078033, + 12.85117505566216, + 13.129808979167192, + 13.41050860883629, + 13.682113883904265, + 13.970007124245505, + 14.25659636900969, + 14.533496888165852, + 14.825556253707173, + 15.114661339511507, + 15.390982998995568, + 15.676442715762622, + 15.950673586347234, + 16.22648841788473, + 16.510164390876515, + 16.787586376391996, + 17.059385215373506, + 17.32915554265866, + 17.589821311067574, + 17.851042436220453, + 18.120806514425322, + 18.381316539093813, + 18.649363293214517, + 18.92072779695792, + 19.17939668683508, + 19.44458360066395, + 19.716406254396798, + 19.973203953715267, + 20.248927654873327, + 20.53149678648731, + 20.80213783736742, + 21.081990773637354, + 21.365355880616196, + 21.643618225661513, + 21.913061774422967, + 22.190558366707357, + 22.465459989288973, + 22.736167042598407, + 23.00860562348474, + 23.2693424039515, + 23.529741273826666, + 23.793060143465997, + 24.050393670369758, + 24.308112897371167, + 24.561037908110176, + 24.814086088154934, + 25.072132468240415, + 25.32709391472432, + 25.58879628783784, + 25.862435987606062, + 26.124248052301922, + 26.400771359272834, + 26.698637999743013, + 26.988779903511194, + 27.28977737611257, + 27.61778207808079, + 27.933296000574693, + 28.233553746679014, + 28.559360939600225, + 28.893196662831155, + 29.213767786933026, + 29.549688880343254, + 29.898193639548563, + 30.236051826725706, + 30.575490053951725, + 30.921617312784136, + 31.266528699970756, + 31.61511586526169, + 31.965928409854495, + 32.321088124303174, + 32.68624282041068, + 33.05311612040869, + 33.41499561528636, + 33.78580401630252, + 34.162269284435375, + 34.53349236470104, + 34.902784680066155, + 35.28014955050072, + 35.65206884471092, + 35.993916155834775, + 36.337238246147166, + 36.69093602799156, + 37.01142486875497, + 37.32938252248089, + 37.66952001589818, + 37.98674315243737, + 38.292031888684036, + 38.617174936741286, + 38.93331799020795, + 39.244696475262366, + 39.572183475508645, + 39.89469340117806, + 40.21105414540574, + 40.5329396915485, + 40.852677910951414, + 41.170964054845285, + 41.492393746208634, + 41.816278996971505, + 42.13843244992256, + 42.4624769820841, + 42.78190785217412, + 43.10162998868757, + 43.41904839217346, + 43.74270882506173, + 44.06166939448674, + 44.3840251748717, + 44.70933557184713, + 45.02849952323979, + 45.33869853550536, + 45.65795522292771, + 45.9561873041327, + 46.244189478798894, + 46.542770418974314, + 46.82553262290039, + 47.10560214467375, + 47.397143331513625, + 47.67650898688305, + 47.951679475099674, + 48.262276345092104, + 48.54204525971228, + 48.817546869468444, + 49.10046596855581, + 49.39099902472938, + 49.67309590453489, + 49.9531390439686, + 50.2395789778626, + 50.52052218117748, + 50.795787443730156, + 51.07781152015942, + 51.35955903180017, + 51.63221003744897, + 51.911141814574215, + 52.19219993001085, + 52.46280337212093, + 52.73295430455883, + 53.00086997289239, + 53.25639675369177, + 53.514251272506066, + 53.76726885445143, + 54.01573680083499, + 54.267316364946964, + 54.51975090757005, + 54.77606529568504, + 55.029706361850785, + 55.28613124379961, + 55.55111631024073, + 55.820080831954876, + 56.0918879101304, + 56.364504005935174, + 56.63876528594555, + 56.91522558123022, + 57.18948768938687, + 57.45746616064551, + 57.72299585349498, + 57.992154637738096, + 58.25895001039742, + 58.52162243605322, + 58.78797891035919, + 59.057869470114625, + 59.32823146555272, + 59.59978179601026, + 59.869960334038346, + 60.154406857621844, + 60.433110048736474, + 60.70321189802036, + 60.98811954336956, + 61.2733693518662, + 61.53315476632863, + 61.806216591765086, + 62.086372734152064, + 62.33739996545596, + 62.57978455088455, + 62.826714824026105, + 63.05091904688225, + 63.24594773053274, + 63.45187542531075, + 63.65136295895432, + 63.82437506428474, + 63.99467278315867, + 64.15715766589464, + 64.29938772830046, + 64.43342067932468, + 64.55592054085274, + 64.66513713671445, + 64.76063170755718, + 64.84109386619431, + 64.90327777550321, + 64.9530878591095, + 64.98873716556929, + 65.01147423361941, + 65.02570767302133, + 65.02749972294426, + 65.01412424861836, + 64.9870922648049, + 64.9485383058607, + 64.89876947747825, + 64.83623928964768, + 64.75912746305288, + 64.67046203291542, + 64.57204155291505, + 64.45662609625938, + 64.32712540620042, + 64.19121308087333, + 64.03978132981177, + 63.873811932100324, + 63.699796682439825, + 63.507081971503794, + 63.302754832272456, + 63.08476247700988, + 62.847875973720406, + 62.60001405754087, + 62.338156798886146, + 62.06505294352749, + 61.78422636080124, + 61.495918882771704, + 61.20062871625016, + 60.89715647145221, + 60.59363227711049, + 60.286338617564006, + 59.97581702374971, + 59.66764178163206, + 59.35917472999657, + 59.0499470723258, + 58.73613869538399, + 58.41415273479658, + 58.09010416596422, + 57.77650297850374, + 57.45572065962611, + 57.12661173148182, + 56.81478018523037, + 56.49384328172674, + 56.165808011887776, + 55.84210982481136, + 55.52822010997151, + 55.20576107600213, + 54.88515707480901, + 54.57524655272796, + 54.25470433239023, + 53.932389323263045, + 53.618865361326115, + 53.29827369296802, + 52.97328779013662, + 52.6508437224558, + 52.330288949532154, + 52.00047183719301, + 51.6697709764731, + 51.3445725332754, + 51.00953256245475, + 50.675199188807724, + 50.347056527984535, + 50.01951657085091, + 49.69460635081357, + 49.37087699839047, + 49.039663193308186, + 48.7183576570489, + 48.39442939401609, + 48.06187421811483, + 47.735367706458796, + 47.40791623822752, + 47.08038176449596, + 46.75490105480903, + 46.428951274188265, + 46.099389827713274, + 45.77181593362555, + 45.44576347159304, + 45.11157220136288, + 44.782696246636846, + 44.45444085837797, + 44.11948276656226, + 43.78698960850408, + 43.460844945475515, + 43.12957279153525, + 42.80656058785394, + 42.47900659761572, + 42.14010304827866, + 41.81312894911944, + 41.4828844834615, + 41.14073464378206, + 40.790831824081856, + 40.458683095589194, + 40.11086212170768, + 39.74970426633614, + 39.39882618202941, + 39.04807585689426, + 38.694243359613246, + 38.333119226864, + 37.988340428417885, + 37.64166357394087, + 37.286300971218516, + 36.94067299149588, + 36.59429440030454, + 36.245001646987184, + 35.894488555799505, + 35.550597899545004, + 35.206908551835106, + 34.85800110128992, + 34.51274108570734, + 34.16109721333436, + 33.81582738929942, + 33.46808696874815, + 33.114084831080845, + 32.77641000358633, + 32.43553485318641, + 32.090718871663896, + 31.745921897846507, + 31.41410309010996, + 31.080169378701054, + 30.736477653480044, + 30.363381905863072, + 30.02845064741058, + 29.68423954889631, + 29.331032746250823, + 28.9809945998811, + 28.637363081978908, + 28.290136301718768, + 27.94504537970999, + 27.60622534312888, + 27.263000026771746, + 26.920784363114365, + 26.583815648547414, + 26.256011092523174, + 25.92365447564597, + 25.593690151688918, + 25.281026421461352, + 24.96259905015177, + 24.63841194877399, + 24.32563880841202, + 24.012127146120758, + 23.68589962457247, + 23.373195495681, + 23.068473395322435, + 22.748129764280563, + 22.440043876570734, + 22.14487558793027, + 21.83551863312298, + 21.53421228111542, + 21.248201984464405, + 20.945708396456133, + 20.64081927466012, + 20.357449089040124, + 20.03149966441319, + 19.720093229948088, + 19.435201812480095, + 19.144905494480355, + 18.841035547667776, + 18.55253000673612, + 18.264586541756902, + 17.965788952557034, + 17.671908548287185, + 17.37875574603664, + 17.0797388664511, + 16.783577182279164, + 16.48957195162242, + 16.196627188069524, + 15.908961657880663, + 15.619467707340434, + 15.329402507274027, + 15.041683546863892, + 14.751878699487346, + 14.461495813257766, + 14.170690971569112, + 13.8867959149224, + 13.593944847952267, + 13.302901500358487, + 13.016083493508878, + 12.72172994277544, + 12.428402293371853, + 12.135758882422708, + 11.839532109935789, + 11.538786474773989, + 11.241012185373176, + 10.944394413391453, + 10.644743644029987, + 10.344443309982122, + 10.046514095085957, + 9.747651902947501, + 9.445357567582166, + 9.144482895339513, + 8.849365986402391, + 8.550908631399782, + 8.25931297358785, + 7.972316267253725, + 7.687355281947255, + 7.404022902957972, + 7.125064806315193, + 6.8493587915491965, + 6.56815624385909, + 6.289947758426632, + 6.007619796696353, + 5.727679501862931, + 5.450295600272493, + 5.13650291779756, + 4.850484427189774, + 4.574164910703354, + 4.293910887024876, + 4.004374565766532, + 3.7120510453182836, + 3.4269112996098055, + 3.1344891416584884, + 2.8360522011068374, + 2.547019245380965, + 2.2494028422549746, + 1.9489033896265402, + 1.67120455158615, + 1.3868309317285878, + 1.0929825361587568, + 0.815642809736947, + 0.5402877602571728, + 0.25779440471505605, + -0.015820090274220804, + -0.2894913126194905, + -0.5640564076527189, + -0.8356416725538327, + -1.1072331463548326, + -1.3841510328431743, + -1.6591995343901804, + -1.9404886167329474, + -2.220919669520379, + -2.4986442046069617, + -2.7728521855353336, + -3.0438554155927364, + -3.313997694802523, + -3.5625877364363183, + -3.7915781436545024, + -4.0189937800303435, + -4.229870076382449, + -4.417881997703746, + -4.595480579252699, + -4.757489951167618, + -4.896623387289247, + -5.018915844925662, + -5.119489835476398, + -5.195548705790415, + -5.25126228266642, + -5.2841795569265635, + -5.292831710637094, + -5.278892062242572, + -5.244600399280449, + -5.194089304822076, + -5.123294391606358, + -5.03399507068378, + -4.933235474052575, + -4.815188985987018, + -4.681240280654256, + -4.538723052923676, + -4.382249427723075, + -4.213460040110186, + -4.0361065794578845, + -3.8502910466976052, + -3.656025545820314, + -3.4560829154449006, + -3.2524945997325934, + -3.043261252966324, + -2.8316333868655486, + -2.620229119594151, + -2.4110323757562764, + -2.2066924996544364, + -2.00518040356106, + -1.8107207804503536, + -1.620505805022866, + -1.4323830570331701, + -1.2491373686815526, + -1.0698302730834983, + -0.8932338729370016, + -0.7231197783989942, + -0.5577946798268661, + -0.39997884575165277, + -0.25086064533969765, + -0.10150288629249732, + 0.03921114626320604, + 0.17471077749946817, + 0.3043070416622088, + 0.43648982178307133, + 0.5622748639074678, + 0.6734836419307776, + 0.7867008460158456, + 0.895962611369247, + 0.9965770945643719, + 1.0958311059249572, + 1.1938361087859697, + 1.2821110310831099, + 1.364231352420128, + 1.4454265973633418, + 1.520340716139314, + 1.5930753419076706, + 1.6646118890652004, + 1.7291068967679482, + 1.7891544553959013, + 1.8456985207786494, + 1.899244506357675, + 1.9475202976315285, + 1.9929574748169114, + 2.03579577285625, + 2.0764217109349326, + 2.1140307854178264, + 2.1496401316420592, + 2.1850458865790854, + 2.219208730447587, + 2.2539632541126435, + 2.2906514400572338, + 2.3297655444874543, + 2.371185444490704, + 2.41644779667443, + 2.464060172631494, + 2.5109721037633066, + 2.5602644036293203, + 2.6108143478517976, + 2.6613617881714995, + 2.714123178891581, + 2.7684536843776764, + 2.8228949993006247, + 2.8800268016741852, + 2.9403840877793135, + 3.002161407579184, + 3.068184020594977, + 3.139146949739317, + 3.2143579905857766, + 3.2949232127770065, + 3.3818421415057895, + 3.4739901364427124, + 3.570184815458072, + 3.6720720455078406, + 3.7770999048557936, + 3.887869376895746, + 4.00661919157578, + 4.129030728272307, + 4.2560521838599055, + 4.393061839658805, + 4.533440260262142, + 4.6775180037611035, + 4.830011862211025, + 4.988896039339954, + 5.144000392428633, + 5.3049028724758145, + 5.47212379418288, + 5.638976742362163, + 5.807526688047787, + 5.982524727679, + 6.159214030937705, + 6.332095180397173, + 6.511497045887136, + 6.693704704756934, + 6.875197369226239, + 7.063564473750477, + 7.255672142776363, + 7.442886691707591, + 7.635592936096776, + 7.8346533040875626, + 8.03509816929982, + 8.237577875031166, + 8.448307817888143, + 8.66072048865215, + 8.872612942982652, + 9.08268721501466, + 9.295330537878796, + 9.51006012488097, + 9.724262240432347, + 9.938272629074817, + 10.158517169446744, + 10.382777336405727, + 10.602156621345047, + 10.82086117104478, + 11.047291725091869, + 11.272708492209368, + 11.491988903181552, + 11.72105359252825, + 11.952157487481044, + 12.177594801573768, + 12.41005064143213, + 12.648525756456184, + 12.884252070621573, + 13.119909581516461, + 13.365365905045502, + 13.606950302108704, + 13.84355089162025, + 14.090705051007193, + 14.339801637631709, + 14.579391152293853, + 14.823229366209237, + 15.071063546514575, + 15.309981807870773, + 15.553155563947865, + 15.803085414087619, + 16.0460542892863, + 16.28853145973164, + 16.530594019284234, + 16.767750430938626, + 16.997994732664846, + 17.22914615892, + 17.464042032722208, + 17.696195435545526, + 17.928963400106287, + 18.170396313340994, + 18.404911770979936, + 18.632773201619653, + 18.86861396003305, + 19.107525723154236, + 19.337515409785976, + 19.571872163418092, + 19.81537774092592, + 20.049121205306683, + 20.279423950116357, + 20.518393498541517, + 20.747714328000868, + 20.98186053415768, + 21.21400590800481, + 21.435743480005325, + 21.663773828905068, + 21.884492568732025, + 22.10230068911461, + 22.337482609855414, + 22.55678803148629, + 22.77148449953714, + 23.000846659949364, + 23.23139734517778, + 23.465707952139407, + 23.708546282416, + 23.94843354868638, + 24.199872438773035, + 24.461934267263292, + 24.729895379270047, + 24.996771028896625, + 25.283612970463412, + 25.570698071989074, + 25.853188213337447, + 26.162006779248262, + 26.47999145755729, + 26.78723584250772, + 27.12176317086207, + 27.451275937616725, + 27.734800856121986, + 28.03247936867568, + 28.33961146345534, + 28.636296723208126, + 28.936545363686367, + 29.246599874849714, + 29.55022391570878, + 29.850466486255595, + 30.152564197833787, + 30.456848339169074, + 30.777947437062487, + 31.09633074574183, + 31.413915306395243, + 31.733919333118052, + 32.05738918618142, + 32.38339297504573, + 32.69845253609786, + 33.02233050460258, + 33.35051633388529, + 33.68203245147105, + 34.018937032723066, + 34.3539873254395, + 34.69617026899503, + 35.028056427609776, + 35.353837752109136, + 35.67806336236072, + 36.00211278982288, + 36.31680367933958, + 36.639117222661454, + 36.9614908740441, + 37.26872273738408, + 37.57922006591536, + 37.89567640057429, + 38.211777147447854, + 38.528604536691105, + 38.852246853332126, + 39.17607981673305, + 39.498979405826006, + 39.824025274175206, + 40.145148721288294, + 40.476339975004876, + 40.81106746865938, + 41.14129810873627, + 41.474835183906976, + 41.81025367921867, + 42.14166012501361, + 42.47222463361508, + 42.80454492939298, + 43.13266055277677, + 43.46339955497243, + 43.788767565801884, + 44.11270992545289, + 44.4421659920752, + 44.76786017852259, + 45.08523809354388, + 45.41192795750231, + 45.73191436790232, + 46.0443173180707, + 46.36863719179993, + 46.680583537321326, + 46.98535134429957, + 47.300896233115886, + 47.60753805478654, + 47.908290016873806, + 48.22005742068531, + 48.524680338591075, + 48.81226824718113, + 49.117739807019106, + 49.424977028106625, + 49.716295513344164, + 50.02017166739853, + 50.327518375444534, + 50.61753374457286, + 50.91192433762515, + 51.210994094867324, + 51.497095491069466, + 51.786802823370024, + 52.082655715673305, + 52.36433625058349, + 52.64086855305455, + 52.9196097987463, + 53.18989176032296, + 53.45672496766371, + 53.71847554639376, + 53.98392127395361, + 54.247868095035905, + 54.51594943747289, + 54.78578329656477, + 55.053175965256905, + 55.32673404988352, + 55.60816434695921, + 55.891096660041555, + 56.17002278113821, + 56.45718733425426, + 56.739335430895515, + 57.01436135947399, + 57.294636784008155, + 57.56281328200112, + 57.820343777994964, + 58.08795471171312, + 58.36098770603641, + 58.61376757722674, + 58.86528033184651, + 59.1287464001122, + 59.38797958767201, + 59.63834330315669, + 59.891565926035796, + 60.15613322949835, + 60.41511892721383, + 60.66205547127083, + 60.91463548034098, + 61.17888758280835, + 61.42780964441885, + 61.67701956066958, + 61.94424795824756, + 62.19870373326381, + 62.430696439641245, + 62.66668740599379, + 62.89723983116863, + 63.094398205962435, + 63.28490475865507, + 63.482910310962495, + 63.660491151964685, + 63.821230030324756, + 63.98086805759875, + 64.12197267361248, + 64.24792760066693, + 64.36453889731763, + 64.46800888376497, + 64.5564510546822, + 64.62922632692454, + 64.6812992209274, + 64.71739132296442, + 64.73789964974321, + 64.7439040715773, + 64.73688022912468, + 64.71286656664903, + 64.67176819925788, + 64.61390344327381, + 64.53959924444034, + 64.45385923247711, + 64.35086128700219, + 64.22866983655938, + 64.09896598619568, + 63.95289561913557, + 63.784124616501664, + 63.61083168698891, + 63.41961471446286, + 63.209482144673196, + 62.99583111634186, + 62.77014618565708, + 62.52167367434831, + 62.26658233785969, + 62.00675270962785, + 61.72922993287618, + 61.44233320712871, + 61.15492822946826, + 60.86354132292463, + 60.56485050857393, + 60.257210856349765, + 59.94326087065825, + 59.6265391529923, + 59.30248363140266, + 58.97248495867293, + 58.64288748884854, + 58.30485072795838, + 57.9556159486451, + 57.60989846051303, + 57.26828973042716, + 56.90938151070443, + 56.56201036558662, + 56.2260318703524, + 55.87258210292476, + 55.52450545347809, + 55.191678950907026, + 54.842569777325664, + 54.50034430187689, + 54.16397664791392, + 53.81506068723594, + 53.46844999673037, + 53.12546618533615, + 52.771237548232456, + 52.416131885196044, + 52.06997292964902, + 51.70921728574256, + 51.34932654969274, + 50.996254010251924, + 50.632475120190506, + 50.27304033140169, + 49.920462892005354, + 49.564575846793105, + 49.2084079767248, + 48.850906416209334, + 48.50046930037752, + 48.14063878476699, + 47.77996322785137, + 47.42325662962246, + 47.06725232626325, + 46.71008107261035, + 46.35046553471646, + 45.993880165998355, + 45.63807784940863, + 45.27762151816358, + 44.87704195462212, + 44.51989654388736, + 44.15479523062273, + 43.78421874294206, + 43.420459137595664, + 43.050112333314246, + 42.68113629964051, + 42.31362731680097, + 41.93485694238308, + 41.55918420381393, + 41.189714940355074, + 40.801464269560746, + 40.411148977985675, + 40.042291799925536, + 39.649731442874064, + 39.253051860289105, + 38.87489921935038, + 38.48771087127243, + 38.083414891431914, + 37.70616935852628, + 37.32691393297396, + 36.931171793510565, + 36.55070476573083, + 36.177786735914644, + 35.79020476557115, + 35.407788641532385, + 35.038779597638246, + 34.66077094312423, + 34.27934693319909, + 33.90105384636693, + 33.527572022715994, + 33.143359280365985, + 32.76026593437598, + 32.38679497305845, + 32.00730000585379, + 31.626719826835444, + 31.254946739186128, + 30.887289382377276, + 30.512247442201993, + 30.13658462182371, + 29.766528681871424, + 29.38976250500205, + 29.004155919429586, + 28.62909146399714, + 28.254264130612647, + 27.876338314365942, + 27.505595716712246, + 27.131808965108885, + 26.757524197591497, + 26.389461805315932, + 26.026468433337648, + 25.6618095218435, + 25.30414354373347, + 24.958017631664948, + 24.601153949659874, + 24.24740650062091, + 23.900121622434913, + 23.537202272270793, + 23.183317636581993, + 22.835473512785967, + 22.48132141853015, + 22.138567909739955, + 21.800347632044677, + 21.458087837225776, + 21.127569173612148, + 20.79410490896639, + 20.44979926071972, + 20.131252020127988, + 19.807254862470852, + 19.46250668203238, + 19.14309515678464, + 18.822158666322974, + 18.484389662209296, + 18.15802249536964, + 17.839350604459312, + 17.503790610679896, + 17.18279635353825, + 16.887316563593416, + 16.58432027539839, + 16.285836656258173, + 15.998488711337787, + 15.706050705041125, + 15.412486367453946, + 15.12526468906649, + 14.831709058834692, + 14.539009667809236, + 14.239272893116445, + 13.931095235562534, + 13.619771167922194, + 13.308466798262845, + 13.001946361769999, + 12.69230938113229, + 12.382536700062241, + 12.075128830025376, + 11.768998362231162, + 11.457195405539851, + 11.144141366307275, + 10.832027317209997, + 10.518315653260595, + 10.204546415956004, + 9.896141915774662, + 9.592504687984121, + 9.284819313742853, + 8.982192400780749, + 8.685558266774898, + 8.390206477635632, + 8.096370276346233, + 7.809191266980111, + 7.52074451752643, + 7.232554645694854, + 6.947315584632098, + 6.652718868692668, + 6.355835606186661, + 6.066645304814446, + 5.7368072265099395, + 5.428234579838464, + 5.126423041081522, + 4.821908919914601, + 4.509444073749548, + 4.205763490389693, + 3.903414356462298, + 3.5895961220837638, + 3.2857902397490633, + 2.9879391894659926, + 2.67833424372988, + 2.3763449437131494, + 2.0799139729703624, + 1.7783088479566478, + 1.493890339972635, + 1.2080900397306307, + 0.9196675895400847, + 0.6486909989695223, + 0.37832567836853914, + 0.10259769135183895, + -0.16153310687831507, + -0.4287159968190723, + -0.7035148421559364, + -0.9805875505298111, + -1.2669542513347407, + -1.5492923349737737, + -1.8222514448022245, + -2.097713892939078, + -2.370835217615415, + -2.646681655038601, + -2.905696173590179, + -3.1487680002484337, + -3.4002994387283474, + -3.632539819233667, + -3.838726917758838, + -4.043406966843576, + -4.24119518731128, + -4.422860342940131, + -4.593148047467437, + -4.749831707061056, + -4.889870678773691, + -5.014872457500469, + -5.121991177980183, + -5.210338830976306, + -5.283298642679399, + -5.338418185267794, + -5.374688487883849, + -5.391714241780363, + -5.389777739731842, + -5.368472267339411, + -5.33043607064049, + -5.2753607264986435, + -5.205343541496031, + -5.120891760653099, + -5.022079124443184, + -4.910970696160349, + -4.78897079947705, + -4.655103139485727, + -4.512457571891651, + -4.359771112636242, + -4.1962573686174105, + -4.027853879376715, + -3.852368771853214, + -3.6674716577417565, + -3.4803658908609085, + -3.2918598507939962, + -3.07996566948812, + -2.887443932799642, + -2.6961274624367877, + -2.507135316960963, + -2.320736468016825, + -2.13376342129394, + -1.952028989159487, + -1.7716734828900949, + -1.5934054902590746, + -1.4199812351256735, + -1.2455211223044407, + -1.0777437100022877, + -0.910810587782139, + -0.7441583383260169, + -0.5830847179693679, + -0.43107570674228857, + -0.2808515446782764, + -0.1300501962348853, + 0.009926393514131816, + 0.1476784415624258, + 0.2784038338805753, + 0.40936338142276285, + 0.5382515338782801, + 0.6521455559490862, + 0.7635723765825918, + 0.8721639877723049, + 0.9712182010899587, + 1.0656798874971782, + 1.158557291897791, + 1.2421219532289738, + 1.3158638484406604, + 1.3861825987702523, + 1.450762393804458, + 1.5102063422491143, + 1.5678243800161544, + 1.6251682260404348, + 1.6716292464865594, + 1.7151689668009984, + 1.755435088106825, + 1.7920800449472067, + 1.8266724882279906, + 1.8601518435947482, + 1.8930350153638453, + 1.9250848774172855, + 1.9572235517317285, + 1.9903661874944014, + 2.022570447022477, + 2.055078452895796, + 2.0880934506908715, + 2.122330578346664, + 2.15866461123757, + 2.1963953276216595, + 2.2370243152175133, + 2.278847503475203, + 2.3204867073438584, + 2.3631674410288195, + 2.4073494602853054, + 2.451241663264259, + 2.4953097573735237, + 2.5397788014105283, + 2.5832132640758574, + 2.627321859696513, + 2.672179946191852, + 2.7182270060143026, + 2.7665467777316457, + 2.816291704063999, + 2.8705622404497277, + 2.929571861087087, + 2.99252319453981, + 3.0623735453840646, + 3.1376643520774383, + 3.216343267746385, + 3.299847663197868, + 3.3899491208748698, + 3.482849375700695, + 3.5831036484864667, + 3.6913679897846046, + 3.8035171898147864, + 3.9225387871201254, + 4.050032560389264, + 4.181438980745696, + 4.318249906501666, + 4.459155651995905, + 4.608287772914404, + 4.760499880534019, + 4.914963744884975, + 5.076347902144622, + 5.240123099284234, + 5.4027019118657496, + 5.567479621773198, + 5.737459031182647, + 5.907947508791681, + 6.081090529806267, + 6.263127347756526, + 6.445007073111551, + 6.628983398764286, + 6.821272284107228, + 7.010893620787833, + 7.203977853603422, + 7.402243835791255, + 7.602581138899236, + 7.805230439447765, + 8.01309451265696, + 8.221852422807364, + 8.433820757497474, + 8.647279369491388, + 8.861585659684101, + 9.08181850967727, + 9.306252053634548, + 9.531414875545613, + 9.759532590099607, + 9.993641587754778, + 10.23174123739043, + 10.466871662435148, + 10.700222546768892, + 10.939381371773377, + 11.176673943003353, + 11.404401041630985, + 11.64138289472096, + 11.881184063747966, + 12.113396873501927, + 12.353177290690343, + 12.5998717836122, + 12.842794898013647, + 13.085699841831085, + 13.338513065865257, + 13.589450205157714, + 13.834399378071131, + 14.089876531234875, + 14.347077091053173, + 14.592908996360181, + 14.841486039645286, + 15.093321437212415, + 15.331556576044584, + 15.574403568768822, + 15.821583107533652, + 16.0611295719606, + 16.297697164385607, + 16.53418646450021, + 16.765386661023303, + 16.990314980255295, + 17.216597429601407, + 17.44552127048095, + 17.66665243205992, + 17.8910406576397, + 18.119733505116766, + 18.336743633297925, + 18.55144023915765, + 18.76852671378836, + 18.98584964248148, + 19.190370507385456, + 19.402717830991467, + 19.620739332169286, + 19.828276315307928, + 20.040357066708093, + 20.254537966505755, + 20.49311640466681, + 20.753235745072647, + 21.013008320752785, + 21.280429705574765, + 21.558215948844328, + 21.836372812850524, + 22.115965984997004, + 22.41933462761023, + 22.711468248149906, + 23.00969163255522, + 23.30703458214062, + 23.58310835796809, + 23.873034749211637, + 24.178178294893403, + 24.47011223597752, + 24.769835527903183, + 25.08583194315802, + 25.386693593331973, + 25.700763811746032, + 26.027037841098014, + 26.340176298684018, + 26.682766453605822, + 27.038233969204494, + 27.380909537241617, + 27.745617367445757, + 28.1070922824339, + 28.448298874907188, + 28.8066269562617, + 29.171678224467673, + 29.518985504304503, + 29.86759547145183, + 30.216972832130267, + 30.54914544592294, + 30.88164712615573, + 31.22100666424289, + 31.55297080947975, + 31.884712721367116, + 32.217118736114884, + 32.545459704568, + 32.878679677904394, + 33.207928653927056, + 33.52813888519988, + 33.84902197186782, + 34.172714721169605, + 34.49377977705521, + 34.81598010816266, + 35.13182488361413, + 35.44826883788044, + 35.77075710724621, + 36.07689771581422, + 36.37378503080216, + 36.6807861390401, + 36.98075973279811, + 37.26767382100874, + 37.56842979834957, + 37.86963955975098, + 38.15969722122062, + 38.45580161464718, + 38.76110016203662, + 39.06199398474091, + 39.36771843696578, + 39.67740872911487, + 39.9855587754359, + 40.29456256903874, + 40.60019229868071, + 40.90327050383104, + 41.21184330531727, + 41.51981952972206, + 41.82999013774019, + 42.14604447812906, + 42.460178188693924, + 42.772951080528365, + 43.09183138662514, + 43.408459982364754, + 43.72615930826093, + 44.053726633883684, + 44.37651136670914, + 44.703720400557195, + 45.04042166885038, + 45.3686570398013, + 45.693127205500424, + 46.02812001940895, + 46.350753614996556, + 46.6729639076944, + 47.00092712608722, + 47.3245376024245, + 47.65438105311737, + 47.98632260625169, + 48.31092154141555, + 48.636701418295544, + 48.96499882148257, + 49.27563619145835, + 49.591945748707886, + 49.91539073525895, + 50.225923925985626, + 50.53254943666014, + 50.84620884637542, + 51.14906282039165, + 51.448422497159065, + 51.752595879656795, + 52.04710583076322, + 52.34230902748567, + 52.63790453084533, + 52.921337805461555, + 53.199494897331725, + 53.47165555686957, + 53.73654889633494, + 53.997737016956535, + 54.25561636060131, + 54.510861381951315, + 54.77029386496579, + 55.06053969883743, + 55.3193383983537, + 55.58082024557244, + 55.85062771619083, + 56.12071725307524, + 56.392055962064916, + 56.66217275660554, + 56.931493530240104, + 57.1966339481428, + 57.44677164563119, + 57.6873530623383, + 57.924220512679625, + 58.15907116976025, + 58.3912630010043, + 58.62377832077256, + 58.851321260818885, + 59.10287487694168, + 59.33504509529673, + 59.57042643500657, + 59.81149397990794, + 60.06278227891432, + 60.322238930259225, + 60.571051984832394, + 60.82080423671204, + 61.08384036148947, + 61.34286503803346, + 61.58794316880902, + 61.8437706439411, + 62.09881775362492, + 62.32089755367982, + 62.53454052056264, + 62.74630175145445, + 62.94457989312166, + 63.130617165692314, + 63.30653276702939, + 63.48291226075136, + 63.64894863152556, + 63.80075249599611, + 63.947766474523085, + 64.08541484176192, + 64.20750007567015, + 64.31397851543635, + 64.40369614470518, + 64.47734175619775, + 64.53155235638658, + 64.56344758980786, + 64.57522459354611, + 64.56784924064979, + 64.54117725777655, + 64.50133789629463, + 64.44727571376464, + 64.3770239006336, + 64.29414330018272, + 64.20319906056727, + 64.09786941692346, + 63.98289957747269, + 63.86021539159947, + 63.72746527155486, + 63.58147624182828, + 63.415167704781815, + 63.23663332833086, + 63.04501831961145, + 62.8398984317355, + 62.62102175495072, + 62.393070935941104, + 62.15185199735371, + 61.89612203648324, + 61.62730159901355, + 61.35261255589393, + 61.06829994514864, + 60.77102648018289, + 60.48047917141674, + 60.18005429956885, + 59.86944303231687, + 59.56562553655119, + 59.25479964282162, + 58.93279964631588, + 58.61608106694816, + 58.294073570021276, + 57.95706660640934, + 57.62876015258999, + 57.30336307418381, + 56.955990486703904, + 56.627564783204384, + 56.30628201828773, + 55.96301696889808, + 55.63436355396282, + 55.319763992937965, + 54.984482804533506, + 54.66441558443428, + 54.352180015388406, + 54.0286580749201, + 53.70719325236333, + 53.3886501726395, + 53.06230401224373, + 52.731668350798024, + 52.412423122362966, + 52.08170047802152, + 51.745636318909945, + 51.41149661568205, + 51.072346262180716, + 50.727779820139986, + 50.38928898735916, + 50.052498885253186, + 49.71281937780201, + 49.37749797819582, + 49.03390404960647, + 48.700251814160616, + 48.35921581537463, + 48.02127885746068, + 47.684205040099805, + 47.34877727967469, + 47.01771160378635, + 46.6802549782342, + 46.34358952010222, + 46.008492299730314, + 45.66983424511466, + 45.33014596992044, + 44.988998076119074, + 44.64970229673532, + 44.30000670789822, + 43.94686821583238, + 43.602196916148266, + 43.24808656120025, + 42.89496174219601, + 42.549242456566404, + 42.195039376330804, + 41.83918424394172, + 41.48919747411654, + 41.12886003408778, + 40.74886684685023, + 40.38811989720975, + 40.02884140177651, + 39.64348857394865, + 39.27526751145392, + 38.91065315121915, + 38.52843839556926, + 38.15225066902699, + 37.78868833241302, + 37.42093369487591, + 37.048781869567144, + 36.688228472261045, + 36.322442865970366, + 35.95616404118417, + 35.58629777277088, + 35.22371972020449, + 34.85993276181598, + 34.49211194094666, + 34.11838919501381, + 33.74769060072603, + 33.372177836474386, + 32.98294533148796, + 32.605988974888945, + 32.23114449570224, + 31.855930457185696, + 31.47490764885328, + 31.107792099615526, + 30.742036242287266, + 30.371554085971116, + 30.0100173229397, + 29.649829556487436, + 29.28690399276509, + 28.92150101741794, + 28.561126082793443, + 28.198323600284166, + 27.83517689781057, + 27.484811670582832, + 27.124325971388696, + 26.766156510232815, + 26.43099554126496, + 26.095146063414553, + 25.766167784679496, + 25.439322157228318, + 25.115069424206542, + 24.794096000709757, + 24.47487619049869, + 24.152300380127528, + 23.83314968040659, + 23.512875548459412, + 23.19206815996017, + 22.868718126091483, + 22.545778659676944, + 22.236157072837628, + 21.92301654821605, + 21.611526983296386, + 21.311079123300285, + 21.008302593247297, + 20.692435674978185, + 20.396246974677336, + 20.103165807568764, + 19.782412327001, + 19.4783316260115, + 19.185830950993875, + 18.871202785834285, + 18.562886050709672, + 18.26154136620148, + 17.94875555199643, + 17.63233703293708, + 17.320291069456587, + 17.00032266578921, + 16.67785560084743, + 16.36205563908135, + 16.042474419225428, + 15.725923824977155, + 15.410000894901648, + 15.094628872283552, + 14.77648574930314, + 14.460395819218052, + 14.142751673486185, + 13.823369410041467, + 13.506447100941761, + 13.184745425880198, + 12.86778818234603, + 12.549026881564068, + 12.228168567008979, + 11.908284167956305, + 11.588478854851386, + 11.266112739400324, + 10.939209275467062, + 10.615200727707855, + 10.296276319492407, + 9.972265014895568, + 9.650100344969468, + 9.338667614876224, + 9.026342017909288, + 8.703826193371327, + 8.401514083771268, + 8.099325816982839, + 7.792379381817953, + 7.494380065916911, + 7.202459416762018, + 6.913678551652247, + 6.623988483081557, + 6.333109610630427, + 6.050653709657182, + 5.766810988370467, + 5.473133881269483, + 5.185415609733411, + 4.905068480871893, + 4.6044260266247985, + 4.312106694023325, + 4.030710209433614, + 3.726784538346991, + 3.419859610385219, + 3.1286423951767772, + 2.819764879529908, + 2.513363454681323, + 2.2128895355849902, + 1.8946201943710554, + 1.6051951040340207, + 1.3158081979557188, + 1.0107166900957267, + 0.7253845666588653, + 0.44549848234501915, + 0.15353634205481423, + -0.1281046415739806, + -0.40572982811506086, + -0.6889670310031285, + -0.9665987965814913, + -1.2404288296019068, + -1.520702291402006, + -1.8017624984197276, + -2.0787265340135628, + -2.355608599093969, + -2.631483375192749, + -2.907848355638494, + -3.1796249548835362, + -3.4412848125260926, + -3.69879347973123, + -3.9459625066219095, + -4.173527906680129, + -4.396660487168673, + -4.604218135217778, + -4.794572865551297, + -4.9704763904342455, + -5.128378907668659, + -5.268002320869248, + -5.388141710743154, + -5.488471018685102, + -5.56785751230851, + -5.62492419998967, + -5.661582132813968, + -5.6759973982339575, + -5.666581855227908, + -5.6344054198887665, + -5.582573105739994, + -5.513781895788568, + -5.426070927740838, + -5.3200222886457045, + -5.199076794136644, + -5.0610631763309755, + -4.8937124820967215, + -4.732086200679933, + -4.560271489259866, + -4.382539473528136, + -4.198374773354525, + -4.007936925954206, + -3.816133258836189, + -3.617903581258127, + -3.4160871601057368, + -3.213608481780186, + -3.0081901879802797, + -2.8020587069395044, + -2.596419055165063, + -2.3928484523809, + -2.190678112623667, + -1.9893057933517218, + -1.7913854641689455, + -1.5936060656188609, + -0.9055332106891132, + -0.7202858792343564, + -0.5381017910878791, + -0.36189036003927605, + -0.19629464373643796, + -0.03529972288378039, + 0.12289807262798322, + 0.2682500300033732, + 0.406924152008886, + 0.5388519785188258, + 0.6729251349545429, + 0.79656391838147, + 0.9065861613852987, + 1.0168516544131518, + 1.1210998984660312, + 1.2170604487497922, + 1.3118797821312187, + 1.4030447200049618, + 1.4847487089507099, + 1.5625214298299035, + 1.6388612267685054, + 1.7088665143980293, + 1.7777265222074548, + 1.844379588015374, + 1.904504983689095, + 1.9617284691656787, + 2.0160884187698387, + 2.0678511700965467, + 2.1159761486962596, + 2.1616371433353097, + 2.2059646616270174, + 2.2490020785144726, + 2.2913435867961907, + 2.3343285040848074, + 2.375243589447204, + 2.415710591879883, + 2.4564812330843515, + 2.497381433608937, + 2.5392208070742384, + 2.5821798466491637, + 2.627702478105555, + 2.673581533360386, + 2.718808036815791, + 2.765642071681866, + 2.813899998343954, + 2.8617301090722487, + 2.910400970166254, + 2.958888707576651, + 3.008884420846659, + 3.060900064688732, + 3.1167167582750577, + 3.1760859876925984, + 3.238122450159414, + 3.3072711932363115, + 3.381902710246488, + 3.4605047088174423, + 3.5470994454358262, + 3.638975419457842, + 3.7344211983582603, + 3.8363684797590283, + 3.9432508962962625, + 4.0557799867542235, + 4.178665348989349, + 4.306950149653362, + 4.440201165874506, + 4.582995041856619, + 4.729542900084111, + 4.878648098764896, + 5.032457236144575, + 5.19284134159112, + 5.351994994915723, + 5.517313565817845, + 5.687524039363754, + 5.854458967695315, + 6.021909599178358, + 6.194905065084231, + 6.370900523239295, + 6.543685470315409, + 6.720218946811099, + 6.899336004380133, + 7.077531798400286, + 7.262264787013468, + 7.462392813182556, + 7.64646670945532, + 7.835299070815758, + 8.024393551725165, + 8.215195676296187, + 8.414057033552687, + 8.616186517126499, + 8.819278416757804, + 9.025451638405203, + 9.228713556298894, + 9.435084481866628, + 9.644681118145497, + 9.854871196128133, + 10.068442891658682, + 10.283523960122878, + 10.497319393428349, + 10.708215498230638, + 10.915984365130619, + 11.123251930592202, + 11.33219643011607, + 11.541963271812863, + 11.744413100437864, + 11.947628061073338, + 12.15730893005468, + 12.363172566586455, + 12.571220587737818, + 12.790676958205008, + 13.012793343422562, + 13.233326001860208, + 13.453757700628822, + 13.67894627842613, + 13.90309718686793, + 14.122800867862784, + 14.344669104077772, + 14.568182815204022, + 14.787521931013131, + 15.003433168402763, + 15.218338458244752, + 15.430876495916666, + 15.639582983358668, + 15.844588520545768, + 16.05174380151191, + 16.259047246035017, + 16.462297162647182, + 16.661347033979755, + 16.860977629761397, + 17.05949013197176, + 17.253111135804968, + 17.44504564465885, + 17.6401583815982, + 17.83519359255791, + 18.029425903284928, + 18.227382487519517, + 18.431599042932586, + 18.63377679978206, + 18.833792647361186, + 19.036284943961576, + 19.244474425587782, + 19.456774302585004, + 19.659814323713807, + 19.877098373594915, + 20.100438703083036, + 20.319917585601303, + 20.543766370264326, + 20.768664805149218, + 20.998345468507342, + 21.235920777755084, + 21.469506739891646, + 21.710129629308224, + 21.955909499200317, + 22.19819034760357, + 22.44649920050249, + 22.707863303552728, + 22.95174793241345, + 23.21081010704054, + 23.47786316387744, + 23.73868761449372, + 24.01880536165217, + 24.296832398886973, + 24.56788949591203, + 24.85556031060897, + 25.142281351469617, + 25.423643007964415, + 25.72464386485637, + 26.01895038167825, + 26.315335770028263, + 26.64082113110321, + 26.96066545597112, + 27.28624599078172, + 27.628947445084588, + 27.953217297777137, + 28.269162393212962, + 28.603487317229146, + 28.933690325584937, + 29.254466570448663, + 29.59050285952364, + 29.92550839868592, + 30.24909657195234, + 30.5770083001913, + 30.905122860465795, + 31.231010423798143, + 31.559262162619206, + 31.88398509689268, + 32.2108119605712, + 32.54232007447706, + 32.872106604835544, + 33.19256010378698, + 33.51571448848831, + 33.84088122133021, + 34.16274371439139, + 34.48012493535317, + 34.79252421156048, + 35.11004664828505, + 35.42708782008047, + 35.726610739928226, + 36.0211962725397, + 36.324234882644504, + 36.61710760027611, + 36.9007061324053, + 37.19828843945955, + 37.49343713484368, + 37.7774137315602, + 38.07035180128131, + 38.37164388866992, + 38.66706211087181, + 38.96897598154521, + 39.27801683983014, + 39.58379605967718, + 39.892441616186375, + 40.20099727596609, + 40.503739711250745, + 40.8108368624679, + 41.12180090546971, + 41.42701005464316, + 41.735725772783354, + 42.04540315179996, + 42.352414388167595, + 42.65640966308489, + 42.96352025542926, + 43.265252950206786, + 43.57210629372062, + 43.87829734685928, + 44.18101684634248, + 44.49111422266982, + 44.80019788610365, + 45.10202019961984, + 45.40680062895141, + 45.71514213481711, + 46.00658506419657, + 46.30552971112497, + 46.604923301718046, + 46.890712312286006, + 47.18432888916051, + 47.4812373152195, + 47.766914703063264, + 48.05462974618402, + 48.34828635492092, + 48.636458523977325, + 48.91389718974907, + 49.20176904214493, + 49.48894937346556, + 49.76999933830532, + 50.05000035979489, + 50.333867718123514, + 50.61099748803371, + 50.88664904079643, + 51.16610820987319, + 51.440624144719024, + 51.71103759327883, + 51.98618737280329, + 52.25737914374822, + 52.5217630297111, + 52.784522883857385, + 53.040372919948936, + 53.287854956033186, + 53.53823351443804, + 53.780852597439655, + 54.02045186356351, + 54.26358486732929, + 54.50591946952668, + 54.75067775552222, + 54.99308269842895, + 55.237332200941026, + 55.48885777538655, + 55.74401608796219, + 56.0034074966469, + 56.26436926298783, + 56.5252578911605, + 56.78774650693654, + 57.052075559431124, + 57.310561620276395, + 57.561755081479596, + 57.81279715033571, + 58.06395005545917, + 58.315590142946945, + 58.559517316828604, + 58.803518975904524, + 59.053411989053515, + 59.30331536726503, + 59.555794626289696, + 59.80293572966091, + 60.06096650364455, + 60.31982084164096, + 60.57144263069977, + 60.824982384716236, + 61.09138043168508, + 61.347393230172294, + 61.59460315790011, + 61.85675367324556, + 62.11327753414165, + 62.345455283874784, + 62.57586327145023, + 62.80557759401787, + 63.009485864983894, + 63.198347631823296, + 63.39957847029329, + 63.591787590451, + 63.76385496827071, + 63.93504345932741, + 64.09366715367625, + 64.2338342111524, + 64.3677806292545, + 64.48918464764402, + 64.59867583680094, + 64.69665705731443, + 64.77725374697798, + 64.83874879562084, + 64.88505916888899, + 64.91489085055541, + 64.93038406380604, + 64.9341319705511, + 64.92233532213571, + 64.89225069458912, + 64.84514281575301, + 64.78244882666036, + 64.70625125679383, + 64.61303344300852, + 64.4996095387883, + 64.3734970535468, + 64.2339227017979, + 64.0691859896756, + 63.88896819814262, + 63.70375365171411, + 63.49316904235379, + 63.27003097567863, + 63.04038520626878, + 62.792939300967944, + 62.52367035463808, + 62.249024343745795, + 61.964051455209635, + 61.66040703004095, + 61.35143480655067, + 61.04253551823063, + 60.72799430745338, + 60.407094720964544, + 60.08204947598009, + 59.75988867394303, + 59.437473814982866, + 59.11102800787768, + 58.78040174762059, + 58.45325357354585, + 58.12015763497961, + 57.780899333531345, + 57.446734731009535, + 57.115655924856334, + 56.76866200668808, + 56.43350146774667, + 56.10827947488392, + 55.76794415355786, + 55.432375413390915, + 55.1116529849876, + 54.776453349765816, + 54.44359453282654, + 54.119817944939314, + 53.78502742488549, + 53.4277132717604, + 53.06139014538398, + 52.68583885032106, + 52.30431773601525, + 51.93287947469784, + 51.55348048905213, + 51.16574006591912, + 50.78389947445136, + 50.40018377617962, + 50.00941020931337, + 49.64340551744632, + 49.29206799133966, + 48.938546084378174, + 48.58867618589109, + 48.23383844633296, + 47.88577328970176, + 47.53023447121266, + 47.173707586527684, + 46.820242424401805, + 46.46781799675155, + 46.103409238991574, + 45.72447732081331, + 45.346780235565554, + 44.97116839295966, + 44.587123004483, + 44.20523034735631, + 43.822082556998055, + 43.441341164791176, + 43.049628719138255, + 42.6594343328787, + 42.28943645633909, + 41.920745700898514, + 41.55799309504139, + 41.1977903715551, + 40.82692552894466, + 40.46146671199581, + 40.10087192633143, + 39.726164387091195, + 39.34589358690573, + 38.98944966303418, + 38.651636567391584, + 38.32425882280544, + 38.01970816131352, + 37.71222590274016, + 37.390523144529, + 37.085873049825175, + 36.78996535301918, + 36.478351726858214, + 36.172612847937394, + 35.873466986720395, + 35.542506328442826, + 35.19681710752306, + 34.84645722701486, + 34.5024150040763, + 34.158944207428334, + 33.81090803333378, + 33.45678865861211, + 33.1121335436967, + 32.769690331014154, + 32.40815465777267, + 32.06706189203102, + 31.73818279646971, + 31.4069414911656, + 31.07141025377262, + 30.740760278913392, + 30.416356646953968, + 30.08528185137061, + 29.759391274916094, + 29.42772033894885, + 29.09610144670529, + 28.75241495438663, + 28.40410558038202, + 28.061581491679252, + 27.711663374722416, + 27.368337363239547, + 27.030615584438536, + 26.687481351701408, + 26.350956695011487, + 26.017128460063248, + 25.680873594593724, + 25.354413419917726, + 25.02105608913142, + 24.683945123823275, + 24.356105780718323, + 24.023412552566047, + 23.683258456495615, + 23.350663617080645, + 23.01876605452908, + 22.679042868844995, + 22.345885916622905, + 22.021623798616123, + 21.68508393173521, + 21.36169283990485, + 21.043670755965216, + 20.718635705571007, + 20.384923576823788, + 20.07480465686862, + 19.762502906204453, + 19.425026897000897, + 19.11439078097833, + 18.795944904723587, + 18.458809071542838, + 18.134303137948027, + 17.813531672569077, + 17.48548662970209, + 17.15539366600941, + 16.833337937069704, + 16.504947576978854, + 16.17856720712977, + 15.858821738650159, + 15.541762267997488, + 15.228637423722681, + 14.917071765386117, + 14.604487895980826, + 14.28627926911162, + 13.974503061860622, + 13.656429371616163, + 13.3404123787466, + 13.023892349615393, + 12.701381914664266, + 12.383701079919026, + 12.064896914940544, + 11.739240492008918, + 11.414799327872279, + 11.091392310492523, + 10.764094984524677, + 10.429069747075674, + 10.099131017199557, + 9.773648377993087, + 9.441144262057035, + 9.110134992705483, + 8.790093031749594, + 8.472448988555438, + 8.142569254349775, + 7.8333889572317865, + 7.527669386290945, + 7.214041748256324, + 6.916003033105072, + 6.619070113737984, + 6.3180704452008225, + 6.018776346591357, + 5.718338982304064, + 5.41570104806967, + 5.1174876762822255, + 4.811089517586735, + 4.501946025743641, + 4.20121277371134, + 3.885178117446997, + 3.578472156205737, + 3.2775196307968795, + 2.967018547400865, + 2.6615713850033176, + 2.362585466607191, + 2.0619598369580623, + 1.7614724045696086, + 1.467291176818494, + 1.1701490216286663, + 0.8837039337661199, + 0.603138431506288, + 0.3177505564621903, + 0.042715205771723413, + -0.22772672857181492, + -0.5037060126876416, + -0.7775078376792488, + -1.0500912699145741, + -1.3228068596113436, + -1.5980246643056533, + -1.8751649877266727, + -2.155724401313098, + -2.4374175534989213, + -2.7204681321512783, + -3.004759790301973, + -3.2825837585752717, + -3.5635196294257505, + -3.844599231918461, + -4.108929472553468, + -4.355539781550006, + -4.602136164130792, + -4.837561129653576, + -5.050913706385881, + -5.255292933767793, + -5.444573000333677, + -5.613724738106135, + -5.764613166766576, + -5.89486343805325, + -6.0012105472892845, + -6.083679178417491, + -6.144279096912507, + -6.181145924893161, + -6.193345038951731, + -6.1810041955283195, + -6.146742981568169, + -6.093689040653491, + -6.020825678996818, + -5.928579732561607, + -5.819909132686005, + -5.693930044611588, + -5.551643259906084, + -5.394657387626238, + -5.223724822466757, + -5.042341800653289, + -4.851204704680763, + -4.650707512509256, + -4.44701709546334, + -4.236353534312547, + -4.020654759030604, + -3.804755671838709, + -3.5849668775342356, + -3.363576250108232, + -3.1454174331024327, + -2.9333303460849955, + -2.705144559208491, + -2.501982563564464, + -2.305897280378726, + -2.1135333152809634, + -1.9252315355328815, + -1.7419106292937618, + -1.5619352282249188, + -1.386481713313186, + -1.2173168293417802, + -1.0522609216836865, + -0.8961551600101378, + -0.7489704980416187, + -0.6036996526193943, + -0.4672034113201273, + -0.33643150036056485, + -0.21182347923938555, + -0.08482572960006235, + 0.03296397525118956, + 0.13803464980561533, + 0.24429856547015677, + 0.3454335683637869, + 0.43954582150569926, + 0.5334954886752733, + 0.6244473203261978, + 0.7063456210966875, + 0.7851896171914984, + 0.8612002936545564, + 0.9318731319943926, + 1.0018181314141354, + 1.0671257523852353, + 1.1258879628822924, + 1.1809616679514416, + 1.2334821353629821, + 1.2812093367658166, + 1.325666385260795, + 1.3686041659870374, + 1.4099076662315462, + 1.4499290517415064, + 1.4907965292561967, + 1.5305527105384111, + 1.5695873487805367, + 1.608453778429702, + 1.6473324628176782, + 1.687414433484031, + 1.729308702492355, + 1.773169058670581, + 1.816219857288633, + 1.859536499174332, + 1.9055744125094838, + 1.9524449696609882, + 2.0002754204736526, + 2.050465902746975, + 2.1034009360950887, + 2.158835107190497, + 2.2189088148105123, + 2.2836575508606796, + 2.3514594579191392, + 2.42645668414064, + 2.5154658448068625, + 2.600699162149884, + 2.6926498157705754, + 2.7892670112848563, + 2.889296569616385, + 2.9946889905899896, + 3.10416519459054, + 3.221796389748498, + 3.346078809395236, + 3.472685600013573, + 3.607533929214433, + 3.7509264135645783, + 3.8963735007702684, + 4.04416873424519, + 4.201493208581886, + 4.358072752952976, + 4.5163945008173805, + 4.682692641802298, + 4.848551319856644, + 5.011137882671261, + 5.180033770078293, + 5.356054272324572, + 5.527107496638038, + 5.706445254492088, + 5.892280888362062, + 6.078415003256876, + 6.267129554359015, + 6.460220463822334, + 6.650792478128393, + 6.844007918761906, + 7.038716912625716, + 7.234618093278297, + 7.432177543885677, + 7.632253280451951, + 7.832501437779651, + 8.036113494446496, + 8.238500622933111, + 8.441959857142116, + 8.649697421859123, + 8.857914540485808, + 9.06784467671421, + 9.279509886787089, + 9.494501098185962, + 9.710581470196464, + 9.925165163460168, + 10.137982635913584, + 10.353671208173067, + 10.567534015319746, + 10.773636502374774, + 10.985118077350945, + 11.200748201140998, + 11.430137892805606, + 11.643173038108484, + 11.8643859833317, + 12.083578785284102, + 12.300526889528768, + 12.524141572316488, + 12.749414702449705, + 12.969373668561387, + 13.191827963013733, + 13.418715946653448, + 13.640801245474163, + 13.86077314267707, + 14.080304952921253, + 14.299583825172823, + 14.516181255782323, + 14.73020382396844, + 14.946936588198518, + 15.163763204325228, + 15.374499965516316, + 15.583758124223097, + 15.817707630037336, + 16.025291150787165, + 16.229280108240037, + 16.436727486302235, + 16.645484611920427, + 16.854201739038114, + 17.0659749294851, + 17.284841724042852, + 17.502460175411226, + 17.71786174047734, + 17.933773055075328, + 18.158336403565595, + 18.38256046813477, + 18.601257332975912, + 18.83665401579923, + 19.0734634686356, + 19.30969532152967, + 19.549601001562625, + 19.791946072332866, + 20.03840718469108, + 20.30439411736261, + 20.569584186003024, + 20.844517190035486, + 21.1204217978466, + 21.394687422977103, + 21.684774478492354, + 21.958034750016054, + 22.244051984744427, + 22.53713143874562, + 22.824205022873294, + 23.10776614129646, + 23.385240858599833, + 23.65797518720824, + 23.945970514931957, + 24.230270875446703, + 24.512673946933806, + 24.813113842738602, + 25.10233557345587, + 25.397884107445652, + 25.71855475117096, + 26.028041548957507, + 26.351343668615986, + 26.68575590513501, + 26.996142230999617, + 27.30395344319394, + 27.629776045724558, + 27.950893244854537, + 28.2611035397097, + 28.5859201923331, + 28.90814021056158, + 29.229602936099422, + 29.553092375862388, + 29.87486064627909, + 30.192607767403327, + 30.51042962659957, + 30.823502634365923, + 31.13375300688445, + 31.45087371269537, + 31.764004553176324, + 32.06766447014032, + 32.39341599006021, + 32.718837290770544, + 33.03510027911376, + 33.3463992613523, + 33.64756612922129, + 33.94617542466793, + 34.255050344476714, + 34.55131838602722, + 34.841364384051616, + 35.13445191695125, + 35.41799046189206, + 35.69620731174678, + 35.973741706683825, + 36.261288494959075, + 36.54478247218361, + 36.82695666689895, + 37.116922815166525, + 37.41256072421824, + 37.707831468103656, + 38.00872071365846, + 38.31329239861413, + 38.6179417348102, + 38.92529250682758, + 39.23395592716675, + 39.53843395393223, + 39.84719625293089, + 40.15980982992883, + 40.47009087675628, + 40.7839357535985, + 41.10095171075927, + 41.41825747162264, + 41.73496441055351, + 42.054541753462495, + 42.40265093370169, + 42.722656445858824, + 43.03857658584681, + 43.34864572402307, + 43.66011327126799, + 43.962136639181885, + 44.25243848245562, + 44.544883366892684, + 44.83171962686003, + 45.09653897255874, + 45.36768906546432, + 45.637221438401646, + 45.88882581382236, + 46.14897988405553, + 46.41622086873738, + 46.67607099653956, + 46.93944312785133, + 47.2048915937463, + 47.47262414790793, + 47.746249220992354, + 48.01267618730963, + 48.28041246564395, + 48.56134167021955, + 48.83708002400132, + 49.10976134983403, + 49.38936506870274, + 49.66653409358757, + 49.9388924462077, + 50.218316015606185, + 50.4995795949478, + 50.77236879297137, + 51.050803173116705, + 51.33342612259046, + 51.607561540700296, + 51.87974732198954, + 52.151611620542646, + 52.41284562631809, + 52.67546485613451, + 52.936004070807655, + 53.193201383713294, + 53.45457919581241, + 53.71845973642336, + 53.98525718826073, + 54.25023885372703, + 54.52055892070706, + 54.7986588253103, + 55.08004421599197, + 55.362986041574054, + 55.64904672366078, + 55.934471099982424, + 56.22135277492174, + 56.503781796397305, + 56.77773502457396, + 57.05089683628028, + 57.32428101234249, + 57.59573833184962, + 57.85666623944034, + 58.12154010965457, + 58.391645423184535, + 58.657362866016065, + 58.919849929034385, + 59.187307549871846, + 59.46034189639111, + 59.72105673151717, + 59.97064623049739, + 60.229233568362766, + 60.48017833241788, + 60.70828653434588, + 60.94601499059789, + 61.18950379361661, + 61.413769014146204, + 61.62721584709056, + 61.83880244151634, + 62.04472677191079, + 62.23085377371617, + 62.40331467063941, + 62.58307273001009, + 62.7575633834552, + 62.91572538400384, + 63.07009673391234, + 63.21861885140278, + 63.3523820611257, + 63.47982287601544, + 63.59737939749105, + 63.702644157699, + 63.797777698533366, + 63.88024453387794, + 63.944304152278626, + 63.99392725900502, + 64.03032182735477, + 64.05176875652805, + 64.06237210631396, + 64.06015352266682, + 64.04193750864499, + 64.00772164837375, + 63.96002942127532, + 63.898873163966506, + 63.82465309936775, + 63.733687949043016, + 63.62518887593727, + 63.509547544666844, + 63.375653174297796, + 63.21973625822764, + 63.05705469971158, + 62.88178110943676, + 62.68109407174189, + 62.475897362132514, + 62.258471396252645, + 62.0225423698425, + 61.771100803914905, + 61.51068596185073, + 61.23617819214634, + 60.94791909314268, + 60.65523709365595, + 60.355634634359774, + 60.05106288924525, + 59.73772692929278, + 59.414918127434696, + 59.088021249379125, + 58.76118062644071, + 58.42625361610826, + 58.08605063037285, + 57.751000659041715, + 57.40694454161398, + 57.05239679798535, + 56.70208412110874, + 56.35877036115654, + 56.0121654229517, + 55.66903072582529, + 55.34031550701341, + 55.004413038414384, + 54.663170850421764, + 54.34097856517889, + 54.011614757336964, + 53.67759462784281, + 53.35820630982758, + 53.03000900966272, + 52.691812770745585, + 52.362577935168794, + 52.02487748232644, + 51.68148221838634, + 51.343946761468054, + 51.00731364943348, + 50.658509395291404, + 50.3149963058302, + 49.97429120791977, + 49.62406996975568, + 49.28316674858516, + 48.94741734527262, + 48.60937152840948, + 48.2738599212006, + 47.93615200607705, + 47.597865261738406, + 47.265035203957154, + 46.92330600016169, + 46.58334572730593, + 46.24421300146834, + 45.90481473770937, + 45.564814098548695, + 45.222948283602726, + 44.88293613593048, + 44.54081318129575, + 44.1992418322938, + 43.85576555504636, + 43.51257238337112, + 43.13742224619705, + 42.79627412979432, + 42.47542429946151, + 42.155481308622136, + 41.83331146430156, + 41.51786731340956, + 41.196961636232764, + 40.86971653351226, + 40.551942732000285, + 40.23136807544322, + 39.89682062544872, + 39.55564858254047, + 39.219208384251445, + 38.86794395491559, + 38.500192869860705, + 38.15303873942999, + 37.80347293953438, + 37.439323163349925, + 37.08651469954306, + 36.746095077791125, + 36.40122845765831, + 36.05496445755603, + 35.7360019126959, + 35.413045291149125, + 35.0952853451161, + 34.77529491296396, + 34.45407105823076, + 34.142722876688296, + 33.82955356132992, + 33.51061655691465, + 33.19173457697036, + 32.88096345347836, + 32.54827392697, + 32.20498156300351, + 31.877355956071632, + 31.546283377741254, + 31.216964779996715, + 30.887743410182694, + 30.55784703657244, + 30.23722634217426, + 29.910279100908483, + 29.58723844771856, + 29.25845221091206, + 28.92811986655665, + 28.598642621370384, + 28.261944494174124, + 27.92880745710866, + 27.5940510878878, + 27.253396735536025, + 26.92044177453328, + 26.583884060950933, + 26.235062442156472, + 25.89736598135097, + 25.55855684518251, + 25.214662121806352, + 24.878568754466276, + 24.53942263294736, + 24.206942890801013, + 23.871915926423387, + 23.534805604967126, + 23.201299966915197, + 22.86268519216118, + 22.526700575076095, + 22.19926147072557, + 21.865783484718555, + 21.535510160770436, + 21.220041175085377, + 20.896734430871327, + 20.576951269525935, + 20.27149008635767, + 19.95001726982173, + 19.626571553667095, + 19.32199223551015, + 18.998102712291804, + 18.665971402492307, + 18.356704910527252, + 18.03656786081625, + 17.707133069995464, + 17.38983255981904, + 17.07158393796357, + 16.738792722458758, + 16.416040303002166, + 16.0944023144123, + 15.729914921947158, + 15.407543335222126, + 15.090145385069743, + 14.768604332931492, + 14.448150227220925, + 14.131861963159732, + 13.806758147170486, + 13.486913201573813, + 13.162810485908063, + 12.83269625452117, + 12.500141654542965, + 12.167289543245012, + 11.834431447760407, + 11.496983854387905, + 11.15779818431299, + 10.82129093851567, + 10.483207713624981, + 10.140754572101255, + 9.798951610127345, + 9.462586139396949, + 9.121803117335823, + 8.7865083666709, + 8.453853150389874, + 8.120510152478584, + 7.789907493059814, + 7.464405394020024, + 7.139228377455467, + 6.808466691090132, + 6.488017501892993, + 6.1701321648956045, + 5.855051707521304, + 5.542533110306519, + 5.231328451415327, + 4.9288739455715165, + 4.625884119175401, + 4.322361873902274, + 4.020552023145748, + 3.728283765647613, + 3.4334918939376013, + 3.1511300130188244, + 2.883878458666854, + 2.6097050245238997, + 2.326947643444119, + 2.053568866195254, + 1.7856872030207225, + 1.5022966690135036, + 1.2264350621945965, + 0.9590449531241733, + 0.6745057266113504, + 0.38829202874258334, + 0.10795474061330454, + -0.18155047416974424, + -0.45739207773139845, + -0.7282433435874759, + -1.0077589999534862, + -1.2842548289649247, + -1.5578548031766535, + -1.8343055538706883, + -2.1030963701494088, + -2.3666402507641, + -2.632814120824226, + -2.896756056793806, + -3.1680736586950413, + -3.443784790763174, + -3.716246693331426, + -3.98903129973996, + -4.264097397811469, + -4.534033968659492, + -4.795089790007558, + -5.051376274255919, + -5.303895251400505, + -5.537556563005276, + -5.754773602886346, + -5.961115804552593, + -6.145027749943365, + -6.3120905789231845, + -6.460477047508187, + -6.583998216061229, + -6.689171298728174, + -6.770647650232525, + -6.828816544846511, + -6.86778534563269, + -6.8861866592681835, + -6.882417746013902, + -6.8576845715567085, + -6.814432817882744, + -6.75543987226458, + -6.678612733234952, + -6.583381516191917, + -6.473655005318456, + -6.348797261087411, + -6.2084892099714555, + -6.0557130246369635, + -5.890417298559696, + -5.715535869755915, + -5.532418892134846, + -5.340326721043689, + -5.143240411797461, + -4.939733838251594, + -4.726426010942679, + -4.50992914779845, + -4.292618282379692, + -4.072099645064109, + -3.8502220065756707, + -3.6316662974271052, + -3.416556018566003, + -3.2009806902244153, + -2.991767938284576, + -2.7853588248105403, + -2.5769233373267415, + -2.3756204917167927, + -2.1772858789223757, + -1.9844038384257254, + -1.7983641050915198, + -1.6187250602067969, + -1.4484440080770205, + -1.29011517248927, + -1.134602049819094, + -0.9904344058338127, + -0.857363447720482, + -0.7318187582439283, + -0.6064976505864388, + -0.48891576061274666, + -0.38715534828389414, + -0.28646427326372836, + -0.1909542037827831, + -0.10368299823231786, + -0.018553371252633608, + 0.06463429017684078, + 0.1390380194409851, + 0.20934035449305566, + 0.2777317514903072, + 0.3401867057762835, + 0.4012298409357635, + 0.4605596181628006, + 0.5143245497573187, + 0.5659180276806073, + 0.6152387453007909, + 0.6611055791572242, + 0.7037442757468706, + 0.7455801536710408, + 0.786713000517608, + 0.827177839751327, + 0.8687379450620145, + 0.9092409628232775, + 0.949216809461107, + 0.9891701292255028, + 1.0293815414411287, + 1.0705505066574867, + 1.1127814314610136, + 1.1570346192254346, + 1.2022044631299016, + 1.2470801233833706, + 1.292623051597733, + 1.340348799381267, + 1.387982809906152, + 1.4365695678226016, + 1.4865182910651291, + 1.5382550363541274, + 1.5918681396933239, + 1.6497744895756554, + 1.7114060323854448, + 1.7752610977110548, + 1.845267095203342, + 1.920949269530587, + 1.9993213411102517, + 2.083360934567576, + 2.171719803486823, + 2.262854406091134, + 2.3591318486611077, + 2.4597473028065107, + 2.565087966806386, + 2.6801691172377424, + 2.7990119371914925, + 2.922477408045615, + 3.055248355948018, + 3.1928837054998023, + 3.331659540040816, + 3.477005691493211, + 3.628130493964792, + 3.7791794101816674, + 3.938052200885702, + 4.1029681181648545, + 4.265166159707468, + 4.429389935933034, + 4.600991294680711, + 4.773744846492555, + 4.946782151343482, + 5.131815072976966, + 5.320909050205132, + 5.510837901260894, + 5.708581679614273, + 5.9045603981233405, + 6.103769293302831, + 6.308107878661441, + 6.513861516247532, + 6.721052618320775, + 6.933156108092944, + 7.146037729817484, + 7.359723997181099, + 7.571971367930326, + 7.783876837642502, + 8.000297944154742, + 8.217121046863822, + 8.4328366714951, + 8.651733360271738, + 8.874584811357723, + 9.098109026339534, + 9.316791388353957, + 9.532107437735919, + 9.74977462950637, + 9.96545948088208, + 10.172108612711238, + 10.383703116335342, + 10.598463408079777, + 10.807137295600814, + 11.01834403255542, + 11.237105672108077, + 11.45938910265045, + 11.694453233417244, + 11.935146118440368, + 12.176634413009975, + 12.414186156925892, + 12.654512182987249, + 12.898073798084962, + 13.138586370133297, + 13.379244009751835, + 13.621404584695183, + 13.859684507409824, + 14.087126069314799, + 14.312808041347102, + 14.540350062327564, + 14.771487483868926, + 14.996304343333364, + 15.218878398441973, + 15.444254146440244, + 15.66426412960093, + 15.879454639517009, + 16.092588744321706, + 16.29663812090623, + 16.50016121673227, + 16.707028597458546, + 16.92048582846289, + 17.13459210200239, + 17.34647026114372, + 17.55853301916839, + 17.778105018460604, + 18.028276016859294, + 18.246186767261264, + 18.480483505807722, + 18.726487737277626, + 18.96924048155895, + 19.212372881909864, + 19.465111884808394, + 19.71994378629688, + 19.98105056027148, + 20.2390508085983, + 20.504147576103353, + 20.781186065152237, + 21.060760345808834, + 21.38406990350752, + 21.67371646670524, + 21.96909510997013, + 22.302994353914077, + 22.613678027648195, + 22.932973776850208, + 23.254471341321885, + 23.58085762918641, + 23.904233486232176, + 24.22900502407487, + 24.566036645480807, + 24.89448025962728, + 25.24375419601947, + 25.6063024328597, + 25.96076856734515, + 26.331696345587428, + 26.696650391537958, + 27.04078515510014, + 27.39510893461458, + 27.745195463582213, + 28.082773135929116, + 28.43313705967818, + 28.78236167525347, + 29.115106018627642, + 29.450376123914733, + 29.79000032108117, + 30.116754031823966, + 30.442039031638664, + 30.772894481308473, + 31.099415796827778, + 31.42900661434075, + 31.748819040548845, + 32.07116720017948, + 32.39702309037348, + 32.72376709364862, + 33.04436735521042, + 33.35863885731298, + 33.68016402220356, + 33.990388710534916, + 34.28875239772071, + 34.58601787175292, + 34.88008462645111, + 35.169653165845155, + 35.46034703240285, + 35.75372787289096, + 36.04204450288758, + 36.33252700812174, + 36.627405500986455, + 36.92614551777965, + 37.225004367777984, + 37.53009329890057, + 37.83865505582688, + 38.14487269270122, + 38.45424291207142, + 38.7626707813245, + 39.06611515039217, + 39.372528971759216, + 39.682028446888914, + 39.986941682001394, + 40.2943528099418, + 40.60500112353574, + 40.9111971494637, + 41.21643613954518, + 41.52183461422509, + 41.82336247585669, + 42.12594957164481, + 42.431568078034495, + 42.732452693405065, + 43.03610774299223, + 43.34058176162709, + 43.63944667135497, + 43.93397494702619, + 44.23483443695702, + 44.526262421000524, + 44.81135461227428, + 45.110038059412005, + 45.39688489018558, + 45.6798581782165, + 45.975107573356034, + 46.2636051081498, + 46.54532332699521, + 46.83706628638965, + 47.131593701259405, + 47.41773361933465, + 47.7032721229727, + 48.00243938622417, + 48.29648060254163, + 48.58440807891567, + 48.88103139978401, + 49.174589368443804, + 49.457142751249826, + 49.7459033573279, + 50.03736053441394, + 50.317935962213674, + 50.60229173889855, + 50.8913117585073, + 51.16937300756991, + 51.44229372642988, + 51.71542210894189, + 51.979756929036164, + 52.24440458458036, + 52.49971992022472, + 52.75706688514533, + 53.015035777834115, + 53.27214720638787, + 53.53475543268456, + 53.79381461708486, + 54.05630492363875, + 54.326118265064665, + 54.60011560409699, + 54.872355961295355, + 55.148151379951244, + 55.424350400700845, + 55.69750527055456, + 55.97335606190813, + 56.24031711380249, + 56.498488847217565, + 56.78287865877448, + 57.04451314855204, + 57.29250903361896, + 57.533400724152635, + 57.78434859485366, + 58.032422836994975, + 58.27752003751181, + 58.51726800072292, + 58.76525461844545, + 59.011705439279275, + 59.250407998490516, + 59.48491623294628, + 59.72897912446549, + 59.972630493365244, + 60.202696581880694, + 60.44000228169704, + 60.685867582313556, + 60.91811852354203, + 61.13633107503039, + 61.35425769867261, + 61.56806531052361, + 61.759467585993, + 61.93565015021401, + 62.11793197847979, + 62.29301749252574, + 62.451852740240966, + 62.607906185266025, + 62.75875784698378, + 62.89694333011973, + 63.02889958224118, + 63.15058677272968, + 63.26062184058398, + 63.36012094084811, + 63.44651795492295, + 63.512435015827144, + 63.56175265996502, + 63.59612559748676, + 63.6139636745057, + 63.61920877753554, + 63.60918692054274, + 63.58169243764771, + 63.53681808773292, + 63.476313820296994, + 63.40188017895111, + 63.31448327956754, + 63.208480320222144, + 63.08531006735948, + 62.955774402603716, + 62.806198246255455, + 62.63558241796377, + 62.46324563778636, + 62.271752179674195, + 62.061288532058775, + 61.8492120682386, + 61.624942643909264, + 61.37761140408682, + 61.12413294527372, + 60.8666282038319, + 60.59385559353855, + 60.311984368264206, + 60.02862753649854, + 59.741672577266954, + 59.45478316534175, + 59.16092316074118, + 58.859693043350205, + 58.56287019097253, + 58.26482147374656, + 57.95522017665791, + 57.650224200081425, + 57.34455620366391, + 57.027352770072554, + 56.7090451438743, + 56.39741000767495, + 56.08112548351126, + 55.749804992901055, + 55.43610825331594, + 55.125283269120104, + 54.79827422318538, + 54.4802907353971, + 54.17260545704457, + 53.84856460657545, + 53.53055109599369, + 53.21869712094296, + 52.893553583416875, + 52.569814609773815, + 52.25010259967469, + 51.92023912884787, + 51.58519350867348, + 51.2578816763553, + 50.92415847002732, + 50.581400355844856, + 50.2429351689552, + 49.90132558365967, + 49.55239643476251, + 49.20796724575674, + 48.86529888300375, + 48.519804532655584, + 48.176728742364745, + 47.82713059127643, + 47.485059053942166, + 47.13596090792385, + 46.78452322104806, + 46.435140779581126, + 46.08719025439868, + 45.743216475898976, + 45.39081995533591, + 45.04121833354553, + 44.694500312451474, + 44.34189687025481, + 43.98875569270595, + 43.63696621092538, + 43.28904975206391, + 42.93210859319833, + 42.57719472032346, + 42.22509506788287, + 41.86773079782118, + 41.517387733562614, + 41.16389637183546, + 40.80148189677796, + 40.44792571317824, + 40.09447148864406, + 39.72075955718182, + 39.353361693500396, + 39.00343699756572, + 38.62693972049357, + 38.24908491098979, + 37.891951044162376, + 37.52068890096244, + 37.13811628220774, + 36.778832146781994, + 36.420901176268664, + 36.04092968922288, + 35.6788090050402, + 35.31765065984594, + 34.94985814412416, + 34.58063848062147, + 34.21981027035386, + 33.85920299185756, + 33.49507600577225, + 33.12545685001016, + 32.76296258944008, + 32.4106400529251, + 32.0436692088269, + 31.684299499163878, + 31.331659780563903, + 30.978727922111222, + 30.617596108427197, + 30.267483899637472, + 29.920594538435076, + 29.56670028832235, + 29.215389264114734, + 28.855647360182086, + 28.492188927135437, + 28.12437997485845, + 27.760720804476456, + 27.394600970703802, + 27.027424989947484, + 26.670031555011715, + 26.305739869999925, + 25.94297801615253, + 25.58850395515252, + 25.26607519299904, + 24.964618799043013, + 24.66328955106067, + 24.364075989673783, + 24.067192810022544, + 23.772658422171926, + 23.475670593136233, + 23.17585032961566, + 22.88372773926903, + 22.59221182072908, + 22.272041181378697, + 21.954288912381646, + 21.63958880821498, + 21.317313051285886, + 21.007785445761705, + 20.702385345197655, + 20.379239878643816, + 20.07181985899018, + 19.775592479197925, + 19.453773846032266, + 19.161181854327836, + 18.896776633797465, + 18.61113212252427, + 18.330368735674178, + 18.062388169820455, + 17.785330659556053, + 17.50237019474772, + 17.229485267472764, + 16.955229994979153, + 16.67794388292299, + 16.397473415861125, + 16.11770674218455, + 15.836274600531612, + 15.55455783900755, + 15.276293479439436, + 14.99232603740878, + 14.711762085015975, + 14.427112464142356, + 14.143762146137949, + 13.86540619453985, + 13.54640470783924, + 13.218474134346373, + 12.888380401905051, + 12.55339307780027, + 12.220700617514062, + 11.890403734415067, + 11.558441079845426, + 11.219822790932099, + 10.876110811319919, + 10.542965475924149, + 10.231556891235483, + 9.925105122111749, + 9.621698622249122, + 9.327206339329758, + 9.026184834278407, + 8.722788765696748, + 8.434323294820636, + 8.14264940109942, + 7.85014377391896, + 7.56348646785636, + 7.26531865586253, + 6.965573743396781, + 6.7364189552556635, + 6.436357495989647, + 6.132640635374989, + 5.842124573901207, + 5.541700699838323, + 5.232434186396392, + 4.9361583962613125, + 4.628812172934618, + 4.330646270748619, + 4.049697558417797, + 3.7601718815017264, + 3.4637925797563422, + 3.175074741436031, + 2.886257553207683, + 2.5887426562212403, + 2.299066787187788, + 2.0035672417404045, + 1.7111503304233877, + 1.4303365975998472, + 1.1406978751850647, + 0.8562919541469354, + 0.5817256903956658, + 0.30849749626210543, + 0.035742596280797845, + -0.2361472716204736, + -0.501812448884666, + -0.7684478878070887, + -1.0346126138753036, + -1.3013148706669555, + -1.56933918472811, + -1.835013785014885, + -2.106475866160406, + -2.37797946708163, + -2.642838788443494, + -2.9107729213645386, + -3.180816207389365, + -3.438567332171064, + -3.680366455465112, + -3.9303736482247142, + -4.180064680475931, + -4.409136441251674, + -4.624129182196215, + -4.830739875012404, + -5.015453027440241, + -5.184961146387359, + -5.338237010945065, + -5.470848876488653, + -5.586274615163125, + -5.6895046437444385, + -5.761137836515069, + -5.816179616407459, + -5.853069331812829, + -5.869807017353507, + -5.866915426439278, + -5.845749744437026, + -5.80821207783152, + -5.754127551244888, + -5.683173784825192, + -5.510167634079095, + -5.408909445425552, + -5.292340821777165, + -5.162216398550747, + -5.021847685901615, + -4.870151776422177, + -4.711641616236854, + -4.547608675196245, + -4.373845339341901, + -4.196082566789811, + -4.014873357699236, + -3.8265568191341397, + -3.638090298356028, + -3.4490127774672006, + -3.2564712067299926, + -3.06502833648855, + -2.8755967041412127, + -2.6890411057661283, + -2.5056247231174287, + -2.3233842588209637, + -2.1462542412655408, + -1.9736918837031894, + -1.803009813616574, + -1.6355752910803116, + -1.4732049627363617, + -1.314577095065891, + -1.1615305302164751, + -1.0151283115855734, + -0.8739680112872652, + -0.7433523130433113, + -0.6180819929762711, + -0.49539272370385756, + -0.38261310656961955, + -0.27432990210811736, + -0.17256456613616444, + -0.0698907934648858, + 0.025478337233864945, + 0.10989054325316672, + 0.19449855120799486, + 0.27423439875930544, + 0.3481185038823451, + 0.4206747079867086, + 0.49075149973324783, + 0.5550549612014197, + 0.6139736519331291, + 0.6703282447993555, + 0.7216402537087765, + 0.7699003045023958, + 0.815827484837417, + 0.8564383951876848, + 0.8930150913731605, + 0.9272432818661582, + 0.9576201906054729, + 0.9870251551619573, + 1.0156126500363718, + 1.0447276861828458, + 1.075209174360083, + 1.1063146996624507, + 1.1370235576398728, + 1.1656018972030031, + 1.1935135264976722, + 1.2203562748998997, + 1.246738046811861, + 1.2736495406900918, + 1.3014027357995102, + 1.358087701911475, + 1.3880244384467904, + 1.419513582859927, + 1.4520385777138551, + 1.4873453402515704, + 1.5247633158349356, + 1.562106361039703, + 1.603338540357024, + 1.647070752171706, + 1.6947591215192284, + 1.7468546225711385, + 1.8033383247060628, + 1.866125860687536, + 1.9334541780063867, + 2.007925034773766, + 2.091817630096701, + 2.1822125278852806, + 2.2836110754512413, + 2.3938072956317837, + 2.510889897549979, + 2.6375668722268593, + 2.7742051203855462, + 2.921406637385945, + 3.0803495810335297, + 3.250477206672981, + 3.4292496246264745, + 3.623319154106817, + 3.83003409477385, + 4.046213141283251, + 4.278602715992718, + 4.523746725741298, + 4.7762099305664325, + 5.032608170070021, + 5.333979472218956, + 5.616808252059614, + 5.902257349340332, + 6.2029375814380305, + 6.513747982814721, + 6.822335880089604, + 7.140833540054166, + 7.468767047961354, + 7.798398607387442, + 8.13203567731275, + 8.474694577031805, + 8.821338472931537, + 9.172007587376124, + 9.528492588356098, + 9.891306398575036, + 10.255789691225026, + 10.625329708347609, + 10.996952463027247, + 11.370876801480476, + 11.748790541600247, + 12.133270827594714, + 12.516976201987678, + 12.905508491832617, + 13.292099907931657, + 13.685612537839273, + 14.069238670694848, + 14.452370930332016, + 14.844482194210325, + 15.232004869334297, + 15.61076352732441, + 15.968329346719006, + 16.355697599847378, + 16.73779927785946, + 17.120548425419734, + 17.500561245132975, + 17.88099957327373, + 18.24488306422906, + 18.60834747070571, + 18.97773249088594, + 19.33774552160794, + 19.695810267743, + 20.051719174013048, + 20.402652181864873, + 20.748812670433367, + 21.070143922532612, + 21.389038137456005, + 21.69329242274018, + 21.969758916698183, + 22.249711727567828, + 22.508849984132087, + 22.752312955673336, + 22.99269459367493, + 23.211214675033723, + 23.4053173992618, + 23.602523156661245, + 23.77980927032106, + 23.933299088651065, + 24.08567418996952, + 24.220316114452203, + 24.33496367289798, + 24.4456645581303, + 24.539797298984702, + 24.62210589232148, + 24.690297605278072, + 24.74375990397271, + 24.790631714533415, + 24.831336910894436, + 24.86577514279673, + 24.898253253186166, + 24.930656370985364, + 24.963648700003624, + 24.995714731870738, + 25.005661187952445, + 25.01410190907516, + 25.02158438394257, + 25.029132689257356, + 25.035729046708546, + 25.041477585003094, + 25.0470777358424, + 25.052245408553183, + 25.056732527740117, + 25.060431762227783, + 25.094678339374095, + 25.132813337741332, + 25.17152405113053, + 25.210957592363897, + 25.25106678397374, + 25.28398351670111, + 25.325460961044023, + 25.36753035197118, + 25.41078936625082, + 25.45505144985349, + 25.465871791115084, + 25.472901983372125, + 25.480177327515246, + 25.487408108124246, + 25.494626655925757, + 25.502031489439943, + 25.50936516406744, + 25.516762682825803, + 25.524243141759463, + 25.53175572893784, + 25.55720569168713, + 25.584709697353798, + 25.612343385639903, + 25.63993883029349, + 25.66756661466328, + 25.69523046840099, + 25.72288781255104, + 25.75059128363196, + 25.77831851905882, + 25.806152510085287, + 25.815989333208538, + 25.824030105553163, + 25.83215595124888, + 25.840177058754218, + 25.84810762637963, + 25.856227044856343, + 25.864377482842592, + 25.872448534934318, + 25.880711399748133, + 25.888912607922236, + 25.934648372595436, + 25.985273705841266, + 26.03588121201844, + 26.086293021992187, + 26.13639857803408, + 26.186447094074175, + 26.23663204373448, + 26.286584584062055, + 26.33630277959924, + 26.386557467787203, + 26.397176568353146, + 26.403262376314263, + 26.409197421036534, + 26.414859713730827, + 26.420515684708143, + 26.4261463436701, + 26.431842552375098, + 26.438154411630492, + 26.443953536438645, + 26.449634727571773, + 26.451168133121342, + 26.452618420038505, + 26.453840337168376, + 26.45507357710075, + 26.45654756357641, + 26.45796410577846, + 26.459256326940025, + 26.46060844477516 + ], + "yaxis": "y" + }, + { + "mode": "markers", + "showlegend": false, + "type": "scatter", + "x": [ + -36.829195933875525, + -76.14891175101936, + -3.5940645335563204, + -34.912059375843626 + ], + "y": [ + 26.43059833243257, + 22.861480398725924, + -13.507485368311604, + 72.42462600701336 + ] + } + ], + "layout": { + "legend": { + "tracegroupgap": 0 + }, + "margin": { + "b": 0, + "l": 0, + "r": 0, + "t": 0 + }, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "heatmapgl": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmapgl" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + }, + "xaxis": { + "anchor": "y", + "domain": [ + 0, + 1 + ], + "title": { + "text": "x" + } + }, + "yaxis": { + "anchor": "x", + "domain": [ + 0, + 1 + ], + "scaleanchor": "x", + "scaleratio": 1, + "title": { + "text": "y" + } + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "fig = px.scatter(x=positions[:,0],y=positions[:,1])\n", + "fig.add_scatter(x=landmarks[:,0], y=landmarks[:,1], mode=\"markers\", showlegend= False)\n", + "fig.update_layout(margin=dict(l=0, r=0, t=0, b=0))\n", + "fig.update_yaxes(scaleanchor = \"x\", scaleratio = 1)\n", + "fig.show()" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "array([[-36.82919593, 26.43059833],\n", + " [-76.14891175, 22.8614804 ],\n", + " [ -3.59406453, -13.50748537],\n", + " [-34.91205938, 72.42462601]])" + ] + }, + "execution_count": 11, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "landmarks" + ] + } + ], + "metadata": { + "interpreter": { + "hash": "341996cd3f3db7b5e0d1eaea072c5502d80452314e72e6b77c40445f6e9ba101" + }, + "kernelspec": { + "display_name": "Python 3.8.12 ('nbdev')", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.12" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +} From cf5e3729e085ae63453073ed5391bf0b23a7aecc Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 19 Mar 2022 15:19:25 -0400 Subject: [PATCH 091/116] Fixed parsing error and cleaned up --- examples/RangeISAMExample_plaza2.cpp | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/examples/RangeISAMExample_plaza2.cpp b/examples/RangeISAMExample_plaza2.cpp index bf30cfbb7..aa61ffc6c 100644 --- a/examples/RangeISAMExample_plaza2.cpp +++ b/examples/RangeISAMExample_plaza2.cpp @@ -67,10 +67,10 @@ using gtsam::tictoc_print_; namespace NM = gtsam::noiseModel; -// data available at -// http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/ Datafile -// format (from -// http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html) +// Data is second UWB ranging dataset, B2 or "plaza 2", from +// "Navigating with Ranging Radios: Five Data Sets with Ground Truth" +// by Joseph Djugash, Bradley Hamner, and Stephan Roth +// https://www.ri.cmu.edu/pub_files/2009/9/Final_5datasetsRangingRadios.pdf // load the odometry // DR: Odometry Input (delta distance traveled and delta heading change) @@ -99,8 +99,7 @@ std::vector readTriples() { std::ifstream is(data_file.c_str()); while (is) { - double t, sender, range; - size_t receiver; + double t, range, sender, receiver; is >> t >> sender >> receiver >> range; triples.emplace_back(t, receiver, range); } @@ -112,10 +111,12 @@ std::vector readTriples() { int main(int argc, char** argv) { // load Plaza2 data std::list odometry = readOdometry(); - // size_t M = odometry.size(); + size_t M = odometry.size(); + std::cout << "Read " << M << " odometry entries." << std::endl; std::vector triples = readTriples(); size_t K = triples.size(); + std::cout << "Read " << K << " range triples." << std::endl; // parameters size_t minK = @@ -149,7 +150,7 @@ int main(int argc, char** argv) { // We will initialize landmarks randomly, and keep track of which landmarks we // already added with a set. std::mt19937_64 rng; - std::normal_distribution normal(0.0, 1.0); + std::normal_distribution normal(0.0, 100.0); std::set initializedLandmarks; // set some loop variables @@ -184,6 +185,7 @@ int main(int argc, char** argv) { newFactors.emplace_shared>( i, landmark_key, range, rangeNoise); if (initializedLandmarks.count(landmark_key) == 0) { + std::cout << "adding landmark " << j << std::endl; double x = normal(rng), y = normal(rng); initial.insert(landmark_key, Point2(x, y)); initializedLandmarks.insert(landmark_key); @@ -199,6 +201,7 @@ int main(int argc, char** argv) { // Check whether to update iSAM 2 if ((k > minK) && (countK > incK)) { if (!initialized) { // Do a full optimize for first minK ranges + std::cout << "Initializing at time " << k << std::endl; gttic_(batchInitialization); gtsam::LevenbergMarquardtOptimizer batchOptimizer(newFactors, initial); initial = batchOptimizer.optimize(); From 41094dce0be30ea820b0deb4dc03d68da13936b3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 19 Mar 2022 15:19:33 -0400 Subject: [PATCH 092/116] Added reference --- .../examples/RangeISAMExample_plaza2.ipynb | 16436 ++++++++-------- 1 file changed, 8223 insertions(+), 8213 deletions(-) diff --git a/python/gtsam/examples/RangeISAMExample_plaza2.ipynb b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb index e62423695..f11636606 100644 --- a/python/gtsam/examples/RangeISAMExample_plaza2.ipynb +++ b/python/gtsam/examples/RangeISAMExample_plaza2.ipynb @@ -17,9 +17,19 @@ "Author: Frank Dellaert" ] }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Data is second UWB ranging dataset, B2 or \"plaza 2\", from\n", + "\n", + "> \"Navigating with Ranging Radios: Five Data Sets with Ground Truth\", by Joseph Djugash, Bradley Hamner, and Stephan Roth, available at https://www.ri.cmu.edu/pub_files/2009/9/Final_5datasetsRangingRadios.pdf\n", + "\n" + ] + }, { "cell_type": "code", - "execution_count": 1, + "execution_count": 49, "metadata": {}, "outputs": [], "source": [ @@ -42,7 +52,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 50, "metadata": {}, "outputs": [ { @@ -68,7 +78,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 51, "metadata": {}, "outputs": [ { @@ -93,7 +103,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 52, "metadata": {}, "outputs": [], "source": [ @@ -105,14 +115,14 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 53, "metadata": {}, "outputs": [], "source": [ "# Set Noise parameters\n", "priorSigmas = gtsam.Point3(1, 1, math.pi)\n", "odoSigmas = gtsam.Point3(0.05, 0.01, 0.1)\n", - "sigmaR = 100.0 # range standard deviation\n", + "sigmaR = 100 # range standard deviation\n", "\n", "priorNoise = NM.Diagonal.Sigmas(priorSigmas) # prior\n", "looseNoise = NM.Isotropic.Sigma(2, 1000) # loose LM prior\n", @@ -124,7 +134,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 54, "metadata": {}, "outputs": [ { @@ -144,7 +154,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 55, "metadata": {}, "outputs": [ { @@ -154,7 +164,7 @@ "NonlinearFactorGraph: size: 1\n", "\n", "Factor 0: PriorFactor on 0\n", - " prior mean: (-34.2086, 45.3008, 1.1205)\n", + " prior mean: (-34.208649, 45.300764, 1.12050365)\n", " noise model: diagonal sigmas[1; 1; 3.14159265];\n", "\n", " Values with 1 values:\n", @@ -177,7 +187,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 56, "metadata": {}, "outputs": [ { @@ -221,14 +231,14 @@ " newFactors.add(gtsam.RangeFactor2D(\n", " i, landmark_key, _range, rangeNoise))\n", " if landmark_key not in initializedLandmarks:\n", - " p = rng.normal(loc=40,scale=5,size=(2,))\n", + " p = rng.normal(loc=0, scale=100, size=(2,))\n", " initial.insert(landmark_key, p)\n", " print(f\"Adding landmark L{j}\")\n", " initializedLandmarks.add(landmark_key)\n", " # We also add a very loose prior on the landmark in case there is only\n", " # one sighting, which cannot fully determine the landmark.\n", " newFactors.add(gtsam.PriorFactorPoint2(\n", - " landmark_key, Point2(-40, 40), looseNoise))\n", + " landmark_key, Point2(0, 0), looseNoise))\n", " k = k + 1\n", " countK = countK + 1\n", "\n", @@ -255,17 +265,17 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 57, "metadata": {}, "outputs": [ { "name": "stdout", "output_type": "stream", "text": [ - "5476377146882523136: [-36.82919593 26.43059833]\n", - "5476377146882523137: [-76.14891175 22.8614804 ]\n", - "5476377146882523141: [ -3.59406453 -13.50748537]\n", - "5476377146882523142: [-34.91205938 72.42462601]\n" + "5476377146882523136: [-35.97329685 26.31658086]\n", + "5476377146882523137: [-75.1003452 21.01144091]\n", + "5476377146882523141: [ -1.03876425 -12.13811931]\n", + "5476377146882523142: [-36.08926944 72.3500464 ]\n" ] } ], @@ -279,7 +289,7 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 58, "metadata": {}, "outputs": [ { @@ -301,7 +311,7 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 59, "metadata": {}, "outputs": [ { @@ -323,8189 +333,8189 @@ "showlegend": false, "type": "scattergl", "x": [ - -34.20865765277028, - -34.20837627489812, - -34.20804341121378, - -34.20769819900134, - -34.20745791562606, - -34.207262384639584, - -34.20686768496456, - -34.20651586952684, - -34.206068051490725, - -34.20568191285258, - -34.20531779706161, - -34.20487525574619, - -34.20441594634689, - -34.20403934106818, - -34.20366719891563, - -34.20321548065241, - -34.20279758581938, - -34.20236982691178, - -34.20208044779656, - -34.20178452579769, - -34.201476810903344, - -34.201131364439505, - -34.20083959268987, - -34.20050783633701, - -34.20021641568552, - -34.1999036391564, - -34.19960845622661, - -34.19935481630433, - -34.1991197153355, - -34.19886207299627, - -34.19866445873396, - -34.19846692568774, - -34.19824814825021, - -34.19804389331806, - -34.19779278422965, - -34.197561076711025, - -34.19736024057739, - -34.197189125239845, - -34.1969835943833, - -34.19676091619598, - -34.196608333385896, - -34.19640233825663, - -34.196130467067924, - -34.19598494582688, - -34.19585039867902, - -34.195696091766784, - -34.195498091510714, - -34.19535353058579, - -34.19519795908968, - -34.1950071167798, - -34.194831094182135, - -34.19461985854805, - -34.19441132026083, - -34.19424822642422, - -34.194081780417626, - -34.19391357666842, - -34.193711429634185, - -34.19354560895851, - -34.19343110907236, - -34.19325256825953, - -34.19313133842211, - -34.19296665495514, - -34.192788116797225, - -34.19265451354776, - -34.192513435453314, - -34.19234391846579, - -34.19218930175465, - -34.191838323058576, - -34.19136570856127, - -34.190928229906305, - -34.190511990806826, - -34.19000761972925, - -34.18946318971993, - -34.18897791236561, - -34.18851864150678, - -34.18800608441713, - -34.18743169138802, - -34.187036933672935, - -34.18662146295106, - -34.186165007801236, - -34.185817766053745, - -34.185405809463184, - -34.18489058464781, - -34.18448357822621, - -34.18409518154167, - -34.18357571608114, - -34.18309387250541, - -34.18256248424499, - -34.181945835241166, - -34.18134727077619, - -34.18075641955187, - -34.18020608448097, - -34.17963922444816, - -34.179030908528105, - -34.17846295752322, - -34.17789438126163, - -34.17735517301769, - -34.17683902681143, - -34.17646759077013, - -34.17613625869724, - -34.17569496410317, - -34.175274199432124, - -34.174986261943396, - -34.1746536384632, - -34.17437934491031, - -34.17396057959478, - -34.17348400091052, - -34.173132109277056, - -34.172711744705396, - -34.17229359208847, - -34.171889686935685, - -34.171385951929445, - -34.17092532852038, - -34.17054598449141, - -34.17013012377779, - -34.16967802854073, - -34.16919048706976, - -34.168700394094, - -34.16835264800961, - -34.16800957980584, - -34.16756748692532, - -34.167100635865324, - -34.16670327117912, - -34.16635987105999, - -34.165916396897536, - -34.16543888597081, - -34.164981052151965, - -34.16464236988413, - -34.16438165036788, - -34.16395683830689, - -34.163500921448296, - -34.163203159566095, - -34.16283304045582, - -34.16233482182268, - -34.16201880326297, - -34.16150158543522, - -34.16117214943242, - -34.16087247015591, - -34.16069370051231, - -34.160288097838524, - -34.15986460694333, - -34.159654913244964, - -34.159330520615946, - -34.15894290784079, - -34.15854197964232, - -34.15806600534028, - -34.157651010814675, - -34.15733633819677, - -34.15688964504245, - -34.1562164494654, - -34.155904707964396, - -34.1555960279812, - -34.155176861289206, - -34.15470441225209, - -34.15431155084816, - -34.154022421184415, - -34.15379683660929, - -34.153615481685534, - -34.15320786275925, - -34.15285406634137, - -34.1526312702774, - -34.15238434289839, - -34.15197873628081, - -34.151463716790985, - -34.15075297645223, - -34.150422920229474, - -34.150106454424375, - -34.14953083643422, - -34.14865404131877, - -34.147403188210866, - -34.146541461534724, - -34.145832799117535, - -34.14480842908335, - -34.143733929260904, - -34.142752588831556, - -34.14178504499314, - -34.14080054418268, - -34.13987637403273, - -34.138956497883136, - -34.137983706253095, - -34.13707987779172, - -34.13619140755394, - -34.135239035151116, - -34.1342465874728, - -34.13332047604423, - -34.13232866206878, - -34.13133065383901, - -34.13053467472447, - -34.12989457270364, - -34.12914895123361, - -34.12828154203491, - -34.12738571557727, - -34.12655868998526, - -34.12594547630765, - -34.12524399982086, - -34.12438184847555, - -34.12359907359514, - -34.122897400403204, - -34.12237940255494, - -34.121723362493036, - -34.120850538344364, - -34.12029414700698, - -34.119673381183986, - -34.11892484075732, - -34.117959209281125, - -34.11637980957664, - -34.11539288296394, - -34.1139206718875, - -34.112529323577334, - -34.111201361189806, - -34.10715961721005, - -34.099200943828784, - -34.08528778483324, - -34.063537358389006, - -34.0330176108807, - -33.99466330117002, - -33.95228927011852, - -33.91102636757699, - -33.87648411911662, - -33.848949423962125, - -33.82880245368321, - -33.813795371332816, - -33.80302765011269, - -33.79557557067424, - -33.789009500143464, - -33.781028897828314, - -33.769330768968906, - -33.750080307764335, - -33.722410907571, - -33.685802846989034, - -33.63966975965821, - -33.58426987377947, - -33.52025064735403, - -33.44676174131417, - -33.363576136128266, - -33.26935813802871, - -33.163122367170935, - -33.04542280551315, - -32.91817693229932, - -32.78261009875481, - -32.63640547090148, - -32.47640794287209, - -32.306688975113, - -32.12775566866747, - -31.940826864370234, - -31.742477831501663, - -31.53463009871392, - -31.319720548495376, - -31.08998509855075, - -30.8540957508384, - -30.61341296572028, - -30.357335204560368, - -30.094857736558367, - -29.825185182220352, - -29.55171753116922, - -29.269164559501284, - -28.98246080248745, - -28.702613976531723, - -28.41678215375779, - -28.127357109874872, - -27.841149083706476, - -27.55633122678872, - -27.26815228010316, - -26.987175657910743, - -26.71343258961448, - -26.4438583365748, - -26.176709586931796, - -25.9175906251324, - -25.67618980468899, - -25.43181643150372, - -25.19374803478677, - -24.990787477060266, - -24.78739899338199, - -24.589083405331888, - -24.40598476077686, - -24.231696326766766, - -24.06742150344417, - -23.908247046205076, - -23.750254982784725, - -23.609050007658485, - -23.470707450260925, - -23.33088879992566, - -23.20471360256028, - -23.08279521662908, - -22.960770106964247, - -22.846398323856718, - -22.739628244678563, - -22.637878731144024, - -22.538663275812723, - -22.44413423905337, - -22.356602438124526, - -22.273226931552326, - -22.197142974973296, - -22.123574506593187, - -22.05518455320675, - -21.99415465600562, - -21.939564935384716, - -21.88550475592873, - -21.83459698486749, - -21.7858842220242, - -21.73712767832763, - -21.68528019783519, - -21.6341471189187, - -21.58451865634108, - -21.533989778555632, - -21.48224823566605, - -21.434144485609504, - -21.384718433528295, - -21.330711643441262, - -21.278102263962182, - -21.228086229019123, - -21.174898125871866, - -21.1201216471771, - -21.06835717672824, - -21.012090180196257, - -20.958190803479805, - -20.9017989297325, - -20.847027929669178, - -20.791057465910786, - -20.73374607686016, - -20.677984615004902, - -20.62054153562771, - -20.561217397664468, - -20.497570656327234, - -20.436068060400043, - -20.372574664767427, - -20.304225814998883, - -20.234036096947104, - -20.160782558230018, - -20.086083122244485, - -20.00808627936259, - -19.927156617257467, - -19.84457613832099, - -19.75900958016967, - -19.671388081969617, - -19.58207076920672, - -19.490130965447076, - -19.39417286396094, - -19.29683608347038, - -19.19548418857807, - -19.085321208130296, - -18.975105151884314, - -18.86180077327289, - -18.738236649074565, - -18.610154872731925, - -18.480393406542845, - -18.339463266757704, - -18.194233996767583, - -18.044253991578852, - -17.88604692974885, - -17.725857015409737, - -17.557590371526267, - -17.37878631399246, - -17.19776384735875, - -17.01042240300562, - -16.80999598265039, - -16.610564485432956, - -16.405565930644755, - -16.188663405589807, - -15.975014538427745, - -15.759063358341724, - -15.534507995711774, - -15.312377832471743, - -15.091463892047729, - -14.861614635491696, - -14.631523592524267, - -14.408883046579172, - -14.182184206264761, - -13.955999806789674, - -13.73228921372798, - -13.508890099247246, - -13.280310842785969, - -13.051393633045917, - -12.822749073638654, - -12.5947518203909, - -12.363772827011108, - -12.136682714475835, - -11.91104035249452, - -11.682605748870857, - -11.4584028711377, - -11.234707711039341, - -11.007860412464913, - -10.78504111279112, - -10.567121477406495, - -10.348688471478162, - -10.13583488500359, - -9.931177033479994, - -9.7022312235608, - -9.493358327175411, - -9.291263453811862, - -9.090902699597233, - -8.890794589408246, - -8.694020682483048, - -8.502326962491017, - -8.310469169971078, - -8.123326610292315, - -7.939504428022957, - -7.756233922866621, - -7.578392200121858, - -7.398413327196626, - -7.2182629267388325, - -7.041919998827723, - -6.866546197523425, - -6.690360426827359, - -6.5228069558437936, - -6.36347577941645, - -6.200987190064998, - -6.050007480928178, - -5.912232311551511, - -5.7743416728836205, - -5.646420306052364, - -5.5325949134200485, - -5.422918295268944, - -5.323892537691768, - -5.238663186195628, - -5.162665786407667, - -5.101381785082697, - -5.052723869574644, - -5.015244782305614, - -4.9919866108588895, - -4.9825583435547545, - -4.987316861859119, - -5.006256414313346, - -5.04201747568707, - -5.097422039433109, - -5.168815768125782, - -5.25713726768217, - -5.36305329576835, - -5.48888337339212, - -5.639287440052063, - -5.817416709808972, - -6.005550857156813, - -6.2073870642528455, - -6.436954242954809, - -6.674188290893242, - -6.919673867376524, - -7.197024991217148, - -7.481743967619861, - -7.7632116739282, - -8.063956446057551, - -8.375625528507998, - -8.690637452178606, - -9.013983746734263, - -9.339718894808357, - -9.665754291246362, - -9.999708490001447, - -10.331941006221287, - -10.663667670193183, - -10.998085705180765, - -11.331495899154495, - -11.662676948690304, - -11.997659662064569, - -12.326420081367713, - -12.655203291863426, - -12.98587095881301, - -13.310765222518047, - -13.634780920747755, - -13.960896670198567, - -14.284108881408201, - -14.607413513757185, - -14.932899279001981, - -15.262078111243333, - -15.591412638981694, - -15.923511099171229, - -16.258262911703923, - -16.59737276316696, - -16.94018105423836, - -17.2909484860004, - -17.655068612728492, - -18.0207371994716, - -18.38856463954403, - -18.7691510321504, - -19.149187833538363, - -19.52520105852179, - -19.91402415182552, - -20.31591058028569, - -20.70140767958901, - -21.097312765680723, - -21.512012551973932, - -21.9042354163522, - -22.31047375709063, - -22.73151624550871, - -23.133425368061893, - -23.548574543556498, - -23.974953994743817, - -24.377725107507008, - -24.788768501880945, - -25.20780217756491, - -25.596585457089272, - -25.986839797348612, - -26.403570854025947, - -26.80481618663611, - -27.19151604914389, - -27.604095502488054, - -28.013040181107904, - -28.399561120040854, - -28.806305096361402, - -29.21836060889838, - -29.612333991750894, - -30.014839001888117, - -30.42101969427448, - -30.812849563600615, - -31.20975150080373, - -31.607386345888898, - -32.001140911476554, - -32.398511738416815, - -32.795673562184895, - -33.19043549084416, - -33.591818893107636, - -33.99170159046605, - -34.395001772313535, - -34.8007159742122, - -35.21246146096016, - -35.62157246081787, - -36.03028500254523, - -36.43892827784079, - -36.84281499403664, - -37.23936120912264, - -37.6357100863053, - -38.03227527745555, - -38.43341536444668, - -38.842734157084585, - -39.25935801324063, - -39.676612237452915, - -40.09331920677003, - -40.50845440957805, - -40.921070304427836, - -41.34229428167896, - -41.7668309225472, - -42.18790223607136, - -42.59759140395779, - -43.00343010658945, - -43.41118345011088, - -43.818104387761196, - -44.226856572447986, - -44.63207297851732, - -45.04105873294049, - -45.452137717302335, - -45.848582357761366, - -46.246420071019344, - -46.656200074653064, - -47.056121644452084, - -47.45516448410812, - -47.86059878098149, - -48.26812764507053, - -48.66813762511848, - -49.06550271312794, - -49.462743587503844, - -49.85160033511153, - -50.236067455967294, - -50.63236592602849, - -51.0230252239154, - -51.402841949384964, - -51.79340413782777, - -52.1793847503508, - -52.54627719981708, - -52.92818013165972, - -53.30531632375098, - -53.67051783551845, - -54.051273229532896, - -54.432923306503874, - -54.797667966942946, - -55.17853015764748, - -55.55729922853328, - -55.92182316112514, - -56.30369922294296, - -56.68044305487901, - -57.041036489211216, - -57.41233647793287, - -57.7706682135264, - -58.127233440631706, - -58.4924456555522, - -58.852217044817216, - -59.20945677748908, - -59.56867753427188, - -59.92014152015811, - -60.270052574470235, - -60.631476885203405, - -60.98028694706533, - -61.33516553788088, - -61.689908810375684, - -62.02306126130879, - -62.35798184038503, - -62.69004704965884, - -62.99241843758069, - -63.300429779674246, - -63.6044627683144, - -63.883826499514534, - -64.15754939083865, - -64.42281867173546, - -64.67275723743165, - -64.90508952457635, - -65.12955525690963, - -65.34213047273701, - -65.54035548783273, - -65.72858304977794, - -65.90175985054115, - -66.06830228723238, - -66.22920044003294, - -66.37684053648285, - -66.5147227022707, - -66.64282244339906, - -66.76334412013065, - -66.87755657410239, - -66.98131503045009, - -67.08105425508822, - -67.17957589698175, - -67.26732669092793, - -67.34696553722583, - -67.42086056045576, - -67.48424165958828, - -67.53977030995661, - -67.58892626747567, - -67.62521470008504, - -67.6495189664005, - -67.66748200634846, - -67.67350495619027, - -67.66310281912445, - -67.63681921992985, - -67.59625719827237, - -67.54390581011167, - -67.47791181357339, - -67.39699369051641, - -67.30124835953411, - -67.18999145508437, - -67.06654777360508, - -66.93275642679862, - -66.7870188333484, - -66.63200535676094, - -66.46921861044694, - -66.29260496988596, - -66.10287213961468, - -65.90578769689013, - -65.70338794784624, - -65.48873574040499, - -65.26757863662448, - -65.05711231214029, - -64.83312390224027, - -64.59441784791593, - -64.37011538587512, - -64.14028001725154, - -63.885524179488435, - -63.641244695497605, - -63.3985459897878, - -63.13394209674045, - -62.87644812985557, - -62.62080580414671, - -62.352721230763194, - -62.089715954521054, - -61.83156654673461, - -61.56893223476824, - -61.310292262630064, - -61.054001022681945, - -60.79466881062043, - -60.533762342770004, - -60.27561420364428, - -60.01727189473518, - -59.76324569629319, - -59.511562431911166, - -59.26429214368505, - -59.01350129596539, - -58.76796019139932, - -58.52106867458063, - -58.272875656176666, - -58.02981520878215, - -57.79409549812396, - -57.550958925549175, - -57.324053662051085, - -57.1047014444447, - -56.87444734156775, - -56.65463950696342, - -56.433119865646276, - -56.201243660638085, - -55.97842127648121, - -55.75555379279634, - -55.503766595057634, - -55.280159034461285, - -55.059498820467, - -54.83036613495392, - -54.595453683291524, - -54.36695449025803, - -54.13681195180934, - -53.89960604756126, - -53.66668449453342, - -53.43921231795147, - -53.2050036097736, - -52.96975591697278, - -52.738378298576784, - -52.50058143730088, - -52.26149106162401, - -52.03035347222737, - -51.797685452499195, - -51.566514662511324, - -51.344339918580104, - -51.11699128329711, - -50.89267816639776, - -50.66994217142387, - -50.44150315843499, - -50.2078232899057, - -49.968287475176126, - -49.72991752485483, - -49.48660386162624, - -49.232905254156954, - -48.97354091627121, - -48.71138241606341, - -48.447217300053985, - -48.18043385266988, - -47.91202142850183, - -47.64473404164936, - -47.38565772901833, - -47.128686329031105, - -46.86718251551342, - -46.60861341694757, - -46.35334698823539, - -46.092455573640706, - -45.82910723039233, - -45.56767442415841, - -45.30781123187224, - -45.04927088820327, - -44.77723833877998, - -44.511498656988465, - -44.254477628267395, - -43.98023839839559, - -43.706126594039254, - -43.45476071311876, - -43.18497471956452, - -42.901799613816934, - -42.636584261112105, - -42.36457612373446, - -42.071178953831904, - -41.78871608839509, - -41.52471671017607, - -41.23353784019416, - -40.932875163883075, - -40.64906532262748, - -40.34279881141663, - -40.023969009031084, - -39.715363572293434, - -39.393132970570335, - -39.07022363376905, - -38.748440288186494, - -38.419963820390116, - -38.08605157788975, - -37.75877465535211, - -37.421029182409036, - -37.087867531694336, - -36.765705079761084, - -36.42426520040904, - -36.07874871115632, - -35.74587992277794, - -35.40834356887657, - -35.06710994573955, - -34.73199222388137, - -34.40664678937468, - -34.07699779100251, - -33.76136244895746, - -33.46016948598249, - -33.15648449712948, - -32.85592076987152, - -32.57466832758714, - -32.292490123671044, - -32.01020800140973, - -31.741604353620243, - -31.469942663967327, - -31.20847515829357, - -30.956116870204347, - -30.705778329254887, - -30.466686800437184, - -30.23671593374634, - -30.015966086982132, - -29.80404929245738, - -29.60284763420318, - -29.41091369748634, - -29.22475934111039, - -29.047339831863482, - -28.876763478737516, - -28.71320960128329, - -28.558254442726433, - -28.40833616544292, - -28.263854515016146, - -28.12471881580457, - -27.98791269481932, - -27.854024781435854, - -27.727141563221338, - -27.599430483592645, - -27.4711775043917, - -27.35152567991133, - -27.229861756103972, - -27.105764113868315, - -26.985615083763363, - -26.870097430871592, - -26.75168988415617, - -26.63282706372104, - -26.518590899920646, - -26.40292360487485, - -26.286826704518603, - -26.174016289968826, - -26.05961812669295, - -25.944797560137037, - -25.83104325707594, - -25.717249115805537, - -25.599840375010448, - -25.481528577202834, - -25.36496648818335, - -25.24501449406681, - -25.124890260714952, - -25.006158782308173, - -24.886944194957987, - -24.767729947132178, - -24.650078324754315, - -24.530190556934365, - -24.413659275357002, - -24.295336833298865, - -24.17445381450801, - -24.05542934494462, - -23.934421841950442, - -23.812780868032956, - -23.693483309785638, - -23.574794738836673, - -23.456171584759993, - -23.339965689277857, - -23.225990425140644, - -23.111106122208927, - -23.00155994453248, - -22.89556935154261, - -22.789439606384583, - -22.686707513840453, - -22.59111141043223, - -22.497742028538134, - -22.409379353553174, - -22.323477397674704, - -22.239658370541928, - -22.164170884769486, - -22.0918536833376, - -22.020727933566217, - -21.952044764584247, - -21.888064655657626, - -21.821762101566964, - -21.75197916838357, - -21.68501071438019, - -21.619063616663286, - -21.553166711357957, - -21.48504583721297, - -21.420525815700625, - -21.356303702746956, - -21.28685939394922, - -21.218415115716088, - -21.151822514907103, - -21.087634191426336, - -21.02437443552054, - -20.962096986706154, - -20.900119053190263, - -20.838125089802865, - -20.777815917118446, - -20.718057691702477, - -20.660129583277982, - -20.60288567452934, - -20.543722503545894, - -20.487238613238645, - -20.43007415739744, - -20.37141205325075, - -20.3128528281756, - -20.258073694657217, - -20.203510494966917, - -20.14647122632617, - -20.082973993621103, - -20.024612713225867, - -19.963387326162582, - -19.897915978102425, - -19.829622262869968, - -19.757922655086105, - -19.682344784712182, - -19.60327070377297, - -19.52166863863207, - -19.433802043497366, - -19.34062902699642, - -19.2430030185819, - -19.14051075814092, - -19.029890647416014, - -18.913328003639542, - -18.796706146225763, - -18.674022770807362, - -18.54471855578794, - -18.41558776231358, - -18.281870638283987, - -18.13901454597218, - -17.998066271991835, - -17.856675336109355, - -17.703753252988538, - -17.551270708037396, - -17.400445276210593, - -17.237442053139276, - -17.073643356971125, - -16.913527814019, - -16.74041603453929, - -16.565332628964775, - -16.400213935532765, - -16.207552236682343, - -16.021819420661284, - -15.84699159823023, - -15.667092161135956, - -15.472862269674522, - -15.285584644868019, - -15.096443074120153, - -14.898381387044548, - -14.702442507468776, - -14.50569646553477, - -14.304213243436743, - -14.101884043077925, - -13.89790007157055, - -13.6925179574355, - -13.487772380728252, - -13.278775065666851, - -13.066927240203983, - -12.85544049886375, - -12.641558360879957, - -12.425720748674701, - -12.209913136668696, - -12.000315021602171, - -11.78457517923467, - -11.570082369561755, - -11.358789654589712, - -11.142454059079778, - -10.927120137433844, - -10.712321075149939, - -10.498084417658669, - -10.284525097788132, - -10.075458410060298, - -9.867457346567777, - -9.658123727625295, - -9.449737686444529, - -9.24419233451893, - -9.039731972618624, - -8.835429992753749, - -8.63443954140641, - -8.43716601147788, - -8.239300304776066, - -8.047246647206697, - -7.861151680568275, - -7.677379012068177, - -7.495564985735251, - -7.3175797799355005, - -7.145247668396517, - -6.971100946005515, - -6.79818711501, - -6.623724463640425, - -6.452319125855208, - -6.2834299550182875, - -6.092329402049868, - -5.919343678281793, - -5.7553176678986295, - -5.5937185390268285, - -5.43252603328783, - -5.276230407073092, - -5.130505296363279, - -4.98964925773899, - -4.854131605454319, - -4.729948581233919, - -4.611616391338887, - -4.503037179655838, - -4.412044415619663, - -4.3271521731974705, - -4.249017111637989, - -4.185941179324683, - -4.134477041885564, - -4.092668897513787, - -4.063360782544444, - -4.046259142699124, - -4.041987399667728, - -4.051165990521669, - -4.073942925994559, - -4.110904863075316, - -4.162155800894148, - -4.229589187754156, - -4.311708575703241, - -4.408036906953321, - -4.518048653510903, - -4.645305455200856, - -4.797822423005665, - -4.964389803278236, - -5.142189574296227, - -5.3496404030185865, - -5.573421464205477, - -5.8042203754495025, - -6.056196937945198, - -6.3238885381876, - -6.596875542862387, - -6.889274784715866, - -7.191884297538913, - -7.4937589053751275, - -7.810973156955758, - -8.136824574834591, - -8.456284840556274, - -8.7803609463077, - -9.110558869488141, - -9.42884479504251, - -9.754570350900178, - -10.08489775246689, - -10.401053313764542, - -10.720085558570752, - -11.040959627890507, - -11.348055976571189, - -11.654843661604891, - -11.961467456921028, - -12.26110491752206, - -12.557122158412735, - -12.853110392915866, - -13.147070394263933, - -13.437303080943583, - -13.728441347763876, - -14.0200730857591, - -14.312458451202858, - -14.608030522885487, - -14.906012356330399, - -15.210220122427952, - -15.515335418884517, - -15.82269192168044, - -16.133865703043043, - -16.44536785719234, - -16.759637217915845, - -17.0773552923272, - -17.396324436625346, - -17.720947525509334, - -18.045811567461666, - -18.36833981094028, - -18.70341705933958, - -19.034431574137617, - -19.36440746612907, - -19.69380241432439, - -20.03834957779887, - -20.381633972572452, - -20.710868759344486, - -21.061224770465973, - -21.41481077775693, - -21.751772958151705, - -22.100085007084378, - -22.464598463301268, - -22.813701792291237, - -23.16655013515301, - -23.535642575259036, - -23.891293926911082, - -24.243458057965356, - -24.608870430459667, - -24.969477256203113, - -25.322978156143186, - -25.681319764813868, - -26.046168505850687, - -26.406209755560276, - -26.764979695950537, - -27.126126577743964, - -27.492197609902387, - -27.851708092325026, - -28.211751823870774, - -28.582144695012385, - -28.949830327619164, - -29.312297244894527, - -29.680971094527823, - -30.05658799726269, - -30.42076889669658, - -30.782121693656595, - -31.151937148506285, - -31.50868387365998, - -31.864770361874942, - -32.22472307222192, - -32.579652484711154, - -32.935901065223995, - -33.29114491063867, - -33.640503436774694, - -33.994216855514225, - -34.35321090838215, - -34.70674728111639, - -35.06249478488046, - -35.421161482096394, - -35.77562375872252, - -36.12974053530249, - -36.486515097977424, - -36.8370658726633, - -37.18068676390196, - -37.53142686680611, - -37.872407846824466, - -38.21643646462669, - -38.569893577771786, - -38.924134497406854, - -39.27836194064444, - -39.6457889908704, - -40.01213107413774, - -40.371512898998496, - -40.735175913412974, - -41.103419692920994, - -41.46152909375386, - -41.82291452907854, - -42.18912045641845, - -42.543963530852125, - -42.89219062707086, - -43.24495670516598, - -43.596896295463736, - -43.94121527772567, - -44.295846063177855, - -44.65139743521477, - -44.999648750108186, - -45.35302240608575, - -45.70714106778485, - -46.04816524916467, - -46.39334279322935, - -46.74265592846308, - -47.087629640850004, - -47.42769461755935, - -47.7719132994987, - -48.11683068133768, - -48.45966445230252, - -48.79888708358816, - -49.139283764720005, - -49.481140565990195, - -49.820486761193955, - -50.157087057923746, - -50.49979109401643, - -50.84745899871575, - -51.18736165268032, - -51.52598826062575, - -51.87104199378865, - -52.21195432076135, - -52.53979326355826, - -52.87643566540903, - -53.214515952253265, - -53.54183693038462, - -53.87473864666174, - -54.214336495193294, - -54.54753707147511, - -54.877573466675855, - -55.21828555021866, - -55.55193018142669, - -55.87701746527285, - -56.214779429937714, - -56.552187979127204, - -56.87605564387785, - -57.20468550384501, - -57.53744766585467, - -57.85808955993053, - -58.181214786661464, - -58.50953441606787, - -58.82957961496041, - -59.14822813829285, - -59.469528783707865, - -59.78602746488803, - -60.094818935602525, - -60.40350912456221, - -60.71625486364919, - -61.023813147028875, - -61.33148151388015, - -61.64680711051246, - -61.95282404511547, - -62.24773425030408, - -62.549122581110055, - -62.8488991713276, - -63.13099518064569, - -63.41094680154312, - -63.69120627991752, - -63.95643549358305, - -64.21247184750521, - -64.47027285329462, - -64.70957452410602, - -64.94398146032917, - -65.17056064808759, - -65.37618318321724, - -65.57638368642908, - -65.76356719574198, - -65.94007956259367, - -66.11979176972015, - -66.28099245704996, - -66.43312909088498, - -66.59094718720128, - -66.74154073512811, - -66.88413745934777, - -67.02239669463482, - -67.15165902341101, - -67.27978847903408, - -67.40427857430315, - -67.52146269219321, - -67.62924162797573, - -67.73714594390412, - -67.83706817775604, - -67.92215303249631, - -67.99806012379929, - -68.06352660700529, - -68.114528246376, - -68.15650009436126, - -68.18561812245795, - -68.2009157524861, - -68.20975108721088, - -68.21089135487408, - -68.19887332851475, - -68.17239258964494, - -68.13456534354545, - -68.08697910663294, - -68.02953461515013, - -67.96137592236013, - -67.88159070510437, - -67.78414929393003, - -67.6751948052676, - -67.55503541456446, - -67.42371365758812, - -67.28068940289505, - -67.12671078192913, - -66.97141841057255, - -66.80741063558389, - -66.63820417250463, - -66.46100290687446, - -66.27891622921368, - -66.09586409399127, - -65.9043404136652, - -65.71378359831859, - -65.5213950468977, - -65.32249297762922, - -65.11904406686214, - -64.91990933948763, - -64.7129140460563, - -64.50153698206827, - -64.29670270151745, - -64.08743684046358, - -63.87138264015154, - -63.653867546403404, - -63.43370662687731, - -63.20738863236294, - -62.98017210553031, - -62.750438214939905, - -62.51765901233964, - -62.2861672750576, - -62.04696108955838, - -61.8031091077138, - -61.56043092051491, - -61.31142073302581, - -61.05747383135898, - -60.803977918221925, - -60.54889253417473, - -60.29118333843693, - -60.03715104565685, - -59.78084579626353, - -59.52867865538103, - -59.27630899666948, - -59.01770696294031, - -58.76201321053243, - -58.51178548751056, - -58.25464965577174, - -58.004382435736005, - -57.76346431473836, - -57.51193708359743, - -57.26996822146708, - -57.03189888319683, - -56.78509754948844, - -56.54587294641515, - -56.30881746048974, - -56.06256540458002, - -55.82369926153637, - -55.595726809168, - -55.35184090645175, - -55.10661727517301, - -54.872596990014024, - -54.62613911727918, - -54.37486906368861, - -54.13633923490666, - -53.8914630572816, - -53.6410196432496, - -53.3980215009388, - -53.149782734602475, - -52.89496150840424, - -52.651615152303215, - -52.41126251219881, - -52.170185606678025, - -51.93622701981825, - -51.705446999793345, - -51.47966887694434, - -51.24973403092119, - -51.02004229414803, - -50.78523161316766, - -50.54848733851053, - -50.31518575293781, - -50.07665072401502, - -49.83009771395729, - -49.5828132161494, - -49.33715365801616, - -49.082157337157234, - -48.83193333014188, - -48.58873290677186, - -48.34144416320349, - -48.10360173323675, - -47.87009470992484, - -47.622514706473574, - -47.363966739705205, - -47.12013795521646, - -46.87257049162197, - -46.61062913375097, - -46.35200814212822, - -46.097583433824305, - -45.83687587139437, - -45.563170967350636, - -45.29591709740525, - -45.037523455519576, - -44.77131210219301, - -44.49284996858265, - -44.23091373251442, - -43.964006574815805, - -43.672839750953095, - -43.38599077479786, - -43.110946250191546, - -42.816501303423415, - -42.51417479511037, - -42.23818749026477, - -41.9574496142742, - -41.650858897770384, - -41.3528863546484, - -41.05379292343766, - -40.72557625370128, - -40.39969781586623, - -40.07113987252099, - -39.728536258790534, - -39.38724721786888, - -39.04220905850102, - -38.68599662597201, - -38.33535987726679, - -37.974115925958536, - -37.61024733531228, - -37.25587461258331, - -36.88864640813949, - -36.51849771971568, - -36.15724795826422, - -35.79554363469556, - -35.42964631157209, - -35.08112319361428, - -34.73884994084711, - -34.392755894705495, - -34.074077979693655, - -33.76393325300418, - -33.442883513001235, - -33.1489629236288, - -32.85990276701371, - -32.56837015476392, - -32.294684172890086, - -32.028774898971186, - -31.75718767402392, - -31.495730807416944, - -31.24791565919711, - -31.00121962124004, - -30.759627234807496, - -30.530664629688705, - -30.310852079543675, - -30.09607289768241, - -29.883862359017467, - -29.677880790471516, - -29.480891444958747, - -29.289993440013557, - -29.10261107047686, - -28.92364991150457, - -28.748139666612893, - -28.573226178117782, - -28.40592874609806, - -28.245276083201215, - -28.082977954940496, - -27.931234064689665, - -27.789710518065313, - -27.644616675377932, - -27.506947402047835, - -27.378522436375814, - -27.245882670417625, - -27.11663794071789, - -26.99300541098765, - -26.86722145658784, - -26.742737620858613, - -26.620127305638263, - -26.495194364643197, - -26.369159116174483, - -26.245335215615878, - -26.115857229254324, - -25.98389129610689, - -25.85370763143319, - -25.717637410421045, - -25.582103450486787, - -25.44680215508687, - -25.30825672214228, - -25.168758099994903, - -25.029521586542533, - -24.893230068326957, - -24.752276262732824, - -24.610893805664148, - -24.471651749104904, - -24.331871781410168, - -24.194466328335597, - -24.057916487969454, - -23.925633212669805, - -23.796289157373838, - -23.668940136514355, - -23.531217314779276, - -23.415495706932536, - -23.301692937313973, - -23.190532314594886, - -23.0870812858565, - -22.98828267493393, - -22.895022149441242, - -22.80659696819355, - -22.722293959750044, - -22.6447131143414, - -22.572189884252822, - -22.499300442670005, - -22.42756830472304, - -22.35967804104907, - -22.28575079230414, - -22.209094019249193, - -22.136547437571625, - -22.063304942142754, - -21.984911102927903, - -21.910468924042853, - -21.834243310557962, - -21.750318264668973, - -21.669245972574057, - -21.59321120154545, - -21.515850918555735, - -21.44011386348618, - -21.366266375229404, - -21.290963462074345, - -21.21501499338668, - -21.14235551246563, - -21.072393903507383, - -21.002448463060183, - -20.93182383747362, - -20.865088656369338, - -20.797770586972558, - -20.72998308241188, - -20.6655264338563, - -20.602766499874217, - -20.53845797512729, - -20.47269378482167, - -20.40544985601269, - -20.335254295360638, - -20.260348601716093, - -20.18245196414492, - -20.09956836404846, - -20.01167021052066, - -19.921454109351217, - -19.824992540687557, - -19.721312578357868, - -19.611836768816712, - -19.494748073623743, - -19.36847981299224, - -19.236203231070814, - -19.101819824012058, - -18.95885288915273, - -18.811931958697485, - -18.66121378735747, - -18.497255021956903, - -18.330527538292355, - -18.160174752164238, - -17.980221273569583, - -17.797022578069004, - -17.610027628843415, - -17.4166767583467, - -17.22516942646293, - -17.02880138213018, - -16.824918570644137, - -16.632689144140926, - -16.434556785191827, - -16.222013833958925, - -16.022114363750095, - -15.821539263401311, - -15.606529188295276, - -15.395644280380646, - -15.187167820010343, - -14.966706975796223, - -14.754468490541361, - -14.558943657146083, - -14.356619727420545, - -14.154401602462695, - -13.956618199868508, - -13.752031676596259, - -13.543654641602096, - -13.338672335098378, - -13.128921204221147, - -12.919115743911556, - -12.705119718601106, - -12.487170768127378, - -12.26869919382645, - -12.051085271849994, - -11.837548192783965, - -11.623348978756004, - -11.409444851129606, - -11.197392062057354, - -10.988675819087593, - -10.779523375280213, - -10.573066747040784, - -10.367401132602206, - -10.160219747027968, - -9.952428517322884, - -9.747949968604173, - -9.54854295388597, - -9.348898020945425, - -9.153006389797316, - -8.963902231676316, - -8.77758035848527, - -8.595694620894326, - -8.420927563968194, - -8.249744821381304, - -8.081435122747934, - -7.917227007839054, - -7.75070768175025, - -7.586101597221615, - -7.429471770624002, - -7.257298823333568, - -7.104645340776128, - -6.961988780756195, - -6.823759126985268, - -6.687554489360367, - -6.558984384204702, - -6.436291091041718, - -6.312319001932537, - -6.194234905523938, - -6.080969034550201, - -5.967389673532327, - -5.860152286876645, - -5.757794801920761, - -5.6566256628771105, - -5.5658816046674975, - -5.480967770476624, - -5.402178448446612, - -5.335477512080547, - -5.277246076256775, - -5.224878962971179, - -5.182095094719288, - -5.1480953224626065, - -5.123399800086929, - -5.1092777228028465, - -5.104623772748024, - -5.110473145305642, - -5.128940831361704, - -5.161308524207603, - -5.207978306248866, - -5.271269279630029, - -5.346436629042738, - -5.435858600197381, - -5.553335213973659, - -5.684702745226146, - -5.820986069841115, - -5.9746325807390726, - -6.143048938440841, - -6.3218157059790085, - -6.5166538008814605, - -6.727708238719462, - -6.952184410523694, - -7.1909903104453585, - -7.436789430370237, - -7.687500259759616, - -7.9524992732315605, - -8.223955056709887, - -8.498474529811658, - -8.779791223014795, - -9.063252158535997, - -9.372851306698582, - -9.655230219915316, - -9.941506797101145, - -10.225248573353394, - -10.510183968052262, - -10.798768470577533, - -11.084219929884725, - -11.366391943635408, - -11.64959740145844, - -11.928728574571482, - -12.204968161319659, - -12.48090091055975, - -12.75095056671446, - -13.021256515708794, - -13.29636794736704, - -13.567311910690004, - -13.836496873775022, - -14.137436435484469, - -14.411588121872944, - -14.68773255696378, - -14.964013442657567, - -15.240893854913917, - -15.524812012198275, - -15.806282843594758, - -16.088855804412653, - -16.372990571411755, - -16.656715028205927, - -16.948151284131853, - -17.23475908098609, - -17.52405663008479, - -17.821883353352185, - -18.121189083950064, - -18.41457088965136, - -18.7148194283729, - -19.026102464069908, - -19.328581621335758, - -19.637655645853506, - -19.945124335975077, - -20.26227926121529, - -20.587336292560085, - -20.900471973383766, - -21.226886665001466, - -21.56387694747123, - -21.886930643083467, - -22.213782123596182, - -22.55831464687727, - -22.89575416147447, - -23.228296525995525, - -23.578172729600727, - -23.926253247141, - -24.262883026618272, - -24.608882580870766, - -24.992990337304413, - -25.336305299619195, - -25.67942762458503, - -26.02680259945706, - -26.376704909776212, - -26.726666085992726, - -27.074155712129674, - -27.425144936953824, - -27.777110294896342, - -28.128832260266027, - -28.483461804743925, - -28.83945419796568, - -29.197218210322102, - -29.552337395623532, - -29.909835414663057, - -30.263854645961224, - -30.60967243773454, - -30.954746942543842, - -31.30201385584006, - -31.63774173984617, - -31.969276168312284, - -32.309309106966765, - -32.642245420753675, - -32.972022339707046, - -33.305788693989506, - -33.63564342091818, - -33.96360760857367, - -34.292073191653394, - -34.62598433989233, - -34.962465594101225, - -35.28954879153012, - -35.620472907491894, - -35.95672505845251, - -36.28662776203072, - -36.61684557626144, - -36.94621608685265, - -37.26264009973386, - -37.5848620116347, - -37.912084105920485, - -38.22899574176612, - -38.54863505093228, - -38.876444820099465, - -39.20148309022963, - -39.53024159490634, - -39.86651468191604, - -40.20100707177658, - -40.53697160106745, - -40.873887355024635, - -41.21719227675245, - -41.55652242450899, - -41.8924203416051, - -42.23467152791791, - -42.576482252679774, - -42.91109477083226, - -43.24478267401926, - -43.58334279588164, - -43.918646507047164, - -44.253732344290206, - -44.59623954768933, - -44.931913342596864, - -45.264530411590634, - -45.60672172161301, - -45.93795884515952, - -46.269604154834155, - -46.60417550888577, - -46.937858867469686, - -47.26982522955466, - -47.604587474154975, - -47.93592217464142, - -48.26934745159304, - -48.60110561346804, - -48.927175086197344, - -49.254066155153744, - -49.58174814088134, - -49.90660632808245, - -50.23107637867807, - -50.55979378643404, - -50.8917436987979, - -51.220535168451576, - -51.54802249736267, - -51.88062667178284, - -52.209848333029576, - -52.52585866614077, - -52.85119930087964, - -53.18073104114711, - -53.497825215480745, - -53.8227351141769, - -54.15562371428327, - -54.48261674566701, - -54.807288282782686, - -55.14394557857862, - -55.47720722795808, - -55.802191537433224, - -56.14052579619243, - -56.48108908827178, - -56.80918375914819, - -57.14268988422175, - -57.481302985557654, - -57.80399448281153, - -58.13078835801433, - -58.46339988064208, - -58.78884783372682, - -59.11245654910816, - -59.439789331047535, - -59.762743142086926, - -60.07821734342035, - -60.398111042322675, - -60.72434750977929, - -61.04233945739224, - -61.36359753907159, - -61.68552558685144, - -61.98808980267596, - -62.282386413723565, - -62.57122499658275, - -62.85195535224514, - -63.11158079739945, - -63.37237553395694, - -63.63073778922422, - -63.86947022195167, - -64.10925160331492, - -64.34227018456264, - -64.58975127476415, - -64.84543292147062, - -65.08953167538627, - -65.32689911596297, - -65.55733278643139, - -65.77576745875913, - -65.9828568816992, - -66.19225016045954, - -66.3784069843528, - -66.55509949135688, - -66.72186708157075, - -66.86576820382932, - -67.00359969640152, - -67.13642299608212, - -67.25424145811719, - -67.36443358983367, - -67.4697226570013, - -67.55978956201018, - -67.64567135683917, - -67.72916804724449, - -67.79950758673753, - -67.86298358088574, - -67.92219323199015, - -67.972564353899, - -68.01546367063806, - -68.0483974563218, - -68.07040099147785, - -68.08694600942935, - -68.09227031170168, - -68.08075148928833, - -68.05406241329986, - -68.01507570773059, - -67.9664007507879, - -67.90563960681862, - -67.8306438124575, - -67.74177114521864, - -67.63714548533596, - -67.51833295742998, - -67.38874916724625, - -67.24414827629755, - -67.08925912006195, - -66.92560443261574, - -66.75129426201148, - -66.56845577371764, - -66.37778221580734, - -66.17933406941548, - -65.98165946768908, - -65.77904936626595, - -65.56587408067271, - -65.35869392971273, - -65.14959040323969, - -64.92564088737147, - -64.7021476023911, - -64.486095611291, - -64.25295320970861, - -64.01491726958696, - -63.781731700888784, - -63.5409703381668, - -63.28966232614324, - -63.040647788425986, - -62.786962882446886, - -62.52906628303248, - -62.270404792074196, - -62.00692433215578, - -61.74392054616378, - -61.48086048949135, - -61.21250030309478, - -60.94493203647749, - -60.675778946238204, - -60.40437112105071, - -60.1359398044163, - -59.86973634363778, - -59.60021628437911, - -59.33649919844747, - -59.07279114579643, - -58.803107391701985, - -58.54002453020873, - -58.27551531030626, - -58.00572503235222, - -57.74491252097591, - -57.489160350947245, - -57.22613914309932, - -56.97591832788377, - -56.72645975449218, - -56.47386327130982, - -56.22808593385795, - -55.97972758749454, - -55.730354780346225, - -55.48381021687825, - -55.2339933656851, - -54.982163745908096, - -54.74174274868021, - -54.49321718320209, - -54.23834495425245, - -53.99027603454085, - -53.74126329606611, - -53.48407611729288, - -53.234923278913726, - -52.98456172921275, - -52.725766341738286, - -52.46788834710454, - -52.20472972418036, - -51.93819474180007, - -51.67897511484283, - -51.42269666285617, - -51.170692926057846, - -50.923571578648364, - -50.678671852851, - -50.43522112770682, - -50.19153346488385, - -49.93976843551103, - -49.65589603820561, - -49.401811215996666, - -49.143388944656174, - -48.87482302295215, - -48.604484417935886, - -48.33268771624553, - -48.059951800034234, - -47.78568525052522, - -47.51418406991346, - -47.2569113045454, - -47.01017901277052, - -46.76622422855464, - -46.52334558082118, - -46.282048930713934, - -46.03839213126161, - -45.798901053291104, - -45.533075268345726, - -45.28878449528761, - -45.04381906917227, - -44.79269558835044, - -44.531454907327145, - -44.26425464129381, - -44.008788626376884, - -43.753970264792265, - -43.485370298172, - -43.22283533452984, - -42.97348931885159, - -42.70806880953647, - -42.43618369747359, - -42.18888948457328, - -41.939429867018475, - -41.68074324909305, - -41.4255371376996, - -41.16943682462024, - -40.91186907428929, - -40.63815205152, - -40.36003941417462, - -40.07929954669712, - -39.777130073828076, - -39.4570397235451, - -39.13133218251017, - -38.796400427182945, - -38.45948939543574, - -38.115930418119866, - -37.76778565215383, - -37.42206673784064, - -37.06586211795496, - -36.70302579198616, - -36.34792122705641, - -36.03288476294385, - -35.715466802372134, - -35.39327975906087, - -35.075994858784874, - -34.76924621846017, - -34.45205543597953, - -34.148596864654486, - -33.85900809784277, - -33.571580209405624, - -33.281189508290616, - -32.977806838871054, - -32.68122437592948, - -32.3888342647305, - -32.09676660137176, - -31.80632160802792, - -31.52300481168706, - -31.242152314284507, - -30.963346085348668, - -30.691619348407944, - -30.43308620677529, - -30.181230178828628, - -29.930258250525448, - -29.696866478426877, - -29.466847155523265, - -29.239021472583524, - -29.026972166393996, - -28.8237212903129, - -28.621783519943893, - -28.430025531873827, - -28.241866155491973, - -28.054040986262187, - -27.87805176584032, - -27.71021418685295, - -27.539630087736835, - -27.38435680389206, - -27.238892152319405, - -27.08854595439461, - -26.949023332399104, - -26.819225982448028, - -26.682917859090434, - -26.553996079709922, - -26.43164188604073, - -26.30849850592943, - -26.188262287617565, - -26.071176684234214, - -25.95478467593371, - -25.837889211639578, - -25.72565769787192, - -25.6090831455678, - -25.490410760347128, - -25.37187922714603, - -25.25206312999524, - -25.13016530438501, - -25.01009609733855, - -24.8901393943063, - -24.768264223957846, - -24.649552360534514, - -24.529791348565993, - -24.413770288028577, - -24.29357489215293, - -24.17349303794771, - -24.052755247857867, - -23.930564720279055, - -23.809504119812164, - -23.686770507825614, - -23.564303171892195, - -23.442569023961706, - -23.31896576490457, - -23.195598344294645, - -23.07283876649093, - -22.95546625900003, - -22.837554086804055, - -22.722128948949262, - -22.614458107091732, - -22.509820671686885, - -22.410057757095156, - -22.31501803622426, - -22.223569954326916, - -22.138705934772016, - -22.060499210689603, - -21.98384617338542, - -21.908987118375066, - -21.84094153906116, - -21.773424875212275, - -21.701184821441792, - -21.634376703258035, - -21.572484487211174, - -21.5102184136449, - -21.448783042602518, - -21.391561448655736, - -21.3328649170468, - -21.270370983152183, - -21.209024595385703, - -21.148813876046027, - -21.088742584854412, - -21.02744902242941, - -20.964939838097717, - -20.900941901509675, - -20.834707327201077, - -20.76697246412593, - -20.699587458716117, - -20.631934031270504, - -20.559767564483245, - -20.489113801015886, - -20.417698881190578, - -20.344878252095764, - -20.271170893347175, - -20.200973242386176, - -20.132304868802283, - -20.062492769684184, - -19.99404634108976, - -19.924140110056346, - -19.853287205483973, - -19.78095801332462, - -19.707443533284177, - -19.63156149244821, - -19.55245929739752, - -19.47473788950867, - -19.392121425032574, - -19.304250094265583, - -19.216207428785335, - -19.123857039560107, - -19.02650636545839, - -18.922544716211487, - -18.812494535573286, - -18.699170972107435, - -18.58244379245635, - -18.45859968595741, - -18.329501197930224, - -18.193895725187208, - -18.05200564627889, - -17.903262512236594, - -17.747543578216767, - -17.590668064165165, - -17.42615017423268, - -17.25835424182736, - -17.09114063677347, - -16.918762199579422, - -16.736777954421882, - -16.563218495980028, - -16.389427875316613, - -16.197349502565203, - -16.014235854213386, - -15.836343589404848, - -15.644512083276659, - -15.456104541958904, - -15.272143446768258, - -15.083122322955424, - -14.894441617632763, - -14.711319486896373, - -14.52746141925098, - -14.3417640965953, - -14.157278726508983, - -13.967285526208965, - -13.775288452181831, - -13.579680168693109, - -13.38107443699138, - -13.178964650780102, - -12.977252444787776, - -12.771699419863873, - -12.563938401381387, - -12.355934021140786, - -12.142629356441429, - -11.93113366350645, - -11.717669643847204, - -11.501052307978233, - -11.284555626151555, - -11.06844942166838, - -10.852541839399422, - -10.636005026619523, - -10.423527377022992, - -10.213310216982059, - -9.999075763703555, - -9.785930262927305, - -9.577366736144475, - -9.36603030307235, - -9.147755432275234, - -8.939428805736833, - -8.731140399381117, - -8.518671652381668, - -8.31098694241625, - -8.106092132470822, - -7.901629527846874, - -7.6946174871784745, - -7.485699018879198, - -7.281496518549839, - -7.078862784376807, - -6.873897714768329, - -6.676319700273836, - -6.4864640903131745, - -6.289130253810288, - -6.104133571272094, - -5.933536469508783, - -5.757799320920648, - -5.584755887518073, - -5.427087786521035, - -5.268344946207315, - -5.116876057770809, - -4.974848327334748, - -4.832670478293677, - -4.710412238595439, - -4.595053907280515, - -4.480850047095039, - -4.3831196509593315, - -4.298973724467213, - -4.223312224241947, - -4.16251912661842, - -4.115475682752629, - -4.079632921713764, - -4.057683322035281, - -4.0497633088001175, - -4.055863258036774, - -4.076998215256428, - -4.1134502271726925, - -4.164975272496102, - -4.2325182923216325, - -4.318591759797483, - -4.423047853198676, - -4.543722847198863, - -4.684773464165652, - -4.844670432503804, - -5.017705211420784, - -5.217147349040418, - -5.432995513525165, - -5.662264449874713, - -5.909273918413672, - -6.168061038992916, - -6.437447625694629, - -6.719855812733649, - -7.014831557942956, - -7.317825426702909, - -7.622772978317606, - -7.940282393727611, - -8.26320916901528, - -8.586785865539298, - -8.914048899272423, - -9.237595242606512, - -9.556300646951536, - -9.878293249501493, - -10.199021843992485, - -10.513134340491707, - -10.828795519518424, - -11.174391149549265, - -11.481227620596052, - -11.788309280238991, - -12.092349562421603, - -12.39322325232527, - -12.691973430070467, - -12.983382277509811, - -13.274590340662257, - -13.564045654261891, - -13.849703564491298, - -14.136216974038087, - -14.422028737490951, - -14.707283067784356, - -14.99114532930672, - -15.275945174048655, - -15.564766590843552, - -15.852752499044497, - -16.142906850652306, - -17.17314741044977, - -17.478182813658446, - -17.79182832937652, - -18.11079617721354, - -18.42714572180963, - -18.749749002753273, - -19.0816248901036, - -19.40629594972301, - -19.731826082974244, - -20.05841147903698, - -20.401288838203744, - -20.740474809645217, - -21.072438391231586, - -21.42662141925003, - -21.77914286037434, - -22.11837736906065, - -22.471611014192685, - -22.834011270115308, - -23.179721988586955, - -23.53415774461837, - -23.90158646706203, - -24.2544405819262, - -24.610666258146484, - -24.976154241038806, - -25.333454188733036, - -25.689471558670224, - -26.051056875198427, - -26.419257966070656, - -26.786369727597965, - -27.15264842046791, - -27.52334865978693, - -27.894932873525505, - -28.26387342846709, - -28.638491410536695, - -29.015233919415305, - -29.391840090992194, - -29.769291850625944, - -30.15057998175051, - -30.526253229073507, - -30.896677850573962, - -31.26966465648412, - -31.64087742523774, - -32.0007279253995, - -32.36426563289039, - -32.73396917822784, - -33.09182946101586, - -33.45345872141775, - -33.81766227133371, - -34.177694557752176, - -34.53528757347948, - -34.901174909526134, - -35.269196621898715, - -35.62711607127921, - -35.99285285849184, - -36.36277638389323, - -36.725180587024084, - -37.08824653846684, - -37.44433345109259, - -37.78923882709414, - -38.14177079186136, - -38.490278868950035, - -38.83548993586474, - -39.19184373751581, - -39.54921569486623, - -39.90673058848482, - -40.273446003535724, - -40.64015304783525, - -41.00393762273027, - -41.370740488685996, - -41.74091713701195, - -42.09902392828216, - -42.46042622252486, - -42.82537474447516, - -43.179490651063375, - -43.528849507652225, - -43.88205847688059, - -44.232331716935605, - -44.56833052708007, - -44.89985248724656, - -45.2284906256809, - -45.5493857404015, - -45.87614441547058, - -46.22424725687594, - -46.53783796105583, - -46.8537183745384, - -47.165978501112086, - -47.476069407070455, - -47.79506382989975, - -48.11556022545372, - -48.434348355419566, - -48.756109919126644, - -49.06988091178277, - -49.380598624341346, - -49.690779680787195, - -49.997267269464146, - -50.3049975449524, - -50.61072713610734, - -50.911144104523196, - -51.206718908487716, - -51.49952154089539, - -51.79271361906446, - -52.086862643448995, - -52.38092796772231, - -52.666114434227445, - -52.950917199642994, - -53.24378484397096, - -53.53078472662074, - -53.816388825820525, - -54.114016522739774, - -54.41317251061458, - -54.70798654818017, - -55.00045128159819, - -55.2997366557262, - -55.59838606562386, - -55.89137971230882, - -56.188058153598625, - -56.489160884856666, - -56.78881823532458, - -57.08930989206927, - -57.391741350204185, - -57.692745173151515, - -57.99057008646997, - -58.28297681813924, - -58.575543138993766, - -58.86903618089999, - -59.15816470046521, - -59.442831041731225, - -59.729271902696276, - -60.016024283583214, - -60.295415946986914, - -60.57171222326323, - -60.85248685486421, - -61.13238359286206, - -61.40840686037356, - -61.68662383327404, - -61.96647724375321, - -62.23837500263527, - -62.502096957689474, - -62.760493470537035, - -63.01658868620819, - -63.27047895359807, - -63.50826020631331, - -63.751709585442306, - -63.99228771054395, - -64.22153675376323, - -64.45136706449661, - -64.67401691207169, - -64.89087507459233, - -65.106517446601, - -65.31253473777473, - -65.51536748455793, - -65.71155381379072, - -65.89730880834624, - -66.07802958081712, - -66.2568334350681, - -66.41367613797222, - -66.57235287423055, - -66.72910938266696, - -66.87218144916228, - -67.01347147311785, - -67.14473095443732, - -67.26327976348009, - -67.37890441972439, - -67.48361775389816, - -67.5762377628514, - -67.6674938020023, - -67.7491293121327, - -67.81838468367297, - -67.88191109430018, - -67.93618316791971, - -67.98133990499582, - -68.01715817116215, - -68.04118431443811, - -68.05657977150146, - -68.06603921525864, - -68.06342856125076, - -68.04596045508238, - -68.01518506720029, - -67.97347259576468, - -67.92268206371651, - -67.86021994208443, - -67.7861755823915, - -67.69975808599018, - -67.60095100857507, - -67.4934195066361, - -67.37627270805676, - -67.2482438994998, - -67.11073870702361, - -66.96623401873879, - -66.8113376015874, - -66.64647559103149, - -66.47144652637122, - -66.29156644766901, - -66.1108632901167, - -65.92190724816146, - -65.72716727582748, - -65.53873886504608, - -65.34470480409853, - -65.13905019836768, - -64.93716412962752, - -64.73962551762308, - -64.52631575912591, - -64.31077071691386, - -64.10085223510309, - -63.882594558202356, - -63.656813799009974, - -63.43510654249091, - -63.208947542039255, - -62.97752796227855, - -62.74848487076831, - -62.514877330043205, - -62.28154834304957, - -62.05219778968952, - -61.81971488031907, - -61.584094628424914, - -61.351293511264686, - -61.113761592572054, - -60.87427425174988, - -60.636052446036175, - -60.39865609892982, - -60.15902393001214, - -59.924705926141165, - -59.68590459739886, - -59.447092126024984, - -59.211142750873265, - -58.96858000853882, - -58.72783673028705, - -58.49276578472339, - -58.25714823689183, - -58.0182650131093, - -57.794135858412766, - -57.5628600650443, - -57.32908277899748, - -57.10322510004539, - -56.868014170082205, - -56.62955861028737, - -56.39809843734877, - -56.1617801757568, - -55.92196704229794, - -55.68934583397833, - -55.46334633026685, - -55.22719909196398, - -54.992554547595326, - -54.76169334006083, - -54.52965323139209, - -54.29467957012429, - -54.066640298967734, - -53.84073233980438, - -53.610602003022834, - -53.38239275488003, - -53.15383851165397, - -52.92009762022746, - -52.68988001827451, - -52.46368493446851, - -52.23918400016331, - -52.021429454858115, - -51.810113332496485, - -51.594940866430484, - -51.386823461491225, - -51.179549268093474, - -50.96621960282022, - -50.749779523243724, - -50.528890585193665, - -50.3101877073193, - -50.08814360606012, - -49.857553105868305, - -49.62187189069538, - -49.3829594751214, - -49.14177276858828, - -48.900210588080874, - -48.658576175881926, - -48.414857305623684, - -48.178163184624616, - -47.94791360964173, - -47.71489974734685, - -47.47955062429109, - -47.24258062910488, - -47.011546636966834, - -46.77584374169844, - -46.53319506962506, - -46.29080597647534, - -46.04607075076184, - -45.80436712260419, - -45.54888612559069, - -45.29302623879207, - -45.04261198579043, - -44.78852661576912, - -44.51998027688438, - -44.26230853726105, - -44.00935795739714, - -43.73445301016194, - -43.457632107481345, - -43.1939152143408, - -42.91824131676634, - -42.63096257128518, - -42.36365961289818, - -42.10241000710876, - -41.81297046055366, - -41.51796373579707, - -41.23143676531105, - -40.92113763704598, - -40.606892251486805, - -40.30022890223715, - -39.97706596929543, - -39.657648821759686, - -39.33657419881249, - -39.00522352284926, - -38.67613681457556, - -38.34936825255397, - -38.01209357295046, - -37.678517169079996, - -37.34836826179574, - -36.99805686093465, - -36.64505427476551, - -36.29905258356289, - -35.948714717804265, - -35.59390738162773, - -35.24811213806463, - -34.90949555582719, - -34.567481565253374, - -34.24592603650697, - -33.937294662885776, - -33.621962712142306, - -33.315087209689324, - -33.03286414559924, - -32.7438962484879, - -32.46124429651965, - -32.19514194763271, - -31.931629684838693, - -31.66562934275739, - -31.413636124569884, - -31.17015669148171, - -30.925899168706554, - -30.688058667965244, - -30.461262313263457, - -30.241066780068092, - -30.025459427801167, - -29.81439984751964, - -29.614409069979523, - -29.42345523035274, - -29.238179503987503, - -29.055850882559447, - -28.88193772330147, - -28.71080987628412, - -28.541607115220092, - -28.37991731223352, - -28.223646009794745, - -28.06594750115205, - -27.917853390565092, - -27.77809345992737, - -27.63426271065992, - -27.495838170192673, - -27.365493223456493, - -27.23043474407258, - -27.096650196234123, - -26.968707927363088, - -26.83995375834438, - -26.704144730972136, - -26.565968946554342, - -26.427652172387216, - -26.287307899422835, - -26.151541713723248, - -26.011902670125803, - -25.869222456010576, - -25.727646136726076, - -25.586396620153735, - -25.442464723509012, - -25.307541277935947, - -25.177722888531928, - -25.04600908381682, - -24.917121572267266, - -24.788125411527496, - -24.662039297282313, - -24.53182931521357, - -24.399620126439526, - -24.267452661191722, - -24.133540617960936, - -23.995636126760715, - -23.853515305897222, - -23.714171059538444, - -23.578191257976414, - -23.44216862851543, - -23.310895225673786, - -23.183907249776336, - -23.063520810172292, - -22.942438759213363, - -22.824832329508865, - -22.717735109243844, - -22.615610707046123, - -22.517291680403947, - -22.422491462697835, - -22.331134837332154, - -22.248243963609365, - -22.16978687815482, - -22.093176398706508, - -22.01944584829417, - -21.95121705486948, - -21.88579223943143, - -21.821502822345227, - -21.763843742305273, - -21.709343889518678, - -21.652646960406056, - -21.598710947348714, - -21.54846774613765, - -21.493919830806792, - -21.438652213157617, - -21.38442425464531, - -21.326744362612235, - -21.266598716013863, - -21.20500619847264, - -21.142429721477257, - -21.079348065052375, - -21.01472626823717, - -20.94951722524327, - -20.886028908842263, - -20.822940275257913, - -20.75488132953802, - -20.69074946712982, - -20.629465710400524, - -20.567361864538576, - -20.504057880498937, - -20.44361271371172, - -20.38431961969177, - -20.32272947393359, - -20.259079127211745, - -20.190229059079506, - -20.116169726382388, - -20.034808625595353, - -19.94606171186625, - -19.853561276949925, - -19.754038063000156, - -19.650394833854403, - -19.544781420698843, - -19.43262049913946, - -19.314214499500526, - -19.1902777316672, - -19.061786076432135, - -18.933767326625006, - -18.79853376685333, - -18.661247472734505, - -18.52719926587841, - -18.38940716913294, - -18.246644100954516, - -18.106142906429113, - -17.964895443170374, - -17.8159615878383, - -17.664483037358462, - -17.51443774750091, - -17.355682865318865, - -17.197776038334222, - -17.039103784047885, - -16.874082576074187, - -16.702668619872654, - -16.537701235242935, - -16.370540557097137, - -16.18695180139197, - -16.016725783392605, - -15.841114752710066, - -15.6509785869013, - -15.4640804517942, - -15.276518958243155, - -15.083292607797304, - -14.888891144387616, - -14.69838754911703, - -14.50406689039443, - -14.307454029086736, - -14.111003316125702, - -13.912422283353548, - -13.713651235853419, - -13.513900237430422, - -13.314401368792659, - -13.111179904798744, - -12.911452707155615, - -12.709102012793903, - -12.510644090152551, - -12.313918253669252, - -12.114851699028497, - -11.919709982314373, - -11.726520385163177, - -11.529653227947433, - -11.334206437284548, - -11.141027640066572, - -10.947911924409743, - -10.754110868757065, - -10.565428209175893, - -10.377840332203059, - -10.185543787097933, - -9.994676687883254, - -9.8099209645742, - -9.625504437036492, - -9.436851783690933, - -9.258801554602389, - -9.083457851716325, - -8.902209382937015, - -8.727783505526311, - -8.555528958324672, - -8.381863023688284, - -8.207941606531735, - -8.031832381492727, - -7.852682171794043, - -7.677737487619914, - -7.499830232370012, - -7.32343444121509, - -7.15412986713176, - -6.97742937956745, - -6.808263461437903, - -6.645239230553583, - -6.480126330553118, - -6.321610129894153, - -6.171406040112868, - -6.025782510531592, - -5.8840604152574105, - -5.750222640994218, - -5.620357549438017, - -5.499672325962924, - -5.3875974493949625, - -5.27970169969005, - -5.181373672890584, - -5.09244340726824, - -5.010364330417337, - -4.939180123770951, - -4.87932959992753, - -4.83092898776508, - -4.794338018227281, - -4.770845822589469, - -4.761479650395224, - -4.767347263675286, - -4.790003260981669, - -4.83002707553688, - -4.8857563635534556, - -4.962009810454228, - -5.062494608257472, - -5.182496145017407, - -5.319464080856335, - -5.48646447435295, - -5.6781672343620535, - -5.8818786152041165, - -6.1093658639785975, - -6.353615042867167, - -6.607929683684417, - -6.8780239507149, - -7.16209689562419, - -7.456209988506733, - -7.755236388109119, - -8.065939563465781, - -8.383962262434833, - -8.703661947642509, - -9.029328828734164, - -9.351076408907938, - -9.670234092492473, - -9.990746753030484, - -10.310794466310988, - -10.624628182040013, - -10.937141983048106, - -11.246744698762829, - -11.551981303232175, - -11.854876207444745, - -12.152643821505787, - -12.447524421561937, - -12.740226959383119, - -13.025775042882891, - -13.31259659865821, - -13.598497596494655, - -13.878944892651946, - -14.160843513240069, - -14.445097367089, - -14.72880539492346, - -15.012365001907149, - -15.326899446551678, - -15.61753894322012, - -15.907490575849256, - -16.199323265377256, - -16.49399935871493, - -16.792340988507664, - -17.096481318043487, - -17.40324943071121, - -17.71432425738958, - -18.03554537615367, - -18.358983961304972, - -18.682138973977246, - -19.0180636692091, - -19.353281887089786, - -19.6902777995624, - -20.02729388854081, - -20.38171430666889, - -20.732631105220477, - -21.07599373850713, - -21.44454535889323, - -21.81149554677682, - -22.16536606181982, - -22.534285346715343, - -22.91203407012189, - -23.27393526122621, - -23.64896254038367, - -24.031010326557475, - -24.399525504603716, - -24.776205613627123, - -25.156406424881997, - -25.526184129708575, - -25.8994498320983, - -26.283550700911295, - -26.66314143660697, - -27.038982509312035, - -27.423303471452627, - -27.809498058081246, - -28.189723880756414, - -28.57597217680803, - -28.96952099376038, - -29.36163903154931, - -29.754513215060598, - -30.15316752755474, - -30.544086102844883, - -30.929702536223648, - -31.320676052334807, - -31.700346764452423, - -32.07358755573875, - -32.458027951279476, - -32.83454559896451, - -33.205169920591686, - -33.58145862924901, - -33.9576391690854, - -34.32451164127945, - -34.69708534191942, - -35.07466363624796, - -35.44092166896769, - -35.8112400397407, - -36.22187416482816, - -36.58558715914228, - -36.95019923390805, - -37.30722039055362, - -37.66022645519799, - -38.013865676811584, - -38.36429207274727, - -38.71955888602662, - -39.08086347353355, - -39.437007420312284, - -39.80208930662878, - -40.174053129625705, - -40.536293716082035, - -40.894992762822845, - -41.26334274470197, - -41.62206518692534, - -41.973968096581395, - -42.33501311442969, - -42.689788615724005, - -43.02963554909753, - -43.37327266607992, - -43.72533593541936, - -44.06457962885775, - -44.4099779056109, - -44.75767671814547, - -45.09718448453561, - -45.43531725412767, - -45.776304553782836, - -46.108939369182984, - -46.44315197593767, - -46.77671320836342, - -47.1097916500584, - -47.44092674373454, - -47.77223045426809, - -48.10040012601571, - -48.4314894830876, - -48.75754412267551, - -49.078659471510015, - -49.40134906470348, - -49.720839445720365, - -50.040349840036484, - -50.360188312589415, - -50.682491734446636, - -51.0052570146535, - -51.327311560291925, - -51.649295372723095, - -51.974327279246154, - -52.29802564782532, - -52.61238112329573, - -52.93298379299863, - -53.25988223727866, - -53.60583207414197, - -53.92246057642615, - -54.24806808279626, - -54.56842567866411, - -54.88147735525404, - -55.20225750322398, - -55.52506010969101, - -55.8387378677252, - -56.15384444336004, - -56.473451500630524, - -56.78653006164733, - -57.09791242056369, - -57.40896515875888, - -57.71766858472592, - -58.021961041411565, - -58.32165198305714, - -58.62245827442661, - -58.92386458923721, - -59.217323747072484, - -59.50993694388504, - -59.838094191706325, - -60.131659958931856, - -60.41831426312358, - -60.71057614856131, - -61.00365228998208, - -61.293513825360534, - -61.58340389910705, - -61.87590932124566, - -62.16118369846589, - -62.438659026915936, - -62.708841181370545, - -62.98038388744832, - -63.243801013062196, - -63.494203051516244, - -63.751191428207626, - -63.999712028628686, - -64.2406005326087, - -64.47703712670896, - -64.70642542945515, - -64.92931317062418, - -65.16318724935785, - -65.38729506878302, - -65.6060726891053, - -65.81616202686729, - -66.01449779138751, - -66.21162846234624, - -66.38659094581782, - -66.56085536796608, - -66.73244684473043, - -66.89035451771738, - -67.03507457511772, - -67.16900249744889, - -67.29275896729585, - -67.41457951260044, - -67.52543905902068, - -67.62724231781792, - -67.72924406711621, - -67.82068476790911, - -67.89999965240955, - -67.97326809434492, - -68.03443977924331, - -68.08705114968794, - -68.1302694767572, - -68.16066800177673, - -68.18272920647078, - -68.19867952246226, - -68.20181207445387, - -68.18951883961707, - -68.1646274842005, - -68.12918384282501, - -68.08260255189471, - -68.02393911772455, - -67.95286829617942, - -67.86868226662678, - -67.7702939523941, - -67.66037218650199, - -67.53937115307448, - -67.40384807520357, - -67.2596935111753, - -67.10973633176081, - -66.94149530078502, - -66.7680674613186, - -66.59164428152881, - -66.41174341663618, - -66.23469514052006, - -66.0554457105644, - -65.86565807463982, - -65.67983002419086, - -65.49355369495187, - -65.29764628527755, - -65.1033288156557, - -64.91078935487995, - -64.71669034036273, - -64.51016631909441, - -64.30264164333961, - -64.0939707719879, - -63.879767744820796, - -63.66013353700236, - -63.43950714809001, - -63.21546653838599, - -62.989324697392306, - -62.76366186457419, - -62.53377246857059, - -62.30305713381066, - -62.07500725259491, - -61.84397569998243, - -61.61013784941881, - -61.37655537051623, - -61.13853762360535, - -60.89692275488019, - -60.65466443261562, - -60.41124009451162, - -60.16567979786915, - -59.8992134922145, - -59.65392790922492, - -59.41130718281685, - -59.1727282859495, - -58.93186539834098, - -58.69888095003819, - -58.474625899546936, - -58.249619840917575, - -58.02886352448362, - -57.82697080168654, - -57.61986416040366, - -57.412477854243484, - -57.21790629901126, - -57.01417455503435, - -56.80427539332728, - -56.60051983870767, - -56.3909301755096, - -56.17867322852458, - -55.96567590669834, - -55.75002019127368, - -55.53821000436251, - -55.32275563397752, - -55.097034951736006, - -54.874554282590935, - -54.65154556264045, - -54.42015676403187, - -54.1891977712623, - -53.9614974957198, - -53.72591319541674, - -53.48680118342321, - -53.25012897881014, - -53.00595907394144, - -52.75762124270159, - -52.51642386106821, - -52.27492439426055, - -52.03446135545029, - -51.80338771123684, - -51.570131743521394, - -51.339573288905584, - -51.111819435022326, - -50.8786841191399, - -50.640249050916225, - -50.398346501704374, - -50.157928984684986, - -49.91153730186999, - -49.65681732613714, - -49.39851113453391, - -49.138684563959714, - -48.87561029299528, - -48.61332713480645, - -48.351313973049365, - -48.09391763721541, - -47.844131904719525, - -47.5925508667915, - -47.33823620512275, - -47.084624928978656, - -46.837978267530694, - -46.582914096065664, - -46.32267761569632, - -46.06674810210955, - -45.81358593373239, - -45.55259010126162, - -45.28519390370538, - -45.02927634043554, - -44.781689275642115, - -44.52085863738756, - -44.26726591293619, - -44.03319750372196, - -43.783763958900835, - -43.52248442722238, - -43.27260548524963, - -43.02231897415474, - -42.761132332254896, - -42.49383754189107, - -42.23604587339814, - -41.98449023263584, - -41.713577270098575, - -41.43731140915635, - -41.16821530747471, - -40.88274234060668, - -40.584601594446006, - -40.29027130515817, - -39.981488308192475, - -39.66911822323395, - -39.359846685451615, - -39.04055651844393, - -38.71213240045084, - -38.387212631084445, - -38.0545504745387, - -37.71601498515601, - -37.391258543936985, - -37.05362203171195, - -36.700536008170076, - -36.35747655690082, - -36.015072282920364, - -35.66764202829099, - -35.32003928951747, - -34.98211857521233, - -34.64601291789126, - -34.31012468152238, - -33.99917280616775, - -33.69036934635618, - -33.37252637187671, - -33.07801542439387, - -32.793133970565, - -32.49856686616356, - -32.22140147035971, - -31.95255704580614, - -31.68582930214602, - -31.423631772945555, - -31.1739095830452, - -30.930711126470772, - -30.692076432081222, - -30.46416432851567, - -30.244015760179764, - -30.034802928863694, - -29.83187604724801, - -29.632595413163973, - -29.440857524061972, - -29.258080208780836, - -29.079226062327194, - -28.902690554308926, - -28.735352235137242, - -28.570039077963198, - -28.40421427345232, - -28.244859088491445, - -28.092574801800435, - -27.943005642885478, - -27.799709405209214, - -27.664916180262097, - -27.529275668507786, - -27.394708065742588, - -27.26959806318795, - -27.144448935461774, - -27.01768573990916, - -26.89787609366886, - -26.777365424158678, - -26.65398058306212, - -26.53442257492223, - -26.413244125949667, - -26.2905665921127, - -26.16954957018384, - -26.047865366896147, - -25.921803248337532, - -25.795793335642138, - -25.671125904950184, - -25.542272870482364, - -25.416761141290415, - -25.292304464815377, - -25.16654336774769, - -25.041264557897748, - -24.916893199446427, - -24.79358078621804, - -24.672231319722187, - -24.548652199182136, - -24.42655841947077, - -24.305231593550875, - -24.18320677676784, - -24.064023907822595, - -23.945339160114113, - -23.8289148212615, - -23.71282700567663, - -23.597508985821865, - -23.482437735536017, - -23.370468805176095, - -23.251013585785863, - -23.142821782250813, - -23.041046932935984, - -22.942268845593144, - -22.844489189901505, - -22.74958296518811, - -22.655536346114808, - -22.563102470299114, - -22.477491037207717, - -22.393557353489836, - -22.30970519529215, - -22.226692937187224, - -22.14600634224972, - -22.06266736309336, - -21.975538256320444, - -21.896577154454505, - -21.82141801150044, - -21.74538678778868, - -21.671662864113483, - -21.60365542603736, - -21.535091750690743, - -21.464296664202067, - -21.398950542882325, - -21.33559701583881, - -21.27496859266713, - -21.214309574897396, - -21.1521963503551, - -21.091359317870097, - -21.030699439283005, - -20.969579625976433, - -20.9098221161416, - -20.85162585422419, - -20.79021143043873, - -20.72591263963573, - -20.66632930359653, - -20.606756013391703, - -20.54793563100285, - -20.489295377111368, - -20.432874415698684, - -20.378494230646304, - -20.32391958757059, - -20.269627165249354, - -20.213192398605802, - -20.15483064850556, - -20.095594385340217, - -20.033812313778647, - -19.969942780704837, - -19.90350039406957, - -19.833527866239653, - -19.764014785982017, - -19.692108766412368, - -19.61360639638979, - -19.532550458494118, - -19.44773062430693, - -19.355592283156742, - -19.25834594038665, - -19.1534272375535, - -19.043982858127226, - -18.92849206129195, - -18.806684199137845, - -18.67850867398856, - -18.54067541708158, - -18.396960040558653, - -18.249224811303247, - -18.091554930154057, - -17.926856700358016, - -17.761750058542518, - -17.58543179215636, - -17.405605300622042, - -17.22859798607869, - -17.039129325914118, - -16.848666693439938, - -16.6686330336351, - -16.47652264047373, - -16.278866978601055, - -16.09137994161027, - -15.897040527105835, - -15.693751042780153, - -15.4966742148757, - -15.298197050089271, - -15.089348171692212, - -14.885089128457635, - -14.6819258564195, - -14.449113779667437, - -14.238462294996125, - -14.027180938854725, - -13.810463310106211, - -13.59211177590087, - -13.377071793323289, - -13.159329879227819, - -12.947782978232762, - -12.73648038212877, - -12.525048836825933, - -12.315720323875656, - -12.109352970906356, - -11.906677108230163, - -11.705393518953267, - -11.505387198968648, - -11.30924365056562, - -11.114067544486828, - -10.918693505094573, - -10.726333082328877, - -10.539315941056248, - -10.351655575671991, - -10.164587177282716, - -9.97766109026659, - -9.79021576216002, - -9.602406903104615, - -9.415187739159482, - -9.230366463441761, - -9.044213924765177, - -8.862251104887306, - -8.681349789377212, - -8.501347110457658, - -8.321457502881403, - -8.140273101105624, - -7.962422570741458, - -7.7838871558740985, - -7.604338394898698, - -7.425114977611501, - -7.249151616998797, - -7.071273543879868, - -6.899545543739369, - -6.737215706948102, - -6.571567806855794, - -6.399927947089783, - -6.232808456374319, - -6.070741063907515, - -5.902810867076883, - -5.741294598085184, - -5.586845810918248, - -5.426456899643438, - -5.27174834862525, - -5.129183736000645, - -4.9889571805071835, - -4.86339172223333, - -4.750069251820169, - -4.642505876003119, - -4.54585226879615, - -4.460211877510048, - -4.384058913325851, - -4.321146436868113, - -4.27187270826552, - -4.236265106477961, - -4.216005860397327, - -4.210176772519647, - -4.220354095654507, - -4.2473615803990485, - -4.292681161497685, - -4.3587749747053355, - -4.445349518086225, - -4.5524076363952135, - -4.683500954836085, - -4.8432594067400325, - -5.022028914400991, - -5.2191401875980645, - -5.440063084845116, - -5.672922677038756, - -5.922664565901052, - -6.188808705343841, - -6.461947549427972, - -6.754117920110981, - -7.052798465791427, - -7.35059411751251, - -7.661967325805363, - -7.9832890317025464, - -8.297017429364743, - -8.611832612467229, - -8.930462069406301, - -9.240934484010658, - -9.550160389278119, - -9.862375700301817, - -10.168760128912231, - -10.473256055642691, - -10.777581275065579, - -11.075524237624167, - -11.371149705828651, - -11.662907304778852, - -11.952265851473792, - -12.240132377325695, - -12.52370127523571, - -12.808053908403776, - -13.097543095082074, - -13.384641468399407, - -13.669836436712401, - -13.958753857364563, - -14.250420843215275, - -14.541161131699276, - -14.832444982102599, - -15.131949392039019, - -15.431893213659425, - -15.734957774675108, - -16.04875672451202, - -16.36280414491753, - -16.683553232004968, - -17.00699308186, - -17.332747334602168, - -17.667887062929207, - -18.006987923791336, - -18.34423684463063, - -18.695508690381114, - -19.04334643942763, - -19.383285249998647, - -19.72287251600759, - -20.078413829905095, - -20.43400135525887, - -20.776686380526844, - -21.14124394717289, - -21.50906632415472, - -21.86146422365928, - -22.224969733501066, - -22.604764968625048, - -22.966135933097714, - -23.333190888492236, - -23.712322423120806, - -24.07678349836263, - -24.44302401814183, - -24.81916976232616, - -25.184358791921095, - -25.550925890268402, - -25.92440996628066, - -26.299281066303568, - -26.671911481988346, - -27.04590893036592, - -27.42363718412834, - -27.799273898283765, - -28.177081677650502, - -28.555931951833543, - -28.938372998127534, - -29.320798679575173, - -29.703302227329466, - -30.085839146691445, - -30.464179820922475, - -30.838759530642555, - -31.217494140793907, - -31.583673161430763, - -31.94729185703748, - -32.321546013104644, - -32.68507945473096, - -33.047322176730255, - -33.414348603841425, - -33.77725214880683, - -34.13121959916513, - -34.49136493089003, - -34.858149523061954, - -35.21317117890908, - -35.57320167927696, - -35.93912655339301, - -36.297759702010254, - -36.658166114989136, - -37.01584278101903, - -37.363671882451406, - -37.71918818737856, - -38.07009011853977, - -38.4192419354633, - -38.779972176411505, - -39.138676472252456, - -39.49906960422623, - -39.869975854523005, - -40.241600283067065, - -40.60342805716733, - -40.971095771213015, - -41.339607651174774, - -41.69576764207521, - -42.05619454683223, - -42.41976727018062, - -42.7712731748833, - -43.117881304040026, - -43.47096678291186, - -43.81918218196119, - -44.160421813372125, - -44.51270227679648, - -44.863395806909736, - -45.20718075785223, - -45.558118553094246, - -45.899440869304115, - -46.24028870659253, - -46.58268028396712, - -46.922831346866076, - -47.26038864953452, - -47.6007955930503, - -47.938188878742935, - -48.27607148286675, - -48.611115283100666, - -48.94177586453975, - -49.27426430952204, - -49.60512664717823, - -49.93364108685517, - -50.26499397829418, - -50.60010530903664, - -50.93593920746131, - -51.267822894194, - -51.59801866473734, - -51.93094760277337, - -52.26200271980654, - -52.58137243184985, - -52.90707399580594, - -53.23821734458246, - -53.558469572304226, - -53.879483425254215, - -54.2092128421484, - -54.54185155314612, - -54.88932727075317, - -55.24249321569978, - -55.596643036632805, - -55.942674701815115, - -56.290443054981836, - -56.640411972020516, - -56.98408075989082, - -57.325307407783605, - -57.666136180459816, - -57.99724724428649, - -58.310970848072145, - -58.619696760548145, - -58.92702186794036, - -59.236775048101684, - -59.537340151671366, - -59.83459656830051, - -60.13572461652187, - -60.4324845962634, - -60.72202133405235, - -61.00940804596916, - -61.284146701549226, - -61.555728698510464, - -61.82696216986305, - -62.10138520566945, - -62.37045248164464, - -62.63220986432724, - -62.88779565580989, - -63.14171686106158, - -63.42171388515108, - -63.65871347807436, - -63.90220543119827, - -64.14685131473944, - -64.380434954368, - -64.60878200641977, - -64.83653060712273, - -65.05782932678203, - -65.2770852740441, - -65.48701069616845, - -65.6911606816281, - -65.89607652863722, - -66.09474127384375, - -66.31184830494684, - -66.49555014564436, - -66.67650043253545, - -66.87310345199377, - -67.04243044693298, - -67.20109124786681, - -67.34934314279768, - -67.48868190342226, - -67.6152598900484, - -67.72943327169341, - -67.83696138410691, - -67.92957533813689, - -68.00756133962416, - -68.07396299553434, - -68.12490626916019, - -68.16165420916077, - -68.18447059190872, - -68.19471965844453, - -68.19422577114908, - -68.17963605247925, - -68.14973647685582, - -68.10357412857022, - -68.04309324752415, - -67.97207058491907, - -67.88761146640188, - -67.78784341323492, - -67.67681140481433, - -67.55214102633916, - -67.41354055578304, - -67.26579036318951, - -67.10583100720318, - -66.94292764651082, - -66.77491661115016, - -66.60226357385955, - -66.42403430874768, - -66.24711004653231, - -66.07194777803723, - -65.8888736709726, - -65.70669644053216, - -65.52605098415836, - -65.3389185521889, - -65.14908149935475, - -64.96048925841929, - -64.76972608456713, - -64.57381824928201, - -64.3791344660323, - -64.18148199195709, - -63.981151055753415, - -63.77752144969465, - -63.57319723378935, - -63.365163333170734, - -63.15492654382409, - -62.945898469985636, - -62.73241123742727, - -62.51923284037687, - -62.308349848833195, - -62.094569124912574, - -61.876731772078266, - -61.660221863054424, - -61.43827108087202, - -61.21159987807561, - -60.98462798178336, - -60.75627815165769, - -60.52564879010985, - -60.296167193870836, - -60.06459632240016, - -59.82995713548851, - -59.59667484648438, - -59.3579326006824, - -59.11505296780608, - -58.87564497207802, - -58.63757934739215, - -58.392745508136976, - -58.155700546167544, - -57.926264880692045, - -57.68475196623979, - -57.45165653454874, - -57.21967681709609, - -56.976653191345996, - -56.740985283310046, - -56.51031439087568, - -56.27255462907921, - -56.03777018960083, - -55.81333338627688, - -55.587746813302, - -55.351435034574585, - -55.119544184925374, - -54.89091806950956, - -54.65315513065476, - -54.41529335908701, - -54.18454709911138, - -53.94641026415759, - -53.70438234670335, - -53.467279125317376, - -53.22438777065321, - -52.97598323518786, - -52.73635432009008, - -52.49902106545069, - -52.26215693833489, - -52.032434838484114, - -51.80143886598082, - -51.57815664422095, - -51.35058741694427, - -51.12037014615864, - -50.88821687901644, - -50.64957361497919, - -50.41436834867109, - -50.17546861867721, - -49.92890091489961, - -49.6789750660276, - -49.429652796231004, - -49.17569703060559, - -48.9207764239108, - -48.67046159851721, - -48.41863653161014, - -48.17785718793287, - -47.93933897121058, - -47.67281443309361, - -47.42377282292627, - -47.185082938086424, - -46.94882815642885, - -46.700490486465725, - -46.45525309815263, - -46.21177766739795, - -45.97069543633762, - -45.719215041775186, - -45.47124758114668, - -45.22963354800662, - -44.990147497932135, - -44.7387569525379, - -44.48866234233836, - -44.24992910988856, - -43.99863821366199, - -43.732647083377834, - -43.47267251101343, - -43.217003439382125, - -42.95010965130786, - -42.676783674005726, - -42.41717333370034, - -42.164115996782556, - -41.89254509713656, - -41.61708458340238, - -41.34734913493048, - -41.061625157362165, - -40.7652650433777, - -40.47133710313652, - -40.16424603143145, - -39.85368225169909, - -39.54273118661796, - -39.222530030983044, - -38.89157386271389, - -38.563973957574525, - -38.227126143397115, - -37.88248697364101, - -37.55197748559018, - -37.20839009955219, - -36.85044275868542, - -36.50248672176635, - -36.156593284841016, - -35.80565575556108, - -35.457912478486016, - -35.12443794837501, - -34.79063364554585, - -34.46089862331865, - -34.158724860412335, - -33.85711200902962, - -33.54851771848214, - -33.26904674483539, - -32.99048511996118, - -32.70763129128961, - -32.44397959648887, - -32.186520092905944, - -31.92207919171088, - -31.66654454313218, - -31.423143867287802, - -31.180937758785337, - -30.941562837459823, - -30.710265389050218, - -30.48591565277127, - -30.27155217361085, - -30.06044039019869, - -29.852837116124395, - -29.65821965345719, - -29.47374363829907, - -29.289308221845356, - -29.11355146632258, - -28.94326228285456, - -28.771299701455444, - -28.60391715640494, - -28.44478188561241, - -28.287143868490215, - -28.128547136297414, - -27.982156688014772, - -27.84108800553709, - -27.695576842662707, - -27.55768435920355, - -27.427185144312723, - -27.29078783811361, - -27.15701972986323, - -27.02789292391146, - -26.89630659737769, - -26.766524754676166, - -26.63890827340488, - -26.50998986811527, - -26.37930138100591, - -26.252635785012448, - -26.122613742951934, - -25.989233641777307, - -25.85619187003529, - -25.723001737915244, - -25.58702980593626, - -25.45334178306973, - -25.320643132813696, - -25.186769046028385, - -25.056151207291038, - -24.925521577812056, - -24.799887659456303, - -24.67113774492623, - -24.541946985087716, - -24.41353367974446, - -24.284415243938945, - -24.157379816213925, - -24.028791788956305, - -23.90251251487836, - -23.778305565422993, - -23.652621510385604, - -23.52801573154487, - -23.406664723236712, - -23.290583916296562, - -23.17299805591505, - -23.05803106552739, - -22.948452539768354, - -22.840906137286407, - -22.737569530668804, - -22.636938082674405, - -22.538817962300598, - -22.44839958144037, - -22.360081603669116, - -22.271002634935414, - -22.184900618477602, - -22.103239130672712, - -22.014479762357627, - -21.925076219122143, - -21.84358296127434, - -21.762901278132713, - -21.680065064600818, - -21.603796169976505, - -21.5298319625657, - -21.448699523720126, - -21.37053181201758, - -21.29522768411689, - -21.220193220675228, - -21.144932436311436, - -21.069502756738537, - -20.993000401104982, - -20.915139598245805, - -20.836362476713152, - -20.759848821063958, - -20.685694248929767, - -20.607965797768685, - -20.531906658937547, - -20.4582291401625, - -20.38468112958522, - -20.309451168894814, - -20.238488598494687, - -20.169293725160717, - -20.098530092779974, - -20.02660230942389, - -19.9500141454091, - -19.869935506011178, - -19.786749288357925, - -19.70078623204097, - -19.611337121528702, - -19.517673369750533, - -19.42401636348683, - -19.32484162536539, - -19.219512380743346, - -19.11009234439682, - -19.00561746281542, - -18.900630452626732, - -18.789210306109172, - -18.67288115520019, - -18.55344480226453, - -18.4306162347505, - -18.301523436571486, - -18.166633892675442, - -18.030478909515868, - -17.891823566838152, - -17.735483461156054, - -17.573967505978977, - -17.40960829443117, - -17.23748555687319, - -17.068687548978406, - -16.898923225515574, - -16.71677063759025, - -16.541886205758647, - -16.370041594298264, - -16.1794668729959, - -16.002906841016575, - -15.838150680923476, - -15.65541404846038, - -15.470282902125652, - -15.28934621217244, - -15.10011313197145, - -14.904843790414107, - -14.715755247753119, - -14.52645821299971, - -14.332290870385137, - -14.132606731027836, - -13.931727493688731, - -13.72738080668493, - -13.520244894338862, - -13.314763867680039, - -13.10528222978969, - -12.898854902486203, - -12.689737788942864, - -12.483305136228353, - -12.281972521953938, - -12.052623322930717, - -11.817743968530818, - -11.584338453453785, - -11.348256864236905, - -11.114342842430563, - -10.883604701583929, - -10.654761443621585, - -10.42478171950886, - -10.195302979942849, - -9.97475231693026, - -9.769998519232248, - -9.571054807203446, - -9.375417913997303, - -9.184170727774703, - -8.988597397886682, - -8.791890416085007, - -8.602719953838504, - -8.411860111056003, - -8.21997760218974, - -8.031556981128379, - -7.8376941515003775, - -7.643111751732136, - -7.447022164396884, - -7.249836894600815, - -7.05142909650045, - -6.864192343081893, - -6.673116519509215, - -6.480025557699567, - -6.298781596663485, - -6.114105451143301, - -5.937361607614952, - -5.7721289455864175, - -5.607215117982718, - -5.4434819972844135, - -5.288422461368478, - -5.137776625133515, - -4.987381387024947, - -4.846559694129956, - -4.709753934769112, - -4.578624702006177, - -4.457572723125548, - -4.339024241729415, - -4.2294753258954865, - -4.130914987869087, - -4.039879148273867, - -3.95657914556615, - -3.8826764758420067, - -3.8201087528016426, - -3.7672292828033918, - -3.7256977397103426, - -3.6955138118894784, - -3.6770146209065997, - -3.6715946955947816, - -3.6808656487423788, - -3.7055355155165337, - -3.7449386071828585, - -3.802030474497758, - -3.8794570338897474, - -3.97420013018582, - -4.083911746718939, - -4.221500530721805, - -4.387535942198094, - -4.566653020215587, - -4.76113262777675, - -4.976709965202321, - -5.199257730520783, - -5.434835159250235, - -5.685380549926435, - -5.9428732363886, - -6.21238316471042, - -6.50696499359925, - -6.773886359439698, - -7.053750767225963, - -7.33973572622452, - -7.626456913534832, - -7.916782464454037, - -8.205646712319059, - -8.492050094030459, - -8.779053840349983, - -9.064313604001057, - -9.33384660439048, - -9.61646527958896, - -9.900424270673751, - -10.183177791607156, - -10.46027226751575, - -10.739440009601028, - -11.016061103154998, - -11.288266148574056, - -11.56284721691582, - -11.832733983018528, - -12.10052109320295, - -12.373206564594877, - -12.643139739294062, - -12.911854727461288, - -13.185682238104803, - -13.46016140509024, - -13.735541888662391, - -14.012805277113669, - -14.291571137100174, - -14.576080596574343, - -14.861663923350035, - -15.147062863209158, - -15.436449379522982, - -15.729661487595468, - -16.025683577990534, - -16.3259641118826, - -16.628643167328327, - -16.93640083820361, - -17.25237864626378, - -17.56434155192122, - -17.881837796544843, - -18.21125739537088, - -18.535305797214715, - -18.863330300252386, - -19.190294409900005, - -19.531916121181638, - -19.869821903325168, - -20.197928657670445, - -20.5461424621001, - -20.892740304918068, - -21.226708387833042, - -21.570438651134808, - -21.92730913622124, - -22.27337495356273, - -22.619024390057913, - -22.976571053052066, - -23.32787112560278, - -23.673687321816168, - -24.02903025793823, - -24.381686420947037, - -24.726948925539567, - -25.07982105962973, - -25.427353101501105, - -25.781701017069786, - -26.13694409316997, - -26.48784201106306, - -26.84263462170883, - -27.200202960430932, - -27.557248079750657, - -27.912253275792036, - -28.27559316550701, - -28.63439632886228, - -28.991763551401778, - -29.353511115547064, - -29.709783645660497, - -30.01323901761087, - -30.362695436940708, - -30.710804430413184, - -31.048522993817613, - -31.392226461220748, - -31.737511267222768, - -32.072843154855654, - -32.41893289161984, - -32.76050294582449, - -33.093835998479435, - -33.43253142031484, - -33.774557551109254, - -34.11879081435566, - -34.45416380248082, - -34.79214542782523, - -35.13956589482416, - -35.47964635722244, - -35.82015204080372, - -36.15523614887767, - -36.479142864119574, - -36.80674706483185, - -37.1291116637628, - -37.447048364440334, - -37.764806536344665, - -38.08264704370983, - -38.39453813804148, - -38.710798351912224, - -39.02222979718832, - -39.32246295221218, - -39.6186140469893, - -39.90659619198359, - -40.18426418681222, - -40.45012198626207, - -40.74392973947109, - -41.00145920924832, - -41.24388350087197, - -41.48352599803586, - -41.71949558891751, - -41.943007478604, - -42.162533594962134, - -42.3767548274806, - -42.58190509390349, - -42.7769890588805, - -42.96672207836876, - -43.14921278631825, - -43.32522528291063, - -43.49400343403272, - -43.655386636374224, - -43.80946632043466, - -43.95835746958686, - -44.0986616858918, - -44.234111722028814, - -44.362705841581004, - -44.48787799190498, - -44.60818177282764, - -44.726030293359415, - -44.84005633801287, - -44.95205489166338, - -45.05506360824793, - -45.153203812309336, - -45.24850106503814, - -45.337966490095056, - -45.42247563763865, - -45.46732325894877, - -45.545759674876685, - -45.61877177427002, - -45.68643047744021, - -45.747090283895865, - -45.804888994986875, - -45.857196480917096, - -45.90643402647283, - -45.95488229329985, - -46.00148330239156, - -46.04480654641061, - -46.084664143937616, - -46.121982462449786, - -46.156163476189214, - -46.185184775311804, - -46.21000581689569, - -46.231883910132005, - -46.2501290064271, - -46.26582681121732, - -46.27905374974234, - -46.288700712577295, - -46.29704694548059, - -46.30527065409081, - -46.31250846518448, - -46.317928943784885, - -46.32228100271273, - -46.32542482762396, - -46.32747488306811, - -46.328919653780396, - -46.32986608599402, - -46.3304398726619, - -46.33083244968079, - -46.330799733883694, - -46.330557374228555, - -46.330329932323, - -46.330030683635066, - -46.32966117343729, - -46.32929646015045, - -46.32893328567334, - -46.32857092034011, - -46.32817699677578, - -46.32776764111201, - -46.32763750722102, - -46.32752353585319, - -46.32741971950408, - -46.327311341827425, - -46.32721412055969, - -46.32712851929781, - -46.32704343720672, - -46.326961885047375, - -46.326889645591145, - -46.3268292156383, - -46.32625332436312, - -46.32558996719882, - -46.32489536106943, - -46.324172070980374, - -46.32341546088188, - -46.31854893589611, - -46.3177119394207, - -46.31683521102417, - -46.31590373459938, - -46.31493176385335, - -46.31468611420354, - -46.31452037781347, - -46.31434516935154, - -46.31416596403488, - -46.31398190557863, - -46.313789053324385, - -46.31359229044191, - -46.313388579072296, - -46.3131777660119, - -46.3129605319642, - -46.31220793694785, - -46.31137463406303, - -46.31051845738101, - -46.30964367184241, - -46.308749128709785, - -46.30783345566822, - -46.3068996753256, - -46.30594324377183, - -46.30496486113546, - -46.303964665004116, - -46.30360411258737, - -46.30330338414397, - -46.30299313539405, - -46.30268222063515, - -46.30236990386346, - -46.30204335822196, - -46.30171050285596, - -46.30137528525517, - -46.30102610097923, - -46.30067419875487, - -46.298681681678026, - -46.29643981480972, - -46.29415891872216, - -46.29185035169715, - -46.28952100105424, - -46.2871632931724, - -46.28476434163069, - -46.282341589514715, - -46.279900163436906, - -46.277397162465554, - -46.276858249478906, - -46.276545553239885, - -46.276237437701376, - -46.275939097285224, - -46.27563698229068, - -46.27533217631425, - -46.27502008355396, - -46.27466962203694, - -46.274343699054235, - -46.27402063184802, - -46.27393243420421, - -46.27384803666774, - -46.27377608733807, - -46.27370256016782, - -46.27361375448261, - -46.27352735658383, - -46.27344759052145, - -46.27336324828337 + -34.20850096446654, + -34.208238954743685, + -34.20792902100424, + -34.20760757184568, + -34.20738361846996, + -34.20720176000561, + -34.20683416597183, + -34.20650648822083, + -34.20608935588558, + -34.20572966544402, + -34.20539047307245, + -34.204978189129015, + -34.204550257854706, + -34.20419937583317, + -34.203851648593165, + -34.20343169052313, + -34.203042274235045, + -34.20264363032312, + -34.2023726490794, + -34.202098140666784, + -34.20181134675162, + -34.20148933862536, + -34.20121738216338, + -34.2009080994932, + -34.20063643983228, + -34.20034481742374, + -34.2000696237222, + -34.19983311428898, + -34.19961392234484, + -34.19937365514169, + -34.199189402854074, + -34.19900317603461, + -34.19880114105563, + -34.19861066740314, + -34.19837645150039, + -34.19816029290118, + -34.19797297627397, + -34.19781332693034, + -34.197621612689275, + -34.19741383124952, + -34.19727147453903, + -34.19707929682523, + -34.196825570993276, + -34.19668981102975, + -34.1965642221961, + -34.196420248329694, + -34.196235418026966, + -34.196100527762006, + -34.19595528348216, + -34.19577717294135, + -34.19561281660328, + -34.19541564722681, + -34.19522091075678, + -34.19506867319604, + -34.19491322906737, + -34.19475617348167, + -34.19456738946074, + -34.19441257759611, + -34.194305608523415, + -34.19413890108838, + -34.19402563257533, + -34.193871851019416, + -34.19370503405217, + -34.19358027267171, + -34.19344531751981, + -34.19329006230464, + -34.19314564970173, + -34.19281770202517, + -34.19237269478954, + -34.19196721038553, + -34.191578273729284, + -34.19110684869285, + -34.19059806524432, + -34.19014443601172, + -34.18971520292186, + -34.18923602362348, + -34.18869913427268, + -34.18833003245038, + -34.18794166622675, + -34.18751483624891, + -34.187190230565314, + -34.18680050834423, + -34.18632317786081, + -34.185942639398604, + -34.18557941319778, + -34.185093513453985, + -34.18464292833133, + -34.184145833297634, + -34.1835690413308, + -34.183009218187, + -34.18245641784577, + -34.18194165756511, + -34.181411245583405, + -34.180842191387, + -34.18031070625432, + -34.17977878608106, + -34.179274141905964, + -34.178791235572014, + -34.17844353743938, + -34.178133542359454, + -34.17772043770016, + -34.17732671873731, + -34.17705071666225, + -34.17674574279609, + -34.17648907354066, + -34.17609695070887, + -34.175650899786554, + -34.17532133596385, + -34.1749278740639, + -34.1745363562516, + -34.17415109707245, + -34.17368635309034, + -34.173255122177345, + -34.172899756560206, + -34.17251040591449, + -34.172086874520765, + -34.171630360950736, + -34.17117119532719, + -34.17084558026226, + -34.170524084280146, + -34.170110063374906, + -34.16967258385827, + -34.16930042973883, + -34.168970613859635, + -34.16856304460919, + -34.16811576085387, + -34.16768676123481, + -34.16736099295385, + -34.167124898097356, + -34.16672691923807, + -34.16629949645637, + -34.166020544017336, + -34.16567348824885, + -34.165206629486555, + -34.1649102522274, + -34.16442554900806, + -34.16411656055334, + -34.163835743037595, + -34.163667960830786, + -34.163287829216934, + -34.16288151302674, + -34.16269395430048, + -34.16238991455418, + -34.162026429660955, + -34.161650280510415, + -34.16120406524903, + -34.16081468768969, + -34.16051969428689, + -34.16009094929095, + -34.15946914274596, + -34.159176862117704, + -34.15888727213249, + -34.15848397635331, + -34.15805064953907, + -34.15768222447644, + -34.15741075690409, + -34.157199236984766, + -34.15702885116569, + -34.156646530479655, + -34.15631433417576, + -34.15610539694631, + -34.155873450868484, + -34.155492955086224, + -34.15500939848627, + -34.15434250697164, + -34.15403249529436, + -34.15373559707832, + -34.153195077612814, + -34.15237223406272, + -34.151197823002306, + -34.150389061340434, + -34.14972355532398, + -34.14876182425223, + -34.147753205875084, + -34.1468315985221, + -34.14592332052173, + -34.14499865748368, + -34.14413081753902, + -34.14326697595306, + -34.14235363131009, + -34.141504566972635, + -34.140670341648466, + -34.13977560684852, + -34.138843663846956, + -34.13797352118324, + -34.13704209938618, + -34.136104337300594, + -34.13535680475344, + -34.13475717277114, + -34.13405664376714, + -34.13324167350189, + -34.13239793097516, + -34.13162108183035, + -34.13104483686513, + -34.130370325655754, + -34.129575170192076, + -34.12883978107497, + -34.12818004157837, + -34.12769342542458, + -34.12707652242479, + -34.12625640229815, + -34.12573308632649, + -34.1251498038307, + -34.124445847032156, + -34.12353836877944, + -34.122053316887815, + -34.1211257367895, + -34.119724360218534, + -34.11843319269593, + -34.11718493708246, + -34.11338507210205, + -34.10590214862871, + -34.09282073690137, + -34.07236785491298, + -34.04366888084793, + -34.007605138373535, + -33.96775324384806, + -33.92893317560639, + -33.89642176487315, + -33.87043613439064, + -33.85153191238244, + -33.83740516873628, + -33.82726615508978, + -33.820250147386204, + -33.81406643483115, + -33.806553260040644, + -33.79553734291343, + -33.77741136696219, + -33.751353316306194, + -33.71687278795068, + -33.673404994787944, + -33.62118686393082, + -33.56068922257415, + -33.49143699335243, + -33.412834311016205, + -33.3237099791763, + -33.22310971008737, + -33.11154866410422, + -32.990842000614734, + -32.86212511539496, + -32.72309606849177, + -32.57062017013406, + -32.40851697353658, + -32.23720250997644, + -32.05784746076087, + -31.866728622723116, + -31.666281580501536, + -31.45888722393481, + -31.236188791114166, + -31.006924763292396, + -30.77239936272471, + -30.52223313580673, + -30.2651984576044, + -30.000474598875655, + -29.731386707719196, + -29.452770053026384, + -29.16946897839721, + -28.89232263981253, + -28.60861583098035, + -28.320690784708873, + -28.03548898720037, + -27.750887893729637, + -27.462116131387482, + -27.179759975432518, + -26.903824475123297, + -26.631328055718043, + -26.36043103504407, + -26.096833531141332, + -25.850422454635652, + -25.602392293361373, + -25.35759661816489, + -25.14796974324249, + -24.936472171543887, + -24.729593124054873, + -24.537083022661065, + -24.353155730789634, + -24.178930832936064, + -24.00913393888203, + -23.839729121837294, + -23.687506229039517, + -23.537568073364582, + -23.385293532067568, + -23.247396754879265, + -23.113088745898345, + -22.97788261894402, + -22.85033600215608, + -22.7302817180564, + -22.614875683411867, + -22.501606043047857, + -22.39296302095069, + -22.291124620939094, + -22.1931172182229, + -22.10259642363014, + -22.01442660431957, + -21.930835891539587, + -21.854838952711773, + -21.785225767526434, + -21.71575024868301, + -21.648654064018306, + -21.584573001491112, + -21.520141220887233, + -21.45177011272198, + -21.384492813439486, + -21.318955993291997, + -21.25214802678836, + -21.183657070739866, + -21.119719849680337, + -21.054127260365053, + -20.983247893375697, + -20.91436578568897, + -20.84846061043535, + -20.77885808389792, + -20.70787520393427, + -20.64043121965617, + -20.567976117179327, + -20.49802638852945, + -20.425461212722524, + -20.35479298424054, + -20.282674033670123, + -20.20903252554625, + -20.137397231124215, + -20.064022256051153, + -19.989043931523284, + -19.90910114815038, + -19.83232039990529, + -19.753511678281324, + -19.669105733913366, + -19.583314519263745, + -19.494616842451236, + -19.40443270134451, + -19.310538831842955, + -19.213843720805905, + -19.115886189028437, + -19.01472079114958, + -18.911519476095137, + -18.806724464509383, + -18.699383897195215, + -18.587828190276884, + -18.475139327437294, + -18.358508133023715, + -18.23250049997659, + -18.107209041615686, + -17.97898633278654, + -17.839883042643052, + -17.69648363507199, + -17.551859605023964, + -17.39543380713658, + -17.234970818650286, + -17.070046627768086, + -16.896655854204827, + -16.72189078956723, + -16.53903862823957, + -16.345578366064313, + -16.15040970857468, + -15.949004036301039, + -15.73409882318099, + -15.520776286461096, + -15.301925922368234, + -15.070678004620648, + -14.843307150651425, + -14.613679045242476, + -14.375157473101241, + -14.139389072791404, + -13.904988476433443, + -13.661150612368795, + -13.41707736541694, + -13.180820011095541, + -12.940189575595827, + -12.700155724224805, + -12.46287048059889, + -12.225978074095101, + -11.983676868668432, + -11.741119724603255, + -11.498800839246972, + -11.257118257374717, + -11.01223198786857, + -10.771316621036691, + -10.531816609803048, + -10.289242645492118, + -10.051094210070056, + -9.813321328273139, + -9.572194435045677, + -9.335290205071642, + -9.103435364388192, + -8.870725952526021, + -8.643668752575262, + -8.425262228892867, + -8.180860199005918, + -7.957839554013466, + -7.742057345061757, + -7.528013744629356, + -7.314109479110836, + -7.103808525252691, + -6.898801427447551, + -6.693570821226059, + -6.493186831966468, + -6.296214106306464, + -6.099657869405394, + -5.908827113614065, + -5.715615709860129, + -5.521984170694302, + -5.332461478571686, + -5.143684708007091, + -4.953569959626599, + -4.772259464875152, + -4.599443535946358, + -4.422658612841595, + -4.25775388602834, + -4.1065418176812125, + -3.954217993435107, + -3.8120387751928058, + -3.684418011623918, + -3.560233442270346, + -3.4467609954925646, + -3.347455125665888, + -3.256983334164835, + -3.1818452917066, + -3.119373397337299, + -3.0677831078079105, + -3.031257649766328, + -3.0084601096112937, + -2.999507935999349, + -3.0054698298286207, + -3.0281236342209943, + -3.0700352925929155, + -3.128581122683889, + -3.204051529859299, + -3.29715812617134, + -3.410492761151179, + -3.548730766585928, + -3.7148238763535497, + -3.892215883500358, + -4.08410985314791, + -4.303713350962656, + -4.53199807872445, + -4.769603912150116, + -5.039499581466397, + -5.317875891463045, + -5.594221969919161, + -5.890632592115414, + -6.198945169797842, + -6.511674328245961, + -6.833766739908534, + -7.159226307604196, + -7.485880834688631, + -7.8213576057842005, + -8.155947721189817, + -8.490831353136372, + -8.82915319130515, + -9.167136649612592, + -9.50351549191835, + -9.844389215804224, + -10.179525657340298, + -10.515272701348366, + -10.853513119276752, + -11.186384006918765, + -11.51885458278919, + -11.853887739779578, + -12.186218771001966, + -12.518838054018211, + -12.85379646413921, + -13.192524168500752, + -13.531297475935212, + -13.87278381731817, + -14.216843064780582, + -14.565137202540603, + -14.916964860695987, + -15.276638133253954, + -15.649521404743567, + -16.023504645043484, + -16.399218438899965, + -16.787539834221676, + -17.17487956619213, + -17.55780193233755, + -17.953415497509326, + -18.36193162941352, + -18.753242349393854, + -19.1547288146283, + -19.57488363759125, + -19.97196405956268, + -20.382959986893194, + -20.808590477926927, + -21.214446333859488, + -21.63333896306491, + -22.063312427305817, + -22.469330277045458, + -22.883562574578935, + -23.30562305116361, + -23.69693990260586, + -24.089484082222096, + -24.508476133226807, + -24.91173666527541, + -25.300314654764954, + -25.714811859707304, + -26.12548731270093, + -26.513524431697025, + -26.921808472447154, + -27.335390292031736, + -27.730896380438267, + -28.135096223390125, + -28.54305955816263, + -28.936817600015, + -29.33587430829889, + -29.735739337632634, + -30.131784852729698, + -30.531510034799926, + -30.931020949816958, + -31.328154826694753, + -31.73203776645058, + -32.134486553878176, + -32.54050706752538, + -32.949192934150325, + -33.36421956031278, + -33.7768751678339, + -34.18940158319885, + -34.6021492023042, + -35.01047415651771, + -35.41171781082104, + -35.813119692813984, + -36.215050467039944, + -36.621893345222226, + -37.03717132871312, + -37.46002493725777, + -37.883741357496945, + -38.30719995932858, + -38.72938025987588, + -39.14924357296815, + -39.57802315670335, + -40.01043348825386, + -40.439590791865776, + -40.85750222093139, + -41.27182723776138, + -41.68831190734649, + -42.104015239877675, + -42.52170843545669, + -42.93599499431075, + -43.354357210777145, + -43.7750624616118, + -44.180848445444646, + -44.58812097321755, + -45.007713562651716, + -45.417312323038956, + -45.82621709698976, + -46.24179036897837, + -46.659494896046056, + -47.0695288423755, + -47.476973756636134, + -47.88445074356961, + -48.28357380372633, + -48.67844143188854, + -49.08561638451694, + -49.48706722067271, + -49.877482019089115, + -50.279156256808044, + -50.676273600636236, + -51.053999874666324, + -51.447405905939775, + -51.835994120984935, + -52.21242997655724, + -52.60506604706158, + -52.998686597981106, + -53.37501814955399, + -53.768167517412685, + -54.159168318936786, + -54.53551172277161, + -54.92985669052983, + -55.31894439666703, + -55.69133528047126, + -56.07482392120389, + -56.444863159140716, + -56.81320710027343, + -57.19053508956895, + -57.56215251701041, + -57.93099347502464, + -58.30172428484685, + -58.664305554440965, + -59.025359706567336, + -59.39829137353854, + -59.7582141542276, + -60.124530748974514, + -60.4908578766057, + -60.83505696904816, + -61.18130885226007, + -61.52499966132512, + -61.83836490363596, + -62.158196325612444, + -62.47435398172692, + -62.76534189619135, + -63.05109916028611, + -63.32856523564792, + -63.59049106119492, + -63.83443997198932, + -64.07088373841837, + -64.29533435273933, + -64.50526421490805, + -64.7052822956055, + -64.88974984865094, + -65.06757453538047, + -65.23988864735162, + -65.39869442920023, + -65.54776860045122, + -65.68685907210161, + -65.81838416625914, + -65.9438257267132, + -66.0586877840251, + -66.16983067614979, + -66.2802816919717, + -66.3794524945481, + -66.47116560935949, + -66.5580783084223, + -66.63414777564289, + -66.7028493866808, + -66.76637121729858, + -66.81648907329419, + -66.85396394868584, + -66.88622644304414, + -66.9069131925393, + -66.91060786059475, + -66.89911095628779, + -66.87390242235816, + -66.83644811340965, + -66.7854338571656, + -66.71980373895558, + -66.6393075249817, + -66.54347632615395, + -66.43556800084674, + -66.31751313422161, + -66.1879628899378, + -66.0492213591998, + -65.90249473180852, + -65.74234707643778, + -65.56934163451142, + -65.38876145051714, + -65.20278639422463, + -65.00492563650491, + -64.80032711231964, + -64.60508760719165, + -64.39640405531888, + -64.17347324859307, + -63.96347278695096, + -63.74783369003469, + -63.50827319197837, + -63.27817201058187, + -63.049125731267196, + -62.79906825605081, + -62.55571846530885, + -62.314009308642575, + -62.06057816611769, + -61.812002866040984, + -61.568008672865844, + -61.31977697955609, + -61.07544160626518, + -60.83338909845368, + -60.58843697818208, + -60.342020309956226, + -60.0982834257727, + -59.854435946413936, + -59.614697844411104, + -59.37731347930396, + -59.1442368134974, + -58.907917683733785, + -58.67663687502402, + -58.44415651110442, + -58.2105060936788, + -57.98171333830625, + -57.75986034582937, + -57.53099620873651, + -57.31742354180103, + -57.11094708789625, + -56.89404473721648, + -56.686883256420124, + -56.47789349938912, + -56.25906193982285, + -56.04874031747729, + -55.838189439977356, + -55.60030507722978, + -55.389217653260076, + -55.18088735036473, + -54.964419297405115, + -54.74251225436768, + -54.526641540244455, + -54.309039392756404, + -54.08466206621436, + -53.864323502833976, + -53.64917961946586, + -53.42760336382845, + -53.20497730544819, + -52.98581775877011, + -52.76052182351032, + -52.53402751945837, + -52.3150187111637, + -52.09446139112003, + -51.875301855406015, + -51.66458491630855, + -51.44880184949696, + -51.23583887481144, + -51.024251639441495, + -50.8071041651678, + -50.584758876264836, + -50.35673439549038, + -50.1297573599387, + -49.89796426630089, + -49.6561733825751, + -49.408897775010146, + -49.158956206097, + -48.907045966962926, + -48.65259274481218, + -48.39660932186194, + -48.14165349692995, + -47.89462459547674, + -47.649591173534326, + -47.40018989835032, + -47.153616860328476, + -46.910162188884115, + -46.66125059392396, + -46.41004047357298, + -46.160765219588185, + -45.91311081595627, + -45.66671801274094, + -45.40747481662267, + -45.15426593717196, + -44.909388930303805, + -44.647962917352636, + -44.38667975642351, + -44.146999413931816, + -43.889502030617585, + -43.61894147724354, + -43.365040674727965, + -43.10397341963339, + -42.82173856681402, + -42.54942670163961, + -42.29427549203657, + -42.01245170382104, + -41.72086995614185, + -41.44495855163145, + -41.14649300925449, + -40.83513244019241, + -40.53309408854726, + -40.217082860406435, + -39.899885571661386, + -39.58322762333115, + -39.25927891824996, + -38.929237385790294, + -38.60501927350662, + -38.26979751771763, + -37.9385310519133, + -37.61768400267112, + -37.277203470340076, + -36.93210187510192, + -36.5989670409393, + -36.2605671033598, + -35.917965476399594, + -35.58097928977165, + -35.25319314601881, + -34.92046457703637, + -34.60122646328586, + -34.29598638239527, + -33.98750709553549, + -33.68152469734872, + -33.39455183864643, + -33.105969452117364, + -32.81664183529315, + -32.54062425940163, + -32.26072655522608, + -31.99050060497156, + -31.72877191156155, + -31.468227199983055, + -31.21843403205665, + -30.977134869050094, + -30.744551200538588, + -30.520450877430214, + -30.306724802221535, + -30.101948932135542, + -29.90258558513699, + -29.711945872526478, + -29.52797590846506, + -29.350878727858255, + -29.18247502170537, + -29.01909000846517, + -28.861102358688207, + -28.708252894134002, + -28.557369426591453, + -28.409309883669305, + -28.268708922244162, + -28.126963558263956, + -27.984308901106722, + -27.85100925439488, + -27.71529717169798, + -27.576840023148723, + -27.44251871424342, + -27.313256895515355, + -27.180729339362657, + -27.04782848835487, + -26.92002153360609, + -26.790315116923516, + -26.660100898820513, + -26.53355776255497, + -26.405116036858658, + -26.276057964785224, + -26.148177020639906, + -26.02033937766196, + -25.88848134437824, + -25.755681789181292, + -25.624872901363535, + -25.490242505278097, + -25.355470932101024, + -25.22236384459584, + -25.088800442352564, + -24.95535322982862, + -24.82351898930916, + -24.689119954604983, + -24.558511466905593, + -24.425997464165782, + -24.290544088167824, + -24.157214348218936, + -24.021861518407203, + -23.885871920684064, + -23.7523139250111, + -23.619343365392247, + -23.486278389618853, + -23.35571588003516, + -23.227448808905987, + -23.09791383972981, + -22.973946373338865, + -22.853558225518288, + -22.732734754033817, + -22.615414309116364, + -22.50516554436355, + -22.397252798556945, + -22.29470452337946, + -22.194411644474002, + -22.095695812618867, + -22.005828463686132, + -21.918981677629155, + -21.832796787388066, + -21.748707256505124, + -21.6700995782513, + -21.588476863832106, + -21.502785620624614, + -21.42035927917382, + -21.33895745261171, + -21.25746798767443, + -21.173432789420303, + -21.093717056254025, + -21.01421380814389, + -20.92910815212903, + -20.845431538646466, + -20.763570632347665, + -20.683981750056073, + -20.605257257783588, + -20.527823423418333, + -20.450680999068584, + -20.37330676600147, + -20.297762528648224, + -20.22249251447037, + -20.149339684754093, + -20.07675386335212, + -20.001966877314885, + -19.930592511200402, + -19.85838426092376, + -19.784511919787423, + -19.71074907849777, + -19.641326428023383, + -19.57203711207824, + -19.499837444978393, + -19.419880274945527, + -19.3467494212837, + -19.270347377065946, + -19.18931053505767, + -19.105591213435552, + -19.01875416637844, + -18.92788485237338, + -18.8336186850511, + -18.73710595657461, + -18.634141549797043, + -18.525922295281873, + -18.413488281084675, + -18.296599974487968, + -18.171392414075658, + -18.040355925748102, + -17.910027118057833, + -17.77338992847017, + -17.629885914394755, + -17.487061658089928, + -17.339625102593942, + -17.18249906920041, + -17.027878626052093, + -16.873170781463866, + -16.706255793779288, + -16.540318732606554, + -16.376606673490276, + -16.2001022273604, + -16.023159396344724, + -15.850571060076042, + -15.664271270944365, + -15.475896287314427, + -15.298426651813514, + -15.091561042812065, + -14.892259901334407, + -14.705024033893125, + -14.512483072769651, + -14.305026564216309, + -14.10519411144605, + -13.903524572486049, + -13.692464657487488, + -13.483742809265246, + -13.274246955139253, + -13.059759920135956, + -12.84455403674611, + -12.627799045360609, + -12.409685667361273, + -12.1924413750488, + -11.970868912787585, + -11.7464236450359, + -11.522442826727415, + -11.295977029960582, + -11.067532313046188, + -10.839099112981014, + -10.61717452483189, + -10.388719073544767, + -10.16158941914945, + -9.937843429918663, + -9.708727087611281, + -9.480656932105369, + -9.253151528476407, + -9.026050056669934, + -8.799426062753268, + -8.577421694627647, + -8.356533192411291, + -8.134179831465978, + -7.912744714117008, + -7.694252414226817, + -7.476803140464561, + -7.259360915045362, + -7.045289914935967, + -6.835186557510802, + -6.6243444886204585, + -6.419611856274912, + -6.2210353157285665, + -6.02486892025979, + -5.83073140440032, + -5.640612261893859, + -5.4562844787822256, + -5.269901658356259, + -5.084882915776098, + -4.898135437540016, + -4.714547937466565, + -4.533587236559559, + -4.3288310694700245, + -4.143397569531199, + -3.967343203614429, + -3.7935401456925155, + -3.619734248375605, + -3.450697890446953, + -3.2925389530276097, + -3.1389235386498022, + -2.990376432907575, + -2.8535680191276174, + -2.7222266067770535, + -2.6005019413857395, + -2.497352417612733, + -2.4000035272737996, + -2.3089878530450045, + -2.2337449494523565, + -2.1701904299675587, + -2.1159681678033944, + -2.074625610913162, + -2.045475535555629, + -2.029161475575345, + -2.026358986910275, + -2.0371416488528715, + -2.0618610307693253, + -2.100938228557439, + -2.155907372425467, + -2.2255863659585926, + -2.3095800842277896, + -2.407399203609409, + -2.5225881586497594, + -2.6630509837274308, + -2.8185007212722084, + -2.986035983338265, + -3.183263172760066, + -3.397533865505796, + -3.619823420106108, + -3.8637291704136136, + -4.124021877019453, + -4.390613092861507, + -4.6773400070370545, + -4.975224485938064, + -5.27345518278105, + -5.587907304664719, + -5.911992859510572, + -6.230762785194832, + -6.55513967648047, + -6.886529345227692, + -7.206733306233928, + -7.5352635724096775, + -7.869206688399662, + -8.189496714942116, + -8.513422442809402, + -8.83988899464593, + -9.152968752423135, + -9.466355174354861, + -9.780120593229137, + -10.087283830882374, + -10.391203247701847, + -10.695466047400185, + -10.997952737530179, + -11.2968763513574, + -11.59695340044311, + -11.89762892723237, + -12.199047458639765, + -12.503552294087825, + -12.810250490063101, + -13.123043937553804, + -13.436433210200024, + -13.751874414867586, + -14.071036938215897, + -14.390312532211357, + -14.712179025001948, + -15.03737136375139, + -15.36352784876661, + -15.695121715030757, + -16.026625347948894, + -16.355412133457943, + -16.69674625962069, + -17.033640657897166, + -17.369267607448105, + -17.704054002405943, + -18.054108663868952, + -18.40259955279605, + -18.736412744667824, + -19.091415333251987, + -19.449470775356403, + -19.79053783368905, + -20.142884001997782, + -20.511361012524375, + -20.864014383527227, + -21.220138142465128, + -21.592449615714653, + -21.95105644301703, + -22.306083533920376, + -22.67429333385156, + -23.037392076997108, + -23.393195909901355, + -23.75368144445266, + -24.12053574396884, + -24.482355018737177, + -24.84277917128603, + -25.20546346341832, + -25.57296965523862, + -25.933788732782507, + -26.295052429160425, + -26.66664627437255, + -27.035480756971413, + -27.399127734923916, + -27.769060923278527, + -28.146037446226607, + -28.51169084023298, + -28.87468841939414, + -29.24624414963434, + -29.604713050167096, + -29.962627439354968, + -30.32445985346866, + -30.681273837093627, + -31.03950346961145, + -31.39679867260935, + -31.748219274989207, + -32.10410935222879, + -32.46541736589728, + -32.821335797797595, + -33.1796506882653, + -33.54110010763142, + -33.89853684918133, + -34.25586492273972, + -34.61612883746897, + -34.97040605630931, + -35.31793899655061, + -35.672835745619764, + -36.01812177167872, + -36.36670621473768, + -36.72506259706506, + -37.08436397400378, + -37.44385573591024, + -37.816975636283104, + -38.18916070593347, + -38.55455601119412, + -38.92460038130979, + -39.299503653654085, + -39.66411577470547, + -40.03225720112146, + -40.40549389662069, + -40.76736290191831, + -41.12269769746697, + -41.482852300709595, + -41.84225629509178, + -42.1938791629395, + -42.55609226584854, + -42.91934939165613, + -43.27528231397707, + -43.636636751629936, + -43.99890114014338, + -44.34786787571027, + -44.701227001123364, + -45.05899890206312, + -45.412497155596654, + -45.761181757254725, + -46.11438109125427, + -46.468353171673265, + -46.820220999222904, + -47.16840113637365, + -47.51786808464334, + -47.86888628608643, + -48.21737330898203, + -48.56310893062025, + -48.91521831222494, + -49.272464591852795, + -49.62173762377014, + -49.96970628222811, + -50.32443776675892, + -50.67498731428199, + -51.012205085006684, + -51.35865074123352, + -51.706623319588275, + -52.043596672557385, + -52.38645600411932, + -52.73627141639067, + -53.07957442147244, + -53.41971349747408, + -53.77095151892777, + -54.114957890414765, + -54.45019496610639, + -54.79856140679166, + -55.146660878574004, + -55.48081222853083, + -55.81990923461163, + -56.16331143241947, + -56.494210845184845, + -56.82777955894273, + -57.166836628774895, + -57.49731944828853, + -57.82638527590838, + -58.15808213867223, + -58.48476491883403, + -58.803442229655566, + -59.122058537933945, + -59.444892148310636, + -59.762422052013186, + -60.08008914024777, + -60.40578938497902, + -60.72188398200776, + -61.02658827196787, + -61.33811740634257, + -61.64817223693242, + -61.94016895889685, + -62.23021658249741, + -62.52097652742526, + -62.79630336970065, + -63.06227947815229, + -63.33040216818478, + -63.57961685109977, + -63.824155271857705, + -64.06078522539734, + -64.27601863921969, + -64.48611394439426, + -64.68291275551678, + -64.8688910556516, + -65.05883481493532, + -65.2295824985437, + -65.39107094542109, + -65.55888416912086, + -65.71953239347093, + -65.87235787735521, + -66.02122733852457, + -66.16097797595631, + -66.3001078504453, + -66.43607181753445, + -66.5649978184758, + -66.68447963809102, + -66.80496996462325, + -66.91749658058505, + -67.01499682792995, + -67.10451054468302, + -67.18398164698797, + -67.24855957610923, + -67.30529088716048, + -67.3489588700816, + -67.37678516450451, + -67.39878145401124, + -67.41350821822829, + -67.41462716887222, + -67.4014549685066, + -67.37738092142811, + -67.34327272135867, + -67.29916608466613, + -67.24443754844559, + -67.17819032906456, + -67.09504772459013, + -67.00028290392237, + -66.89428747725327, + -66.77724842495371, + -66.64867135313715, + -66.50926243576065, + -66.36805672868711, + -66.21853389972787, + -66.06400771932115, + -65.90164156157225, + -65.734632794016, + -65.56657721606501, + -65.39037351954278, + -65.21468008734657, + -65.03688644861485, + -64.85251657624295, + -64.66359622923198, + -64.47857172903966, + -64.28603113159828, + -64.08911541569569, + -63.89806627292407, + -63.702733993316485, + -63.50088321116002, + -63.29755695886102, + -63.09161931112981, + -62.87983162884179, + -62.6671544312839, + -62.451920772708206, + -62.2337393737835, + -62.0166704822151, + -61.792339473587255, + -61.56352323841773, + -61.33568055930336, + -61.1016579322237, + -60.862786281664306, + -60.62418752885767, + -60.383963344211935, + -60.141195225475855, + -59.901914270296935, + -59.660478242705985, + -59.42293859390448, + -59.18513332557597, + -58.941345177919416, + -58.7002959173493, + -58.46433951249894, + -58.22189301364764, + -57.986011878624765, + -57.75913529554494, + -57.52218633547478, + -57.29423931936483, + -57.0698705213643, + -56.837254235681065, + -56.611813590205564, + -56.388279414302474, + -56.15604413982848, + -55.93087161005591, + -55.71582916372175, + -55.48567875695876, + -55.254269686957365, + -55.03334941884798, + -54.80055829621406, + -54.56311277320943, + -54.33762906335555, + -54.10600016746531, + -53.869014087005894, + -53.63889286127345, + -53.40369522408548, + -53.16219284132628, + -52.931527826394884, + -52.703625976211065, + -52.47509795814298, + -52.25330743116507, + -52.03453983917092, + -51.82054456648979, + -51.602559678881605, + -51.384751277985615, + -51.162011385075836, + -50.93741702373425, + -50.71615399273452, + -50.48993478386764, + -50.25605295810436, + -50.021506529335404, + -49.788406338011605, + -49.54634219897052, + -49.30882398784405, + -49.078007785005084, + -48.843338943819056, + -48.61757268965913, + -48.39566728328335, + -48.160147679826615, + -47.91391012701571, + -47.681482808142384, + -47.445264365310344, + -47.19521380793525, + -46.94829331667921, + -46.705173200194736, + -46.45590249097712, + -46.19414798768018, + -45.938591625021985, + -45.69135464833386, + -45.436556691036294, + -45.1700352242094, + -44.9193464817555, + -44.66370427821693, + -44.38462162809643, + -44.10928850903636, + -43.84475633329836, + -43.56101912259667, + -43.26916780925776, + -43.00215538749537, + -42.730103248848714, + -42.43255454426534, + -42.14271369274558, + -41.85100933746453, + -41.53016148815435, + -41.210831215664115, + -40.88815509054743, + -40.5510344005366, + -40.21464673634862, + -39.873850051081675, + -39.521198215048955, + -39.17320252466675, + -38.81390435094139, + -38.45129600828928, + -38.0975338708504, + -37.73035353362482, + -37.35950643773611, + -36.99679419638933, + -36.632887522917756, + -36.26406605379358, + -35.91209689382184, + -35.565609465375076, + -35.21445744958684, + -34.89036309066244, + -34.57407088684302, + -34.24588188342661, + -33.94459584976613, + -33.647373976645035, + -33.34684672071522, + -33.0639932380401, + -32.78837738725645, + -32.5060827451208, + -32.233616178662146, + -31.974568655034858, + -31.715857675406586, + -31.461831254485197, + -31.22039968696241, + -30.987933228162344, + -30.760172487308616, + -30.53458248163382, + -30.314936479045173, + -30.104151305456135, + -29.899127412438165, + -29.697353012702013, + -29.5040090923272, + -29.31373973405169, + -29.123571697693556, + -28.941167377881264, + -28.76558256105084, + -28.587589482188562, + -28.420649669863987, + -28.264423190323043, + -28.103857859423396, + -27.95094691330261, + -27.807944638035227, + -27.660012091095293, + -27.515775067245535, + -27.37740325508359, + -27.236327458306935, + -27.09665204951298, + -26.959008262330904, + -26.818546998844113, + -26.67694543511828, + -26.53794803076415, + -26.39265680223, + -26.244917938631552, + -26.099260537815184, + -25.947248918197815, + -25.795964651986313, + -25.645215501942417, + -25.491078797437968, + -25.335977085982055, + -25.181077948821404, + -25.029432783995343, + -24.87271441809661, + -24.71553012384757, + -24.560659198297937, + -24.40528157733817, + -24.25222422438953, + -24.099913260358807, + -23.95199826779356, + -23.80705387831147, + -23.66389650129534, + -23.50860153926942, + -23.377205840182665, + -23.247375051793995, + -23.11994141914694, + -23.000168906362543, + -22.885095003156678, + -22.77561164838907, + -22.671021165335954, + -22.570048134501, + -22.475925129539053, + -22.3871268371147, + -22.297129381391294, + -22.208194495110913, + -22.124045343718752, + -22.032814062121165, + -21.938671705458578, + -21.84945388620275, + -21.75913901266592, + -21.66291869108665, + -21.571842556129557, + -21.47889433693878, + -21.377522783740005, + -21.279676525653205, + -21.187195966730886, + -21.092740410870768, + -21.00013433181636, + -20.910009128995, + -20.81803034627194, + -20.725254572870437, + -20.635908500377614, + -20.549458520919444, + -20.462560882591013, + -20.375027708946895, + -20.29179943034236, + -20.207735550713927, + -20.123140092350056, + -20.0422695909282, + -19.963284652474147, + -19.882417677939628, + -19.80006098860956, + -19.7164917979833, + -19.629668419272896, + -19.537748434389247, + -19.44329916286591, + -19.343888268147293, + -19.239331412049115, + -19.132778184945618, + -19.019851930988047, + -18.899693634244414, + -18.7740222361764, + -18.64098764588919, + -18.498694309792743, + -18.35070991187078, + -18.201133407197233, + -18.042508094909714, + -17.880072443923964, + -17.714131263705024, + -17.534272578123293, + -17.352049855298723, + -17.166474852006907, + -16.971031804739926, + -16.77285335055818, + -16.57108523614885, + -16.362789926429176, + -16.1568502058274, + -15.945924725414416, + -15.727011384518159, + -15.52087926321072, + -15.308608777976925, + -15.081023749659833, + -14.867190488523567, + -14.65261469516981, + -14.422873334341448, + -14.19775737997882, + -13.97538784029993, + -13.74029848216648, + -13.514067712925359, + -13.305662879590912, + -13.090133036188979, + -12.8749084736165, + -12.66460687077586, + -12.447283591667928, + -12.226123652789182, + -12.008635692779118, + -11.786103363661667, + -11.563554636491423, + -11.336508136336477, + -11.105139193387451, + -10.87310897973837, + -10.641936490991498, + -10.41504853696415, + -10.187361287970107, + -9.959962900483445, + -9.734518728442552, + -9.512464440594053, + -9.289723557559512, + -9.06962063046247, + -8.850349641018138, + -8.629493815200412, + -8.408026328287127, + -8.190105732462012, + -7.977462748886694, + -7.764403192292031, + -7.555317194741051, + -7.353277302203586, + -7.154073892218664, + -6.959369532699178, + -6.772135414139355, + -6.588362759891173, + -6.407471870227311, + -6.230809235740635, + -6.0514239953809925, + -5.873849213501359, + -5.704583332793421, + -5.517992193649563, + -5.351842156381033, + -5.195978546597032, + -5.0444182955658725, + -4.89452980585661, + -4.75265711854504, + -4.616714693316472, + -4.478987911620376, + -4.347586387492915, + -4.221261991556717, + -4.094105073197255, + -3.973620987203808, + -3.8582581195654524, + -3.743854038062321, + -3.6406250204203503, + -3.543159820531951, + -3.451697622539284, + -3.373083583306613, + -3.302958184860286, + -3.238454729469617, + -3.1840381544859695, + -3.138262606993281, + -3.101446047905101, + -3.075092558166955, + -3.057787655905119, + -3.051154313913769, + -3.057541909161938, + -3.0777058046686556, + -3.11226177300754, + -3.1633028148244224, + -3.2269528478740774, + -3.3055484962963204, + -3.411798257575102, + -3.5327781800075804, + -3.6598205132349197, + -3.8042761382970274, + -3.9637921100409432, + -4.1343610580237, + -4.321488710941954, + -4.5254183007263, + -4.743492198481461, + -4.976546490154955, + -5.217377413034586, + -5.463944656267498, + -5.725466210792774, + -5.9942265008430455, + -6.266880248401289, + -6.547174852306351, + -6.830449296321783, + -7.140692472535568, + -7.4244805791327595, + -7.712915267119155, + -7.99947758519533, + -8.287869958446791, + -8.580775449727524, + -8.870859696915527, + -9.158148441959966, + -9.44699351667771, + -9.732155623590316, + -10.014872063053648, + -10.29775979865664, + -10.5749857424261, + -10.852780150019186, + -11.13579070510385, + -11.414735024671282, + -11.691983571243979, + -12.001988427141596, + -12.284375625399804, + -12.56870016424334, + -12.853058122056988, + -13.137900260390332, + -13.42979842600842, + -13.719020086320706, + -14.009281632255217, + -14.301011028445044, + -14.592116426583539, + -14.890971598247424, + -15.184707720545834, + -15.481093409437367, + -15.785987358772202, + -16.092112434469538, + -16.39191902946486, + -16.69850670541692, + -17.0161434213426, + -17.32450689834855, + -17.639360481835368, + -17.952300054487637, + -18.27492426202884, + -18.60534648107577, + -18.923198927697737, + -19.25420879463818, + -19.595659059684134, + -19.922765883100173, + -20.253464392487235, + -20.601756971249607, + -20.942552896658825, + -21.278023387366545, + -21.630659974387093, + -21.981249616001126, + -22.32017323749989, + -22.668377046161826, + -23.05463993470257, + -23.399669839059996, + -23.744378497142918, + -24.093191328550297, + -24.44436936299327, + -24.795515704871704, + -25.14414383087788, + -25.496241874938153, + -25.849278367345228, + -26.20207562252542, + -26.55782194511243, + -26.9148884183778, + -27.273738204083404, + -27.62996812180062, + -27.988628487833694, + -28.343905979595174, + -28.69105165873182, + -29.037582666102935, + -29.38635666555043, + -29.723594788931088, + -30.056689528810995, + -30.398340778637635, + -30.732889562974144, + -31.064289829857046, + -31.399693377691765, + -31.73114349509177, + -32.06073470265107, + -32.39085993270465, + -32.726477933935236, + -33.06476388178211, + -33.39372387206702, + -33.72672082897999, + -34.065249854126584, + -34.39760966485348, + -34.73058887095751, + -35.06296182746248, + -35.38255055373931, + -35.70814463524432, + -36.039025349592656, + -36.35972932359205, + -36.68348309060314, + -37.015753113562184, + -37.34542599091974, + -37.67911904288027, + -38.020693570149206, + -38.36066205243361, + -38.70234003793076, + -39.0451492945628, + -39.39470491993342, + -39.74042583403011, + -40.08281748005475, + -40.43186199005066, + -40.78057224431363, + -41.12203865389018, + -41.46267864179745, + -41.808416009280755, + -42.1509228039912, + -42.49332936056103, + -42.8435430598219, + -43.18692325830212, + -43.52734250106671, + -43.8776940098036, + -44.21698436032345, + -44.556835639299806, + -44.89983918658318, + -45.242047277374795, + -45.5826423524521, + -45.92626112623457, + -46.26649535067602, + -46.60896010384153, + -46.949825362626704, + -47.28504508563118, + -47.62134759487119, + -47.95862599059289, + -48.29311570298762, + -48.62734834939975, + -48.96608905881075, + -49.30823556860031, + -49.64709563386687, + -49.98457430475821, + -50.32742155888007, + -50.66680723085256, + -50.992571879080906, + -51.32806674987615, + -51.6678732874057, + -51.99491914646086, + -52.33010756345978, + -52.67357247262765, + -53.010980957968805, + -53.346069446378266, + -53.693569866543896, + -54.037595073463436, + -54.373086426955794, + -54.72237993359764, + -55.07397645239609, + -55.412614130024785, + -55.75677926690112, + -56.106190350043306, + -56.43909434686085, + -56.77630047366981, + -57.11950997288579, + -57.455225540470664, + -57.78897197103224, + -58.126435303607316, + -58.45929014889902, + -58.78439546632375, + -59.11397571401777, + -59.45000916190445, + -59.77746170812227, + -60.108321017355244, + -60.440039735420875, + -60.751897208358145, + -61.05539281208393, + -61.35354119299772, + -61.643599581934104, + -61.912007900310435, + -62.18193003148963, + -62.44967261244594, + -62.69734117106019, + -62.94625825298737, + -63.1885117669288, + -63.44629136317529, + -63.71321495812481, + -63.96855143572826, + -64.21750078899412, + -64.45998084573628, + -64.69048974510206, + -64.9097276652017, + -65.13231715848787, + -65.33119631774655, + -65.52088910011457, + -65.70062746247886, + -65.8565819388565, + -66.00708425595732, + -66.15325504641662, + -66.28385190357783, + -66.40717356075399, + -66.52631527291177, + -66.62958093381904, + -66.72924851871147, + -66.82707187290991, + -66.91117047812757, + -66.98971235880302, + -67.06456025223856, + -67.1300129744069, + -67.1889735503678, + -67.23783511245693, + -67.27488175592373, + -67.30723066911459, + -67.32866615617212, + -67.33249111606224, + -67.32121765826327, + -67.29769196841443, + -67.26372753216401, + -67.21770276411456, + -67.15775947255702, + -67.08362594093559, + -66.99374450078747, + -66.88971886776457, + -66.7747525958143, + -66.64499872374087, + -66.5047908956285, + -66.35542672806882, + -66.19544669942078, + -66.02707019249198, + -65.8507498384762, + -65.66671210846613, + -65.4831662845677, + -65.29471575998292, + -65.09597657589894, + -64.90250498287553, + -64.70670321752343, + -64.49651569008526, + -64.28647349591253, + -64.0832888223937, + -63.8636405810657, + -63.6391231646599, + -63.4189590613997, + -63.19149285289527, + -62.95389538462015, + -62.71839446630718, + -62.478440369530034, + -62.23445317242666, + -61.98963337497661, + -61.740036658029396, + -61.49076695590796, + -61.241328126844905, + -60.98683623445296, + -60.73310879462256, + -60.477894447425896, + -60.220686607194, + -59.96636730543988, + -59.714213309905475, + -59.4590148414393, + -59.20951404769694, + -58.96006911126184, + -58.70508896088304, + -58.45649206354154, + -58.20666486943769, + -57.951979833842046, + -57.70589026616218, + -57.464689786537754, + -57.21669082657974, + -56.980934676128975, + -56.745921029818305, + -56.50802576386077, + -56.276750829476114, + -56.04317179109562, + -55.80867142570943, + -55.57667262122025, + -55.341456448501326, + -55.10434011192988, + -54.877842723637585, + -54.643498335668696, + -54.403127624811034, + -54.168984336643426, + -53.93372568497106, + -53.69061024371152, + -53.45504493834885, + -53.21811788454279, + -52.972977071567044, + -52.72832673016044, + -52.47843122474741, + -52.22517971900285, + -51.97870037637053, + -51.73492669184909, + -51.495159189060026, + -51.25994896995887, + -51.02679480745267, + -50.7949423064563, + -50.56273688923523, + -50.322646298805935, + -50.0518369270235, + -49.80940060456466, + -49.56274912715791, + -49.30633051674411, + -49.048153248661066, + -48.788574214159524, + -48.528002933079165, + -48.26586732939847, + -48.0063101472052, + -47.76030630870287, + -47.52441189578046, + -47.291128619127235, + -47.05883153043223, + -46.82799772148867, + -46.59482025492095, + -46.365585376495105, + -46.11109902775143, + -45.87727287335853, + -45.642914140177105, + -45.40265378491914, + -45.152736261013686, + -44.897224738899496, + -44.65296719519171, + -44.40939803456398, + -44.15264580641331, + -43.90177598054978, + -43.663467940761436, + -43.409574537718164, + -43.149188443721904, + -42.91191714832933, + -42.672110917469624, + -42.423003772869414, + -42.17677983247791, + -41.929123357104196, + -41.67955502117077, + -41.413873554753664, + -41.14334513864083, + -40.86956510701395, + -40.5741653030368, + -40.26044947653966, + -39.94043634888155, + -39.610520471411476, + -39.277888904030334, + -38.93790784879036, + -38.59248930617415, + -38.2485112170478, + -37.89317134392239, + -37.53036248814005, + -37.174427806825406, + -36.85794224453516, + -36.53845093440649, + -36.21348196170747, + -35.89285402641411, + -35.582396884716175, + -35.260874017508556, + -34.95264533947338, + -34.657933152357934, + -34.364936308225865, + -34.06839631466887, + -33.75798183397996, + -33.453822376036925, + -33.15327496730229, + -32.85245477930143, + -32.55264967900641, + -32.25956613718065, + -31.968360034488466, + -31.678558658588116, + -31.395253608918217, + -31.12487086303531, + -30.86073486042292, + -30.596911207466043, + -30.35094700172187, + -30.107916916846243, + -29.86662969238843, + -29.64140287514268, + -29.42465730060835, + -29.20873141950385, + -29.003208174876242, + -28.801047166518092, + -28.598559421673098, + -28.408279489559504, + -28.226271545182716, + -28.04055186945441, + -27.87096283596155, + -27.71148765551883, + -27.546167521352587, + -27.39230417727304, + -27.24877580876583, + -27.09783215893978, + -26.954937921799782, + -26.818949965758552, + -26.681676601821323, + -26.547398310076627, + -26.416396387906435, + -26.285743836643963, + -26.154399525411, + -26.028216440474537, + -25.89718916840326, + -25.76383098390717, + -25.63069841007004, + -25.496061982526225, + -25.359107458747367, + -25.224247495385317, + -25.089574969004996, + -24.95285873066305, + -24.819494799318345, + -24.684718566617278, + -24.554116616503265, + -24.419019357854157, + -24.284172149282224, + -24.148707793931205, + -24.01186473981563, + -23.876342746496064, + -23.738868073052906, + -23.601694397583806, + -23.46532239616867, + -23.32692643656262, + -23.18872086142345, + -23.05105840492789, + -22.91885948279839, + -22.785663621276885, + -22.654800919142524, + -22.532057954698, + -22.411929968003665, + -22.29671530099123, + -22.186545449912806, + -22.07959033186948, + -21.979140273166, + -21.88559955764864, + -21.793155405157744, + -21.701638186393176, + -21.617775345367917, + -21.53450567338066, + -21.44536929480654, + -21.36241397007175, + -21.284528674198466, + -21.205495079814423, + -21.127556831766018, + -21.054384220246313, + -20.97955361232512, + -20.90073577389424, + -20.82357507949722, + -20.74731866628342, + -20.6711798956272, + -20.593662158870323, + -20.515250902662043, + -20.435299164524103, + -20.35293541021248, + -20.268813027999187, + -20.185173336563242, + -20.10105356746033, + -20.0118211480889, + -19.92464043858409, + -19.836792297259407, + -19.747523545570328, + -19.6571131930019, + -19.570821403242952, + -19.486117255630514, + -19.40006239938822, + -19.31576568805221, + -19.230069952903875, + -19.143307897505597, + -19.054961879789328, + -18.965652637571274, + -18.873872155913173, + -18.778858428906904, + -18.68578786711409, + -18.58738025704817, + -18.483825961339633, + -18.381112187414274, + -18.2740657788208, + -18.162325042151902, + -18.04407412307408, + -17.919854667959843, + -17.792509316116345, + -17.66184175675464, + -17.523915424889008, + -17.380889757343244, + -17.23131569457251, + -17.07543853247107, + -16.912602931612362, + -16.742816293028714, + -16.57246049417901, + -16.3943147157906, + -16.212966686173175, + -16.032686508658802, + -15.847141521277802, + -15.651425656594203, + -15.464992511939615, + -15.278464908435609, + -15.072448379880425, + -14.8761217062947, + -14.685520947858995, + -14.480019650318107, + -14.27821657976232, + -14.081162336099894, + -13.878548719850825, + -13.676114825254635, + -13.479426329362635, + -13.281653292041767, + -13.081932356207679, + -12.883715506200103, + -12.679829250555638, + -12.474074208665568, + -12.264738759020902, + -12.052432689037936, + -11.836503537782825, + -11.621061684740479, + -11.401713923807238, + -11.180083391260311, + -10.958317772071153, + -10.731046098698549, + -10.505790343847037, + -10.278488349239959, + -10.047943367741272, + -9.817561506108019, + -9.587572898564792, + -9.35766954806178, + -9.126937303434898, + -8.900387525863927, + -8.67631977764867, + -8.448014145550228, + -8.220877478765015, + -7.998791010097954, + -7.773894684448212, + -7.541617244165808, + -7.320168571875958, + -7.098763267260314, + -6.8729716888569605, + -6.652353600687759, + -6.43479038495738, + -6.217797107537136, + -5.998216552350932, + -5.776678779729985, + -5.560223461091686, + -5.345274024557623, + -5.127561761243892, + -4.917491843645876, + -4.715461570545477, + -4.505065395882604, + -4.307361113708217, + -4.124523779496649, + -3.9355579397707596, + -3.7491507672574134, + -3.5787963356111887, + -3.406589393198464, + -3.24175832452202, + -3.086619820093648, + -2.930549832146983, + -2.795652688582039, + -2.6676514831264004, + -2.5401125480067064, + -2.4299029546326705, + -2.333505659562151, + -2.2450534950716903, + -2.17204735922884, + -2.1128176477362017, + -2.064530519347138, + -2.030370074393183, + -2.010393138338829, + -2.004138709737753, + -2.012870078493015, + -2.0370841526207615, + -2.0763602872947198, + -2.131686324194107, + -2.2055013778985, + -2.2978840990695226, + -2.4069163471706303, + -2.5364879960175424, + -2.68534378683897, + -2.848188644199925, + -3.037611048174019, + -3.2441099854616016, + -3.4647746970836804, + -3.703799504275772, + -3.9553835254678953, + -4.218520760246446, + -4.495366437253349, + -4.785639833248068, + -5.08484574406934, + -5.386986180057311, + -5.702574899155793, + -6.024555013090089, + -6.348233572480257, + -6.676596928656058, + -7.002112491822304, + -7.323535097965916, + -7.64907641442559, + -7.974162122243784, + -8.29329386687016, + -8.614724092092834, + -8.967351104418675, + -9.281004572916306, + -9.595351486147798, + -9.906920463817347, + -10.215609104682294, + -10.522452460283825, + -10.822021762894998, + -11.12167338367002, + -11.419731886306183, + -11.71402587006081, + -12.009303977815186, + -12.3039125702886, + -12.59794267786584, + -12.890491044518715, + -13.183914504029614, + -13.481320566748892, + -13.77774003043691, + -14.076319692672689, + -15.135851789820482, + -15.448746547073267, + -15.7701082496401, + -16.09652425161251, + -16.419857209306667, + -16.74923535317632, + -17.087754028882582, + -17.418509385474984, + -17.749829044650806, + -18.081905985797718, + -18.43035359220856, + -18.774654053643356, + -19.111139682495992, + -19.46983396195551, + -19.826603384066924, + -20.169733909783766, + -20.52679978792883, + -20.892862525450653, + -21.24183538689616, + -21.599351761140987, + -21.969785438463287, + -22.3253797601872, + -22.684291974552025, + -23.052360362425834, + -23.41196124967644, + -23.770153047626177, + -24.133781319508433, + -24.50390460074309, + -24.872779437632673, + -25.240713528172346, + -25.613006170135684, + -25.986125133400538, + -26.356572373107657, + -26.732719884490372, + -27.110898722633916, + -27.488921639221125, + -27.867802714125826, + -28.250522161210075, + -28.627673559074477, + -28.999630763154563, + -29.374260600789675, + -29.747133847477823, + -30.108627139695123, + -30.4738748947489, + -30.845345249687618, + -31.20496502543251, + -31.56838718343814, + -31.934373093137385, + -32.29625825293812, + -32.655795528669486, + -33.023786562502075, + -33.394066451795176, + -33.75437144700971, + -34.12279959224543, + -34.49565203273659, + -34.86116745868966, + -35.22769623168896, + -35.58748552490108, + -35.93626152603457, + -36.29294327802148, + -36.64582261485386, + -36.995657073893845, + -37.35707992209258, + -37.719757995762386, + -38.08279784436257, + -38.45545006209987, + -38.82825938742799, + -39.19826192510871, + -39.57148727374065, + -39.94837305387175, + -40.3131466176835, + -40.68148435156973, + -41.053580633180246, + -41.41471059380327, + -41.771110999942785, + -42.13160233797795, + -42.48929319127417, + -42.83258211303702, + -43.17156392946248, + -43.50777876759926, + -43.83621764122727, + -44.17080271291086, + -44.52739005309362, + -44.84879118581973, + -45.172689735288515, + -45.49298321643188, + -45.81118501611773, + -46.13863714923011, + -46.46773403246215, + -46.795166887960754, + -47.1257062847864, + -47.44813465160126, + -47.76764993598219, + -48.086771459399884, + -48.40222941032584, + -48.71907808757432, + -49.03399471655375, + -49.34354732591616, + -49.64813474894097, + -49.94981490289839, + -50.251862128363726, + -50.55493943284664, + -50.85796949254924, + -51.15180674861884, + -51.44529451950592, + -51.74712457823629, + -52.04292433028553, + -52.33742608542614, + -52.64444297727034, + -52.95310408136931, + -53.25735769920424, + -53.559259930307086, + -53.868186045975776, + -54.176431125540695, + -54.478829869137414, + -54.78500535792089, + -55.095673466036885, + -55.40471352965616, + -55.714435944882986, + -56.02605195190667, + -56.33613734445318, + -56.64287796102448, + -56.94404246659396, + -57.2454612627552, + -57.547812439847576, + -57.84562457342142, + -58.13879443261982, + -58.433761921080084, + -58.72899131468643, + -59.01665140201153, + -59.30114472694361, + -59.590252232730855, + -59.87847927387634, + -60.162801188955875, + -60.44947893580497, + -60.738067632631044, + -61.01861847533337, + -61.29090609295296, + -61.55798266103622, + -61.823011438212895, + -62.08601868209725, + -62.332524119480766, + -62.585320398106404, + -62.835515300168986, + -63.07422177960659, + -63.31370164822563, + -63.54605428117169, + -63.7728317320232, + -63.998742709320645, + -64.2148619436213, + -64.4281100223949, + -64.63494551952286, + -64.8312054221813, + -65.02270635297941, + -65.21286313376582, + -65.38030932523728, + -65.55025723287066, + -65.7186392970733, + -65.87307562484358, + -66.02658267148043, + -66.16997682946553, + -66.30036537860236, + -66.42860486157353, + -66.54586257112908, + -66.65080224457779, + -66.75524537867345, + -66.84978197627228, + -66.93204206142951, + -67.00986209234982, + -67.07818786683039, + -67.13766003323333, + -67.18855777233131, + -67.22686182700441, + -67.2561763081435, + -67.28037100105091, + -67.29232540801087, + -67.28902093918421, + -67.27309618532365, + -67.24619829938165, + -67.20977023756896, + -67.16182994888243, + -67.10232748696933, + -67.0303655676146, + -66.94613023023517, + -66.85302319135522, + -66.75040284348367, + -66.63711735946971, + -66.514289986404, + -66.38405686478657, + -66.24356107069106, + -66.09319796269615, + -65.93253183883319, + -65.76682167290186, + -65.60006941227343, + -65.42529806307405, + -65.24472705747665, + -65.06968890862828, + -64.88883274173362, + -64.69673994010479, + -64.50796366224124, + -64.32312159258277, + -64.12314018644014, + -63.92081827337502, + -63.72362476919724, + -63.518495215160286, + -63.30621814697917, + -63.09775156198335, + -62.88512388334975, + -62.66755489876957, + -62.45221622175098, + -62.23244384909481, + -62.01294574095953, + -61.797165848834396, + -61.57844859793764, + -61.35676750292627, + -61.13764904108875, + -60.913958948083966, + -60.68835770839192, + -60.4639032078944, + -60.240140380911946, + -60.01428124793145, + -59.79349400741151, + -59.568453565516144, + -59.34337280034526, + -59.12099930516383, + -58.89234417074142, + -58.66546206150973, + -58.443926654764425, + -58.22197563076419, + -57.99691914914282, + -57.7858573920524, + -57.56798673677686, + -57.347636867085846, + -57.13459913937889, + -56.912562430064085, + -56.687429448579756, + -56.468789942761816, + -56.245386985762075, + -56.018754601727956, + -55.799065418774035, + -55.5855183332723, + -55.36229348495816, + -55.14053947443615, + -54.9222949185408, + -54.70282645857301, + -54.480597882969064, + -54.26499998226399, + -54.05146625314503, + -53.833881587790664, + -53.61799894792032, + -53.40159086033317, + -53.180210132692544, + -52.962174855186966, + -52.747858101984505, + -52.5351623575907, + -52.328901860940086, + -52.12870463886185, + -51.924782676423575, + -51.72756685644262, + -51.53106038072766, + -51.3286602838826, + -51.123117717595456, + -50.91323763770998, + -50.70543784235384, + -50.49438155851113, + -50.27510822028462, + -50.050909480063616, + -49.823669528226226, + -49.59422691319602, + -49.36440612388891, + -49.134583903761175, + -48.90276059387876, + -48.6776976551374, + -48.45875150493637, + -48.237037244812875, + -48.01299505200677, + -47.78735522324146, + -47.56730557931867, + -47.34259502952261, + -47.11120550652267, + -46.88007594379417, + -46.64671633762666, + -46.416150078136745, + -46.172300421953395, + -45.92810876478263, + -45.68903856733507, + -45.446385626242474, + -45.18985324628705, + -44.94372691322733, + -44.70192897308499, + -44.4388573852421, + -44.17362366263393, + -43.92040723303416, + -43.65516753542635, + -43.37830386078054, + -43.12025807725942, + -42.86759601270207, + -42.58731737506445, + -42.30107905713094, + -42.022423625323306, + -41.719980538226665, + -41.41304072763449, + -41.11286088896048, + -40.795923494360935, + -40.48217486048098, + -40.16624475184209, + -39.83954074672723, + -39.51433138503104, + -39.19059499041351, + -38.855692630079304, + -38.52375773208069, + -38.19461421504617, + -37.84480949933679, + -37.49163018486492, + -37.144637803730156, + -36.7925621307796, + -36.43533341187442, + -36.086511974681386, + -35.74411094330811, + -35.3974239198621, + -35.070615321269564, + -34.75612404371996, + -34.433828009503436, + -34.119296782661245, + -33.82917333821225, + -33.53119170654072, + -33.23896565819366, + -32.96298573650396, + -32.68880755570047, + -32.411180307255314, + -32.14730907317692, + -31.89148736574123, + -31.63406399894263, + -31.382816104159236, + -31.14260470511524, + -30.908738528997826, + -30.679175267360588, + -30.453972229323984, + -30.239954435773935, + -30.034953451987597, + -29.83544699147934, + -29.63870010592736, + -29.45051392019687, + -29.26484764906907, + -29.080832426982415, + -28.904547605644584, + -28.733812127457593, + -28.560948097803262, + -28.398201418249936, + -28.244219460857213, + -28.085503298428566, + -27.93239840355711, + -27.788020578850716, + -27.6382945306535, + -27.489944406321268, + -27.347831741300396, + -27.204421570626206, + -27.05296883779879, + -26.898753759572028, + -26.743990246723495, + -26.58693748758553, + -26.434903402143977, + -26.27864859898281, + -26.118987136725572, + -25.960688848867633, + -25.80263384082788, + -25.641587531545945, + -25.490634425886167, + -25.345428899364343, + -25.198233210221513, + -25.054022176188564, + -24.90948308823688, + -24.768150125688518, + -24.622367149289303, + -24.47454313616094, + -24.32689585944346, + -24.177551516639706, + -24.02368924149357, + -23.864973243607917, + -23.70908548011217, + -23.55665080355543, + -23.40380073678331, + -23.255790164156334, + -23.112005237974362, + -22.974921510501254, + -22.836658156324113, + -22.701933896202043, + -22.57860038025221, + -22.460292385077597, + -22.34604813811691, + -22.235431708965255, + -22.12778442554132, + -22.02883321507727, + -21.934526113250715, + -21.841440296149116, + -21.750985679990453, + -21.667079661963893, + -21.5867976110394, + -21.508110597429436, + -21.437055558110558, + -21.36902699900956, + -21.298175186937353, + -21.230834669316433, + -21.167569360273735, + -21.099309576083893, + -21.030590119263348, + -20.963200368387593, + -20.890956437634305, + -20.8155983053334, + -20.738588165632944, + -20.660873903780818, + -20.58267998099796, + -20.502745508009546, + -20.421955384431214, + -20.34330220580916, + -20.265145814853938, + -20.18118020561016, + -20.102040809730145, + -20.026286139676, + -19.94960758496676, + -19.87154028788423, + -19.796544460529947, + -19.722975346652813, + -19.646816421842942, + -19.568828146982252, + -19.485389574699816, + -19.396748886114946, + -19.300280064223347, + -19.196228108034806, + -19.088681697785233, + -18.973792366598712, + -18.855078107823672, + -18.73464300770831, + -18.60742735561582, + -18.47426458226979, + -18.3356953708922, + -18.192468238461107, + -18.05014620355314, + -17.900311344850667, + -17.748259627428386, + -17.59985239845478, + -17.44749018124793, + -17.289831861687734, + -17.13476711030833, + -16.978987429061053, + -16.815182750249186, + -16.649125894399738, + -16.484893876493732, + -16.31141786509426, + -16.13937011537734, + -15.966794840397359, + -15.78756663352844, + -15.60156817702558, + -15.42305278717738, + -15.242249598749698, + -15.043921348952347, + -14.860129157670553, + -14.670611824815383, + -14.465757156182125, + -14.264695572567078, + -14.063136254561105, + -13.855595937981844, + -13.646791011708268, + -13.442235373770762, + -13.233586255091215, + -13.022735948499761, + -12.812340887866805, + -12.599936269082722, + -12.3875157182114, + -12.174185056595656, + -11.961061223735184, + -11.743969719285408, + -11.530653431910961, + -11.314437774434387, + -11.10220201621013, + -10.891674418989599, + -10.678543557240541, + -10.469547248740419, + -10.2624515237825, + -10.051378919587437, + -9.841779070441515, + -9.634490779696469, + -9.427093585360735, + -9.218670150847851, + -9.015585082397052, + -8.813825543884338, + -8.607017514119331, + -8.401703878797997, + -8.20298074403046, + -8.004702741756736, + -7.801652168700154, + -7.610108952407171, + -7.42142288803849, + -7.2264885692473735, + -7.039059526496087, + -6.8538488835666485, + -6.667048806111803, + -6.480069200058203, + -6.290853721787352, + -6.098503309303771, + -5.9105502171822195, + -5.7192761035844, + -5.529391050315129, + -5.346962338968414, + -5.156469172134299, + -4.973915853484037, + -4.797752869141554, + -4.6190817736512875, + -4.447224680955508, + -4.283957503658762, + -4.125194422673401, + -3.970335520706842, + -3.823632292155835, + -3.6807675216413864, + -3.547546651900776, + -3.423187895815954, + -3.3027916263417385, + -3.192411461611369, + -3.091623219459845, + -2.9974353690905984, + -2.9142283907573603, + -2.842398311146486, + -2.78200160182335, + -2.7332929856987773, + -2.697585945913979, + -2.6758406562339077, + -2.6692647170003116, + -2.6794013408390134, + -2.7068345307342736, + -2.750243888382191, + -2.8140204735141774, + -2.9019989163318414, + -3.0102149280354915, + -3.136163434944975, + -3.292116164523131, + -3.4732407107632817, + -3.6673367794577665, + -3.8855819480982174, + -4.121239444135406, + -4.367886537153666, + -4.6310590045092255, + -4.909107602324732, + -5.198241707007494, + -5.493338337837971, + -5.801065701760351, + -6.11715304648553, + -6.436004558689778, + -6.761900661809447, + -7.08484882685639, + -7.406039134764869, + -7.729457535360628, + -8.053267053009991, + -8.37159367129153, + -8.68936576889038, + -9.004949568297512, + -9.31682047245802, + -9.62696774417688, + -9.93245417582924, + -10.235487151275668, + -10.536757563008043, + -10.831021603735033, + -11.126865921930344, + -11.422013064881448, + -11.711720823201341, + -12.003050423904435, + -12.296803887576305, + -12.589869543335947, + -12.882519007259162, + -13.206824304862469, + -13.506153041046147, + -13.804482252710493, + -14.104526524025465, + -14.407232207829418, + -14.713380061745976, + -15.025173389468257, + -15.339392391657894, + -15.657636340223394, + -15.985835400864142, + -16.315854623638366, + -16.645196662538208, + -16.98721157759249, + -17.32813326129069, + -17.670578183215763, + -18.012771106910797, + -18.372457112967986, + -18.728236276014083, + -19.07590688798593, + -19.448794833792853, + -19.819856423742173, + -20.17754088957126, + -20.55025241238078, + -20.93166781440896, + -21.29683990132369, + -21.674990368027238, + -22.06002927686083, + -22.43131262677279, + -22.81070485571307, + -23.193418361000578, + -23.565429945496376, + -23.940763282180978, + -24.326808498268797, + -24.70813635926141, + -25.085573837306793, + -25.471415865390853, + -25.85905754259594, + -26.24067967699594, + -26.62835577756132, + -27.023276222597836, + -27.41673543567052, + -27.810942640593055, + -28.21092489010343, + -28.603232087112556, + -28.99032235059943, + -29.38285130277187, + -29.7640527462422, + -30.138842298441205, + -30.524940716961034, + -30.9031609071591, + -31.275535933580933, + -31.653674064251156, + -32.031825364270404, + -32.40078807806816, + -32.77565139090284, + -33.15572092407154, + -33.524616131218615, + -33.89788555388855, + -34.31205031475888, + -34.67917302969318, + -35.047490717617805, + -35.40843109635998, + -35.765511114477306, + -36.12346065001754, + -36.47838098507164, + -36.83849735418127, + -37.20493953280114, + -37.566328907076304, + -37.93701170042838, + -38.31494730759715, + -38.6832600789177, + -39.04813864890323, + -39.42307988909404, + -39.788370226073305, + -40.14692481413972, + -40.514965166964416, + -40.876722858299054, + -41.22342213010617, + -41.574186828760354, + -41.93368443234105, + -42.28015563616246, + -42.63314166434982, + -42.98871329167694, + -43.336115226771106, + -43.682257706749766, + -44.03144549426208, + -44.37217780132779, + -44.714603335792184, + -45.056444297411836, + -45.39785578436033, + -45.73739926610399, + -46.07722256707363, + -46.41392265976048, + -46.7536884124984, + -47.08837036597805, + -47.41816538407625, + -47.74972236062895, + -48.07810458489749, + -48.406582657969295, + -48.735465316936306, + -49.06695767124381, + -49.39895970424358, + -49.73018564900906, + -50.06126296328641, + -50.39551242883402, + -50.72834905185715, + -51.05150893735426, + -51.38114781399141, + -51.717259812594975, + -52.07301299189745, + -52.39875053442496, + -52.733819938449834, + -53.06355532999838, + -53.38589277702482, + -53.716245957876666, + -54.04869301317649, + -54.37178924855617, + -54.69642329062652, + -55.02574949580002, + -55.34834129208912, + -55.669145147422846, + -55.98960028704136, + -56.3076972647037, + -56.621269058949764, + -56.93013001812104, + -57.24022509237409, + -57.55092377293988, + -57.85341381392597, + -58.15499335547893, + -58.49317394099913, + -58.795631088408726, + -59.091024596135846, + -59.39217311527495, + -59.69419299884416, + -59.99299964095694, + -60.29196990099787, + -60.59386658038928, + -60.88848406793987, + -61.17521208756635, + -61.4546765742016, + -61.735882797629706, + -62.00895634729002, + -62.26878311208972, + -62.535928099095486, + -62.79467599850539, + -63.04577366907901, + -63.29258615431078, + -63.532465026755965, + -63.76603160470231, + -64.01143698884582, + -64.2470503431708, + -64.47776937000921, + -64.69985146036979, + -64.91011890076263, + -65.11988179054424, + -65.3067541269102, + -65.49349294740588, + -65.67787352151993, + -65.84831801820904, + -66.00543237013562, + -66.15149592500164, + -66.28718826595971, + -66.42162106870808, + -66.5449400884666, + -66.65912764232849, + -66.77431064903143, + -66.87844686027412, + -66.97074860087946, + -67.0581201025096, + -67.13291211280782, + -67.19976263984901, + -67.2577201728544, + -67.30180824980346, + -67.33745312389016, + -67.36778895840271, + -67.38511135378526, + -67.38654074476754, + -67.37602965781693, + -67.35486159496755, + -67.32253305632219, + -67.27822350802018, + -67.2214423833344, + -67.15138090897804, + -67.06713408138613, + -66.97115496015253, + -66.86398241166371, + -66.74260535983153, + -66.6124286904359, + -66.47603631568566, + -66.3223538863303, + -66.16347486178844, + -66.00119848845848, + -65.83522823405262, + -65.67165984607001, + -65.50577920561427, + -65.32982397618471, + -65.15726721485673, + -64.9839874745163, + -64.80122020292747, + -64.61961921010575, + -64.43955916572844, + -64.25791070889484, + -64.06429147947685, + -63.86949330469262, + -63.67349152816083, + -63.47230699031968, + -63.26594689905641, + -63.0585791504768, + -62.84804847784432, + -62.63558106177187, + -62.42359538938827, + -62.20750638047554, + -61.99064999614591, + -61.77627137593541, + -61.5591030115546, + -61.3393009777562, + -61.119650829716875, + -60.895726935657365, + -60.668349275660866, + -60.440341380750475, + -60.21114195590213, + -59.9799352263799, + -59.72910276464591, + -59.498188999257664, + -59.26975687989393, + -59.04510407064621, + -58.818231079100684, + -58.5988116024957, + -58.38759521545623, + -58.175723036610236, + -57.967848630035796, + -57.77784702640796, + -57.582916018358446, + -57.38763405398029, + -57.2043625573086, + -57.01231722463997, + -56.81442331127769, + -56.62234054540864, + -56.42458477237226, + -56.224255895006415, + -56.02328811809464, + -55.81992462558698, + -55.62008498502751, + -55.41666243639262, + -55.203566020502805, + -54.99347717623862, + -54.7827257372063, + -54.563907961629525, + -54.34541200182019, + -54.12995911009073, + -53.90694176591345, + -53.68048133160258, + -53.45608410949461, + -53.22444569531539, + -52.988828306748424, + -52.759969627072124, + -52.5307230438456, + -52.30249765484058, + -52.08318313925874, + -51.8617495682587, + -51.64291895230069, + -51.42674271864286, + -51.205374836573014, + -50.978822865355845, + -50.74893558123603, + -50.520451718492126, + -50.286235222182874, + -50.04404205777941, + -49.79841125314252, + -49.55133029598883, + -49.301142538041006, + -49.05171706351374, + -48.80262570546493, + -48.55795012537514, + -48.320503554169306, + -48.08122853844462, + -47.83923244013082, + -47.597854027344184, + -47.36296859969274, + -47.119848164271716, + -46.87179152215019, + -46.62784398461014, + -46.3865185398944, + -46.13758662508226, + -45.882506913206186, + -45.638350768579734, + -45.40202584931485, + -45.15286767081181, + -44.910602981557574, + -44.68683528605533, + -44.44814233486934, + -44.197869411745884, + -43.958137197320205, + -43.7175201928318, + -43.4659316411832, + -43.20799095845028, + -42.958669988965056, + -42.714975562290384, + -42.45226502704055, + -42.18397429266377, + -41.92212531907494, + -41.64374813716246, + -41.35245730080967, + -41.06432149035486, + -40.761467928484095, + -40.454594322204976, + -40.150273450651085, + -39.8354963456903, + -39.51103483054273, + -39.18926132755797, + -38.859115427458796, + -38.52251769893648, + -38.19902540483133, + -37.86218669225267, + -37.50934723842243, + -37.16581799944193, + -36.82223660091939, + -36.47303888228664, + -36.123074121166894, + -35.782204882836574, + -35.442409260937794, + -35.102056320517846, + -34.78629987780564, + -34.471883439756084, + -34.14746347121026, + -33.84605388489217, + -33.553708101905876, + -33.250563454522336, + -32.96460424785478, + -32.68641759692767, + -32.40952811630079, + -32.13647907841946, + -31.875496718347694, + -31.62040906978592, + -31.3692731568516, + -31.128653885588243, + -30.895484754384583, + -30.673021061602277, + -30.4564499076067, + -30.243102858337505, + -30.037110492090004, + -29.840072342414665, + -29.646596192747868, + -29.45520323757677, + -29.27322605585274, + -29.092874082076392, + -28.911547352606625, + -28.736870940234013, + -28.569567648391725, + -28.404831342714697, + -28.246515067547016, + -28.097330488214077, + -27.946981831102516, + -27.797469042688693, + -27.65824620050871, + -27.518667348820248, + -27.377270208336014, + -27.243466225191476, + -27.108572634055996, + -26.970365830634698, + -26.836377997977227, + -26.70039720608668, + -26.56266711343642, + -26.426854755029865, + -26.290415675286066, + -26.149065128213227, + -26.008000462419282, + -25.868400980166317, + -25.72419946234665, + -25.583747645422825, + -25.44457752090553, + -25.304002733636057, + -25.16402169134971, + -25.024850126056847, + -24.886710853992444, + -24.75077367734998, + -24.612215773194514, + -24.475219884022657, + -24.33902673184721, + -24.20212450543729, + -24.068034805090296, + -23.934360297636253, + -23.80302587282976, + -23.671934351942323, + -23.541636228121696, + -23.41150044334196, + -23.28447644210979, + -23.148561389650993, + -23.025401165750644, + -22.90954852775124, + -22.796729788349747, + -22.684810104200672, + -22.57605822622979, + -22.46792378791558, + -22.361120401782223, + -22.261551301205262, + -22.16353455580876, + -22.064981855155263, + -21.966975526131932, + -21.87150168248146, + -21.772723029819876, + -21.66942948268381, + -21.57520608187572, + -21.484674383312882, + -21.39262706670191, + -21.30338594612345, + -21.220403163730513, + -21.136668215983228, + -21.050642316748583, + -20.971266422092764, + -20.893704719430318, + -20.819095103855986, + -20.744356394558064, + -20.668110426183997, + -20.593575790907362, + -20.51913769651664, + -20.44398529835246, + -20.37019633369734, + -20.298325499929867, + -20.222271214700026, + -20.14286692746316, + -20.068865753641326, + -19.994722344735, + -19.921408639803634, + -19.848279216226192, + -19.77733712660915, + -19.708843692405654, + -19.639876490727172, + -19.571363877498232, + -19.500457183976046, + -19.42755711057401, + -19.353821194607914, + -19.277222947707447, + -19.198696655644017, + -19.117528511903302, + -19.032573119760347, + -18.948416948005327, + -18.8617110322628, + -18.76787339255267, + -18.671976260282626, + -18.572269788069963, + -18.465027304774082, + -18.35302653550974, + -18.23322606697562, + -18.109198924002346, + -17.97901877700008, + -17.8424357393355, + -17.699650572565574, + -17.546991433374593, + -17.388572184205284, + -17.22651462273087, + -17.05426537516221, + -16.875136298756033, + -16.696253347316734, + -16.505823524083787, + -16.312044657667926, + -16.121715044231273, + -15.918228961012252, + -15.713662817862469, + -15.520349065238337, + -15.314117388062634, + -15.101981873349454, + -14.901015296769765, + -14.692722931406239, + -14.47507862921057, + -14.264177112491339, + -14.051834892143809, + -13.828488818514472, + -13.610171729805234, + -13.392998744052473, + -13.14431326671235, + -12.919627335562577, + -12.694532034725631, + -12.46382295349791, + -12.231529775858943, + -12.002729134096949, + -11.770840032936897, + -11.545372404882938, + -11.319961015720121, + -11.094155532004333, + -10.870343496667056, + -10.649476851254931, + -10.432298095911957, + -10.216307836805138, + -10.001517123035553, + -9.790703986991717, + -9.580788044014426, + -9.370481683762973, + -9.16321502127577, + -8.961535107073983, + -8.759009779363042, + -8.557318526251073, + -8.355886338897776, + -8.153905396308813, + -7.951682623975034, + -7.75027452716869, + -7.5512766894352366, + -7.350702686380873, + -7.154769967425929, + -6.960011268123255, + -6.766274518296466, + -6.572764187927147, + -6.37801869391982, + -6.186990444418874, + -5.9952547142450285, + -5.8024834919889425, + -5.610113250581571, + -5.421421402540372, + -5.230705688924124, + -5.046683022305792, + -4.872716593779623, + -4.6951301980288855, + -4.511179217587073, + -4.332158443315197, + -4.158427781620778, + -3.9781560199225248, + -3.804624532867186, + -3.6385278102201566, + -3.4657404385840342, + -3.2985543996196376, + -3.143760131127154, + -2.990897550279068, + -2.853284988059845, + -2.728124024093954, + -2.6083346915128622, + -2.4995781005502993, + -2.401952119700064, + -2.3136789494691223, + -2.238971619951746, + -2.178121549782583, + -2.1308086498294294, + -2.0989279496834654, + -2.0811384019076833, + -2.0791462567281584, + -2.0941115217407553, + -2.127357150261988, + -2.1812564930478997, + -2.255843138179999, + -2.351285321542093, + -2.470949885461389, + -2.619418061092849, + -2.7877105289187534, + -2.975052188900128, + -3.186661968551388, + -3.4111859653665855, + -3.653318850390739, + -3.9126615935363556, + -4.1800908551126845, + -4.467339948394169, + -4.76213772483465, + -5.057079131423051, + -5.366431454037695, + -5.686629453715802, + -6.000219054441521, + -6.315818757227649, + -6.636045568944125, + -6.948817367054708, + -7.261130271977808, + -7.577241231467479, + -7.888166201756551, + -8.197871795054352, + -8.50808823068634, + -8.812478521149504, + -9.115105767042023, + -9.414291744215312, + -9.711444317474582, + -10.007502270019703, + -10.299487170473892, + -10.592538344186792, + -10.891153498312034, + -11.187520981503875, + -11.482022983094124, + -11.780385466250532, + -12.081554951147046, + -12.381652289882577, + -12.682140856885521, + -12.990862659199513, + -13.299742955942214, + -13.611617440190054, + -13.934305403208066, + -14.256927111462618, + -14.586113170885733, + -14.917746982119734, + -15.251391235544043, + -15.594129593187766, + -15.940412518175888, + -16.28431813443251, + -16.642108913478406, + -16.995968507434565, + -17.341447380945205, + -17.68624308935871, + -18.046967535864507, + -18.40739677468867, + -18.75423808809474, + -19.122883537464627, + -19.494562086443743, + -19.850467709603112, + -20.217375693444236, + -20.600471912205226, + -20.964774255638137, + -21.334574125398436, + -21.71635453927342, + -22.08321685900946, + -22.451794632413858, + -22.830192417191082, + -23.197398613331025, + -23.56588574348082, + -23.9411828469809, + -24.317713222784892, + -24.691862653126957, + -25.067342381426663, + -25.446518281020253, + -25.823575223588996, + -26.2028494895185, + -26.583118605135837, + -26.966954059517665, + -27.35077087822334, + -27.734676910582905, + -28.118658584974153, + -28.49849501805635, + -28.87466346669121, + -29.25502327108787, + -29.62282677381422, + -29.98810194848637, + -30.36409863788679, + -30.729381056802502, + -31.093416129346256, + -31.462290431553313, + -31.82712487808434, + -32.183114856408764, + -32.54546634304612, + -32.91461519520696, + -33.27211085075718, + -33.634882201375724, + -34.00379296069003, + -34.365538004602506, + -34.729305012827695, + -35.09053582815073, + -35.442051401313115, + -35.80147397332604, + -36.156478428285936, + -36.509943348927166, + -36.87540585234159, + -37.23901072209325, + -37.60450716369108, + -37.98091776311527, + -38.35826093083761, + -38.72586756756725, + -39.099598938468134, + -39.47442917873935, + -39.83691641541903, + -40.204012329161955, + -40.574518240633275, + -40.93284919279329, + -41.286376866942405, + -41.64670181348839, + -42.002212553600565, + -42.3507670717366, + -42.710882038521, + -43.06959132588439, + -43.421435885960044, + -43.7807719502002, + -44.13042410569125, + -44.47974523087207, + -44.83083555170508, + -45.17975029971333, + -45.526137563452274, + -45.875589050399924, + -46.22206441573103, + -46.569064381392046, + -46.91316488006124, + -47.252871500956985, + -47.59460254898223, + -47.93472843239765, + -48.27245989973975, + -48.61316785031234, + -48.95780558244229, + -49.30319506797552, + -49.64442423993319, + -49.98381841805986, + -50.32604717784858, + -50.66631640577856, + -50.99451219306471, + -51.32925243718483, + -51.66956924331703, + -51.998736515246826, + -52.3287767677094, + -52.667858253196044, + -53.01000201520464, + -53.36753357541763, + -53.73099880724471, + -54.095482201916454, + -54.451681350020955, + -54.80973824207325, + -55.17013669730103, + -55.524106384949896, + -55.8756427780986, + -56.22684818609178, + -56.568173790368725, + -56.89164961503797, + -57.210054830820965, + -57.527142887254534, + -57.84681566068695, + -58.1570298021242, + -58.463839291949, + -58.77464051965263, + -59.080840617557335, + -59.379611364919995, + -59.676143211914265, + -59.95963755435715, + -60.239955016541984, + -60.52007216423825, + -60.80366715994708, + -61.08194029433051, + -61.35281209135889, + -61.61752644560808, + -61.88090988763418, + -62.17169681900389, + -62.41810160592986, + -62.67171699605905, + -62.92700286480446, + -63.171093429782275, + -63.40996922133053, + -63.648671884466815, + -63.881023424434204, + -64.11161156677625, + -64.33274081599845, + -64.5484139784681, + -64.76538019545904, + -64.9762134188021, + -65.20740470348781, + -65.40373475442904, + -65.59756447844596, + -65.80873944884215, + -65.99163835726283, + -66.1642621214959, + -66.32658432151234, + -66.48021806007075, + -66.62097019240412, + -66.74939135202578, + -66.87171558534783, + -66.97876032382108, + -67.07211215897057, + -67.15447761613395, + -67.22104224477765, + -67.2741529478326, + -67.31308135995369, + -67.33853409042516, + -67.35370455384614, + -67.35460539923463, + -67.33965814033566, + -67.30902899364848, + -67.26404469862514, + -67.2078001782688, + -67.13824374251357, + -67.05358555831275, + -66.95710528627973, + -66.84693482330073, + -66.72309386440044, + -66.58992031612112, + -66.44468496860021, + -66.29607605628406, + -66.14247628542849, + -65.98439382705837, + -65.82077959233854, + -65.65819730422088, + -65.49709534143815, + -65.32840960359943, + -65.16012022721834, + -64.99283673717963, + -64.81902387014065, + -64.64236745794976, + -64.46675564704715, + -64.28902454181636, + -64.10627233332251, + -63.9245189968719, + -63.739895374679506, + -63.552789948909144, + -63.36255950167904, + -63.171640173338844, + -62.977289859578626, + -62.78089205260735, + -62.58559801107137, + -62.385988271432005, + -62.18664524096537, + -61.98937501139463, + -61.78934089875508, + -61.585390276013854, + -61.38256301127122, + -61.174410387424665, + -60.961679105118876, + -60.74845623489055, + -60.533814350995335, + -60.31690206841151, + -60.10096530121553, + -59.882987962738184, + -59.66207909539635, + -59.44231655656435, + -59.21722167022417, + -58.98802951173427, + -58.76205771207255, + -58.53723530877152, + -58.30593089017669, + -58.08199102346705, + -57.86537305766054, + -57.63728994130255, + -57.417093154127556, + -57.19783982644442, + -56.96809559375092, + -56.745401588101466, + -56.527400212898556, + -56.302759666354554, + -56.08121448281064, + -55.86963629564599, + -55.65688287615789, + -55.43401671720818, + -55.21534072806675, + -54.99965622634113, + -54.77522794277379, + -54.550565532425885, + -54.33252560499146, + -54.10737652938803, + -53.87845931182021, + -53.65398134783925, + -53.423887931321886, + -53.18849279457918, + -52.96138067614139, + -52.73633495991684, + -52.511767140085105, + -52.293945992345314, + -52.07486610261543, + -51.86308025501084, + -51.64710141416969, + -51.4285046739303, + -51.207936041427956, + -50.98112666724028, + -50.75759524732726, + -50.530524647357275, + -50.29611717891968, + -50.05853979565974, + -49.82148790953997, + -49.579964240667685, + -49.337494641666325, + -49.099491975439534, + -48.86009979050132, + -48.63134517445355, + -48.40446603377749, + -48.15076643023613, + -47.91352750034972, + -47.68602777604388, + -47.4606470698996, + -47.22363976674354, + -46.98960292127097, + -46.75719495268253, + -46.526941675163066, + -46.28666461660954, + -46.049829381604496, + -45.818999186174935, + -45.590109752221245, + -45.34974987102058, + -45.11066667581404, + -44.882333624532365, + -44.64177533187349, + -44.38690967518651, + -44.13745327703394, + -43.89167800014418, + -43.6346765855797, + -43.37106746872596, + -43.120170567487335, + -42.87514780108498, + -42.61189937175488, + -42.3444472783157, + -42.08199659401624, + -41.80345028441472, + -41.514048526503196, + -41.22651686968583, + -40.92555981169007, + -40.620679684726795, + -40.31489772743544, + -39.99940914928018, + -39.672597049306184, + -39.34823267667472, + -39.01389573865975, + -38.67111447699712, + -38.3417180772891, + -37.99869991142855, + -37.64066093269598, + -37.29183094018727, + -36.944293079592875, + -36.59102497377393, + -36.240332036105386, + -35.903320575532284, + -35.56515687007894, + -35.23029923900151, + -34.92269420854079, + -34.614763213636685, + -34.29892708616655, + -34.01210940746176, + -33.72535284716105, + -33.43346597443473, + -33.16069412386568, + -32.893568944678464, + -32.618449071051465, + -32.351954603625344, + -32.09740388948943, + -31.843371052113444, + -31.591763948974286, + -31.34816043213504, + -31.111338409549965, + -30.884495494391107, + -30.660592507642257, + -30.43986832898685, + -30.232311921187634, + -30.034832536263558, + -29.836882422200684, + -29.647805933322292, + -29.464161681522267, + -29.278335121264682, + -29.09703501070668, + -28.92426903504328, + -28.752792917301697, + -28.57969357253216, + -28.419568014755612, + -28.264885833516104, + -28.105049263851885, + -27.953223004070953, + -27.809238189289864, + -27.658637193310675, + -27.51092928949594, + -27.368130468550394, + -27.22228630232354, + -27.078306792113878, + -26.93666850605959, + -26.793280175586176, + -26.647893986261852, + -26.506868769852076, + -26.362206492738075, + -26.213789442975205, + -26.065900168254448, + -25.917723340433536, + -25.76644333607956, + -25.617643956734327, + -25.469910724251086, + -25.32087796709313, + -25.175205130333048, + -25.02923169482956, + -24.88858201198964, + -24.744508251223348, + -24.599890378823794, + -24.45614000552284, + -24.31174841617279, + -24.169613655949668, + -24.025554899223497, + -23.88392619934849, + -23.744495502265423, + -23.603328354286806, + -23.46321450382037, + -23.326411948354405, + -23.195045748240727, + -23.06177641883814, + -22.93121302256855, + -22.80615728391779, + -22.68289856818865, + -22.56415621191781, + -22.447976935762057, + -22.333911497446024, + -22.22793228306158, + -22.124055858807413, + -22.01852245969138, + -21.91624251358265, + -21.819172107053053, + -21.71383450795761, + -21.60779321331262, + -21.51057160389064, + -21.413535363175278, + -21.313846004326333, + -21.221748340988928, + -21.132012972374937, + -21.034140729436047, + -20.940020427879332, + -20.84880348241341, + -20.757562254644483, + -20.666031727970818, + -20.574703883397184, + -20.482314164119668, + -20.38841150430447, + -20.29335029544132, + -20.200865709932508, + -20.11118814062886, + -20.017291769726018, + -19.925399536618944, + -19.836184497930848, + -19.74708590869075, + -19.655944044723206, + -19.569553194373647, + -19.48507098397482, + -19.398711486551836, + -19.311303325113908, + -19.218866146453074, + -19.122777395645734, + -19.023391537244862, + -18.921415244909824, + -18.815847394177677, + -18.706022277471703, + -18.59663693758805, + -18.481433923823037, + -18.360150135271645, + -18.23514641089734, + -18.11650148987277, + -17.998273267605136, + -17.873623826276784, + -17.744163833825844, + -17.611702852220468, + -17.475956962954065, + -17.333844386239388, + -17.185815383871923, + -17.036862941336874, + -16.88543948550195, + -16.71508023090852, + -16.539657270708158, + -16.361528991185704, + -16.175309519380576, + -15.992975878334086, + -15.809859644432564, + -15.613581896340465, + -15.425261356390541, + -15.24047317195969, + -15.035840578274309, + -14.84650269721174, + -14.670204811131125, + -14.475004061424876, + -14.277627277337423, + -14.085006727846713, + -13.883696292373584, + -13.6760943845444, + -13.475113325042148, + -13.273863511387828, + -13.06761417066516, + -12.85571265687709, + -12.642648543091907, + -12.426046847370069, + -12.206646246010985, + -11.989051906594568, + -11.767208718892018, + -11.548567712995542, + -11.327059003885726, + -11.108289901515315, + -10.89483712861106, + -10.651596952608092, + -10.402437268413932, + -10.154654641580422, + -9.903982397230568, + -9.655577505284743, + -9.410451765981142, + -9.167145777093761, + -8.922410420456462, + -8.677950678765317, + -8.442878178667304, + -8.224549091238233, + -8.012244108645312, + -7.803377836943842, + -7.5992916658262235, + -7.3905951917552155, + -7.180661574635478, + -6.978917859540822, + -6.775344940328747, + -6.5707139938575985, + -6.369800614404133, + -6.16294179079084, + -5.955294821820569, + -5.7494593187793015, + -5.53920160205076, + -5.327561320334729, + -5.127665088135819, + -4.923495928887167, + -4.716923102821366, + -4.522760306960668, + -4.324679740492083, + -4.1349298904023835, + -3.9574413344576356, + -3.779892597270801, + -3.603220899922884, + -3.435553303622606, + -3.272291094171636, + -3.1088952667081533, + -2.9554104392099503, + -2.8056806730677, + -2.661758505747535, + -2.528416841861101, + -2.397186683423948, + -2.27517888973646, + -2.164584053072101, + -2.0615658461716873, + -1.9662971884350573, + -1.880455250454103, + -1.8062125159846574, + -1.7416060408752518, + -1.6883575246470086, + -1.6464221118954492, + -1.6161019349254333, + -1.598952334573434, + -1.5962239149252784, + -1.6088778091433145, + -1.6365442606316238, + -1.6817466445111175, + -1.7471709239700712, + -1.8304379054912938, + -1.9293634624295373, + -2.0557765917490776, + -2.2106226245532574, + -2.379448232045034, + -2.5642431789587876, + -2.770485432445319, + -2.984658334705341, + -3.2125196137460006, + -3.4560509928231054, + -3.7074353443265613, + -3.9715840351858427, + -4.261318533939599, + -4.524814887744411, + -4.801974158007338, + -5.086049453114505, + -5.3717500378122764, + -5.661918145237242, + -5.951433251046758, + -6.239212786650746, + -6.528322701353272, + -6.816435192112626, + -7.093688572207026, + -7.380497893714439, + -7.669322202948817, + -7.957540775263811, + -8.240558247756539, + -8.526147085033289, + -8.8094926928902, + -9.088670509354857, + -9.370651659488038, + -9.64811978897924, + -9.92364255285066, + -10.204372674559558, + -10.482359883396267, + -10.759157124840334, + -11.041214801482244, + -11.323874997705309, + -11.607346828275382, + -11.892572715090681, + -12.179160979136796, + -12.47143522716537, + -12.764556620481914, + -13.057292124639014, + -13.353928227169805, + -13.654242722158928, + -13.957140782146217, + -14.264127794442901, + -14.573264478042214, + -14.887181306730454, + -15.20907860518733, + -15.526499329387255, + -15.849211824472095, + -16.1837218211788, + -16.51242832777449, + -16.844908402576852, + -17.17604128776223, + -17.52185730380651, + -17.86363848644997, + -18.195146483620313, + -18.546750146028806, + -18.89652427529972, + -19.233422785718236, + -19.58001510150497, + -19.93962503028559, + -20.288186067872886, + -20.63609329753014, + -20.995772633526173, + -21.348988875525382, + -21.69659190603601, + -22.05360912650614, + -22.407707415262625, + -22.75424121571816, + -23.108273307268206, + -23.456800500960327, + -23.81209383041351, + -24.16824531704238, + -24.52007929669434, + -24.875864462154343, + -25.234450167280023, + -25.59249566257504, + -25.94840914936964, + -26.312619561636854, + -26.67225056181053, + -27.03042670043228, + -27.393002228059295, + -27.750145402605973, + -28.056119222177905, + -28.406556474352666, + -28.755716255364483, + -29.09454159159732, + -29.43946894773987, + -29.7860694420215, + -30.12272349580964, + -30.47029680231665, + -30.813465404750218, + -31.14857999508093, + -31.489246573379937, + -31.83343464508342, + -32.180106428740125, + -32.5181274336786, + -32.859070374984235, + -33.2098595497299, + -33.553603501315536, + -33.89825888738154, + -34.237887134155855, + -34.56665357821295, + -34.899538291821145, + -35.22762919113327, + -35.55176383432408, + -35.87623956047461, + -36.201292388560894, + -36.5207841866333, + -36.84531761093447, + -37.165586545365954, + -37.475087034752455, + -37.781226759500434, + -38.07977000686565, + -38.36833329366603, + -38.64527235782367, + -38.95212376368915, + -39.22191254840864, + -39.476727235435135, + -39.72943703874776, + -39.978926081087, + -40.21587167988429, + -40.44927422439422, + -40.67779494125739, + -40.89732908766, + -41.10698439454845, + -41.31169356236648, + -41.50934421279334, + -41.70070147597102, + -41.885089193801406, + -42.0623696183549, + -42.23242790307994, + -42.3975268493152, + -42.554139770735866, + -42.706005443434805, + -42.85119877794946, + -42.99326441183154, + -43.13043244029614, + -43.26536152526621, + -43.396386244919455, + -43.525692046003925, + -43.645579472730375, + -43.76058152027081, + -43.87314104004291, + -43.97967154488688, + -44.08086289472793, + -44.14137311119168, + -44.23687926633128, + -44.32673352167267, + -44.411268496572475, + -44.488690502888126, + -44.563273244780454, + -44.63163749042488, + -44.69691641427846, + -44.76166908041577, + -44.82416156640577, + -44.88329338084764, + -44.938867626121535, + -44.991684912561816, + -45.04115679053738, + -45.084374913991404, + -45.12328908023327, + -45.158615138261865, + -45.18908164182476, + -45.21715773717338, + -45.241843955700894, + -45.26225978074167, + -45.2812397669999, + -45.29912954405049, + -45.31495342648793, + -45.32909914608487, + -45.34129563765416, + -45.35123159378307, + -45.36002550833295, + -45.367429663092, + -45.373450790889294, + -45.37892491568039, + -45.38348451296948, + -45.38709576122565, + -45.38987259486149, + -45.39201223749755, + -45.39378837231216, + -45.39522130842233, + -45.39638158814507, + -45.39745662734854, + -45.39852915472637, + -45.39959623986342, + -45.40060689908244, + -45.4009172382536, + -45.40117706279354, + -45.40140460923213, + -45.40163051313254, + -45.4018254182305, + -45.40199439764787, + -45.40215732635067, + -45.40230463500697, + -45.402431118078326, + -45.40253451824544, + -45.40347533642653, + -45.4045009196911, + -45.40552077161054, + -45.406543967452464, + -45.40756378700323, + -45.40413971615596, + -45.405139804092926, + -45.40612640666854, + -45.4071109824521, + -45.40809951205476, + -45.40833313628159, + -45.40847880006112, + -45.40862585447327, + -45.40876694322939, + -45.40890264220816, + -45.40903780334378, + -45.409165907549266, + -45.40928989672995, + -45.40941046317816, + -45.40952603744997, + -45.409900894210814, + -45.41028605882007, + -45.41065411389173, + -45.41100188576985, + -45.41133135166681, + -45.4116413057063, + -45.411932882404905, + -45.41220387265481, + -45.41245398582146, + -45.41268703353797, + -45.412762329630134, + -45.41281787658448, + -45.412867679042265, + -45.41291217928194, + -45.41295127054923, + -45.41298450778652, + -45.41301281485027, + -45.4130352475178, + -45.41305221925071, + -45.41306374612866, + -45.41309799695799, + -45.413099614007116, + -45.41306145129848, + -45.41298698123988, + -45.41287818974583, + -45.41273854380772, + -45.4125637350658, + -45.41235486001969, + -45.412116954526766, + -45.411841286248574, + -45.41177303123894, + -45.411730072958946, + -45.4116850162911, + -45.411637649842746, + -45.41158623264187, + -45.4115310064707, + -45.41147140268202, + -45.411400723873406, + -45.41133185972873, + -45.41126062736721, + -45.41124040327362, + -45.41122029569904, + -45.411202513724646, + -45.41118365673517, + -45.41116019455542, + -45.411136594624296, + -45.411114116089095, + -45.41108971761326 ], "xaxis": "x", "y": [ - 45.3008156780876, - 45.30139249659502, - 45.30207388412416, - 45.302779365342516, - 45.30327017525618, - 45.30366755396359, - 45.304470145008935, - 45.30518387263864, - 45.30609090911849, - 45.30687156544467, - 45.307606550331045, - 45.308498081838486, - 45.30942195356706, - 45.310178104221386, - 45.310926488730445, - 45.31182747165074, - 45.31266222320987, - 45.31351501570955, - 45.314094239896505, - 45.31467869635597, - 45.31528909457208, - 45.31597277766448, - 45.31654964174645, - 45.317203857669774, - 45.31777798392741, - 45.31839253279861, - 45.31897215740679, - 45.319468677500254, - 45.31992878987747, - 45.320431444448275, - 45.32081689665318, - 45.32120610300833, - 45.321625721527056, - 45.32202211593169, - 45.32250820449737, - 45.322955418807005, - 45.3233432006593, - 45.3236721494652, - 45.32406768610164, - 45.32449448721753, - 45.324786667993585, - 45.325181078207635, - 45.32569962486422, - 45.325977368459846, - 45.326232633712586, - 45.32652617078259, - 45.32690094971074, - 45.327175032373795, - 45.327468279438456, - 45.32782881931442, - 45.32815955695149, - 45.32855726232112, - 45.3289479042678, - 45.32925402295475, - 45.32957195489748, - 45.32988602204331, - 45.3302553562011, - 45.33056458182725, - 45.33077645486678, - 45.331108311543844, - 45.33133192390389, - 45.33163701185809, - 45.3319656771283, - 45.33221244624497, - 45.33247912474411, - 45.33278226233508, - 45.3330664033172, - 45.33370888493417, - 45.33458040982336, - 45.33537000147783, - 45.33612905222214, - 45.337045324723526, - 45.33803467707128, - 45.33891321918778, - 45.33974516663382, - 45.340669989337506, - 45.341706933303875, - 45.3424165803379, - 45.34316434906252, - 45.343982178039354, - 45.34460533149476, - 45.345352162774525, - 45.34626063496387, - 45.346987307893635, - 45.34767841539286, - 45.34859987931272, - 45.34945584746354, - 45.350395505481366, - 45.35148574922371, - 45.35254371492952, - 45.35358334727091, - 45.35455292738862, - 45.35554700714752, - 45.3566151497575, - 45.35760786605543, - 45.358603163309496, - 45.35954239913033, - 45.36044313293403, - 45.36108732179106, - 45.36166416591801, - 45.36242752377537, - 45.36315745628319, - 45.36366896891568, - 45.36422668083271, - 45.36470075387124, - 45.365418958998745, - 45.36623907015416, - 45.36684004409919, - 45.367561299130706, - 45.36827572050837, - 45.36897988583669, - 45.36982052976597, - 45.37060570595836, - 45.371247589681396, - 45.37195435313954, - 45.37271734665364, - 45.37354313216032, - 45.374367704722154, - 45.374955454021205, - 45.37553003991417, - 45.37627435510372, - 45.37705473867891, - 45.377721903573075, - 45.37831286704026, - 45.379033142782866, - 45.379830947639604, - 45.38059243751599, - 45.38117249069004, - 45.381584204690135, - 45.382289755173126, - 45.38304080280461, - 45.383534270318066, - 45.38414144610749, - 45.384963056608626, - 45.3854795917873, - 45.386329977947234, - 45.38686672616464, - 45.387358926539015, - 45.387647810618766, - 45.38831143294449, - 45.389019970667675, - 45.38933818219206, - 45.38986687054689, - 45.390494593561264, - 45.39114008025351, - 45.39191132113288, - 45.39257737356896, - 45.39308626634105, - 45.39382450230375, - 45.394881821393, - 45.39538367284164, - 45.39587702399459, - 45.39656761866656, - 45.39729705610352, - 45.39792512989577, - 45.39838165972011, - 45.39874233865337, - 45.39902638582274, - 45.39967427948701, - 45.40023006427122, - 45.400584152467445, - 45.40096982891739, - 45.40161061108628, - 45.40241610102564, - 45.40353330610432, - 45.404046616503614, - 45.40454401090433, - 45.40543917032443, - 45.406808970991854, - 45.40875166726319, - 45.41009398234997, - 45.41119017778836, - 45.41277666718019, - 45.414441898035896, - 45.41595401106941, - 45.41744928896387, - 45.41896141057751, - 45.42038195091547, - 45.42179378705188, - 45.42328822555661, - 45.424667636170554, - 45.42602883424413, - 45.42747793039279, - 45.42899354980808, - 45.43039835660806, - 45.43190844253109, - 45.43341773885088, - 45.4346268542106, - 45.43562375873985, - 45.43674924925812, - 45.43805682224895, - 45.439370632660086, - 45.44061735675941, - 45.441537158339806, - 45.44261891673703, - 45.44387328724353, - 45.44504649112133, - 45.446088310458094, - 45.446863676367514, - 45.44783462592337, - 45.44913497438336, - 45.44995477834738, - 45.4508777616672, - 45.45197956661854, - 45.45340942077631, - 45.45573246220501, - 45.45718909584074, - 45.45938684207846, - 45.461389196091126, - 45.46334061612658, - 45.46926139318614, - 45.48089777711856, - 45.501214711717786, - 45.53288822687134, - 45.577290444240646, - 45.633096606635455, - 45.694498226716014, - 45.753903368151434, - 45.80324708003626, - 45.842514531229476, - 45.871001472155704, - 45.89232880537815, - 45.90755927947151, - 45.91810200470127, - 45.92735225768559, - 45.93863367975251, - 45.95510226972569, - 45.98220132377144, - 46.02101755307864, - 46.072201015367, - 46.136281479681884, - 46.21268366519937, - 46.30023381874523, - 46.3987222526035, - 46.50841955536481, - 46.630216313790825, - 46.764829759859204, - 46.91125682816488, - 47.067105943074985, - 47.2301537665803, - 47.40069902256385, - 47.57923186470848, - 47.75964445930259, - 47.93985239218809, - 48.11860858050425, - 48.297836894706336, - 48.472262707350595, - 48.63911928992631, - 48.80357382257347, - 48.95798249389381, - 49.10089279573725, - 49.237599758046144, - 49.362792853770976, - 49.47604431993286, - 49.57548028229101, - 49.66420073780353, - 49.7399837451903, - 49.799237489241285, - 49.84418947149259, - 49.875802185057275, - 49.89222039768281, - 49.89099748302868, - 49.87043247632826, - 49.83138604513381, - 49.77439663659841, - 49.69922220649449, - 49.60464481714886, - 49.493100513352935, - 49.36949924541319, - 49.22537423589797, - 49.06192063745789, - 48.90056135171285, - 48.71326156484875, - 48.50677767207073, - 48.29123013154028, - 48.06217323972727, - 47.8263036719102, - 47.574960042544, - 47.30548547698959, - 47.045676425305, - 46.77277482648385, - 46.47996621724064, - 46.19731751334456, - 45.90729061412997, - 45.598604405795726, - 45.29071891001583, - 44.980974826570744, - 44.66267315736977, - 44.335157104668696, - 44.00718979490236, - 43.67453768698372, - 43.33532658956795, - 43.00035013818195, - 42.66252204416129, - 42.31053292607663, - 41.96500768512144, - 41.61781986964398, - 41.262578113674586, - 40.889098081171305, - 40.53548505220367, - 40.17463957841586, - 39.79404993323112, - 39.4227806618875, - 39.05773260388129, - 38.683176224769205, - 38.29913475580295, - 37.93580532168676, - 37.56441738761964, - 37.17811635258044, - 36.804510099558854, - 36.44113900340817, - 36.064546098911265, - 35.69372087141643, - 35.334615656045194, - 34.9644569027439, - 34.597104208935136, - 34.22727820122309, - 33.86389863684194, - 33.49488431760243, - 33.12181591189096, - 32.759274732150935, - 32.395474510484995, - 32.03804504836804, - 31.66601075130246, - 31.31725611808596, - 30.967690039639177, - 30.601231172111575, - 30.245156493319932, - 29.893627092750066, - 29.540271224832736, - 29.177603179598087, - 28.817969149126267, - 28.467078341879606, - 28.11085186343826, - 27.755593154455127, - 27.402708520690407, - 27.05160239263043, - 26.69603599407251, - 26.34608845173437, - 25.997783470672367, - 25.636561296441418, - 25.292832310208993, - 24.952662739209387, - 24.59828609904642, - 24.24889079335562, - 23.90981742879898, - 23.556238946751584, - 23.208548846812583, - 22.867356255936546, - 22.520619688446672, - 22.1876450455937, - 21.854303830472148, - 21.51917623638629, - 21.19556415285358, - 20.873701750356773, - 20.542221125944344, - 20.2240715322587, - 19.90671534746058, - 19.57797828845812, - 19.263416671605512, - 18.949845388828383, - 18.629574691901183, - 18.31678177799355, - 18.007455306366328, - 17.686616681291696, - 17.36593154591251, - 17.053670632089403, - 16.734225319944265, - 16.41665371576344, - 16.105345159951728, - 15.795884134788553, - 15.482673454930206, - 15.16978272106591, - 14.856165353792097, - 14.542356140388431, - 14.223514689927992, - 13.906649352658695, - 13.589123697081071, - 13.265220477639241, - 12.945816900600125, - 12.62347924681104, - 12.296554103238934, - 11.974138151036009, - 11.655235559168181, - 11.328660914920984, - 11.003878164777806, - 10.689554109617307, - 10.336243739986498, - 10.012882028606871, - 9.70006425773776, - 9.387405783443159, - 9.07221919192586, - 8.76318492149884, - 8.459091266684318, - 8.15366952352691, - 7.851049574429019, - 7.550825329024207, - 7.2475686489489695, - 6.95111250129687, - 6.649122672343673, - 6.3415263993000455, - 6.040796463926234, - 5.735054831825614, - 5.417440985445541, - 5.103882331876352, - 4.796628215343878, - 4.4710126942388495, - 4.154003125172445, - 3.8482676826184345, - 3.520071410336961, - 3.196028968250423, - 2.8827003196684813, - 2.5533895948068066, - 2.2256742525251783, - 1.9065839344434248, - 1.5787089986988987, - 1.2651164732978843, - 0.9526818893866802, - 0.6337693479703133, - 0.3341686963750352, - 0.03254823819888407, - -0.27648412447609516, - -0.5687027525870395, - -0.8635005364573746, - -1.1665914153099537, - -1.454811315170887, - -1.7427599098874327, - -2.0294113008777246, - -2.3085698226508033, - -2.5797839307054833, - -2.8474848989618433, - -3.0857886310911478, - -3.305761264129615, - -3.525632163772129, - -3.722457127936083, - -3.894970666098154, - -4.057218885737025, - -4.194189076241781, - -4.303664293010956, - -4.39493505559735, - -4.463884314162211, - -4.508502390300171, - -4.529686531299095, - -4.528705855772213, - -4.507491266321912, - -4.465671421355342, - -4.405001886944767, - -4.32625764130935, - -4.230554011243292, - -4.119715288476124, - -3.994783832463368, - -3.8540688232855236, - -3.7025005624448304, - -3.5376120998679643, - -3.358881803838362, - -3.171118176019267, - -2.972527316378767, - -2.7633975361435636, - -2.549750915092249, - -2.3316471827646374, - -2.109896765989796, - -1.8863183099210437, - -1.6652110461765917, - -1.4451771478074735, - -1.226889137720352, - -1.011277772934694, - -0.7993051441073634, - -0.5897134119466692, - -0.3830455392882667, - -0.1864948954127271, - 0.0004078606033779599, - 0.1841737451301992, - 0.3581433899216065, - 0.523106531424442, - 0.6856718939917603, - 0.8448896943368465, - 0.9852469551509175, - 1.120574499501041, - 1.2534584683232481, - 1.372300570357847, - 1.4891902499772482, - 1.6025651196027995, - 1.700974297405831, - 1.7950677733487508, - 1.886022272846113, - 1.9685798216488397, - 2.050010889495398, - 2.1279426241905512, - 2.1940161643564493, - 2.2545925319915137, - 2.315099925122909, - 2.369688620213981, - 2.4208469471933536, - 2.4734767901004764, - 2.5217831366172576, - 2.564724544275585, - 2.60865494652897, - 2.652391161093852, - 2.6958755206167906, - 2.743230773389391, - 2.7926624770464876, - 2.8450847000196515, - 2.9027667471179592, - 2.9621795538146714, - 3.0228889257776115, - 3.08511995497618, - 3.147228635069744, - 3.209805052764536, - 3.275428095767219, - 3.3425320247803243, - 3.4132174717170405, - 3.4896686082634463, - 3.5732865496411255, - 3.662835601032349, - 3.7584972016324896, - 3.860760868542198, - 3.970510709658999, - 4.085992883988966, - 4.209555049949327, - 4.340229789785011, - 4.4786732655191575, - 4.62312839460308, - 4.773898205177146, - 4.929969700935827, - 5.092612765295047, - 5.261896756172644, - 5.43572917477412, - 5.61676170286682, - 5.805103169990768, - 5.998199751734249, - 6.194148892434426, - 6.396021645392319, - 6.60351207877032, - 6.812150181151334, - 7.024439891419589, - 7.239593035908757, - 7.461798938328259, - 7.689736019284011, - 7.910876789935185, - 8.134178225766638, - 8.366337537529912, - 8.595205430692014, - 8.828259709925012, - 9.067759325112458, - 9.308143599918386, - 9.544916660600956, - 9.782906022073732, - 10.02445110245041, - 10.266502632981478, - 10.511513709381713, - 10.767614786337361, - 11.021663554114792, - 11.271077075426104, - 11.532421447231798, - 11.794230143723857, - 12.048732529840379, - 12.318792424498856, - 12.587589110078033, - 12.85117505566216, - 13.129808979167192, - 13.41050860883629, - 13.682113883904265, - 13.970007124245505, - 14.25659636900969, - 14.533496888165852, - 14.825556253707173, - 15.114661339511507, - 15.390982998995568, - 15.676442715762622, - 15.950673586347234, - 16.22648841788473, - 16.510164390876515, - 16.787586376391996, - 17.059385215373506, - 17.32915554265866, - 17.589821311067574, - 17.851042436220453, - 18.120806514425322, - 18.381316539093813, - 18.649363293214517, - 18.92072779695792, - 19.17939668683508, - 19.44458360066395, - 19.716406254396798, - 19.973203953715267, - 20.248927654873327, - 20.53149678648731, - 20.80213783736742, - 21.081990773637354, - 21.365355880616196, - 21.643618225661513, - 21.913061774422967, - 22.190558366707357, - 22.465459989288973, - 22.736167042598407, - 23.00860562348474, - 23.2693424039515, - 23.529741273826666, - 23.793060143465997, - 24.050393670369758, - 24.308112897371167, - 24.561037908110176, - 24.814086088154934, - 25.072132468240415, - 25.32709391472432, - 25.58879628783784, - 25.862435987606062, - 26.124248052301922, - 26.400771359272834, - 26.698637999743013, - 26.988779903511194, - 27.28977737611257, - 27.61778207808079, - 27.933296000574693, - 28.233553746679014, - 28.559360939600225, - 28.893196662831155, - 29.213767786933026, - 29.549688880343254, - 29.898193639548563, - 30.236051826725706, - 30.575490053951725, - 30.921617312784136, - 31.266528699970756, - 31.61511586526169, - 31.965928409854495, - 32.321088124303174, - 32.68624282041068, - 33.05311612040869, - 33.41499561528636, - 33.78580401630252, - 34.162269284435375, - 34.53349236470104, - 34.902784680066155, - 35.28014955050072, - 35.65206884471092, - 35.993916155834775, - 36.337238246147166, - 36.69093602799156, - 37.01142486875497, - 37.32938252248089, - 37.66952001589818, - 37.98674315243737, - 38.292031888684036, - 38.617174936741286, - 38.93331799020795, - 39.244696475262366, - 39.572183475508645, - 39.89469340117806, - 40.21105414540574, - 40.5329396915485, - 40.852677910951414, - 41.170964054845285, - 41.492393746208634, - 41.816278996971505, - 42.13843244992256, - 42.4624769820841, - 42.78190785217412, - 43.10162998868757, - 43.41904839217346, - 43.74270882506173, - 44.06166939448674, - 44.3840251748717, - 44.70933557184713, - 45.02849952323979, - 45.33869853550536, - 45.65795522292771, - 45.9561873041327, - 46.244189478798894, - 46.542770418974314, - 46.82553262290039, - 47.10560214467375, - 47.397143331513625, - 47.67650898688305, - 47.951679475099674, - 48.262276345092104, - 48.54204525971228, - 48.817546869468444, - 49.10046596855581, - 49.39099902472938, - 49.67309590453489, - 49.9531390439686, - 50.2395789778626, - 50.52052218117748, - 50.795787443730156, - 51.07781152015942, - 51.35955903180017, - 51.63221003744897, - 51.911141814574215, - 52.19219993001085, - 52.46280337212093, - 52.73295430455883, - 53.00086997289239, - 53.25639675369177, - 53.514251272506066, - 53.76726885445143, - 54.01573680083499, - 54.267316364946964, - 54.51975090757005, - 54.77606529568504, - 55.029706361850785, - 55.28613124379961, - 55.55111631024073, - 55.820080831954876, - 56.0918879101304, - 56.364504005935174, - 56.63876528594555, - 56.91522558123022, - 57.18948768938687, - 57.45746616064551, - 57.72299585349498, - 57.992154637738096, - 58.25895001039742, - 58.52162243605322, - 58.78797891035919, - 59.057869470114625, - 59.32823146555272, - 59.59978179601026, - 59.869960334038346, - 60.154406857621844, - 60.433110048736474, - 60.70321189802036, - 60.98811954336956, - 61.2733693518662, - 61.53315476632863, - 61.806216591765086, - 62.086372734152064, - 62.33739996545596, - 62.57978455088455, - 62.826714824026105, - 63.05091904688225, - 63.24594773053274, - 63.45187542531075, - 63.65136295895432, - 63.82437506428474, - 63.99467278315867, - 64.15715766589464, - 64.29938772830046, - 64.43342067932468, - 64.55592054085274, - 64.66513713671445, - 64.76063170755718, - 64.84109386619431, - 64.90327777550321, - 64.9530878591095, - 64.98873716556929, - 65.01147423361941, - 65.02570767302133, - 65.02749972294426, - 65.01412424861836, - 64.9870922648049, - 64.9485383058607, - 64.89876947747825, - 64.83623928964768, - 64.75912746305288, - 64.67046203291542, - 64.57204155291505, - 64.45662609625938, - 64.32712540620042, - 64.19121308087333, - 64.03978132981177, - 63.873811932100324, - 63.699796682439825, - 63.507081971503794, - 63.302754832272456, - 63.08476247700988, - 62.847875973720406, - 62.60001405754087, - 62.338156798886146, - 62.06505294352749, - 61.78422636080124, - 61.495918882771704, - 61.20062871625016, - 60.89715647145221, - 60.59363227711049, - 60.286338617564006, - 59.97581702374971, - 59.66764178163206, - 59.35917472999657, - 59.0499470723258, - 58.73613869538399, - 58.41415273479658, - 58.09010416596422, - 57.77650297850374, - 57.45572065962611, - 57.12661173148182, - 56.81478018523037, - 56.49384328172674, - 56.165808011887776, - 55.84210982481136, - 55.52822010997151, - 55.20576107600213, - 54.88515707480901, - 54.57524655272796, - 54.25470433239023, - 53.932389323263045, - 53.618865361326115, - 53.29827369296802, - 52.97328779013662, - 52.6508437224558, - 52.330288949532154, - 52.00047183719301, - 51.6697709764731, - 51.3445725332754, - 51.00953256245475, - 50.675199188807724, - 50.347056527984535, - 50.01951657085091, - 49.69460635081357, - 49.37087699839047, - 49.039663193308186, - 48.7183576570489, - 48.39442939401609, - 48.06187421811483, - 47.735367706458796, - 47.40791623822752, - 47.08038176449596, - 46.75490105480903, - 46.428951274188265, - 46.099389827713274, - 45.77181593362555, - 45.44576347159304, - 45.11157220136288, - 44.782696246636846, - 44.45444085837797, - 44.11948276656226, - 43.78698960850408, - 43.460844945475515, - 43.12957279153525, - 42.80656058785394, - 42.47900659761572, - 42.14010304827866, - 41.81312894911944, - 41.4828844834615, - 41.14073464378206, - 40.790831824081856, - 40.458683095589194, - 40.11086212170768, - 39.74970426633614, - 39.39882618202941, - 39.04807585689426, - 38.694243359613246, - 38.333119226864, - 37.988340428417885, - 37.64166357394087, - 37.286300971218516, - 36.94067299149588, - 36.59429440030454, - 36.245001646987184, - 35.894488555799505, - 35.550597899545004, - 35.206908551835106, - 34.85800110128992, - 34.51274108570734, - 34.16109721333436, - 33.81582738929942, - 33.46808696874815, - 33.114084831080845, - 32.77641000358633, - 32.43553485318641, - 32.090718871663896, - 31.745921897846507, - 31.41410309010996, - 31.080169378701054, - 30.736477653480044, - 30.363381905863072, - 30.02845064741058, - 29.68423954889631, - 29.331032746250823, - 28.9809945998811, - 28.637363081978908, - 28.290136301718768, - 27.94504537970999, - 27.60622534312888, - 27.263000026771746, - 26.920784363114365, - 26.583815648547414, - 26.256011092523174, - 25.92365447564597, - 25.593690151688918, - 25.281026421461352, - 24.96259905015177, - 24.63841194877399, - 24.32563880841202, - 24.012127146120758, - 23.68589962457247, - 23.373195495681, - 23.068473395322435, - 22.748129764280563, - 22.440043876570734, - 22.14487558793027, - 21.83551863312298, - 21.53421228111542, - 21.248201984464405, - 20.945708396456133, - 20.64081927466012, - 20.357449089040124, - 20.03149966441319, - 19.720093229948088, - 19.435201812480095, - 19.144905494480355, - 18.841035547667776, - 18.55253000673612, - 18.264586541756902, - 17.965788952557034, - 17.671908548287185, - 17.37875574603664, - 17.0797388664511, - 16.783577182279164, - 16.48957195162242, - 16.196627188069524, - 15.908961657880663, - 15.619467707340434, - 15.329402507274027, - 15.041683546863892, - 14.751878699487346, - 14.461495813257766, - 14.170690971569112, - 13.8867959149224, - 13.593944847952267, - 13.302901500358487, - 13.016083493508878, - 12.72172994277544, - 12.428402293371853, - 12.135758882422708, - 11.839532109935789, - 11.538786474773989, - 11.241012185373176, - 10.944394413391453, - 10.644743644029987, - 10.344443309982122, - 10.046514095085957, - 9.747651902947501, - 9.445357567582166, - 9.144482895339513, - 8.849365986402391, - 8.550908631399782, - 8.25931297358785, - 7.972316267253725, - 7.687355281947255, - 7.404022902957972, - 7.125064806315193, - 6.8493587915491965, - 6.56815624385909, - 6.289947758426632, - 6.007619796696353, - 5.727679501862931, - 5.450295600272493, - 5.13650291779756, - 4.850484427189774, - 4.574164910703354, - 4.293910887024876, - 4.004374565766532, - 3.7120510453182836, - 3.4269112996098055, - 3.1344891416584884, - 2.8360522011068374, - 2.547019245380965, - 2.2494028422549746, - 1.9489033896265402, - 1.67120455158615, - 1.3868309317285878, - 1.0929825361587568, - 0.815642809736947, - 0.5402877602571728, - 0.25779440471505605, - -0.015820090274220804, - -0.2894913126194905, - -0.5640564076527189, - -0.8356416725538327, - -1.1072331463548326, - -1.3841510328431743, - -1.6591995343901804, - -1.9404886167329474, - -2.220919669520379, - -2.4986442046069617, - -2.7728521855353336, - -3.0438554155927364, - -3.313997694802523, - -3.5625877364363183, - -3.7915781436545024, - -4.0189937800303435, - -4.229870076382449, - -4.417881997703746, - -4.595480579252699, - -4.757489951167618, - -4.896623387289247, - -5.018915844925662, - -5.119489835476398, - -5.195548705790415, - -5.25126228266642, - -5.2841795569265635, - -5.292831710637094, - -5.278892062242572, - -5.244600399280449, - -5.194089304822076, - -5.123294391606358, - -5.03399507068378, - -4.933235474052575, - -4.815188985987018, - -4.681240280654256, - -4.538723052923676, - -4.382249427723075, - -4.213460040110186, - -4.0361065794578845, - -3.8502910466976052, - -3.656025545820314, - -3.4560829154449006, - -3.2524945997325934, - -3.043261252966324, - -2.8316333868655486, - -2.620229119594151, - -2.4110323757562764, - -2.2066924996544364, - -2.00518040356106, - -1.8107207804503536, - -1.620505805022866, - -1.4323830570331701, - -1.2491373686815526, - -1.0698302730834983, - -0.8932338729370016, - -0.7231197783989942, - -0.5577946798268661, - -0.39997884575165277, - -0.25086064533969765, - -0.10150288629249732, - 0.03921114626320604, - 0.17471077749946817, - 0.3043070416622088, - 0.43648982178307133, - 0.5622748639074678, - 0.6734836419307776, - 0.7867008460158456, - 0.895962611369247, - 0.9965770945643719, - 1.0958311059249572, - 1.1938361087859697, - 1.2821110310831099, - 1.364231352420128, - 1.4454265973633418, - 1.520340716139314, - 1.5930753419076706, - 1.6646118890652004, - 1.7291068967679482, - 1.7891544553959013, - 1.8456985207786494, - 1.899244506357675, - 1.9475202976315285, - 1.9929574748169114, - 2.03579577285625, - 2.0764217109349326, - 2.1140307854178264, - 2.1496401316420592, - 2.1850458865790854, - 2.219208730447587, - 2.2539632541126435, - 2.2906514400572338, - 2.3297655444874543, - 2.371185444490704, - 2.41644779667443, - 2.464060172631494, - 2.5109721037633066, - 2.5602644036293203, - 2.6108143478517976, - 2.6613617881714995, - 2.714123178891581, - 2.7684536843776764, - 2.8228949993006247, - 2.8800268016741852, - 2.9403840877793135, - 3.002161407579184, - 3.068184020594977, - 3.139146949739317, - 3.2143579905857766, - 3.2949232127770065, - 3.3818421415057895, - 3.4739901364427124, - 3.570184815458072, - 3.6720720455078406, - 3.7770999048557936, - 3.887869376895746, - 4.00661919157578, - 4.129030728272307, - 4.2560521838599055, - 4.393061839658805, - 4.533440260262142, - 4.6775180037611035, - 4.830011862211025, - 4.988896039339954, - 5.144000392428633, - 5.3049028724758145, - 5.47212379418288, - 5.638976742362163, - 5.807526688047787, - 5.982524727679, - 6.159214030937705, - 6.332095180397173, - 6.511497045887136, - 6.693704704756934, - 6.875197369226239, - 7.063564473750477, - 7.255672142776363, - 7.442886691707591, - 7.635592936096776, - 7.8346533040875626, - 8.03509816929982, - 8.237577875031166, - 8.448307817888143, - 8.66072048865215, - 8.872612942982652, - 9.08268721501466, - 9.295330537878796, - 9.51006012488097, - 9.724262240432347, - 9.938272629074817, - 10.158517169446744, - 10.382777336405727, - 10.602156621345047, - 10.82086117104478, - 11.047291725091869, - 11.272708492209368, - 11.491988903181552, - 11.72105359252825, - 11.952157487481044, - 12.177594801573768, - 12.41005064143213, - 12.648525756456184, - 12.884252070621573, - 13.119909581516461, - 13.365365905045502, - 13.606950302108704, - 13.84355089162025, - 14.090705051007193, - 14.339801637631709, - 14.579391152293853, - 14.823229366209237, - 15.071063546514575, - 15.309981807870773, - 15.553155563947865, - 15.803085414087619, - 16.0460542892863, - 16.28853145973164, - 16.530594019284234, - 16.767750430938626, - 16.997994732664846, - 17.22914615892, - 17.464042032722208, - 17.696195435545526, - 17.928963400106287, - 18.170396313340994, - 18.404911770979936, - 18.632773201619653, - 18.86861396003305, - 19.107525723154236, - 19.337515409785976, - 19.571872163418092, - 19.81537774092592, - 20.049121205306683, - 20.279423950116357, - 20.518393498541517, - 20.747714328000868, - 20.98186053415768, - 21.21400590800481, - 21.435743480005325, - 21.663773828905068, - 21.884492568732025, - 22.10230068911461, - 22.337482609855414, - 22.55678803148629, - 22.77148449953714, - 23.000846659949364, - 23.23139734517778, - 23.465707952139407, - 23.708546282416, - 23.94843354868638, - 24.199872438773035, - 24.461934267263292, - 24.729895379270047, - 24.996771028896625, - 25.283612970463412, - 25.570698071989074, - 25.853188213337447, - 26.162006779248262, - 26.47999145755729, - 26.78723584250772, - 27.12176317086207, - 27.451275937616725, - 27.734800856121986, - 28.03247936867568, - 28.33961146345534, - 28.636296723208126, - 28.936545363686367, - 29.246599874849714, - 29.55022391570878, - 29.850466486255595, - 30.152564197833787, - 30.456848339169074, - 30.777947437062487, - 31.09633074574183, - 31.413915306395243, - 31.733919333118052, - 32.05738918618142, - 32.38339297504573, - 32.69845253609786, - 33.02233050460258, - 33.35051633388529, - 33.68203245147105, - 34.018937032723066, - 34.3539873254395, - 34.69617026899503, - 35.028056427609776, - 35.353837752109136, - 35.67806336236072, - 36.00211278982288, - 36.31680367933958, - 36.639117222661454, - 36.9614908740441, - 37.26872273738408, - 37.57922006591536, - 37.89567640057429, - 38.211777147447854, - 38.528604536691105, - 38.852246853332126, - 39.17607981673305, - 39.498979405826006, - 39.824025274175206, - 40.145148721288294, - 40.476339975004876, - 40.81106746865938, - 41.14129810873627, - 41.474835183906976, - 41.81025367921867, - 42.14166012501361, - 42.47222463361508, - 42.80454492939298, - 43.13266055277677, - 43.46339955497243, - 43.788767565801884, - 44.11270992545289, - 44.4421659920752, - 44.76786017852259, - 45.08523809354388, - 45.41192795750231, - 45.73191436790232, - 46.0443173180707, - 46.36863719179993, - 46.680583537321326, - 46.98535134429957, - 47.300896233115886, - 47.60753805478654, - 47.908290016873806, - 48.22005742068531, - 48.524680338591075, - 48.81226824718113, - 49.117739807019106, - 49.424977028106625, - 49.716295513344164, - 50.02017166739853, - 50.327518375444534, - 50.61753374457286, - 50.91192433762515, - 51.210994094867324, - 51.497095491069466, - 51.786802823370024, - 52.082655715673305, - 52.36433625058349, - 52.64086855305455, - 52.9196097987463, - 53.18989176032296, - 53.45672496766371, - 53.71847554639376, - 53.98392127395361, - 54.247868095035905, - 54.51594943747289, - 54.78578329656477, - 55.053175965256905, - 55.32673404988352, - 55.60816434695921, - 55.891096660041555, - 56.17002278113821, - 56.45718733425426, - 56.739335430895515, - 57.01436135947399, - 57.294636784008155, - 57.56281328200112, - 57.820343777994964, - 58.08795471171312, - 58.36098770603641, - 58.61376757722674, - 58.86528033184651, - 59.1287464001122, - 59.38797958767201, - 59.63834330315669, - 59.891565926035796, - 60.15613322949835, - 60.41511892721383, - 60.66205547127083, - 60.91463548034098, - 61.17888758280835, - 61.42780964441885, - 61.67701956066958, - 61.94424795824756, - 62.19870373326381, - 62.430696439641245, - 62.66668740599379, - 62.89723983116863, - 63.094398205962435, - 63.28490475865507, - 63.482910310962495, - 63.660491151964685, - 63.821230030324756, - 63.98086805759875, - 64.12197267361248, - 64.24792760066693, - 64.36453889731763, - 64.46800888376497, - 64.5564510546822, - 64.62922632692454, - 64.6812992209274, - 64.71739132296442, - 64.73789964974321, - 64.7439040715773, - 64.73688022912468, - 64.71286656664903, - 64.67176819925788, - 64.61390344327381, - 64.53959924444034, - 64.45385923247711, - 64.35086128700219, - 64.22866983655938, - 64.09896598619568, - 63.95289561913557, - 63.784124616501664, - 63.61083168698891, - 63.41961471446286, - 63.209482144673196, - 62.99583111634186, - 62.77014618565708, - 62.52167367434831, - 62.26658233785969, - 62.00675270962785, - 61.72922993287618, - 61.44233320712871, - 61.15492822946826, - 60.86354132292463, - 60.56485050857393, - 60.257210856349765, - 59.94326087065825, - 59.6265391529923, - 59.30248363140266, - 58.97248495867293, - 58.64288748884854, - 58.30485072795838, - 57.9556159486451, - 57.60989846051303, - 57.26828973042716, - 56.90938151070443, - 56.56201036558662, - 56.2260318703524, - 55.87258210292476, - 55.52450545347809, - 55.191678950907026, - 54.842569777325664, - 54.50034430187689, - 54.16397664791392, - 53.81506068723594, - 53.46844999673037, - 53.12546618533615, - 52.771237548232456, - 52.416131885196044, - 52.06997292964902, - 51.70921728574256, - 51.34932654969274, - 50.996254010251924, - 50.632475120190506, - 50.27304033140169, - 49.920462892005354, - 49.564575846793105, - 49.2084079767248, - 48.850906416209334, - 48.50046930037752, - 48.14063878476699, - 47.77996322785137, - 47.42325662962246, - 47.06725232626325, - 46.71008107261035, - 46.35046553471646, - 45.993880165998355, - 45.63807784940863, - 45.27762151816358, - 44.87704195462212, - 44.51989654388736, - 44.15479523062273, - 43.78421874294206, - 43.420459137595664, - 43.050112333314246, - 42.68113629964051, - 42.31362731680097, - 41.93485694238308, - 41.55918420381393, - 41.189714940355074, - 40.801464269560746, - 40.411148977985675, - 40.042291799925536, - 39.649731442874064, - 39.253051860289105, - 38.87489921935038, - 38.48771087127243, - 38.083414891431914, - 37.70616935852628, - 37.32691393297396, - 36.931171793510565, - 36.55070476573083, - 36.177786735914644, - 35.79020476557115, - 35.407788641532385, - 35.038779597638246, - 34.66077094312423, - 34.27934693319909, - 33.90105384636693, - 33.527572022715994, - 33.143359280365985, - 32.76026593437598, - 32.38679497305845, - 32.00730000585379, - 31.626719826835444, - 31.254946739186128, - 30.887289382377276, - 30.512247442201993, - 30.13658462182371, - 29.766528681871424, - 29.38976250500205, - 29.004155919429586, - 28.62909146399714, - 28.254264130612647, - 27.876338314365942, - 27.505595716712246, - 27.131808965108885, - 26.757524197591497, - 26.389461805315932, - 26.026468433337648, - 25.6618095218435, - 25.30414354373347, - 24.958017631664948, - 24.601153949659874, - 24.24740650062091, - 23.900121622434913, - 23.537202272270793, - 23.183317636581993, - 22.835473512785967, - 22.48132141853015, - 22.138567909739955, - 21.800347632044677, - 21.458087837225776, - 21.127569173612148, - 20.79410490896639, - 20.44979926071972, - 20.131252020127988, - 19.807254862470852, - 19.46250668203238, - 19.14309515678464, - 18.822158666322974, - 18.484389662209296, - 18.15802249536964, - 17.839350604459312, - 17.503790610679896, - 17.18279635353825, - 16.887316563593416, - 16.58432027539839, - 16.285836656258173, - 15.998488711337787, - 15.706050705041125, - 15.412486367453946, - 15.12526468906649, - 14.831709058834692, - 14.539009667809236, - 14.239272893116445, - 13.931095235562534, - 13.619771167922194, - 13.308466798262845, - 13.001946361769999, - 12.69230938113229, - 12.382536700062241, - 12.075128830025376, - 11.768998362231162, - 11.457195405539851, - 11.144141366307275, - 10.832027317209997, - 10.518315653260595, - 10.204546415956004, - 9.896141915774662, - 9.592504687984121, - 9.284819313742853, - 8.982192400780749, - 8.685558266774898, - 8.390206477635632, - 8.096370276346233, - 7.809191266980111, - 7.52074451752643, - 7.232554645694854, - 6.947315584632098, - 6.652718868692668, - 6.355835606186661, - 6.066645304814446, - 5.7368072265099395, - 5.428234579838464, - 5.126423041081522, - 4.821908919914601, - 4.509444073749548, - 4.205763490389693, - 3.903414356462298, - 3.5895961220837638, - 3.2857902397490633, - 2.9879391894659926, - 2.67833424372988, - 2.3763449437131494, - 2.0799139729703624, - 1.7783088479566478, - 1.493890339972635, - 1.2080900397306307, - 0.9196675895400847, - 0.6486909989695223, - 0.37832567836853914, - 0.10259769135183895, - -0.16153310687831507, - -0.4287159968190723, - -0.7035148421559364, - -0.9805875505298111, - -1.2669542513347407, - -1.5492923349737737, - -1.8222514448022245, - -2.097713892939078, - -2.370835217615415, - -2.646681655038601, - -2.905696173590179, - -3.1487680002484337, - -3.4002994387283474, - -3.632539819233667, - -3.838726917758838, - -4.043406966843576, - -4.24119518731128, - -4.422860342940131, - -4.593148047467437, - -4.749831707061056, - -4.889870678773691, - -5.014872457500469, - -5.121991177980183, - -5.210338830976306, - -5.283298642679399, - -5.338418185267794, - -5.374688487883849, - -5.391714241780363, - -5.389777739731842, - -5.368472267339411, - -5.33043607064049, - -5.2753607264986435, - -5.205343541496031, - -5.120891760653099, - -5.022079124443184, - -4.910970696160349, - -4.78897079947705, - -4.655103139485727, - -4.512457571891651, - -4.359771112636242, - -4.1962573686174105, - -4.027853879376715, - -3.852368771853214, - -3.6674716577417565, - -3.4803658908609085, - -3.2918598507939962, - -3.07996566948812, - -2.887443932799642, - -2.6961274624367877, - -2.507135316960963, - -2.320736468016825, - -2.13376342129394, - -1.952028989159487, - -1.7716734828900949, - -1.5934054902590746, - -1.4199812351256735, - -1.2455211223044407, - -1.0777437100022877, - -0.910810587782139, - -0.7441583383260169, - -0.5830847179693679, - -0.43107570674228857, - -0.2808515446782764, - -0.1300501962348853, - 0.009926393514131816, - 0.1476784415624258, - 0.2784038338805753, - 0.40936338142276285, - 0.5382515338782801, - 0.6521455559490862, - 0.7635723765825918, - 0.8721639877723049, - 0.9712182010899587, - 1.0656798874971782, - 1.158557291897791, - 1.2421219532289738, - 1.3158638484406604, - 1.3861825987702523, - 1.450762393804458, - 1.5102063422491143, - 1.5678243800161544, - 1.6251682260404348, - 1.6716292464865594, - 1.7151689668009984, - 1.755435088106825, - 1.7920800449472067, - 1.8266724882279906, - 1.8601518435947482, - 1.8930350153638453, - 1.9250848774172855, - 1.9572235517317285, - 1.9903661874944014, - 2.022570447022477, - 2.055078452895796, - 2.0880934506908715, - 2.122330578346664, - 2.15866461123757, - 2.1963953276216595, - 2.2370243152175133, - 2.278847503475203, - 2.3204867073438584, - 2.3631674410288195, - 2.4073494602853054, - 2.451241663264259, - 2.4953097573735237, - 2.5397788014105283, - 2.5832132640758574, - 2.627321859696513, - 2.672179946191852, - 2.7182270060143026, - 2.7665467777316457, - 2.816291704063999, - 2.8705622404497277, - 2.929571861087087, - 2.99252319453981, - 3.0623735453840646, - 3.1376643520774383, - 3.216343267746385, - 3.299847663197868, - 3.3899491208748698, - 3.482849375700695, - 3.5831036484864667, - 3.6913679897846046, - 3.8035171898147864, - 3.9225387871201254, - 4.050032560389264, - 4.181438980745696, - 4.318249906501666, - 4.459155651995905, - 4.608287772914404, - 4.760499880534019, - 4.914963744884975, - 5.076347902144622, - 5.240123099284234, - 5.4027019118657496, - 5.567479621773198, - 5.737459031182647, - 5.907947508791681, - 6.081090529806267, - 6.263127347756526, - 6.445007073111551, - 6.628983398764286, - 6.821272284107228, - 7.010893620787833, - 7.203977853603422, - 7.402243835791255, - 7.602581138899236, - 7.805230439447765, - 8.01309451265696, - 8.221852422807364, - 8.433820757497474, - 8.647279369491388, - 8.861585659684101, - 9.08181850967727, - 9.306252053634548, - 9.531414875545613, - 9.759532590099607, - 9.993641587754778, - 10.23174123739043, - 10.466871662435148, - 10.700222546768892, - 10.939381371773377, - 11.176673943003353, - 11.404401041630985, - 11.64138289472096, - 11.881184063747966, - 12.113396873501927, - 12.353177290690343, - 12.5998717836122, - 12.842794898013647, - 13.085699841831085, - 13.338513065865257, - 13.589450205157714, - 13.834399378071131, - 14.089876531234875, - 14.347077091053173, - 14.592908996360181, - 14.841486039645286, - 15.093321437212415, - 15.331556576044584, - 15.574403568768822, - 15.821583107533652, - 16.0611295719606, - 16.297697164385607, - 16.53418646450021, - 16.765386661023303, - 16.990314980255295, - 17.216597429601407, - 17.44552127048095, - 17.66665243205992, - 17.8910406576397, - 18.119733505116766, - 18.336743633297925, - 18.55144023915765, - 18.76852671378836, - 18.98584964248148, - 19.190370507385456, - 19.402717830991467, - 19.620739332169286, - 19.828276315307928, - 20.040357066708093, - 20.254537966505755, - 20.49311640466681, - 20.753235745072647, - 21.013008320752785, - 21.280429705574765, - 21.558215948844328, - 21.836372812850524, - 22.115965984997004, - 22.41933462761023, - 22.711468248149906, - 23.00969163255522, - 23.30703458214062, - 23.58310835796809, - 23.873034749211637, - 24.178178294893403, - 24.47011223597752, - 24.769835527903183, - 25.08583194315802, - 25.386693593331973, - 25.700763811746032, - 26.027037841098014, - 26.340176298684018, - 26.682766453605822, - 27.038233969204494, - 27.380909537241617, - 27.745617367445757, - 28.1070922824339, - 28.448298874907188, - 28.8066269562617, - 29.171678224467673, - 29.518985504304503, - 29.86759547145183, - 30.216972832130267, - 30.54914544592294, - 30.88164712615573, - 31.22100666424289, - 31.55297080947975, - 31.884712721367116, - 32.217118736114884, - 32.545459704568, - 32.878679677904394, - 33.207928653927056, - 33.52813888519988, - 33.84902197186782, - 34.172714721169605, - 34.49377977705521, - 34.81598010816266, - 35.13182488361413, - 35.44826883788044, - 35.77075710724621, - 36.07689771581422, - 36.37378503080216, - 36.6807861390401, - 36.98075973279811, - 37.26767382100874, - 37.56842979834957, - 37.86963955975098, - 38.15969722122062, - 38.45580161464718, - 38.76110016203662, - 39.06199398474091, - 39.36771843696578, - 39.67740872911487, - 39.9855587754359, - 40.29456256903874, - 40.60019229868071, - 40.90327050383104, - 41.21184330531727, - 41.51981952972206, - 41.82999013774019, - 42.14604447812906, - 42.460178188693924, - 42.772951080528365, - 43.09183138662514, - 43.408459982364754, - 43.72615930826093, - 44.053726633883684, - 44.37651136670914, - 44.703720400557195, - 45.04042166885038, - 45.3686570398013, - 45.693127205500424, - 46.02812001940895, - 46.350753614996556, - 46.6729639076944, - 47.00092712608722, - 47.3245376024245, - 47.65438105311737, - 47.98632260625169, - 48.31092154141555, - 48.636701418295544, - 48.96499882148257, - 49.27563619145835, - 49.591945748707886, - 49.91539073525895, - 50.225923925985626, - 50.53254943666014, - 50.84620884637542, - 51.14906282039165, - 51.448422497159065, - 51.752595879656795, - 52.04710583076322, - 52.34230902748567, - 52.63790453084533, - 52.921337805461555, - 53.199494897331725, - 53.47165555686957, - 53.73654889633494, - 53.997737016956535, - 54.25561636060131, - 54.510861381951315, - 54.77029386496579, - 55.06053969883743, - 55.3193383983537, - 55.58082024557244, - 55.85062771619083, - 56.12071725307524, - 56.392055962064916, - 56.66217275660554, - 56.931493530240104, - 57.1966339481428, - 57.44677164563119, - 57.6873530623383, - 57.924220512679625, - 58.15907116976025, - 58.3912630010043, - 58.62377832077256, - 58.851321260818885, - 59.10287487694168, - 59.33504509529673, - 59.57042643500657, - 59.81149397990794, - 60.06278227891432, - 60.322238930259225, - 60.571051984832394, - 60.82080423671204, - 61.08384036148947, - 61.34286503803346, - 61.58794316880902, - 61.8437706439411, - 62.09881775362492, - 62.32089755367982, - 62.53454052056264, - 62.74630175145445, - 62.94457989312166, - 63.130617165692314, - 63.30653276702939, - 63.48291226075136, - 63.64894863152556, - 63.80075249599611, - 63.947766474523085, - 64.08541484176192, - 64.20750007567015, - 64.31397851543635, - 64.40369614470518, - 64.47734175619775, - 64.53155235638658, - 64.56344758980786, - 64.57522459354611, - 64.56784924064979, - 64.54117725777655, - 64.50133789629463, - 64.44727571376464, - 64.3770239006336, - 64.29414330018272, - 64.20319906056727, - 64.09786941692346, - 63.98289957747269, - 63.86021539159947, - 63.72746527155486, - 63.58147624182828, - 63.415167704781815, - 63.23663332833086, - 63.04501831961145, - 62.8398984317355, - 62.62102175495072, - 62.393070935941104, - 62.15185199735371, - 61.89612203648324, - 61.62730159901355, - 61.35261255589393, - 61.06829994514864, - 60.77102648018289, - 60.48047917141674, - 60.18005429956885, - 59.86944303231687, - 59.56562553655119, - 59.25479964282162, - 58.93279964631588, - 58.61608106694816, - 58.294073570021276, - 57.95706660640934, - 57.62876015258999, - 57.30336307418381, - 56.955990486703904, - 56.627564783204384, - 56.30628201828773, - 55.96301696889808, - 55.63436355396282, - 55.319763992937965, - 54.984482804533506, - 54.66441558443428, - 54.352180015388406, - 54.0286580749201, - 53.70719325236333, - 53.3886501726395, - 53.06230401224373, - 52.731668350798024, - 52.412423122362966, - 52.08170047802152, - 51.745636318909945, - 51.41149661568205, - 51.072346262180716, - 50.727779820139986, - 50.38928898735916, - 50.052498885253186, - 49.71281937780201, - 49.37749797819582, - 49.03390404960647, - 48.700251814160616, - 48.35921581537463, - 48.02127885746068, - 47.684205040099805, - 47.34877727967469, - 47.01771160378635, - 46.6802549782342, - 46.34358952010222, - 46.008492299730314, - 45.66983424511466, - 45.33014596992044, - 44.988998076119074, - 44.64970229673532, - 44.30000670789822, - 43.94686821583238, - 43.602196916148266, - 43.24808656120025, - 42.89496174219601, - 42.549242456566404, - 42.195039376330804, - 41.83918424394172, - 41.48919747411654, - 41.12886003408778, - 40.74886684685023, - 40.38811989720975, - 40.02884140177651, - 39.64348857394865, - 39.27526751145392, - 38.91065315121915, - 38.52843839556926, - 38.15225066902699, - 37.78868833241302, - 37.42093369487591, - 37.048781869567144, - 36.688228472261045, - 36.322442865970366, - 35.95616404118417, - 35.58629777277088, - 35.22371972020449, - 34.85993276181598, - 34.49211194094666, - 34.11838919501381, - 33.74769060072603, - 33.372177836474386, - 32.98294533148796, - 32.605988974888945, - 32.23114449570224, - 31.855930457185696, - 31.47490764885328, - 31.107792099615526, - 30.742036242287266, - 30.371554085971116, - 30.0100173229397, - 29.649829556487436, - 29.28690399276509, - 28.92150101741794, - 28.561126082793443, - 28.198323600284166, - 27.83517689781057, - 27.484811670582832, - 27.124325971388696, - 26.766156510232815, - 26.43099554126496, - 26.095146063414553, - 25.766167784679496, - 25.439322157228318, - 25.115069424206542, - 24.794096000709757, - 24.47487619049869, - 24.152300380127528, - 23.83314968040659, - 23.512875548459412, - 23.19206815996017, - 22.868718126091483, - 22.545778659676944, - 22.236157072837628, - 21.92301654821605, - 21.611526983296386, - 21.311079123300285, - 21.008302593247297, - 20.692435674978185, - 20.396246974677336, - 20.103165807568764, - 19.782412327001, - 19.4783316260115, - 19.185830950993875, - 18.871202785834285, - 18.562886050709672, - 18.26154136620148, - 17.94875555199643, - 17.63233703293708, - 17.320291069456587, - 17.00032266578921, - 16.67785560084743, - 16.36205563908135, - 16.042474419225428, - 15.725923824977155, - 15.410000894901648, - 15.094628872283552, - 14.77648574930314, - 14.460395819218052, - 14.142751673486185, - 13.823369410041467, - 13.506447100941761, - 13.184745425880198, - 12.86778818234603, - 12.549026881564068, - 12.228168567008979, - 11.908284167956305, - 11.588478854851386, - 11.266112739400324, - 10.939209275467062, - 10.615200727707855, - 10.296276319492407, - 9.972265014895568, - 9.650100344969468, - 9.338667614876224, - 9.026342017909288, - 8.703826193371327, - 8.401514083771268, - 8.099325816982839, - 7.792379381817953, - 7.494380065916911, - 7.202459416762018, - 6.913678551652247, - 6.623988483081557, - 6.333109610630427, - 6.050653709657182, - 5.766810988370467, - 5.473133881269483, - 5.185415609733411, - 4.905068480871893, - 4.6044260266247985, - 4.312106694023325, - 4.030710209433614, - 3.726784538346991, - 3.419859610385219, - 3.1286423951767772, - 2.819764879529908, - 2.513363454681323, - 2.2128895355849902, - 1.8946201943710554, - 1.6051951040340207, - 1.3158081979557188, - 1.0107166900957267, - 0.7253845666588653, - 0.44549848234501915, - 0.15353634205481423, - -0.1281046415739806, - -0.40572982811506086, - -0.6889670310031285, - -0.9665987965814913, - -1.2404288296019068, - -1.520702291402006, - -1.8017624984197276, - -2.0787265340135628, - -2.355608599093969, - -2.631483375192749, - -2.907848355638494, - -3.1796249548835362, - -3.4412848125260926, - -3.69879347973123, - -3.9459625066219095, - -4.173527906680129, - -4.396660487168673, - -4.604218135217778, - -4.794572865551297, - -4.9704763904342455, - -5.128378907668659, - -5.268002320869248, - -5.388141710743154, - -5.488471018685102, - -5.56785751230851, - -5.62492419998967, - -5.661582132813968, - -5.6759973982339575, - -5.666581855227908, - -5.6344054198887665, - -5.582573105739994, - -5.513781895788568, - -5.426070927740838, - -5.3200222886457045, - -5.199076794136644, - -5.0610631763309755, - -4.8937124820967215, - -4.732086200679933, - -4.560271489259866, - -4.382539473528136, - -4.198374773354525, - -4.007936925954206, - -3.816133258836189, - -3.617903581258127, - -3.4160871601057368, - -3.213608481780186, - -3.0081901879802797, - -2.8020587069395044, - -2.596419055165063, - -2.3928484523809, - -2.190678112623667, - -1.9893057933517218, - -1.7913854641689455, - -1.5936060656188609, - -0.9055332106891132, - -0.7202858792343564, - -0.5381017910878791, - -0.36189036003927605, - -0.19629464373643796, - -0.03529972288378039, - 0.12289807262798322, - 0.2682500300033732, - 0.406924152008886, - 0.5388519785188258, - 0.6729251349545429, - 0.79656391838147, - 0.9065861613852987, - 1.0168516544131518, - 1.1210998984660312, - 1.2170604487497922, - 1.3118797821312187, - 1.4030447200049618, - 1.4847487089507099, - 1.5625214298299035, - 1.6388612267685054, - 1.7088665143980293, - 1.7777265222074548, - 1.844379588015374, - 1.904504983689095, - 1.9617284691656787, - 2.0160884187698387, - 2.0678511700965467, - 2.1159761486962596, - 2.1616371433353097, - 2.2059646616270174, - 2.2490020785144726, - 2.2913435867961907, - 2.3343285040848074, - 2.375243589447204, - 2.415710591879883, - 2.4564812330843515, - 2.497381433608937, - 2.5392208070742384, - 2.5821798466491637, - 2.627702478105555, - 2.673581533360386, - 2.718808036815791, - 2.765642071681866, - 2.813899998343954, - 2.8617301090722487, - 2.910400970166254, - 2.958888707576651, - 3.008884420846659, - 3.060900064688732, - 3.1167167582750577, - 3.1760859876925984, - 3.238122450159414, - 3.3072711932363115, - 3.381902710246488, - 3.4605047088174423, - 3.5470994454358262, - 3.638975419457842, - 3.7344211983582603, - 3.8363684797590283, - 3.9432508962962625, - 4.0557799867542235, - 4.178665348989349, - 4.306950149653362, - 4.440201165874506, - 4.582995041856619, - 4.729542900084111, - 4.878648098764896, - 5.032457236144575, - 5.19284134159112, - 5.351994994915723, - 5.517313565817845, - 5.687524039363754, - 5.854458967695315, - 6.021909599178358, - 6.194905065084231, - 6.370900523239295, - 6.543685470315409, - 6.720218946811099, - 6.899336004380133, - 7.077531798400286, - 7.262264787013468, - 7.462392813182556, - 7.64646670945532, - 7.835299070815758, - 8.024393551725165, - 8.215195676296187, - 8.414057033552687, - 8.616186517126499, - 8.819278416757804, - 9.025451638405203, - 9.228713556298894, - 9.435084481866628, - 9.644681118145497, - 9.854871196128133, - 10.068442891658682, - 10.283523960122878, - 10.497319393428349, - 10.708215498230638, - 10.915984365130619, - 11.123251930592202, - 11.33219643011607, - 11.541963271812863, - 11.744413100437864, - 11.947628061073338, - 12.15730893005468, - 12.363172566586455, - 12.571220587737818, - 12.790676958205008, - 13.012793343422562, - 13.233326001860208, - 13.453757700628822, - 13.67894627842613, - 13.90309718686793, - 14.122800867862784, - 14.344669104077772, - 14.568182815204022, - 14.787521931013131, - 15.003433168402763, - 15.218338458244752, - 15.430876495916666, - 15.639582983358668, - 15.844588520545768, - 16.05174380151191, - 16.259047246035017, - 16.462297162647182, - 16.661347033979755, - 16.860977629761397, - 17.05949013197176, - 17.253111135804968, - 17.44504564465885, - 17.6401583815982, - 17.83519359255791, - 18.029425903284928, - 18.227382487519517, - 18.431599042932586, - 18.63377679978206, - 18.833792647361186, - 19.036284943961576, - 19.244474425587782, - 19.456774302585004, - 19.659814323713807, - 19.877098373594915, - 20.100438703083036, - 20.319917585601303, - 20.543766370264326, - 20.768664805149218, - 20.998345468507342, - 21.235920777755084, - 21.469506739891646, - 21.710129629308224, - 21.955909499200317, - 22.19819034760357, - 22.44649920050249, - 22.707863303552728, - 22.95174793241345, - 23.21081010704054, - 23.47786316387744, - 23.73868761449372, - 24.01880536165217, - 24.296832398886973, - 24.56788949591203, - 24.85556031060897, - 25.142281351469617, - 25.423643007964415, - 25.72464386485637, - 26.01895038167825, - 26.315335770028263, - 26.64082113110321, - 26.96066545597112, - 27.28624599078172, - 27.628947445084588, - 27.953217297777137, - 28.269162393212962, - 28.603487317229146, - 28.933690325584937, - 29.254466570448663, - 29.59050285952364, - 29.92550839868592, - 30.24909657195234, - 30.5770083001913, - 30.905122860465795, - 31.231010423798143, - 31.559262162619206, - 31.88398509689268, - 32.2108119605712, - 32.54232007447706, - 32.872106604835544, - 33.19256010378698, - 33.51571448848831, - 33.84088122133021, - 34.16274371439139, - 34.48012493535317, - 34.79252421156048, - 35.11004664828505, - 35.42708782008047, - 35.726610739928226, - 36.0211962725397, - 36.324234882644504, - 36.61710760027611, - 36.9007061324053, - 37.19828843945955, - 37.49343713484368, - 37.7774137315602, - 38.07035180128131, - 38.37164388866992, - 38.66706211087181, - 38.96897598154521, - 39.27801683983014, - 39.58379605967718, - 39.892441616186375, - 40.20099727596609, - 40.503739711250745, - 40.8108368624679, - 41.12180090546971, - 41.42701005464316, - 41.735725772783354, - 42.04540315179996, - 42.352414388167595, - 42.65640966308489, - 42.96352025542926, - 43.265252950206786, - 43.57210629372062, - 43.87829734685928, - 44.18101684634248, - 44.49111422266982, - 44.80019788610365, - 45.10202019961984, - 45.40680062895141, - 45.71514213481711, - 46.00658506419657, - 46.30552971112497, - 46.604923301718046, - 46.890712312286006, - 47.18432888916051, - 47.4812373152195, - 47.766914703063264, - 48.05462974618402, - 48.34828635492092, - 48.636458523977325, - 48.91389718974907, - 49.20176904214493, - 49.48894937346556, - 49.76999933830532, - 50.05000035979489, - 50.333867718123514, - 50.61099748803371, - 50.88664904079643, - 51.16610820987319, - 51.440624144719024, - 51.71103759327883, - 51.98618737280329, - 52.25737914374822, - 52.5217630297111, - 52.784522883857385, - 53.040372919948936, - 53.287854956033186, - 53.53823351443804, - 53.780852597439655, - 54.02045186356351, - 54.26358486732929, - 54.50591946952668, - 54.75067775552222, - 54.99308269842895, - 55.237332200941026, - 55.48885777538655, - 55.74401608796219, - 56.0034074966469, - 56.26436926298783, - 56.5252578911605, - 56.78774650693654, - 57.052075559431124, - 57.310561620276395, - 57.561755081479596, - 57.81279715033571, - 58.06395005545917, - 58.315590142946945, - 58.559517316828604, - 58.803518975904524, - 59.053411989053515, - 59.30331536726503, - 59.555794626289696, - 59.80293572966091, - 60.06096650364455, - 60.31982084164096, - 60.57144263069977, - 60.824982384716236, - 61.09138043168508, - 61.347393230172294, - 61.59460315790011, - 61.85675367324556, - 62.11327753414165, - 62.345455283874784, - 62.57586327145023, - 62.80557759401787, - 63.009485864983894, - 63.198347631823296, - 63.39957847029329, - 63.591787590451, - 63.76385496827071, - 63.93504345932741, - 64.09366715367625, - 64.2338342111524, - 64.3677806292545, - 64.48918464764402, - 64.59867583680094, - 64.69665705731443, - 64.77725374697798, - 64.83874879562084, - 64.88505916888899, - 64.91489085055541, - 64.93038406380604, - 64.9341319705511, - 64.92233532213571, - 64.89225069458912, - 64.84514281575301, - 64.78244882666036, - 64.70625125679383, - 64.61303344300852, - 64.4996095387883, - 64.3734970535468, - 64.2339227017979, - 64.0691859896756, - 63.88896819814262, - 63.70375365171411, - 63.49316904235379, - 63.27003097567863, - 63.04038520626878, - 62.792939300967944, - 62.52367035463808, - 62.249024343745795, - 61.964051455209635, - 61.66040703004095, - 61.35143480655067, - 61.04253551823063, - 60.72799430745338, - 60.407094720964544, - 60.08204947598009, - 59.75988867394303, - 59.437473814982866, - 59.11102800787768, - 58.78040174762059, - 58.45325357354585, - 58.12015763497961, - 57.780899333531345, - 57.446734731009535, - 57.115655924856334, - 56.76866200668808, - 56.43350146774667, - 56.10827947488392, - 55.76794415355786, - 55.432375413390915, - 55.1116529849876, - 54.776453349765816, - 54.44359453282654, - 54.119817944939314, - 53.78502742488549, - 53.4277132717604, - 53.06139014538398, - 52.68583885032106, - 52.30431773601525, - 51.93287947469784, - 51.55348048905213, - 51.16574006591912, - 50.78389947445136, - 50.40018377617962, - 50.00941020931337, - 49.64340551744632, - 49.29206799133966, - 48.938546084378174, - 48.58867618589109, - 48.23383844633296, - 47.88577328970176, - 47.53023447121266, - 47.173707586527684, - 46.820242424401805, - 46.46781799675155, - 46.103409238991574, - 45.72447732081331, - 45.346780235565554, - 44.97116839295966, - 44.587123004483, - 44.20523034735631, - 43.822082556998055, - 43.441341164791176, - 43.049628719138255, - 42.6594343328787, - 42.28943645633909, - 41.920745700898514, - 41.55799309504139, - 41.1977903715551, - 40.82692552894466, - 40.46146671199581, - 40.10087192633143, - 39.726164387091195, - 39.34589358690573, - 38.98944966303418, - 38.651636567391584, - 38.32425882280544, - 38.01970816131352, - 37.71222590274016, - 37.390523144529, - 37.085873049825175, - 36.78996535301918, - 36.478351726858214, - 36.172612847937394, - 35.873466986720395, - 35.542506328442826, - 35.19681710752306, - 34.84645722701486, - 34.5024150040763, - 34.158944207428334, - 33.81090803333378, - 33.45678865861211, - 33.1121335436967, - 32.769690331014154, - 32.40815465777267, - 32.06706189203102, - 31.73818279646971, - 31.4069414911656, - 31.07141025377262, - 30.740760278913392, - 30.416356646953968, - 30.08528185137061, - 29.759391274916094, - 29.42772033894885, - 29.09610144670529, - 28.75241495438663, - 28.40410558038202, - 28.061581491679252, - 27.711663374722416, - 27.368337363239547, - 27.030615584438536, - 26.687481351701408, - 26.350956695011487, - 26.017128460063248, - 25.680873594593724, - 25.354413419917726, - 25.02105608913142, - 24.683945123823275, - 24.356105780718323, - 24.023412552566047, - 23.683258456495615, - 23.350663617080645, - 23.01876605452908, - 22.679042868844995, - 22.345885916622905, - 22.021623798616123, - 21.68508393173521, - 21.36169283990485, - 21.043670755965216, - 20.718635705571007, - 20.384923576823788, - 20.07480465686862, - 19.762502906204453, - 19.425026897000897, - 19.11439078097833, - 18.795944904723587, - 18.458809071542838, - 18.134303137948027, - 17.813531672569077, - 17.48548662970209, - 17.15539366600941, - 16.833337937069704, - 16.504947576978854, - 16.17856720712977, - 15.858821738650159, - 15.541762267997488, - 15.228637423722681, - 14.917071765386117, - 14.604487895980826, - 14.28627926911162, - 13.974503061860622, - 13.656429371616163, - 13.3404123787466, - 13.023892349615393, - 12.701381914664266, - 12.383701079919026, - 12.064896914940544, - 11.739240492008918, - 11.414799327872279, - 11.091392310492523, - 10.764094984524677, - 10.429069747075674, - 10.099131017199557, - 9.773648377993087, - 9.441144262057035, - 9.110134992705483, - 8.790093031749594, - 8.472448988555438, - 8.142569254349775, - 7.8333889572317865, - 7.527669386290945, - 7.214041748256324, - 6.916003033105072, - 6.619070113737984, - 6.3180704452008225, - 6.018776346591357, - 5.718338982304064, - 5.41570104806967, - 5.1174876762822255, - 4.811089517586735, - 4.501946025743641, - 4.20121277371134, - 3.885178117446997, - 3.578472156205737, - 3.2775196307968795, - 2.967018547400865, - 2.6615713850033176, - 2.362585466607191, - 2.0619598369580623, - 1.7614724045696086, - 1.467291176818494, - 1.1701490216286663, - 0.8837039337661199, - 0.603138431506288, - 0.3177505564621903, - 0.042715205771723413, - -0.22772672857181492, - -0.5037060126876416, - -0.7775078376792488, - -1.0500912699145741, - -1.3228068596113436, - -1.5980246643056533, - -1.8751649877266727, - -2.155724401313098, - -2.4374175534989213, - -2.7204681321512783, - -3.004759790301973, - -3.2825837585752717, - -3.5635196294257505, - -3.844599231918461, - -4.108929472553468, - -4.355539781550006, - -4.602136164130792, - -4.837561129653576, - -5.050913706385881, - -5.255292933767793, - -5.444573000333677, - -5.613724738106135, - -5.764613166766576, - -5.89486343805325, - -6.0012105472892845, - -6.083679178417491, - -6.144279096912507, - -6.181145924893161, - -6.193345038951731, - -6.1810041955283195, - -6.146742981568169, - -6.093689040653491, - -6.020825678996818, - -5.928579732561607, - -5.819909132686005, - -5.693930044611588, - -5.551643259906084, - -5.394657387626238, - -5.223724822466757, - -5.042341800653289, - -4.851204704680763, - -4.650707512509256, - -4.44701709546334, - -4.236353534312547, - -4.020654759030604, - -3.804755671838709, - -3.5849668775342356, - -3.363576250108232, - -3.1454174331024327, - -2.9333303460849955, - -2.705144559208491, - -2.501982563564464, - -2.305897280378726, - -2.1135333152809634, - -1.9252315355328815, - -1.7419106292937618, - -1.5619352282249188, - -1.386481713313186, - -1.2173168293417802, - -1.0522609216836865, - -0.8961551600101378, - -0.7489704980416187, - -0.6036996526193943, - -0.4672034113201273, - -0.33643150036056485, - -0.21182347923938555, - -0.08482572960006235, - 0.03296397525118956, - 0.13803464980561533, - 0.24429856547015677, - 0.3454335683637869, - 0.43954582150569926, - 0.5334954886752733, - 0.6244473203261978, - 0.7063456210966875, - 0.7851896171914984, - 0.8612002936545564, - 0.9318731319943926, - 1.0018181314141354, - 1.0671257523852353, - 1.1258879628822924, - 1.1809616679514416, - 1.2334821353629821, - 1.2812093367658166, - 1.325666385260795, - 1.3686041659870374, - 1.4099076662315462, - 1.4499290517415064, - 1.4907965292561967, - 1.5305527105384111, - 1.5695873487805367, - 1.608453778429702, - 1.6473324628176782, - 1.687414433484031, - 1.729308702492355, - 1.773169058670581, - 1.816219857288633, - 1.859536499174332, - 1.9055744125094838, - 1.9524449696609882, - 2.0002754204736526, - 2.050465902746975, - 2.1034009360950887, - 2.158835107190497, - 2.2189088148105123, - 2.2836575508606796, - 2.3514594579191392, - 2.42645668414064, - 2.5154658448068625, - 2.600699162149884, - 2.6926498157705754, - 2.7892670112848563, - 2.889296569616385, - 2.9946889905899896, - 3.10416519459054, - 3.221796389748498, - 3.346078809395236, - 3.472685600013573, - 3.607533929214433, - 3.7509264135645783, - 3.8963735007702684, - 4.04416873424519, - 4.201493208581886, - 4.358072752952976, - 4.5163945008173805, - 4.682692641802298, - 4.848551319856644, - 5.011137882671261, - 5.180033770078293, - 5.356054272324572, - 5.527107496638038, - 5.706445254492088, - 5.892280888362062, - 6.078415003256876, - 6.267129554359015, - 6.460220463822334, - 6.650792478128393, - 6.844007918761906, - 7.038716912625716, - 7.234618093278297, - 7.432177543885677, - 7.632253280451951, - 7.832501437779651, - 8.036113494446496, - 8.238500622933111, - 8.441959857142116, - 8.649697421859123, - 8.857914540485808, - 9.06784467671421, - 9.279509886787089, - 9.494501098185962, - 9.710581470196464, - 9.925165163460168, - 10.137982635913584, - 10.353671208173067, - 10.567534015319746, - 10.773636502374774, - 10.985118077350945, - 11.200748201140998, - 11.430137892805606, - 11.643173038108484, - 11.8643859833317, - 12.083578785284102, - 12.300526889528768, - 12.524141572316488, - 12.749414702449705, - 12.969373668561387, - 13.191827963013733, - 13.418715946653448, - 13.640801245474163, - 13.86077314267707, - 14.080304952921253, - 14.299583825172823, - 14.516181255782323, - 14.73020382396844, - 14.946936588198518, - 15.163763204325228, - 15.374499965516316, - 15.583758124223097, - 15.817707630037336, - 16.025291150787165, - 16.229280108240037, - 16.436727486302235, - 16.645484611920427, - 16.854201739038114, - 17.0659749294851, - 17.284841724042852, - 17.502460175411226, - 17.71786174047734, - 17.933773055075328, - 18.158336403565595, - 18.38256046813477, - 18.601257332975912, - 18.83665401579923, - 19.0734634686356, - 19.30969532152967, - 19.549601001562625, - 19.791946072332866, - 20.03840718469108, - 20.30439411736261, - 20.569584186003024, - 20.844517190035486, - 21.1204217978466, - 21.394687422977103, - 21.684774478492354, - 21.958034750016054, - 22.244051984744427, - 22.53713143874562, - 22.824205022873294, - 23.10776614129646, - 23.385240858599833, - 23.65797518720824, - 23.945970514931957, - 24.230270875446703, - 24.512673946933806, - 24.813113842738602, - 25.10233557345587, - 25.397884107445652, - 25.71855475117096, - 26.028041548957507, - 26.351343668615986, - 26.68575590513501, - 26.996142230999617, - 27.30395344319394, - 27.629776045724558, - 27.950893244854537, - 28.2611035397097, - 28.5859201923331, - 28.90814021056158, - 29.229602936099422, - 29.553092375862388, - 29.87486064627909, - 30.192607767403327, - 30.51042962659957, - 30.823502634365923, - 31.13375300688445, - 31.45087371269537, - 31.764004553176324, - 32.06766447014032, - 32.39341599006021, - 32.718837290770544, - 33.03510027911376, - 33.3463992613523, - 33.64756612922129, - 33.94617542466793, - 34.255050344476714, - 34.55131838602722, - 34.841364384051616, - 35.13445191695125, - 35.41799046189206, - 35.69620731174678, - 35.973741706683825, - 36.261288494959075, - 36.54478247218361, - 36.82695666689895, - 37.116922815166525, - 37.41256072421824, - 37.707831468103656, - 38.00872071365846, - 38.31329239861413, - 38.6179417348102, - 38.92529250682758, - 39.23395592716675, - 39.53843395393223, - 39.84719625293089, - 40.15980982992883, - 40.47009087675628, - 40.7839357535985, - 41.10095171075927, - 41.41825747162264, - 41.73496441055351, - 42.054541753462495, - 42.40265093370169, - 42.722656445858824, - 43.03857658584681, - 43.34864572402307, - 43.66011327126799, - 43.962136639181885, - 44.25243848245562, - 44.544883366892684, - 44.83171962686003, - 45.09653897255874, - 45.36768906546432, - 45.637221438401646, - 45.88882581382236, - 46.14897988405553, - 46.41622086873738, - 46.67607099653956, - 46.93944312785133, - 47.2048915937463, - 47.47262414790793, - 47.746249220992354, - 48.01267618730963, - 48.28041246564395, - 48.56134167021955, - 48.83708002400132, - 49.10976134983403, - 49.38936506870274, - 49.66653409358757, - 49.9388924462077, - 50.218316015606185, - 50.4995795949478, - 50.77236879297137, - 51.050803173116705, - 51.33342612259046, - 51.607561540700296, - 51.87974732198954, - 52.151611620542646, - 52.41284562631809, - 52.67546485613451, - 52.936004070807655, - 53.193201383713294, - 53.45457919581241, - 53.71845973642336, - 53.98525718826073, - 54.25023885372703, - 54.52055892070706, - 54.7986588253103, - 55.08004421599197, - 55.362986041574054, - 55.64904672366078, - 55.934471099982424, - 56.22135277492174, - 56.503781796397305, - 56.77773502457396, - 57.05089683628028, - 57.32428101234249, - 57.59573833184962, - 57.85666623944034, - 58.12154010965457, - 58.391645423184535, - 58.657362866016065, - 58.919849929034385, - 59.187307549871846, - 59.46034189639111, - 59.72105673151717, - 59.97064623049739, - 60.229233568362766, - 60.48017833241788, - 60.70828653434588, - 60.94601499059789, - 61.18950379361661, - 61.413769014146204, - 61.62721584709056, - 61.83880244151634, - 62.04472677191079, - 62.23085377371617, - 62.40331467063941, - 62.58307273001009, - 62.7575633834552, - 62.91572538400384, - 63.07009673391234, - 63.21861885140278, - 63.3523820611257, - 63.47982287601544, - 63.59737939749105, - 63.702644157699, - 63.797777698533366, - 63.88024453387794, - 63.944304152278626, - 63.99392725900502, - 64.03032182735477, - 64.05176875652805, - 64.06237210631396, - 64.06015352266682, - 64.04193750864499, - 64.00772164837375, - 63.96002942127532, - 63.898873163966506, - 63.82465309936775, - 63.733687949043016, - 63.62518887593727, - 63.509547544666844, - 63.375653174297796, - 63.21973625822764, - 63.05705469971158, - 62.88178110943676, - 62.68109407174189, - 62.475897362132514, - 62.258471396252645, - 62.0225423698425, - 61.771100803914905, - 61.51068596185073, - 61.23617819214634, - 60.94791909314268, - 60.65523709365595, - 60.355634634359774, - 60.05106288924525, - 59.73772692929278, - 59.414918127434696, - 59.088021249379125, - 58.76118062644071, - 58.42625361610826, - 58.08605063037285, - 57.751000659041715, - 57.40694454161398, - 57.05239679798535, - 56.70208412110874, - 56.35877036115654, - 56.0121654229517, - 55.66903072582529, - 55.34031550701341, - 55.004413038414384, - 54.663170850421764, - 54.34097856517889, - 54.011614757336964, - 53.67759462784281, - 53.35820630982758, - 53.03000900966272, - 52.691812770745585, - 52.362577935168794, - 52.02487748232644, - 51.68148221838634, - 51.343946761468054, - 51.00731364943348, - 50.658509395291404, - 50.3149963058302, - 49.97429120791977, - 49.62406996975568, - 49.28316674858516, - 48.94741734527262, - 48.60937152840948, - 48.2738599212006, - 47.93615200607705, - 47.597865261738406, - 47.265035203957154, - 46.92330600016169, - 46.58334572730593, - 46.24421300146834, - 45.90481473770937, - 45.564814098548695, - 45.222948283602726, - 44.88293613593048, - 44.54081318129575, - 44.1992418322938, - 43.85576555504636, - 43.51257238337112, - 43.13742224619705, - 42.79627412979432, - 42.47542429946151, - 42.155481308622136, - 41.83331146430156, - 41.51786731340956, - 41.196961636232764, - 40.86971653351226, - 40.551942732000285, - 40.23136807544322, - 39.89682062544872, - 39.55564858254047, - 39.219208384251445, - 38.86794395491559, - 38.500192869860705, - 38.15303873942999, - 37.80347293953438, - 37.439323163349925, - 37.08651469954306, - 36.746095077791125, - 36.40122845765831, - 36.05496445755603, - 35.7360019126959, - 35.413045291149125, - 35.0952853451161, - 34.77529491296396, - 34.45407105823076, - 34.142722876688296, - 33.82955356132992, - 33.51061655691465, - 33.19173457697036, - 32.88096345347836, - 32.54827392697, - 32.20498156300351, - 31.877355956071632, - 31.546283377741254, - 31.216964779996715, - 30.887743410182694, - 30.55784703657244, - 30.23722634217426, - 29.910279100908483, - 29.58723844771856, - 29.25845221091206, - 28.92811986655665, - 28.598642621370384, - 28.261944494174124, - 27.92880745710866, - 27.5940510878878, - 27.253396735536025, - 26.92044177453328, - 26.583884060950933, - 26.235062442156472, - 25.89736598135097, - 25.55855684518251, - 25.214662121806352, - 24.878568754466276, - 24.53942263294736, - 24.206942890801013, - 23.871915926423387, - 23.534805604967126, - 23.201299966915197, - 22.86268519216118, - 22.526700575076095, - 22.19926147072557, - 21.865783484718555, - 21.535510160770436, - 21.220041175085377, - 20.896734430871327, - 20.576951269525935, - 20.27149008635767, - 19.95001726982173, - 19.626571553667095, - 19.32199223551015, - 18.998102712291804, - 18.665971402492307, - 18.356704910527252, - 18.03656786081625, - 17.707133069995464, - 17.38983255981904, - 17.07158393796357, - 16.738792722458758, - 16.416040303002166, - 16.0944023144123, - 15.729914921947158, - 15.407543335222126, - 15.090145385069743, - 14.768604332931492, - 14.448150227220925, - 14.131861963159732, - 13.806758147170486, - 13.486913201573813, - 13.162810485908063, - 12.83269625452117, - 12.500141654542965, - 12.167289543245012, - 11.834431447760407, - 11.496983854387905, - 11.15779818431299, - 10.82129093851567, - 10.483207713624981, - 10.140754572101255, - 9.798951610127345, - 9.462586139396949, - 9.121803117335823, - 8.7865083666709, - 8.453853150389874, - 8.120510152478584, - 7.789907493059814, - 7.464405394020024, - 7.139228377455467, - 6.808466691090132, - 6.488017501892993, - 6.1701321648956045, - 5.855051707521304, - 5.542533110306519, - 5.231328451415327, - 4.9288739455715165, - 4.625884119175401, - 4.322361873902274, - 4.020552023145748, - 3.728283765647613, - 3.4334918939376013, - 3.1511300130188244, - 2.883878458666854, - 2.6097050245238997, - 2.326947643444119, - 2.053568866195254, - 1.7856872030207225, - 1.5022966690135036, - 1.2264350621945965, - 0.9590449531241733, - 0.6745057266113504, - 0.38829202874258334, - 0.10795474061330454, - -0.18155047416974424, - -0.45739207773139845, - -0.7282433435874759, - -1.0077589999534862, - -1.2842548289649247, - -1.5578548031766535, - -1.8343055538706883, - -2.1030963701494088, - -2.3666402507641, - -2.632814120824226, - -2.896756056793806, - -3.1680736586950413, - -3.443784790763174, - -3.716246693331426, - -3.98903129973996, - -4.264097397811469, - -4.534033968659492, - -4.795089790007558, - -5.051376274255919, - -5.303895251400505, - -5.537556563005276, - -5.754773602886346, - -5.961115804552593, - -6.145027749943365, - -6.3120905789231845, - -6.460477047508187, - -6.583998216061229, - -6.689171298728174, - -6.770647650232525, - -6.828816544846511, - -6.86778534563269, - -6.8861866592681835, - -6.882417746013902, - -6.8576845715567085, - -6.814432817882744, - -6.75543987226458, - -6.678612733234952, - -6.583381516191917, - -6.473655005318456, - -6.348797261087411, - -6.2084892099714555, - -6.0557130246369635, - -5.890417298559696, - -5.715535869755915, - -5.532418892134846, - -5.340326721043689, - -5.143240411797461, - -4.939733838251594, - -4.726426010942679, - -4.50992914779845, - -4.292618282379692, - -4.072099645064109, - -3.8502220065756707, - -3.6316662974271052, - -3.416556018566003, - -3.2009806902244153, - -2.991767938284576, - -2.7853588248105403, - -2.5769233373267415, - -2.3756204917167927, - -2.1772858789223757, - -1.9844038384257254, - -1.7983641050915198, - -1.6187250602067969, - -1.4484440080770205, - -1.29011517248927, - -1.134602049819094, - -0.9904344058338127, - -0.857363447720482, - -0.7318187582439283, - -0.6064976505864388, - -0.48891576061274666, - -0.38715534828389414, - -0.28646427326372836, - -0.1909542037827831, - -0.10368299823231786, - -0.018553371252633608, - 0.06463429017684078, - 0.1390380194409851, - 0.20934035449305566, - 0.2777317514903072, - 0.3401867057762835, - 0.4012298409357635, - 0.4605596181628006, - 0.5143245497573187, - 0.5659180276806073, - 0.6152387453007909, - 0.6611055791572242, - 0.7037442757468706, - 0.7455801536710408, - 0.786713000517608, - 0.827177839751327, - 0.8687379450620145, - 0.9092409628232775, - 0.949216809461107, - 0.9891701292255028, - 1.0293815414411287, - 1.0705505066574867, - 1.1127814314610136, - 1.1570346192254346, - 1.2022044631299016, - 1.2470801233833706, - 1.292623051597733, - 1.340348799381267, - 1.387982809906152, - 1.4365695678226016, - 1.4865182910651291, - 1.5382550363541274, - 1.5918681396933239, - 1.6497744895756554, - 1.7114060323854448, - 1.7752610977110548, - 1.845267095203342, - 1.920949269530587, - 1.9993213411102517, - 2.083360934567576, - 2.171719803486823, - 2.262854406091134, - 2.3591318486611077, - 2.4597473028065107, - 2.565087966806386, - 2.6801691172377424, - 2.7990119371914925, - 2.922477408045615, - 3.055248355948018, - 3.1928837054998023, - 3.331659540040816, - 3.477005691493211, - 3.628130493964792, - 3.7791794101816674, - 3.938052200885702, - 4.1029681181648545, - 4.265166159707468, - 4.429389935933034, - 4.600991294680711, - 4.773744846492555, - 4.946782151343482, - 5.131815072976966, - 5.320909050205132, - 5.510837901260894, - 5.708581679614273, - 5.9045603981233405, - 6.103769293302831, - 6.308107878661441, - 6.513861516247532, - 6.721052618320775, - 6.933156108092944, - 7.146037729817484, - 7.359723997181099, - 7.571971367930326, - 7.783876837642502, - 8.000297944154742, - 8.217121046863822, - 8.4328366714951, - 8.651733360271738, - 8.874584811357723, - 9.098109026339534, - 9.316791388353957, - 9.532107437735919, - 9.74977462950637, - 9.96545948088208, - 10.172108612711238, - 10.383703116335342, - 10.598463408079777, - 10.807137295600814, - 11.01834403255542, - 11.237105672108077, - 11.45938910265045, - 11.694453233417244, - 11.935146118440368, - 12.176634413009975, - 12.414186156925892, - 12.654512182987249, - 12.898073798084962, - 13.138586370133297, - 13.379244009751835, - 13.621404584695183, - 13.859684507409824, - 14.087126069314799, - 14.312808041347102, - 14.540350062327564, - 14.771487483868926, - 14.996304343333364, - 15.218878398441973, - 15.444254146440244, - 15.66426412960093, - 15.879454639517009, - 16.092588744321706, - 16.29663812090623, - 16.50016121673227, - 16.707028597458546, - 16.92048582846289, - 17.13459210200239, - 17.34647026114372, - 17.55853301916839, - 17.778105018460604, - 18.028276016859294, - 18.246186767261264, - 18.480483505807722, - 18.726487737277626, - 18.96924048155895, - 19.212372881909864, - 19.465111884808394, - 19.71994378629688, - 19.98105056027148, - 20.2390508085983, - 20.504147576103353, - 20.781186065152237, - 21.060760345808834, - 21.38406990350752, - 21.67371646670524, - 21.96909510997013, - 22.302994353914077, - 22.613678027648195, - 22.932973776850208, - 23.254471341321885, - 23.58085762918641, - 23.904233486232176, - 24.22900502407487, - 24.566036645480807, - 24.89448025962728, - 25.24375419601947, - 25.6063024328597, - 25.96076856734515, - 26.331696345587428, - 26.696650391537958, - 27.04078515510014, - 27.39510893461458, - 27.745195463582213, - 28.082773135929116, - 28.43313705967818, - 28.78236167525347, - 29.115106018627642, - 29.450376123914733, - 29.79000032108117, - 30.116754031823966, - 30.442039031638664, - 30.772894481308473, - 31.099415796827778, - 31.42900661434075, - 31.748819040548845, - 32.07116720017948, - 32.39702309037348, - 32.72376709364862, - 33.04436735521042, - 33.35863885731298, - 33.68016402220356, - 33.990388710534916, - 34.28875239772071, - 34.58601787175292, - 34.88008462645111, - 35.169653165845155, - 35.46034703240285, - 35.75372787289096, - 36.04204450288758, - 36.33252700812174, - 36.627405500986455, - 36.92614551777965, - 37.225004367777984, - 37.53009329890057, - 37.83865505582688, - 38.14487269270122, - 38.45424291207142, - 38.7626707813245, - 39.06611515039217, - 39.372528971759216, - 39.682028446888914, - 39.986941682001394, - 40.2943528099418, - 40.60500112353574, - 40.9111971494637, - 41.21643613954518, - 41.52183461422509, - 41.82336247585669, - 42.12594957164481, - 42.431568078034495, - 42.732452693405065, - 43.03610774299223, - 43.34058176162709, - 43.63944667135497, - 43.93397494702619, - 44.23483443695702, - 44.526262421000524, - 44.81135461227428, - 45.110038059412005, - 45.39688489018558, - 45.6798581782165, - 45.975107573356034, - 46.2636051081498, - 46.54532332699521, - 46.83706628638965, - 47.131593701259405, - 47.41773361933465, - 47.7032721229727, - 48.00243938622417, - 48.29648060254163, - 48.58440807891567, - 48.88103139978401, - 49.174589368443804, - 49.457142751249826, - 49.7459033573279, - 50.03736053441394, - 50.317935962213674, - 50.60229173889855, - 50.8913117585073, - 51.16937300756991, - 51.44229372642988, - 51.71542210894189, - 51.979756929036164, - 52.24440458458036, - 52.49971992022472, - 52.75706688514533, - 53.015035777834115, - 53.27214720638787, - 53.53475543268456, - 53.79381461708486, - 54.05630492363875, - 54.326118265064665, - 54.60011560409699, - 54.872355961295355, - 55.148151379951244, - 55.424350400700845, - 55.69750527055456, - 55.97335606190813, - 56.24031711380249, - 56.498488847217565, - 56.78287865877448, - 57.04451314855204, - 57.29250903361896, - 57.533400724152635, - 57.78434859485366, - 58.032422836994975, - 58.27752003751181, - 58.51726800072292, - 58.76525461844545, - 59.011705439279275, - 59.250407998490516, - 59.48491623294628, - 59.72897912446549, - 59.972630493365244, - 60.202696581880694, - 60.44000228169704, - 60.685867582313556, - 60.91811852354203, - 61.13633107503039, - 61.35425769867261, - 61.56806531052361, - 61.759467585993, - 61.93565015021401, - 62.11793197847979, - 62.29301749252574, - 62.451852740240966, - 62.607906185266025, - 62.75875784698378, - 62.89694333011973, - 63.02889958224118, - 63.15058677272968, - 63.26062184058398, - 63.36012094084811, - 63.44651795492295, - 63.512435015827144, - 63.56175265996502, - 63.59612559748676, - 63.6139636745057, - 63.61920877753554, - 63.60918692054274, - 63.58169243764771, - 63.53681808773292, - 63.476313820296994, - 63.40188017895111, - 63.31448327956754, - 63.208480320222144, - 63.08531006735948, - 62.955774402603716, - 62.806198246255455, - 62.63558241796377, - 62.46324563778636, - 62.271752179674195, - 62.061288532058775, - 61.8492120682386, - 61.624942643909264, - 61.37761140408682, - 61.12413294527372, - 60.8666282038319, - 60.59385559353855, - 60.311984368264206, - 60.02862753649854, - 59.741672577266954, - 59.45478316534175, - 59.16092316074118, - 58.859693043350205, - 58.56287019097253, - 58.26482147374656, - 57.95522017665791, - 57.650224200081425, - 57.34455620366391, - 57.027352770072554, - 56.7090451438743, - 56.39741000767495, - 56.08112548351126, - 55.749804992901055, - 55.43610825331594, - 55.125283269120104, - 54.79827422318538, - 54.4802907353971, - 54.17260545704457, - 53.84856460657545, - 53.53055109599369, - 53.21869712094296, - 52.893553583416875, - 52.569814609773815, - 52.25010259967469, - 51.92023912884787, - 51.58519350867348, - 51.2578816763553, - 50.92415847002732, - 50.581400355844856, - 50.2429351689552, - 49.90132558365967, - 49.55239643476251, - 49.20796724575674, - 48.86529888300375, - 48.519804532655584, - 48.176728742364745, - 47.82713059127643, - 47.485059053942166, - 47.13596090792385, - 46.78452322104806, - 46.435140779581126, - 46.08719025439868, - 45.743216475898976, - 45.39081995533591, - 45.04121833354553, - 44.694500312451474, - 44.34189687025481, - 43.98875569270595, - 43.63696621092538, - 43.28904975206391, - 42.93210859319833, - 42.57719472032346, - 42.22509506788287, - 41.86773079782118, - 41.517387733562614, - 41.16389637183546, - 40.80148189677796, - 40.44792571317824, - 40.09447148864406, - 39.72075955718182, - 39.353361693500396, - 39.00343699756572, - 38.62693972049357, - 38.24908491098979, - 37.891951044162376, - 37.52068890096244, - 37.13811628220774, - 36.778832146781994, - 36.420901176268664, - 36.04092968922288, - 35.6788090050402, - 35.31765065984594, - 34.94985814412416, - 34.58063848062147, - 34.21981027035386, - 33.85920299185756, - 33.49507600577225, - 33.12545685001016, - 32.76296258944008, - 32.4106400529251, - 32.0436692088269, - 31.684299499163878, - 31.331659780563903, - 30.978727922111222, - 30.617596108427197, - 30.267483899637472, - 29.920594538435076, - 29.56670028832235, - 29.215389264114734, - 28.855647360182086, - 28.492188927135437, - 28.12437997485845, - 27.760720804476456, - 27.394600970703802, - 27.027424989947484, - 26.670031555011715, - 26.305739869999925, - 25.94297801615253, - 25.58850395515252, - 25.26607519299904, - 24.964618799043013, - 24.66328955106067, - 24.364075989673783, - 24.067192810022544, - 23.772658422171926, - 23.475670593136233, - 23.17585032961566, - 22.88372773926903, - 22.59221182072908, - 22.272041181378697, - 21.954288912381646, - 21.63958880821498, - 21.317313051285886, - 21.007785445761705, - 20.702385345197655, - 20.379239878643816, - 20.07181985899018, - 19.775592479197925, - 19.453773846032266, - 19.161181854327836, - 18.896776633797465, - 18.61113212252427, - 18.330368735674178, - 18.062388169820455, - 17.785330659556053, - 17.50237019474772, - 17.229485267472764, - 16.955229994979153, - 16.67794388292299, - 16.397473415861125, - 16.11770674218455, - 15.836274600531612, - 15.55455783900755, - 15.276293479439436, - 14.99232603740878, - 14.711762085015975, - 14.427112464142356, - 14.143762146137949, - 13.86540619453985, - 13.54640470783924, - 13.218474134346373, - 12.888380401905051, - 12.55339307780027, - 12.220700617514062, - 11.890403734415067, - 11.558441079845426, - 11.219822790932099, - 10.876110811319919, - 10.542965475924149, - 10.231556891235483, - 9.925105122111749, - 9.621698622249122, - 9.327206339329758, - 9.026184834278407, - 8.722788765696748, - 8.434323294820636, - 8.14264940109942, - 7.85014377391896, - 7.56348646785636, - 7.26531865586253, - 6.965573743396781, - 6.7364189552556635, - 6.436357495989647, - 6.132640635374989, - 5.842124573901207, - 5.541700699838323, - 5.232434186396392, - 4.9361583962613125, - 4.628812172934618, - 4.330646270748619, - 4.049697558417797, - 3.7601718815017264, - 3.4637925797563422, - 3.175074741436031, - 2.886257553207683, - 2.5887426562212403, - 2.299066787187788, - 2.0035672417404045, - 1.7111503304233877, - 1.4303365975998472, - 1.1406978751850647, - 0.8562919541469354, - 0.5817256903956658, - 0.30849749626210543, - 0.035742596280797845, - -0.2361472716204736, - -0.501812448884666, - -0.7684478878070887, - -1.0346126138753036, - -1.3013148706669555, - -1.56933918472811, - -1.835013785014885, - -2.106475866160406, - -2.37797946708163, - -2.642838788443494, - -2.9107729213645386, - -3.180816207389365, - -3.438567332171064, - -3.680366455465112, - -3.9303736482247142, - -4.180064680475931, - -4.409136441251674, - -4.624129182196215, - -4.830739875012404, - -5.015453027440241, - -5.184961146387359, - -5.338237010945065, - -5.470848876488653, - -5.586274615163125, - -5.6895046437444385, - -5.761137836515069, - -5.816179616407459, - -5.853069331812829, - -5.869807017353507, - -5.866915426439278, - -5.845749744437026, - -5.80821207783152, - -5.754127551244888, - -5.683173784825192, - -5.510167634079095, - -5.408909445425552, - -5.292340821777165, - -5.162216398550747, - -5.021847685901615, - -4.870151776422177, - -4.711641616236854, - -4.547608675196245, - -4.373845339341901, - -4.196082566789811, - -4.014873357699236, - -3.8265568191341397, - -3.638090298356028, - -3.4490127774672006, - -3.2564712067299926, - -3.06502833648855, - -2.8755967041412127, - -2.6890411057661283, - -2.5056247231174287, - -2.3233842588209637, - -2.1462542412655408, - -1.9736918837031894, - -1.803009813616574, - -1.6355752910803116, - -1.4732049627363617, - -1.314577095065891, - -1.1615305302164751, - -1.0151283115855734, - -0.8739680112872652, - -0.7433523130433113, - -0.6180819929762711, - -0.49539272370385756, - -0.38261310656961955, - -0.27432990210811736, - -0.17256456613616444, - -0.0698907934648858, - 0.025478337233864945, - 0.10989054325316672, - 0.19449855120799486, - 0.27423439875930544, - 0.3481185038823451, - 0.4206747079867086, - 0.49075149973324783, - 0.5550549612014197, - 0.6139736519331291, - 0.6703282447993555, - 0.7216402537087765, - 0.7699003045023958, - 0.815827484837417, - 0.8564383951876848, - 0.8930150913731605, - 0.9272432818661582, - 0.9576201906054729, - 0.9870251551619573, - 1.0156126500363718, - 1.0447276861828458, - 1.075209174360083, - 1.1063146996624507, - 1.1370235576398728, - 1.1656018972030031, - 1.1935135264976722, - 1.2203562748998997, - 1.246738046811861, - 1.2736495406900918, - 1.3014027357995102, - 1.358087701911475, - 1.3880244384467904, - 1.419513582859927, - 1.4520385777138551, - 1.4873453402515704, - 1.5247633158349356, - 1.562106361039703, - 1.603338540357024, - 1.647070752171706, - 1.6947591215192284, - 1.7468546225711385, - 1.8033383247060628, - 1.866125860687536, - 1.9334541780063867, - 2.007925034773766, - 2.091817630096701, - 2.1822125278852806, - 2.2836110754512413, - 2.3938072956317837, - 2.510889897549979, - 2.6375668722268593, - 2.7742051203855462, - 2.921406637385945, - 3.0803495810335297, - 3.250477206672981, - 3.4292496246264745, - 3.623319154106817, - 3.83003409477385, - 4.046213141283251, - 4.278602715992718, - 4.523746725741298, - 4.7762099305664325, - 5.032608170070021, - 5.333979472218956, - 5.616808252059614, - 5.902257349340332, - 6.2029375814380305, - 6.513747982814721, - 6.822335880089604, - 7.140833540054166, - 7.468767047961354, - 7.798398607387442, - 8.13203567731275, - 8.474694577031805, - 8.821338472931537, - 9.172007587376124, - 9.528492588356098, - 9.891306398575036, - 10.255789691225026, - 10.625329708347609, - 10.996952463027247, - 11.370876801480476, - 11.748790541600247, - 12.133270827594714, - 12.516976201987678, - 12.905508491832617, - 13.292099907931657, - 13.685612537839273, - 14.069238670694848, - 14.452370930332016, - 14.844482194210325, - 15.232004869334297, - 15.61076352732441, - 15.968329346719006, - 16.355697599847378, - 16.73779927785946, - 17.120548425419734, - 17.500561245132975, - 17.88099957327373, - 18.24488306422906, - 18.60834747070571, - 18.97773249088594, - 19.33774552160794, - 19.695810267743, - 20.051719174013048, - 20.402652181864873, - 20.748812670433367, - 21.070143922532612, - 21.389038137456005, - 21.69329242274018, - 21.969758916698183, - 22.249711727567828, - 22.508849984132087, - 22.752312955673336, - 22.99269459367493, - 23.211214675033723, - 23.4053173992618, - 23.602523156661245, - 23.77980927032106, - 23.933299088651065, - 24.08567418996952, - 24.220316114452203, - 24.33496367289798, - 24.4456645581303, - 24.539797298984702, - 24.62210589232148, - 24.690297605278072, - 24.74375990397271, - 24.790631714533415, - 24.831336910894436, - 24.86577514279673, - 24.898253253186166, - 24.930656370985364, - 24.963648700003624, - 24.995714731870738, - 25.005661187952445, - 25.01410190907516, - 25.02158438394257, - 25.029132689257356, - 25.035729046708546, - 25.041477585003094, - 25.0470777358424, - 25.052245408553183, - 25.056732527740117, - 25.060431762227783, - 25.094678339374095, - 25.132813337741332, - 25.17152405113053, - 25.210957592363897, - 25.25106678397374, - 25.28398351670111, - 25.325460961044023, - 25.36753035197118, - 25.41078936625082, - 25.45505144985349, - 25.465871791115084, - 25.472901983372125, - 25.480177327515246, - 25.487408108124246, - 25.494626655925757, - 25.502031489439943, - 25.50936516406744, - 25.516762682825803, - 25.524243141759463, - 25.53175572893784, - 25.55720569168713, - 25.584709697353798, - 25.612343385639903, - 25.63993883029349, - 25.66756661466328, - 25.69523046840099, - 25.72288781255104, - 25.75059128363196, - 25.77831851905882, - 25.806152510085287, - 25.815989333208538, - 25.824030105553163, - 25.83215595124888, - 25.840177058754218, - 25.84810762637963, - 25.856227044856343, - 25.864377482842592, - 25.872448534934318, - 25.880711399748133, - 25.888912607922236, - 25.934648372595436, - 25.985273705841266, - 26.03588121201844, - 26.086293021992187, - 26.13639857803408, - 26.186447094074175, - 26.23663204373448, - 26.286584584062055, - 26.33630277959924, - 26.386557467787203, - 26.397176568353146, - 26.403262376314263, - 26.409197421036534, - 26.414859713730827, - 26.420515684708143, - 26.4261463436701, - 26.431842552375098, - 26.438154411630492, - 26.443953536438645, - 26.449634727571773, - 26.451168133121342, - 26.452618420038505, - 26.453840337168376, - 26.45507357710075, - 26.45654756357641, - 26.45796410577846, - 26.459256326940025, - 26.46060844477516 + 45.30065635922624, + 45.30124205437229, + 45.30193400755794, + 45.30265046529222, + 45.303148779253284, + 45.30355241309474, + 45.30436763201242, + 45.30509261653337, + 45.30601404203569, + 45.306807104326325, + 45.30755378323268, + 45.3084595882965, + 45.30939829386062, + 45.310166602457215, + 45.31092652284556, + 45.31184263146779, + 45.31269093838768, + 45.3135576272191, + 45.31414556023766, + 45.31474025871411, + 45.315360652914144, + 45.31605557841787, + 45.31664194012994, + 45.31730697535071, + 45.317890613009425, + 45.31851538132313, + 45.319104667384806, + 45.319609469309746, + 45.32007727141195, + 45.320588366136754, + 45.32098028619176, + 45.32137490542775, + 45.3218027568607, + 45.322205865337594, + 45.322700240070716, + 45.323155095223285, + 45.32354950746685, + 45.32388409129931, + 45.32428643617517, + 45.324720620555965, + 45.325017845529025, + 45.32541910711946, + 45.32594672200731, + 45.32622930094886, + 45.32648902428704, + 45.32678770395347, + 45.3271690999394, + 45.327448012220245, + 45.32774646010955, + 45.32811341332325, + 45.32845006239287, + 45.328854892378736, + 45.32925256389109, + 45.32956418507035, + 45.3298872080439, + 45.330206948208186, + 45.33058368137483, + 45.330898532790556, + 45.33111427854165, + 45.33145221325836, + 45.331679937477944, + 45.331990641078995, + 45.33232540056891, + 45.33257673594378, + 45.33284641602727, + 45.33315718987583, + 45.33344664049978, + 45.3341012148372, + 45.33498707332209, + 45.33579373852934, + 45.33656718067833, + 45.337500908131304, + 45.33850912961951, + 45.339404503757684, + 45.34025240597607, + 45.34119504699709, + 45.34225198723166, + 45.342975385452, + 45.34373765087828, + 45.34457141712823, + 45.34520671973865, + 45.3459652914809, + 45.3468944913872, + 45.34763544710913, + 45.34834020280647, + 45.34927992179219, + 45.350152851503346, + 45.35111122525774, + 45.35222320834729, + 45.353302302900545, + 45.35436280634842, + 45.355351858982594, + 45.35636600921168, + 45.357455718978656, + 45.35846858023884, + 45.359484076225094, + 45.36044248198346, + 45.36136159825707, + 45.36201903786664, + 45.362607731819615, + 45.36338685277333, + 45.3641318443685, + 45.36464971564687, + 45.365223329150176, + 45.365707271298, + 45.36644051487314, + 45.36727776004473, + 45.36789140847082, + 45.36862781694657, + 45.36935732697808, + 45.37007171229736, + 45.37093491702046, + 45.37173675951087, + 45.37239239138229, + 45.37311424419294, + 45.373893642577876, + 45.3747371400346, + 45.37557952956787, + 45.37617997045989, + 45.37676707820621, + 45.37752752882974, + 45.378324959843155, + 45.379006673860545, + 45.379605142930025, + 45.38034676039454, + 45.381162078651684, + 45.38194037878425, + 45.382527586665006, + 45.38295425868896, + 45.383675463602145, + 45.384443316479214, + 45.38494781921849, + 45.385568689166135, + 45.38640871629172, + 45.38693699116032, + 45.38780653396654, + 45.38835553836785, + 45.38885891735504, + 45.389154530847094, + 45.3898332667208, + 45.39055161538907, + 45.39088370020398, + 45.39142454130535, + 45.39206677437021, + 45.39272727527996, + 45.39351633320761, + 45.39419795561232, + 45.39471870690721, + 45.395467328939716, + 45.3965562787684, + 45.397069915703106, + 45.397574952630535, + 45.398274735105915, + 45.39902863728136, + 45.39967158075588, + 45.40013911515351, + 45.40050842848147, + 45.400799460712484, + 45.40146284138777, + 45.402032107932655, + 45.402394761819686, + 45.40278992019668, + 45.403446170751124, + 45.4042712768712, + 45.40541550236088, + 45.40594147911467, + 45.40645103491125, + 45.40736818440101, + 45.40877140195812, + 45.41076173057873, + 45.41213695009949, + 45.413260271751, + 45.41488591444327, + 45.41659224102789, + 45.41814194246695, + 45.41967431722273, + 45.42122421702902, + 45.42268026571465, + 45.42412747733741, + 45.4256593487682, + 45.427073589205904, + 45.42846906335461, + 45.42995491671941, + 45.431508868967576, + 45.43294949070756, + 45.43449795571096, + 45.436045896077744, + 45.43728591240688, + 45.43830163804861, + 45.439456093556636, + 45.44079735860992, + 45.44215224015999, + 45.44343120932357, + 45.444375003035816, + 45.445473560628116, + 45.44677225297314, + 45.44797609993086, + 45.44904543456109, + 45.44984120341096, + 45.45083794348416, + 45.452172561035646, + 45.45301431712992, + 45.45396179300497, + 45.45509309570998, + 45.45656097111738, + 45.458946085778955, + 45.460441648941014, + 45.462685237721104, + 45.46475459325952, + 45.466758441210935, + 45.472838358761976, + 45.484788098251514, + 45.50565315221926, + 45.53818408883597, + 45.5837903752552, + 45.64111097475223, + 45.704187093594705, + 45.76522474138874, + 45.815936438604616, + 45.856251405721544, + 45.88558165611295, + 45.907505296726434, + 45.923163721268345, + 45.93400337920274, + 45.94351507725153, + 45.955115010582595, + 45.972050141859455, + 45.999918103421045, + 46.03983971828734, + 46.09248763925718, + 46.158414662017144, + 46.23703736619839, + 46.327072657177446, + 46.42859592850699, + 46.541639647834934, + 46.667231187151486, + 46.8061285382561, + 46.957309432679715, + 47.118302808644636, + 47.28683927792054, + 47.463314218233265, + 47.64834611054478, + 47.83566798625701, + 48.023172248939865, + 48.20956769266305, + 48.39662784137522, + 48.57955770996967, + 48.75555971609832, + 48.92948050858245, + 49.093625856117846, + 49.24649494120659, + 49.393815701230196, + 49.52991360445883, + 49.65438721604678, + 49.76523014549145, + 49.8657542055838, + 49.95354106003255, + 50.02452950595315, + 50.081488363030104, + 50.125347509952476, + 50.153806861592756, + 50.16461030378974, + 50.15624106610237, + 50.12911427774848, + 50.083836488523914, + 50.02017330276769, + 49.93702726391105, + 49.836609476753964, + 49.723397604679526, + 49.58920810115112, + 49.43606536365915, + 49.28353242203603, + 49.10416673639415, + 48.90626942969818, + 48.70003420605666, + 48.478655587866776, + 48.25004021935163, + 48.00576350908627, + 47.74332031709656, + 47.48982967303377, + 47.22313318201167, + 46.93662462568459, + 46.659443183046186, + 46.37493857465736, + 46.07180596975934, + 45.76914529901862, + 45.464300795957406, + 45.15069647264574, + 44.82778404522427, + 44.504214552495256, + 44.175672589939694, + 43.84039272948602, + 43.50903893858218, + 43.174720354105986, + 42.826041969874936, + 42.48349316746876, + 42.139016908716485, + 41.786461125674016, + 41.41556209947847, + 41.064403391404404, + 40.70602954504817, + 40.32807491275439, + 39.959394441926364, + 39.59687493350447, + 39.2248773385048, + 38.84348071036869, + 38.48260607577791, + 38.11372693814414, + 37.73017677472638, + 37.359222962492275, + 36.99840874913466, + 36.624498682198684, + 36.256436845624044, + 35.89994905495483, + 35.532620226739965, + 35.167989300368006, + 34.80099922747861, + 34.44037918294277, + 34.07418353586902, + 33.70399761498599, + 33.34426143382196, + 32.98334220062625, + 32.62887100293793, + 32.2600001708878, + 31.91429267155726, + 31.567862840036128, + 31.20477116469836, + 30.852135211188124, + 30.5041019515858, + 30.15437616855528, + 29.795493418235086, + 29.439773034543396, + 29.092867442925655, + 28.74074003409194, + 28.389689200180523, + 28.04108618783154, + 27.694376883639453, + 27.343390182357584, + 26.99807895619347, + 26.654587155780035, + 26.298581014537678, + 25.96005462606094, + 25.62522181335514, + 25.276650295123694, + 24.933256141845575, + 24.600249322179046, + 24.25324649044085, + 23.912317605463883, + 23.578091177360236, + 23.238691252751593, + 22.913128686706337, + 22.587558377602974, + 22.260670840822804, + 21.945386829709058, + 21.632131528260782, + 21.309847674618073, + 21.00083876508177, + 20.692869915956067, + 20.374059350389338, + 20.069267127553385, + 19.76556702024636, + 19.45555588051149, + 19.152908458260175, + 18.853670810727607, + 18.54332865279199, + 18.233151029185514, + 17.931059701218214, + 17.621971149590077, + 17.314731946458686, + 17.01364025257034, + 16.714380610703095, + 16.411528787587354, + 16.109089073258097, + 15.805912897581694, + 15.502517862735598, + 15.194229158304234, + 14.887743611100595, + 14.580535534255668, + 14.267081270570092, + 13.957935779247167, + 13.645837748807345, + 13.329297699110638, + 13.017084780374136, + 12.708165383851261, + 12.391605224475741, + 12.076588495210615, + 11.771657252356125, + 11.428856918233718, + 11.115085510666857, + 10.811547455719008, + 10.508092171074775, + 10.202100623559728, + 9.902107827661291, + 9.606825690276896, + 9.310224501023288, + 9.016231326587475, + 8.724466119535888, + 8.429646961681588, + 8.141380509861708, + 7.847680658910126, + 7.548387398439552, + 7.2557844820569155, + 6.958131601985776, + 6.648654056656934, + 6.342844172003127, + 6.0429672685303055, + 5.724886961082017, + 5.414892843547536, + 5.1155752002257335, + 4.793823666094012, + 4.475778975369742, + 4.167811483842318, + 3.8436931817113065, + 3.5206956344703415, + 3.205702010388127, + 2.88152243930825, + 2.570958053977248, + 2.260990016202482, + 1.9440542354900103, + 1.6457803016981958, + 1.344874972001644, + 1.0359357387089771, + 0.7431647760945245, + 0.4470713207390033, + 0.14182208713334643, + -0.14927943330410953, + -0.44086000184198426, + -0.7319241037042714, + -1.01638476911375, + -1.293997171603349, + -1.5693275790496173, + -1.815731952007402, + -2.0444292003357356, + -2.274251979854682, + -2.481389733636101, + -2.6646039940176514, + -2.838972470329237, + -2.9884123218117042, + -3.11023864851491, + -3.21472992012814, + -3.2974032758040073, + -3.355915431645531, + -3.3913835382922035, + -3.4048123854802816, + -3.39803858859178, + -3.3710280857549937, + -3.325108369200027, + -3.2611074439519006, + -3.1802804961620454, + -3.084287327127412, + -2.974114920253723, + -2.8483406607594324, + -2.7114471000777796, + -2.5612456990820673, + -2.3972975979451885, + -2.2240683506681793, + -2.0399820767784145, + -1.8454583819492636, + -1.6462925311363519, + -1.4426765317417052, + -1.2355122652243018, + -1.0266833604456562, + -0.8203287147004672, + -0.6151670102511687, + -0.41186524360498994, + -0.21142850065476018, + -0.014788827337959793, + 0.17912239878214273, + 0.3695248181338274, + 0.5497528631733597, + 0.7202484735149064, + 0.8870487712695617, + 1.044087887633294, + 1.1923079643531156, + 1.3375689256931582, + 1.478910789980186, + 1.6021343359196878, + 1.7198753508456497, + 1.8343477615511954, + 1.935784009373079, + 2.034653048186079, + 2.1293593031519724, + 2.209958860284805, + 2.285664476839112, + 2.3577403536442203, + 2.422468884831358, + 2.4857085427293923, + 2.545101229466147, + 2.5939810802864383, + 2.63730522737304, + 2.6793949775599177, + 2.716254932991565, + 2.750329503332266, + 2.7847351056235126, + 2.8149824253505944, + 2.840858525848436, + 2.866832856374559, + 2.89238014379388, + 2.9184729701399044, + 2.9480580670122456, + 2.979556576918602, + 3.0146754054240814, + 3.054826423352543, + 3.096675035659461, + 3.139990556703625, + 3.184667815612314, + 3.2292327942258465, + 3.2743714193132347, + 3.32226300056172, + 3.371700814595118, + 3.424566973691934, + 3.4830876993069837, + 3.5485035527291973, + 3.619961418131344, + 3.6975441393227633, + 3.781726261926542, + 3.8735972866285193, + 3.9715187448803877, + 4.077521685436444, + 4.190621417091774, + 4.311281690122221, + 4.437588575041153, + 4.569883254801034, + 4.7074473641466374, + 4.8516013531248126, + 5.002459568735386, + 5.157973202353776, + 5.32030188422588, + 5.489787275327103, + 5.664176150901903, + 5.841915989421802, + 6.025743569696181, + 6.215099677021708, + 6.4056394329494495, + 6.599747195124951, + 6.796871578543679, + 7.000876578665662, + 7.210515601989129, + 7.414008863247476, + 7.619599845586016, + 7.833515395655514, + 8.04457660123133, + 8.25985916135352, + 8.481300158080627, + 8.703533225016418, + 8.922489518320095, + 9.142777567531969, + 9.366623691436404, + 9.591344715497799, + 9.819215722954493, + 10.057646146450304, + 10.29427445882235, + 10.526748962602603, + 10.7706706591195, + 11.015257917073688, + 11.253385326295108, + 11.506395584240968, + 11.758353643179158, + 12.005630872525707, + 12.267258033357656, + 12.530909801550804, + 12.786219345300823, + 13.057092854792527, + 13.32675583986419, + 13.587365823600374, + 13.862357481099695, + 14.134623496051223, + 14.394828503880833, + 14.66369232146545, + 14.921908316794884, + 15.18178455458598, + 15.44913444616254, + 15.710475691890215, + 15.966310648688792, + 16.220032134403954, + 16.464998920790475, + 16.71058892492495, + 16.964207762201045, + 17.209136022293695, + 17.461327162857966, + 17.716838938047527, + 17.960616386513582, + 18.210827985277778, + 18.46779453122991, + 18.71105572938212, + 18.97297690737294, + 19.241911854540295, + 19.500014477003784, + 19.767568083880867, + 20.039002069566862, + 20.306012026346778, + 20.564985494761704, + 20.83235000158009, + 21.09764463708101, + 21.35937942682989, + 21.6232834573419, + 21.876158423324846, + 22.128987388840248, + 22.384981603051383, + 22.63557889065227, + 22.886990330602675, + 23.1340420780325, + 23.381549899588997, + 23.63432836002035, + 23.884484257210527, + 24.141551206805165, + 24.410597473604646, + 24.668300827657163, + 24.941057687774595, + 25.235389680352345, + 25.52246640034228, + 25.820733265212404, + 26.146261319287532, + 26.459876076891092, + 26.758775995034405, + 27.083479341448516, + 27.416728140297526, + 27.737446902315366, + 28.074198688632993, + 28.424149427074962, + 28.76398193325348, + 29.105992458154173, + 29.455341264256788, + 29.804127060503248, + 30.15726674063583, + 30.5131652108559, + 30.873861402715676, + 31.24506793191564, + 31.61839907168172, + 31.987082870538966, + 32.36529463382383, + 32.74973439340146, + 33.129260166990576, + 33.507090698883566, + 33.89352452630285, + 34.274803994394475, + 34.62557077132737, + 34.97840526938305, + 35.3422523640149, + 35.67228967036853, + 36.00004151381821, + 36.351047157615085, + 36.67870026120099, + 36.99436114487999, + 37.3308200786596, + 37.65797535807802, + 37.98028943410984, + 38.319243502578786, + 38.65300220649891, + 38.980404389671115, + 39.31352333739406, + 39.6443216231381, + 39.9735661614373, + 40.30608505693576, + 40.64112651950941, + 40.97431678441473, + 41.3094050207714, + 41.639694499983264, + 41.970172151397996, + 42.298154479387556, + 42.63252777091632, + 42.961975135376704, + 43.29487399499332, + 43.63078203673385, + 43.960324113806855, + 44.280587363603054, + 44.61022584117488, + 44.91814656157118, + 45.21551535146278, + 45.52393224649588, + 45.816086558073636, + 46.105626265729946, + 46.40708217324153, + 46.695976393416366, + 46.980681696970024, + 47.302051147569, + 47.59138340375597, + 47.8763230782806, + 48.16904590905884, + 48.46962976416081, + 48.76150376781474, + 49.051398520258836, + 49.347994812593775, + 49.6389114935602, + 49.923916276300005, + 50.21596991028357, + 50.50779320964663, + 50.790358821381034, + 51.07948178153422, + 51.37078619788843, + 51.65129645766725, + 51.93142224600338, + 52.209249332542704, + 52.474303990615155, + 52.74191204645305, + 53.004554558054494, + 53.26258271656714, + 53.52397070358046, + 53.786443744982456, + 54.05305086160046, + 54.316936240388834, + 54.58382060666164, + 54.85971421690486, + 55.139833110999646, + 55.422915124787856, + 55.7068940366129, + 55.9926321361938, + 56.28063917988319, + 56.56640100698341, + 56.845524203622524, + 57.1221086914137, + 57.40251863786673, + 57.68043863229484, + 57.95409464108825, + 58.2316791416228, + 58.51290285072393, + 58.794513578866905, + 59.07724275831911, + 59.358543609297875, + 59.65469311588764, + 59.94482815433133, + 60.22598664665075, + 60.52269524291083, + 60.819740480228326, + 61.09034466522357, + 61.37502407232589, + 61.66738107404477, + 61.92984680065179, + 62.18397791345223, + 62.44359295123307, + 62.680022794538566, + 62.88649249020206, + 63.105048476809586, + 63.317588877884944, + 63.502937534715095, + 63.686564391128805, + 63.86294009574444, + 64.0186306609059, + 64.16673301835688, + 64.30334395151725, + 64.42663562399538, + 64.53651397526073, + 64.63161466900597, + 64.70816300520418, + 64.77281153676934, + 64.82311159398937, + 64.86002769221417, + 64.8892987824187, + 64.9063208822544, + 64.90763321466169, + 64.89550866877087, + 64.8720369381132, + 64.83709216836066, + 64.78896813125499, + 64.72646694884126, + 64.65180600879873, + 64.56676316067332, + 64.46485226581336, + 64.34873269231545, + 64.22535653966474, + 64.0865173517071, + 63.93315970541152, + 63.77116117350705, + 63.59061669908269, + 63.3980218639613, + 63.19137370472949, + 62.96576109058118, + 62.728687979886935, + 62.477231154300924, + 62.21413222611236, + 61.94292872182762, + 61.66377917267032, + 61.377245128534945, + 61.08228224831478, + 60.786882322751936, + 60.48741490343282, + 60.18441305967586, + 59.883376067533106, + 59.58182549475365, + 59.27927534524969, + 58.971913215094816, + 58.656278852646786, + 58.33845528784237, + 58.030759945024286, + 57.71592718520604, + 57.39280002548415, + 57.08655392095955, + 56.77130031276584, + 56.4490628529945, + 56.13098410273622, + 55.822499964849065, + 55.50558258918016, + 55.19053868704912, + 54.88597372525349, + 54.570850756057624, + 54.253975835514126, + 53.94573842453985, + 53.63051043994362, + 53.31091129134796, + 52.993804550829, + 52.67858715138811, + 52.35427618518613, + 52.029122339850936, + 51.709388406735044, + 51.37997236972773, + 51.05126997517338, + 50.72869087137583, + 50.40673533921882, + 50.087407082488724, + 49.76918964500379, + 49.44359393141434, + 49.12774868708828, + 48.80936249396381, + 48.482471009638466, + 48.16154030687558, + 47.83975326351295, + 47.51791137988673, + 47.198017846154094, + 46.87762889692828, + 46.55362901235234, + 46.23150805396997, + 45.91080859581661, + 45.58201851787454, + 45.258302837766585, + 44.93505012540116, + 44.605107474019384, + 44.277477323798685, + 43.955016245727585, + 43.62820678836799, + 43.30942836303323, + 42.98600470233816, + 42.65115161151966, + 42.32784807714479, + 42.001137866568904, + 41.66248222985032, + 41.315973962492706, + 40.9869940930252, + 40.64246110903902, + 40.284759235795846, + 39.93720250367378, + 39.58972856230055, + 39.2391737060455, + 38.881433406578324, + 38.53986266002814, + 38.196382868875865, + 37.844457631283646, + 37.50221303275838, + 37.15913681583543, + 36.81304313884099, + 36.465684266328594, + 36.12490782074833, + 35.78431103636534, + 35.43850879148098, + 35.09626933188624, + 34.74763222137042, + 34.40528131864121, + 34.060431499684526, + 33.709413402553835, + 33.374583192523616, + 33.03659172933373, + 32.69472681307677, + 32.352871024716386, + 32.02382317548636, + 31.692640813105342, + 31.351825875548375, + 30.981931236957166, + 30.649926729282427, + 30.308778463062776, + 29.958820918627342, + 29.612163221650928, + 29.27205607700253, + 28.928528663361543, + 28.587289296537417, + 28.252425888312267, + 27.913438454958953, + 27.575693933844544, + 27.243387472339872, + 26.920450503404965, + 26.593324956162824, + 26.268851354846873, + 25.961662584533766, + 25.648983227043615, + 25.330841804496647, + 25.024094124192995, + 24.716810376168564, + 24.397226452860163, + 24.09106675332628, + 23.792899362983363, + 23.47963434262606, + 23.178586035797643, + 22.89036554768616, + 22.588507931956737, + 22.29472900096752, + 22.016067916560125, + 21.72151298888659, + 21.424651910482837, + 21.14884867245253, + 20.831723694209558, + 20.52882144534976, + 20.251926737154022, + 19.969856166318113, + 19.674857734782908, + 19.394901622127772, + 19.115589157764912, + 18.825826774014903, + 18.540882879612287, + 18.25670131857264, + 17.966870319203498, + 17.679928870075006, + 17.395216912925186, + 17.111623677846932, + 16.83327633895371, + 16.553289938794, + 16.272858561236113, + 15.99475508423096, + 15.714673362984552, + 15.434100350148046, + 15.153104332282986, + 14.878737149287456, + 14.59569361776559, + 14.314400851082752, + 14.037187911041322, + 13.752669178415237, + 13.469130969104476, + 13.186252551954205, + 12.899769263558902, + 12.608741436899221, + 12.320483607054424, + 12.033333952864483, + 11.743212867818992, + 11.452400836491277, + 11.163832061493704, + 10.87428313586358, + 10.581298211797025, + 10.289585233925095, + 10.003460194212307, + 9.714023874585337, + 9.431185913029365, + 9.152679304249583, + 8.876103763020335, + 8.60106861338303, + 8.330234351226155, + 8.062399392062407, + 7.789153086387231, + 7.518843322043353, + 7.244486191065995, + 6.972379311833277, + 6.702715121419891, + 6.397657078386688, + 6.119546934832735, + 5.850730903770537, + 5.5778769180651375, + 5.295731491782003, + 5.010585368516014, + 4.732149618759102, + 4.446223579405364, + 4.154052964445426, + 3.8707771410600462, + 3.578668000483556, + 3.283248346031772, + 3.009831509551147, + 2.7294772185752003, + 2.439359255974464, + 2.165069821066807, + 1.8922510554894079, + 1.611875081193677, + 1.3398181623517504, + 1.06716635467668, + 0.7930661827227454, + 0.5213396865892294, + 0.24900753508883527, + -0.02927115132790787, + -0.30631210960349814, + -0.5903008760638585, + -0.8740797373657807, + -1.1557809442866598, + -1.43457206073578, + -1.7109215467472685, + -1.9875241679544764, + -2.243214593134427, + -2.4798193150215364, + -2.716157479213643, + -2.9366919052011538, + -3.1346932650920354, + -3.323224561917978, + -3.4968741879849956, + -3.6479032785146766, + -3.782963066035635, + -3.8967752603163106, + -3.986063585407675, + -4.05570221046406, + -4.102947137383738, + -4.125668714420832, + -4.126023698323803, + -4.106316079237101, + -4.069879750356919, + -4.013507029812954, + -3.9388505583439106, + -3.8521203595204794, + -3.748246727545021, + -3.628567392124721, + -3.4997206517553705, + -3.356917373552429, + -3.2018029807575537, + -3.037824888284141, + -2.8652333256444793, + -2.684198629368167, + -2.4974028485933752, + -2.306800582453958, + -2.1105985560625293, + -1.9120259660815933, + -1.7137098506786699, + -1.5177394157354076, + -1.3267271944641734, + -1.138814197084552, + -0.9579866704342876, + -0.781498247925053, + -0.6072680113377534, + -0.4379243557395881, + -0.2726371571455989, + -0.11020970900653274, + 0.04568686663126684, + 0.19655028292906002, + 0.33990140254323953, + 0.4746665422254469, + 0.6091185402850376, + 0.7351145318647105, + 0.8559473234029513, + 0.9709084656969998, + 1.0877879580709697, + 1.1983330275124655, + 1.2949339891721148, + 1.3926104580928997, + 1.4861922949559723, + 1.5718667115192695, + 1.6556812775728242, + 1.737533576764661, + 1.8103433203707366, + 1.8768386752259385, + 1.94169337644323, + 2.0008644539328135, + 2.058011016547057, + 2.113376084090168, + 2.161917395027421, + 2.206327915063, + 2.2470241984415624, + 2.2844376943959053, + 2.3167971720485934, + 2.3463759940634703, + 2.3732528454295974, + 2.3977015645263875, + 2.419424716496846, + 2.4391257210056154, + 2.4581661721343564, + 2.4760834025730842, + 2.4948209717097534, + 2.5152157292469712, + 2.537726956003219, + 2.563045175832419, + 2.5923259488744463, + 2.6235803001400018, + 2.6547104375531503, + 2.6882468672845015, + 2.722868273296302, + 2.7577078965335047, + 2.7947002260250353, + 2.833303583593914, + 2.8722764445081204, + 2.913744128947523, + 2.9582002371524707, + 3.0043149595698164, + 3.054572368166239, + 3.109635545671697, + 3.169127382480864, + 3.233982551457134, + 3.305067027519865, + 3.381649352350055, + 3.462579502841436, + 3.548881480285042, + 3.6387510749962053, + 3.73422127659939, + 3.837246845655587, + 3.9438950955057437, + 4.055148513043715, + 4.175796563345039, + 4.299857145929124, + 4.427920028760938, + 4.564200864570259, + 4.706662589097586, + 4.845795057310785, + 4.990574450932911, + 5.141452335010133, + 5.2924638623179305, + 5.445462298161452, + 5.6047012143928665, + 5.7656655200045765, + 5.923161432890435, + 6.086715257279508, + 6.253030729176701, + 6.418953847168114, + 6.591517594838, + 6.767784638605135, + 6.939741504314393, + 7.117000458113039, + 7.300423866865699, + 7.485421635925301, + 7.672668670726102, + 7.867973639907908, + 8.064928215884052, + 8.261454641495268, + 8.456323783215645, + 8.653707009385208, + 8.853109363506482, + 9.052095269379818, + 9.251010569352694, + 9.455883497431737, + 9.664548108832998, + 9.86867958138228, + 10.072192968002337, + 10.283140091676069, + 10.493257173499961, + 10.697821767737025, + 10.911771274136825, + 11.127694008643468, + 11.338431291874018, + 11.555933018342088, + 11.77915157388375, + 11.999906705493894, + 12.22073278204977, + 12.450875494394165, + 12.677462465857127, + 12.89944884663247, + 13.131417460797836, + 13.365342006427221, + 13.59036767840702, + 13.819426994262399, + 14.052295347324945, + 14.27679261328338, + 14.505431181488275, + 14.74058925982937, + 14.96915917570018, + 15.197299561430436, + 15.424908144460323, + 15.64782793185962, + 15.86418333806608, + 16.081449408336358, + 16.302276766260317, + 16.520593847042477, + 16.73952000038133, + 16.966763792036904, + 17.187508805665516, + 17.402097786691098, + 17.62437166898507, + 17.849784911959865, + 18.067067204532794, + 18.288807239623967, + 18.519673597989403, + 18.741453074728906, + 18.960201003842627, + 19.187528970108, + 19.40603607314136, + 19.6295802469014, + 19.851471769792692, + 20.063892902360426, + 20.28284044547063, + 20.49506265498528, + 20.70484641453179, + 20.931845452406186, + 21.14380278638029, + 21.351556856093342, + 21.573710934054002, + 21.797372150281266, + 22.025143555702744, + 22.26162635728783, + 22.49555917009494, + 22.74108251568682, + 22.997379529708848, + 23.259893410872117, + 23.521739121800756, + 23.803526124778454, + 24.085909301716974, + 24.364358564513505, + 24.66952019053571, + 24.984296990340198, + 25.288991394864112, + 25.621334529400418, + 25.94923672774287, + 26.231807525533302, + 26.528803991800288, + 26.83558524180938, + 27.13251200071202, + 27.43363846792482, + 27.745063153098563, + 28.050495350322393, + 28.352985451389543, + 28.657802793457517, + 28.965318681392027, + 29.290414036766883, + 29.613305450592385, + 29.935893118228776, + 30.261392835932636, + 30.590872510173433, + 30.923368052022465, + 31.244988057728378, + 31.575803204180385, + 31.911151803658623, + 32.25018089339783, + 32.59480910699614, + 32.937627402566825, + 33.28794588439994, + 33.6279347381299, + 33.96190557936996, + 34.294610113578194, + 34.627339545147244, + 34.95052864881934, + 35.281680386612635, + 35.6130857622301, + 35.9290746696189, + 36.24852163663968, + 36.57422177102859, + 36.899631083515544, + 37.22588313597998, + 37.559215504866344, + 37.892777877735455, + 38.22551890017168, + 38.560538554247486, + 38.89158251079862, + 39.23302529975385, + 39.57820606213428, + 39.91884227485884, + 40.26306141062812, + 40.60937815640735, + 40.951666628629305, + 41.29318404025987, + 41.63657129801098, + 41.975595254807295, + 42.31734029198733, + 42.65353646987068, + 42.98831713780912, + 43.32888139048449, + 43.6655586896088, + 43.99368605046921, + 44.33142138232008, + 44.66215604052806, + 44.98490126596221, + 45.320020446725124, + 45.6423555683974, + 45.957346640807316, + 46.28348996674704, + 46.60040390395959, + 46.911337690664304, + 47.23368236810229, + 47.548562973696995, + 47.84594364853935, + 48.161893501649466, + 48.47966621412509, + 48.78104052066766, + 49.09550960412552, + 49.41365828497713, + 49.71392945487082, + 50.01885034497675, + 50.32869305739655, + 50.62525095914379, + 50.92564264333343, + 51.23246453113018, + 51.524620784434596, + 51.81150141540853, + 52.10062067544182, + 52.380974291115784, + 52.65774195484237, + 52.92921084593508, + 53.204554760149584, + 53.4783903496776, + 53.75658240531161, + 54.0366105377843, + 54.31404765242369, + 54.59787519797507, + 54.88992129520901, + 55.18350011196275, + 55.47300473071834, + 55.77115199960749, + 56.06407678115986, + 56.34957599191736, + 56.640500017847735, + 56.918919577569525, + 57.18651191609925, + 57.464796277014536, + 57.7489816803978, + 58.01228352171607, + 58.27448447590476, + 58.549261764877976, + 58.81966354190635, + 59.0810190597338, + 59.34550804391031, + 59.621904510986425, + 59.89243981498452, + 60.15054633062333, + 60.4146359330284, + 60.690927131716464, + 60.95117336000782, + 61.211926574230255, + 61.49175187232582, + 61.75862622972725, + 62.002538063312464, + 62.25130083747442, + 62.494978305394376, + 62.70413113581055, + 62.90684831747295, + 63.11819867225374, + 63.30876360557971, + 63.48255241562824, + 63.65652732608937, + 63.81188357849256, + 63.952223161903035, + 64.08384835040273, + 64.20228694366901, + 64.3058778678585, + 64.39431052265087, + 64.46181476053984, + 64.5138221164496, + 64.55037676437557, + 64.57202236022114, + 64.58122002040913, + 64.57357281798858, + 64.54846525516317, + 64.5066277721625, + 64.44855207527613, + 64.37828463181846, + 64.29050019600527, + 64.1837097623907, + 64.06820377617622, + 63.9359705388783, + 63.78154042851915, + 63.62139498865959, + 63.443128478639025, + 63.246074115359114, + 63.044716788422015, + 62.830994017778295, + 62.59475675268386, + 62.35145991094609, + 62.102827126482275, + 61.836469170239184, + 61.56052117465298, + 61.28350782294512, + 61.00211248774538, + 60.71319822773284, + 60.415230565970255, + 60.11068377896734, + 59.80297097306492, + 59.487662636397125, + 59.166261821624495, + 58.84489002582075, + 58.51493489560721, + 58.17376645681918, + 57.83577562934087, + 57.50159619448542, + 57.150206968316674, + 56.8098775057813, + 56.480478255854734, + 56.1337826236115, + 55.79212702638441, + 55.46529845716434, + 55.122389420158356, + 54.78620751035339, + 54.45562989734567, + 54.112611391115095, + 53.77183859158204, + 53.4346064857942, + 53.08624326957375, + 52.73705271285156, + 52.396702556113986, + 52.04201990757297, + 51.68831138692674, + 51.341335793576874, + 50.98392454616007, + 50.63082960851566, + 50.2845751874734, + 49.935157892616516, + 49.585502316420516, + 49.23450291787667, + 48.89043106822508, + 48.53718118140634, + 48.183106174437874, + 47.83290180765036, + 47.48342297947092, + 47.13267354616005, + 46.779444550330155, + 46.4290543350682, + 46.079316639733236, + 45.72484143705796, + 45.33074088809445, + 44.97905968459101, + 44.61934566425871, + 44.25404515186802, + 43.89440567514032, + 43.52880276659065, + 43.16432513341936, + 42.80109993962998, + 42.426443112120424, + 42.05458400887959, + 41.68869886475714, + 41.30406811282386, + 40.91732412143384, + 40.55184686255979, + 40.162958205166085, + 39.77007580965446, + 39.39551996242697, + 39.011968802918155, + 38.61155593306669, + 38.237991349744036, + 37.862498253284045, + 37.47087662406409, + 37.09438850324539, + 36.725218789343096, + 36.34145903615912, + 35.962788171007944, + 35.59742720821883, + 35.22314046889542, + 34.845470615037904, + 34.47077348983268, + 34.10078165992983, + 33.720052942159576, + 33.34048087728195, + 32.970353952554824, + 32.59422500184866, + 32.21704072487308, + 31.8485029905479, + 31.48400049576467, + 31.112191483180407, + 30.739825730803798, + 30.37312850259972, + 29.99985756267379, + 29.617963798496188, + 29.2467291159945, + 28.875955840739014, + 28.502309183512967, + 28.135940856742728, + 27.766807861272547, + 27.39749678995351, + 27.034658109848234, + 26.677225788696784, + 26.318530075613232, + 25.967085718463615, + 25.627262362385075, + 25.277091515812, + 24.93020802031985, + 24.58994780320747, + 24.23465416028736, + 23.88850758412448, + 23.548554735994852, + 23.202723948728426, + 22.86842250365915, + 22.538816273231063, + 22.205466008741364, + 21.883740759053744, + 21.559288904454927, + 21.224337741051304, + 20.91460446251487, + 20.59968776191551, + 20.264677799873517, + 19.954420542202634, + 19.642669745042046, + 19.314741441083697, + 18.998021408460353, + 18.688882635627362, + 18.36340240744392, + 18.052109997714656, + 17.76556782272875, + 17.47181725701148, + 17.182570274630805, + 16.904251916910184, + 16.62114939379875, + 16.33708929371887, + 16.059215464919923, + 15.775224779471078, + 15.492091854500226, + 15.202113729578942, + 14.903877747934894, + 14.602521465534105, + 14.301146836855489, + 14.004371042662179, + 13.704510927008922, + 13.404502075527272, + 13.106773714107563, + 12.810173788665038, + 12.50792605386516, + 12.204309055755756, + 11.901595980951306, + 11.597353718742553, + 11.29308072858805, + 10.994020537350567, + 10.699498462628563, + 10.400942490118092, + 10.107273838156436, + 9.819291714596416, + 9.53246740519458, + 9.246960777908608, + 8.967798298246185, + 8.687201947034684, + 8.406735056830456, + 8.129034611020845, + 7.84208767826444, + 7.552771676692099, + 7.270788312748914, + 6.948883786893604, + 6.647360760685175, + 6.352150079582912, + 6.054043535841086, + 5.747904281550427, + 5.450203041801112, + 5.153571962327716, + 4.845539280114005, + 4.547248750200525, + 4.254694092048906, + 3.950410623554936, + 3.653454874272269, + 3.361836168080324, + 3.0649956197929056, + 2.784864028950497, + 2.5030941040493673, + 2.2184336888929423, + 1.9506677645006707, + 1.6831380259049515, + 1.4099914836804952, + 1.148007225055149, + 0.8825854868148396, + 0.6091438528935407, + 0.3329631741793019, + 0.047078976871867295, + -0.2352447315031835, + -0.508756199989569, + -0.7853828673457621, + -1.0603026857941362, + -1.338679442750711, + -1.6007652894089202, + -1.847553644318416, + -2.1040329713990307, + -2.3418535145622625, + -2.5538629993803976, + -2.765133911770426, + -2.9701720576168875, + -3.1595598230605817, + -3.3382909620172394, + -3.504147407326207, + -3.6539679529776756, + -3.78939863520616, + -3.907272219931894, + -4.0066095925570115, + -4.091204898540712, + -4.158262119894641, + -4.206623367713327, + -4.236058617552424, + -4.246644353929049, + -4.239034035612159, + -4.213506574398528, + -4.171128279359379, + -4.113710327681287, + -4.0419241443501, + -3.9559111690968516, + -3.857513719772755, + -3.748090036784706, + -3.626855195420487, + -3.496670562598065, + -3.3563265848874084, + -3.205151737412957, + -3.0488316854022117, + -2.8854476964654956, + -2.7128724275487377, + -2.5379062116092443, + -2.3614629685122734, + -2.163055172621855, + -1.982818367233269, + -1.8038731289925154, + -1.6272554952898974, + -1.4532546008280691, + -1.278990090742027, + -1.1098506009116396, + -0.942136755407772, + -0.776576723408273, + -0.6158370508830519, + -0.4544020997355928, + -0.29942973559885255, + -0.1454188060245573, + 0.007936003205972264, + 0.15565305258712397, + 0.29457625258933406, + 0.4314142580302064, + 0.5683430981854892, + 0.694846679137476, + 0.8188379360171041, + 0.9358809833941538, + 1.0527320108236529, + 1.1671660272613753, + 1.2671443883084748, + 1.3640722172091344, + 1.4577010292601715, + 1.542415850180607, + 1.6223748629558545, + 1.699971255890312, + 1.7685763797422365, + 1.8275838981024881, + 1.8824069707097382, + 1.9315755100308414, + 1.9761177832561962, + 2.0184224135107582, + 2.058772295444945, + 2.090048449146628, + 2.118414284995719, + 2.1433218020241127, + 2.164499847176934, + 2.183624398856786, + 2.201745563914696, + 2.2191163862191376, + 2.2356112568211453, + 2.252205190590705, + 2.2696734386851425, + 2.2861436871219065, + 2.3028388082520315, + 2.320156656784082, + 2.3385900642083643, + 2.3592713493285324, + 2.381709319584404, + 2.4070750850405918, + 2.433536714213401, + 2.460323180625303, + 2.488334737445989, + 2.517470701544321, + 2.546629802554478, + 2.5761035809681236, + 2.605801430812296, + 2.6346378618305946, + 2.664230743227441, + 2.694549804929435, + 2.7258159022823096, + 2.759238603216797, + 2.7944993759776464, + 2.8341113639860507, + 2.878222183433039, + 2.9265506539557307, + 2.9817570389312267, + 3.0424355076743477, + 3.10706981078607, + 3.176268493362981, + 3.2518366092586892, + 3.3306555083175096, + 3.4167003836949985, + 3.5103863409690583, + 3.608075276617331, + 3.712465197951945, + 3.824986779880386, + 3.9414953622228603, + 4.063337721981724, + 4.189228453085594, + 4.32305494845731, + 4.4601335086936915, + 4.599612768708412, + 4.745724565432593, + 4.894244097721296, + 5.041885910037444, + 5.191764910987589, + 5.346624945272, + 5.502136993699961, + 5.66031023985374, + 5.827040420228186, + 5.993915138638752, + 6.163019081791028, + 6.340004190690086, + 6.51480791576448, + 6.693052797442919, + 6.876344788889039, + 7.061744999846965, + 7.249530507137674, + 7.442401885917925, + 7.6363173798228825, + 7.833347531175167, + 8.031939902077687, + 8.231630218605986, + 8.437204769860044, + 8.646940742133532, + 8.857529835015656, + 9.07108788216632, + 9.290443494699435, + 9.513642844314555, + 9.734015257909563, + 9.952667334600143, + 10.176895422656376, + 10.399408406976416, + 10.612948927801359, + 10.835322750369697, + 11.060327826084288, + 11.278301473239495, + 11.503489875629574, + 11.73523294520646, + 11.963468785348505, + 12.191789007678494, + 12.429478131732653, + 12.665443031503617, + 12.89579158070827, + 13.136067873538982, + 13.377967392787282, + 13.609060380777938, + 13.842656718036658, + 14.079282585095763, + 14.303025116185163, + 14.531193772188637, + 14.76343373257601, + 14.988364717265448, + 15.210401108907472, + 15.432194824916941, + 15.648898221378381, + 15.859666504257781, + 16.07159243459752, + 16.28587704705328, + 16.492741049637687, + 16.70271477593439, + 16.916959488029352, + 17.120388676395603, + 17.321872086130636, + 17.52598437352893, + 17.73069132213282, + 17.923541381424986, + 18.12415877679045, + 18.33055247009981, + 18.527339344950683, + 18.728619393999544, + 18.93229651117788, + 19.159708602880198, + 19.4082784942946, + 19.657013882891285, + 19.913688153069966, + 20.1810237350667, + 20.44925984654765, + 20.71943223986166, + 21.013255340780542, + 21.296880996082397, + 21.587008717105277, + 21.87669543522121, + 22.14614390357882, + 22.429699716773424, + 22.72867919352653, + 23.015124808272496, + 23.309689131058693, + 23.62072737599991, + 23.917317997509155, + 24.22728923897416, + 24.549557830741826, + 24.859284779918198, + 25.198737878170633, + 25.55124425892161, + 25.891361522185825, + 26.253819551000504, + 26.613487891441043, + 26.953390314574257, + 27.310638571378494, + 27.675098879004985, + 28.02257609685884, + 28.372024437456844, + 28.722782278393833, + 29.056779778170263, + 29.391639482158382, + 29.733978619258064, + 30.06954199813284, + 30.405578557387145, + 30.74290460478035, + 31.076644811849285, + 31.415921869142643, + 31.75168566214963, + 32.07880615187477, + 32.40706885545298, + 32.73851460197841, + 33.0676807176834, + 33.39832381666462, + 33.722583165076074, + 34.047658623891216, + 34.379238402257826, + 34.69422166225884, + 35.000045231143986, + 35.31662744158378, + 35.626168566857515, + 35.92233434856951, + 36.23308218134385, + 36.54449892409094, + 36.84456016976044, + 37.1509961306791, + 37.46708218572251, + 37.778666332331575, + 38.09528208590343, + 38.41604525917596, + 38.73530274120566, + 39.055625712890404, + 39.37255657030364, + 39.68694055810615, + 40.00704721386262, + 40.32652264170847, + 40.648259894550165, + 40.97597427139211, + 41.301638338918146, + 41.62584438215976, + 41.956297836934525, + 42.284245628285845, + 42.613262425546324, + 42.95240079702139, + 43.28646993462193, + 43.625021677518454, + 43.97328896243987, + 44.312702543278725, + 44.64813124991473, + 44.99439254626033, + 45.3277421467613, + 45.66063501705099, + 45.99941329622676, + 46.3335422645042, + 46.67401168335572, + 47.01662165443693, + 47.35177127067828, + 47.68824468473037, + 48.02732167165485, + 48.34825278519832, + 48.67520754566773, + 49.009570294261664, + 49.330733779477306, + 49.64803478144664, + 49.97272288173262, + 50.28626181294306, + 50.59636292421281, + 50.91164452188793, + 51.217231473830275, + 51.523743506303816, + 51.83079606383554, + 52.12537571031702, + 52.41455454927051, + 52.69755428166409, + 52.97307848949289, + 53.244803055412994, + 53.51315808323412, + 53.77889165725008, + 54.0491643707451, + 54.35163494380637, + 54.62137644655208, + 54.893989465334805, + 55.17536679309078, + 55.45710389409889, + 55.74015307895498, + 56.0220228048467, + 56.303164609917786, + 56.58000819492296, + 56.841236795067466, + 57.09245391592853, + 57.339838256342624, + 57.58516029644259, + 57.82775634694091, + 58.070779490401414, + 58.308651526869305, + 58.57167097058137, + 58.81437714424254, + 59.060321005464154, + 59.31221678831944, + 59.57476904619701, + 59.84574422526881, + 60.10556921586334, + 60.36630394592955, + 60.64091672994618, + 60.911254785589264, + 61.16707885205474, + 61.434349921802685, + 61.70112616186897, + 61.93388386434675, + 62.15830832844092, + 62.38125936047842, + 62.590587097629445, + 62.787725268168, + 62.97481626703805, + 63.16308213907139, + 63.34120860191085, + 63.50523215150407, + 63.665414522459955, + 63.81702987323637, + 63.95334470163948, + 64.07447428964709, + 64.17894658610709, + 64.26765538233062, + 64.33715010727487, + 64.38424431844649, + 64.41170181037019, + 64.42031773573312, + 64.40931520031016, + 64.38339297026431, + 64.34336667198134, + 64.28737658398609, + 64.21855403422586, + 64.14121152797942, + 64.04995761227521, + 63.94846791151717, + 63.838660338765, + 63.71870140813576, + 63.58564694001701, + 63.43286502924833, + 63.26756956130647, + 63.089021454444065, + 62.89696735199743, + 62.69109830514015, + 62.475849872656646, + 62.24723760717158, + 62.00403832883274, + 61.74744926263506, + 61.48441603100128, + 61.21147438509104, + 60.92554547200103, + 60.64556168698664, + 60.35556131366098, + 60.05528774603434, + 59.761106324338954, + 59.45953567556409, + 59.14674387373742, + 58.83877987674616, + 58.52537351931939, + 58.19696747819619, + 57.87673206832023, + 57.55904407515568, + 57.219522834317935, + 56.89825560150076, + 56.583692262369006, + 56.247382950278954, + 55.925194275975464, + 55.61661738404746, + 55.287665670641275, + 54.97358775518657, + 54.667044557843184, + 54.34926065592826, + 54.033403777056186, + 53.72032698465734, + 53.39942408763453, + 53.07425797607542, + 52.76026576865347, + 52.43499851719745, + 52.1044872768535, + 51.77589236535425, + 51.44234818902297, + 51.10348480799015, + 50.77061054705971, + 50.43943035416799, + 50.105447993078876, + 49.775680140952204, + 49.437693937288984, + 49.109475016229915, + 48.774063273912645, + 48.44174250821862, + 48.11031287371997, + 47.780591614667, + 47.455178389408125, + 47.12345403343129, + 46.79250829325339, + 46.463096924711756, + 46.1302104268118, + 45.79628426756038, + 45.46087308387347, + 45.12707494978503, + 44.78291080964345, + 44.435197543313826, + 44.095601761189705, + 43.74644247020221, + 43.398053080714256, + 43.05685402972333, + 42.707021234983905, + 42.35524805506865, + 42.009044387462, + 41.65243165458508, + 41.276103231129696, + 40.9187023488142, + 40.5627451827555, + 40.18094692538712, + 39.81602462825786, + 39.4544890754482, + 39.075386646568006, + 38.70226880539241, + 38.3415785656529, + 37.97676501433701, + 37.60772571361131, + 37.250223049724525, + 36.88744324348057, + 36.52416454726091, + 36.1573556895985, + 35.79788148487995, + 35.437265081393555, + 35.07271719105067, + 34.70233914650486, + 34.334966911426164, + 33.96279699298524, + 33.57711933124139, + 33.20363930786742, + 32.83230262301181, + 32.460658625022646, + 32.08325053537434, + 31.71958169915117, + 31.357203914839488, + 30.990154777772926, + 30.631982239623195, + 30.275221666848807, + 29.915767642342555, + 29.55390361714718, + 29.197115634246998, + 28.838005033417023, + 28.47869388507307, + 28.13208967675225, + 27.77559158249143, + 27.421637809516504, + 27.090678679335795, + 26.75922066017794, + 26.43484794550527, + 26.11289662642745, + 25.79380377776938, + 25.47813120634998, + 25.164360541699196, + 24.847550507204833, + 24.534393432863162, + 24.220401011247223, + 23.90615233246471, + 23.589665253530022, + 23.273895528473595, + 22.971481724084825, + 22.665888937391326, + 22.3620898886782, + 22.069296232048632, + 21.77440371495339, + 21.466856629222264, + 21.17859792836629, + 20.8934541543908, + 20.58147048470993, + 20.285748877176808, + 20.001366350635404, + 19.69549193285993, + 19.395772270006105, + 19.102822298479825, + 18.79866540471908, + 18.49086458184024, + 18.18718747554513, + 17.87562827174696, + 17.561654080135373, + 17.25428736220401, + 16.943385909834873, + 16.635600645459125, + 16.328601752378894, + 16.022285516326736, + 15.713355480669735, + 15.406459366001444, + 15.098179998114757, + 14.788261722135921, + 14.480811970868182, + 14.168821267560622, + 13.861490918040086, + 13.552445228312457, + 13.241443743478781, + 12.931410145368236, + 12.621438580723158, + 12.308900177709276, + 11.991856791088074, + 11.677526845036505, + 11.368176690497656, + 11.05392183631032, + 10.741464037040421, + 10.439526008169324, + 10.136818386414463, + 9.82423644278, + 9.531400298275525, + 9.238686371846137, + 8.941403335004782, + 8.65284802362914, + 8.370242659390138, + 8.090755133450198, + 7.810471819959358, + 7.5290850443663935, + 7.255905312909552, + 6.981271089469676, + 6.696914938425842, + 6.4181863050356345, + 6.146481325295194, + 5.85483052076996, + 5.570950955358325, + 5.297348884398934, + 5.001466191033476, + 4.702468465076711, + 4.418485385786011, + 4.116906583262891, + 3.8174808038538623, + 3.5235553830862942, + 3.2118632499177506, + 2.9281086942201098, + 2.6440876629142287, + 2.344325939053991, + 2.0635779600180695, + 1.787671719069037, + 1.4993269583573747, + 1.2207628985657388, + 0.9454794304059446, + 0.6640958804600767, + 0.3877002089322421, + 0.11448444930974705, + -0.16578620518746093, + -0.44750527714441424, + -0.7258070032432261, + -1.0046909442100316, + -1.2832724040354047, + -1.5631608335006302, + -1.839274903874311, + -2.10599621587619, + -2.3694675277233017, + -2.62343893987978, + -2.858403956492617, + -3.090102958119805, + -3.3069641079040974, + -3.507229477288608, + -3.6938382521769215, + -3.8629814663577817, + -4.01420132205265, + -4.1466584356736265, + -4.259877706509005, + -4.352527189824512, + -4.422964230685253, + -4.473565063110901, + -4.502183007140632, + -4.507021577830109, + -4.489283337148372, + -4.45174440211488, + -4.397050804131656, + -4.323598131913655, + -4.231769913016596, + -4.124768055855302, + -4.000782801956151, + -3.848806574422038, + -3.7008431642453847, + -3.542712038947353, + -3.378535522961384, + -3.2077932292354094, + -3.030690460174938, + -2.8519001098794727, + -2.666681213026716, + -2.477801972577572, + -2.288094039386811, + -2.0954870850756433, + -1.902136836077668, + -1.7092534902537027, + -1.5183759989546781, + -1.32893877896922, + -1.1404759348918994, + -0.9554250517824684, + -0.770610521851054, + -0.1285582442863698, + 0.043080907309530216, + 0.211280767432397, + 0.37327933021129, + 0.5247876104488909, + 0.6714241109417203, + 0.8148578400793581, + 0.9457752361654689, + 1.0699833089646602, + 1.1874050240947238, + 1.3062525644859002, + 1.4148382096503505, + 1.5101383386416976, + 1.6047030472306796, + 1.6933293187395781, + 1.7742607545942723, + 1.8534355266406306, + 1.9285556499646628, + 1.9949586429074053, + 2.057049811045084, + 2.117137136923471, + 2.1715376262881505, + 2.224645268626372, + 2.2751400325408344, + 2.3194737710752404, + 2.3609646532785145, + 2.3993493477777537, + 2.434847778227501, + 2.4667596720468703, + 2.496246389384398, + 2.524205932018945, + 2.5508374102446174, + 2.5768897875550767, + 2.603334615586056, + 2.627617746830503, + 2.651458920424354, + 2.675565875821827, + 2.699632969712007, + 2.724885295219408, + 2.7514870422184745, + 2.7805366985599824, + 2.8100202298576566, + 2.839351985580052, + 2.870126952080361, + 2.902052472474704, + 2.934071944572666, + 2.9667649677538774, + 2.999161281092309, + 3.033247502509151, + 3.069458790047973, + 3.109101654141103, + 3.1521991926926627, + 3.1984060810843857, + 3.2513735416748735, + 3.3096335977130296, + 3.3721912004533228, + 3.442704234125669, + 3.518800508446662, + 3.598955450020016, + 3.6852691404136575, + 3.776690115407541, + 3.873897199025853, + 3.9809590777696595, + 4.093369901196933, + 4.21073543806722, + 4.337228720660737, + 4.467472306282675, + 4.600399174940791, + 4.7378920080515625, + 4.8818043434231715, + 5.025019052801778, + 5.174247070572004, + 5.328205564256003, + 5.479368840755798, + 5.631256669496028, + 5.788513887931863, + 5.948897262006386, + 6.10670218711256, + 6.26844904483016, + 6.432903803230794, + 6.596779259376989, + 6.7669267608152985, + 6.951513019733041, + 7.121582061617247, + 7.296303722578637, + 7.471446604902217, + 7.648390856797305, + 7.8329936775282905, + 8.020794966136831, + 8.209632808845917, + 8.401417620202345, + 8.590646064052626, + 8.783114896662422, + 8.978829742472467, + 9.175300105333713, + 9.375093784722608, + 9.576483388082313, + 9.776822687641996, + 9.974478826265862, + 10.16913283903571, + 10.363268687008691, + 10.55903746225986, + 10.75563130245319, + 10.945306668273254, + 11.135763190050596, + 11.332323488480347, + 11.525328914372237, + 11.720578016653537, + 11.926693929229051, + 12.135399727870412, + 12.342714717150432, + 12.55003234180756, + 12.761801265083607, + 12.97256146778967, + 13.179128127067901, + 13.387694609538476, + 13.597709724968675, + 13.80361797596977, + 14.006064805723163, + 14.207421030004635, + 14.406475207674958, + 14.601841720278095, + 14.793749819797004, + 14.987798478702754, + 15.181954233018319, + 15.372252885129878, + 15.558553037905114, + 15.745354404116084, + 15.931025015334148, + 16.112133567599226, + 16.29169380601665, + 16.474231645900765, + 16.65673077203514, + 16.838598653819968, + 17.024090442972696, + 17.215763953323627, + 17.40575160280916, + 17.593940114722514, + 17.78483760605761, + 17.981528288357495, + 18.182422671778454, + 18.374776814112163, + 18.581111160182836, + 18.79362259697671, + 19.002776113219582, + 19.21626970605701, + 19.43112870827955, + 19.65102080898132, + 19.878853568831616, + 20.10312546864239, + 20.33456798064165, + 20.571455677987018, + 20.805307917268557, + 21.045403500637494, + 21.298626572310877, + 21.53535576431192, + 21.787166760774234, + 22.04704548994729, + 22.30130520146322, + 22.574917940685502, + 22.846884374467052, + 23.11244824903883, + 23.394736111510714, + 23.676559415391722, + 23.953561991223374, + 24.250244848173462, + 24.540664243181794, + 24.833706554567964, + 25.156073221083844, + 25.473212534749933, + 25.796484527816077, + 26.13727266230354, + 26.460167230968434, + 26.77512580126815, + 27.108708116478457, + 27.438704853826536, + 27.759939243778156, + 28.097005722458324, + 28.43352407824126, + 28.759042039978237, + 29.089389232226157, + 29.420449816116722, + 29.74983119488025, + 30.08212078675594, + 30.411269707900978, + 30.742944489098743, + 31.079775794747977, + 31.415306515442328, + 31.741820418039623, + 32.07149075857679, + 32.40361086995983, + 32.73287821237294, + 33.05788248022835, + 33.377945876076446, + 33.703491287061006, + 34.02881086933761, + 34.336350875136155, + 34.63920540415571, + 34.95101710678149, + 35.252506576967846, + 35.54453913345566, + 35.85123718330825, + 36.1556024863718, + 36.44855841864565, + 36.750834738479114, + 37.06178859755466, + 37.36669465341993, + 37.67828627342124, + 37.99722984607634, + 38.3128101331543, + 38.63145517761055, + 38.94999809789752, + 39.262558010339916, + 39.579606480905696, + 39.900656383320424, + 40.21583267579129, + 40.53472068673256, + 40.85465562257616, + 41.171871203786324, + 41.486037357245635, + 41.80341437120019, + 42.115184424916826, + 42.432267817800195, + 42.74869006613391, + 43.06151791935443, + 43.3820080676286, + 43.70140529186662, + 44.013298163509596, + 44.328170401408954, + 44.64674426514315, + 44.947785521041396, + 45.25663632901949, + 45.56604597424447, + 45.86151513692612, + 46.1652166857148, + 46.47234999090252, + 46.76795480259499, + 47.06580954138513, + 47.369754222452364, + 47.66790276213002, + 47.955036340077136, + 48.25304046096536, + 48.55028755018086, + 48.84124349388114, + 49.13120357369446, + 49.425155662794786, + 49.71207103834986, + 49.997415742459815, + 50.28675152243265, + 50.57106337226466, + 50.851292024285996, + 51.13648119935449, + 51.417560945870974, + 51.69166214349666, + 51.96406627724454, + 52.22926991177055, + 52.48582986037931, + 52.745453668301394, + 52.99701452760204, + 53.24552141987308, + 53.4978257580014, + 53.7494697455108, + 54.00373136573797, + 54.255545635500454, + 54.50935013800976, + 54.770800669626155, + 55.036105044860285, + 55.30578103475355, + 55.57712629270071, + 55.84841517886736, + 56.121305819378854, + 56.396127182219146, + 56.66480154268678, + 56.92590628816359, + 57.18698185333048, + 57.44827129411211, + 57.71011908320546, + 57.963999775378376, + 58.218160972638955, + 58.47851432665823, + 58.73886674078835, + 59.0018961803807, + 59.25945908560965, + 59.52850899544941, + 59.7983985531829, + 60.06082253745904, + 60.325324743604384, + 60.603310869586814, + 60.87044228018748, + 61.12857127677023, + 61.40259509282569, + 61.67108245307185, + 61.91466944388023, + 62.15701613438367, + 62.39918205440036, + 62.61468586808511, + 62.814890921539984, + 63.02869703724511, + 63.23373607245903, + 63.41827901302412, + 63.60299309694622, + 63.775328972893604, + 63.92889207470187, + 64.07696865776536, + 64.21234997683516, + 64.33590342676878, + 64.44841181662521, + 64.54345291530073, + 64.61930888948838, + 64.6804588488602, + 64.72498316710659, + 64.75503192542301, + 64.77423687634494, + 64.77803140213041, + 64.76324698744891, + 64.7316474879003, + 64.68467452846008, + 64.6238135747295, + 64.54563229844479, + 64.44741475264918, + 64.3356181562903, + 64.20980251223435, + 64.05914493782261, + 63.89264825264366, + 63.72007165595962, + 63.522447573320285, + 63.31200360543133, + 63.09432787491209, + 62.85875514113911, + 62.60149057913376, + 62.33823598972425, + 62.06428886562031, + 61.77172285159672, + 61.47355105704766, + 61.17496468507821, + 60.87045058716934, + 60.55938185071553, + 60.24397081513541, + 59.93095284858972, + 59.61728220176726, + 59.299333939218656, + 58.97707926350325, + 58.65792783521924, + 58.33271154277494, + 58.0012539725055, + 57.67455351559774, + 57.35069668912867, + 57.0110033390398, + 56.682707863948245, + 56.36397335195614, + 56.03032003075439, + 55.70119001727611, + 55.386535174913206, + 55.05762540355066, + 54.73099797658368, + 54.413186029836865, + 54.08440679283176, + 53.73343743190345, + 53.37357244061748, + 53.004494568369005, + 52.62954228046007, + 52.26446093215443, + 51.8915976868798, + 51.510535483981364, + 51.13531867866375, + 50.75821421464184, + 50.37417727794913, + 50.014487343204124, + 49.669224905922185, + 49.321863973983824, + 48.97802674707963, + 48.62923138335952, + 48.28707355315305, + 47.93763151574009, + 47.5872907197428, + 47.24000687906527, + 46.893839862634835, + 46.53587658051037, + 46.163590570402484, + 45.79241563967316, + 45.42317540460844, + 45.04551180986331, + 44.66978917424429, + 44.29262343794187, + 43.91757027134529, + 43.531587538619334, + 43.14696794743754, + 42.78206108151733, + 42.41824049184275, + 42.060184243998044, + 41.70452003079957, + 41.33805206358612, + 40.9766109893554, + 40.61983341924642, + 40.24887535369847, + 39.87223229958563, + 39.519149902919985, + 39.18455634113386, + 38.860337834576384, + 38.55863130316872, + 38.25385652507213, + 37.934972214089946, + 37.63300200201469, + 37.3396025668475, + 37.03070272139799, + 36.7277037174502, + 36.43124540575485, + 36.10315588004389, + 35.76046113590517, + 35.41316425324658, + 35.07222237259091, + 34.731873722071725, + 34.387032236592475, + 34.036139478930146, + 33.69462576680907, + 33.35530418497045, + 32.99712842178764, + 32.65920215189999, + 32.333351840655396, + 32.0051779050895, + 31.672771298385804, + 31.345114919508905, + 31.023647925277686, + 30.69561782251355, + 30.372857957424703, + 30.04455318675462, + 29.716530650772686, + 29.376775009459283, + 29.032727437247416, + 28.694625437234627, + 28.349447040615075, + 28.011036457098466, + 27.678311777443966, + 27.340469359712845, + 27.009506139351178, + 26.681481223625706, + 26.35123343731874, + 26.030749965565633, + 25.703695028905464, + 25.3729809368927, + 25.05138638577504, + 24.72510824817708, + 24.39159632548782, + 24.06553639184264, + 23.740206121656943, + 23.40739769660998, + 23.081261657381123, + 22.763948496106984, + 22.434754638579886, + 22.11865931239052, + 21.807961662977746, + 21.4905386192929, + 21.164729629764402, + 20.862205917135583, + 20.557598524940502, + 20.22856773223279, + 19.92575997577919, + 19.6153881903489, + 19.286986859541866, + 18.97106000671142, + 18.65889334937452, + 18.33971068441129, + 18.018534079578565, + 17.705214573794848, + 17.385735385576314, + 17.068365578110665, + 16.757617040072198, + 16.4496460625785, + 16.145614271502176, + 15.843183457518938, + 15.539724258363853, + 15.23081033491441, + 14.928168044593754, + 14.619350352711118, + 14.312415204065331, + 14.004900876356503, + 13.691505397129548, + 13.382761226417156, + 13.072808436633192, + 12.75617255762379, + 12.440687864840086, + 12.126135942931526, + 11.807694599494935, + 11.481563043217621, + 11.160286642289627, + 10.843404375716958, + 10.519724274272413, + 10.197474213686554, + 9.885910478792159, + 9.576727165359841, + 9.255507127598605, + 8.954497568968769, + 8.656825556729501, + 8.35151396705426, + 8.061474395638424, + 7.7724433786617295, + 7.479411741392958, + 7.188095097181444, + 6.89573277042006, + 6.601306178114268, + 6.311113766360433, + 6.012875205586886, + 5.711826949516217, + 5.418867168237042, + 5.11094740753219, + 4.812014104697031, + 4.518557033966874, + 4.21565271665293, + 3.9175057084956775, + 3.6254461948470915, + 3.331545966540914, + 3.0376112132400044, + 2.7496280170382965, + 2.458511058356632, + 2.1776750685582287, + 1.9023324270350852, + 1.6219873136478071, + 1.3515619052253622, + 1.085310220601021, + 0.8132238274266218, + 0.542831482048225, + 0.27315570468110895, + 0.0028421577680153853, + -0.27049276703125885, + -0.5463268248329006, + -0.8262004551646298, + -1.107879395286346, + -1.3916557107149121, + -1.6774387069881023, + -1.9574536540348448, + -2.2414835550731893, + -2.526726733690335, + -2.796098289993876, + -3.0485159716884143, + -3.3022453823800215, + -3.545904518964392, + -3.7680426080445755, + -3.9822654167228353, + -4.182143455408361, + -4.362342772072077, + -4.525006759792942, + -4.667669520894381, + -4.786895394067779, + -4.882482773350822, + -4.9567380382589485, + -5.00760632093183, + -5.033904877646841, + -5.035950736923687, + -5.015924590660966, + -4.977009753510907, + -4.918364667515823, + -4.840335445178749, + -4.7456233965048025, + -4.633561589034956, + -4.505079616704708, + -4.36172030627776, + -4.204324694798168, + -4.036262663020632, + -3.8583288185661546, + -3.6709480583204877, + -3.480061577759506, + -3.282265203079415, + -3.079398118769766, + -2.87609039202851, + -2.6689610642012136, + -2.4603357019972623, + -2.2549151712934425, + -2.0555541820113747, + -1.8414780652124227, + -1.651346634081261, + -1.4682549265943972, + -1.2889642340245302, + -1.113857587858442, + -0.9438890907116492, + -0.7775191634099369, + -0.6157830205941762, + -0.4605198406816952, + -0.30980998000948873, + -0.1681397575337732, + -0.03536969681095837, + 0.0949241979294292, + 0.21648296179149223, + 0.33224419728985344, + 0.44184639524177516, + 0.5530670602380464, + 0.6552431131693358, + 0.7450458870719152, + 0.8349279146221444, + 0.9197564848703558, + 0.9981466064915008, + 1.0757093210853481, + 1.1498858268519423, + 1.2157172484173244, + 1.277918760588237, + 1.3369809429183377, + 1.3913095375182345, + 1.4445619806903216, + 1.4930199416312082, + 1.5353990216939157, + 1.57393914736842, + 1.6094500826339255, + 1.640371474278643, + 1.6681913617370199, + 1.6941189600356357, + 1.7183310280475588, + 1.7415256307133822, + 1.7652994469640837, + 1.7876405491265939, + 1.8093238050473628, + 1.8308054348159348, + 1.8520438795362315, + 1.8748257790396303, + 1.8996520904616516, + 1.9262057756298006, + 1.952449525353578, + 1.979242520411555, + 2.008259301776948, + 2.0384574799230704, + 2.069874562285853, + 2.1033989223984486, + 2.139669610737211, + 2.178847733484213, + 2.2224087485069375, + 2.2704188602062985, + 2.321978765945034, + 2.3805472836395496, + 2.451333063077684, + 2.5204186862095352, + 2.596175004887099, + 2.6769282243746972, + 2.7612674531780805, + 2.850935968758286, + 2.944825825949513, + 3.0466485157760412, + 3.1548488331499427, + 3.2655988413770833, + 3.3841870985236198, + 3.5110067392985895, + 3.6403081450036745, + 3.772111482310876, + 3.91300797460865, + 4.053585243976242, + 4.196203948618943, + 4.346386942022684, + 4.4964075473362435, + 4.6438185147866395, + 4.797364815007405, + 4.957656078701385, + 5.113551060641826, + 5.277450170411978, + 5.447738805582302, + 5.61868728094935, + 5.792274115754509, + 5.970106560387088, + 6.1457914048665065, + 6.3240470581112325, + 6.5038232997804295, + 6.684811613747742, + 6.867542189719006, + 7.0527788657473085, + 7.23832605270834, + 7.4271045363039025, + 7.61488157945303, + 7.803947766682915, + 7.997218280776169, + 8.191109069136724, + 8.386710094937602, + 8.584029781015781, + 8.784563043070957, + 8.98616378095811, + 9.186300524490916, + 9.384675712138709, + 9.58578425900947, + 9.785127603053741, + 9.977131089883029, + 10.17423205860926, + 10.375199026198787, + 10.589069677872354, + 10.787897957613902, + 10.9944989318322, + 11.199313719525836, + 11.40220889785868, + 11.611422327244709, + 11.822203056455006, + 12.028078159659541, + 12.236382887514369, + 12.448917898577703, + 12.656943496096835, + 12.86293268568178, + 13.068496729897587, + 13.273911901456566, + 13.476843235127044, + 13.677405638669933, + 13.880626236854065, + 14.083914035531546, + 14.281469296468464, + 14.477584788810997, + 14.696795871184278, + 14.891196227875946, + 15.082311130722983, + 15.276633135204207, + 15.472227614634006, + 15.667924286693639, + 15.866672791542968, + 16.0723923531363, + 16.277184547378898, + 16.48010689593563, + 16.683861003762978, + 16.89619857368472, + 17.108556511388578, + 17.315968162417718, + 17.539772148344706, + 17.765361978006677, + 17.990712281871108, + 18.21992972308881, + 18.451895868100554, + 18.68826151201862, + 18.9436482275444, + 19.19867073009613, + 19.463662386025156, + 19.730008903195234, + 19.9952377679208, + 20.276325961206325, + 20.541583971021918, + 20.819617418066056, + 21.104824436489302, + 21.38463648974693, + 21.66152259805987, + 21.932805429587546, + 22.199802235368654, + 22.482130779534508, + 22.761252586310977, + 23.03887936669711, + 23.334516634642657, + 23.61941361492147, + 23.911167285421456, + 24.228285841106565, + 24.53476624296535, + 24.855426896910537, + 25.18760203848001, + 25.49634142742295, + 25.802876757165475, + 26.12767599834626, + 26.448340980539754, + 26.758791512708367, + 27.084390931040822, + 27.40786261649449, + 27.731069968144634, + 28.05683599811312, + 28.3814308398038, + 28.702588021869904, + 29.024447450977327, + 29.342072286186745, + 29.65736677249564, + 29.980166530694827, + 30.29936164656833, + 30.609351396683735, + 30.942218991646982, + 31.274985758940357, + 31.59873538561554, + 31.917679388804146, + 32.22637499903647, + 32.53261266046398, + 32.84957140299829, + 33.1537604937998, + 33.45175328611491, + 33.75321001672992, + 34.04505669586066, + 34.3315081975387, + 34.61734665505737, + 34.91373649998367, + 35.20612154712153, + 35.4972385862957, + 35.79638421038561, + 36.10143582856517, + 36.40616431502931, + 36.7166564837261, + 37.03092016042375, + 37.34524010017537, + 37.66244537940462, + 37.98099835555076, + 38.29525213913023, + 38.613917564197976, + 38.93655431141074, + 39.25684937883945, + 39.58090054663728, + 39.908278426885154, + 40.2359741012518, + 40.56312289221807, + 40.89323347893464, + 41.252771217355594, + 41.583297146888995, + 41.90962386932896, + 42.22992667364179, + 42.55172726340942, + 42.86374484428655, + 43.163666724218984, + 43.4657626112107, + 43.76206757207292, + 44.03554399500987, + 44.3155751391994, + 44.59400240126925, + 44.85395319498643, + 45.12284975288024, + 45.39909856508403, + 45.66769236792282, + 45.94006227356499, + 46.21462418755764, + 46.4915005790355, + 46.77438105175335, + 47.04990057016058, + 47.32688896385801, + 47.6175106516778, + 47.90280342864727, + 48.18506541471182, + 48.47461299275151, + 48.761709218167425, + 49.043855530041554, + 49.333408220082184, + 49.624954836179626, + 49.907927570110175, + 50.196870979637715, + 50.49018285919311, + 50.77470018970976, + 51.05728309383378, + 51.33949904509417, + 51.61068049658557, + 51.88334215765688, + 52.153806801541364, + 52.42080888823905, + 52.692224989140016, + 52.96637536516427, + 53.24359290174978, + 53.51893086188829, + 53.799865792365004, + 54.088940690466885, + 54.38145622363204, + 54.67559382248205, + 54.972990652781654, + 55.26971689965987, + 55.567887137864005, + 55.861405261790225, + 56.146119876549264, + 56.43012315788755, + 56.71446933117696, + 56.996859523816624, + 57.26842312183835, + 57.544300551709576, + 57.825632761545144, + 58.10239128015138, + 58.375800451310475, + 58.65452129529378, + 58.93909611047069, + 59.21085667673081, + 59.47113500778839, + 59.740987264165724, + 60.00288489650001, + 60.2411062117452, + 60.489616959428595, + 60.74440561630401, + 60.97948612363302, + 61.20377689502732, + 61.42669067933879, + 61.644217562591095, + 61.84154689449571, + 62.02494818540991, + 62.216494455226645, + 62.40301496814696, + 62.5729062602609, + 62.739733953662665, + 62.90127769126194, + 63.0479087832785, + 63.188862066127065, + 63.32009926727753, + 63.43892000765799, + 63.548062032563706, + 63.64495326883894, + 63.723300638418195, + 63.78756769276339, + 63.83887868470011, + 63.87464820900632, + 63.90015377300029, + 63.91353245152039, + 63.91048662090791, + 63.891427781412744, + 63.85912787946155, + 63.813384867752916, + 63.75416329934468, + 63.67813296736693, + 63.584576370320185, + 63.482783152394894, + 63.36265994441006, + 63.22093511317302, + 63.07142173192214, + 62.90890336399922, + 62.72142432038193, + 62.52867142173112, + 62.323333738872115, + 62.09941765674898, + 61.85980415567179, + 61.61067513099217, + 61.347178835717614, + 61.06974311268001, + 60.78741520466235, + 60.497830705641256, + 60.20279873773858, + 59.89873348432303, + 59.585043621096226, + 59.266936513389, + 58.948489803259854, + 58.621791337080595, + 58.28971966682808, + 57.962389710684064, + 57.62597298102287, + 57.27909752193891, + 56.936167214092045, + 56.599916639903, + 56.26025818730859, + 55.923789485388916, + 55.601350547949295, + 55.27176884837666, + 54.93680527794924, + 54.62045518974739, + 54.296942341618085, + 53.96884906228317, + 53.65506611243988, + 53.33251378359047, + 53.00009929624337, + 52.676468408131186, + 52.34445179465412, + 52.00681219218575, + 51.67495333296684, + 51.34402544088789, + 51.001131750417386, + 50.66352177516216, + 50.328657755750555, + 49.984471850724496, + 49.649447251285785, + 49.319524842901195, + 48.98736591985296, + 48.6577174415375, + 48.32583472324404, + 47.993326969072214, + 47.66618385550341, + 47.33024882085921, + 46.996015374056576, + 46.6625747941048, + 46.3288997901906, + 45.99449743748959, + 45.65820973178802, + 45.32367401442467, + 44.98701469094136, + 44.65087242754459, + 44.3128161997339, + 43.97490572725108, + 43.60540030037656, + 43.2693660002701, + 42.9533266225585, + 42.63806078501144, + 42.32052615358233, + 42.0095836811218, + 41.693147034220765, + 41.37030589200015, + 41.056625342652836, + 40.74007253894454, + 40.40955698480483, + 40.07238619335842, + 39.73983985942109, + 39.39260096861668, + 39.029058991457305, + 38.68573293410243, + 38.33982956594653, + 37.9793949940433, + 37.63018870182943, + 37.29310655753665, + 36.95160633019749, + 36.60880867832948, + 36.293045043930555, + 35.97320318330131, + 35.65843250820487, + 35.34143487093785, + 35.023269264007865, + 34.71491328954702, + 34.404730125534805, + 34.08880522075607, + 33.77287508607854, + 33.464978895564755, + 33.13532789499079, + 32.79521185152687, + 32.470538905825705, + 32.142421903556844, + 31.816023894313595, + 31.489715051373466, + 31.162633798062817, + 30.844728987655056, + 30.520512393006193, + 30.200186095790748, + 29.874214475069444, + 29.546783390008734, + 29.22024519972762, + 28.88660565295937, + 28.556615940743562, + 28.225122145310184, + 27.887892089126876, + 27.55833359518771, + 27.225281584961564, + 26.880269079369786, + 26.546483679129313, + 26.211752975406316, + 25.872264985783026, + 25.54079640197197, + 25.206617009471472, + 24.87929742152391, + 24.54970022173698, + 24.21830077512884, + 23.89078380024956, + 23.55858934148418, + 23.229282320037715, + 22.90869003444346, + 22.582503646843886, + 22.259829266745648, + 21.951962768662916, + 21.636761446826245, + 21.325235204922894, + 21.027892349667027, + 20.71510396184291, + 20.400388442243187, + 20.10406009212683, + 19.788973839438082, + 19.465898738205222, + 19.16521682464404, + 18.853977589852196, + 18.533844973163838, + 18.225560236998408, + 17.916390066821002, + 17.593149552008764, + 17.279735159101676, + 16.96738557844563, + 16.61353796299852, + 16.300786009462797, + 15.993030516912416, + 15.681375942368238, + 15.370879265711897, + 15.064397930064088, + 14.749228817483711, + 14.439039644775507, + 14.124585889320837, + 13.804131998714254, + 13.481147050734426, + 13.157733911860888, + 12.834151570500785, + 12.505922526550986, + 12.175900497336459, + 11.84838349465872, + 11.519249127080254, + 11.185757644129255, + 10.852782421353982, + 10.525000382206137, + 10.192836056464515, + 9.866128307061684, + 9.542051026352523, + 9.217309348473334, + 8.895321172734855, + 8.578402333638502, + 8.26170217041076, + 7.939481330769564, + 7.627377744402807, + 7.3177884251394145, + 7.010961355341202, + 6.70668843031132, + 6.403785089924659, + 6.10947597925163, + 5.814662071230183, + 5.519360755593465, + 5.225755566271759, + 4.941538545824498, + 4.654884637718361, + 4.38037694029395, + 4.120549845484478, + 3.8539538181153965, + 3.579046402777778, + 3.313308735996936, + 3.0528396543980385, + 2.7771352753989516, + 2.50866923525166, + 2.2483543666163492, + 1.9711689430605315, + 1.6920598186618878, + 1.418285367364076, + 1.1352485535177619, + 0.8652150394627393, + 0.5996267110920918, + 0.3251281950151414, + 0.053165143872573595, + -0.2163908265782503, + -0.4892134221579513, + -0.754967675341181, + -1.016081762235151, + -1.2804261208534857, + -1.5432177157655607, + -1.8140142664177707, + -2.0899060194822106, + -2.36329393983016, + -2.6378118023299026, + -2.915525029592267, + -3.1890168242133385, + -3.454539702908877, + -3.7163576609103215, + -3.975675678123687, + -4.2169925406172375, + -4.442689768247701, + -4.658572553725139, + -4.852573105338675, + -5.030485206627612, + -5.190462235832259, + -5.3259049753047725, + -5.443858062965672, + -5.538424480407576, + -5.609667089114421, + -5.66232695645199, + -5.694878036607654, + -5.704945724777047, + -5.694117560591922, + -5.664957132654981, + -5.619711295630675, + -5.556593805077401, + -5.475222126440451, + -5.379112331432588, + -5.267802947825157, + -5.141050971444225, + -5.0015617749878665, + -4.8494632509374025, + -4.687618016712599, + -4.517439685474579, + -4.338229332376084, + -4.153840410571848, + -3.9630722745112554, + -3.762739198445909, + -3.559114993832612, + -3.354593878788111, + -3.1470325361190508, + -2.9382350311469287, + -2.7327155931539, + -2.5306624485787, + -2.328507542270429, + -2.132728645912017, + -1.9398885568742124, + -1.7454978122007605, + -1.5582439754376392, + -1.3742513527750697, + -1.1958249393208156, + -1.0243365165770353, + -0.8596568349141067, + -0.7045010362854772, + -0.5612043749577209, + -0.4213395870413378, + -0.29265799824540595, + -0.1747140709160461, + -0.06427383575028402, + 0.04523888440500598, + 0.1470176048847739, + 0.2335592457807787, + 0.31806725376161676, + 0.39725495085779616, + 0.4688920850625567, + 0.5378993094566618, + 0.6042473556930033, + 0.6626326850149867, + 0.7166694726914491, + 0.7682639322389797, + 0.8145747696512449, + 0.8593962881678019, + 0.902068632543713, + 0.9396647149657125, + 0.9750302682532217, + 1.0078196208749777, + 1.0370968429022625, + 1.0632475635657515, + 1.0885355014874818, + 1.1129560030203436, + 1.1368010358379101, + 1.1616439975988324, + 1.185384436834196, + 1.2084431698441171, + 1.231475823346499, + 1.254762415104005, + 1.279003680873743, + 1.304490645361735, + 1.3321634619381912, + 1.3605681174269533, + 1.3892327278655954, + 1.4186765175872023, + 1.449830915578756, + 1.481366538781976, + 1.5139104799467373, + 1.5476033220878807, + 1.583263999062211, + 1.6211933233438354, + 1.6631383793633245, + 1.7085112718607305, + 1.7566245083624843, + 1.8106609482744596, + 1.8701071709030277, + 1.9325622125965751, + 2.000600405276433, + 2.073073719730457, + 2.1487545459062662, + 2.229233110974539, + 2.314248791055779, + 2.404061883807194, + 2.503093932077756, + 2.605972973079022, + 2.713395029001061, + 2.8296484655673715, + 2.9507293024997834, + 3.073381872513424, + 3.202339794245352, + 3.337032920952903, + 3.4721955709684758, + 3.6149854181753436, + 3.7636729912526707, + 3.910178150042658, + 4.058923070848974, + 4.21475164808327, + 4.3719460968550985, + 4.529731913673303, + 4.699013206401141, + 4.872421310561653, + 5.046968437777668, + 5.229006277495889, + 5.409705435527416, + 5.593652208359495, + 5.782655045033461, + 5.973170236368014, + 6.165235802080729, + 6.362082629896817, + 6.559839729215012, + 6.758378728278356, + 6.955605431440671, + 7.152684060701755, + 7.354195314330586, + 7.556177350072287, + 7.757156526317015, + 7.961187881364418, + 8.169003680971045, + 8.377459379121646, + 8.581252383706312, + 8.781756769247409, + 8.98448890738033, + 9.185323285345376, + 9.377647316277997, + 9.574631679098811, + 9.77453789199406, + 9.968845107737579, + 10.165648840966393, + 10.369614482872768, + 10.576969644898908, + 10.796436682491988, + 11.021275163606756, + 11.246864619549918, + 11.468880277362299, + 11.693590573508914, + 11.92143585618974, + 12.146513612658033, + 12.371844212598857, + 12.598693790863255, + 12.822096235578423, + 13.035439877280268, + 13.247246640349253, + 13.460973546419812, + 13.67818491273366, + 13.889488252801932, + 14.09869730671219, + 14.310534066599072, + 14.517203507884803, + 14.719377674133092, + 14.91959255573849, + 15.11129102371526, + 15.302603365919937, + 15.497272166423574, + 15.698383337483369, + 15.900379833012433, + 16.10047374125098, + 16.301025074430772, + 16.509151973958257, + 16.746694732657037, + 16.953910521678782, + 17.177209192109522, + 17.41215293423783, + 17.64433768572708, + 17.877133390770577, + 18.119552844386924, + 18.364348477256137, + 18.615503268685643, + 18.86396729684635, + 19.119776393134917, + 19.387481743891833, + 19.65799693723779, + 19.97138913535241, + 20.252628616256146, + 20.53972116370472, + 20.864599743802877, + 21.167491705195776, + 21.479459035401458, + 21.794086367754364, + 22.11399182898066, + 22.431454120196182, + 22.750859270112684, + 23.08280638027464, + 23.40683337366142, + 23.752317076511204, + 24.111574288181092, + 24.463440793015387, + 24.83238042227069, + 25.195968103920862, + 25.539312503153802, + 25.893310860662872, + 26.24369925261043, + 26.582267823747525, + 26.934328990924996, + 27.28588487239649, + 27.621442569502996, + 27.960117425471747, + 28.303818723395178, + 28.635159948539933, + 28.96563663478973, + 29.302293916387427, + 29.63502560679554, + 29.971363294207848, + 30.29806216363941, + 30.627519894388662, + 30.96068694316108, + 31.294987541140635, + 31.623092608346326, + 31.944797115786923, + 32.27409768959656, + 32.592069090265866, + 32.89812328844543, + 33.2033668790907, + 33.50553426591979, + 33.80315270375641, + 34.10199116335442, + 34.40374116129653, + 34.70037769128913, + 34.99930901872234, + 35.3027502455714, + 35.61019483415942, + 35.91778870110349, + 36.23177032401961, + 36.549318572671865, + 36.86447146895361, + 37.18297074853924, + 37.50051483488108, + 37.812978772462074, + 38.12853715955711, + 38.44735728290711, + 38.761536901895255, + 39.07845222453753, + 39.398809727184464, + 39.71473270566849, + 40.029760352806896, + 40.34504792610765, + 40.656417875372846, + 40.968938220175374, + 41.28462245556623, + 41.595517406598056, + 41.9094211795519, + 42.22432579850013, + 42.533473369050185, + 42.8382291810717, + 43.149608904374205, + 43.451222239978314, + 43.7461698096567, + 44.055228739426425, + 44.3520907788295, + 44.64503373770526, + 44.950728556177175, + 45.24935317712527, + 45.54098436312996, + 45.842943558877685, + 46.14755303458895, + 46.443326146505704, + 46.73854919902926, + 47.04786138192352, + 47.35185725399669, + 47.6496011629088, + 47.95643597017896, + 48.26021279372815, + 48.5526815219461, + 48.85167784575071, + 49.15353998314599, + 49.44431352175967, + 49.73911939311548, + 50.03882848645932, + 50.32720195041783, + 50.61033855379421, + 50.89366193587728, + 51.167884941565404, + 51.442476792158224, + 51.70740478669174, + 51.97455183959459, + 52.2424372398762, + 52.50955159749591, + 52.7824441181921, + 53.051639281404725, + 53.324425481435284, + 53.60486635010587, + 53.88963555239475, + 54.17262292819129, + 54.4593666694105, + 54.746556348026466, + 55.0305015067513, + 55.31720677899201, + 55.59453917403792, + 55.86299504245453, + 56.15888068132426, + 56.43126106967637, + 56.689559026047526, + 56.94065230347727, + 57.20232586978722, + 57.46099179998578, + 57.716605912095446, + 57.9667704481623, + 58.22562514258538, + 58.48279049995408, + 58.73193463906139, + 58.97679471021057, + 59.231726255130766, + 59.48618960316225, + 59.72657914780032, + 59.97475629090222, + 60.23213442959812, + 60.47564590161082, + 60.7049426999666, + 60.93445010429704, + 61.16012701900658, + 61.3628146677447, + 61.550008156074576, + 61.74411336584359, + 61.93120147403796, + 62.101802479904414, + 62.270331330755454, + 62.43413388237453, + 62.58517546562002, + 62.73057604318588, + 62.8658714391403, + 62.989543574071305, + 63.103099285653244, + 63.20404152139367, + 63.28437587397921, + 63.34853626378916, + 63.39811140601858, + 63.43054360930116, + 63.45097372267109, + 63.4567870942156, + 63.4447036226012, + 63.415166511477636, + 63.37023820702246, + 63.31125332955198, + 63.23868736126066, + 63.14754852230307, + 63.03907964589805, + 62.92303318853251, + 62.78694141392481, + 62.63013965343733, + 62.47033102323899, + 62.291344581506586, + 62.09359031103882, + 61.89338210735949, + 61.68071930303039, + 61.44532632829423, + 61.203398502780615, + 60.956911902839714, + 60.69511980115445, + 60.42411300080536, + 60.151264974959936, + 59.874515231224194, + 59.597389428236895, + 59.31315620970049, + 59.021405078511236, + 58.73348260878832, + 58.44388700203228, + 58.14274849214298, + 57.845826988627806, + 57.547992367501905, + 57.23870777395376, + 56.928117561617285, + 56.62382853069168, + 56.31482853049869, + 55.990849826911465, + 55.683937631249485, + 55.379659002614254, + 55.05940881942585, + 54.7478383274686, + 54.446228891852904, + 54.12854095685096, + 53.81675817839018, + 53.51092358754183, + 53.191921350580614, + 52.874242507329065, + 52.560490915928355, + 52.23665547370583, + 51.9077213338404, + 51.586335427714964, + 51.25869299864215, + 50.92217315579611, + 50.58992709820675, + 50.25454632426013, + 49.91197629794347, + 49.57380078223236, + 49.237340611949016, + 48.898109266487566, + 48.561150029770815, + 48.217675361077035, + 47.8814988613294, + 47.538440549060454, + 47.193064510530945, + 46.84970730673195, + 46.50781183219243, + 46.16979702769043, + 45.82343644077698, + 45.479765835147404, + 45.13888378364644, + 44.79218792981562, + 44.44490713561993, + 44.0988326524609, + 43.75639413298596, + 43.405006335112816, + 43.055527911170955, + 42.7086224383385, + 42.35636752516571, + 42.01094060050921, + 41.66224869226204, + 41.30453120325186, + 40.955322427633995, + 40.606122509777826, + 40.23671831132266, + 39.87349021139226, + 39.5275216361299, + 39.15532054602195, + 38.7817917199122, + 38.42861344698394, + 38.061284715268485, + 37.68275186248695, + 37.327194044766365, + 36.97288601560147, + 36.59687620499849, + 36.23856852027886, + 35.88109543832795, + 35.51698266869542, + 35.151454114699064, + 34.794316267355306, + 34.437446570826715, + 34.0771206780121, + 33.71134847630277, + 33.35259399364076, + 33.003896861735065, + 32.640723827922415, + 32.28507059277639, + 31.936035330965904, + 31.586702433075484, + 31.22925195912165, + 30.88262143045321, + 30.53913232170126, + 30.188714527696792, + 29.840928928588454, + 29.48492688340245, + 29.125366374489975, + 28.76159707627873, + 28.402096387015956, + 28.04029167738964, + 27.677618347007837, + 27.324717705275482, + 26.96516969116016, + 26.60742238152953, + 26.25813582849179, + 25.940644512843257, + 25.64412781515667, + 25.348022830332283, + 25.054248705830318, + 24.762940172729472, + 24.474128236011488, + 24.183142438830497, + 23.889583459808744, + 23.60377062481296, + 23.31867446763228, + 23.00573403717028, + 22.69543862677699, + 22.38831817031561, + 22.07397291674327, + 21.77221620303394, + 21.474625655377526, + 21.159855111507262, + 20.860472983457548, + 20.57213799635636, + 20.259065357779058, + 19.974570675468115, + 19.717712944410955, + 19.440432089622206, + 19.16813345630301, + 18.908419499224287, + 18.64000437675221, + 18.36595897269595, + 18.101705674415747, + 17.836092414791384, + 17.56766658637108, + 17.29630341598981, + 17.025696047063235, + 16.75357804943685, + 16.481298915640618, + 16.21239540766006, + 15.937971120749795, + 15.666811668372599, + 15.391689270983614, + 15.117745913680936, + 14.848566220763917, + 14.540019487081059, + 14.222796660348196, + 13.903347266645358, + 13.579127085268404, + 13.257103352453145, + 12.937332081227593, + 12.61581250883567, + 12.287693670984922, + 11.954463566316953, + 11.631394681600423, + 11.329342568479117, + 11.031985211164129, + 10.737523628601888, + 10.45177322208383, + 10.159690898535434, + 9.86528611566276, + 9.585463943766001, + 9.302510829422065, + 9.018771681351822, + 8.740721821328417, + 8.451412847625747, + 8.16055976991773, + 7.940739885595652, + 7.649689547274853, + 7.355041201225335, + 7.073086663607159, + 6.781403498982336, + 6.480975198189406, + 6.193000995912802, + 5.894118683471748, + 5.604056865569893, + 5.33068637775697, + 5.0487330235721695, + 4.759880363605886, + 4.478298131655137, + 4.196421392600951, + 3.905844195969257, + 3.622675096119216, + 3.3335103833622286, + 3.0471742784361973, + 2.7719845417630884, + 2.487867692040898, + 2.2085807352402806, + 1.9386381623244573, + 1.6696997892504515, + 1.4008923722223003, + 1.1325338854488094, + 0.8698931640746329, + 0.6058550815292704, + 0.34178591209782944, + 0.07667844538865048, + -0.19026593451683016, + -0.4554406244379945, + -0.7270459916318173, + -0.9993729438317401, + -1.2657127999327225, + -1.5359056209694093, + -1.80910351197689, + -2.0707859508561195, + -2.3171929634210486, + -2.57303096028214, + -2.8298091729269363, + -3.06656586192069, + -3.2899355731611752, + -3.5058629323482395, + -3.7002218758350507, + -3.8799659060810683, + -4.044154401469258, + -4.188005818183804, + -4.3152184885170035, + -4.431354366367503, + -4.514703010052084, + -4.582047960812328, + -4.631528872229713, + -4.660910020821575, + -4.6708403048030105, + -4.662449926632847, + -4.637595003710751, + -4.596236011176684, + -4.537947385026952, + -4.376888542703274, + -4.288209726394857, + -4.18429492589649, + -4.066784639944364, + -3.9387904539825316, + -3.799571967547997, + -3.653433657150335, + -3.501583167393676, + -3.3401169800524984, + -3.1744481619690124, + -3.0052437357619475, + -2.829155463434466, + -2.6527959456576737, + -2.475772365932245, + -2.2955140655935677, + -2.1163822744969565, + -1.9392996466493302, + -1.7651734640595305, + -1.5942498473022266, + -1.4247547430679854, + -1.2604125493983682, + -1.1006254540448448, + -0.9428929999493842, + -0.7885739354253732, + -0.6394382491121076, + -0.49422949338813715, + -0.3547025436789347, + -0.2220377492865131, + -0.09497282596831103, + 0.021735167796699595, + 0.13285858280024343, + 0.24087676995385654, + 0.33923224114094186, + 0.4329200110885978, + 0.5201430763632404, + 0.6076261201085276, + 0.6879757431943925, + 0.7578119823986187, + 0.8269555418893362, + 0.8913029716133205, + 0.9503621390414663, + 1.0076633251910367, + 1.0619069384761641, + 1.1108600056309395, + 1.154451832954652, + 1.1949563456065757, + 1.2306989835976558, + 1.2636346948814599, + 1.2938187560504752, + 1.3188102651418132, + 1.3400979295708186, + 1.3587029727938362, + 1.3736961944225057, + 1.3874170183239944, + 1.4002813212691323, + 1.413864282540611, + 1.428639923213225, + 1.4439159929580396, + 1.4588185530447295, + 1.4716824922168787, + 1.4835117408193126, + 1.4944732530514964, + 1.505037309620955, + 1.5159365970329328, + 1.5279182777271618, + 1.5710227590004497, + 1.585487163567568, + 1.601561593277515, + 1.6191296376214352, + 1.6392118118171357, + 1.661332817227168, + 1.683818426776412, + 1.7097134479140736, + 1.7383053758480917, + 1.7712132265080818, + 1.8082864177801734, + 1.8495958259515872, + 1.8971048618132835, + 1.9495414443591164, + 2.0089977824310385, + 2.0774488692880864, + 2.152719910738682, + 2.238964543324992, + 2.334237456808289, + 2.4368837415056133, + 2.548951046986737, + 2.6712010864801186, + 2.804199387424994, + 2.9489350548037434, + 3.104840352919012, + 3.2696446307951232, + 3.449537370291477, + 3.6422762528119206, + 3.844964818735719, + 4.064028170637739, + 4.296194383137763, + 4.536128453129303, + 4.780515740575605, + 5.068595331826337, + 5.339755000188887, + 5.614200312412775, + 5.903984607704475, + 6.204051350614986, + 6.502448630503951, + 6.810922050815234, + 7.129056537553518, + 7.449288520433644, + 7.773967266604292, + 8.107895570113833, + 8.446125235123965, + 8.788662654274459, + 9.13733022137939, + 9.492647484169803, + 9.849955649461563, + 10.21254506524584, + 10.577595066343726, + 10.945159109465557, + 11.317011962849532, + 11.695576288011447, + 12.073581835360525, + 12.45651816101892, + 12.83768461737093, + 13.225855182239112, + 13.6045467550301, + 13.982960369263015, + 14.37046998740073, + 14.753653591504062, + 15.128301092639678, + 15.48333670659692, + 15.866854354862518, + 16.245350633101292, + 16.624730674923363, + 17.001686838803085, + 17.37919471421535, + 17.740406988155204, + 18.101336461510847, + 18.468215679311406, + 18.82581382576176, + 19.18161067675971, + 19.535407199454607, + 19.884345087594586, + 20.228653998324123, + 20.548386356183464, + 20.865869997294162, + 21.16885830062872, + 21.444246808429096, + 21.723230991549734, + 21.981530352651177, + 22.224328239948395, + 22.46410538987838, + 22.682047779183893, + 22.87564032840609, + 23.07241333225752, + 23.249333466160344, + 23.402534058412485, + 23.554669446076673, + 23.689115788959498, + 23.803609375044548, + 23.914176643879845, + 24.00819998804275, + 24.090429572476623, + 24.15856535870222, + 24.21198547003588, + 24.258824715173773, + 24.299506484657044, + 24.333927203988285, + 24.36638965023104, + 24.3987771413772, + 24.4317546647794, + 24.463807479798007, + 24.47374998174773, + 24.482187505217095, + 24.489667268472083, + 24.497212999751582, + 24.50380722017657, + 24.50955393584218, + 24.515152386071996, + 24.520318624688684, + 24.5248045628062, + 24.52850286369933, + 24.562741464181546, + 24.600868556033113, + 24.639572183517366, + 24.678999202340567, + 24.71910268613251, + 24.752167541806834, + 24.79364139014063, + 24.835708363767267, + 24.87896621837055, + 24.9232279506598, + 24.934048566691608, + 24.94107921159258, + 24.948355187402903, + 24.955586820345676, + 24.962806447321853, + 24.97021256670934, + 24.977547770122076, + 24.98494706269543, + 24.99242952739627, + 24.99994437339902, + 25.02540271299319, + 25.052916655074828, + 25.08056116530959, + 25.108168293242098, + 25.135808603887792, + 25.163485883998344, + 25.19115746111873, + 25.218876122759994, + 25.24661949756898, + 25.274470489049747, + 25.284313636520654, + 25.292359845297213, + 25.30049146549067, + 25.308518479646892, + 25.316455103602966, + 25.32458102322264, + 25.332738211605577, + 25.340816196491332, + 25.349086424508247, + 25.357295176651835, + 25.403074324577638, + 25.45374928722011, + 25.504408168173335, + 25.55487276861665, + 25.605032335771533, + 25.655136174273608, + 25.705378138595986, + 25.755388975120873, + 25.80516652331133, + 25.855482764168823, + 25.866115316851094, + 25.872209004406198, + 25.87815187371181, + 25.88382182578971, + 25.889485629453922, + 25.895124265033186, + 25.900828708697823, + 25.907149898069797, + 25.912957769240567, + 25.91864769467925, + 25.920183502332854, + 25.921636104878875, + 25.922860010393627, + 25.92409529747196, + 25.925571771507055, + 25.92699075098118, + 25.928285237895963, + 25.929639765365053 ], "yaxis": "y" }, @@ -8514,16 +8524,16 @@ "showlegend": false, "type": "scatter", "x": [ - -36.829195933875525, - -76.14891175101936, - -3.5940645335563204, - -34.912059375843626 + -35.97329684506414, + -75.10034519689322, + -1.038764248227812, + -36.0892694400111 ], "y": [ - 26.43059833243257, - 22.861480398725924, - -13.507485368311604, - 72.42462600701336 + 26.316580859038513, + 21.011440906439965, + -12.138119313965529, + 72.35004639855165 ] } ], @@ -9393,19 +9403,19 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 60, "metadata": {}, "outputs": [ { "data": { "text/plain": [ - "array([[-36.82919593, 26.43059833],\n", - " [-76.14891175, 22.8614804 ],\n", - " [ -3.59406453, -13.50748537],\n", - " [-34.91205938, 72.42462601]])" + "array([[-35.97329685, 26.31658086],\n", + " [-75.1003452 , 21.01144091],\n", + " [ -1.03876425, -12.13811931],\n", + " [-36.08926944, 72.3500464 ]])" ] }, - "execution_count": 11, + "execution_count": 60, "metadata": {}, "output_type": "execute_result" } From e2bc0fac6b4e2164a991128b8a73399ab9acb902 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 19 Mar 2022 19:50:30 -0400 Subject: [PATCH 093/116] add test demonstrating apply does not enumerate all leaves --- gtsam/discrete/DecisionTree-inl.h | 1 - gtsam/discrete/tests/testDecisionTree.cpp | 14 ++++++++++++-- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 3f82ce9a6..0ebfc86bc 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -786,7 +786,6 @@ namespace gtsam { template DecisionTree DecisionTree::apply( const UnaryAssignment& op) const { - std::cout << "Calling the correct apply" << std::endl; // It is unclear what should happen if tree is empty: if (empty()) { throw std::runtime_error( diff --git a/gtsam/discrete/tests/testDecisionTree.cpp b/gtsam/discrete/tests/testDecisionTree.cpp index 935d433c6..f234905e3 100644 --- a/gtsam/discrete/tests/testDecisionTree.cpp +++ b/gtsam/discrete/tests/testDecisionTree.cpp @@ -462,7 +462,7 @@ TEST(DecisionTree, ApplyWithAssignment) { DecisionTree probTree( keys, "0.01 0.02 0.03 0.04 0.05 0.06 0.07 0.08"); - double threshold = 0.035; + double threshold = 0.045; // We test pruning one tree by indexing into another. auto pruner = [&](const Assignment& choices, const int& x) { @@ -475,8 +475,18 @@ TEST(DecisionTree, ApplyWithAssignment) { }; DT prunedTree = tree.apply(pruner); - DT expectedTree(keys, "0 0 0 4 5 6 7 8"); + DT expectedTree(keys, "0 0 0 0 5 6 7 8"); EXPECT(assert_equal(expectedTree, prunedTree)); + + size_t count = 0; + auto counter = [&](const Assignment& choices, const int& x) { + count += 1; + return x; + }; + DT prunedTree2 = prunedTree.apply(counter); + + // Check if apply doesn't enumerate all leaves. + EXPECT_LONGS_EQUAL(5, count); } /* ************************************************************************* */ From 7b9dc5735ba1d10063f5ef6ce4bb0ae644bc75d0 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 19 Mar 2022 19:51:23 -0400 Subject: [PATCH 094/116] remove unnecessary using --- gtsam/sfm/SfmData.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/sfm/SfmData.cpp b/gtsam/sfm/SfmData.cpp index 43b1f5911..6c2676e48 100644 --- a/gtsam/sfm/SfmData.cpp +++ b/gtsam/sfm/SfmData.cpp @@ -426,7 +426,6 @@ NonlinearFactorGraph SfmData::generalSfmFactors( NonlinearFactorGraph SfmData::sfmFactorGraph( const SharedNoiseModel &model, boost::optional fixedCamera, boost::optional fixedPoint) const { - using ProjectionFactor = GeneralSFMFactor; NonlinearFactorGraph graph = generalSfmFactors(model); using noiseModel::Constrained; if (fixedCamera) { From 8c55ac729b944613886014436164a20fa5910f2c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 19 Mar 2022 19:51:59 -0400 Subject: [PATCH 095/116] check for mac silicon for march=native --- cmake/GtsamBuildTypes.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index fac2bdba5..9058807ad 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -191,7 +191,7 @@ endif() if (NOT MSVC) option(GTSAM_BUILD_WITH_MARCH_NATIVE "Enable/Disable building with all instructions supported by native architecture (binary may not be portable!)" ON) - if(GTSAM_BUILD_WITH_MARCH_NATIVE) + if(GTSAM_BUILD_WITH_MARCH_NATIVE AND (APPLE AND NOT CMAKE_SYSTEM_PROCESSOR STREQUAL "arm64")) # Add as public flag so all dependant projects also use it, as required # by Eigen to avid crashes due to SIMD vectorization: list_append_cache(GTSAM_COMPILE_OPTIONS_PUBLIC "-march=native") From f8abd44615936f41b09d0bbcd9c7a0b3233b31e3 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 20 Mar 2022 13:23:34 -0400 Subject: [PATCH 096/116] Added spaces back --- gtsam/linear/NoiseModel.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index cf10cf115..8bcef6fcc 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -134,7 +134,7 @@ Gaussian::shared_ptr Gaussian::Covariance(const Matrix& covariance, /* ************************************************************************* */ void Gaussian::print(const string& name) const { - gtsam::print(thisR(), name + "Gaussian"); + gtsam::print(thisR(), name + "Gaussian "); } /* ************************************************************************* */ @@ -285,7 +285,7 @@ Diagonal::shared_ptr Diagonal::Sigmas(const Vector& sigmas, bool smart) { /* ************************************************************************* */ void Diagonal::print(const string& name) const { - gtsam::print(sigmas_, name + "diagonal sigmas"); + gtsam::print(sigmas_, name + "diagonal sigmas "); } /* ************************************************************************* */ @@ -355,8 +355,8 @@ bool Constrained::constrained(size_t i) const { /* ************************************************************************* */ void Constrained::print(const std::string& name) const { - gtsam::print(sigmas_, name + "constrained sigmas"); - gtsam::print(mu_, name + "constrained mu"); + gtsam::print(sigmas_, name + "constrained sigmas "); + gtsam::print(mu_, name + "constrained mu "); } /* ************************************************************************* */ From bf8fa75163bd17fb1769e3b2057c7d6fa625ec0e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 20 Mar 2022 13:24:15 -0400 Subject: [PATCH 097/116] Updated everything up to and including custom factor, including more explanation about H --- doc/Code/LocalizationExample2.cpp | 8 +- doc/Code/LocalizationFactor.cpp | 7 +- doc/Code/OdometryExample.cpp | 8 +- doc/Code/OdometryOutput1.txt | 17 +-- doc/Code/OdometryOutput2.txt | 24 +++-- doc/Code/OdometryOutput3.txt | 18 ++-- doc/gtsam.lyx | 168 +++++++++++++++++++++++------- doc/gtsam.pdf | Bin 825916 -> 1620931 bytes 8 files changed, 176 insertions(+), 74 deletions(-) diff --git a/doc/Code/LocalizationExample2.cpp b/doc/Code/LocalizationExample2.cpp index d22180314..df9469a64 100644 --- a/doc/Code/LocalizationExample2.cpp +++ b/doc/Code/LocalizationExample2.cpp @@ -1,7 +1,7 @@ // add unary measurement factors, like GPS, on all three poses -noiseModel::Diagonal::shared_ptr unaryNoise = +auto unaryNoise = noiseModel::Diagonal::Sigmas(Vector2(0.1, 0.1)); // 10cm std on x,y -graph.add(boost::make_shared(1, 0.0, 0.0, unaryNoise)); -graph.add(boost::make_shared(2, 2.0, 0.0, unaryNoise)); -graph.add(boost::make_shared(3, 4.0, 0.0, unaryNoise)); +graph.emplace_shared(1, 0.0, 0.0, unaryNoise); +graph.emplace_shared(2, 2.0, 0.0, unaryNoise); +graph.emplace_shared(3, 4.0, 0.0, unaryNoise); diff --git a/doc/Code/LocalizationFactor.cpp b/doc/Code/LocalizationFactor.cpp index d298091dc..2c1f01c43 100644 --- a/doc/Code/LocalizationFactor.cpp +++ b/doc/Code/LocalizationFactor.cpp @@ -1,13 +1,12 @@ class UnaryFactor: public NoiseModelFactor1 { double mx_, my_; ///< X and Y measurements - + public: UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): NoiseModelFactor1(model, j), mx_(x), my_(y) {} - Vector evaluateError(const Pose2& q, - boost::optional H = boost::none) const - { + Vector evaluateError(const Pose2& q, + boost::optional H = boost::none) const override { const Rot2& R = q.rotation(); if (H) (*H) = (gtsam::Matrix(2, 3) << R.c(), -R.s(), 0.0, diff --git a/doc/Code/OdometryExample.cpp b/doc/Code/OdometryExample.cpp index 2befa9dc2..7af27c60c 100644 --- a/doc/Code/OdometryExample.cpp +++ b/doc/Code/OdometryExample.cpp @@ -3,13 +3,11 @@ NonlinearFactorGraph graph; // Add a Gaussian prior on pose x_1 Pose2 priorMean(0.0, 0.0, 0.0); -noiseModel::Diagonal::shared_ptr priorNoise = - noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); -graph.addPrior(1, priorMean, priorNoise); +auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); +graph.add(PriorFactor(1, priorMean, priorNoise)); // Add two odometry factors Pose2 odometry(2.0, 0.0, 0.0); -noiseModel::Diagonal::shared_ptr odometryNoise = - noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); +auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); graph.add(BetweenFactor(1, 2, odometry, odometryNoise)); graph.add(BetweenFactor(2, 3, odometry, odometryNoise)); diff --git a/doc/Code/OdometryOutput1.txt b/doc/Code/OdometryOutput1.txt index cc34e8ef2..70aba38ee 100644 --- a/doc/Code/OdometryOutput1.txt +++ b/doc/Code/OdometryOutput1.txt @@ -1,11 +1,14 @@ Factor Graph: size: 3 -factor 0: PriorFactor on 1 - prior mean: (0, 0, 0) + +Factor 0: PriorFactor on 1 + prior mean: (0, 0, 0) noise model: diagonal sigmas [0.3; 0.3; 0.1]; -factor 1: BetweenFactor(1,2) - measured: (2, 0, 0) - noise model: diagonal sigmas [0.2; 0.2; 0.1]; -factor 2: BetweenFactor(2,3) - measured: (2, 0, 0) + +Factor 1: BetweenFactor(1,2) + measured: (2, 0, 0) noise model: diagonal sigmas [0.2; 0.2; 0.1]; + +Factor 2: BetweenFactor(2,3) + measured: (2, 0, 0) + noise model: diagonal sigmas [0.2; 0.2; 0.1]; \ No newline at end of file diff --git a/doc/Code/OdometryOutput2.txt b/doc/Code/OdometryOutput2.txt index acfa0b95d..6567bea6c 100644 --- a/doc/Code/OdometryOutput2.txt +++ b/doc/Code/OdometryOutput2.txt @@ -1,11 +1,23 @@ Initial Estimate: + Values with 3 values: -Value 1: (0.5, 0, 0.2) -Value 2: (2.3, 0.1, -0.2) -Value 3: (4.1, 0.1, 0.1) +Value 1: (gtsam::Pose2) +(0.5, 0, 0.2) + +Value 2: (gtsam::Pose2) +(2.3, 0.1, -0.2) + +Value 3: (gtsam::Pose2) +(4.1, 0.1, 0.1) Final Result: + Values with 3 values: -Value 1: (-1.8e-16, 8.7e-18, -9.1e-19) -Value 2: (2, 7.4e-18, -2.5e-18) -Value 3: (4, -1.8e-18, -3.1e-18) +Value 1: (gtsam::Pose2) +(7.5-16, -5.3-16, -1.8-16) + +Value 2: (gtsam::Pose2) +(2, -1.1-15, -2.5-16) + +Value 3: (gtsam::Pose2) +(4, -1.7-15, -2.5-16) diff --git a/doc/Code/OdometryOutput3.txt b/doc/Code/OdometryOutput3.txt index e346ccb4d..514d804cd 100644 --- a/doc/Code/OdometryOutput3.txt +++ b/doc/Code/OdometryOutput3.txt @@ -1,12 +1,12 @@ x1 covariance: - 0.09 1.1e-47 5.7e-33 - 1.1e-47 0.09 1.9e-17 - 5.7e-33 1.9e-17 0.01 + 0.09 1.7e-33 2.8e-33 +1.7e-33 0.09 2.6e-17 +2.8e-33 2.6e-17 0.01 x2 covariance: - 0.13 4.7e-18 2.4e-18 - 4.7e-18 0.17 0.02 - 2.4e-18 0.02 0.02 + 0.13 1.2e-18 6.1e-19 +1.2e-18 0.17 0.02 +6.1e-19 0.02 0.02 x3 covariance: - 0.17 2.7e-17 8.4e-18 - 2.7e-17 0.37 0.06 - 8.4e-18 0.06 0.03 + 0.17 8.6e-18 2.7e-18 +8.6e-18 0.37 0.06 +2.7e-18 0.06 0.03 \ No newline at end of file diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 29d03cd35..482aaac25 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -134,14 +134,10 @@ A Hands-on Introduction \begin_layout Author Frank Dellaert -\begin_inset Newline newline -\end_inset - -Technical Report number GT-RIM-CP&R-2014-XXX \end_layout \begin_layout Date -September 2014 +Updated Last March 2022 \end_layout \begin_layout Standard @@ -162,7 +158,7 @@ Overview In this document I provide a hands-on introduction to both factor graphs and GTSAM. This is an updated version from the 2012 TR that is tailored to our GTSAM - 3.0 library and beyond. + 4.0 library and beyond. \end_layout \begin_layout Standard @@ -221,8 +217,10 @@ Georgia Tech Smoothing and Mapping It provides state of the art solutions to the SLAM and SFM problems, but can also be used to model and solve both simpler and more complex estimation problems. - It also provides a MATLAB interface which allows for rapid prototype developmen -t, visualization, and user interaction. + It also provides MATLAB and Python wrappers which allow for rapid prototype + development, visualization, and user interaction. + In addition, it is easy to use in Jupyter notebooks and/or Google's coLaborator +y. \end_layout \begin_layout Standard @@ -237,13 +235,13 @@ l complexity. \end_layout \begin_layout Standard -You can download the latest version of GTSAM at +You can download the latest version of GTSAM from GitHub at \begin_inset Flex URL status open \begin_layout Plain Layout -http://tinyurl.com/gtsam +https://github.com/borglab/gtsam \end_layout \end_inset @@ -741,7 +739,7 @@ noindent \begin_inset Formula $f_{0}(x_{1})$ \end_inset - on lines 5-8 as an instance of + on lines 5-7 as an instance of \series bold \emph on PriorFactor @@ -773,7 +771,7 @@ Pose2, noiseModel::Diagonal \series default \emph default - by specifying three standard deviations in line 7, respectively 30 cm. + by specifying three standard deviations in line 6, respectively 30 cm. \begin_inset space ~ \end_inset @@ -795,7 +793,7 @@ Similarly, odometry measurements are specified as Pose2 \series default \emph default - on line 11, with a slightly different noise model defined on line 12-13. + on line 10, with a slightly different noise model defined on line 11. We then add the two factors \begin_inset Formula $f_{1}(x_{1},x_{2};o_{1})$ \end_inset @@ -804,7 +802,7 @@ Pose2 \begin_inset Formula $f_{2}(x_{2},x_{3};o_{2})$ \end_inset - on lines 14-15, as instances of yet another templated class, + on lines 12-13, as instances of yet another templated class, \series bold \emph on BetweenFactor @@ -875,7 +873,7 @@ smoothing and mapping . Later in this document we will talk about how we can also use GTSAM to - do filtering (which you often do + do filtering (which often you do \emph on not \emph default @@ -928,7 +926,11 @@ Values \begin_layout Standard The latter point is often a point of confusion with beginning users of GTSAM. It helps to remember that when designing GTSAM we took a functional approach - of classes corresponding to mathematical objects, which are usually immutable. + of classes corresponding to mathematical objects, which are usually +\emph on +immutable +\emph default +. You should think of a factor graph as a \emph on function @@ -1027,7 +1029,7 @@ NonlinearFactorGraph \end_layout \begin_layout Standard -The relevant output from running the example is as follows: +The relevant output from running the example is as follows: \family typewriter \size small @@ -1546,7 +1548,7 @@ E(q)\define h(q)-m \end_inset -which is done on line 12. +which is done on line 14. Importantly, because we want to use this factor for nonlinear optimization (see e.g., \begin_inset CommandInset citation @@ -1599,11 +1601,11 @@ q_{y} \begin_inset Formula $q=\left(q_{x},q_{y},q_{\theta}\right)$ \end_inset -, yields the following simple +, yields the following \begin_inset Formula $2\times3$ \end_inset - matrix in tangent space which is the same the as the rotation matrix: + matrix: \end_layout \begin_layout Standard @@ -1620,6 +1622,110 @@ H=\left[\begin{array}{ccc} \end_layout +\begin_layout Paragraph* +Important Note +\end_layout + +\begin_layout Standard +Many of our users, when attempting to create a custom factor, are initially + surprised at the Jacobian matrix not agreeing with their intuition. + For example, above you might simply expect a +\begin_inset Formula $2\times3$ +\end_inset + + diagonal matrix. + This +\emph on +would +\emph default + be true for variables belonging to a vector space. + However, in GTSAM we define the Jacobian more generally to be the matrix + +\begin_inset Formula $H$ +\end_inset + + such that +\begin_inset Formula +\[ +h(qe^{\hat{\xi}})\approx h(q)+H\xi +\] + +\end_inset + +where +\begin_inset Formula $\xi=(\delta x,\delta y,\delta\theta)$ +\end_inset + + is an incremental update and +\begin_inset Formula $\exp\hat{\xi}$ +\end_inset + + is the +\series bold +exponential map +\series default + for the variable we want to update, In this case +\begin_inset Formula $q\in SE(2)$ +\end_inset + +, where +\begin_inset Formula $SE(2)$ +\end_inset + + is the group of 2D rigid transforms, implemented by +\series bold +\emph on +Pose2 +\emph default +. + +\series default +The exponential map for +\begin_inset Formula $SE(2)$ +\end_inset + + can be approximated to first order as +\begin_inset Formula +\[ +\exp\hat{\xi}\approx\left[\begin{array}{ccc} +1 & -\delta\theta & \delta x\\ +\delta\theta & 1 & \delta x\\ +0 & 0 & 1 +\end{array}\right] +\] + +\end_inset + +when using the +\begin_inset Formula $3\times3$ +\end_inset + + matrix representation for 2D poses, and hence +\begin_inset Formula +\[ +h(qe^{\hat{\xi}})\approx h\left(\left[\begin{array}{ccc} +\cos(q_{\theta}) & -\sin(q_{\theta}) & q_{x}\\ +\sin(q_{\theta}) & \cos(q_{\theta}) & q_{y}\\ +0 & 0 & 1 +\end{array}\right]\left[\begin{array}{ccc} +1 & -\delta\theta & \delta x\\ +\delta\theta & 1 & \delta x\\ +0 & 0 & 1 +\end{array}\right]\right)=\left[\begin{array}{c} +q_{x}+\cos(q_{\theta})\delta x-\sin(q_{\theta})\delta y\\ +q_{y}+\sin(q_{\theta})\delta x+\cos(q_{\theta})\delta y +\end{array}\right] +\] + +\end_inset + +which then explains the Jacobian +\begin_inset Formula $H$ +\end_inset + +. +\end_layout + \begin_layout Subsection Using Custom Factors \end_layout @@ -1680,13 +1786,13 @@ UnaryFactor \series default \emph default instances, and add them to graph. - GTSAM uses shared pointers to refer to factors in factor graphs, and + GTSAM uses shared pointers to refer to factors, and \series bold \emph on -boost::make_shared +emplace_shared \series default \emph default - is a convenience function to simultaneously construct a class and create + is a convenience method to simultaneously construct a class and create a \series bold \emph on @@ -1694,22 +1800,6 @@ shared_ptr \series default \emph default to it. - -\begin_inset Note Note -status collapsed - -\begin_layout Plain Layout -and on lines 4-6 we add three newly created -\series bold -\emph on -UnaryFactor -\series default -\emph default - instances to the graph. -\end_layout - -\end_inset - We obtain the factor graph from Figure \begin_inset CommandInset ref LatexCommand vref diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index d4cb8908f51fef25d5cbbc7f29868238b152be2b..6ea916d338b236846093f357f0bde33e0222177c 100644 GIT binary patch literal 1620931 zcmb@tb95$KyY3y^NyoPJ#Oc_!ZQC8&wr$&H$2K~)opd^1ul26A_j=FX=Zrnh`TnV= zM%Ao2N7XauUB9}n`zDhY7NujN2f&aG9o`+Dm)_^i4voM72pI|O3@u^4ekEiOwXk+J zas2&jZQyJoY+__*Y(mH&ZDMQYY);6`&d5y2%M0V=>}X6wy5y_yE7v=RMQ zshr-+_g}-mj6p^L%W4T#%G~^Cd7p?G#8^b2w-h$XKsj&%ixNUb{eCZR@mrI(pse zvCF)yJC*9$N4{_pt80?=VvpSCKNXG*WOV+ZY&K$WNnJw`b1z6_+wo=D_@%C_qTBQ_ z@XbNWDCD^1!H_-7h+7lFHU%62`1x2j^=_#A;IjRA1ay7x+6X}O#{f&5&@y`@Xg5eY znK*aAURA(s*FZY)gv5qTxi9tf1Ab!g1N+s@5E=U2)NC%bT?2)*z?|nmRriQof~)hI zo9UdnIon4KW|3o?Ei<3~$>XFaQ)asuF?A4{h-VhB@ObB}Er?cZsriQs8VZCgahfQ}y^k7HrEhoCbn z3Q`3i?3xQWycSZ1Tc)3PDz9xYXC`=QlZwDAsSCfWeOu{s#qU!vt+%CQjh7c+LyQ>< z)Q+CEW*W&difKow6HODoLMi1tl!9d{DjWa6dxos$&Me_oUf;~UWqtt4DL9|tQk$$E z`Z0H2QO2#y^5D>83p4?&uT6px?BJ}lEVOj|UV!x?i{5FQw{y3Xc-RE<`u+W<{SOaX zvXB1ucArPx^0);!Ck(-UA6;1fLFRii{BH}bP_lvQWKs2ruA__)YTb4Zhb9na-vUYE zr5LR^eM8;iLNf%me{6JgZOri;8ht|))kX=3n>cTvcG?p=B9Js-5s&lZw*#R|x3ql+ zNh<2W=W?*tkWiNeRUrj0s|#74QX>wE2akWG64X784PIpdj=hS+HxRkn@IeC#!}xk3 z`Q@0hP$y#0W(^$&-a;59uK6fIM#a$mi@bPz3nhzxK%8)wxluOZqz$fd4i3@Rki>~J zMre|#UBk`S_ld^9S05svLx#~0)4p{g=lCUjAkbfU?Y{mumfR84Kh7hDMLf^mQj5&* z_l5B(@!Ag`-tza<&2;eZS|EpMFP3_z$@TT39FduOX(Oi~7T&3)d_MMy%KMyn?C=HI zr+R1vga=fJSl9Y;YmAL?BQ5HX;7f1&bp;T$0~ST=%f|*GlEyZeA){TubftCmm@a%k z9~6x(fQh3!0>bT#T53>P8tGaZbj1UE&4Xv|=;N*)q$#rE5 zWHEnC0pIl;`f=_uOl8Qm1kQ$kMrsNwfR#fcnG-Ql!c9i(=r3Rf<9NFC@Jd-#OX9O>Y$BJ1DwSgh2wo%(%*|gI7w> z@ILUDlkotH#8iPpCZ@NIY{_!Ory=DSWomQO9#jwOtioM9y_K!di2vF|hVL$?{u;JX zvAX?buT@*{3>lgI#h+0Em?pcR$Pyjh;X_{?3&5G zL`cck;^IyGJm(BCg@h<`a;NAXJ*M0e&-4;WALbXQna{|eB)zXDAZ`El}h4}S^g;#tQ6zXUxzm9UA9ak-ao_aBItXHPlR#`Q?9dTg|!DFu_ zu?sP=6$V&)pU)1K_XX%t=X-?$x)$92>Z6?X=>kOVa1}+ zL9cFX^LeOf|HH59R5*hC$?dpZJ+HSgRC4ud7P#ZE8?W8`51rTMvb>onaN#TjE3e^I zmc=)Z7EJ)X3OGqJ)X5GY43H1}FU-HtRGj2hhNW?nTNEcm&Kk4cg-qJ;^L>*5kqpVSeL@IUB7hvkf+Za!Jw}XB7p;MKL`V zdwi)m52b@P{VDAcByJ-=eRvL`8+IYUK?YLVlL*H9P-XEh=pJANT3djjAy`c8RSg{` zWUP7gprZsIVM2c;#DgOs+S=+GOmFUQP;&p6;hQ2Mu2Gr!ao`_9O*%0lBF+i z$=PQMZ6=^kR*vwM$J1*%gj#j5>#XR@;ELjEm><22v2{#A)lAVQ)=)}Gk7#txrH>=mWla9!h<<53?-hLv-kym%M>&@reC5GlJ5d2;+1 zO=&vPs8{0j>`1v^%&v3FtUs_9RB?-x0{7$m&4cx z)o)_$n%^CO{lviCqvHF~=wMjB9(M^|+oo)7;B`oCjvJ^xm0hDLZc1sx>e} zb99Tk74gqNv=)W2v~#Wk-?R#u3@PIt4gtP9@h4dhJjIJ$M|_B;IkxzQUS&wS8{e0P z1FxhG@%ta2W5XybBXwGs`#1pE(=OF6VKMt+&GqxkOIM*8GN)sm+b5Ku<(0h3T5!-i z56^*lbc9X?hZg~TXcc}NKU&gRAm*+~p0LM*fJZ^>S%j5Tp_0N0nh1oE*9OnN^Uv^} zYn*NZr~Orw{Z1`mKbR}64JJ~KC_fovl)RsgwPZ9{ zaYDl$^}PW&0e9GWQ)Z4ptOD{ovVYj#_c6I{R8i2%3CP6`O$BUs49Zhn6Vv+6s3ShT zWpLtcRaRs(J{f6k?;_EMnz*v$iWtDzfJU&)Mi?b9pL%F=TpR4>YhrXc@fFT$YTjRgL^!MH$ zILq`8tX1}~|IM-T24;V59ZhVV37LPNRwQIlG;y+XaWpb-z1 z-wk9;j4ccV?c52q7=IsNV`3&`=VaD_`OU$9jq}HKf8(>fqn(kGi8GY*|Iseh~{|U^QI063- z=9iiit{ZGfTlX||Md$(0em_V$hdfxSbtvlRvvRWNDbrihB?|-2(eH|Sg6VX~XICYCE z6QMJ_v7f1PiDw+@2Gh4y?o&K6wrC4qzstmn-NYLmQ`m-iQ&@KkXHJg@QG`V6*NA;F ze_*A}_5}0WJuO!17AQUK2wM^1b-vT-3NKF&?T%w9g{VSi7}=LZh0 zSJP-}55|zga=-){t?uvZU^pA5hU)kEK^*M<;ZH!9nNrCiSG#A@(8EOIo;s}rZCamo z-!x14gm*-exstMQ7^E7D+L0eR@kNDKynY?)QL~%;2IBS|mT;*G(N*R}ZM4Rr4LmQ+ zvA+Kj*2>KIIX$0b`Ij2p$NdpZYy%@Z-0(*AZPV@@5Fu=f0=eaUQQe0+#qz^B1Q=xg zZA-`L7u?`-xke6ZOZ%vAm-LhiX8UYD&$TgzFws4sBVnS#zJ#aFYcR;;&KY8GA5TIB zPNtyHh{S->DGz@#DpP&;Jt%ROuet!i?}-Tn6=|JcHmOE^P?@rU6lh!PG2!^hFJ3-d zjW4^CD6kB;Frl(RDnJ65)gy7b2HX9WE;t07bfLkZ{IQ{WOU|i+DmbVI4~I*{RloD~ zVM*tC&i~zw;!PAyyko!^)MFO|9hqw0tlILW) zf1eYJwHUDeg+O&7_1ek6myWjA*7polr+Hy~EB+du1Okdo0=GaMjyUNsW4xdIM_Z^P zh&Y~~mXo1;2ArDY{UM@61LVn|fep}HWT5P4b(%nWhE0QWmpdLLDUj z3eY(gK__bv=5#qlRM9qV8^kI@#s6}bl)OF$3iQAzf4sQ<6D^1mQF9IfbFBJ%f~frb z6hyxGbnaQl$i>Ae05ohxzIM817vd|@cV#NH;eFRU?5p0741+YmlU%WgxI$WKr)hyl zIXurM{|ur5@=!HS$}!v-*6M_g{Yqg?hU)d!3kWnp$Lo+nLhE@8kXR?j! z27J0gNw}Utk;plAO(L(Z@NiNOk=H8})qeRGW@Xz6(FU2gaee_~dGy0R=2=@0+s3Fe zZa_1A?P>~7$IkeN4yQ*Dr1S{HHRlQP6~xt)co+84eWaX+p-kn&l2fqw?w72y9KvTaK|Xm$7nsR{<%tiVnP#CT`O1oU`#XU?)QDLtC<{ukxdvs5b^ ze+-fP^ZHy#D2A4JU!9OEO8#>m? z;jVl0Mg_OL)I$N|q9x7>Kq!+7O-Md`gr!{^Hp%nE0smd z##SzmSpJD-J1WLy>4w&#g;8^hHf%g!7al<`xH`k>`|4Skv$}5kmL+T6J^W&HG(wQLeJgtivbjzEK&)=7A-@M#W+it?vA|oe{jhkRPaCHl0Pr}zXKB%LZ(0H>GvrA z2`T?ZCQScR%@DxC`frlqQj(n906)_3^#|JZD!#hglU}D-G>Xvy|K>@*dzpN52|s1p zNvj)GQ+|GU7%n5v!{OA0aZB&%B-0QsvwuW-ND9Qr2qoaF{uwCP6~P^Jlyovl+lYAp zEaXHLa*5>X*brkS8XT3W4Q?Cs^d`pZ{uOvE6e>B%Lzq>}4R640t=DZl`ZgNP_0^Nt zk7necIFI~xc6Q=2k$qhH0M*06b7j07L8I~YEiL6}p8l;L<0^5!qly;a4I|1kO(_$g zu0HDKAJgoo+fwk13Nn~Zk8_d5NhU|SiM?&eO_($3cJ3^UiWY9U(1Sj@)J+e$Oxrd; z7~i=*4WupaMt^Ju?_*}U6ks`Q^lPwZG29QAO{QqTuhv2m_d?7w%jHH|E4*uE)j|d) zXUDB$n0pqol*;ZRZtJ@6vAGJLWLy6N)4`l7YLE{=4rhCqz5e`W0oMzhtjqiLzfQB? zocff|+m0JCsHoqx*Q+JuUP%xYICZ@PN*e3HWNDV2^r3*m@Q-w=L z505sa4Zz^iG!lwoExsJl>Fx~&3(+4j zg7%r+_ZU_a#u_HLUa5QnJ%38gtS-Ern}0d5y~rpHJ*-&cMnHU~BWOeFyG~WPznQgO z&!=N|%YRAMP+VR@_HmmsX!kMa-G!cII3wqmK`AH||$5XbERL%Q(LvaYQ4>L!;cnG2IItwT~{FHjvh*Jwa#h`0z zte#<_VilPf5v{-0S0?0;7~V%qIN{_UD}RAh_`-oTF-$}V3)YXWuNcS+pqfLFGCVzR zWP)G%A>(h)GjC5-Ury_(i9r8{9`?wk&mBUXAuBd-Pm3^C~8V z`&m5r-)yIG`6$WptI+SgKW^z1g8R4b(0&IFF3fZdT-<-E@vyJ!jwWK7MUO1-!N^#} zKn5-Tg8Ts~JoLdY1yl0oLN0>l8#yxra)rl2p#yvm!=|hCE_>6AJY`^?okaBuxJ_>^ zFWCi+UCIdg(K`x>_S9{8UGV(aNM3Znl zr3!w&NmQruECdHugyc0KQi9Js`{ve6Sd%PnWUkfm5)R|`nSJikSB^`a&%j1WYe2Od zX5VDL)dA{|t6Xwdy(I~LLgD9(6Euc|4sn9PkRd~`@FoaOA`y8xvk7!+ib+~QWW7A| zcPo@-RIU+_GY`%~>hgJ}ah_r3tM~%PRXVC&q;F7-%1E!JTTfeeTW`SZGYKlSrcyzH zBHNAz;LB5ET}ZFc#~uj+pdlGIAVgdO?XpRj=V?YBx?!}tMnnl=M0W*Wh$Dkhi8;BK zd}5^1i_*r3(36v=KZB7%+DdalBP7WzV(dpx7N8&qrRr`y8Tf3s-<-oL-<_DVdxM1X+cIqtc3-Mh!?#8HrtZofoXR zEg6YD`#B9Qr7RsSCGRw>7ygNiAVWV_VWt3s%c$hzv2uS_Ln5g@Z3zBoS!2{A@G6@$ z*q*6+BuHy3oBf1>vT!zjkXpI{H;F9AhPi!*(ykwqZ*>Sk(IRT7*? z2T(teNF{b~8QBU9SGD`%6&T2?sCqKgCI|_H%-*p|p@$eP3ey6KJU=bg z>Zd#*X|(}PC@weUH1zC8kxKSKKqbZs1jz(Syuy!?14G`;N2e&l+8}lU$4#m$F`ZGP zbW4lz@hiDlRjjF{(m*3(g4)gc#WAjHUT!SU!2NZUXvBR?yRIQ10S0CI#PYOhrtJ$& z7*ds#PUN11S>)wN=#dzsz@;oQN#c$2(iulQ!b`%@gdx+G39prD&^5g!0WaoQc;6+V z?onW?!0Bd5?}2mB=@H2@%N{g(1o4THDVLh8K?kO{A&rd{8xkZ21O(l)o+KBq&J3&A zWQjiQJs2afkDyUekW!^c<3U>Jks_4d!pQDOYhS{9yxJ_hzA(qyZ+x+=TbRtPjzzs! zCj>RU;n07@zK7aKB7hDXBsRw1{cvgHpqe)ma`)o{t(7!Nqu=Q&bz-SQS5byRNaQT~}4i#H4r_#()F_UfYWFTfvL7wPhd`Hz4`1KdY33GPNX2?Y^HN+3;_?M=c866@s{%CF1rI3;U;hd zLj^xL9ZtXTAA+#v7oi(591H=#B5)NCoHETe(u|xk`(t32!6D~8z)8nw-KSwO%(*fI zhLKkLVY!1rB z-ji77V4%*_r5*0$*wlS<0aab4134_KLQv$`p5>8O2_Cr*{iGQCc=OtALoAx1s|Z^RDLAW?z$M zjSYj@vL-Us93B^8Yc2d5#1uOqsgV)T*W_|^Z_%q4BCoeld|E-Z%vq zxYncW^(@%qLZ;j1FuJ@w+9gTCL|!=*DYqqB zXGV!|^Jc>gtmreIzPE6Il>xNOka*!vxLiTO0_e7>Ql96oVDxmmTOy0$w;L}ghK_H>0c%XZIyP6aHwZd3RmIv-3h8e zf{M5(%~UTSPMo}YMDC8xK&V`Hfep7)UmW<=gRT}WFpr97=6R^R!(!DvFZXvJ$crAv zO*yUC?&^G8>3)!&Lzy{-0Mw50=;k*u8R0#{9t^z29ZkAt9IQS-BCJ9BrKhO9b8lcl zxNEhY6etIMLV*n^2<~nBGPTLj@wTEr*cf%y!mWIN=a$gtrAS#E;R^U=T-VSwbO@xh5&|;tG z&{|5y(uayOu1gtn6>Ko$68EnHC#n{n43um4EmE4FDrR)2-e(lj!sWK+yzE zb!0Z$k<A4#nDdd;Ojx9D=EgmFZXDj{iQiy~s8Y17Y%*^UU(6%wj7&VR8JixfypK&BWh``B^*PRAtRBh&^gIr|g0xF3;(@*43t4a!2ZgjN zO{wJ7*#c#z&3+i*mRo1U!5;*0FBDAODJh{Rj2oLhBw9^bHCvU@@q;6IzKAd)Q9-C1 zz-pm^qNkDWC`7`oBewy{K{m)KCb@O_y-~0VCK&vw`b3K-ys#y~g+g&kOV7)F#$nfQ zNplt;v7CduR1NF~Io2mKjB;p{6&XO|6ow#ZiXT3Z>17=YWk8B&w{w}fHKQ&ztP0u4 zJI?;r&0YHf5EgX!Ji+@=a>|R?z-R^>U~m{7)LZznaG8bn?(bC^2ou~7T)RlMd}Jx}IT8V{k+BvddYy9b%Ds3Dih|m(bDgc)WTlZ$S4!g<7 zLP11#36oMkWc|))1!*$vy{oU|>p!A!-7}}=s#n`%TkJ=%al>9h!mr0`r<>~^%f7w; zlQ{PB&9dVa&vtf@&BI$ZDQ9!*+v}A-s@Llf6z!%sSl!dPtKoF(qw7d4iA+k7(=-Ry zS$bqT*&_yn4(^ObV6xKa;! z>M?Y?Ow1fKFx->uQ{y>bMYiU7)HEl!oO-q_NGf9YcDD)2`1DxCMCQzIB|34;eAR0o zWV#x*e|)VQE#~PE`-~_BZF=Ksta7FOK=Ufn)JcrMLH)YyeLsek3PWLx^-Q{Z(-fZA zb+$=kiCJ%aT^SHE(#oz73_-eOJ@R~Iue)LO0o&bqs^P|eOEIxx1B$a5<#A~9^QiKA zipj(a9JEA918XN-29C*^s(cpV_C%IlM*t3lY+a4{+HQ945QxgqciPD?(Z3*bf2_@7R=Ag`^$k zYre8YE$evsMVQfY^&^I6+qg&+g`0yIC47xwZ!nT0Esw5ryNTOO`9++z*?`NL6Hq(u zB%=JczW7&HIzAKQn=k8*rO3G}vJ5{sYE)L7L;O0~c+;w|nx7pftFgQ+ua#^5UuGe+WiEbqT zb2PBwLGgXH5(}6QxWsgwZmO!h_M}4dk-JZ?j;XJz&!bpY;YinNSsL2i5F!Bias=n z+gL0&S^{Rv4yOg1bMrwLC;?wMF-VnPl660EcT2?x7$GGl5j#GJZ|Sna|BZ9($WkQh zEQhB7_4JEr8z4E)mxuBSlSb9{($o(VuDOst%Q-;Oma!XG!lz3qpbddey+Q|<^c!s( zTl!pgvtQTkXsxmNmv4Yf3YPHsr`J(x#fEx(!f;{=_m~1}o~NhvvRrbWLO(${!8HFg zg#QoF%XI&3lQR-B|A$e|Nyz+{I;rgOw^ROymCj7a{HGfJ z+l?n=P?s~bG%@;@%`R%gM9B1q(*9e&6t(%?>|Zzg?~3C;mH7Wwas1bF{kvZVB^N{I zKl2Dg?Hq0X@bn#R{%pZS$RPMa}}frO%1G_O#aY2|IWhYVEJF< z&y+1oTqd~S>tm`1uo&MFd>lyz6v;J6S};QCg^}KkWfk@=tA=C7(o7U(Ur@D zSI(vpGAB84A(*^|V$xEZyC_(eY`v+S8R#*&w5Q)>duy<^EP*Q<+dLoGjeS+si+y!* z_honKdpX%j?(}*JlpHJ*d{%y~qwy;-FZ0mA5}x z(d*(pZLY;Tfu@|+?kU{!Dg2&Uku^QPJc24#StQ3u$G#>HLrT^BlvHchj6E?o4hHb8 zXA(BN-aMhc9-gmmzbrBh6}H^$0u?%fNIaw_I}dY|*9;};i8PEgs_@xxKt?$=MOQPQ zAEuoTnze)M;T3UvaflcG4u-0IGI)LR=|Onkg4X>_xVIHcXU4uQ3(+)US-%Dc=I9L( z+OH7-1TG2`^T}|f*-#qF5Q%aE8Z@N80Ir$ItVEoekWsb;q>TxO-GnJM49k6>|50Z7Bfl8PEPv zP8nbd-AIeCF#v(|cC{qMpqZCIZ_Yx_iY8s2S8R?b(UuNel4O6gEutvAw~jU`B3)jP z{06|xWWRD`t>y6j-XSp4;g6SSmDtTE~gUb?;s zxMY=|A6yB>f<0~Z7)_cgV@e-e4l-?IlAh6`5}EN--M|Pwytnb&1}d|~=YTqnmL6|8 znf-h{h!~GNJhs@2@vcWlE4S8mXExXyX|8BvC-d(O_e81A)N~K*O|nDQBv8KdDsu4% zf+&+5vGAh9kkM-zvZTnv3cONjrK^LaaZ#Eg78Wld=5WNAxW!;&wgfdvGwC~*s!kbX zOr?XcD0)sQceJ&K*wSa*9REVH3Cpars%Yn|F&YL|IxyC0-Gq2_HnXG$KJz>jabeK< zma%h3go*Pf#sYg6`+wu3{4)vXe;56P?5yn^mFx|SO#WQiLQYJ7ujD@h(|;uYi2XkN zXW;uIUj1j9&!55R?*RM%OCVzY9o(5YSP22Y0}_A*@Na>L`L7qj|8pQ>shl-IGhFI6eg0ry8THR-#LmRCur-)&!8^FT<8g(GDCa%E!_%kGH=oD%(<#$S zsnp{oLyyulBC)nQp-Gy~1EB!>8OrDu(XGEcROd>a*nu)~5My3}rl(kNvY)+V{UJV3 zxz)U6oRZKl!yTMwMS#apg^ORn+vuKPEa+tpePZg-v^eEeh0ES^jJoo0ZBa5bLn3z?A58-Wb z8!b6N$1Bzvm@ryc8P&|(;SnKrjfNxYm(73h7BbLEvgI>9nAkFj4LsYPj`WSQ#3XIq{)n}i!%mPHU-OQv-2JkDe|*^AyaTA5=i4TWr$ zVGpj}0#D9i*4pbBI`(`FnF;xIV=pIxmI%6wU&p079oOxHIX>pC40s^MyYWpA4147{KO%pWJgweghaBPDMfo_vH7b}b4? zvA8!WCHm3%sM|+-X_IIu!gTNn! zH@3g4ZU`BKO?e+GaJII9EuvE-|xU7h!9qo7U3^*+B$YxP)N|@=BV;;mMfk+ij!Lt05Cj(xA+4n7j1MLlayKBZgnCU5W@W znTAcedHiKH?&YP%@{###@7fN&kJ1Ov*td6;Tk?yU9D%4DjUDTYDu!-!peItzOuWXP zWEG$$8wmcx-72|jLZCZvpr-Atd;Ab<-Gre%I11RviwkQf;9M(uniKZ-+yJ}r-Vn~` z^ogr?RqhfDK7SI4F8~vf!;;bxDdEXUIE2(0dE}v{|`*7`MSEDhek_ z&_UtmoxxxI)#K=mVS;>@c6~9~C?K(XvaQg}UG#vwgE{5fBp}D^cz}dRKuK-+zJYk3 zYaubgjP-PxSI5^n#WH{Ub^JyEs~usxD=k2*bo2xlYwSo?K#Ntl6J*^Ff)WSmoCm|= zPtOQKs}GOs2e1d-CIkxd6Gs9~0i_oQvET=55a3+}f)QX^1$GUzvFGj9r`?AlhKPfkY_&F(}YEQFSPsTVcUCby8qtBCB}fB9L;C zj5vfMoc3t(c!vW}h|qk4G)(jnto=}p-^DGe2Fr$$j7w=oX{yo~M{K4@0RPv3V#B5S z5_O6yK38Zqj1=lryD~rq8=DuTwna1Sb~vWia2OZFslGWq7*_>Yf@z-Y^Y%ETyoh&G>H&W3`J6^^d^602}@!favt(-qQvi9#$t|` z8vMF)HKe(OdSr+ReDX<@|k7o@8=KE2(a&di1#zdPKgGze;|#fhhFz_bd4q)~V);?lukZ z1WSly6eJsl8D8N$ajl!IGvbM{ z7rieeo(?|{oOC}xn~<4k9a0|R9%3Ihjw?b8FzUYm6tRk<5~Dh!V((dw+GqA>HrQ${ zbU(YOl3%H9slAeklTDL>lVdBSRqU3~ma;2sD&!U!Ey*nnEY~dGm*^{_XG&+>a%Qsi zSUwMahMv`Rgnw&$vwR#p<2g&j&cN=$#==&?PGuQk#mcbF_?~f?am+H>WUdL@45oRg zdEBhan4Eq!sccHt7|EGmU2|DVH^*DFRmoFrRMx0&Rw&yzjjEGCuf;CVs@g7J8>_=gbqr6Y)FwI};>NsC#HP!t<)LD`jVp_Y(5?$!^>9ZPY#_ zg(pS*f<);~w#GEoH2icSEF8uS#v&c28f5ti_v6X1ODBz1Kxf1clx3f;fhgW12L2WY1> zUaUJdAC^zd)WqraYdBEj;}GEOAbp0T4wN5C*F5O8yB&h9BzA_rCmfH^97o^kyqNrq z2TKiV2$~a49nuLmlBkjRBC!u5C(!)Er9tn`|DZf6E~$_TP(D{aWf9c$(zGB*W)M+F zqXXcf=w=vXDP$Dt7`IruQb8@?pNp5KbkZ>GOpEy?{U{zqnn@O@0o!QVux%!0k~^+2 ziG1{Mka1u;f%pCX`@0XTDXW`{S&!?lke~gmS5^qs!OJz;8||`gI{h8Hk3HwHHiS0f zYc~_36VWC(JGK$qiwb!Pbv^p#jn_vbg6)C|yWMotS_sy|)?chIw@e$WEjLn$b>|)p zC-x%t+_Ju5o%$BxZ7>OS*qz06)8-B{_}vGH91js_iu z7<`LmtaZ2%#`_wY48KIfK zyty3SQp9HADebv)>bH=MH;qTfm-*@S5cQOv(Kv1EiyQZ#Yd%{1pR`<5uv3#TZ{ijN5rCAN94!3uYNI`>W`(D71Q$Whl{)w{h7uvv)GU}A%@T7*IKzj@R{-%8qp@v zGqGy1nW)#Ot#9=Y!#5LAsSEqTy;Q$io|ES)bA8<2yUh&058YVJou~6jZkP3NzAZo5 z92=h;EVx-*my||qSN8Bd`G4fU8$FE1pI*ql$R+1S^SOCJ|GaZ2w=q51c@DaN|F7)( zrvmi{`~EIrkq{CRG;lI8Cj66D6$y3zX#U4Jz(3W;|MrXZuaa>#04L+WeI#~g+a%(! zJNotBt4)g8X0v8IV;o;qSm$2e4R^fkRd0q;CKpgj8g@z5w9`yX$9C@|lmfGu@=wQU zBV;R+7%SUOq5MlmRX*gw?_Ozws{f4Ci^M%N+?TnFO!lq zcgOp7$0ixc!B8>jvzv2HTVZau@y*qfpu6jXuJHb{^MtR^!xgn#Jdrf~sJ6vU&Fy^3 z6T2bd*>|UBjrVk-@^ax@XM6ZBnvM^vhsWwXcJ2rf>{gT0I{O)Y1vZzgZL!BDZt^~nO)Bz~JsRSlDqeSGlxil_;4r?6rL zuEv8`$4A>vt?%*@*i$<-moL2>%n}>l?wgi+86I{=uY28#XDTx_V5WQNuL!PGb0w@K zTRW5UtC4<@jA^}0Tpl@mxSEuZ*X8oQ{B@?522G=Kr)6ClaG-wIBnVjNAS~sG7uWG4{oxE64TlhxQ zLL*aEZL(TLlp)j)?I~zDLJQ>1r$(!1U!Ht%k9nPfXzBK;mw-1B4A*TTyEQL-I>Hr? zAPL4KKMMeQKI&EMro$#rkyBb9pp_K4(?`8^>p7+&o(B`pl~W7ZrD$+18$BOwO*pgj ziw#*`@0XXcdR-BArduOuC=u>)zOsg0KcASQxA|af7N}(_27ca(WE?pF-#ipJ^Z4-BfPRCK82-*nKaW*LsUaySVUJ9u#@sd zBkS;pCip~#%9xqzox{`u(qYpG$w5<0wXbirra8KLf6pazX@L`ndEO_l)K;qtF3m=2jzWlgt{|49wWZO>%=v zP75u7bU9^>d0b&aWXbH;SCeoW*OVPXoyZu9j|ZC3s78bYW^4AGmf0DjVjH|8{DfR7 z_U+EZ$xSwytT9aw(-t~BKr3h0y1S}OCN@ui$$lD+sFk`oWeJ^y&e0hB%;c{vfYZvJ z`kcT`)!E3b+en?d^W?>?E7H&RKw_RHL2A8ZQ+$1mH zoo!~4&al|h6NNJs*mIMvYZ5N9Wd;4P&Sx3D0WvG>N|S5*tXTt@=bX@kerdPKfA_2G zdWvV4ilCKLslTvbZrlXc1{*zNIuFe|I)zFjcKfEYBS$5GMTa6-f#AyGx;F%xp^m2jvC zWYuYI)#-T%e+70^?|T-h;Q@OaMjezD@H2qa?o!G#+Ey5PUlacj_C$X(zciRb;xW}z z@Fz^O{Jyt~zBXu;)kuQwy7H)uQV~AfMtQ_}Rh8M6ehpcIEjp3SseDKSLQHnrT8eAk zn#4%8Jd6oVkdP~@U}OzAXhB6GN^%5w@TI18mnQJO^49;y>U)@I)HNRq*IaetF$;94g%IWHU zX%j|^r)%b=WqiVTEm|7NZMdE%o@bjui=38I7<l3 zaP`9xiaQ%a*_FM=ET^(IBA>)kB ze|WwUO>!Hb$IUXpEyLv_J#4`nY~?BReBFBu%haW?T?qKdId+PfbeIiw{qhY(mTvc3 zO6@S2!V9(2^qR_O-3;lNACsl4N@&lH%JEoM;mz7a_yqzo7v9ffsBEKyemQ|k|6k5` zNOH)xj*&Yy12Or5ndm>gz0&yr^GZe;B=}dzr|BptQkf{t*W?YgTHj>*DO2(1qAWD@ z^`QyYT;y;5KgQlMO0q3c*G}8cth8<0wr$&$wr$&HrCDjC(zdhG=9hcl?%lg@f9Ib5 z6)_@WtulyJ6hFm4>3E)GUuCz;lycPS@5NPzL>s$6w1U)@=|_gp^(g;n14i1 zhJd!MJ|bQ%fsuvTusbozAC|z;q_$Og^wdms_@ItlD@OHO>f%LbaXS5+5)YuzB@o)HyCRgCisisybO)tlhSLI*5(FF%B@dAH$jk z;Ws#=CSDxOPebX*RarnqxEcZ|hb&)oZ>>LBV?r zf~1CN12NEu-gb|`nk47(TiSK!>mDcs>B`>Ne`JS=%zf-fNZjyTOESO~(Tkvh*c|3c zrw0MN_*qXqr5V69p~RJQoKz5rk}_Ak7qRC3)JQm%XREC7Io&g@XSzed-qavr^!MQ? zMs)|QT-m{fKih<;x-;VTA`c!V(0|Pv44;&Dt#9E7z`tea4OL8of{~~Rf=~;bJum}8 zt4zNMLug1a3_zJ85D;}UOG80MQIwq&k@4XhSe`2|%Zau(*zUQvspBpc4Vh4ZXiMZ* z%qV>wx(xHZz>P*opb6SH(8G{AxapGL7HTff&0X6$suf3Yf|dqp?Jh7LstyCLN_f4C zh`P{K)Nt6mjvFH$&rb7~!$S)ZZg5x2EFLK+{}t;e7+}1b>a!MWc)mN`h}O~6M1F8k z8oe6wy|U#p+JJ0?defROK*O#&&eO0u+iFT;Gu_#g*x(8duS2!5&iN2yTSy=vn?M)N zPpP2D({cY!F}i_07*iR(ZiA)|&VG28@W$yTye4K!{^lgHX@kHZR&mDMPqC2OFk2I6 ziAI}jd#frth>b`Sk}q6>Jc!7fn^$2t(X@5r)b`pqJs_RWN1IkHHr7flXqAG~(k;v3 zI=z)xImQ5uo42YA6Q-w2NF}>y{us#s_Rv@(@xjBgT(ri3YJWdy6k0DfGXsT1GxXR) z0J{heEZrmt#CS(I5-!0YK(a62u3nQgLBLSR(9NRZr!{bCeYlk*;5z=Uf%-9q0N4N^ zi5791n0)T`ToGj25>V@~Lwk?_{xL>h=z}CB>i6XgKtKxI_9~k`UhB_3lQ212QWEl137<;C#u;Gyu z6Qt?L6=Fa^Jkew$k;;@66tNHhR3xMjF#1EVZN&z*T$xD2#9#|!Me8E0kF0qGyb{LD z#x}!28z^kqj$tX*a(;ERyC~uQgHCzUNeD{BVAm1z;;mLrOjN20I1J)p6i9(e00|#Z z+aYKf92|F}A+&UC%#4QdhMi!*I{v!}dicQ{off3aHID2AI3?rE0vQs3DD`ud$b!Er zFs}QP*tNW{B|oAB^%&U+`fwsaelmpL+ilris>!hi5MDl34ic>ddG4Aaq25q4zq&71 zd=J6u9+`1y%<^IsBL~X#Ar0L$EIE$p@^0#n8EVyyw>yUGd2VDkW{?hg-yXmmnS9e| zEgZp7lz_1aSQ631dkSY|Fle6b_`Q+M8Ok%?{nC#&u!3$G-ft;raMQ3!eaYM1$(84L)b<-ktc=>|7Ec>3~dG@105>_MJ}#s=v#&( zAxJmtk@38JJ_cAJ{HeTzNXmGY1&ZE9&gWBOl8FV5S&x{EHLF)?^R&dF_3DCI$u1pasw!tShiKvgLPRNvSF(j)S1+ELD&GQF+kwNRwo%9 z2X5lnNv-ivs59GL8!dMSC2|XIo`Ke7N7~L zhl$pM&D%6TPXlEK)1OM?nuF*a#swOYq`S1t)L*Ce2rt)qiykPZs1(Wz=H0kqkKxwD z&#B8PD0(d;7`?oVK&$D);YATrF`68MFd|VTbk~&>|H3{6>_X`Gl(Ayn=*_Ulwq}k_ z#!_O(Dy%Q_Lb`6vlYAb#FiE>^x&y#EMyYvi*S^1%#yr$Qt2XVAl8bO@{1`^=pTs14 zi{sd+e8tRijuuq|S{k_6rbimE1$x>=C-TZzPqz5R*hU*lbvAH3YT_7RsZ44bM1{=y z@%ugM_6|rk<{P{RoewT1xE6T}j!?z-qRr_&<5Yw2ixdOwSFF?!&X%~*2-{lE@R$Tz z(^SbjYHYA_s^QZkwfJMWhi>7|U7FG=_!h6c%k@=U#`1xzGOd!A4Z?1C?8+;{8NvZ2 zabBR8wLvk$j>J3A`w|&hhP@F8+TZpkAVq$04bHNW@N=Sy^634C+$h17Sp&EsH14;M zGY24Y6l9a3`JXRaJW3^rRz7QeDD%E>wrlBGP8aP@Hl9V19HGvNZ&{3^>^Nc7ryJm8 zK4UTBN=*Zs0NE)|{!Iv%qh+A|O0}we%|~S+=JG5>Nmy#^K(^v7Cs~&KbX_^fr6{!n zFl~=-FJK!C%+0j9%6Er0uh_ryb%sD#LQWtfS0&OMo~7^;1BX0U3r|yO_sR)IgI5Ik z)7U@rA@;6}Bfk@wK*MaCub4EVC8&4_5Mm5B6lR#E5T$hNjr1czva+<2*$S&rWOTA% z-?aR0Z}Io!otW8&6BCz$kwE&kgFqiPOX|y+Y6To1TO%d(b8Q z_X7IM@V*bHmzTpI^u%@rqUlJ(7?|2+MJ1 z0fhEH_CQ*RH=XLaUhTQ&tIM5EG{-1>Z2=(sseXRGdE_+2(}mbrYX*Jd@A5RB?*g(r zs7Ap2hR++3D#$K(uZONEe!5jvRuqbP<$bqDI{+mAinonEX_2E~L-Tj3U#EEKjw;^7F-L*py2)wH6R_59ft2B5nwIGp?Rin=IeM|$#r8-vSRVE-}6QA%)tI=iD<+wSH;#(cO z?q4e^64Qhcq<1OE*apyOUs(q`Tt&6S>1)qwcXb+rSV)+65G+fiZ)!LuC>}3D;&^V< zu4=OVQQ_=i=NAT`2t4P>JeRP64q112#>jV-u*0!;HVHk%5OObc#$}=$J*DdcaSo?C zraX4*KD|=D%cw?lDCCkL=%j8b;5%{&O_G%6duGFtpu`G)g7o~{ruk@E?;VG*bSrmj zj|s#9Qlsq%2*m+<=-8vAb%oH1&uL(pABH3Ftm@I`@z$(nP28|HJYe}bW{)!H8<1<0 zDE8{d^Fmu{Uru2O4f~M){dM(umDLwN^Tjcea*r3qhy?Dovtoa$#l2>fbg7kenXX@o ze(*XaQx8%n#P1!6{LtHoaKr`{Qz~=_gw25n8lfK0J1J1sV~fJfNV0tSRz!o0igBnz zdy*)RJqsFX;mz^-{s;PD_Bmn@kvb&joE8M_1{$q!y5@HNHD6B%2rPi7YrfmqP7S_5VE&u1GMtV; z02uHwlD1F)m>)cSPYTFal)Iab%TtWN9ir1YIM=NY5H=`sOzGfYKboy=;!)tJ#Nq7W z+p5fRIdQmvY)EcgEkr)^6uOhNu{o%^!$=S57;&L?AUiM%MO{)f>ZL(Tdd$}izX6%W z!FYSUH|lxgBB7&dS)Mr5`)t?#jXObLp!D3imVvhsca&%Oa(&R#rub0%o6dV+JT!EZ zmm~g;cR(G+iqOh2Qz`7+`eX1LVW47N^>>`!c{<1S?Y1QAF(x(UbUoLd2bPKf9h?>` zHj}MGXf1&;e}!kS+LE;&n8>&?*8#c6VTYfs;aFTYYk`q8tek0xFTc2*9(7=Pxz$Xu ze-V}|!d)>HDM(oo<39VrSbKIEwkR z|75F;gN`VWmq2-cqP;Cv6f5O>q*#7udgtrTH)3=?FC!l~G2Z%85otTmAz@s+OEl46 ziaUKjAK9=&;_*Z?P{r~2D&7(E$IB_cV<05p79al3^=aKPvr}hQx@9%MhYMTKmO-J- z)MG)c|5_Gxdzpj3aL}K}#J)h-GIi;c|JE=+7lVh`@Z~1^F_DXQVHSBl6vrgr5YhH# zb6JxEiM}d-BU!I`aTVY%-R3-8_h~t;R!yoS9jCyeKzhHtucrma#N_k{C7~LGSDsM8 z%w@Fe8B)EkNFWC$TWGT{2>QJIHjn~(y#~BNt5=Nut!O99vQ-&J!h;)J5_w3V%>jZ7 zd+0W+3Cb8gLqbD=0{MM&1)&ezL=5@%OyzKHFo{aBXoRU0Emdpq$%Om>JaVB^t>@+O z6L`9|?(YAmWcj->;lH7`nf?K5|0MzWvw`_<PBC5%NFw^u;~?^_njTlKC&T{0qru z{tGVuyWivs6KDQEaQPoY{Riy*rwdu)3nKq=P5k3s{EOH8^Ra)P(*KDO|MO(x)2Ue) zf0>iN2yt-}3o~=)KkohcjEsSk)jt?-K?`Rmc@sw=I~#jD+b{Fnm$>eqtT)I1&U_gG z000020RHE9?9cQ6@1y+JheRhQFY`5)f4wK>zw0+-{}|?f@MvO=249f+KZ-pjrZ2qo ze+ANt)xfot)Ykae9!=}|av1wWQvglI!zKV4LbnM?{eut<@gc$@6|3|&c6$|O3(7<) zQT;g;B2`a^s_Etx1jinnlg0l=TX)ni%=P*VC!ZVZrv?=vSf}mxuvsr&iY^ z*b7ZiPq!`PrE5;8Z`b=SvYUj_D*&NjT@gTAtVSGh!fP(8kfl&MFky!B*C#Pu}+Q(n&=upTj9Y<#|T%4qt9hv%U+KDkS{6) zy*I*>FGrKGKNQy<0FaB0M*bGe8?8Vt83EA7wOu5rfz*a}p08pW(ckLV4{(V(N+{0p zB=s%skkSo|A;06sIDZE}G;Jo*j$R zjgsF`xrkpQEc7O?z8A>Me1~2NNCu1vN*->c5#Z4ao9uNT$}t)`p--K6EU2xm&QW+u z5NKJTEn%Gm4{L?!`-RH+1m5B?6jtD5kEkOCdcF?^I$%abJ4%9K9XR(`vS@XZxsz~ruAyC?r&cykWn?VC7k(8l~ifo{^AcX>Cq=OE{gpof$ zwDP|OA{iGc$g4r{ZT4l<=~qj4tmaWbbzv7CPJKLiZipLd-&EUnzA-y5sQx5Z9haHg zeW^L+S6>*2B_mU+??Nw+LOl6{Z zj)P8D*Ljcey%MXK^|#E0<=IXJdWkExO+VUGmQ&PIp;Op_fJeG{SxdS+&-vG@^=I?x zQtY@aq(JRaNRqWDjG8owhB)B(QI)7e0p<~DNK|*IP#5knJ3wJMxK1Lc-#{=J*^%`y z1mC~$$TA9+^FTkSJn%B))W*fZ5ZotPKYMz8(2*I>KaV6;F~&=pEu_Li7LUEfw;|I; zyJH59Wv_s*yr1iwzn`O@henW--wbyTenfAKZUPd?T{k@;zOioxwCv)9fp)3BF>e;| zzg`<%dA&MpEFKk66duiW#Qycr}PQB}YA( z!^PLXZD}xbE*epVF}_A9jr}lfXE>1-D*;dJA4p5NYGn!p&|s=go0S&Ah}K_a5=z_S z9Wo*|YQrbM6lT0cMo)I3gRR0gz&go=XrNP4=Gd(3`8*-Aib^#GMTzA#O9RU?E+#dB z#hm3pQWFUoR-Q4QAr`&ug~J?3u7X1<G@G)MeFKTyyX@3;!0Nvx0Oh-M($il|-YQ6DB^4*^eTj**yb&&X|zqdYVc3=uR7 zKp1pIYPD}}_Y=v)deriHIwyuV*nWu|1+Cv3G=JO6B3wF)gwohy+mzVYfy7JAEQMueNOdRz>-(v(Loyh8`qQkFRcLct>G2h-UOhkel zb`t1JI8F+4pc#fnAh`^yTJUVv^asvwLD(`x96_;J24}2yKiUGSGUSawI(c}H2(TF` z<{$$MoVi|S2BQg}#=$K5?-Spkdj;#wsR5<>8SAK}14io^&zY*Qv;u90T=ij>ThyUl zu{!*81~2qC)bSp`A5sF8<|#Z-m?CgYfCe-B@`V)=$eAcKlG>6KB|%LUwUS%}c<%jlqt1yj+hz13&<$SNc5x$8_IG{b+zfu)vxC6O zm#Tw6ACUoxm%a*b8xS<)s83%OVn#FzKNDtS;O{K8l$R-&Ro0_S<&4e{$rh_FT9iL4 z7c2YvC;up~_sg6acsm&ViX=KkCR0vJc1@CtpG%}e(o^_b(cH<9Gg&(yPs&sw`Y)=J z%;VP+vXiA_p1UO&mJrbXY{VgPGjWWAD6ApfA;=+?A)}$Vh?I!xh+4_22>xPWlj1Sj zWYy$xN*+p~iq(pTijNA3ij@i}Wwr{|iX5e`+803?nMuh>F&bT&s%CYY!c~E$Tgweg zyLp#+oQ1#zv$F98wX#c9zG5G-_u!C_kZjR7(RR`NA*g7uXeKOp7F{Nn^crberC#lU zDic$i$ z&$b8M-_WaFoX$90+44C4vcXfb*-V_V&JH?O8~Qrk7iR4p&eJCk$Fq0m_pKf)9t$2@ z$2z~h%`DC47UdS`Rq0jwYWIu-u+=ebW9?&AF|!-n&uv%drxOgzo3~EX&0b~fP!&3e z3Wy38QWgS>W{cWIYYgQNaST;P$71o(6G&sr?8+RbTQhN({o<3g%i3c9XsvJv9ok?i zPUFlVO`Brduvj(VG&i+Hvn6F&Gj<)S+FI}B9^qc|%6^8t<%QOX1c0s|Yn$>efI{34doAQgL8pn8=4#PjGe~p zad|@(izo~&9I0QtZa^L!os&5Kv2aqsw6HR)v8#RLH7>Fdyr;O|FkQU1(95#gw0>W9 z)(FXp{EMtAXNGr&XDu)rdaK3LmeV%g_Q1B<*0+_b{dU7@!%liW4TIHTcHl64nv6pR zNp_X>q&c)^SUI*B*9O4^~Tmu{u z$O1UeVbqba(}PovjDcLd3Bo4A{}%1E(%_RRjwWIlX{hmGlV3?i$r6tVI0*-% zHWV2YOo~{Fy2T+yH4?uwSPfPKEYRnqe+^hnp4{Cf-M!rXJjtJ1lDkabVJLJQnoNIS ziZs(rGhw9qzIeTo(dga?Zzj*A$n;>^xi@%o>K5qK>eM`exeb2Hc9jbi0CEQ6E$F+0 zwX-MvIl+?NrSYL*)%YUpUx201!>-<`@y5+X=;`@TnYEm?!GY(frxfqGC_+S`U6Vg0F+c%795`N>?qC z^1J$EO-;E^OIFX@Fx^J?`qM!uYC08d^__N`4XRDD@xtVSf8}G-I9uD)%gls~);Msi4 zUN=&R+Qlj|>Piwy{0j>TbtWw))wBq;RyE%>W4$h4-Y<+&hAm^y@bugT?}Z1$;mM@r z;BpdjPWiH3UKG~On?21+vfCV3KhBGt6pp4o5gz)}U1eWKZ$FM=b*{Q*ZVDe`#ppbA ztxvCx*>4hu<-};+buHV^UD}=_rjr*d6Kiu?(cFID-N&8rt#5C(E@RHQ-<#e{uC0W=mB z{S?{^h5rPDgnu&p&oK9A>i#3l{hiAEGqe4T%4Ggu7c~Dfys>`G3jBTHP_>p;>|XO9 z3Pt%XV|_7H37r-he-IfU6q!ut=n`{Mcr2~P!fG3ihR(#31G$ppvyT*?qqrpMm4>cG zL%b9sh5enjYc9N#-1W=#TMMM>m8-0o zWE&)|T{b$aM=>qbtQ`&R>1_`C9=slv>aClPOl+{)wKy(XYD{W*!>^7jyc55d#~FRK zY;G1NW*NP*FTZo$eeYu2T9#cXv|*vsin=c3`V4$M$Z~O3M4d{bR3`MoEK$X)nH8%* zEm*jQE#J96+iFRe+{(^Aui6akg(oyQa;VzG%WL9F7bxtosVB$N8=KVf0b*j7bNLyu zyCl=Cad`jBl?+u<)pRpy!Botn(1(Nyns>K)OyziO?We_LIl7Yjsw@T_@i2>{{Lm|zj+=`Gp)9&fan&{yc&#VDP zAdpgxn0t^j2fMMBGi<8XZKFLn8bv-oTCn~Wz;3@-=6j!6`(;B1IPLtErR+s=6!+PV z(oWiuS#`U$iuE`_gm7^XN++J>2Uiw+a1lu9P-TV*f#(tm^aHfT83qIbPi8rK0PV~* zx;4l6+8?#2sps4C>j!7e8;6V@Kii@<5BcU1w#Yee!9%)HPboZOdD3Q`Qw6o$Uw&z;((P@Tryy2&F*49X74pUf zSf*;?T|B;zi5zk{CFA0zMWEC*2!mPFviZloA05QXVcJb55D@4pks$UQW@Z zfRJI2@K%rQf&oI2@m?t&whATF|FR2`i0Wh*6R6G1w=yEP7UwC5G7mVJaJl3ppn+D< zwVNFfR)zeXSyI&4mqp}BysvrYQDP?^+m_Wh>4^YeTW@1At|y(|p8AbhV2Z;+ENI3B z=}Xvy{R%1ImspXuJICKhi0P4|GWdS3880U+mGGoN4AxHX5(xHv$zpF{W?7KWC+Xi;EL^$a`sjr- zphB;0R2WE{g5qzG8KkFKoe+lFSR4>m0T>fkaS36FSaGOTo+)weXLX@S_c>eZ?vkHX)$ zFLkH0fGP4L9VnFInjJ=Pq>)!>r44h#G-yng6GHVIoFj8RX*HDpbpsr9QwbPcoPqKiy- zR4$(>cr3z7i+8b3kv#=j3l~dPQMXOMbkbBH&g%-T#p#tZjYT)I%d#_(@x zw`2syR#ZCwwL@h940C6E7})oq`HiU4Cs zS#t2?HICqCC+PB|(h5|6C=5c*!TcJ}=$s4wglsAL!NiUdU34zSxcqQPxQr!W3E#mF zt(95o5L?frGaHpc0Q2upCjMTdAe7T>AhEW5n|3LnX^(-x;k8G0yq{nK4hkHF2o$j1 z^P;q6K74%~*;8oEw1f$dK#Vvz>_Qai1M<_O`G~7dA&i8985m<}jsaOAIU3~szUJIR zlL^zvtr}H$6($m5Fb_mEuvani*m!4-d`@W=To(J|cAK*f3Epr;k8ylSRJ`1ag49wN z?OuNA1hY9YNVPNfweEo5lVt#`J*0ryS#bP>2m=Hx3Hp_V3;ZjfLY^9YcU`aBknO_^mwJmpqhQz)>{9XX3X#ai|>&Be2i!v<`%N+ zLFzZ{@cdI)Gya;#@t;8VXI>%q?jWAmxj9hLF5Me~(4QpLp(9tDct72dA*UJ;mosev z>NG~f&-j{g`DIRNDhG2ENZs6DUekBDTVQ}8zCUJofhsCJj^KqgGWl|AoKEugKAIK< zyYgdE>iupd&ttU(Ug=gX=dP!vHg7Old+djzBv4}z+Vq^3I|z{A$ExtKKIR+};fc20 zT2wf}cp31{OSP0MP^=bY+~AFkqZbZ=EoO_4hQRh+&tV6dssxG1{Fu?%rI(czNz;&2 z`$!MC!(bNUjg`dw z$n^B~dyH8nyBAOg4d&v*4N0iQ0#tx=>Jzs#xw(RigZXCcNIeb;p#s=L6I8sXxnvJc zyV61Gm3_lU5U-};xn5#)y_o_M=Wd}Mv=qIYYLsa=SVBKdiz<=t9NmRm$W!1+@||{OVOl>PXGj9V-9YOC&lN^k2cT~bOOw=wD zR)qEA>v;0|Q!jrAlG$@9Nw@ZBHYPjpzA*1`d4bB!fuyaMang7_24&kgGl(#X1LSX! z{WVL<%p?cD^ud%`W)jo@c`@h+7<6uNnbfMv$%LJO-?Vi0a;hbDqQ0_5X3|gz@F!Y{ zUeXsQAg*gbBv1MUl3oLQ0K7Zz$R;1d0Nv*Jv^b37a2CvgEeDn9_XP?p0rQEOW~1 z!2tNy7mBeEkV)WlJEpI8^escgDqO1Mv6s#bQA1`T$qTCAZOKyAw zrEd%R&6LswTHC*aA#DCbnr3tYyroElM`YlZ#NsC$uuHfDDFOfx9}a@0{t&XI#Tg2=hi3_rWL+SB zcD|v&bIdS2OlkR`Ky=U~4|~~(MQX9koni*lR)$U-?{OhN?(-&a)_3w8Ev{;+Y*7u| zb)a(AP(G&_R1E!>gLB>pcxhKTdk!$DQ=DdfC92c*iVjC$w)P5<(UwkW6MY}v-UT#8 zPM^GnVLJx%E@c_)k~*u0JOv7qs8?%5TEgw!3Z8_f9h~nw?;D?h^JRXI{~1xgv{e7n zg#9<2HuFDf-oHBSKlAH<(`o;?M*i0&xBk`kewD@lRw6_F%R~0% z>SFn;cK&;#{I{O^?-lajjA#E;nEla3|4U)^Z@M3rKRW4uj{g6(c#?_jtN;FcOmEWC zh+Q8-^f{{4-)!|uHN@-0-v0@S((mu}GcYR?{DN9d%F~pckR!!-zvZQ6zmnI@$&6Y1 zr{4sQtD2gMnu_m&ir3M{akrDm?$|Q?hP<$C(vWR($EQ8K+s}1?PX?GPjiR9|eCHO= z$LViu_j6%lmVWM0ZQmG9N-fTRYWSv^&(wH9*%Z*4);+zceM=e$YXDA zvS&mpWvg{9oFCV+@p<1@+bzA89Gp{Z;oRF_ttWZ-?WsKTZfzwpf4Z>wI_cRZaq{U{ z32cMsrM-G4fyrZ$A^%Mz%;|{i68JGuUhxA$lk&&dp--9Qm$7g=mB)7it4+ zV$$)jaIK!aqFM9ulh!^XuPD7HnTYl-RP zujN#QUAPsb)#fh49zK?pcQ`6rAD=}aG?7EXdm)B`t!KFO!YKUP9{tfMV?G0+BG!yHK`IFe*UeOg0=a3S zJt8G9bnD?j=-TtcFY(Cwj=2=e$OkJ#dr#z6`dW!d%sauUE7dP>Jyksd)H%Ud4cGSj zAi*?cL==I~^T#sE>n0+-=sf;fx*BV|HjcK~g={=};avKGU%& zIFEw4ubgB7;u_^N7S6%RG<2-A85(C}&@;BV$3R-WkNNqf^TV7$4Ln-HW*d~PBigoo zPFZigco+M;jO+4YP?ejw*opv-6973beOHben(1Fb(P7Z<&Pvtxb%rcI_lcka|h_IA}0|X~hr(Hw@r3fJfChP4G zSOu#9N+5|bL~*bn8T{++b3?uDNM?tvM@L>X{R&5elVNNM6a+4lz&pB_D`HpI3%NkA zP}2d1B82)}Fblg7tXTI%OnOn`6jz`@q^=wJ#7x_i`qrf!i&|Y5=q{#$ zi7hzka?(~I1d5n2&{fVXUAf%rnOLReA)xnhfwQFVq!4%bmb5cIBi})502@LWC&%d@ zCkQD(5aQJ}i`b3VenUp$OX_xjr6yUrx-xI-L;0!AkpiTS4Z@no23esajJO6NSW5_O z5HRWFN1KkwfTngW8)thUO=*_uW*P4GYLv2KSge#2?UarXf!h!4ZK(E^2Rm9GNq)zr zMWDhzM5w9@w-lDI+Q@I*9wUxn5{()VqF*OFMUD2Bh<@wjb0u`y>9>uRM%0FM{88$+ zf%U6V2t9c(@8b;xTlTDlG)Q6Z>YHu!@xFQ&OF!tuqO%qQ%R$?%p(#<^PciY(;u5}9 z2>jPdNG9wuLum|&s;Llvyj!T{E6bZjKhx*#TMWOGg&&0ja>osx{2eCmp$$`>vP3Pb6vWPXi+lJk@UI; zy^V;t14e|kgJ}HSHCFSp6)pT2^ju&eJ$;n!oHMsmYmpD^&L+V z#{1|x^(q$dcglV0O)TJjx9>Jk?Gf_+$*P(yVj!JE9JwG;wpT)68b$7`fIUt6Ha|Ad z!xbowFx}NNwlV(})~Xcyh@ZWc3Ed$+@J-4kSFH5;X`TUm+@E`NjQiSSpm>iHl<`z` z;Px}pCqx_G&0XSKzw~p|hd=uS2I}hzqz!Y6*l&TbTXw|$Z{a>Ezq>PyKX1;H(6nOU zJ=^QFgfGO+y(L!MYS(`c;@k#WueY&&!>b7}UKdc=@QgRsPHg_!fB0P7?XMGW&Iom5 z5HJo{oPP~OzN7@|o{d)k#US@C^I_$~&)aPX`h)UmL}WJ@)&ACp<`R1o2eOFcw$nFL z*|Lz%e;xOavz8s@Eb4M^3QrrFea~hL#6B88TE~iRNnO3(NJ}3c^UfywQudC;rV^be;IJI`vvDVO~t?D*Y z{B8;MU>NA)QZ6h~>SOqJA*kjiPcoz&>f9j7aufC@@(ED?R63owxc2y-VFUW;6bkWq z(8cMewm{$1alnCjI0Z4F60~8|DWws*HaP)MMR8cvvHw+}+bYj}iQ3G74xZRGc(s!M zUe`z6WF?VddW{#4D#@ws3nlLNXLYIyS@a=@j_Uw27@V52w=476%tF&-FI$=*s_`8}{meCr z@J}L6s4XBlZN~)a2OX%G3fkNUiYA5}kSKip4X+|qmNx-HthCT6K*&USP5kh({YW?_ ztk{%}4XjOej70LDXpA2=I4OaRr8v(E)(2U8Kaf$X(U|q)N>UC9T6pYFuNF1gO;x}e zRo{^{#lB=tpR1urg#7$-T@{=8hk8`w^1fYS)5Lc!62F(Qmu_|auuOoexW$P8I98iw ze^9!Ga{JEE0_HBre7n14sFhDw#mzK?7gG%d6dkl-1C{v|-OT*KyJbp#rgR3{MNi`9 zp@e0oW*VcW>ZE)QhG#bEqM#p+oDIs31+KVe`1oAHB9vA!*E(L@UhJL(gBYh6!>{PQ zS~j|$Ewi|ut9wW6bc}4PGC|Q32(MxsDaM?09>>{RQ3O7;btXMI0Y$t*aIFR8+fPLDBY2J(@wN_}b5+Zy6d zJ5zy7L%&tINGtpy!e#(bh!kf&(y%dtiWtZ#srW+x9#TuEDh$K<8ZEK1^M?czh{?K6 zG<$P}Ix<6=^jkP(S`8U6XnHM2*>rcTt>!>P2*Sppq*@==&zXL)fI8-IM=&hu>gOOU zS14cLH)I&w(&Kt_2;uSELCMqV7c8(KfOciyf|q*A%W*J{2OEsMP>0(hfMk!v-GWtKnEPR_&GVSQ1Q_YiVb!vV#M&|=^MH=*=V#z}Y{2)>(0{H`T&pGqJuSzq-66?qq9cd5*np)zPk$)j3(y#jv#dRpBMr{s<;h3%ys zO1tQJDlr%IFyaAaeB;XO;plV=nfzWQqp-f`0R_9f!G6CG;j!?@-(@Vbv~a3~!Gd2) zX_>@RnIs}EEeR-Vgy5P5zcB12<$bcPcfYflXzbST)w`d6<56tA&7!uI1M2j1Wu={| z!Ht@M!L~D6O-59z$V#$w^nB4q2N9v!bn0Zl~2exenav9Gl$W&aoaE==YSCy7p9YOv_`zDCCW5l^5l^AtW4DDn} zj$7__nVf6B&&8Ctzx=mt z7di06&K^GxC9v?Td*C)2FQ)VxpDI+g{LM$_$gY!(BQ**}rX;uC==T}I5Xp}NAh~#; z*f@q={&;K?7ppZe>3gaO~b_X}A6C%pa_ll~{={cqC)e+&43pB(u69Kb&l{vX%I{43%A5%>Q# z3-E8V4F4U5{&$G|U-J+DK5_8hT9=rZSpP5Ul9ra!AD2iRuH}CPk&(pch^)-y{(;Mu zC_OjSRPvj73|LTrQ70k^@>dGiyVkq!`_!i2U~rx|dty39QQcAVkq;c-lieG9_sBat zG%_Dzc`jOdPvx8M)3-POXT%R9Hv;2wuTZh@9RconPLFF#g$n5K8flt8?aYO}<9$!jIBg1L8jbV&fg$biv;??_v>mJa&IQ~7Mq zBDS=%d%M32|B}cGkwAG|?t!#VgiiUG+SVb?kIQAbg+@Dk@)cBVC1lBBvfAAGoo~ZU^`@_3d(04;{;8NwcUIA`b+MJ~S&(>?jyE5wx2ZPH zbFPTHX*U@jtHvw!mbdE7I&&K8*v0C*X}7dcvrbI~ZSg5@y0ue>hd}-2wEVTO zuOrYI3`wm^2k)Vh<~ZX{a24hi36TSu2=1tSprDpm!4NX1=I!iJY$FpaD?|hgUAjh< zFM=DEN%khDk6VUiTN>E36evcJfPeG;7hYah*bd)$vL#A+*DpKU04luUE__Y_;Z=pZ z*#T-eqZCX;i%bT>zI&OlV~B0;iM=9V^*K4_T-dZo`q0CUc3$v7Zg_X3?*Lj6qcqtv zjU$3XoN-O=V5tz85jbS3Ke<}is<&SrUZ8M?N63*Xx3TIJ?0x)+6NssURIFf^A)Ygp z0L2VYLhC;$sSw>zQzmlw^{CS%+#vj%BGXZ^b`|t(@fq64Aig(! zTvLIsUm}7KQc04}*nh~z)So&_k%?V>J{UZCo@8Xrr}KuRdv)>EvSpPpTxs6BrLB^@ zFmO?2!sQCBR7D?E>Wzq?0mLxl8gcmi*hK zlRNnTN839F>C$H1x`kD?ZQIr=+qP}nwr$&7W!tvRRo1GiQ{B72-f!>SAI^z5f1b#U z$js-CJ0pM0Ip#G6hIsq$d5gx)Yuwfjho1G#Og7@{dvA1cN(#B7w6_|BB@196{`$#m zGy!nFwhe1MKlC+1aVr|U+ebm=K}Dh@r>?F$3UV zoG#d#Dw!V5qV6uVMh~z8sAxF9k5%@dr$Hz6_B)|gUz8{B&tGn%XhH+|jZ5q;`1GzHeG~Wbz_jr5CFb~)Cm*mUeLQvh+~ul(iG1=p zlJC^HlA(E`NIhPzPWQ5Jc0jZ&Hi@A3R9US8cd}+0c0tr|kJLce#`0io?$kkA#eGDY zMP^|NFfJ{kfAyVZd1Bke^W$`+td$wQzO-%dR>Q+lum_^aQXCUg6>5DusiI@bDda>TUcD2@!hLv+FOq7V zlDk4b;;ftCpjIEGxlD`VD|&*&3?OWuQPM-E71~gf%W?S0x=xD%6i$S0r$MdCabIPP z02ZDN3xm}p-!?h&0-;-DLHfmzV_N0~iN`s9PN)?373Fd&CbYNvmX5Bw$LplZ)>hN&a$WAtgEXXlR zfu|hV&&1M6CTA8tF{|_O*x0thE$KYg#hZY-Rv*eW5HP|u1GvM=+z?rEal8QvR(1|4u^PajPSXe`nbj?5n>^1e_gWq zP)Fl@FqnAndjU4fd-M`V~0T;y!hE+5Af(F8N}FM`A_Sux+s}oYgn}Jy+vW!A4umTR4|7 z5)sn&@bl~o=#%Y!BNi;vkAP z=Es136X8^NNEs|7RwW|zt64W;nnB>7d3-Dw`4Ib;OKL&MLT4aj{s^({QVF6tQOt%o znC95HOrpy#8wd|G`j`l6Q-SUZJb7_4`(sDwD9?q)JeDc<+X|DE(+fd!_AN zXr0121}xPghjuhN(!!SMfH%2#ZH6XCz0HVV+DkStj`B<~NRd7!a_y)jL+DQCs7C)0 zGjWJXQc<%|V~Wg%eRE^U;W+m7tup`ILfPX{v_-NifTHrV9~b1CIs89!gXT*qq%pUT zcWHqZEOl()%)F&GL#GMe+LiL4;DjB1UI-)HZJP!TvBNK4^$R-`Cw(FCOe@o9s+Uy%wq4a zf?A_YyS~k?)WWu>8a_^j+M12_y0+>C&*nY@YB9Pwq+ABsH53Cm`lR1dMD@3q&LFV7 zP!H;P+I$!^0{SzGkUpnngP>+v&{uNqg2-Os#&E;PW>+uV2Hqr`H{uwtxU?43vVeaZv3{L$zUW2^h$sy^tb`K&L%T~17NX#?C1 zqXRxF2Q&DUXr33fw&nPF;fJiMFoOOJW>UGanqgUj^3Qz#$WJ2u?Fi8ll%SP%f%3z+ z-UNP%x_;Q-N_!)#ez;HX&jxn=FyJPU_p;hSp2Y~}>qe-$VRYcQ1B+snyNOCH`r(=vc^njY^B$i1nMoT73zOs)|;R!Pw?CAz6m-&tO`H$WJ2v?Fhj# zc2MxW5(Zc8gMtRFDI`m+?@b~#fZ6oegKgJ9>YgSKB=uUXh=hD(l3|g;!sYIFP5|itBsl>hRQPB;W7#UI7+eGwA-JiPx zvJx~{0T<5uPQk3e{xb%p;dr7g%mwXn<^M^+mZHK8&oGKt;N`k%rJ-oS_029J!^j?+ zHDc7H(6j^FO6AJx@C-aDg>+FXFn@&AH~k?HG$?_s-$Ka4{g$9IXOE=XW5GswX`vrL zS`0DPeFC7^y!}vrvOxyM2df9eXx}4r+@Bv9Q3;{FdLIs&1@*DC6P$}+jV$6HFjV)k z1-Suw>@Niv(`a)Rd=yCrrkOu)f66uTTdgS=w6vk7z-sjgQ=hy%Vm~>xV=IdDI5m^e z20yzmszMQ1Dyc-)rRdcn^oWGgI|gE5jl6_$@g)y^nqZp%&r-bILV7fS{%TnQ2$Q-v zp85hTGU&nkH)ZYrTRxlR|Kzh-{*hhv-==H*{m%bi%G$pw)PGUH|614nN74EBTK3G4_qks0$ZMee^Xg#Z4ef6HC}YyQP|f%?B22mh4_&cgJq%m0fAp0yD}#NiNf zb5AkvYSEjWIO$kZyR37g2SZnPKw${j;hnEiUU|5bFQOnl1O24_LH!wE6qnAql0Wy8 zDA53PjQtM+H0VX?L+C?k)8%}{)OizaX4Bb*6PN5)M$Kzq5yuxa4&%Zqudq&Oqw?E~ zt9j<5^)=_qNQ)SjqOtc5scYp!M~5yIZ`XUmrzVP)JKWhw!T7yXf@uj(=iyN3 zgYSHYujJR`w9M&Y+gP#veF6sS*8M)ev?}f*Em2JeZMZ2$1{6)j) z+dSRM51!A911GwHCTGr9&Q@7v&b6s6qUgx%&(4(^r&YdbKH}@jC8u`+7Hv*Xri{ZPcegW~+LAJ9m6dAUgcBp{)Fi3TJA$tFok$Z` zf1B8AD(#ty;d+ZZ^E=Rf>2#FgDC1qyEE%6)$u_{efL1_ypY>+#RU>Za^G3?*?-;E< z!^bN9WbB(M>fsVmNhSAAU!SP$yQ9>7~QlNp%I7?kdDo1tv**Y{NbA)-ND zk5a4`D@e4Cll2_Cbq@P5l=8;_YFj-$5=o$&oLP2*@!&`uL+9qNm4x8{!J(<8R|ddJ z?29iOm{#y|FYQ@7eC+gq6hXzcp}!#YM)|wro3{PSmA8yg1$NdZD~63qko0j3?+@{G zYqc0v1)&$p@nRj`pjYhoXMo;}N%E*)XmeH#+HE&&cx|=d)>Q-coe9ZpUi7YccgMz- zecqvqY@Zi~Jm?ZygV4g}5prmUXjX^chb+3cX;?3Ct_OTx>y(AToqA}WVl&wXW-?D6 zc{X3vS|+{PyHyQbyyj946_T7$uc_K}>Ii2jABotB1Uexu+^X@)E4VK_20bJ|Z2)UY zwO!2!F?k8K$q7FOF34y&1t-&0hvcK^H>z@2FJ3)t1^qDzth(_71#&vQCk_@&Os%zZ z_-0;5HJUrU6LwHNJA2eR&*$z|Wbqq`m^Q3h?~k1LdS+|@0Pu8i-f05Hb5<+P+o^B3 z=;q4)^q?hEL)w8xt>@KVbO|xc_Xa>SWlvi%6VrG;%zw0OUtaYWJzgAeBdXt=Y?NMk z^{DZ+b%*~Ru+Jx77<+SnbnkA~Y77h^gDEa@Hkq!FNPvo72JakYau0k9-5)Pcr39p zN?lG5jE`b67Rj(?-SF&R`0yh8slYr~BDTaEvB-DBI$=s?lbbe>&-ig8gpm*t|!L#z!ziOck>`Ot6!(sS%u102m(9 z(WpU@i}+v$x72d8Qp%5wU&VWS+Ev!E^!hGQ@j2r|`Nidz+D!PGuORn+Do%JQOk|T( zQf<|9UC~YTuT@s4XJ*phZdYNaD>=YK5feivGy{{azuze7I%^1QJ4N*a^}SJTkT0?B z=dpYcn5&Jv5+|-7`8rJ-7v7(ztlFV3IyhTW0~yqHSA49#CRdGPTUIhC(4(>u!rte; z9C^0ZXT@F~PF|g!FP~)`Hw%sG zS$O@ahZo1MA8t%``Op~d($QnbyNBs)K*qtdWbCe_0f!e;(FEm9)-QF*TSn?Dm3essZL7&@p&JT~aV`tUuaShoRO|FPm9ZzD782pHmd2*8Bn7K6CJegd znhf(fsX+qpptqtyKNTrB|AZHu_n83OsSvzMG^jIrbi_Btkq#ai# zI*Q}oo`ptsp{@W|O|>z|7rldXi39gWW}h)=Y*4#NAQ~T#_d7I4sJ*3pg>1X;HR2;x zz}b>8pcxN`$k`pn&+N)2JPVd;DD)A=L$7~fo9$_juroMCcTa#Xsk}a>4;5Jc?k1?S z<C*-VmNoN)S+ zWKeGLhlkLdT9VRH42}FR!A#XLVg-ff=mT@8gJ5-Y%`EpkrzT$c>kG=QiEe>I6s7fM z;)=Kuy17+a@~X4J4+qdaWo+jQcvkKO)P?0k&>`?n`O^-(Kstd)Mf2i3$|}QCF5NbD z;&p@mPM+Z3pVySu;IAaW_ftykf&-YB7g-W$bMCRq8daSnJ{T2FR*K2jb&VylVp6WN zmU#ySa|XyCc{DVcpcwmM#cbOpcr8DoW4Z!xK_&QAo!PDR+UUuwsRlZE2;SP3Nc5fA zD4hIXO^OT)1wv74V}zlOXbl|ZP}x($M%j_>YF;YxW`h%>D4BaSe`Dx5o$ev1P?WWw zqrXj~`~3YiC_#c-_$;Z~D6jbP#WJq3Pu| zOil8lJpwfxg;$CuvwM&OZape!)VM!Bu1d?w|FS5n6`2@3qXEI~nT8NE!HfedYF4GG zfIvu#1TIIxY>bI3$E(!ZA;doxLoVRR8jN)K)(dJF%@oD+%z}`_y080>o9gbCL#+h{ zIyveo4Y3{s3}PNUmP*z^Zwu)Sht_a7V&?8fKi8-x%5Eb6S~Hk_8Nw$Oh15qy+F$zCPK(wJ?589Z zHhR@+IV40`2xE$A7*jIk6)ZHfoQoXWS}MsYvj!4YA7LIyS=q~x#!}U(s+=|Ck-M^r zgIt?1gPG>E57dW1ai4j3B1&Kk$Bqnd&r5ni9Q7JVg@&%dDEuQ)r0tx9UJdmM;4p zA%MicTAQmf=)l?5AkMftkQu1wlh@}Dj3f&}+MAITzH&~{y%0R$4P4^^c4@+pLw?`% z2Fdg{(^F)(kihG1Q7#(l1VOZV5rrNiY9<6UR;Ct$!@_CwBfaeF?e~X_n$9^P5o@}8 zUzhQi9|GjW1vGN!EF zYoiGphE3gt3WcozpSC%t{T&9a5{)FHF2iK*?wd^u6_X4=ZLYNW~z=Ee&E11m$_UJVuHjXBRKir=aN~lzbN!#dnVf#~SHjv^5|6+xr%?R}OUakCXQK-^ zJuEV>U#bq0hV^DHEJ|_45|UgL^7$+>uBRgp*AFm11BaXog!u#sdm_rx0({4u70vQ{ zWaRuwUoD@%qW+_c9f)K5p1U0;pY9gCi=s^DC4~Fj<8E10K?QXSbT*Ye2#t!Jnj^`- zV$K@CJ6zZZ?%lRRK3_90*vtrVpWx4V;I15)=qGcmV!0 z8_o$4_tyb2kN+*D4Q#P^_O7lJbn(^fC6aE~0)ZE9$WH|#O^8w%(eT#2hhVvOKbtjZ zyEpnI-ce0$*k##0W^)00a)Th)JbY%_QJ%;JG=Z}M0@jM6jC1Bh8{l(EDMC>NCl`oP z!LwE-2(0Uvp{nl_E43EDPKwgRUC@(^R83Lpt~q&MtcbY zhnxn2Z=(XUlssw0+&QPT$qq%uOF%t?Y9L_RsxhVCxb*W6D|6kf*@dF3QlEnGOCA$a z{iZ@Bv1hhnek9Bxc7T%y7{$1!qwMYFwsJ)L2WGO?cfm%2^~lvdpMK#bP>?Nt0U%qQGg_K^xkOQJSUB+W_NaOEToy0u z#Vr!{r%$ELY*FMN!woC;R$imsYXqF;U=>DT!JOrF7!)96(+2A5zJ?xX7G2Lu%RQ*Y z6MGx)l&dTDF+;{%HZC1osJh4?x^jnBXguK4sc88+4~RW&fxdQtFY-`eEmNuJA|Z!I zRu4hSSn;ORcG#yKq0&h^<^#JUvn0Vb<|9L`UAdr$K;ZuI2zfD&@M{PaIkW!bTWBiK z;-7RTAS2j_fjRm^dU$^f#<7F!$DMw1>=!-at6;Ew^HUSRDwfqC9iodkMmtMJZ zl~L$dH8Pk7>b!OUtMc5OC6!+2))lmKJSyNE8s+5TZmuG7q-Px5O8Q5Gc5u$aqcaTw zhU~C{@4z~4L_K?`n;`v3O4#$txIKNRQv733!ZoGt+~cykh}#TznE{p|LJWr0;N0EU ziqnk&Qz`=>hYZF?Ls*y7ak*4OFgZebt-k|^@>M#Qz$uc@Z0ooM*PG%j4iNN>hcu;P zfn8+6x&f(ns}F8FGI3Kwp;2TFb=(#X){|f={V7_5;a8s9GgG1nz|0TyEqv$h+DT&O zMF&o&oeulgh&-%hwG8t7x?jHdgJ*(#V0l(x?%v!A=-j zhJ#hL^+DvEfGD%@2;*!EaUUV2jPhuS2LtF`-+fzt31u_CYf2HAr!_7uR8zidxHLK} zTv}jzx>PvWDd#TjvV~O>qgWBIyM9mb0OY7ynoMi_{=ERT;6*YP9HP-&Ir*qc2zR|C z!5S1W8g8{!erKZlMQuK}GLV1B#m-syhv0ezPBA7M9Nj+tbnef-DB^ABuc~@)FAoh` zlZBb<>6DLvOc!FjwiiU9>l*7GolOU5L5q3W7o6y%fz+INwE@^JrVLg>l0bWS5F|eh7naEXr?t1Q@3XHYq2~Jx4pY4)rTjmMN(siJG83drUMBr zTBYT^Mh%=_X=_YuXIt6|ufksmflJwOloueN4WZCrzRqW+rDPUTgBtr-unRIfUq_;r z)M_wm>SO8ao-4?J4E(-JJ3CAuGT!IXIaUg)xMI&!WABD`#I>ysp|1yD)i>TqJ&ALI zbE3I+NMD5}=crs$YU9t9XNf_KN+b*^g%;wQGuEJf43|UR*^EH~CUT{&$_2OC`&N}{qbCMP0J=F(DkZWyA``h**4W%D ztEh_S%xn)A#2gb$Oxa?-jPAC2hGc=w;_xBj1*cWcD{NR0=ggSjy0CU*=WYt{h?GUl z5lrPv?#OE+PTRsiY1R+G5J+BRcm354-!RgR=H3Y2-ZRC*+Qu2pbLw)TFpdbLD=XAC zxrJbi0AI`Sbf)QpLY&y)Awd{`Ld@&!9Fi0D#c9Z9GZE* z2MsGv;UY7ABf8t>+;jv=BPz9yF|pneMvamqlBtOTqtxgbd)5qDgGW+zx4fQRcm4=` z1&j0H=DdVHj&ldvu8d5bciQuzTcM%H?&LgG9*BOPZ7CDi;fic=+h6!}Z(z5Y*xyW@ zvji=n_ybXTO7Y|8Vq`wrI0J!9*51Tq2ziXYZtFWnGNj#^cW~+2K4T*5TZw!UWC(T? zL@B4QMD;bOovc>pW1xk&w|9_45X%TBrK`J-Y!)>M zGY(1Q-n3qLz6mBr9zE^Zx4N%h&Ipl~L+%>*RIq{02u~aj|4zIZxNYO$!F_UV!hixo zr2TOz&>AvdSAY1}vlC5=kK?wT z@mPCMKM=v|*5JvO(VQxO%jdC%ArRx^okjJxv60n@N+*wKQ~D`eT<^Dw#V}4-?+$u7+-oId3lP0RNF@f9Ch5xs_S=6I zm7cl94nyB;$evloKs`y>sWGM2bg)R;v&?RQ#u49CII9SsLym5tYKW#lgd<#8S!4!A zld6(B1tLU1Bxtnx7YWrL_`bRngLt8i(+-GZIYx;FfLgs^I4E?pV<7Ys`>5qc9yuL_ zmf$t{+fqmTRD9vE(mYtQLankki4DJWRL6%{;$(^nKlI62zJ{c@+9r_Id@q(jbYl#( z{X{W-|Au3@6{8eA5IWRr^UlIwB%9ZW+gYnX->|6Guq?IP9p=GsU)u@R{+(K}*q_LgG`7SE0=W6>LOiyD?S3D_-_fE02I8kRvz)R>_wd@ndD3GL+DPDD-q0@{6351IJiyxF0o=<{X8-vDBbvu59xv(x+5Sxp@WjUS8t4=>1hyi zqCF_r?K&rc@VdkjwqbJNfLlmZF-JP<2xB*k+VDbfs*-yM02*cK)#o3PMnvNi7^*X? z&ua^QW1>ZGr^nMm6QQ@E49vIHrw!+jo;|f*TQ-MZX-ZUr{RlQ(W_x?t=>cn5O&mcu z3^+=|wlNqO?)meUZ+|=zn6O&J-lMc%D9% zgIKHJDGuj~EaO`C9{Sm^kk|7dDdQjb&k3X{TFbue?U0&tpg25xu#L*`t^Avmk_ByG ze#2tmm4OOXOu9X*y&fF8_XA30A|3vKG*-F`bLvdS+YTxL^;qC~14!w`SO*78xlJ9b^IQ!fB#L1^OHWn#FoS)fJlEtOn7sef)h;4PgH>i34_`rka9z&^&Rkx9W@kdtq1E@LQC&|<sQ= z0a8Y2wC(5vdP)3|jsZwQ=vD!6ZFbmuu~_Us_>S5DQR~S;{>(+Kej`|;_`A&Uq*lKH z8UxT(%+UY_{Ds2DMphBrSAT{OKsgaCLiW!Gpa^kik6zvp;$$0b8QrXGEUZ1f68umr zA+9D#fGYK*jZ=v5X_4TR3RY(iPT=+w8Ru=bEyp zl-cE3DJy5&;IoC}2xu9h?!y79grNACO`aq(S8L{N#3Y62^O-1T<^K}z149CN>vJla zI2VGhK!QpgjfNiM3<%9WDbMNk5kjO0CT&7eGq3OrU*S3hKZQPzsa`vps+FbG$OSlQ zf~6U&7`=`P;KoS`yI_%jZ`d7%BkFFSTcWjFPl@}nn?eY`&AC-T?)}#W(=XY zK(&mk$|-GU53T_L_Bs_It%ii3oMCX#<#ghZCWlJzc~ohLS#~_Q)^75U}v%C`G}1xx+gY=*ybMj#3%Utu>Bm!3Gj6$ z{&O`%&+=N%#a!60V{^-=orf%%twp(0&t*r-|jMeGP+(-vH!mVCpl6E60ysMC73 z1dYLhYHu@Gl$=LS)4yY-XIi%1WySg>^^gvw2W2z{MBqGRT_B$v-X^uv&m8J|NSa5P zH?gm->oN@^x?<31fAIDhON^7?KcC$oFF3yDoBT>elq2L%0f>WpU4WM>2oQxq`ojA` zZPyM-gYwCU1K1Y@{KnkLa@s{jf$A;{3mp`>*dj?r@aH>Xe6c!;y}&~N<29Mkh6G_W zFLH8+QMC2uTGfoCN>GIGAZ_qKwH%)89m#(6qw(xL@PUz$-Y%o_!=7sPgwFKm zh<$4naQ4v2)sk^xO1_dB%Yu&co#|dKuA|OyFu_~zT3!y;16$nCgyebDtU2I?-62bO z7GdVM30$99n&Kz6)uILO+k6QwsU%6ZcJ-`^xv52Z%ib;l`SoehPfy^7Vs(Lu1{&QY zk5dVMAqq%Q0L|I-Y~EbMgzSPFQLhqgF=k>Va7V8O`h6I#KL+nfL{Nf0a(wG{xTI9q z0(rReA(P}iT^WJQ9!BM!e0~pARY8&!?mz6!;8b4&s-(#XoK&U)FPV>^$pqzLiUi?8 z@39rAf(4gOuVLanWN3wp-K*rD9`w1IPU12!14pZ#5GD$~(HsaqitXINZ=nL}K|Xx*GV=cru)}O&7E~j_iptiQ?Aq~Z;BS#Yvtm-d zHTh|Ry-q9Nhq*wNdz?*=uM_lT3Go!sNkI(Xm1*ZOrZmpgwKP}NyS6w>#OVPIFJrTk z#bkf2z-TY`%dZ@Fol$=6yA{z{x-!%;U$8n!qhbkh)jndq1qs>mqMMuDQ<%=>nhs-> zw?&+%V|Hb#?K(Z9QOkfGwMQBjs>_}&NervMq>XnX(w(>o| z4`NE=F&1uGGG=4XzfMDDgLF|~(|PY5&cfDHmVFO8tBR74C!e9(?UU@wwfh%&kc1z4 z6lVt?;Ci1|bWCKS-w|+qa&S8^EgCIWdtS@- zmh}X9UIV+N`8IOmwK8F2Ob@*5V%+5J*%X%}_YH}NDV$VKIfZ>4K##Jw%eaO-9&o>* z`=&|~b83^o>c9Kpj5Gbx)WBO0oi555*lOr!fP7)$H40^u*(~7YaK=miDT)=d_|}VY zWddBz5*pYY#}di|Aue3~)CMs*NNU+M@IG}Lc3-@3 zW_tHCfy@l#8ZGkrO(us@$?KeET??17R>V(-NhlRD$4A_i*ZmAR9$H}(^SO>mY0rfg z8Sf8-2iw=uI2&ShubD}MV$0Op4cy6|NdUg7{a7#9bO6&ObTHt7oMM1d9NcR7`wf^Y zAvDLxE5o6o_h{4|^pwQa6^2dL9Uxay=tnF4xRo1>X3L;u+ZZ$S>hTZ|Io{S-L3xC7 z#<^=GsnlgFxE0nEj5GYeHW^O5=<39r)j+aVlkK^|4HNfZ%RP*R9n}EOZJsjhVT`lW zfSs*QHI|-_Czr#i2jg#9q;6%HiK~u`1B&e|D=52a2$?iNoZr+&kmoSvrsb}IIYQ5* zH4N3Yxq>IO)BT#t zLf^39ScIRG0!AytFpLbTrKh?&5}KA;P(gFNf+JXeGbwRSbm{Qh&|_rt@T6lwg84lsQ(d54$FPqx*$9oQr%_Pjy-NP&k=wtr!OA zDQUVO5|1OSJNhKdAi^R|+D;#3#IZ%mnbuIERe&>3HQWa4cE=AyHC#4})|OgIG91m@ zzJg%LG*t?32zO^0Q4h8n-iz&H!0?36G=6ybRH88=QDeT5jB6MAggs`Qy~}UXbV4o# ztI6F9d&B{m=o|pXkw;JP%eJ;Iig(R=fmcqh*N}6{wB(=(;6!%Y`gvpFBkZ7^73lPw z9a5tVXUwK1+pkrRU8-MsR6U?04tV?L!DtLr;$@ud$xm?NOT?y%7Umf{q$+33ctQSD z58tdHPh`2hW+t^_MKbx*94Txy_Jd&HmyCu4S2;@*}&)p|(=$kzU zz%GNn!Q+8&zr>$2E*t-Fnoody3fVw3dZ?1iOHXn0S{=V(kV>yV$>7xqdcanyd7lfK zB$=i$*Vw-N?X%YSStd#-2+<$<2SP2_66f!?PBYw|apAEpXlw2PqM%Nq+iAwat>^Qs zgNBmz8uwFpp#Oouz78yx*i6wN^@gF^Q!=(2wJfFtnSRN~3d2FwBuA_DThWZP!mj=2(6Kg01@p;eJmB-Vq0lDK$sLJ^(&Ff8m}SmQPDAU-o%>Je^?b)yZbJ58 z7|pX|Q%Bldksqn{3@$f4(BDcomMulz8`4(lcN9t-gSl2L{|af5S!J6Fp*nTXOWig$ z-dvCVwPIbZ&%7&D+)9`vBk$=3gN$uAZ95}s>AIVeHP97r=jc50ki@2ocs2j6KC&a9!yC@Lqi`I zWWoJ?T=WzRfk4{Q55UCxHp z8PI`9nyDS0@!(f1nE4u}0OrH7u|mGy2asFULeDK}*2BV$PSs*NONmH3Ai+UDQe@0l zgJXLnM=U0;`+s;SJ0=}w=v6lio`;Ru?FZX<40$gdXHaM)b+tyPth1+#JM{`{xZJvF zXLld3$MwgwKGX{hI5(W2*t{S2@pb{2+bslG4kX{z5Ay46bKtbAetkZ8g^ z&I__Q%6hJ-#Vk-zNFYLJl=FOlgtyU)Jmd#?EaGN?-mBy>E^i%j1ZeCs3MSP)8g;Nc z?x3Ik35+X`|}$50l~?H`b~m5qn>q|qQQFQY=} zv<)giTL~eTIEv-6tyq+8OSCCZEgyYLKZGIPqn=?@`nzIA%C$VrKvcUE-3v8IFL^#R z3T|aOkIv5Q9T!QZE0Ky8o1^q>&BIg>JZhN%8U-Kfi`7o4wwtyR*R%s7L#h&LG>5!R+r)?6>DC=>S};DY zYgeMd|4j@R>tBPl{%4}j-xJpU7QSZV^c@HGt@8Y1`u@LV30VIsApMUK`F~>Z|7WJ# z-yHP*fyn#nJG}urGf`yZA{)Q0NWuov z;$xvwJJtQ2^gMs(%6G0jjhvz9-ao-j{%dAxdYjLAg6w|e+Wfw~p<%t{edTI>tui-K z`1G_*FMRZzymq{3mTPM1Y{*uG%{9O(dMX)qO(5}uAcvm~31T8$aHa0u26m0H{Jx*S za;+;}qE+l15mh*)Q1=eo6#J-I%uNN8r=l6#hb8&CzVDV>@~-{v?tKKqD3V*B+Hn-~ zOaNGvnWqZcI78`|sw0uZ|i~|8Sg_;W)Rp7~N1vdrz;$H6}fFUBq zf$j{vZ8n+vQN&8t`u&j+;JJG|Dff|xJxV2jbEH^Me^7I4Rz11TYSl(2h|a+ljGTB^ z$N6vCuHg;9e^E@?Rv_Hn+@apcEzNhk6j;+o-pqhUHR3W zQ1T^sr@~LNJd!b`vsGQnGJ)(mw#$P$L|tJ<@5Vbku3zR)IM%!0PJ%bMvFJ+fh&rGf zGnGVpAMiIC`^rTuSsHg~v%?@WsJE$C7E4W<>)C(m)RATR2_Cc`n%f@w#6N*qKd`xgVonH< zEMo;fw8Q#t{jBe#%ipD6E~e0ro7&mjY5m@^)pB7>Rb3naI>#YUPi1z$vGS-uQS;Uj zi*l+MB)V1DG!FSh80-6>7wC0YAklybyRet2$=f5(Xq%GxUPBL@zgO@9P?1=U?V7w%Q(NAB$E3t)j?(+rHQhIB~#x z^J9;i0BwJ^89SD%i+(SPgd-Rk_DJ97=iAyNKO~cVu6=L`~E{yVrA*lH&n+P9mP2f4wg@#OTYEvmbl}G%__$JzfDl zJ}tdl#N+xWb7G64B~dBtlF7)Juog^|L!CB_MRj zP+f-%gDEIlfBKMJ@H96+PRX%ESf5>_n+b?SKSo|09s@3WyEIi1^wXFykUdIdRqoom zH58`;bGv1$t4R_H4;8XNt?j3jt}c8SK)GoiFjXQXLdL+_+6fU2jC>APNH(gdo-(wPWdlo5nA}9193%3LT@Zqq5 zaKoaFJ%aC)Qnn7^Lb8j)4z?GKhh_}JfL@s`Bq&MOyH`(v`?TY5RvB=@poXp|rGw!_ zC;2#c=qLY8Vh%y>0*>WA2_eRgI0)H|s7AM{42-Bo$e7wlQHd%kGJ%hL^#bXJI=ilG~<_}2kQT3lwhhN(xtBO zOq=7!qdyM53_lAOcWdNViK72*(Tl!r^C+Rb zp

gZtS41x@%Gt#L4wMD?6*;8@K2*bQ=PThr*;#$BE?5!gjtM-uh|7<^hcQ0!<+? zsPcwnADNZyDD>eFQAV)Oqr?==E2)Rk1`bLvW1H|AHe)XHyZ3t(E&Pz%c}GJdsc-XU3%U#a z;VhfHu3AA<6TheY$I-(Y09Qpe*@}6~YR8*OtB7>Ddj0`hVQG+*@=sj#9XZudh`t-0 zR=N!vGE?y%vqUyZbTG9_6_j$w(boF$6?rdWAlkbKzBIFlO+Dtgt=5%BguZ1=`maQ@ z7h-jHu{K@4$xDos&L&|A`#qb~r`$%R@;)Gpr&J|QpaJ<1-@YElNpESyBt4(@_ZB+5 zuCcO>8Fs|<{-_L3H66-by=I>wNg+%YA{MyP5wbkJ>fVeY#+FG`n@7?5v7#URO@bdZ z%kT5@p>h)=H%oGJL&g;B%|LidFV@v>(|BVEpAW;=!s8!w^trQ3;n6IFN6zPpzCKkpZ(No?adcpS5?s4Mv6K0=E z(0&DK1kT-|y`AhqOkRY31{R)9^1fYODUr)-A~)hZ3CKN~CRKtT;^e_UQJ_*WQzVSO z`waK6Ul5gpMW^8rr|)lX_T`7E9|fDtEl`##wnE*A#Z;WfO{)dq0U(2Z%qY$llrqnP z#8NJGh_Zx7#PB;P2+C7c^ZgT zy&dAtjx<+bD&GZqGzkod0~;?#EaPF8m>BLgK|ci4tqfVYos84cj?LN&DsTHC+)a1H z=WsS71!klS*Nfi>jY5xL0E2cOeo5dVvsp`7!Y2N;xl1Fa4nyS;b|);htqOT10qZ&{ zH(nAfqa-5Iivqz;<&{_Or+^J{o)A!QV!c@xWTw#(lLZ<^WMmGb(M=p|@G6BFFj+?l zn}#g@5@0s8C_#akA6dkyW7Gu2pa7%63g`RN`{9%Z%*(@%1X!8nyN0zf@d?|8bA-|> z5u;Jn$zn9M(eUe?U3ul!AwJGMs=q~Avj{{kq0sO_Ga=70Xk3vN)(Ub)@mc)$x^6kU zfa^z!HRTDnD=BG9sJ;!xHvQOXs+ZLShp>%cRx(6{R+sc^@haVg1q9fpP}jC@#F~+U zJ;8WOi6E~XdtE?^HsDE3SnuJ+hx996jO7Nen*;L;kmg#8<_!SSjEY${)swL-5r)87 zIaPc(12FnbWp0EIm-&yHuAh&NH~N? zj;jnI)=-qRu!vZ0@+2KW12^Ysyf8n-Ep9ukrV&AFK_x8Gewp2GlG%Vdtmz5E3z%TY zEdJv@r_CZq$~=~IXm14+Uvmh;Y}yBoMwJE($a?y27W#D2ui1jzd40>vXcm6^soNu< zp}p`QQls}4r%s0`q@@yjCgov?`%uR7Flj+bj1uwi#LbB4PSw5H2Wli_w6m~6(x$WW z@h2iyodKo<)tn};Sbh3it{^S&=iUXI=_ln%D!ueLvT^ab!e=6X=4G?A9P#tJJ`2+@|I z!or$yaBJC$JDl>$QQ``Jv{Bm9+`J4X6wwO0!kA4EuzC#2F32^%S)&lbtLFQic&a6e zy?|7Cx=LJNWFe+7MiQApjHU}_=1nFRyGvAM_C?_ze70I|*f24eyB+;Ygk80K09Pjm zoHZPqu=#VCY4t;?np?sTq~40UiKbYJ;%|%wYq^0}hSGiZ8|X4t%BB)}d$YbIIi1RF zL<8=xs#tSBm;tGv64~XBq;bxjq<-M=@F4+T6GFml=+tZ}5rG6E;QSOLBx|b&W`JYW zW>5+f*M#}OpjdU)EV2{ZJLV`2Vw{Hx%1IG257L7K>42QxoQ}uqc}BDbK9GLcIP4iK z2VK|zGo?a%8K|BY><0tvKv^r^o>KGb>&5xO7`A5PBqk-uGIRVeyx}9LV+wGIg$fR{ zN22M)QXFOCP6C5b7K2*Zf83#f!fEc|4LhFh(WorNwx5;kcn^iXPN3GqViwXfsqiFi zEcUUX{3K-z<&BdxhZHY7_3@f&+HX`1n3bbD++!&YvIjDw!CrMCor=O5V*Ey&*XdoYByhF>mi6TZYR{v-r zMA4@pD*VQZY{GF19lc&5q@-iEn*={u-Quy4b72q%9z|NQ6KaqNSp=U2P6 ziMzz!JXvjvhPc4k1Zo<9g6git%>VQY9&lo?=Uh_bG3%RY>VI>uu&*$I~7aiK>l+SqqU$4xh+``M$VUx#ag)nlOI|iaw4E{9rED;#@2*&LiO8Iy@mc4^TNt9C>1Argre7>r~BJ9Zvpz#TF z^Mz$XZ8*=4j7^v`974O!o@)dcQ1cGxc*4bL%ftM-8hr{0xkKU6rD7VHx0sS5>BhyR ztffS{KVqfiBBof5lr{1UslxCE4{G-Sy>k*~I6h*8t8O`DpKs}%-u`%a!U(HjhHTwo ziGOBTT7)6K;yAm~-JMaPG_}IOW63gtp096UQlW%Ei~e; z2f2*w=~9yw&do3Y03QxG13Z48QjYgf`nBqA&Mrz}2+i8$|47t&%*B$*8+G{%_H9VlvC0qBBK9YsF*lJ??hpASas?wC4zDkSy9!JkDQ zu-er429?A25G{J5n^5QT-A$!|;TA*W`y6}n$GI`Vs2jUA7!kN+FIov_3B&s|&f^Az zT{yr8m*-9~K6m2)yt45Ge>YunvGyEG@!IoB$kAKR+GDH>PXu7p0jL$^T&<Li8{=ey!{|?swx1Il}^{*7*|K(&9CPt|LDdzsA%>M5n{J#skP)z?3jPp-X zGXJCm|0iGnR|!@E_Wv{h{6p~lXDRo;M)mx^!S&3{e_~bttCZWUy^*vrjOaU}zKckc zg#Z@ZH}p$|H0m&ELhjPSmfu8~E~5XMh$s?O&`SMv@{o5YX@Qry4H4lNNvlpXSYXC= zZnwPqMbUfm`&?=THfgt0YRndg^rr0I*Lm%oU>o2Uvc_(7`btQk6FT+tjCw7CU#UvD zdin{8i!tJ><_`{a>gS=Q6NIcfyG{SL+=rvdoM-|Fotu+(ot=I4^4o)>+HE!J_lw6# z*wl-oXxrur^K1UCs+(+eb(y2Ih_R19nVqFWJV7X_fR^d)nJ9Zu;>k{~>Im%wPF-16 zzp7cr!G)2#{9c#T-G&Oic51f|TdRz^mUeLJbm#;>$ac^ORDnAiXD_2^^>&e`n^pl5 zde>U82ymT0xBJI;vczd@IQmJ9kXKDO3+FJ(30PYr?6@w>;`H1)#%^x9=WJXuVgu)jeZ9Fw1fWdV zIbfkOAo=CQ-O2@CEEg{=BC+xvs@2K`{-~O~o-w|KmwlqAWq~TRstTTw$)?`gSR`iB z(rW(D1trLo+QX~7BS62B3Lug=(L6O-hsa5ls=)8yBK5!jfES^Jg99D z`A$?*r2#j~ugAa7nxY}%WXO_t)kXDg*g~HG%W?@rwna60Ttl#}&&UVjiS)}Y?h*9! zrt=g8rA1jJ-+z7p?6@)QQQGJcV8~ibxAJ%M0(<-*(39i@{eY<*C3r;ExC2>RdUL5X z#dxg4Q|FCpH;x zLrX3*%G)z`f8-mNQUqL@tus=G<8Rf^r`_T;lMC+wT&=ffaZ+*YmZV#2IQc)ZhiN z1&+I?xD)u7o57Wc%3>sN!DJ%<{9KerJc1F!20=mwSxx(Drn+Eu5h!1TN3uxgOA$oG zgz?8X&?5d+c~wM+m&g-2Q`qK;`8L`Fq1E zCr{W5Dw#yKo#!m$9yv0l3j7!0r>$qlxcKLyV>YC4IzawopEh#aliZ0XMIy{W`*Qdu z!k4sQTKPb(rBbOO(T6}E@gs&Y#YpP)dN8~2X7-3n#lY{!ORuMnYuketlBKp0-=QQ$ zfaqu%#O3?kgbKM}HAp4Z$lXeKju6_Q;GY>`xa7ArNSe1Cm!Ni?;5N2cY%+uihQu#~ zTaRe!W6FWzZQ^@c^raB|L|GXmJW!4s2N>+rDI?6IaL6E7j1}Yx3(1^B!u(1pJF&{V zUON_r7&a7;No6{8scZK!Y0_=Q2ysRJzhbn|SQRf9txLohCMnu*=8Pt3twuwC)kG!Co)~iAUeB+?n>f^=fB^XPg@Hdv%m7r zy>W(VemgZTBlw-gXu`hj>`AumE^$$i7R0sCrMjV>;1j2M%OxsWNy zK#S<9>TmF%vSZIf@xq&YcjhoSOxpz65=)=X&8A3)Yzml_zvTVBLCb=s>NI^w4 z$}^k!lkKY1KFqN_@B>qaLt#3>H?c-Z|2(|B!gPiY&-+6H-vHX3_EZNxJ3PSf*u-!> zerzn(uNdbaaTxEZu9)(9$|~=v%9)AC$~nZ!~(AD)T<5; zedsusyKr%`Yptn9Cj~atsdEJ9)mgFUrCaN8;(q6~rFyyULE7KZ-(SS8yb;$t&w{0% z2=$#vSTuEGinh;Q!6mQgVc!dP-qG}Fab*!l6u;LSAW$R7{d6+3l*V@T{E30rX=ufzMOlrlz%c;}!*K$BTUv{HlXxpDT8f39gFKQf9j+lO0kwuT=SwMoLJj79Q1nmH3nP0>1jp_x_e#4v#LAw ztp0S%vtps|VG+Wv7*-vm(fDC`_ymy_wvLrnk%rW3qbEu^BQ#4gaV^H$X*ywxWyE_0t??g@+Q+aOs676U-g9OTgCkg6(tGES_;;BTmujU*JY>V~UdJ5GNFv?wm7C`%-+DWYQ% z5S=Qb^ZZOMn8W{+>5k8P!IF$ZA=UVOwY0(iX~2KgW?r6_5foG8zomZU1%14c%0o1; z%Qhqn_zS+l1>7t`&ggxtQ7p0d1u|{X;u5ku&>Ea)$GOseRN>G3=rI92h(&JNR$OPh z!1(Sp1lgh`Qf3xWfg(xbjHE)P+h~O9>fyQxpr6Mx8m&|vYt-m8ot?Bm-K2%^ui&3Z6v7J@?L+ zrkM!|-LN$V72|9qAub?MfN&~=)jdW6UZ}@C=WUoi(&>Ladjwv4L+s;(b{l+a_2w?E z@|`TQXZffm%)m2Bou^(5IX!Q0VpEW_ol_gm!j_%+I(vbL@bMmgXRyFEckZiK= zA7jInJ$UNc!V;B1B68g=2PZ7qjg2wabOomoeEx)sh6K^8N2DdbX*gVTi$3q}!cNha z_^m;Vae^sSEMat^fmLPxE!H9Lg)v#`qqyOmVy;*!epgoqr?3GONGA!Nla3N$5&KnqWS9+in7SgFC z+HZ(pXvXAxB2yhz?Vp~qNnnJVj^Eyj#Q81dUd)WfYabkyDn?#Ya4eQ8aGm?~uTCSD z+y`C;!LuGEq`S!UmXN2e++HB*PtzQLr|zZck4tvHc&U*M6d@})7)V#PbzUmdqa*C@ zKcMzddog|Va#!^qB{i2^T$7ed}K^hiz? z22-)L@6z)n-7KtLS>nSiQ2-2G#pVdIn z@agC@1c(_=VU+rd#xfS{A#-saVv~=996bZi6C@DhjkUFGAuZrJ1kPM2qy~s77}O_y z5qmiyCo4kd(KNI!;{iTs_R$z)fz}6WL?u3CBt}^L5#!$W#ahPb;h25y+q5=?B=t$z zzAYi^F*<?1KkaR}7VOt&Tp_I5y z)|@(;?OKjUC04XrZ^yE7%r}QS6<*;}YYLh`G-A}cf#18+JTo<@p~ic&&ICi>p!&%M_NfJJOfk-b~*;1Dx*MkK;s0|?e{gKuGaigmoT z{b0#8@i+VE?lF~5q(Rfh|3yT)OY}5wRdG#+CXXI1dY|z2>qGg~xgvc2K~=k@ow}oe z-aYz$<_L^kMf1Qv6r5^l%{;T6HgEaJ9)F?%tE03L{$-+|O3Zj%F2f4vecw^n@AHK{ zbOqm^>bo)9w?o%I^X5lZTKGM+ZM&13M{n2Kh0{#X^U+>v9ef?M_u7xfvMb?&+Z%d# z(_sI6<8DtU_X1O1{>vZo&}AU4Y1nFahIcL+c3XLEb1GN%r)unIjnB7l3p_kM`XNN{ zbR`gU;s-W1RA3R zD{Fn+u=3Nmq)u6bZO``YS;I&BeX_%YqMwo3odz5P_5SYueYd9$E|>u=$la7$IfBd| z2~#S?VjCOZxi#0?u%Zn#q*sIXeml5;wtRhSX;9O3R^6PI*W!JF{{(+Zh_feis2n{7 zmG^T1^)<}5SLg)4+3$Hp-l2Gi*`YxG`doTSETf<@yp%;)-xb%zqJ(w2P;J@vc* zyT)EbdZC#LYb*b-8z$-J)keEgyG{XZRUFn;MaYg;L+-qEl8jMmM$PROIAsuC@-c5Q&-N+O6*Amw%AIs zKXAgwYMYyp;o4PG?MifSo#m0OG>BocIty**@Ybi#p)*eC}i zmIN0|H#xdRieNDoSJ-fT2iCVU2=K(i{a!2(@Wf3(@CAbB>&eg`1UZNOy zKEN?4CWRXS*~QBsYFJt+fK&3nz8@JladjZ*`Ihwq=96aiU;a-k0SUzH|HFJ$5ph?lZISHw~ z`@G+nn0;hsWt-VDwl1NE>ONtlO0g<=hOqn0G>AEve9X(Lbt5e-&6P67apHEKyz;$$ z21Gg|bVi*bHgdy+r-v=hmCV54BFP2T!}A0PL@V6Gd&?9?U<&}JtHhm$U?f4)0fUj# zFeE|Z07x})yh1_4OAASh+CRmc()-I9a%gCSNnbhY!7MTVD#uYT-V{;l>wbyI{!DFa zjv@xgh@?lPR@MSLH-^`TG?x(w;w`dK5w+Z?)6?&amE>jO84|N0w7+Z4Ie2XC2%&du z{zxi);KQn4w(6-P)joZYsrPe%F4LgD2%oVPO-(jaQ5{ze&vUN$b|T(yuJ|FE4D*7- zucc`>*HrgjBZ{=PR-OJBrHRH1zC#8Vvjpb2nh}wgm5T6&)_H;IAP&_!^ehhoIzcb^^iavk)yQk6mNF`*efX`kpUJ!> zr!ep;Mak)kMR!9j-3Wnu?=C$I>~as&H2?O{2~EAoIoxxLd4&^Gbd{j}ha*ziRXnw>^7kh^!rLThu}s`Fzl zh&nqZsnd?jLb-WSC3qSzF4|^>VoL>gQia#d`c9-M;eM@$5uYL73U;1ISWzNy0^mu= zki`h{c%%F$FC(rLjOuV@=`@K59xvRI1!(%YkOs40z9N9x1EZ%1BUG?OXiBh}FU;`o z2e4Hb)P1&eG*mDfl7PF>lGy%pgn6bU1(LFK&eO_<9~_be;!Un9D% z#$|Q45%e0*w2u}D9vd$D3+AL7G0ghz>wXGUx z?c#%jm2kO^78igCNYuiwGX>%gTFW0r^gogkbR<%)=Rm$Bx%|(>I1HrKk-;ymohj3b z9o)&eeo4o;`rR>v_R(;rHo4YlapO)Vp+ZQ0C2kUszG8x>EC?wDt1R?kkyO}_Ee|z# zsmz&#o@YWO4^m5jarYQtRSy~yp(k}e-W7}gj0wOl)sMBbb?Ij&F1@8lv`fWJ1qPTl z6R>qrNipz;zDD_p#k0_q!j3W=DQcCjhwCpmVAf0s!23QJgPk^b4bg(t86$HLn6n_;m>OpB)KoWg1b+DKcKotD*_oY z_hW0Qd6u@2Ty5<3M_q-T<#713#Jeaoziz@um$%0<7dV~O}MprIOJz_JCpZo?+GyaE6hv?LX$ zki(Q;25=*u}ri?jA%>h5KIzW2?7|5A~w)nizBO8G0cy) z@R>k(ses)oBcR;xP!oXw6$mZAdg!r;-2erH_Vy|(t8v>{g-BFbW3RO5rl=$}5j}ep zJVgT%LU+eALM$d|p`iYofJ)Pm&_c8-_>>XHUoxu*8%<%K>5id;8+DO{){UmMMPi#y z!TMo>2mFVj9%H~Iu|nri8>=>h;(1I=n}pH_^h9@$FI9wnK=JXJf@l}GjO}%ni|T1# zKLz6j()aOQn8FlG2h%qx~ zF%F{y7$aEZc#gRSI1Zza5O}@OfBxN9h&6%<2$L=(ozWBXV{TInCM8H{W`;@sGUy>t zjI42ha5ZeWgo4%*`~ru=7|lb90ft+{Lp&YaWV?qLMs@+t;UGXHc^25G=}S+P_)~$6 z`B9xmh~yVuA6BvHpW6nGKNkazTK7oj&333409w;}7*H^MxveJt(jv2&AoG8E$ zXKQv|w@Z+u6K?>!k4W?@So}YB5s};l!eomxf>1Eu%ziDCIc}RBXS0rz=c)zFEOnb>Eu}Y^Hnv${HcJ=VRmiOoawhl3mnb`7mno~GeR5>9 z&~hd>B3#LoL-#ceXivtB)JP#0kb*Qx1Z~+&J z#L8JJ=O@C5&?xTq7}l{)LN*!EM_LSh(ek<(R9aRSgGD*yU(dVHj4ucE=k^td!iL6q%qP`I_b=+BYb2qhld7xU3ZhszmCyL9UIsE4dJh+`E@$m$vehs?m{ z0+E)RR;x((n(Yo@U=5jzBW-EG5BQA*F@vMtMz*;OT~iMYa3UMx0C1i~x-Xdx*^NLH zU)#U}MpxUZ65O~#0fLHOD^NSc2C$A86p5AKJNJ@>D4P;tko(8{7Q$=v_S#AIV|5!m zR&9HqCZ1Ki*ifAd2o@ZIjiLU*2e+`i|1pJQKw(t+8v7L?oQffr@4A<#FFP60_d!?Z z%}00h7en?haqzd9q-6gwocm~SyuC-KLqs*Y5lGK4(hAH-m=X?*oF7TmjpCI88(Bgu zOoIDfq(r~C+G|ZX3v}SH^DpM{$fIboj~D`1LbA!)BuE7L0=s1AwBrt`HQ}BFRy`&H z;k^kEXen<)Ny15!4qwtpMhveVAP`HPNu^N?FGz~^um+K|Cn&HOk&yZ^XvZ8u6ysQl z8uXdQ9j}MCh7bpd zg1Lh>y6+e4I?Sf#F8p`A3h(QDev{v(IKut@INOcWC$pvRcqQkm+pzjMVz*IM(Pd!X z27a7n-rYnBx%7HMgiGaMjIw@!LY*z$71cdo=Y#UlaOYC!!jSvrFuah8A@7gL`J3|~ z`R(_tWf|!cQB=)W`OVFh=Ozb(?^C;mFVHLYNbJGl)vvAqmu6RZfv2x_hq4sm%Xqr* zhqR;pf_n3y-_+oIGPpBqP;`5ZcYrGd<3%9~KlrI}<=?%~r@{OcxN=3umY-SHUU@g# z{Erq!OHAC|xF+wr!M|^d-A)H5ToAk;rmmLHE@pm+|5o7e1L(k$)1s7n*1PAt!H~M2 zJAqvvSARd6SO=0~cZlNwQzAbZEt+<5Z_uLU|K;3&wc`WABQ>0b&Gnc=B^_@h6TZ;d z;eXWA>cG$*Y`mgQ?H%dPch!P_f}d7JnuB_?tv&O6?c#bFo%6YkX`GczkAUD6!qgdy z&=0jZYMu0T_z6UQ<7`dFJz5iA7|e^BC+DiK72XKj-yYGWRfj$!oed4o4x~hq>EF-! zRi7&-4{!e>VTA9HIH>oP7q7c2EdxHIB=x{o|P#HaAU>QSNR1H0r40HtormXV^dLn^^eMac&5{7mUQjAowj6p1Xdm-MsTH zYP$}7US5|Q&puXihp~U~faZgXhqG^(GK$qMp2&{kW*Cat?CSBv6})cG`yMp5w~f+~ zO~Emq-$LIzfXFtu11dX?*D4sn*HyUtN~Uc`LDu_GWVDI{OUt_W{LIY+HCU(8kRM^#jd} zy*wQ9J2zDwG*q;T5@RFa$`g}@2&8Qal#q^RD?f!1tj0Qk9X90Ii>c&RvFZ(Objs%~ ztSYqK>r1%3pSLkGCbrCv%w)8n)0WjxH|r|FKM{u&%edX%AGcHRbV34gPlB+baQq#c`X_yw z;Q>nY@GZ^+0@I_G@`B1uNSB+?{FAHELH65e(7HuG88 zy0(2bVR|;cX}uJVEGF47?YOdnNl=+nB_T~*6qc&|GXJvvn&~|M-Adbl7M=Iq6Q{Jajs`iI{muC0pSyo=%{r7a;cap#V70VhmgK=OfMrIi3Ju3*Culg#O zQ41)VnCMrN9{=tzn<<;ObH}!iSLe8F-pr5O^qKAI8+Q5l-%Fnh#~`6T@Fv2HO)ajt zy=ldA8z{2&nz%(*Jzo<2R4xZLjqToTx^}sTexPf=-^-R%&F^LgI~%MFq)R!Dv?9lU+nd48+x-l1)? z5Kjb5KYWBgez>JY!*DhfFg_{eE?-00_vP|!^#}d9kk8tnk3-Mx)TKXet@?IW6SwDr zCL(0WY;NQg@9IHhQ-sdmUX)!U?BQ9JRaI^h#@!_Nt=6;vOVSm*<*#9gGKYx)ESSH#hX=e&<&*A~1nkuB+KW+fILfNCvww(Z$UZx95>tx26!9 z=S3BAXY9bcod}UVbygw$Mo#U(sb79v18K_V_d9lyI&s?qhZb-%iAx(e0(nWK9mA*f zEf5slb>!^(mmlI3I3|C$&s(R9+1d80j~303tf?PMP(9$2cG#-J*tmKVyQvr9>d@?< zg5S|Zio7YJJL@?TC>PhqJm;`=9>Iin!@(5{B0&C)K9BEKjX~H2eGk;J)g2xlA(hkY z>U{kSxGHf~7bB#hh~Ez%iG|S}Vk9PJiHkW10QS(hg2?EBaBm|VhmY~t$^NS*>2osL zDYjRBKBh9Ni}i@s3%&+d&FI8EP;Y@Y30g@XmziI&R!T@KB zX_yi3%#@F!VM`~ch|E2I)r1$a3?IANLR-I4^+a3hDyA&~NWmgs*{HFXT1>#DSW#$6 z2S`#t&z=|7W=5D*{S2VW2k`cklNnRN>mrv|)m2op(Aia4D{Q^(Bao-?kZ(rPvWRtB zx7;D}&vPG|Em(Rr$BF>@IvNh5lUX>avwCn;bvvXI{@i$8JhV-a0oPyL{vjIjYh zVaH3A{ppyh{~a%|Lwwm+QS~+)8>UlK!NBt1qpc>o!HxtyI{?=_6%ZgAz%s1qVQL`b z5V87`IJ0%6nh7Jiazxo^L^Tr7o@O4jfaV@bYLWIs!P2c)pb7OA);WseQnFsbSL%|{ z0VxaiK0Qe=*Q!L`(mEwsY0!D>XZ-r_*=L69)!a~`Cmw)h0Jg~H%x+*Tk@>+VSnUhT z;mW04*%g&gQh0;-1n*{Z-=M1uP7rT1Orx%ZJ}ro$h#&oeH)Sp63)*dr>+eEOF)FpT zh^E7rYjJDLp&4*%RbtcJht*QZ-q)7>IE5HGgeR89z~P>TA{T_EsZBwR%m zqUuUb7?IOUjMjEAW)oPAh9*<6vv2_+V}nlj!vJe zW@upx70zJ0CRo>A7~ROG6;!dY(UfiYSk)C%V&8KwmeJIoD+~>`y4qmGT~@Fb(=u51 zvZ_X`#!NObZw4yVD8g$r%ZPUEG@J?~Tc&CBVo>SBk_z;NTvo^|gkU_ODXf1sPyw+9 zp;nQznx=}UWL$=Ls?Mx3rV#CX)YK5Z(lmE$5z9Cl(gL*}_3gzHQY0b70kJOUy+F2! z4PqV46%Es{|7-crH5kCAGNQVvRo^i^#gsBFV>FzQtv1qX8??jKr|p`A9zyJq&jxf+ z;uW&QC86gE@ngaKtdL@4sHa( zmSpyl=0`9TBrwz^D2SN$q8&AE)f=}+kI6v`+k<7UFc3eJMN^LcUWaS+m41cG4LHCw zImTrI0)Xw-&3}MS3B?bYUzBAeC~YETzI`SF;vJC>073zSLFZ6t6KB*EdD##}bGc2) zZ#GA`)}7e6kqVRe)uE%@veTlGY2l?qm>Uf+hBjdikpPnhGRn%71BS%FW(k}?r#yu0x+V?k z(sUT&TAA{#a^_-9seMy92NyMeRzysYgXE5IYo^@#ISpYAu3Li3qUJ+L&QdC-px^;d z&Vnn(VN$n^U<(dluS;hK9ipN>0L9`_B{(c?&Cj4eo_Aho?JdOiQej1T=ovM@79l}8 zJ|NYIO9~TUOy}h(Cv|tv5G^LJh}$Uy2{*gyEM#L92G*y11R1)GT$2t~)5JP1Nx9jr zOq5>HQF{s&g8fn*ip&fsClgu;_Ds86UhWPaqZ#TAQk-kKmbx2&DcqwX%3VSFI9e`Eb#7 z4zM$ms@7HM((nn%et*^2CY~VD(T-uG5Q_SuC<;&BsYdvXc(jNqa96B>kVQcEqIlI= z0iaYW(l)TiWmdAJQy3S-Byd-<@AV$85ClN+7;8wWRiuk`kyWfb?99$JmF0+f1x@o6 zSZNpPcDwRqyU#8`y`y2b#YUb*5%Z*)!%Ayl`4C+D<-&lUJkE#|K-G@}HM`svL7cW% zN6=sh(L<;X0gU#Fj{suSk)_ZPr>2~XPehTqibAT@aZ&^g_~po|4o8zZr1ht}fZ_{C zlt?p;SCnzyZDItb31p~Aq?izL4K9?+oCZaKZP}oL3{|gNxlKEU)MqIOJ|JL96_9l$ z5_1hMK*BzTRU)l8Kk;Edk?rLcG4Zt9(o@ z`1wcrgu=O@fztKjt9(@Mq+gz}ri)3mPy!e@qlchf8W##$tHsyKDdopffm~E>I2S~7 zx?yMV-w&M~m6g#L1P3{Bcn#GAB3JDP=ak#2Vsp`H&NVq%)t&jD1bn*5>PsEQ)+v?r~%0Q&J!HXm5fn< z6fBk$Nx)Q&%mwlhRuDyBDMCwVdnGMV+!R${V<^svD&YIm1^QKpeIu0CeokAR_WAIT zHeD6pN)BP#1X)>P_F(DEFqR0i2;Rd;Try7$7beIM(=7VI3=}FR9>fkxJ!)e zOh6tGo9`=%VlM>VQ4rOLd|+N}gk6FVu^$)~gIVmNUY}mDl~*_~9iSgnC{THLo|K}& z8pa;+t#S#WA60BUoKfR_K|80C&nEMtZ3t4Id`aXoCMf0cz$}*p_fHLZ34y)M-Injc z7w7z-yp5BCyAy!k@GCwj#8l}1)=Ux|lT_f+TJbVCIQF;E#v3n5!* zC^f}R*>>eMIaHuL3|&W+;_3vJY0-@ubpR>?i3m{Z6o(dgNq3bnA-_y4d-DKGz;X^N zX3-2$D5$Pqes&aWxoK<|rAVbJ6)=pl@CuO669N{juSF@rvX!E0tQ!KgNIkB8#iR2~ zE_uU;AesXY1}s|aaBR!TYAdtxP5`~D-)&_(&7QV zGI2c+2_DUtOOt+qQP(ZHfNPRgOD}dUA}SivjU!15>G>Ph`FU8*vT7urHhYJ3xy+O> zuFP)FZU61p6ZflBkaXz@NV8Sj$#Il*m3kPsp@%X}&7+=!q|^oG=luE6Z@Cas$>`{X z?rWL2a8^VCQ5Sr)YPXiV@A|iZ0qmdJou8R;=omJ<-+ebUdGxuP1)!~I9|H#;dqq6w z@XQ=<^ganRYodHkFP18bHu^)AJT=7c#SA!NZ($-vzs$hQ$(B^gD#y$!k$DL=_D)>d zrFZUO^LIoQpOL3M+L%$|9*+;+sES~p^3GO6iEAFH9uO72t3{dh4Kr^?!bF-MuW02s zIN-iOQV#Bp<^7S|q93Q`am9OkryUB9pB7?w8swuAtLp*3vug+R$hf%Mw%qykdP;!( ze6j=JvfB^`#%TCZ6I?PD;^FXU@X~&hbGaPg`@fxfNBOPefpE>11q;Bx_&Mv$9@ZU% zDQ1+oZ>;nF=*2L0!nHU>EN%beOy_}snf0&WSU9ut`w#;^)t^fdGo|qz;MX6==3o=g zCIJ3TC-v^Fhmk<17%SoiGl~sM!1k0kjxAV0iwF~`5J|EaP?^C(Owqg)lb^zZvw;5e zCO#D~9)OU3=iY2Y_#vfWeSzwPYxVX`6eE%Rl!HHH8H0CG@<5?aB*D^@3JT3cE3RQA zrVUT7d?3CNi_7j*i(CBul_vodH_E?;D2bbFdwPfQm^c5 zqFya(w&lLb;)dLdw9@1sz4B4QYL!9pX*l3*lraJpp&wa8;0G$^a0URl2xM4*8{%dX zQHXiIPk0YB2nKSsS*M)fVWwDF#Fb;@_yC8z)6d((OGLqq z?(Viti~lPXj0CQM7;k3b`r1N8rCH#`uunVp4*&g4iWj(UUty?`Cs^N8a3;S*7_HizHLcMs$=`ifEy|mCuqHP=py(cu^bNxlpW z`FD0<pfL~YogH58p&9l&DO7lI%G<%#N*1{Xn~n0?csfPX>h;n$8%VpuMx9}b-FtGANg7(6h=>DtgxN1LXda# zd5X>h1{c`ev2m;1C~&Aby!n3rym;oaBqy3>cpDs;{PlPpQLg;VAz@q}u8v$*^FU}p zYzaF~cb$qp$>A^$r;mw{XFT`=Wu-W}3AZT?J#_5zN`kMa@QUMQ{3VUlqk7~wDUJ=h zDY@{}dTSp&LJ|zF9X+#6?4Ux&!sLAZ!f-Z_GF9m#epp7AA1+8}19vQSWlJem{o+ig zDL}En%M@%kRlT)z86!JI)Bz2pQL?&Emgmdiz#39H-qs#7Au-Z+hl~?Fn*wwHQzTxZ z(MrtE29V9T?tab=Lw`Kk-gqn&DKu8OEApdkP4qCKleSA4Whu}X6v`~w%pFfeo>L}$ znWP=kY}TK00EVPJ(jYR0?EwcNjpg0!JsrO-pFoij3*F=^a?-|zNoqLL*EMYv7&tmv zux^F3=T^t-F5eQ}qb8#9z{E4_#|VdfKk@Q7$UEOAr=t@%NJE1qJA;rrM1o?5MCJN! zX$)z?ShIS`SDlc*lqu*mb^A3?{|{x~99`MAXC2$D*tTs~Y}+}pQ&GjXZQD*Ns@O)w zM#a{bd;8tjue)Ere&6|LjlK5XW308tKIi=QoNLaRLtQ4_8nLRp=L~JE>RF#iZ#ebM zN!%P%g>L6GftfoZa)!SmJ&cdzbGeEtqI$4@Pk3Pu1?F}opq%ebCohmr ziwKjAohgb`1(-PJnG56cBgb!_3a~}P6?TdpOTP+_wo{oeJZpcP)9bJH2>Qw$D^cZt z^yExw6vVX*+9~qOEog({G|T}Q6iRi&DL>Uv@mLpCc5s(Pdl#ga z?^DD40ew2bM&VoOjA{?5%G-6e8rp2%h$6~AuP{gOX;do|c(^ z7Y#oW7=(*uRJ$ul2S)i_*_;F1$86!PxOb~R3sn78RCW<5?Xy3Rh=CE5G`s&1pD7` zv0qc&Auh-D4Im`HRDjE}fRc7D_{5*TPH6+pgGm3ee%~M@3q#+P$ALbdIp6ZnaZXyj zV13`|W~gPI8wUz29l<94oC6>09=O?e(fDTL`p=bN2xgsti>+0g_;d6^SH>(r{KG;0 zty81G;`(XU5Q5<{zKMnah~zN1K={OHeK#+}rXY-q~?8G2P5* z9CL>b`!6<)O9NR`q3qJSaEB&8kWR0}^4~E!$ird)+A$JZ4Ig3D8P}Duz=pzfQtK)a zwr9G@y=MXniIU+vFOL!CClDKd4GAK%E0FS!CY~j7c%@4@imG$+_d-+DgPMl%<=xs+ z6!rN02PYFo#2EFVW!Zpx=dWiq?zqf0)J>B|oSPBkl9YLgyd3hW6+=j~02w@rk$!Jn z<$dbWJ3vU?A!JJSf}afb`4}>Kdb|wOe&~N0VtZ>6b<4`+`_<{17w|s2@!;DE+Bvub z3?zaHh(3$oSopHpQz($|U4Ta{hgF(Yu6MWQ0|dH8U+jN!J)HmFas|%+E?4-I2Kjf? z^nc#@FS#BDDH}s`Q(?mYXhr_kN)hV*Vc%+P=csINXl(jtIGl*nUmOt3fA?AaI|uaV zh5tJT^glHYe<~K(2|54Zzy9EWJeWBMIse9FeI9TUa{i6y`WNa4roS{2Fn>@^|4yDA z*T3za%KVv{_g`ovowexQ;W+O@b$bE~1>;}V@gt|*6OjzH+nQ$vFsC6l{R$N-3(U?` z(qs>f0Vp@$HGE<(L6!BQU1o;-Ww460n|P9!nkx>Hs_Wa-*%zsyaSMVx)32;R{?ehZm6 zE1}JBDYlZ!I(}8&N3P)gngki<^Z3FRT2WY4$EgDbXfKwjuLLqmNwl;L1&CzoMLfD+ z>CBOv?jlfD!(9!H;H7G(pqV;-Um4p;0U+nZimj1rN)_>tMVx634AoOAeTFl+3Od9N zc6c%_NzEifrtrPA>82RLP5QPY(uJXh{hBh*1~ zp0|?-<}OvfJh!EtxyLBrF{?3}#&mp5oAmt<#*<}Wh#LYwzTFRCol!`Olkgc=3QW)N z<=P`0CuNWB%%&DiXo!Ao4JQ@geo6>S^7PGJ5H zNS%GZspE=a9_D5VKGuuoeJum=>_Z{wm`|AVEq|K@mTg-o1WZLzVz@n}ctr$z|4MCjfwkX>~&5}J+Ef9T(N&RRvRE-qI-wXL;oBfo0<#XrFc5jql6w#?(lse`YBKOy z%JGRQ)e89;YpFbJJ8h)Z#lp^011&{}?P0^j&9|$XwjtB6Ly8^8Uz5|{k~3CrUFwi0 zb~j(LR$zJFo$5~C=4Z&h5f+qmaEUrAvfEWVXp(zm!!LaS)MZuY1j)G1j?|n=$f*#P zN7OAU=t+k^-B`D0o~I-O)akC_*_ht%c`=ps$6IT`K3z$}F>xo^Pw}pUz@3+URJ9Fz z7;+8)Ut?@!!Iz(1I$*u2a@0BD1a5DHWukv|>X2ay<7V()4)O3w`+4E6A+Du>P31Qv z$4(fvttSwWgcDk;ND^e2bV@5sYVUc-R$qf*nR4a!4>gS$PF&)L5Ckfb@`E?q!e67A z!#x9mnLGEcPoYLemY02Z7pxP5R?VF$U860F_&_vl9InP&ACxlO+YO2=b!X2h}!@)w!F3>l^>mv%MetzAZATZ;WPOzOLf04iO?%LU6&n6lG z-$HjNq~z`)Vr6@z0j!%qVl2|Bn1-`+ihfz?>m-}RDybZd<{JUF(qyT$i)$SE^v#%; z0oJUBE`I#QVQ8+n{C9lcN5jJ%0w3|} zs~g0t5P`G$M~@J1Dvn7p7#ZF~XkU}bZH;2f-SvH`wXHo!ich7wxJPnv9c!C}2C~P^8tGn>^K~c zu-_#T;9cP$a+PBfV0U|wdvt5 z9PI|6xhXDFXPHs}jFW_1q#|}k?>B-OY46Ick#OxBXqyVDG`l&aqZ=?(IvKd!))TA4 zjB9z~HZU)zHr>CC`_CAgK@PF@mPF9I+xeQ%&u?{t2{l(Q;*U@xd#E*eb5wBoe+F?& z)Kp0Gm{svbYhqcCYrWW-;qm@pY6z&@4|Z|sa%sAkRP#Kg4(;~qYEL*#kI_^2I)nOZ zeeN(mYM`wS*zBqn3-|gx%+(g>(@N=CY2`^;fqSO8aQ{|`vCN9s!2L~kY@_|}gZed| zOtIATrLCHbxbva^?;{bY7%WrC|I$?*?>bvUs6XIK_B&ECo%N257d{#r0Vzr<-QGWI z7e{*d%hT0|wppZ!E^%-@{X|`*C$GsH(9D;`INC#rpFEGaz9O&4{KsmM^6U~fmhOR5 zMEQzdJIqj|#nN8B^^$UAYLq3jxMO8QB65gGQ9F&`$s%$?X5oG2E%_*+;x{YWGoYdc zkK;Q#7Gez@>&j_;Q77SFooGw&5!G*jW+>$x+JjnI=6}_35v!{hMO{Jri?5Xqk$52> zN9~}76z?PFxK))3KyNk)c{#%f%^ogILpZgDwOy0WC(-#hK_O3A@Vduf)j zV0Pro9Q|_WFYFy+shvWsc#p@8hIJ4P-4)J65^u>y8nq0H5glKmMPZrW*!$)6ePxko!z{a<$z1s-dF67>b0b|PS-Zysk`bsFJvcu>+j;8gNr5I7#TT`3 z5yl8533URat4PctTfcnfyQeTs31`!Bb1zdH%IoX|v^(cRjKy5v z+)|l5P*G|djgRx-se$3fv_Ag({gx_hD*usm&B%gKy#Ll~bVX9;p`djpE3hU%cM#&xl8~cjg}ojf)93wg-pJQ) z;Q2oypOBqW{5mp>6awWnHF?*rDnQqc z4QI?7y+J|p_|C`?k#oBQfRTrF*90mc&2&89HW{OlI3t5f$6xUH2GdCtpdFZ z=IXwF0u@i4c#)@IMMsTC5Z%3BDwQ?bM08vcMA`+{zG?9*YiKoRdDwrk*J7}G2Qn(> z{2tba0`gIqDmnwcbI7tlF^;8}hw7oIoqK4Q0<`UXDX;DkSx_~c7Z^vwNEbSDK)(n#azzLM4l)~(Y_xbfZ-s{V0>zATYE8f6 z{F+(el=o|9i~0&gI71nLneH$J^G0HbI66?*N8(yKOMWpKR)VCaOOCNTGFln8kB(V& zWrRyT%PghrMR_rp2Q0ILL@!NYGt)jf4b>~IwTnr@z0>kT32Y516sqh>-FyjuR zwrc~jH}NNE*JyS}Y|DaIcd|Dg7~jpxB>wC$EHeBri2fseDKQBOZ#vr%|( zG2^bU!3m?JHxNF7wm%M4oUjI74Rxhz58;KkS$N71Za?glk64pK$zZk|i%u%}3daey zKZ+$2VpA7UpIgOMm!fngR{(2k53Dz$LpDKvIP<9lYaRmvlDn^SCo^`qklq?NX00F9 zY2Bo^pWV7O1Gfz5gT~Lps;rH<^rsfEOps_$-qy_odzLKZ@Hw`nbary(FrDs%bIlaG zX{1`laTRUdilp=}x^$(gMYC*Lay^2Fp@s1hL}1@03S|Q+fd7^%IM5D}$_;gRxa{pVTOCpciTwUMG)z&zp>qXdUz`Bl?`H@ol!EOGNo8Zm zXW;Of#a-Nn7q=QA!pXzac)m|7nf|fZ!*C z32`z|eigS4^9s!}@*7U{!g{?mXEM+az<9)d0=p%p)2dw{sAc2vm+26qaubv=cG<>4 zmP@5V4NHC8v8_mUU8$Au35+cgYMdaJ{$%JGNDul;n#{dqxY|Ic%4a`+DjE|~`vbVd zg_fqF*#5A=Qa%L3Mu{A_`h-*xU_vxEO?VI|v@h4AK&YW6rT*(ACxlkfxR?e;(V#L$ z76DJ=xX{MIU-$A7_6h=#;*bQPghM?taH_5<33m6G)&0^pAcC;F2J{3iqZ8Z;Vu9un zFJ(3c4v4(#JTxepfr*hnl`|P%dA@6j=1Im@ygEc?P(3tD!b~etH&ja-1ZZ%_xhV4u znxh6(Oqr)4NkUx^Oow7($04<1AE-~``z0P*=Q${>x}uSJe~lVMIr-`XA^w}%Rn}M- zhY(Ef3bEdjmW{rEFv6Akou~wnDh-O!Er=>PX}PR$)vTwjKz?iSi}ye^+wa5Si7vXs z^)L+4NdB`JXTepOpus0(fj5*IPDb;eoiZBBIsGtqh|wJu^N~n$&odYV#4SxQ6BR+5 z!Z$Xf!2D{DMFD2GAL3IKCT;zgCZo*MW`v9A1HI@MDgIoNlpGxEz=$gzOO`K-%S7*m(~$6#JH0rZN?g942Q z@l`~o=+ztgnx!asOB)3z1#||drLO=*1}Xx8C!*BrzHa25p~t2tJ>lq*hHnTt%rsB+ zUWs}Yl`+>hL+_fHAP ztxPJ^)W`%}%4vO1t}#_xUf0})L3f}NFZmoH?C`l4GaxS%qXuZOxv}F*RrN zMei^+ku-BT9jQ(k-p+@zyT^{w7xc@K$D&kZU?0bJ&}+zE+1f7yhgZ-A;TdfCC@i(z zNuX3CSYpRc)Kp*-PL5rfbf@Oi71z1+=`k6Us-bvXN;UE9L!984bg`Lyyf!8e0i&aN z+;P>Su)I&oPd+W~dQ!dAL!C@z5y1&3aL)9C2_G2CHj5IHDuCLs86F&Gtt&CiWLSY+ z@6i3M!E7uqr~%_@63Hr5Y}281jZ~UpK^uy3w}xcX0ap{pYLZ01U~6O72zhA-kypgPIpnSe5d5JSp2G%!=mW;feZ_&#_K_KY$3 zTX$;vm7BT*E03Q@S}>F*Wcz5*V%A)XBX}V$TD71?^>$A}=D--;yrW4dc?T=DM+h6d zR$uuGgv-@2X|F2tzk0Lj78s$7L;EjHY2{AY7E_|%S|f^WDpBI`VRtRdk0sP3_J=J8 ztnzJKaUuox?7K=N(YNfO3wx>&If+r1m4}7x1@Gm4KPcoeZFgIhHTO^w=|xCpcvPt< z54K+17<}5-I4`qMhdC9c&7Vyi?y2zlg7=8=!;4~DMf&%GSi?jK;>L@xmy{`~UmT=~ zfyfKlrg{9PK$xim9KII{BJKI*ZQ#AuM2Wk(LAU>Lm^g+8&zvM-v{zfZfr=Zh*+Zb0 z_`bkS(}z>8-hDT?7+TjI%)B-|FHJqzP;K*$0$Evpd*#>Qo7N2smritHkZ#Jn=sHfy z7CfC?{xT_ZOED}v2pZOJG07^K*eJRY>2MfUNhlob*FeFnIrrMHxhP`I@Y*p)wl+~E z^~tzzjlU`>??7eV+30Q0A?4vB^}#pR%Z2)Tl`M2xPi+WWBT#^MZ?)j)KQ@{%S`i5? zH|&{&C(iKfK-2K%RZtm_RV zta1+T_`po4%Zno+sZaUP*jzQL?N;9wm{%Boe=YGO7M?ji;4A^&58)|5@-ZcVw2LW} zK9k2Dwnz!xlSa(8Vb|`w*ll2n?;czu4?V>U*g;3C>-@~m=repy{IUs$O#9x2Zm^Bumlx0#i#^_ActhT6s0Z^+Hy?d7m_bhL^h7<9*qQzq zq4Fz28mF|38r1zoW?iwvxc(FXNj(k>h_fzWFP2>koYS(>0atFO7i*JK<-v*I!sOBO%-0 zvF88PD(7#Y^&g@HHbSnyyj)e-3Az3N^8W;_{}(qMu75NO`j^hG99*3L1!nHjv9Vhl zMt+~v?_~ft(V4J!drEJHiK5Rh1Mvu_LXcV?#OBOWA05+n$4bH154mBQ`{2JcjJ06ajJx^jFYO-`r>2;1)V%KtymF+(@0W0n1@LZ%naBwE*KlI` zZKc&b8f9<8DreuIdC^8pq)jpVy3#yJr3tL@>)4E~zUHk07QHFl=Obgbz&g zf74?qcd65v-`tD2itwmo->pV7l~Ef%+;`R1%OF^A%Q)G-mwTJe;Ij>X@qAN%{nkx; zxm)#gHBqdE6(1AvZ0iT@I{H(&gPk^m6;>1jYh{_Q;LQLIpn#KqcqwU`9q)^>N2L<3 zA|b$x0jZey?C>*7suPRnhCzU!xh!&Dh_tpL+_TDI+>szQQnH^O2fm{$dF*8TP@#S( z8DX*lP!XuW8Z6+Om6GAv_8@9R6eN&aO?Oo~GRlAm%hqdmD`2NaJJwWG;9M$lc;~i> zrM4D1-AtWshq;#C8k9aWy=Us#(=WJ}_OZN*iV?p&f~JWyl*X#D8j1ei3spa_|BV2T zCLh_7y6~!4aTYtzhu~Sdhs8e#4BF(J^?ReVERiDyY2(u`WQSppPq#xM%6tjQJ zj?m9clL4vD0?`JbT(_H`j8<$mrymhZ+S^ktU)r-SQb|Gk$l@|Z1yK6Rpd;}LN0H20 zexLx2`KT>Yj0+RGrMs0%q(ACM6T-X#%SH=z?&ACP7zyXpE+HA-=UL8>1}+t1 z+#ka~%0!kN-%@aZ%HWaGh1&<7!P(oZ>Pq$(z6%WJv5VP#Va;0<#;)ys$ z%USXFFugwHLKYP#Q3L@N;pZJn19+(|O@8st_G&fLE+LOXJIKk&_zbbMGP@z#Nq3(X;DbTpa8y#Z{Jpr2q=$#{^Eal&`Z^rDS-jve-hJ7Z-TR zgyO%!U>-YHPKIkWC_>ZQ7nOH|qr;9|{EtwY`7PpO`Gt;z7v#y(5H2JJZfV69BaQN< zm#_JS6sBgs4_TUnklc}Qa->~D9ZH1UQ7Y}JNaM%1hMjuQRNDz$pe~76#*=!g>C}W| z(pSeQ(Q}MNoz4M|@z>rKP%!fM1+vZ!+|ge_tBij(h5+1z&&H?r%JIk41x>L6Y=R+7}wL>iEm~J+3>koA4clbA>I?hkjwZ zuoEeiLCb-uAUHI92Dk{rsvsCv2+jc|iL5d5K`U@2(k)Q{Q=69?f?|GlvLxuvs|fBZ z5a>ZBk*5<6bSnzTjd8+w-uQWm+Yh`U8;P;CMSt9lJe}c}gmEihTZ7n3rV@e?lL+_c zu}$jPLpO&UnDhx&iLBdB`6%$56b1Teg|s&%=_=q5Z4V-U2yz**uHg_cYc_|Jdo9Y| zJ9aGjc-G|ThV)q)>`l9o2wzOwEGFrNxE2ENl(#DP+D>tc{Z`m5E4WY-J(6hKd2_%_ zAd?9LgoM@5Ma2-<`C9f&0($R77lTXum)Wm2aSZp@DIk~q(B*<_Y*t+X#r{j|4geCK z8T6uP&cUek4XIVm_GknyeBEO(_41}%Iyg^ns2xXZJ%FlE> zw(``fR1ibFJ~h8$KaG%P!*B7Di+R><{LsVP%1u{cwW@j6yzrykEGuHN;0*|O_uT7= zFRXEu>92c&JdHm`Vi$>QTg<6TT}rjJSHhYomrTmsF&3i{(%=A!;n65FgR8w6SqDH6 zDMAjglsE0MSqs z6u)qh5fZvn4?^uzANg!CS)-rZ6lqbRe|duqm|twnq26RBEe}VbT&|#OEX+86-UkCFL!{}uFNJacd*nh%qDblrqZsKM_y=E zZYlr{H!bFsv^TGhNT)1!C~H}|;t^&0cC9SI768bkE_Vo9J5T%L#OEBb7NCA;1v}-d zK|DF<2nQnb0^Hcoj+7Ze(*a5y&uHVJ!DW+ZUHstKO!bj+Il>Rw5h0%RZ$EK=V(BVf zfzwmjH>z;9(ZUE6(};3}6&}HGVbb23*{yG&&(VukkyPaCVW>0Mp4!wsb7WSYIa8@U zj5)ptuO1DxU|wu^C2fLLkZ4zn23D}Noj)qN2s6HSmoqh;n3i3@tl`d`fH^%I*e6MR zQl!=8Rqt&a+ByYwW=sspV21Tf#Ttul#Zg}$maWfZ#7<}6T6^`&Bo1f1>fV~GBWezm z>yqKMM6Glywcdo6U~l~uQDepUB7 z%2(0%b8G|-f|hv6&bJnpSB38te|5iW%Up_b$AO;UFjcI8VAXm{Ix{Pv2*t6%YDO<( z%vVxe0R7d;tWSqzo)na1F!v0Gvd|feC+oP&djgz@XTvJe#15wQY_E>-Kv$@|5OU$i#t9?DGRSx4RSaHLPl6u~JWl8V+KS-W^@CHov!^R^OT z8=go|O{3)Wl;NT(qPCFUsIxU-&H)?^i7D&@~s3m`1Xxgi>*Z$;4oJ3d4k0 zQ3}JtV9ru8Y8?R=4>uQe4JCrZNEKfTZ^DwYe$pY&f_Gx$dieZdt7c;U(1hRE3T_KR z9cW1X1g9LpXpw9KQ`3MH<0wPPGrQ@QEg6*0xUq-r)bb(fTo?8Xb+PydDraM%XN_A6 zRjdeZ2+r_kQH2MQB>IsrfTiq056pLsB)srLD+Bt0N(}b{4v~wgp zSxJ!_jOhMR@aT4zj?-F|xO@haN0rd%bOCHwA(6zXd)TnpGu4I8G-ec#7$uY*G|Mp} zkm3#0k0eFJZ&nlPO1zF>1G_89dSR`O*&XrJDB<&XUid@5zl3F6)Y!j_@ou7L0ALKO zXXF@>Oak1U{RrJ?H0B*+P$0Dq>vZg4Ax-)VnOlQEx$?8{ zf0+n<5$9J&&1lVMa#`5RPk-9CIYTtJAPllgfoI^M^Ht&C6t-^f&!uopLZHc3&w%f= zY3g1Sf)|FJ1-1mMvd=e_S2Dd9EKtlA6`i-^Y;l%RA|Lx0#Ley@xkFqq>FY*Xnh1VCe z_`)@;h?;ri#$tiE*O_NXsy@>(YiIA*#B`f}aKxpq*F@#)jo7KM&t25_V(aZ2AGtdZ znvG-wMteLVq6uqeL{#G0N`U!MBwzM=d7@3{gypO-J4;1mv2q-(oT|t_{f=IspWmg2 zh?5^PH|4alKi0jYaLk)>5o_oy>{Oi^yB}%r7zIq4=RJF^I63{0kf*5PWESz|+_m?{ z1o1w-ar6M{Wo?Agjkb4Cc+{MV%i>lP^Y%V|&GHMZ2hvQ`5Q1^UUA`XL7>9cvw7<$M zHEG*)K}pN~q0tji(Hf50&w-$MihXCLndi`_d;VAbHq|Eu9fKj*@ChTFxL_ujaWa{{g8Y9-#j}u?nt# zRP+B^#=TsB+b8yS06EMhWg#b74AJERg|Ox-rNF-0c8s3E_DzS@{sxAl5Wv10)N zKCipG@J3uO!`|_atwmUQgKa5bd0KehbEL~s+G5S}&>)F#?)U=1v78{hH|>=to8^vv zx?QlpkruS_^;M`T<&7z*?UTPGJ*l#>bg+S7?k}+Fb6(kzP~*1|oEqOFAm08C@b1{G zh*x5jWhp^1^mB=}eNcDd_w@z(=~*Nxr@8pe0P-sTRpW;j#{Q!Q7H<)A!28b$9->{Z zWtFA`6b}!ECRJZ8PYuftRt$q74eou`urT3evNZeQZ^k%wj*i7*{5ROTfpO7L1wTfQ zcJ_cwT)(+j$P8E{N|i*qU8mhy(Ku;Eg^!2~<(Dq z5E@ry#CvRIqfN*vj#n}<2)mA6fU=}Pm9tzFi}adBnCeD$K1RgmaL@BE+430Hx+cJQ z@JhF2wolns9j;q)ybsezGr1y2cr&kLe08IaRG~JN8BDG|RolgHhOf9%t}|o{9RFQl z%hTH&3N5z_mF7YR4`$f2uzujZ&V+4eF>}%FHjrU5&9H-`6wFUJk* zOEH|t(xdt3ueJD2jw$lSsK2ZnvVvF(l#gVH8L4`T4xxS7zwM!P?k6lj7}`86NoAywlTA}|)_d-S5zF$S!} z_uRQ~PDUqB8L9cJ&`gX)BF{5Qmz}AW<4sx2OF#U%7qVw*!UL`+tpMi1;9^_UdAzP$ zF2^nf8@Xb->UUxqlM1N^2_+H5nFq3Uah3cx7K=MYxzutkld0>3ChivxG(2$pDV@cX zqhjKmQx@1Y6a$2Nagz(BP7nm$sYX|!%4wHX3M+p4y0pm&2Nug;?vqH@EO)XEjl=R4 z>nDNy8H4(v)H3UC752XMCsWNE_o3(ME+bS>X~F6y665L;(k0I|4BjzAuDB`xWT*`+1_vYP&QB+nwf;U1`Fj;GW%|^ES}W><&lMo;WU~?GjSJ44i!?f zUchXgc!fsEEI1=BvRJK+pT`t~TmW-g%@y&x#WJdg&&bpd2DdBcE{SM_HWDJD;l(G` zGZ*MwYUb7$W`d0B0vR^Ui)=9XCz1(kHx#03+Ymz`*u%`Cw%Cf{)leSngF)VwMQGs5 z5Qq(PlC9NQonXiTg$$ECNeJdcVO0~XWHb=sUsR1qYM zaISfEiOUf0?$A6!^E7ms(S5()9z(@7C9RxRw>v&z`2~Pb=SwuQ4M|W#?V4nDVRLYs zMm+2NR56V+j7hDeuED>}ZBQJ|M49%gzLlscO>Iqrj2_S2IPr>lV>c;tstH>$`vV9V|?jci7$T##%jI+b*1rqQc+J zS{%@d1Chz8APj_LO)xUtH{O_b@dP-ceW%(PA|S={xkrGobuQ*C)Z_$*B&^E7N;V-+ z=U!45RjnfWDU)kBPm+77>=E?4EQ^AOGs~x!#IBlee4w*he9W-rph%YnMtE#`Tw0{D z@)u0X_nAHz8mnPeSCF$Y=q06%lvP$bUN_gV<~M1W>6S>;2t^ziPLjJODbBKMRQQ|ro_69{|wv!lUNRN|`}@Ma6*H&k4qjGyzd?o@;Qqd^P#muWlR zka2JJ{AKB8WR%hjRw@&fFP3dCOwGS5e4QWcXiPjhb*iLO?xx4)#jP5qHrh+h%WQZ3 zFAK^>L%YSU=@KwlF z#yayhVk448{bjY7I2N%qL(jos|ZXG8f^WSS3CPu>l zOu%D<`Hax}i%t1Q{^ftAS^hx+@K5UR(4$e=fsejy@f7Ue?ZQT`D z#Pv`Tn(ZPl?DKGG2_1#YL7Iy%SSpiyN#jQge|`6&4Zvz^+g;D(C30qqMY<)x=P8V9 zwBf*xI{3J{|LA-hT04IB>d7RqTe{hQ^YC2Xpf4GF*>@G_%Bmr_Xt~+Hy6<@(TJ!aN zd1zT%^X<;sct2drd4G)=Tg&+neqr$Sd70~Z-F1F!@%?`E=+mhiW59jld(KcYw*Th* z?B1GJ2iC0*f_TzQ}sY#=W94(^ITBu>#^GJ zqcyQ`341)|uJJB3_Q3t|o2?{kaAIrbC&FgDp(~eWz$LDaFW;ReLXSw!dBD?6vpjcK z&5*<)3P;Z2uA$#3wzfXaL_z8~Lx|UHoax*<{m^?$PxsZ#oq+dCObe?2^-@pI+i{I= zk@w?iPxo8S$I!>!y}HS6jjuQ17m&>8;MYyxEJKF6%42poj#$-y2Y;w=k zz@G>IGZF|E06ov zt{yrk5g*k^5oI+?(rYCd6)&{B8;2C45igzjmBvM@{Jw{t8*;k-zjS_?Z(s2X5NWL+ zo-dQOp5M5E-QT-6UmPD?^9NA8sCbGrwoeVc%{_E}1bZc?z2T`}e8^YVBJ#AXbxd++ zibcCk5~u85y?JoynSyRiwHzMvm}kxTH6SFXe=K<%+PrrLJa^=_UryJkb8e%!wvKA) zeN%Mp-bwNA<`6+9EncCXHEX1_XAy)#F0JZzf)!MM|Lrah3W zf@ibbY*fn(ABWe4tW9`V-P)uMp0DTw63}fnv9Zhc zYCI$MCHuhm}fnvPx~iqGn7yK>5FVs#R8MnUEZ@*StYdb_28KL8x0RihUq zuX&L`k54+#Ht#$QF<8+3!o2Q97UvDLCW&pmNn`bS@8Rs!*`)eq<#zts&Woj)5{$!U zJBDMsOIL<+sto>8w$b_REr!F})Z5z-BOg%eW&{eEfZBSgOEy}mgX=P}#C008^P0eU zh$7|u5uqVteC&HLR$n<6FarJKOAPz&xxX?GcSyz5Z&cgQ-JU)>1l!_VWJsy^z(#;d zH*e&Y9FeYw!ef+CoxsERuA|5&EtR878NU$WYR=YKDT=R_(QUMMy^w4b`KG7BRV`^ajfSsw(fx5{Yaka5n<4W%u6?)o<#@Kq$65IulGSP6>_JwMWE$ci z64BTbYF(Z-;=!P%e9&+UZAGt?r>P6o+7anmtVC20z^E)@A{QRYSY${ATFVYm) zh#pCj?!-5qW^(0<`}oQg#mX9t5=DI*p~XFKV&iu!_Nu#uVpF=`)GCXMj|DnO9-19O z<}dAp#MsHMOnZryBhQ$m2`rWj5TfSJ${wr@a2}zj^kSr<&#w-!=E!-M zhBz;8l)k7u=HER;-(Ro&0*5QVkJCzisCHZ*gLYs{;o@rugOO|wfL22Nv>wWMsu}@% z5(FV`o3pAJ*1{|PK`y#M{#r{2SSt9U6ipVor_cc(WoB9x?VQ}yD1TltvBGxxEeEoR z7(>lm1l3b~(Xkc{)K60FI9+6LUOk~wH@n`H`B@k&>LidmX!ya4Yoi{GXeS^|1oMlM zM1BBbs_?*}n9P)C$>y|{g8pXP2YC-D>$S(q7fb|k5c`6nB_MU?x{+Y-9tlma#?z`GT< zOarlR(}2880hQ*Bx^g41sO>2)=hK4G(w3Qotx0rjV))Lu58D~`^*2RHiO~5;Ax{is z>U7j(V;Vw~=mE{*uGJ&&th9X*a>_wH3QLokMMc6i4KK-@js-p80nQ;k4dggdQcMJ0 zu|17+Bq?nab?rI;dg9!oAQ-GJUbMy~5qg@VD59ui9Zfq29l(nLzIn3R^~K7m-c?y+ zQHV!vFF|QXYpxyw5hkvvXI1uDe`$rQM#umbi>AImdwHrd)Lw5lp&;aSVLkar)n(i| z(U8X7Q=ZeHwz)c*P?v6eA93E@iJF>;fVL2`$%Ieys&wd?wzkOVlv&0Nw$khcR8*Gp zvGq~qeR!qn7PlIykoDC}XXOf><9r6X6o)F9m)7E_REPp$eSdWaJgTSMV)eBVZZU8i zaRquvPI42>j`nlKuR>qBMO^m>cpw@j+_1GJy-w6hR{nKhidDJCSs4K z_;v8f<`#wvp~EH}TUtj~9V4c_Uc=wvQ4H3yYjN)eVw`80??ANH6Az5{Pl1wFm>+gx zizkjl8QrbR0KnOIsz0`-oP1;U3Y^?xl@7Gw) zOFPSqDtK#%IBL`$lI!2J@XpaS$H;0XwS)(T z##HA&mnwmcBS5lqnbT8k(GebJvYKY4IOgEfJYVzIwv|}vY5P=Ga#K58@Tl+rL3E?c zb)2`P?#B~3mS}j*eAP9r`L0MGyZWzssJOLjag1oqBPRcCBuLR&JC_!|4q`PTkVBs; z`Vpe}(eSe(F2Kci&%pC3yx*_kg_oYq34K-J;#HNyOx9T57JD6*tAKh41pP|rxV2|1 z*m|=~tzs}y%=c33084`FWR;-OxW)|r^aM77g-UGAI3sJ9Bmp`=5~HC}30)G`(}ML9 z+QcO~gqkS1O~<7BFD$XoFTsFBn}L)zT8>WKL|pXKh-!6DS$J#gp)sk?C|CtY6LbwGs<1lg1H^porbZ{#1Dh+Z*mmjH{rPie z2$nn;P~*yHmFdqxXM31uuB4bw+M=NtE2e38~UxMsxw4~xkv|J7yZxeG zmwY)~w8qBRuP_+Rp5dv8@&9s&*^!0Sm;9VRgsdw0H`rvRV-s;5aEjg+f2r*|_hhvHIlUrWqS@L*`a zI~q>9y$`WO648XTtXU#Upv4r}4siAy^u9V=LWLnh+5Y^=_M{a6=nwVf>C-n$W_dH?vT5WWbIWxB++^0mfi| zO^9SfeKBX;+osWQr%}3_J}vS6a1fMQZOPo|+Xxyu~ ziWJ3tr0fmyN#%<&5|!}L{hs=bVz0hz1rqW6um@emq5YM*a=L#$^G?}dA~@eyo=o&@ zbYgF|AR&qtawliSb&(;0pdTjo-e_7vi6st_G(?Oo`&kS`@wcbCcr<;2#DGS1q!E)G z)b*;NZ-6rQZlwEDezn5N?9SValqO!(@pE%Nti8FqCQZ$oqPER1R${fvT^yOoP2Val zBxugJb=XM&Vf{aiZ?s#s7k0;D+DHL+CbPoY=VUSPZj#ArDfR6(TQLh1?%3lmUBV`X zujYP4=ONTppqftIFIGUj0TU7qwkgOX?akx%gS{Ld7W9;dDbRRvan&nL8Mhi^tg)vl zHS7!kpRO4saLex1%F17f9_svsIn&lLActpK@ZvjM<>1FZS6J!~GFR@&RrW!|&7CU{ zA8sC^`%qspV+)(5C_R?#yNu3T$8G)C8|UdGS>+;qWN7W)Dt&Pl1b%j#5TcAs>9BD zHCbvpjgJlli*L2M7|D;OLvn~tdx+fL6DZdw@2w%NVM1KnkoTmU(gg%iN**F_*Ts28 zeIu(j;*WPal}JpWi9apzdbpQil03cs{4a_RsTv|$W@9?sfgQ)LjL84y(-SGlxq2#` z&t~luw%jIs8XD;=yBL35d4Ujh4ZgoHIi>}VKwKhE6FP91lf-t|cE@WicBXXn(B?XK)PqJC*8Hd+ln8*fz6#_yt zIrHZ6N78Rhm*WQ}sBdNBf~tZMlLY=BPhT0;_VavQv_Nqw#ogVlcyKFF+^tA( zcUqvhySqEVy|@(%5Fl8KySw$t_xC^NdGk4u7un73%-nltW>*sT=eotNB?FJe582dN zGJxcfFt=tQ7gOt3fpMRc{W*ev&pRsj;G@W^BvwRHS7>Q+F_0VykIeKYfZ*WlPHgL+aYg`6)#kR2@Y) z{hR=@I`t@wZa*;Gs^@0_E}_ewOiDa`*US%^s2eAnUh*SmIs=J1td+?&f?Z zqr*HT4Q$<8WU6WTwGt=o32c@l-P1DFAvpH^Vj6z01~kpQ3E2Pdo;CqkEP4fA|f%U zAHZ>KZLl#Btzny~^8?&Gr?3!EW*@2_FSC;%^pRwG$xiFolEu5=&F8QV|-0<*T$icH?4ydj8YZyLV$ zk%1H_$%Q6$l@?qz8(kmvzYqMRq2OU48lj*!`3Edlly2Dm^uh!3^nkA;hX+yjX^`Q5 zG4=qm0*UMaKk>CQtmX5Vj*?jjWj$34G%NRg0OZQDj#S)W89?BdsB*flvf(xN6%eQh z9imeV=Amwj8QX8^M$wr=w2XDAtAV``pB`al5%FlSrC7{UfrpaLIhV=H_y>iJ2)WTV+f z%XzzKxy0)&ZCN6S@PS46Ii_rfE+MNtrLYe>yry6FtNh?f6Ug&pqfuaG5^@_Ffg5Nq zW-yFV-t4?+E~Z9^s%g6U<)J`Zpq|QViCfSbN@*lPtLK(ian37IwYtB^T|k@zm6bx& z?1(EOH?bLh7J({+ zOmL36R+eyD=dZr0csvHN1uJjUBi3}`@1G&wE0sdY&553O%Tfpk^#zF(?nz&|?$9;Z z&2;vTCfdNJ=C&vDuxNsln55+1knRX!%b(dx#s|^=Ha#TU5Fuvzrzc6lO|+pMNH2rf_{dSzJc9bFA=d3SqKdp^~uzaIAk;u9MdWg!r86Mhu}^0SiZ zED?TQ;ic=NWgndE&=J*jQu({=`~8??K~22p)iqaabDJL^If44k3dp@;x%pVl^d-T1 z{@Mk|U<})A`fd45pgoiN_8r5t^sraM|MRkii0ou@IW@bBR-|ksE0e*a^j+E^>h;ZZ zK!l>DAf5Y*bEmepe>>^!|Nc*#e`=9`HQt#xKeE%i9gH*9eyw9)*lJU}MXWN`c)F|q z9CPYI(syiY!H86{3EpiI;pY%My%Xt(diolxyv@`;=pbMV*i+1J-Ys5SOjz>7U@0~B zv&r`yayAJ1TbUj^QqLdE^@2|Qm-WPPHNDP%wHFi!Xui|R^T`YL!C0|a=O@~@9|Id0 zJXO`2Pz|4-skdo&yxcu~u)a%Wp=et*2IMO;Rs=kf+y>ajucY@P-Q4$rN8_AqQu8lA zU;s@PpR#$MWsDh0w47Hv38x`Pvu0ll2}%jf~_1%NG3R~5&1=9{E!~O zfi5gfJ>;ETh=d860xQWb$FX@_Ffg|^UXaa1v%GNgb$xYn-m;8^0-&z~WToNtas2Jm z)Z_9oIxQ+g?Cj7#k0R7cCS*fTV&_!wyS^fH!j(L68a<6ww0piy^V@9j@s~X~bbE}{ ze*PtG_vDJKUpuA|&x(-pHf`C7{644#>-BUD!FN6!77d7jZRukuVc)yCOXY~)IR}Jz ze$$zi46CN^5=%TR$133j6Mx=ab97)i} zf#X71(=NH&f$Wr76C7w`V%km~nn(@7*Clb#rANv}gVMCdP^@H*u_g%I8dTVcD`R&v zU+oGf*-A^gJ4?FQ#Tdp6iEj}3?uN!2i@afG|ojVqi9e1gX>*qlI zTl)KRsavg7h{5DUyh&lK=k{ocn1{Q8PQhz~U<~|vSH{$m z&Ech#K+kPBwI<@^9gPu>oCkj5?33;Q+sszfj?Ib*a$+}5iw;a}M11s>qBS?5n3~L* z*HCAqO`_$p=9RhVueC0=a4B{nJ{pa?ysWuoEJ>E# zd@R9O9Bz~p#0{aPs3}Z1fo^75Dd?uHI~Ds45}hooHJob8qaG6 zKJBc}+%cKb+{M&r&Hhje7s8dsC5PqTT7gWlmRi{q;YQc--mj<%N8B|~;DkwIJSUaG zb?h9q^qsHL9o1CMHE$FTb3n--$!jXS@yyodODcl-gyNs>HH41A4xRb2H`P7VK!TWH zmKN&e!%mx}t9d=);}1APj@p*m5N6tuyik^+Zqa`NVoDYVTA(3U?PV zk{)^uLke0K&>W*vAF(JbCiuy=wE7_m$C;qFA*$n)*YTM=i?N3UG&!Kmr{r$6Oidb> z*IzDlMT-Grg~E5gjVdD(fksa;B2>APByicQ$%vT9er5S{s`j}|nS zwX28n)z^nMl915i#{`$=U&s_Hllq3@LO5kO^4aFuO~6VZv64X`|CUCMC>`*!R{Eq_ z!1`u!#z`+a-+=;5?8=p=!kL5AJfLD*ytDW7WBMoh7Z}|?f}A|w*p8tdQx8cbGJlGH>D3;4g)XjUZbZvCg|D>k#+(0S z$NBh0$AVN@S0=KmhY=`kc>|#?X7QXlFLsQKDOY%c7MRXUY@v8q zxrRlppLN&JTLD!$#KEbAy<)ri%fy!xPvhs285p5kpJ~Oi#nCfSe_VMvtL-%%ZnFN# z&tgZOJ+ED`6dbYB=ziT)+N86cpc*qiq_a@91ra@j=JeC^3*T$^)qMOFW5 zY^ebuy`K45uO=5^!~jFGnX&_A1eg8Vbp_8pwa+X5d~N&ULDN7s?P>ytz`Hdc6+!1Z zW&3|Sr$sv1F*H6cWBPPjyVo;O5pD$Ai&w=Ix=<|&5V)fze!=*TDtAT?vnwciY!zmx zsbA?oyo+_+ft`lQ0aPvX>`e!OhUKI>DS@fbZ_}z>*7q~xSwUaR*>!W+w27?d?|}*p znqM`UE?ydw^y%~_>(7~I=>ac)FQ#5}l#H_o+OYc64iWk_9NW@7=GlIuNYBChOlHRdsL96wVt zD2yb~!;3xn*-EgelN}ptNzf@#RSz*Po7t$}eQ!p9i8^dC zff>&?*Lk16e59E$$fpGf>SMYb@{q-^=K!Q7P6~KBl}@D01q38>=b~omM_Fd&=Z;GF z`m!d-_MHi!4?Ata$VX6xd%FvnQr&&bJhYET*MgLrS-|uzG|qIElK9pm)I&y(#9IqK zJ5O<&GmII9Om?k}O`q4)Nbypy8jVu+lf+`LHOSfC_-`kB8aR)yg5zq=e&mT1cwhX` zAj$Nh8qwi|H9y6O@=cf*H`XK5g0rjuYnn_ ztI306PBCR1cBHJGT3{drfig``87}pl61^vG;zEy6_mh^~zZ_ssW@b|0HBPhW!DFiq zV(yIj`6I#4U(|8&Xc2nGXTO2RzIQaljVfY6qDy+q#1!KoxWRmjq{fVhUVr(I zcB!`%BZtUyXvqTVJGqlud@;XaWP0X#OWh9cNah+{RAkRf{k~7z@-N0C-S{F zd+Ai;1w(QuIXQq-t<6Q+q58tdg**n?Ex?Ve|75}|WnpO;JH<^2cfPiIu;T%JBYrHk zn6vS|eQ+&`w48FkjNfZ*W!-z(A01BjNUerhR3kAR#B{6S=a~GyN-MhM3|3;zp;gJpB{D!Qx&nX^#K0Qnc>OTAnlM3iHWkY zzbCSi=~FTVn!f zkge9@%uX((ZL^0@Lu|eKrU?xr4l9$OmLA1hh+Pbh6+ z;`)2@H83R%#UX+HIbmz>|HffC#iH@#e!Z-196B0~C?_`*1!Mh?q(<{yiqVw4q^oqD z=xS{f3{QQzl77LHBt9~#B(WY!YI6ITzSb3!N>#K|262&0A|>hp9au2u7|%j%`P^E? z0zdb$P94}F%5U{tULemJC zN@^TsAnx`LkeR%BSTeRSN|>68jP*41_&pvpId(R1`XE;V5pRHhDjXdwGp+jMZt37J zB#<4YBcnhKl&LPzBfvBb)S&axr-y49txPxFyu%r*&fFn$}qKvxk z)r0E%gzUFGto$t&)Q|Qb`m-mkFU>Aetl%DRWN_O=U=|Lbc0SQhU_YcO(j~)j=$fdG zc#uCu!6^ZHq)pP@>9B|!m^f_IE&h>0tc2=hr?vVoTQlr?>39 z54?-QsyyWlH)7HMU^^6Ea|F92rG7jsU@Q)WG|E~afS2l3u=s%MY|+(Nx{vMOg#Fga zn8NVO5>8|C8Tl#MrCGcQjV;%)J+FX( ze9NAvUN838KZ?6XJE6KFq)Sm*qx2<|`oi^*O~+JiG$%|M|JhLcXMUR4QGOO6!OS=3 zmlI}Yy6L-m3WwL*+v}GNz(jd0?+t?EaT+=qAgTiY$h(EQpz;i`gog_59QLlz2F$xQj<@pl znG&_#RozTl%$qXP={<$G7tG-o`SZcM`{oocGTreg(9|=UU`Sn-jle`drrOQjk9s(T zT&<{BH8qTChAVh5rG{;fV_w(91i8y)u7+zu_ZU{H=WR0*JZ8LhV`1k*d{91-ynv(j zJV9j>>|!v5_>Z)?vigdmpK-NNEz~>wB4K3=_!Y2 zfS!CZDt&5hwIV*VCra=D7IIz(})ON7#D;Q5c$qQ z9VuG4I;qwsSa{cq!j7c!lUWneb8BCro032jzudsF{{Z{uxVm4Crie)I+SA@BTK4U9 z`>|ejHfq=%aAGI1li%>VD!vi-a(;6c-}jerZA1Jaz~ZW=?mVTWUFjY_MgVi^e*1dx z`{?$Qb2-gF(y>c#D5a!__~sdja)jf(!L4uLpGu5(Gihc$cpon;cgS$gznniGA_`d= zntVN9ya#i6$WPtZw@#F=p1!{PN&5Q|*qxv8*V{kn>MOy=f8OGodF6xuo+zCDy`FAf z7x&Q&zuj=Wpk4I6hVY4Qa2kJVK| z@I3>EqD}7;6;`EAl3jB(FZB2_J^XrHRVXrBJH^#0yyx>&Vr%&!b+?CZR)ucj-A}P= z9_+rxn-n{hr|mYOnbGgo#Oum`L?a4`z1Q1rg6}eN40(Y2ldC96J4#c)HHR`;PH_<$ z{_bX+7z=eI37H%o>;=a07}HVOynYMp*aQh|%R0q2%*LvY9=nySzUC(BFU86it-g|Z zV7o+kBDnf*P(v})-@6ZBbNCL1& zZ8*h81CFi&`*JuuxsaDn?;d^~zH{yTrJjC&eC@*j9o%g`6#O#PF!_45W=iZSWIW`R zejg`~ZE@w!S9j}6dOjmsHu~zaK4UFE(js%K8o)uO9=_n7oOW?{m;ZqNkLTm%Ob`>r z7OZ3%*l9n3^7XDTKuIn@X~ywFA*5hg;uZZ;K)!qf64iFhrHOrr=%HYQVU2hSy%Y~0 zfM*@po9eDY>R%P(wXz2qT%fVPM9$b>2UeywX1nzQ3Pn}-%e`Se?;-1vLhwR8;^+H< zEN$WKWMiYFaybOjru_Y?>4GdhOWU52YzG;Lja#?=L`#06VnY)&WmthKuHyMrL`yna zJz=SYWjIBz3MTqoFRl4rsltEc9I=hi4U5;`Rg=*yQKWZy8GeOxO~L%d8l3?}V-5~B zBT>d)D1akVL$Kjq>uyv#^_0+rCGUNsqmi@LpLD&G<8n-@gKv5WB6pEu%6yrM3heW zHF*cjCBJ{pV?Z@;k_pZs$L*T>2-jsIwB(V|kbKD$7A9lAAS>S_gTw>tf5p-KjgCEK ztvvM+6{5Z9XDi^R{QTO(T35FImtmCK-#^FLwlmfpf$^E(kNbvw>qJzqNqh53Md%uw z$mZm?QOE~ZK$m?A2~|~EN{Oc~4~y<5rF>qs%w zzajkn{+Wd7Q5Cz6Qe*(5rOW_59Ov@QrSD~+H)@^m_)-Uz+DH!t$J`(_?MiG1 zrC{gKH^%73ax_W3qi$wd-|}*HHNy)0jT>^R(rdJ+APBcubPbgzVs~IKnpzuzj3`=D zj;fB~86JOqX=}4sqI*+S__*d!+i}_mITZC3t*4-fPR0^P-?2A*rc9C#n^t}QZcr#@ zC_MGYXL5mV5E#y>EqF}rM7W?I5p_QJ?3vB^%mwY@6*$(ozQ@j7f5>Psz$^Z2829ON zFd(;u!)oMVTTxPdkPa=~+${2gLz6h^>T^ZySKh|fryY8J^AdNy{+~Q45eJMmOn2!A zw3nBdrIvXYcYo}VP!xPpQqj-L4(nNgzRNmwl3g@g(~Cv^VU|9r8bxf0UmQ%NS%NG- zxYm_%Zd9H4WM4{*FH(pUNp=N3M8F$|5b8A{-(s7bSD~ z^s2*goo)NX&f|F@k0rY;1&T@YLy2_GwNi*V9k5T&tw-F?_&EoXHiN1>+pzv|CGX-E z7iS~d!YO>+$`Z&WdzBzpa8otC>IA2iCLvbEvl=9iAg7nKw9>A;SGS=f)AhDjW(l)A zo!v`?j7^Q49`apKTy(9Ix{;m&fl48~)`kx(XI3EwjqGez-s+E8JAKoA_uB|q-qzws z)a;!KZ+`>3`@{*P?bcS`Azbr+*Z~lOh$tGfJ7%6|Eu6%cv<4s`uPPWo2CQ|~Z5^e($UB4jq zPT~ZgKF0AV#P~nUBdyG_H6%JBloc5`oLN)rF=Pwj2_r?m42 zi`Q3&uj%~rFV?+&e+DXbTc1$MLC%X1-y7w$)@B7K;MAELrF@BJPU;O)4taKf!uleI z6mtv?SLKHaZs-8lovH0>a~2%DVetK~NRj=a8=B2FGONpJ|J-&W3d@E!BPY zjvGCcbV+$(Cg9mUzPBXRsciV2#05{@*=1qkhPRW%4v<{E&r|bJb?154N;=IzFpJ9A z?yL9KlLny_nWtaS)e8hWFfCM-7B#?Gr;^=zU5Y;PUXA?^TQzAX9g zY&)jk(NiT2ShTZdf!|1yn-z#Q286b1c=Lb1<7bl*7u(GjA6uZ>69YShw49QYFDL&HRg?AxV|THruJ>0Q!#>HIcN>B?ITm8A^DzVPea1VHvWOoWn7E2 zO~d=n?^z01jbP0ZKu@-H7u7QC7W>=6VIKK=j_HU*)NCc2UhQ@xNE--Z-ud_;qNT(h zF65wIJnQB7#?YzxbIl=q;jzQGCs`q1>4;){yV{^_=8T~RssqM|2{0M$5cn~#MCV&> zDNXkq7$@MIXYSafD}n7&(tfGt2=iODek9frelgmwNGvjVB?PxE>G0d3_cTrsIS-~0 zG2XG7TOp=gRWxOv7G1=oxm6>vh#?|EQ)b~6(r;}Im9C>%Oer%fHGpunC>b^X2TZV! zbgi6wtJ+w4phUyb`D3hcs(8nxVcT_WU_rxp)|CxOetB=RYuYhi38cqOzzo9PQJ;1+XgdCt;?LC9yJAXbBtS9n%&d3p z{-B|!iA-Mjf$Qn^^~(QqLzmw&QIHmPpuric$-Ge;b#MX}ZL&W0Zmp5LM9;*NC&%&#dGbBR8=4xFyX=Dh6 zTwqKYnWPn2hEpV&+h4;(Ht%;V2^MS#$MQU->!Fw5D=WBvFWCyzRNW6;rpOhrss#OX z;n<4JU)k(~==pyE5nh1y2e318$kBcI=J?;Q94gI5Gl06e&0b0!- zalwL9CV>Hv88|cFQWpyV=ei|ZAPo@K=!lT=On6sP32Ui{;75`Atzf-W&EHK0V+Ktg z16C?|s+=IIFb^-l^ZKi@^>3Lmf1(9=&QTC?29`-BKJfp!`+H}{pCDO zeWlz-p}2TMhqz;v_s;zGcbfucD(OS-v8Hb-TLaR511Y-QQw`&;TtI)paK;9}_<$M& z|2^;5&u>8X9+yOq9j-{-<4OSSOEAt|A)sV3c8T`Otl?83fL2m$Z0%Z5+Eloz611;`yqo2FsTx|p=?#aIcV>+r=oo6e&PHsJCPlueB#=)Q*D zR4as{rYlaTAFM>`xVFONM=;tBreIyVmZ)SAuIv#td#nkqxJB7(%n@s=X@76}|H-vh zv-z-yQ@sUQ3R;JbIe#>A$k$^{W_r^B<@J^dh?T$ytLj&+`x<)%4|-jbiFPu!ZP})mKIyH zH|VDp&0v29YVD50MwNVpqb>e7YQmPyJmiXQE9?6Z80cCI|i2t(B- z6xvoMF^MvI2cZ*k%ELED+pj&pZ_CJtCjTMUdEKhHh`L~|NnV1x;b%-aU&xD`0|<;{ zy?`=8I80aI)$b?+KaUd^H)Lt<#q5XV_+5HdUy7mR*`60663+NRrFsk9Ka`&RL@QSw zpkzBWL@LQCT58D(%1F|MV z-LV1)u95%$cTK=Bdh#-Dv}Dp~%rE?kF^Lv)mX_k6di4Rt)5BIMWH^VT38 zlMn)qe}Yq9#l%}PB*d8=vb>>p6I&P!HS5@SSg!tUMu-gz`uz))V_cL+*eb2XMAyko z`zul3s);x756(rR9E_wI;1p2Oi~@EgrGK+*7Drxwv9{RLQ;5k?eJ4e$pl)zv zlGF~ojt^FPnt%hv0v&=;r0MoIc|I7m@umOJh5t!+^U2ly`*-zi*b`AGz#cPU6t&13 zC+81BxAU#BiKYLBNRB5YIM23L28kd(n`T-UCI zk3pPzDB=SCsE#>>4P)6%E>6tzEw?lT;o;Prd7V6+QrFwK8KQGAlx;j|=Wl7pTO~a4 zer|WeAA1zVJgsjcxYtTZ{hjm{*V6yzlX3lSNq>^J91)6KklZw=M&B#ZTtSJDxAD_%!?M zfCgL>SW7y^(N1~(LoRpDdfZdrdGYOA0o@bHvP^uxXV0`RI=#Hy0#&Z7WkQ>A(HglX zj#WmzrlY~v^X5~!l*u#x-Uq4EdfLbc#5v=V!XeYQlp;=N=@d^(Iy^v_AoF}V^ug>R zbay;HBpIs~+o>70m)}r@kkocsW^P-k3O#RE1-}~d4qRQXE}oB2o*uPHWB-DE2!lTw zItc?`b^3yN`N8cF7I;B(wD6c~K7L|YbbLHoTAq@-S)o*Nx(IR)J`g_H#S3+%t{Op^ zXl{EA*w0jZ{1N+jrR<5CnEdd!S3gmRcP$Imm310#G1$QJ0Hv)=O%+3NGqq=4fy%*o z+8HR)2VtL%iP+O2xuHgWx^;yYvSr!;vcNfbR6;zCV;6UiB#%%W4}o1xMTl=Y~o zdefYV?WL7(wVMb0FnKJgr6>t^q34^}i&KKD_4b@8!hY*Qz#>_(Mq)CEjl1_f_tAG` z!B72flP^ILW`({EIYhWaY7sM$#o)B8T3;s^2QK~t?WdK_RaN1lb%=4=plnNh3$Z~h zE?vfzdWXAH=dIOsawnZO82wEYP!pVxphE?~MeF;gkpOTo2*sDSbxgR|5uT|dZY=;@!T=0bgvWK++$ve_aheB zYiSWEtZQ6~Jp_VYV$*d&YsJRC+`I3Uq_KV8yW#64RBa|Qa?jbH{nPkTyftx=YRcr# zeRHMBVs@S(TteMNykv&6vVaFinhUydQK2rgb!M)sT}sD=EQDkoLCItSfA55&U_f$n7VDOWV5rRfOw!!ByVA z6WV(b-)UE>wG-alDqxZ|;P5en?|T!ZvPEb%4%sCe)%r8|T>kBCzyzF(YrHCYfVuaq zB&mU3v+hE?g=>X@JFXT9Le{KLVMO>(1YQqqHSU!>^-x69tP@&wf8F3|TFhz{Th(s= z&;q|g*|`(2!sHOjl6@=F@8}{_y#?HcFB=OdvcEH2Kz@D?q864Sp3b;*jDGcSsifc? zk*mo+MhE*!|4nUmWiWr#-a=#oI_Pa_Z-w%|MtYW#Q9+>i>v)Dml=a#Ukscuk8bO2Wt?ec8s6*t7;*Yld$w~$RKbS0@wyR~d z)g0f+VEM(N#$95T9e2QVcZzf(E>gKGCE376W>O}Kh2bG@mJNR{G!qEWFuI%K>d}Kr3J{R$hzR%jH5pZ`d zo~NZXSKsgN-`bO{8&69mL4=xhKNgsH;rUCr**vjzK z^p;u*k~_B`)skBwnQipMS%^^SAfkc-im!)q@E51j|E%m-+UcDatn9N^Ujyy8{}*ap z`H}yOcNpQu?mw3PoSBv(DnR3$`VsiI3!|@%&&yHvdyqEc@E&obbek+V5y0BK8fXlG zjwFk1ew0fTry;0sq)Z;cR^1)1ip5_-w&N*vnB}bf6-m4F!|+y)rbUX0$scz~Lb3c- z!EgTC+qicuLEhf((#Fbm^W^Mw0&{9N9S!*d2JXrygZHAM7u$RNR-C^%>K2vu^b(jO zG+HYpvyiSy5(|^3)-dOgE6Z1>E-DG%-@?wc`dKkih~CtazPg>|Ti;7ab=0-pD8tcr zWlnpVOtN7ISz_`p{nq2EYES!`(2=u&|CXWJ=@4O>Nx8clvSJ6h!rYaVSePi3k27Wt zr`C)3N1<22umoyl3df$@P$bLvHyPl$l6;;jn+UQASc_XT%UH3jsU3wFrscLGkK4O7 z(s4|^66Sfb&SnW2>*~mhHzzR>8!Y0dE0(=LuQXzIe0Ck&_hl^|-Z$02QH3aCRcC!d zb=~1}3NM)dA(~RMWEPy@k_k`6Wbrj2@!6|~nuexq3@1U%B$>Y-S_PX?c3h=&jgqnF zY>-M95Bo$W{5Z|2C+9pSint3P6{IRcS&jv^5=MlgdR85A&wZ1KTRTDW8>AhJ^R%cx z@gBmjLILjqn-TuMg96*$%eVj)l851O?twDx?=-&|aajeOrzN&O+m4Do`Ot&tGoM;x z6i>2}yt3*NmeU77^7q`#5QZcdK(1}p#-C4pEnSY|dBS;cL5d}o#{B4@W#3##w(143 zB7?UBfvfXjIv6#eZ+-8|V8a|>7n-XO+Hn~EdyL@E;d9uw_j!xGAAOLQ{WK8b+x<8WmA7g>q9~ag5#^+8MH> zZ>47;lzrwTEdz33A{FUIl>*|0UcLBnzaLk{tQ}*oms6zl)_Uco%*g$5v%~ZpL&p)%;lm#j0B*12LDze|g zQ>2u3ZOW#X`7@n{S}^Ean>O+7wudy9_9<5xT+$J0m`>3T&U63*C!g_VOt zx1-YZ+ppZ^I@NVa0#7vsOQyC?H={6f?8;&^)vt@ZQXmTOi!2eQ2gqrZ7R)<_{`8bs z_*4$LQZT_Zl3ImGQ&yz7cipbqWv11W?%4#(T5Zl?wkF?V zZ0(yHIPc(pVHV*z4y9-nW~3x0JzqeI#EU*&WoYlzw-&{{`oa6r$U~0PQ!GKdKh16x zp&`(@XVVyOIO_M+S%g8jfs^2imdBSG>#F$FT#D7jun*-P3ya~9gC8~h!m$-O&a!={ zc0~`S#<%KWzMS>P;U>cIqAjbqhJ48>I2*@>B^P0CLjqwCPKG3}vQ6Bj_mTxmL5pIK z^-zYvcvT@U!QOA~A*>f5#|Af}nNQipv23-%jGp!;RUrdR@7A$}AVQsos3J?HJS7^w z`BT%+(5i9Yr`47FMLnT~PYB~}0Uu4GZ(A=?)IrMn!rh(b@F>h2fgN_ZAFP@wpx(Q&v~GdAK3Mkl|ph8GE@1uP8g+p zW(RoJx!GawPSJ-;xZ|BFQ$dV_#3(zleTJ-A-i=D}AIm1mkDNc=9x^H(@lgJ}q zaxXd#uaRCf^SxA>SJRU{q3-c;>WBVdl&RgtF~zDO(lUH zrH0~}@_e|ur?kH(T9f~9V1+LzF8(@Hk=T{Pa}6%B4IZ`lU&j%Et2b!=|X5jDiCnoiW52bg0>el_+YZ;YJf2)Tr)yjzA9UES(n|waBtLq7)s6i_D zoXO!y_oshVH?V2_#4M2Q*L1&4gUWSm#6Y9O)!jw~e}>6#FE`2h?yC3TGN9V|C`|Wo zW)$H1Ggsp8}a?v(!TvwK=OxfOzsmn>6mM-90~t!W=Q$j%v+`d zZDCG^o7EeQ>@54zt)0R-RTqdAqEd zc1$?5Cbv*yTE<0r0fCfqvnrt|^<25#s&tDsr1uWp~pbL;y0$ z%GQ8f*TEuRj#I06+rBQ2n-LG7LH*wVoQ@~4KD2U578LuaiskkPNb=^7HnLfRP>^vi zT&=+1Vw_3=7KlLa_f{2#@FZ6&^#faa{WEXh%`cZG`l#lMfUqkTX7GU5dLB6Wd0we{ zM@TTiIH{C57SUY!l<9SuCB9uw+2?>wKD%D@eLXeX2(0`7Cho(5^Fy9H7BRNviI-#; zzU3(!#nD?vGuhf<71sYmL{41q8S{}Bz?DA->=&;=J zOWfQdnlLM_fO*tcc$hA~f~0L_#NJ&}OuXKn9>-{9*Q1d>Bt%I?4{!-Jn3g_cE zl54lI#vRQQy47WO5ZL$EL+(`}XV}+?Q7fISDoT-Bfx9XUtc)nvL4VkqR8=iCWDoF4 zbV8oza2&3<;;+7Cj~z1TDB7Qts?y<&lEmUVcM-(SA%4!+d@JHkH*i5$Gn_esb0?!>if4G8x4N&mPwz8>lGDFCEXaaVH+l+*>58-6a7@ZE zffezt#NzQZzH&m9$~>dMJKx7t|>FLHGamB5dAg1NdVjgeLosPpA6T2&L`= zS~E-W0mRh1w|qoe?9_o>R%1Uc^;ez!x&oD#p4|$eCoWMCK-~N{Y|udwA6+_=X~--Z zd(Npsy**oGIGD&-&2IyU#COP-jSyt#<%5uLgxNq%=y%Fx6Mn0~!;JU0YOBt!Za)hP zDQ!*!&{F9ZcLA@|ABl`d`;!?_9p@IAi+(2Er6(PjcFuY0${WyIXrp4Hb-t*x@xOwu zqMJA9on!N0fLPMXufMjTi6;r+%`J*s758%FV2CjqsCa$0x*~XWof8%Q)UKE8^t)&U z3jb`JL{*@uQi9n3%5N6^2uhKaNdPdS_o50l?ju%f_$>1|jRH)K+w&F+jjY?x{4CEV zm+|@kv2@PSk#yhJk8MoYv27<4+n(6=Ofs?2v8{=1dt%$^*fu79^L&5r-_@&DtyJNFxWy%oS1vN;_ks9Kwf+-LJpKH_Rz=q3U(|1Cwt8bjV80A^LZ)oK=rJc8_Pa*J_MgMfsE^EDF?L1{;HaI@r zAkn7?{t99`gtO@KNfrzjzDmVQf@c%#d+c`#)k{_o`|E;Qd>1#BCeU+g>$J$ImKX}o1uU{RH`9h?cFGqde1^p8{Z_r{| z%xA0QWh7V!$$13E>a`sHVGj&Rg#y?I*o8JXSmF#)#Wl7!NZG32C0h}vVT{-iVG2}p zq&!CViKE?_=$Jb*C*tHai`Hhh2K>v!x=ajU~=h>~_& zaq15+!&fQ71DV?T?W$-dLw_N}BerEA(r=n8R@El9wP^&Pr?!-{?tbupqFatbH8)dK zJ;bM1qNTnzma`_zEtJRZn>{t9Cy?1ohR_BZV$7{u$v8G0IP)hc5TiHrFEagJ_lY8g zSz6($adH@B?Wye4U{?DnMFi|0aII{oe0r+bWtm&89xL^>=;KD+2x!7*2uK25AjDRs z4r{n3gR6yEb=PwN++e$gUFA_FlHKm`Fe+xXDATn5_w@sxo<7^udlRcA$c&vp4oiVx zR!%?lz7TB$@A;Q9$)6lOfAMKWv>l{srZ9qb5eb=w^jhD$5LgoY)%`^%7A#g6;n_66 zi|t_bw&?4?PO)`5@uH&z-$kI)#PcX+bYgQjlGHEg|C+tuk4EagNb`AN<9~RJl=v!? zXLP^c*xna!yvI<+nzavIIqD+C=bbv5v|k*@O)9&_@vXvKpxL7p6EG%wKF3E5D`@$z zGAyE~)WFZ5(Rt58&q(s#24)x9vz5iHzat&%J?b4|^~EdbN$lHg6Bto|mWr%6j8;je z^}Bc!T<7TDqOB<64aPQ?)uHhwIzr2qr5nLj&>0C{SJB-rN9}?&W3*PamOZp@4DQsi zPGD!1Yl=>n#QPW~Jv_fz6A8>b2I~)xX{L%kwhD%%;@K(fn}c*15tcJ)Yt()a=h`kx z7vLIfR(wGPb8d|}8>Np?1WIw1z2w zg9CTwdJn3P;KgoYg;61ho45a=6H!|~{|^I0n1z|SEM~ljeK^5$%xoRaaRDsRhV6ay z=C#kCjJ2xy{_V0VtJ=Oka~HVZZCWa@al$%)SXHZjvPn7v@+rLhf;@QnA5SLV)}6Q; znR^ymMnIZ-2@$6=5-1c|SQW zZ@+S1+pqCOZEL9*UNO)1MR=YgTZ8}r3GplF6)s?HiF?z`p2tA?u-sK=DG%wri|bd= zuc+m9n!eP% z@M#fyztTuhnW!OU1~Y}DM*n*+<-|?IEKQ=EKJ8V?3WjQD^DT3;zohLQbfCR&(7CP@ zc1Y5eYE~n7`Mu|4zl=**#wj53Yz$gr{#_Q5J@99!4( zvLHAi7{x%K(N0>-S9#SUw(PXpN!N2&$V#tfO4T|Ou;jL9pmB6?_hFFIN4$ZFsu2KW z{FF2&s8Rj38@!9aDG+^LD_r`+RC<<4!w$mwt4E-L4JX~dV7s*4e)jw++(E3->|7IL z-P4nsxvNF5_v{m9V%3~f>h0BoUSQpIqf}|vKdS2y&(;8cs)>z%7FMpPW>4RHuN5ro zhJ&fIXlLhA@qJCp>5S~GrO&ZTWzp`R)Fi!t^Ze7I9hZLmso*Rs0ic^>L|zf`H+ze| z%&6c5Hq-H74F(b=&V*8yKNOmAl=8!^Fu~G(@rjmVeMS^z<(r+wVV$w4^Eu| zKOtb4n?8Eawq(Aibghtj%AqiL!>EW{&{?$t`D;&!vAYJ6xYj<*_t*dJwvT@$wI+zz z{^wRqc(dkBF)`(da?<20w{xa=!Q8LErKvE>UR{?kri?jcN2Kycu4dK*P7-{jg45Uy zqQBLEn#xYdP_XojC}d#|X^Jyjs6nrnq7eis?C6bK072E7p zy41G5kW*6q`8R2gi358cvHa2B>mHH$2VRH4-WRU6Skbg{RJIG-2@US;@p}tZWz7s~ zon|Gz=b%~So9!ZYcRtH;{P%c?VKO@E_R;DJlY!S7&O*PX6b0Wr?kF%|N13^3;oSGR zx^S>R<(6s(S)OGXRBh0>(A*>jnq1+8b>fn?>Vbsw6%+M!u4*(-cZT{?g(uZFov85Al>p7OUOo9f83!>BIOSE6K zUDdXs%+}}`vfNxs!P4}TGpkQ?8g3%VP0dzLZuYg;a>~_+AJ41eRQIbPb*$)Fsc)x9 zbiwnS#ovuVut8X=SSl5bXD3o`f}!3M@BULO47Zm=0 zoo1nGrlNKZfI=8cYD^2+?~$SVDtCo=^^L47)rQdf={37)!_;*{7|)020}dBi60Y7d<@J_;DJ7H;nASC{>?s~6UGpG_ zq!rEQj9<643k=FNp`~I1AZ_~ygIdpsGFN%Mk&^8UdV-lj|60Rx1x{^7kW3O_+QGKr zrU<88VMFEjvQIRV@Y8U$WGYEXoun4Ho4PHFJvj&d|1_d9$r{v7WHo+u%ze|!*+nq& zMf^%N`vKE(@Da1l&42OC0`v_|j^==3Whn@X#}GqgmA0IMvkVHd>@m{tV@-WRC>%p= zU)vhvAn0@ZQT^wt?H!a(GiBMrUdq@Gx1E9GT}jxUS9M*}A3>EKh9LRIqfFo-cQU|f zEMJe7vH#%Q+>**4U7MH=^L7qCHdb86$54yvJWlm_tn7m2Ap#wj)fMt2`wXv%y#3qM<@{b8F^YsNxUiMrfn6Nf`x z^N+=vc`lC{A|>JzcNwN% zqUjy^ilut_A^iIa3BeVORN;e77KHeLUw15}mw4-_(J|0#9od{?^2Ul3qqaR}2 z<#x_gY$8x-t32Qv@ZP`DNTmX^2v(2hz_RTiE4c{7i8ReX7H8@NDeCH=ZyPt~TriWq zdd0ToxG9D@DPXNR%B)Y76bC0wFlx7O+{&sZt4mM{hwlRo{m%2Jz0VR_N$VUkx8dg({ zbf{ud3d^58Yk#`lKPt%k%b)xl)o3hJ8s<<)CL)rIDY(Qn#k z`2k{BpFioYRd{WXxal;i+4z?nRn3E zc)-^*NQ03s*@%r%{&~3~vAm%X7;vkpPgcB9XV0=*f~kzj-r|uO$nQ2AEh4x)HQ*81 z*Z&8c2{P3M2}eJ8De(lBZJI zqN4A^8%pQ|!&HpxPX21o@$L9hEc|qij|}`^BB!uOL^{}5s#G}eYUxE*A^M6E*0Tw$ zG+iiy`oWs8*<34i+$tkHLsrXI!Fdqp2E{_;_|QV~S}BPv^+GQJL%J9ZwKXy}@bd&v zw!KzsP+i98wY9C2$+i{XH8}><(tW+%Yc!7S!8Uw;^I|{Zr^&^Wihde}xeh{dc}IY_3OpTGwtg4Wl$56+A%_;` z$YsS#a8|a0yjWrs4-*vc@cMBsl`Jzk>sW!F^Zg&M4s@>Dm!{HW?3=F%UZzMBP5zBs zf+a2njM-ql8)xKBpRX9@q>$WAz9#+`WHFikA?TQ54!PpAt1(ls`29n?qbAW60{*h+4Je@n9rMYn5Cv%-I!A6?f=nRgD*ey-8x>=ZPM=Ur=6YR@wF9}2?}h|WJIl!bxK4;R&&0$(jms z7K^eNXN|gWSz(qULW#Kk_xUKk>kM68ueOrdC-)LrcAw5C9-%xL!mMZ^!)mq>Q;N-4 z_R1sYSzN%cBp)ekz0y`uCt^cwY*b`k(@g>r4DUma*Dv5v@1$?ztK7BN!>v1e=shzP z<10Rb@5L)&C+TmbQlefF$zH4H&w;sKGH|0Zn8C4U(jU4Gbt}XlzTy8}W$>#MW?wtv z$)p_HNUAAMZPrS7fi%NjiBs{$%+#ux4Bvm4-G;m2>*7}`PQJaBXv5mdG{@ljP4C2& ztul~O31zbaF!lZ!$8J>9q75Wg38^JIUzNo)mUc;?BXCw>7w zXFmnvssW+{o<^ZLlA^)JXxnnQ)@jagb%DeseA!Hn7vc39IeVUBiDkXmnA73N;Xh|djKz6zh8DdB+i+R!(I&O_&h=)-of)gjO<(@PTph7f z?7jTg;=lc`%1M0~Ea{hGhFc|m;aEG_X!4cPNp^E%aZgptpdnnNHBXC+B9Z72mc8Fg z3#fRalPyc}F#eLaS_-n+@@Z{J&HXabvkre7MH+i*76?o{Msw~% z*E~(z3%M!CJ(K9VNTHJ=6pkA9`K*VJ8t%if;On!Rsri4Bff21*GW0B_3nk2NKCX=X z5x};o5l6K$prt#3-HCrJsG@$+P>7h|So3J`J5*r0IA(qC)%SQo^z**!LD@vD~N2Vuq_(WJHW_3`}Yc7vM@uJ%L;T(q^HGcf5jj z2E|5WlO&m$7peHy-Az17JTG%x{>Jc!$T8R3N``<)_{WgDA`~J2BZ=J##dhd^4q;7m zZ#RE5solL*# zIUzR~Cwww1RR|#$61}kgBo>o`ne*j5(eBl!zT9BJ9@cNWU06VyH-D1 zs6A^@#(>;IZ_O~ylyu8htJV1w3y+TQQ2L^08p-yNZ4(Xt%p@!bR={XX9 z`4mVIfh`i)V2DwbZpUUdum}_JkRL(6Mo3@)Ty{gidIyPT% zG#EcR8i1xm4Y^lI#D+fLoc62h%ZL15*B7J`W2+va5>wd!Nh02y`=3-AYVa@#`$gKm z`_#eQbiB`zeBc4GTf__`v7s71=Qu(p?b{yQnCblUe!nZ&^6a&5w_jLg4Ax}Jz9L=G zPVr&4{R?P>?9&P9obtV(7+|}b)BMN9xFY;8ZABklwHH@Di+RYluA^l6O-6`GbQ5bH zCP`>OfHRd#JhxF!&FadPBJoK@TwuJQtk1;l_o;q(j5ck~qtYCSdWA<;DcAQgaF!f2 zR4JTtwnT*9j#vd0g!;swI;~dUfd$eW$0SHkL7pL07qI=Hm5nb`nItc+SIC*vf68~J zP`kIiTh_lUEA+ReU@0U{W&!7aq|tMZWC9gHy?xmhC@3_nw-Qfd9vwm*Qm)ndr4&FX zrxd=(pMjQFIWz}zU0%rA@fD%3ASvn?sAC6}NH^UCl`zEYMMu|GX?`xPr%)`NTJaZi z4FCtldkde{zxREo<6~8Nnew2}Kx_rFJ4Id$$5FK`wYjnnUXhb;A#S~#S^y5ds(&Vi zxWcV2@lJfI52r2^e$%n!&Z$UV>`}M%-sT4P1!Tw`*GS`W1nH~EeL70sWGFYVf%vB9f))$}i_Z@Kz)yk1dHRRbr_uX!)MK{lI&v5v0@D!xD zPLtv$C(43DyLrpuqlQU4E!#(8-I5~b(0h7@RBT@gWxPNHRA`*j& zlV;o8L^8C%u)8An%{i9#TfC4@w*@+M#g|JOWPqQK%w~>8aNtW9TX@jT6kDz-_AtKd zzuD}OhMg_8qSjnQ&SpDJ=85_J=jVtKX@cGW^8RIl8`-9NqD_C{NNQ5(yYX5*<$=y^ zL#oZI@1>b8z4x8Di2L|SV7e#ugwRVgt zD7+wPA1gSHIka8&xjMvw=V=MC8=Te!;|nSO9-Ro7WeRe*&<<6yT%L=ehCZl>lQtvP zNv?nG3aWw>m^(fq?}7Q;PWn|MNuhWTzaY|dt|V_~Se|Vxaj_PLT>r>;uGuwk1g^UH&sy5RLt^#!bc0rJ_l zJ&EH##XVGp-IZFwHTfl#(2$tf>M%ci=lVZq6p8_8^7M=5s`yU(jILmL1nrd~d>at# zR2Ocsr8EhvQDyV?x++%-+^S{-&9kGAV&?ZQs-4Mk5~_-1WX#-H^c3;wi-54iiEMjD zAjQ}LjZ|~uwW1B)^?L3decsi2ocqb^{KB5*ZwrlGIdXIsC znOL(v!rKDbe7TDY&v2XfQ8Kly(|>C0?@zOsnm>q*nN#z}BxmRzxA%42MR$#BI@E?k zri(rI8QBjjuZh_Y;&&1iV$YOh_g5z|L~A=cFZ?&(d2swvgIXMt+*k}evyepU`ljx8 zjfXeTs(0BH(Hg^s0JD3h%=y>2VZwpd{_aB21V;Zbj`~qBJ?diLy+h5qyURB#u8K`h z<1(%)7KTsCqActG{QiL5Nl|27oIOz#MBeivqkyZvHqwz zKrXt$a!4e|TL@%3^(TC7|NmD)bV~G6Rd1^&n<-aq6vglf+t zJOOrI-DkS0yntY3odiCVRX-FTU7d(3BRL!$o@fV3n_EQqXfNgh48*)~5MaP#w{kfn z#SLGSlL}%?6yneMg0GBkFQI$MiBWb!w|}MsTz6A8XEeHGNr8(#2sptbKg@Kf8G8;MjHB-msuaACAx}AH7uZPKLM`+Wk)B?@}&BI5pDhSb=#FeqhOj%Z^s1 zLFfD$zwuOj0IX`f$#cB3IJDl5rDx9tO%w-0oY%BPjOVlzZE3mcV1_v`S%gg^4~9(z z5{1pzZ+MZz0h-bs9GVcHnr145)gJg!#pW^W*&NuUBte+Wz+JF6!qxO73`O})Lz1vq zWym_5m|G|vUyt{wJqfOea?nlW&f8Ey;34vmIbPt${>u+EA}jLJz~kgxQYq+beDRFH zb5UQcrB+Yoaz>4suWqD(;gBnCgETvG8V%~p`hNir|6#dn(OQeF7f;+(3_|eI0QHaC zBj1qEdavrVY=s>6nBrY6rOKC=EDP5 zIUuG1b8MF)RC8f-&IkrB{kkJw1={!T;ZOp3pHQe53k?y6HLtK-ySv)!yBWX6ysd>} zaFG;wb}mUlrl@Mou+&uhczNo~mR@jyykk6K10R3&=IzcyZb&nUfp?M%QgN)W`MvAo zt3>?rQx`0SlUl1pfe#uQHOAZ_*8V)12jZ1TAe8$AXA`c7Sgl@V0(R>_A?7DKXx}aNZd3mSxvqb4-%G7Af zboFp|vQU(TamAF$$%p3s`QT?0>qzIIlod=~yC7%G^AC#TLOgC0ps@Q?4_+q9YE-84 zg8`Q=|NqQ{1W}ouZG5uq4ny|~rf4<7L+Ub{QoV!UGClvbC0W-my!y$bn94! zGc||jR#M<72{SNr;M6O3C)5r2t9<&N`ZtHc@Go6DrNJpI^lyjy443}H0`#yqk)mkcRISjlc#ccm#R?idO)zqsbE8-t*z%1xtFY$hUBcoX>?<~>hlgU&2i z14}~co8E&Z1f*5>jaJVZC$28OuXFsn0%#wnQT$co4sdZTdJj4(R<{cKUSOy~Y^4`mwtQY72YVh;^ce1BZodF8HHYOuAZawA{sf`&3i?E`>2cyWNjX-V(T| zp_rkXRECtBG5T3N-!v`Yv1NO^zq$GKKE_A=yOvx1_{edehPe|{5u?%R>cYa_uTI4y z^u41n)Kgg7&o=rIhS%rVf7*nW|5E!efG~2Xb7ytcqmQ4@BcrgSS~5h?JHM6|En0)Vb+>JdwfA? zg`m@^|Bs9K?-kN^awmUZy^{DsLylOUCYH!bNLcZE=PU!#ZwdGPwa0>nRC7vI&xP0` z8Ael5QJK#0I~*NJHoN*R-wtyR6mRtmIys`5y3kBafdZf%;JKXFLY{$waUnB+Mwr%Y ziO6*!y zmwgOXp+30R?b$BUcKLcjzc^hZAX6g4S?FK$uj^ln=LP_82949-;_gA8DY12gq&%z5 zo6`I*tdhvr2#2{r&bWz#v#O=Y@s4%~0`zCPvM>AXMv$A|s&k~BYYFdp$_(dID)}nV z@m0l{JiZx1{wb9RXLo6G-=Fp?bH{S-%ao*2O-{#$=UPlavy8)ee`|gq*=9`537SSh zXGcBoxjDpeQI;pQXu(;B9IhfD3;A=#*}i9zI+Bn2#uQZ~?7z>%%0m3FP8n#r>#*)1 z!|@~bMO(h1b?h=;k@O==sIMR~@ng)hY&iemCe8xu?0?<_zpS_nRHalcl9_~%8&j^&b}B6q5wsm-zHg}q(lR(joS z#H?}*^h!ooe#W_!tv4v0@U^jev@(Q47%NSu!WS0aR78g`}v|w8qFS& zfHNo*bx{p?3C22!@rZ89HQlLSx^ZVm%{*qIeY_r!aYMzye=*cUUTo-Hns@W^SjSk3 z*Jwd&#fSoE+)-u7e*(c;yf$8~b>aS3y^-MX%lxJJe`!D9U(SO9r~a(@?F9j?9&t6A z>mxVo2-;+F%yqOj0P}lc#hqNtha!y&uVA6v*kAMKg_Ll`LJ~x}i$DCW#XmZEwvGX% z!pvE2Bw6G093j=1<+W6@L2d`%@HQ_u7pWaWuL(0?;+bbC4DYz?^E+NPn=N*}H~9+1 zf>d2Rotf=--w$^Pn97&pT-{#0tCqH(rk~S~vDU2*yd|~Ap22#v6Lhx_9>8{rG|ZZl z@4!QCfH1PN#3D4d7S>-uMy$n}QLGiV?x8z)P1JA5L^ntoZgT#-HOR z!;Du>qQJ3|!NGz`bo3NfAxM>5tzj=9(N^^clT!kaG!mFLjSnyCQbmCd6T6MEgCS#Rc-*XajiJ=!T5pXKjEdE!a*qjCh8SM^ zYE@EIZc>;o{(pQ1@aYxTfVoSiiNt8cgL8)-em~ zded}en^uo-cXD36jLpK$!V`foIYSjkE`=eY*C6W?(~f_IhWk0jn(8H5Snvel(zrFt ziX5l8qqwJ2qh5#4%6nRyS!04}V5$2bzGjeCk5f~2=yju5K*{f2U(w@Xe3j%P4*?OR zMZr#O!SKp=BSvb5%FYCI>f4@o6^Bz1Gy4q~4LXy#hsv4n&V?*O`{pE<+y;u={*BxO z>D|c`FPqPNGQp(#jMs6`+HBc&RuvTu!XVg*Pm(@g{1&qN$j{n?J$M^W3iCasVB71jaRm?5 zC=nPTTZv-r%S(v`ZX{xi_2_(3LA;oXSsq1;Iiy=*ckSvXI1an7d@LUY05+G(7L z*<+x_BRAoo4q7#`=5w&Kj!^GqC%4%o+r&v7&eu( zXUU%@Cn7uXL=u`XmzK1a7-GaV;k+!|S-rYIR2l}^jX{(L=K4U7LAY$RDRLjY#YOU+ z7m+}2gbGQ-gHOX4Hw$hgK?b8>Im{Ce?)Cl3wgW#eZGJ!x|5po{K&E4VZdrHF`<>f` zG%r3dZvEg_`yVW`JcM}Y{%&J~z*b#H&Dl8pP#Ge=GhlA4SAn^{TQ=SUb z7O1)5gN$V<;}ex$$`u({>0I$swQjb$H=4+$lt3$=8GF1)RhAr8Csj1~dvn9J*QloV z1At0Pb5g<)_G2|+QTezU77QbL%dSiy3y-0*lwML{ntNsWeHs+%!=#oZYI(@ z49gtYWKQ_~Jg$$;o)3~u|J>en?YsgEITo1-%<+PLQTUl=n7o(G;91(s;ZMPwFLyqG zwr^a_Lu{XeWyBva8>%QlMiNp2$+4VcF@OtCAG-kCH?44P!EPkg@C)CHYa4#j#?-J3 z+U%?J=i(Oez3jY;36_>USPvZ0At_l-o4+lgT2=kj)Ws4^&5UN%iXK z*P(|zbhZbR-^VpKN@`ThM6Xls{7b6Y|7Ve!Hw(M#yJP({HF%Ydfo6t=iF(wcF>oIc zPha?QCtd};Lpr^IHg#ws{yuVl(I_$y{$hW;H~F;>6S-boFKh{F4RMUXvbKM=H2*wv zKIgjq*C7;Q@J$)kR#$ZkbH6uWI8xs|fni;kNFbC{$#zKgg$=Zk==|t)`Lw##!z55B zS)w}^Z~T`>U+h~X9S(umUw(Mtq4E1lw6i=QIGxm_e|KHA zT2ryXPG8C-RYrOeWKN2K{Tj2Fe7!M9gsG?T%PSWOe)f3fBD#-6vqKIdkQfGg^QPlw-|TLjvrjr+oxv^b^5(LPh$8~kw1SH zxHiDq_jRR!RDKClZY8vNv>)d4?i=i;ya>a}w$)CU%l%Y0M&{7Y#MR2rxR<7e&USG| zIjm2N-f^{~yZ&WM>!qI1gW%SiZW9!@)J9mg2yK}|$VLrPCt<>->5W98D)YCW9b@Gk zU|DtFWY#J3UXY+hEAvzjJ0P__?S~fM@aI+0s7RA1E4RQXu%`_=*{eLrh(Jo2=v!ht zj<58UNJ>hlf90aD?U=V2S0*hE_V5$0p1#SVoVU)I1I5oA8olA}Ls zrtR=Tx-ac6z;D}J?VYI8r{eOAAvmiw&pt@f#ty)+51w!68$yX>UXXNA@SY@WN$r(y zOj=i8kFug4VTv;%Er{Ydlt|E^1TqDJ^N|wui&{6avm;HwQ^tN~BO-!BQEoE(i9|V01Z0mk{uO@JbcCr&}&fgc=>2s|60l6sb>^G7EK@q z{+=y^2Ft3+p%x|sJATVj*HZyNT#MoU)sTXvEiZtP+4XoS+m@*UqkuX41zY>4)JB6! zl?8hQZKG~yGab>}b+CnV8KKk(8Rt`+RO(dM)A=8I{I7TVVsI6t91`$S=h@ue`hOj! z+Ta5eh@pLO1cTD-8)yAclo|zW;LDAyMUwN6?MxkQ47XuwhNas5-A}VP80K_0@`f}{ z%^jO@$UdMArI(at^!Szq$*}}Fj&mLLwYV^2sf~va^b*thzfDJ3x8XtuAS?n$Xss;` zf_oJEbyHSB(K#{qbN>C+U(s4~I%pV)ExKxIu-03+F3029NnFg!IBOk>f~5phsx`E6 z(%Cc`sn>nPXYB7MNH$)jiB>r zhjhUefx*4qw<>m8JgxpLXJLkG=BWN3yPKae&J!p-{(JTS$LCD(5K~140L8OrQ^YDh z(VibmA$~<|6SSqP=MB-IPLz;>t&&|P$>%DMnL!2nBLq7vtaGqsG_B>v zL|M)i^o`4rXRLBsKQtCza|VYB1hw&3-;nT3Tjm&1?rl{L-Sbn$4OH{TsHfbvAYb)i z@O60q4CIV2Fr=E#V$C8TlBt(8W4pfd#}NzNQM!VlLdtVE{oqHhX<2o;C4TI|@BNng zpVhVk@u@))7}F32hVFc!ha%ksWOYsXa!t&kY4`93UY(Pc%IK;%2nx!LY>v1& zn7L~|22RVW1olz{&8uV#**gxQIt@no?ji%EIlFbVy-4Ox-KICWh8lI6P8o5ImR8G$ zOu_g;=qWEN0@giFjNM|YO>>N4g16lcy#Q(;1$YYi*Ju=*X%CR1mu$n2i@!CnSfX7k zdCi5xm3}iPTZg3XnQ>eaIJ7b;e!{mLQsdx~1O=ANH9o(%FWDJtJ9~vX(ojSw=ngHiDh=_oD-@Tnjf2wqq-Ya!>~7^LDyS#+$wLdxlS^%t+^0rVvP<+ zyREtv=!nzbD#lYzdg0=C)RKG|$gjb;3`j&%*qWIz=W@tZU~~cHA43IfOR|4<qR?~1go(S zaY1uV8AmJGAY2Hm*p{TJH2%BF|C%ALlII;s4Y}^7)3A|jR%qDo3JtuKBwQOA2kk5W zS)iUfm%$pqAj3DB)Gh z<|+)Y9Ou>cJcp_6tD5%WCTPs>IGbvYxb7Ny0p{L)BOc-=6V$Ko=e{{@?dG@f5O#pt zm9Q;NK*Rgghp9CJySCb|sD|b;NolPj`;4M}l*7-iHm` z&kiC<{X@eNRO^PU%90JqD$iwbKdzaTIb2i5dZS7dFD{rP(rK7Sr?c4LEYB%^2hvgN zJh%SUDTer5Z8gZxQSitn;h_vK-jTnk2QhbDZ9}Qp+kv2V%`{}|9_HUt3He8V)~3~; zqmsS~p#Vb#JZToiwQ>=~dI-kS8??J6qh?jIz%O@y&p5i!!q8NxxLfQfQ#_!&HHSs# zJ?iM0&Y4E3{HvF;sqNz6zIHkk*v_jV1HRuCiBF=)eu2FEM10$%_a$4$LA}tWDv1 zx}Aaf%Q}?xop+AFkA4bFlqF1|@!KPJnIc2}hawjEjdN$BFgfyMn`l`|V5pdyn!vM7 zslWU8l42Y6LlSXG;{Yp7-AG?P_^>L^5<1{u-k!8hB^#};Q{Sc}*T0zVW;uUSHp33d z_C%T!l2ig-^D^@;N;bZS!UO8rxZx_t@L1x~`u-Jj7@cZf0^W<+A#t{s3>s)fOr>aO z#jr5&B~>j3l=Xq=TOvID=QEYlJ+hitfOzcMQOm&mctD`y@ZSAdChuCOHv^_%iLsOl z{?;=uuq9UISOq{DA3MH>6r7uS?8Btb5v0@0G@{v%|23vUX4^{QpSMZ(O}N_}gwgGQ zhwxOMD~qdGHb2P?#b202BW(gETyejw@U_)#Hf zE)gF;d9FO{#Ux-^Q#e_L`9yk|^^WP6aUzd2gfX3CnZRY`{%sbZj7UNs(4lpFd42N&~IDw%(|m_A$hbFIy&bp=5{yX}v?> z3V1ZG!?;UpW9Hdt8&m70q!_KcorV)q8gEyy*hb@1D!(8S#A_58HE>q8_=YG8KdrKVEF zpu$I+x3|s)Q%<|zx6!5R8=Mh}$}DdTseI;%`kE)y@dLnsZ(c;HOvuLvGMqPN%Ya2I%@TDQP_w6va>m= zBQvi{0E1wwkkn|x@eHy^N>DktWCT&cd7i1_J`wjlOM+||8FQzd(c+(h;6mbQy8N8X zP=zecfR-ROOhG2?&UIfsn9d20r}xP{PqKwDr67SPZ=pvA<=n2Q{X}<-2?lYdg$hSJD_i4k1R!`AwufM1uF5^VKfGVu${_e&p)0z2*ZXa(Z`2TRGri=mmjRCILy-AmM)DUI zC59i|;LQcKhn*$i%zf*M_YMJ>GtN*&6gZNv)-6rot?c;N92t7dIp3}{U6dc+1*J!| z6-1HH^8dc46z_iUfUz=vckV#d$Q;T@VlD9&@Mvl8@IBaEW=)M1RL$LIR zM4Fub5;56NEb<6mt_gwSwL}F5ncoafi{srLp7d&TTEs${o_ib$^&eT*B zFmflh)}OSR)gt~uXFBg`UPP~8Z@f%rsiQWs66Ts_;&ZmAUq*l=x*u0{{(c2Mr7?A!2 zkrC+aDCKo`^%!87Uv#9k?j#Dpe-|SoMu$06#m|qh;90;@=G}BvF#C4Yq|)7jdwt5r zYuFg5(p@YL3rywzVe8JCQ=Q%OgK=|fi?$Dxy2s;0*dcmEn0EQ>J@tNI>yEgwRkOLp z1QdEI&KUo6#o47Q_fv-YfW&4lfxE!ryX3b1;9)dwxoZ4@70{!0L_?PUtoN!GFaeIC zSh4duwIcrHPoi~v)sBb#>?6_)cg>UO_Q185MpsBmUyzw#nt()Uy!`;zFixzwq1{At zMabjKNpzWJLE&Mb+iIx7aa#h1GcWmymea}vu?+t-cZ?GfNOfzBu3Bi zYD94PKsbi*%Ev`_AcHy#`*q#DSd6cP%XF;DMxU+Wr?eN@{&~Ii>FI4C-r3~4Gcadz zD>3wCcE7TKXm3!374(ZZ?lsa_)scuqWY{()=apaJG~xA3E)f)mLO{ zgkeWb>=H^GExWFGO={5BNI^}zD1-6@EP9Bk|! z+m-&<`c~@*jg1`%vky-y<)4y_srcg(7-O z%OY%~sUx9epBBJEA7Q#eo_XY5(N}O6(qc1K$4RiTKLS1{FwS}2PFw?A!Pg!H_f6XL z0Je&G(hFju-S6}}$6pclmlQj*2Q7(CT^HgK`x(K8M2dZ;{;u%ExY26;Wr3yNp20PL zNIo;}){lJ)>Kt34uyLlI6@ys)kv8}3XWmQA?Z0mQ(o(ZOH+uqTCAu?n-8M^hkD1}} zTSr6-ZZCW-xjO6S7_iqo-t$__y{j391-@`6oq0nQ^R__UIanQbB6zYClRCS?_sLl~ z72e_Zvd?w2cJwu-!x@oT68CYf2pUUgXV!KynxuT4a1UAM852>tcKM zkIWRx%q|GX= zW=+1q%y0A#JZjfPhT#B4LOwnd>6FoLPH`W!vKkEY`C9(7x(&P^4jZ(NTGL)pa0!h z_H0$I=ZV|$K_Y5cp)r|*q}2m7B>juv*1al*rN z%I~tqumTQ2wwbIA8n$aY9G6mee=5SR)k$TXcN78R2HB}4vu%HDlzP5JIP2*gSMcU} z>A{?5xSjw(TeQ@sV7#*@gJy~iy7`;)40IPfMg_K z`hiDb+^w(_hsE8cI9uFZiWhfxmlhUxXORLe4#gdcLvi;4ixw#EdiVFg_rCZ2u=|`d z$;nJ6$z&#(WRUraQST&l#Y_Z|(

3T7of{kn)Izo&oB&hcu5()G>Z%X`{Szwzn3G zOXs#bLL&KkrS)G%RS(FEg`9QJIzXG%f{Z`7=5f7N>_ifR;~8p$gE|85Ltm~!eD7RC zayQ9YJM^EQ7oJLo2mh&^cz81&Q1;Y!Zrs6CL*a_9koupYv1C2dvy1TxmHf9?Sac_wCJZZQOAk+XD>JA6o?OiBF}S(7fn31b~R+e^V zk}kd&hFma!05=ctgAk7~P+a`~q5JRK|BFuD-Ni!7$`fb^!znEbLvQ8l2{ZoFs`2QXSfPDW`5sd%fAAo%Sr=Hq=d_eC1*aTyP zwjU2r;QwOy|JUmS4ETTRC2QyCY2^;&ly!trCT(TmVhQ7?vX!%qr!7!`i&x;oe;oNg z?cfVP-es6rt>B*TW7<=Mb#FfOQ@|nbc3blYdS4`a?CE;*+=Q$s)gwD(f0EfXx@;kg`M>IrzcxVe3}dHvhJbK~}O|9CN0x+L*( z{&;2@Qv0@j`S|0l<51$>_2KYs|MAxM<>t)ft@O;4GZWX8GST6g=-*Z8@$vB3OMfP3 zfl2q<#<6M8+h)z<<=xxgn>YWL!I%D*%-Xl3%iG)A$Jmgkv8Br3m+exj?x)Syo41;f zprAvlkgKO>&!>WrhsThf;J2RcS6DErkh{yN;)}ih%*3U{p`suFej;ZJZp-n(5(qk* z*j{CXC0 z|Mc7<@wT1Gd0`sv0J<*@eY=*pR9or*BE`R5^S&V@NxW?PP#o5V+?2jPe2}0o+k89k ze^6_5d7Yzrd)1S;dlP>J;=Nsi3qo$LTwc$g3dB9VyMU7+s`h6M$8!g`EmL;{9VT=Q zJuj~vcvD2@Z>18i7q}sh4~%oPkuSp%&(8%%|FMOi&)balkk^Us%qz}LM!q+htgu^ z*Wu|l)Ajdon^aWYf!%bI*griN7;a+Ug5fWBcED?E2erU6(8JD4Kj9N*wzv@dz=M7y zl|QRWdy#(6)5289<3w!;=$GAfh$;r>c0hj9U+<8ob3d-*lHaXVB#uuGA&=XMuwN-v z@LR)#YK-F-9vZnXk9v1tu9sJdvC~%?-OH%6W5KF>-zQgz-1qm-*ZnRb_xwYc2Dib) z84@q2dLeILT(1t^E^|%ydR|Gip_{LdxIIrhF2QSW7jG{M61#8au`jr9ryV^HxFL+X zv8^F@W0@VnFAgtrdo=#9`)|)5-p1Z8T)N39r7|1}E-tRXoSAFK@tXzCiA%?&PvEfw zFpPzPt;XU6geFlKiA!%R*w3&o{dip9TpRL|CmwRQ1Z&V131gGDZN}(-|N7Tn#tz;S zJxUlkn~HaKDcmk`B2>190SU$a0MNv{yPBt<3v0(NrY;5IJzc@OA&vz%^x}zcuPwEk z=nfX=#|0)FwGuA|_uWCQMgVkYNu!Xh)KC*~R;)n(j?O=vMITM{&ua?kaDqCO%*2BN zcQ!W&>p2R}3QS#0#e?r*5_f0J#q@3N?fhRO9$sx>@BdG}mCW?bk5A9yGQ7*Q(FtyW&-V=Qe1Cdq!LO!N13($yfMlA$ z286(g##C2|q4vw9FV`Wyvn93gd39R1(>;%w+t+9L_n|dGyu{0X9fep0X-9`wgo!U2 ziosipwITQlng)fG)%4;L$;+Mja2Fwu5gewLxsxv42e?UAFVG$j`TNSVp10Z8!Iyu; zblu7Ce!zX@T>i#%Pj}pLPRn#JTav3K3VivSO6>L&D{opUKlVG~(B>(%<2g)x4P5fv z9X6*XzbTc1{dd=aq+czxKlkPI=9Q!^C^@C7?&kF&vZTB3=lH;|&T~iiO0pP0C!#2? z7lWXjl`gYZosIS2#(59$wCl6C*+0M7>Z{|}j&{KPpoB%+svpzqXw|3;YD5d?2= zp-xg?HUhoa;m|4Eyybj{7{@IHI=`o_F;`&~FE9PpF2SX`1pHb2 zCBK&rFJ#HsVB<7F91&e8_rbG}J79A07ur%7WtaxJoU+i{PyW>Rp^$hyuY*BOLqt5e zeXcd`8he@;X#s6{ULbtlu>2?a%e&))CrUs!tDB?a{DkF;>>1)K4D>53RoHX+wf2vfIOyrk%k!ph$O{xLX#_3H_>-4!LaIrU zg83+g4)W6smPtdIZb=hQsrsoVhWUGc9*6Sr5bTRFaAO!2Cw&Zq`Re_TeH$S8~7fi-5JTj}D)!8c_b12Ay@ULun zYHl78#Sjk3N(iAj@KzS&Vk~?^P7WK;xy6w-*pLBpE+w;Lr|LS{srw5u2^6#Y&_vaU z^PnV291n}yfjJ4522N1toasUJ8VB)x@|1L|)m9*k_**%+be1$IsU&m^^6DIe#ndY|Z+fZalaWAdWMNSRE`sBKQfP7YI`D@a@|$5Dl?t?e%>kA`YvCsvf5 z+CXj96n70)6jI~gcMG|vwxvY;Wsv@I808%Lutubd_C0Vf9Fq2 z9??tt(!TlCT!Fe*ez<5k2R;uKsYk3bf=?vyF{wU{jM304&H(UER=B?QQhw8;Q|=l1 zj$UtK5s8UWf1I|4Ee+QFSEd*&Xt~)}NJ9+(X1hyL`1FPZg{WeV7g3hiZmzE$%^9XB zNmXweSq1n~97~X=R(k$UZ-m z%E%6GWYLDtCg-B5aZAuf-sNHk-JgK14;-2qDBJ2$@EH1T;!~=79b2)0=;H^gG*03* z`nkFH$RqpaloLbz;WXtrT=n3p+vkp;k2zant25imPh5@@xAYQu<0zM%_f`%`iwt<@ zb^@7xAa4rAns7NJqq`Kv&}oXljZX2;QBj)6mJPPeKR|}4yZFZAx?ttus0BD?B!uFh zO}V7W{DxoTb_e@L?0^RP^-YMtoRFH$!4o^f<7_qz<}k6x(9;r_pYI*D%yxY1#()H@ zYn*apM9kB1CE}_bB|B9g#3w}};V!;akCx?l9g$;TGJ6nLON^;9aJw(5g_=*d$P|P{FAt!imUnY-k_{VT z9M`gNX%VJK2yxBk4)NrvvSA)dl(5-ueuzIuJ^(JNKjS|+hNwQaOcR4u{Gv;MZm8rG zxe|WCL>>dK4%6^%tpCN#T#}}4?>Sv;j@ocSr))keJc07*Wk!f)VaUiy3eFp*EDaIy!)$GvPG z$x2e!`KliOLK~W+Vl_iDwIxlGlC<`+Y$f99b)2x(@uQ1tT&KTAqeL&(#IcKGirP+o zHq=fcH0)Pvsr1{G!>z%IUb$+{z@eht-fjPn8E_lR3k;yiKg+5!0}@0_a9`!V$Z=7A z$(=8ba$u-dh@Vy3T0_#0G(0PPOjy^S)qpsi>+60qxml` z!p(DNr?^lg2JSnmn0l)ZJYK9s1bf3I`Dd=sG6n}CwUVz0yKDf0ccQ56DUvMsd(2wZq+21{BboEEOLH- zImQ<**YrltL|zrN@WUm;CWJ@A(qlrHCQ(NUdS$bXU-4-E!FjOZwME^IbX^^t;WQyu zoDnx0cFW)8ccFytR2B}L4fOofwM!4GSR#eZg5c%1>JlLkDXjtCXC&|ESijjm)V5j% z!yWmxD_eSyK0gMnWA&^U&MXqs7@I|jLWZVMzn5*lk$n8~$cI79W|Ts40yE0LU|&8b zhcJz-s9Z00lDq_mp)z`d-K1e@hu@2EmUl5T_(075b2Eo}oLKS*Km;yiy_0fu5ozSR z&SA26;0&zpRk)M)@&u-z z1yI-`s#Zv$iO3E!q*snAgNr2sr`KWcWXFsXQ>x*kP$)EaJbF4sv!!l5YcCFcvxICM zhKiW!k~3&rHL3d-;iPv%`O2rOo0X)RGXmk0#4HyUwar%8;J%WTTQxn_y_4tFXyceYFh}vA=R1-A6r@v-V zqyZer=^G61J5`QyHLz3&3^=-{gJz6ReRI3L|H!z^h?FZfx)+xicetX@`<^r)a~ z;~k%UbrcyE0f?J>h{;FcyK2A$Eb7-pF%u%5-6)?SaS9qJnub)gw4Y+o zs5s0h2;3G^wCDj=^MEc|SQLHQD`KN*FPZ3?w_Y8PfumrdM{V~rz}}%REuJR!8#jgm ztAJ)Fgx`nyr;3+ttTb`%fH_A5=JORRERND7&IsnZ6c*qdq+N?hC@9%7kzik6x|(X-Pz`-TV*@1-Tu+ zQB*_Y%ut$-Wss1{r0d=va2nS0O4{7<090c-+koC{{b^RHZRIXR-Yv~PvJ;4dF33ju z&BI*#y&S`0R59bC*xD!RZi+`wn~wN<2<>jxm0+T#y707E}oiv0b;YqbU8#atpk>evrJMw{Wbf1w@`DkE-jWg>JGiv!(Bl z9u;tM1B;Fv7!!$G?MJG%)tN`s9CAz_SGceO55)tr?h3dq&-Kbgw2S8Joi>HtubWsy z9K@bv11FCZ^l^O5@dxRRC?uV;!s$ipj%Ut8mw6zVdC2RU8oV5emNfla zXhRTH4RBCB!{kn$!Fa+)V~>tQcgG6HCSE_u;Z%H7>y0#KR=7oVtLTg5RNx0!ZbV>*SEPrjDwNJo zB83(*nzXJa+~6g1$@e!&^zr5-wGx3g({{(x?H9uf%U?jKfztY9P@EM92G+$v9=G9s z)~xCX=D=9exNh!|?=};)9x{V7K!ip#MW+A->g#H0**vNa?4CCbiZBtW)~1xKAu!2IeHgRVh66~ri@4duX1 zuv0m{{D>xL?Zz83XboOf!cr!}^*gQg>94kUE}93a?_$h;4LW!^yJP)~`1Q_}0-!_l zf=go@vcf3j@FG5iVO%f57!^)UDZ6KC%s;>c=cYdpA^2Ge+rytsd71Rx$fD zi+ewl_^=QRR$zqDd_&;4^rNdy?KUz!)qs2wsVSn5!897L{?RI6=kLxfvn+8&c!iW(vVqlP^aob`%6(NogecX?O`;S{@}`-S=H5#w=&iK$oN zEz@1J7A>-SkM9nP0-s#+jy|{@E`7mpO~eQ@S6!4>rd$=2s&Usy@?hy@L3+I!7-Pgt zs)breqzrUxSbzr?h5B69^8++l2N2oaD2unsAv#TRpD!RjUvFkm%a}^%4VhBdDMW3G zT0x!PK6X<3II$Nlo4EfByu}W{Tbtv#xV5!a5aLz9tG*@dAJA)y^03iEG}`6W%BKg+ zoHWM`M6=;mP9V-6!h*7~E#k{2Q=wI308#Ce_xlN{wf@MOxkGkXI8y?I;1o~wCX`F| zc0PSw^a1KsBaZxY<#FYBl<7V(VW|M)WDb+@tt9adz&DoIsi?^0>?z7Kd?{m!y4kq- zx!wa9K*0<39%;hPUVBM2TTDS8rG&4t<`YP*H9=9`I<;=~LCo?` z&pKq?40WYK@T=~k;o`Q_jcy{*7F)C8cTJ)XTPMTJ$SV_#2MAS1q+iWB9{FB<|M}&m za4L(1`#wXv1wJq}4=}tcGJj9kr+pCU-K{$HL#i8*>EMctOv0VC7+*L|3KVHC?fAjq z|C^DTbDMlLE3aVlHj6TJgo!Dc*6(8L=PtJfo2>Nm5jXG0A%3dK&-j-Z7fz|7<-MQM z+x(dq9-nIaL1~WS%Mgu-9eTqT$L^HZHYB&>WkTZ-Fl{HL--L zHlKUpwPi2*-**D8!!h=5d{M4&m>71E-L4UFcyK98vKYHpaJ77)MaJi!T+^92@Cq;^ zPtJ!DX1{iVIzR{RMM_XNneKYX2) zUGq*fqiDHE&@E~OE(P{1Yj_oyrVUxjDj0ffcINHyc$D8`ytuP#V_Gdv?hqTXQ@!czcH+3|+u|8X9#j*T-)CP)Ox&PJTySZCp zE>!45kh3y0$>Eq2Y60E*X14^Kq)s4@`bb_JSpWbZWJ+0?ZJBvE=EYLhpblcWbYJot z^<%|+Jg&AnhHH->#NiFC>bGZ%)FGMnC1!n&Q`op5t zy^Th1hafRwfw@L|WG6wPic7@mxlleZfFyhD=~9gCDyo&-a8>`X>3# ze_$+%JtUqwdy~>##|NGZ^wHFYnJvLFn+V?+R`mfSCK1?dKM<=Mfc??hzt1=n|HAUi z7D@~pMSl}>0n0_?`+-#YZp1eEz^RwqUu;dhhLwUlNYn7GVJ%cY9(U%Q$jLMs#_!o| zuP)!s`R>xhGBQ757s`MzVyi#W@&|s7xA~znNIiS9j0aZt{QV)Zs1q*~=gUCzxF2Y= zF=IjD=8q764NH`IXPshGc|LC2frewFKxzMtz}@HDXxcR<{A&^K7Eos;)jKLdAHtlL zgy5ffD|@0uQqyg06U6buwsQg1OkTMcjf}qel-2GU!52ARISb{MGn&-!DXfhgDGHfX zmG6Q4e@a+V93=cWqNRxc`qCfqG2fUSpHv8jj*rHxUvqI8! zGq9i-=tyRB0g5l7+^9l310^j)(b)jSz%x7FqSjx7;^(v~m*bQA;xbYt36o0E#L%vG zAx4gN1y&7e%^&c#>AocAT}_p24^C^$Ra*c45dE|0*r?d0a;mS?6TS*95x9@(6po5c z1ed@h{!3$2lt_S0Rdt!9Yh7+@zY4!Iy1IB6DiQ9Qkq_P`2G=T9cX`ubuyP2(=#eJGqs}De{nJ?1DDuss0dsAGa-SYJ9+2m>?M0 z`SFa}MDq8N8r~lfhtW#K$fTc6CvYu%{!@Q5Vh}v$5+TCWbG4!#7RWXnGzcVS^P6IZ5*cVR%x8V)Bn?H39#ao|stXRuC_h`Rm z>Xo7u+S0VZsz8Eyd%zVJou&N2!T#|An{f>Y{Iokh;( zq}_ct=FxVN$*PG`B{v`6iZGb$-@N~Z_BCJ}%6@uhH?Be1UdPNtjjC$bOLukiPsD_N{iJblkNs1 z6Hikp&he62!=Jc9t72dIN$m?@D~)mu4G#S5cJed=o+sizWd|Md!ewCUGP&;c_rh2s zx?zSw>d2N zNkPi7&p%@r&3nuZX7t_g|8^0ZlcsmI=uH$aXDwRK`{QjeE^!u-0=P3*gEm1k5UG!J z=%)U;rTn``#@28tbe+xL&_?bOVY}=lKF|lpT3Z_s$gIDCxRH$s z!L7c7Gy^gfWJ|y+BP_RTVQrAvfH?GDas+fty+N!tDeQ~AdS9O=!n^d|SqNkl*qz;0dih>Tp1X%-Km>mOR;nD76c ziZbD+qg12&$y}}k&?Nd%vYGbkyD(){^91=2R$PwKTYY-$9ng!`Q%(J?a4^!*G4)%Y zp7Nq4m_!5m6FrcjQBkPwK>*kbw=BY>OV2s-0*}7SJ9L#=tpg2H-u^-{vc5qf*5Czy zpu913`gnG7Z!&qf9HhX}Ma##6nP;PFIp}_eZsM` z#K4}e<~P5=)3rbBeD`oYoV1YQn!+B$)J)gcTnxMLxM1vBAt)*JCm2wDdCFZ$Vyoat_-?r@X!7oiyu!H2rD136qapchB6tOU{M`x)C6{vw71NYsLSs$E6 z54%#2d<+f7L!$p;i1s32B>@-Z~)O^VY26{bW=i`ls$M`0n#bO%53oKsllyqY0|8zLIbM8;q4sPmBH3tZhAN0S7 z54n0X>!cG}n&y72De=ZqglPza$uuDH@G4M1-<3%J25s|O?Tlx=ra*7zdlObOw+ z_Fsd+Q%D8{!;VC)%Qn9vY7Q>;|8cY~lhwf$Dd(Whr{$c78Y%pet@V|y`3As3UH-n6 z+iZ+~xMweQ(JTDYP)Ic3Ha4yZ+H9j~EtG82iCJ&;brM0UZg3tOUc${EX3&kAQW7Xh z-}xkNe1~wc)C~SIFr+gh5O&iYBU;DX>DPqYY_g_Mf;eDnpj^?_nWPHr50&Gw6P zjCyoG`Qe(8I6b9Y8S~}S!Vi0mZ$Vm3VtAjkEx$~GS9BmUfi>x+S8u@3f;J7E0I*Em zN5RxOz!HW+#Ant&_@LQA=!8;$Dz+9MsOV-oC2L-WOEdj1Gc3d5zh16IuJP`390Io7z7yArL+z~Z(h*;qD%&>E+| z?-js^1D(4Oq5A=ziZk4ob9OQy`>--UB)h(mQANTe59xLT$?>@Xn^V2Lm`xYdrp0@W z)E^moUK&YH;&8)XYW8?dn0Ak(7KdbpkJ$(A6sSH%qJjw?CJHX z#bpK38lgOmkGtMg0xF3AS=CQuhqHq|lw#Etcmpk%!(YD*yJC~Mb_ZcKLxYZO5DTL? zrNv*@4P$vPFEZ0FK6p?wP3wp{JRlGeA|c8sh90;!0R8SXWkjhjx$_xR9sq8qh@Zp9 z14nj>2SWCTa3FtqT>4j_HtiVBz>fkS(>kLq7oH>~XO=K;-%Viwm{KC*911HDr0P~9 zTnp5L0ryUVPyRv`z-GmOo=79@dXu3(Y?}Ei&*kuxmu!wJnu1;-wTvj#Zjqk&DL)cS zTr(eCoz3oA8GDV!FRsyTVg-;Z0gNJSqt52BVb>Y4TqmP(H*u;5+Mhf`z1U5|YEB}} zeeQh;ygCpb?A?5&!+^SDTuwk_N6%Ln;|2!WA;{y>ggl*ONn7Q$~e^$G!lkpO0=@ z*@rLq)z0AjJ*_<&S#xQC6aC(gJ>d*{;oONN}tH$T0h z;083v8?FBQCX=k~EV#3f%0 z7%wdI5V5^szf6ibYjq)zOJMMq^<5K>&X42&ct&=?^>ld3vG zJ*dc%M`!r7e$~cBKZ`Pd05Vgq{&ezA=mQBa@?7Y=CrOLvdR#W63W{Z5d4UIJo(ZGN;;SXp zW!{S>3$)WFsbH+GWYdU;zehal$FqU^JGSmA3eg}>xG05(t=+78#tjTQx&N!gpj+zq zhmZiQDEda$jK3D0UBnSYk$`&nB>d<>%EeU9mZfBD!mOJ!4%s*++duPsQDkNm7gxj8 z;qVWdqiI_#@4wov&6E?8_=I9?qYT?Z=`PTOZOGl;w%X!-i|GNz9asQ8dfdrY#Hiu+ zg&Ai-q9{35csk;}a`%o%UHI9_3*+`JD3)xWr0ISX#u8l5pA}5E@{VV@4(vUPT(@fb zFM^t5VqZs+UqvsrJ)aZEpunICr%$t)|H`F4vLzs&(JxIq*F>=}8>eKzrZg!7pJE)s z>Qh-qvhiM;$01?AdT29eG$P2!E_Vk$d%e?$9*29{XJ6fZrH0WaCUl+$$L;#o4Q>^f z5NxLy<6+y$xNDzqguG`}YDcSfYCyH4)Cq=HFK)tq`^J{&R2wgS zO=N(C{32|$r4(Oozz0Fp_e`dVqSE2;c7wBB1GYSswh?|z-p|{vM}}U>STf!huc|cb zb|o$6NM$5AHmzzVXofx`F{a$vyewNwEEz$fR$V$q?8El@Rov6g9OVq(5lc!MrgOET zyYI_td=^*Rag51|{`Y&*-WzyuN(hilKC<4_K^F;woqH<%&7>INUMl)xY8tT7FCz&4 zyj4VeKbgCTnWE<~mvUFlyT0`v(%%>7acwR4O@!bmryPGRS@btdF^!RdW`|s4kN{%` zTewR*deyu}W?y}PL~hN^%^b=`1OTXwGeCuKWa)MiwS8Z}0+dhmX|2pTwa- zr=3RM0gHEBYUaPpKq0C%_~1zZ9YWPis6SUW5}l&0slnZ7e!*J6m3w@bZ#abY?xO#R z($_}=Vn=DMTRB39gHXEJpK=S_aZ?uC+5x~}is zP;Ui-YKXIxvfU5LtaqNq_WCY*AI!fq<-gH8E1qyL@WlfjSKtW85#!3$|IMw4w z@yk%~6R(0pdaS%iLc{u)e_Vty?>>!zmXl^g^Twz z6Y+T8cGN?f%a7Ct@DYUpN9-xM78VGPHxGsjT_bSjZs-rsnfW~9(DR^f}m^IJ*VG#Nc*U*jN5@FKGbv`w*Wjhs9 zU{iSD^em3GjW<;Cp9{HYOssRC*axcj+J~~Tk-OijjZ)ZX- z8OwPvh~-(pPYcha(Fu^#0VVsP38TaG$u2z1frC(Aa%8k;0Z71ay2%rz?CEmDQ&J(l zQL_7Ipq`{*L<89wp$=Lptu76hT`#lE-JGB<7EGZc2$hP`np_z6|8ge^_;jal1mH z2YlCB^8T?mup*~XyUCnY<(~XGyVyi}Yf3C2pL-$F905NrD99peicoUb1k4=n2k^-2 z#NAOCoeHm6#T8KNjwrwTu1E4JTVw7&>9-IZr*HjC6lQ zh4kv~Np!=}j3K9TlBbzWFUw@I&}fP75P`&Gc)wr${7s%3{RX3rc5$B5(wg-DdMQ%1 zGP(QMByT(?X&)!eA$mzs5?t&B4t+a|s_kFwwE0%L+P-<&0QC6c5ly0qc#qjR%d1*| z-|7P?GoyU6^s$l$DZV5>((NKcVFBI(YWpXONsO`1_D0pBGC4>MG>G_ni1Sx7I}0kO z{EXucX|i{_2$BA&_6iVQ>bh#9QEAmUXyj(>X!>W$9l7du2jIxw6F1Z5*%@yYZQe^y zXN`5I^bfQU=fy35X$XvQr7|$N3LUpf%X#U<&(5>EHUMkz+&SjNf0uDZJWqYYs)HbAS9{YVUEllt1o8Wu&O!-i4dt@11@GtOBoT7&9`d<}MnSgmYE_}dzRE(n;kRo0@1b-K_e_}>AkWnxpylBIGXN5{Myv?)7UP%5x z1 z=n2-$ROAgY3F`xle*<9$4mEE$1|g(Btgy}x476iZbu06>mv-7ro6RXMM6K_M9~EG? zU@WVy?r{Y!Zqsu#Csmnx6X*aooCmbV7}nE-iebASoy$(p>?$EC6W|}lE=@t3{sf!^#o(QSANiU;fVMcj}4n zQL=|SkyNR7wmjLrBz4f?WRIl#>yr{RwZ0DOTiCY?-mYtevzVN%`5mabiatA1xud>O z2zCqy77xc|#16h1Svj!Dx?*AW1k2XhNA*n-8NAEtyXw{(HFKaMCzQjLQcS(I0J%#P z9x7KqwUB@w>-R05DDeDIc3l1N@m>v`baR6Fl+ValoeAU|IKe}Syu&&^C`3|37QPLO zWoaT`wv6&v+q=G7Q(bJk_2YquH$Z`ymNN&TQBH!USK9ao;@W1irQy{v7T@;nV+;tW z8#~1oNR6rpol$nBf1_gBit_7nIYl<2j1U%%?0z*jjmsboXiaut5}5e%^zg{gZdNE` zVCvk)3~x|?dtH&AQ;5nJjy{3vMS=;%tA@i+Y2aQTYr+)KGOwU}G`W^mR3?y3V-c7B z7T@mFRI-D7gfdssEl#{*agT763SX2092TaZ`Z@JUE{c{2v??59EsK0JtJ~FN?OdLN zU%Wf)Jc~yrZW;5dwsY_Mr&Q7$skW(i5K|Wd@R}PwYFnL4WF9r=R^UM-Yf?HtKyR?L z5E-T2Ug51^>>?}{{9RY55alhznpu2zLLwhfG5Omm3L0$PX=OH4cxkgCt*jO2AR#{BnB*pyW>cX3r%CY%qgZc>^_nww7b6h&cOk) zYrw*1V#1i~kJy>dQrggBC8TPemi0qK&Z~fKAbVeR z0mjDUUH9pn6I53Ew%3lEIm7_3Kxq3{$hF-l3HyDKrZ1-b5x!SXHg#!S{yeVkV?%=qMu~l&|oNpJ5<}j=trJh zUFIErqr_CKlyH?sdZ5QJs;q@G7yrJd=Yx5U@_cu6#bn|<1i7nE#_W^}nW&(kQ~y_+ zL~f0QD@AeSXgo4RtTUlBlB~E@Wdu_&z+GY?pF9|~fI@Xm_sBKPLfi~-GJZ;x@3t#t z&cVj*i|~)3;0y`racHv6M_gh}t8^7%k1A=33MbBD3;bU8$Mra!|;GDV+g#eu_} zpn>j#u~dF2A`b^LBpvtBKr;JYu*==XA+4!D^V90hlJp$|3_G|1>|lL$kY zblVR7-;yxJI?`A!vd~^}p$gm=tXJNQ5AqFEkS_Qrh7l&s4|r!_pHMbs+<*5ZQdmA) z8+izpcjy~74{WX%{^z9$K`=k8ln_gkOk1pR4 z-xY5~Hhx~?{*<<+Z5XcXSC)EfY^EsK@>C*F14ZfjVd><%JQHCz>32Xq>E^iM4>;7m zd5I@3)$>oBus~SLC*WxmNVNH}ap(op+GQe)vPZPj%@@i39GbIowQ0EfR&g{1_6B$M zDLL-dWKJO-AXAX0_VfNBK3`8Y-7@Fk^TakHGj&p&7_jnJxwtYgq2URYb1Jj+X^vxoL;xkmgS#_BM{6nq4V{!wE5d%QshJoh z4JA7A23xPI8XDPk{D3e>0P|PJ07VDOTR~Ry;ps*lH#D1qK?Hr#W$#xC!Is(d{>&re zyVm7V3ZyD2Cd%J!GSJ>h{yg9glE9*m3SnFWlJ~Fw#nM@Dwb6E67k^w5mgybM;A};#h^6z`GIanyO-OT>x(}m8hD|B$%R6zPTDl!$p$dOsa$@`0kHfovwoGGE_5zRTP!!m;E|6^ z+?E=<0^F2wAh}h+0hbU^u{8oIR&Q)olCw=2szASfSkLh>mO0*9UqE)~aN)C`xX;4& z@2Tc%c*@&Kq%Q?s5TgSJr+w?lR5hr1H*(Q?5_}-*HW!_>7jauHv9%q!F`p)bt)(yM z@Djru(C-nhFPw8Je}XjRCs*sfe-{-imNKyZxQcMCaU+uIg(2p2d+q}XOon3%1ZlJ_ zh5M46nbR}@X`b4FJyS(xL1C^OuaKyHCs?}0+G{^aX!wG@vtCE3(>7ZRhR*m z(yNbj#Y*%IFX7@E-za=VtvGH^f?wJ&ex{IIZ%$Jht?i)N_r041=~odNFhhdVT9Y(r zn;GVE>s|nfDCduzzhGT2DkL%{&_S(71`=EVRI`tR%9kH)-@PMx>1m+5I)WrK%6N_$ zC9NR7D`B3*?KJGVmH$MEtHO&f(QLd98%kGG@#I7LQ&6-?4i{-OC4_qT(WID!MsX6_ zsQ>~k1>Q75+m)sDv23N6G<38G>jNP=X~ErIax&7LDg#^)w+MBME3BTn2hXVWoI?~& z*o?W)&sU@Jh2~Rqc`6xvbZ5$$QY{ANNSElx;Fn?iUzJ)U32uuXj+Z3dVk=YiXbb~? zMog!ZMs6D)9ze*ll-+st@mp;)0nG&7Ix!4$L>}pV;J@N8NTf_xHTJNZ%iaEZe(RyR z7}YT|Y5X|iL&pM={-8&WXsS&;eyGl!r-BIVo(*9PX3m(i&h?SyRxJ);Iyx}i{ftlO zP3-W#NW{-E)zhyN<`e|Kaq=`}VR?XAU_U5$Gp$5&Z;W30iKJP1NohO7%4803(F{6F?FDir<{ zFeVOn1ntR)(Ao>ZqC}%*Q6)J%_JxP%huov^LS<`0ronJSu#!TfZslB|ZPq9@*ke<~ z(kX+Emha=HTq*sRw2+cKPP7J<0ess21`9qdlXj?mWTIpPsey9PvPq(@%Fh@Bz)tmw zJNOTc3UQiI`vE9sEywR-A&^v{CgXGQ-Qky7Pr-sg(WazGen}GhisSfP*ueEw&xzVm z1x}TyewBV=UAN5o{_{mA7SY=Par@Mu*blLa4}RFC6ZkNUD0~JGOwWUN^-M#TSaFpk z!M%5mqJiNm;9}1ywzgqWk@8xgv*k9@b?LA?e2~WN=N$9oUpD^>;6`YS_pg)?q^TlR z{DKZ~=qAG%<|l^pmT!nP#M0TO&Jf8QOLc?%)^mtVY9%d^bWs<-jG(NMy;VQ!cgWuw z+iB|#JShK|>2e=$`l9gSIzpc==26G4%wvAN%qR)AFE}K{fLLsI9|_~K8M>%da#Q;Q z`@>36m*(5A`}R?W=MZ_Y4*2wW=q(fCS^4OS-(zTfXXppYj1xsb=jbh5w}lgNOmC?c ze!Z~$Ac@C~nEV&f)?mL2mqJM_KQNX&JU^e**;yud*Z*tT`rscH-9imt+ubr7)cSUs zimt28_Q)MA$aSIs@o)kEN}Dv_Cc7DBrrtuYt248HK*LKlTNcyOrw;Y;kee-{_L z&|p}PiT7xxTd)bAVOHxE(!^6&%L~&?RbJSdnYUWGq{E64om;UTVS?SB=8+Nd@iT_D zt8j2A%Gunl*h*|UWXDK8o=>ecDzTBp&-zOv9Vn2N55h45x$&w%p805U7-hM2FVgLU zZh3*Auv}cR@0Rh8pQphMFRzi-9StfMA#w1#K(p#&!X>Jdi-qWLt~g^<;*pk*`&H#@+O~=%TIg3}w%5O%+ zHs(f2W_8JsHH;SLr=cDmU)GNhoF9FD0?6^tmPV7K^oiAU7xp}3o+oy!jkzY&;W(DK zQ9GlgD^aUTn^;$?vdK;|E?2=SO*AiJF6x4*GEHlan6gs(JU=>OZafhZzB>>F#KF`l zJSB{vh^GfxAN_}lU&05rvh$A(R12eSj6`2<7E+AC^vSFa!g#xCDxNf$xdbqcRkfS; zjzNXswWofF$@Kon|3ac#BHVwqw(bylg4lG9;_#=MGcKJor(+|kCcRusPK#tq;rK*& z$Pwc$nI&f}Lc(y`afcGfFDkPA1^a@0)%hB!!bY(a{w~;aOLcu5I0F zS)f-e=Wk{cb(@(NrHGPwt9KcOXhN7RQY^mM*SG7ti6CC$CRIX6#aH%Jt% zD0AC8VqZc#-Uq+5pgE#wd+w6#^4?^}Tbca#wRW&Lkbk*=p`-ZiJ3W6>)$kE<&n956 z9bR|8)D*67?wB3l@_+pRdbJy|7qOFA)?z6xXs7dyc+P*hwcAKA1F9f-Sy4Ny6HPZv z3btu2QU?j&Vl4W0_b}ASSlV+UWV|?m_GGL3%1G+UKfZg9-WWL1X3+SVbIIaEHrXe~ zy;(;S&u_F&i&&$`xp`xY@pro@`irRXI+g=wUr&|g$NQUZ}09SN*z?ka?YiH=wsoXVo8_UV+7oWsO zAZJ+o6Uki$%2{U3jrh1A&$qi_0jm z?<%JbA!?6l2Pc?xwz5SkhICedmRA3rgFENmt0SsLR>e+?Uu@rZhuuxWS@3ipA}rlA z&6aNUTrQa4XQDTvGb02sw-sdeX~&qz^rtI1Cm{|W8NJaUIwtk-vRud>8n}RmyFER`nT8> zz{NjKy=Gs|$kHEf0-DJ)c$OT%Ub;y}9xmn+zBv7ZK%xp_Hok;aW&lu5HcF_MYr%Gw zNil78EE`N;`{~chL*+9bq53d_pXqcjPj;w7%SN9_`K057EY)q+M=9sC7iI*wjzQNS zew$m3^y3d0P>knq2%Qvb2mVf8x%$K{!dcoaHUfAh)XtAzjM#PN>9nq6Yi+ta*PL9D57cgF1pVEx+S6`j5bZa@nMdaKiZ-0PO_OjG6HQR6N z!L1)J;f*TK7bG>?Cla|T)x-p#+@$y*zuCE7|JqhszY2fd)2#V^r)vXq5~}Abzc{St z%b(%F4r@{-m?^^*L}b%vGj(mkQA~7O8IM~PcV_%~vDqQ8R?oitRsB8boF*7KG#}?- z9|d2@{ia-i0@vx1PRd-^S=#I|DWsiU2UbBrp=fqlp(KT)&EO*i?5+_OXZI3plcB3OMwAvTEDEO9;?{YQc{)2a-aPDD)K zL$gWM-r~|tln})%#LuF*bcI3_^4+naqi~oF4n6WvwXWmZksx>RLCLsj6GGjj&w4d-a8OK~!r=>^Uaq$@nJkA7#=$tI{X2|^fJ7vu#YGgq->yZ&9y(JeA5{od|W zm2Z%mGTd%+g_=IIHj~L>T+L9i{ItK}b|cVM?euiW?qsg3tnphU>~9^oFrcI#<@oyq z4UGv%suG8EyN0XWk08iS{Oq^HtYp^XZb67RUUp3Nwz$=|2J(9h{mq z<%t=uYE8547E-C120d(l%#sC)*bP~xwBVz8kkSIXym%?`?S?h6?x>z6NGTKeppf2v z2^(gu8tTrGuQ_;p5LgmMjqMP}H2`AXaw5h=B*HQDC-ByZJL{3B;>8c<$;67NlLWN zJR(Zkk6AeCdMIV@8W0xnP^D)Uem!HxK~I?Zu6yRh&_5_1vz{*r%Q3k=S6S| za+k;XX^9KdI$glDk#AN{`w8BkgW%JU-xlZo$RF>Acx&FTQGe%mH3un)6d}pmTvYqi z1M9+nQv}>tjC>yWX^wr5&~`CSp@@)W*W_$+sNtCFD7Z9H>r(%B*uqvT^0liR>L#CM zkUd(pr#7N+Dv(OiNI;8DmS*Y}3s0L9==y!#C!iYzNeE?v(0fIY?h9M(*2qBWW)Uo2 zNwEi5GQ{1Gw8XajzJ3)zFLP5;W|t@;PVW)l6ioS=IG;>j=po5riAId;sFG9+!78LOedu6^^4&|V-Kp;l-eoQPG z;Z1_>?JQv(D-BWeXT`oYTf{VN-;rj|bk&Kl2E>d{XaJQn3DU3Px9N>^2fiVL&se~S zM59Pjk+WQn?P)@uH$C3zHsR@MxtH7UhGkXWs+plUm{)m`fG%Bb!G<5kw&8+*FPfk= zGkyMxJ-mDsk3FqAYiraIJx$pq0MCruv$CajQ}#37G&|9PsX5LoiA3SUBLTCi_1?(u zL(#n!6i5ebiUTJN!o3|tgaY%z@<~7`xBE8ou>mQ!q}_Q&Eo>j&oPW`r@sc7ss1+l% z4k@rEe8JVyu#;oC4W}AhrY1IlleI-r6!&cr6f82n2GWeq=ef4oe6_gi)}Yd?)u!iL znlhH*LvWbLzS{;s;V0W$-Pn@$au?X)84mQ#7&SA}v)hO^gf5?^jGy_jPx&8>rjx)p zE15Xr-^As(#W;M|>Py3uzLC3SVXGGXpytc{qnxm9^`tk~W3@mm^TXdVh%Fa~*4{K@ zm4WmcV@Hvm+n*~>NvF2U4$R8C?KK0d+Nw8Qh9`GSce-4zr%kJU+^1f&+lbWN<-^z4 zg8YVZsV0kfkKrt%w8`GSYT$4(JT8V^*PQw}YdJnjN8j0&^3{>XBbIt0XwJ-*y z>vAeOOotLMa56Y*Oekdgv9A|Dc$dGt{(X(iKMMNbFxa8@^H^(>L2Al(rr(u8s?{*! z9O2CM&Fj>hAMWEHYX?F9q8Ydh>$LH9L4NM){3`MP1`=SUic!7PRRp(p8cTJ$+tcU* z%rs=)E^=d%*}tO+@iFCTOgOu(4a9e#trP@*C7BMU2lDi^Js{|{>nQTGYxJ=J$4~rY zW9exu9fy-F(T@l7r4qH$gsS<}9(qR`Mg5floQFdwxd=geN zxqWuWiDohl;Ct}KSmOj@ZrF<1B~Eon0eSgf>PN-pcNVEpHA}PYPxtNo2^@1 z<*=3pdyUmyNAwLP=(@@74CDH@9$T;VjcYz8LgM!Me$H!_sX@&jwY|mKP>*yv+MfM1 zT=)1nhaz@@tLZ2f5)_5xGgOU!sE_8&C7`_%Wq$xonZe2;hIh+%;e~&$o%?fIKT7*4 z?$a%~cY0!umIW^(MVk?9ZIsYvS8hdhv%vF7O3q?1-=y>U*|P=qDKa5?nnWEz?=-{5 zmQ<&3ab6CEMN$XW!@uyo??Y&0lDDB4O$r_i9-&XZ?sXfXw+~7YrkktC<~%3G-3g<+Rcn9MZsf$gS}|F6*TU<8W{WxAry+P}pHiC*C;5@34N%qdxZ01@ zF(^*CqvA5anF?n~utc?K-`x;Gb^TBVBp5y{3pr z_co<1W%;6}tjPv<$bvwYUe%|buxpvZx%gLxyGsQd`gHSiw}18ppq55-nF`Z$UMDI`~eEePsz^s*z?z zewhcSUSD<+xBuUDEmLl=lhBH>@o#KwIf%Diab&4xkuk6z_lZeKQSbMJyVrG~kkBZVVWt|wN_o>UrJ2zxoEx4t18CSwD zSOStz*B66VNTVJYmHSBw!J*(s0!D|eYQZqBR0(oFT?z*Q$!t3&_}hPi<(4U*U6k#q z&Em-DD#t0dslux`ES~$x)*NeuPqhRiR9bo1PyZ5k?M_eL5*Wcc(g=Wnr7rxM@nr z4g!Cj{%jG5plabD_OuVBoLgD5K0_Nnw~3wC|7aqu!rVd*6{I{oy?_#+Iv|3&zSwuK zg-q`^y;x(K{g-Q`(v_`!+2^{bH{0jg1Ej>iUy8(tff*~u^oz0`@BLL|{AC4trTE!| zsylwFY|l}N-eZ+onMlQ}&b+;xbl&quAxAj!EFht#5E;W*&our(+ z8bt=>JJp%r*m%jW#m)UyRK1`>D1gBg9B6zzMg*hbw}tqZxEB={YkU|qt(0?30 zqU#raA_7rNO4(8^P9Rf|F1kgP#Zp2u0N{q;J=FbrQfkazFvBm>hf8m5t7GTguxdWM z=rnqZ=nswL%+6mDmvGY=7d>B5X$hlqoP_>H^OS8;>w)^!!xN&aK$mHjLemP?|+?si(VXw_rozrp2#ev-R^Ksj~YQZ&*5GbQ=!O z2c_VMcXf#Ui?76o$Y;Mb1VdsFM#gGIpOPBOjÖ$|3cH{mAu8frkld=2A_INM$D zl=?42cESo===9(eHnnnJ+c$pLr-X~a^3Pk9azEZBQ`tjR2t^@bTL|t-auu*PdQ0t7 ziEln2N2;^w`GPHvzxsWfYtFLw8(!4RDO$dr#&>d2%8po3gnuP?O6UekAmI!w-Y}~M zweI1$GoKAm#J?~%RcUZuVIhc2tr*^JX;Ey+^W9tC4J=Yg%C|uz&_bOLTg`g%5f-ws z6%!O9gM$T`OF>FZOYdQ3lSAywB!HpXZ~k1zoOeXHIifs3j|asVUavn$x5pVfJ?7st zSo(cj++Y)dbhvSwl3TrxErkw}$%29usnZI)!4p{+@y{64rS7UdtMYK)?iOCIF*?wh zW{RrcB7+wu_KIu<4eMDiEj9)5#B(RS(~o^%63_$~y9i`a)IU2xc|5?D=fjrfTzZ`n zhHYfb&AjlTk7U%_Vx;DgkmI7i478I^ziAv~ExwD=u9T~;cTETp2w#(Yl@oop0E=>A zi5&B1>t#wMy8$xUnJ#)dm?G|A`{P?O6{Ls$g+J);V+`R;h*860vJho3Pe|mFxMRI= zj(mqHw@X+pAaL5jS34!Zl|agC$xbz|gcWx={35w~@Zjk!`KU7+>Gd-Uu8o*TD!I8j z(Xd#Ee5CsEsI~cWFcy5A2r$t4V-$BC2XQak==J9p*fZ)cL;CWq*X;-@>1_s_hBS{@ zAu5sCv`*MzP$19;mDER8Zu-t21SE=D4f#Z|E!8Jo1l#)ESM+PRYe~`+u(SEOz;%~Q zrX;nE=?@cWvId9D@(1&-1NvyYvzk4}?fZV^r`3z7Z2;SGPbpI$kk|Li6wrmERmGSA zkDYY8&ds;u8VGVLrqGx^NYPMfU1Ka~8lJ~QRizOM3=wD{kIu>_sXG0+|I2*zB;qb6 zT~?bAM*~mh#=B-eYdXNyv>fM&P1CbA$}VoBz95SSUq;fi%p?#NKe%#LOd=Sv9^kxi zmyr=TvGo$M43V0FY4F8cu?ige;I~bLS$1;S+Kb)F_5XAUC|O!!2K3`7hX|BL_6AXE zu3nZ5lI==rFwaAK?8-P$vjjOAb1$|#G9f9<{X=7sTB!B;kpr1`*XVw z5Arz$ew}n+lrK*@73ou~fGv|{T$Di-SD0is3SToF{7Ky=nTCwTmK==22u1H{&z=iT z8JuQYiS*wlh%6ZpKl5Ce4&M^CP;J_J**KsG--7mk`FagrDaRC=y&$f$;F-m2@axz( zr|*3uvo(pgS>P#nTAdlz#ktra=fWk@+DVjmE;;m3Ot$gqz6288z9*bqE0TXqf~8Au zs}bAqH7jAb6lb2>X+mn&H2J#>jD1YKm?tyDWhz%wY<#jw`(r-mFdfa6fuXhg?>#cL zlBBht?YtyPxD7|?Ez=V%+~U^eV3;WOySae?h1~s=}_eIBo z-3a-n52#^JSir&Z+l3OxS_v80CCW-wv3qm4OXB&^`ZX)WZAy}<1edoI48p%5CwBJF z{pow;Drs$~PtUcHDCgI8*CiSE>r$W6*#T|8$UGAhG651SzvuXUJ0dJRQC4v1?E4(D zdV_2}%@xllyu{_BI3HnSnV>9YewGUwJIutBLfzN@?=DBx%`1lf0km~6U~3*k6b}oz zRo7>fesp;|VwmiHqKWPP99!#9I!`uo4Zh>{Y{~WaHhbAnIw`U2z@L5SW@OMjEr+{* zRL!W^)Sn1Ik`2#Uu!V_wP51eG{gVxEo>t>azjOYP zzV`ESd?zEPd&0`{Y^O#!RO!SqWUs?u(4iiPRUhiNup$Tn*yeSJxJ*aV+v85>iaQ4! z9QNw;pSNLtl~er+v+-c^+vC*1<5jtvjx;P+FoE%v*!(Oz6sW)7*SbNJP5Pn8oyGJ# zC*{E*pVQ_;lO|uuA#(G-NL3_4r$jvh21gsNJfjBKKUMq5)bd};&ySAqJ6>eM2lAYz zz;pnJXDz4KUblp#;M^!nis7dUPQ%|o00C$b684eGq$GG16QVq^Af+2!pw#kA=53Xy z7+6uT%Yrj5(hzkQI?X<9sw6cT=O;1=Gc1lM?6VN5I0*~wHwYo1Ux&nw27Bg&1SLH{ zYfdaXN|xtiZ>{Y_hBdP1M6foV06FDYZNt@)qf^xXq6i>m*cwm`Pyn1-uu} z_;at_hR&tG5`{UtzcaUg8KroM#o=EJ=hD)&xg%U?SFb>JT9 z524<`LY06S08!gf(oYI&nKXcV_UySvtKD9fUlXY3x{hLy zq2wd@{%vu;ynivN7fL}OzE;dLJ7K^8r%m~G_uN9@Skk#Ehu2P0J+bs7--A(q|Erodo1b(gqe^V6@vtkBa z4JZGE!zon(cJR7yCoY7`B>P8*Jjzbx-{JJqE1|ez9?=SIBp(X*4!U&<<&OoboQW?GP2Z-)*w0q#;CNzlc^iFcZHy|#-4`(bcu$kQ?b3MkTLzHB11v6mLbRBrbr+^rtjod@Gks*f40d z-OwmL05rTvPEGXdLeW8bRL_9;u^Eyzzm0I*-_Fh=M&xfW!ip zDl}=VzR|u~!(Ay@*()^eNzUu0CK zmRUDdY7WLo@q(*-I^Yin!tB<)+F^;k`NsH+@M3n}Osi5mXi29J8^j}zKcmYDc@?Xn zPHq^BVw_Z;XuRX)TgdKuIrXT(I!4;(t?GaZT1i_h0?=vD4;U}NniS_{MCP01sEmqk z8L{-1QTU6`V@@LE3&=rPjjcQ}RX9?6KmR@45&yo(-T0aSFDs6j>W&mW1Bqobfhbd< zn4#wscV=)}|4im89Iz&)4;|n_ii4wXNkD)We}bsD*0ty<4vS$&ivUewDrxu@31*%qLT0Pcq`T#fl}1$FGWy3F z5GH#zhA9eD`Yk42@cQhvvsyBDd_EVcyQoU`l*+d2dbT^2H*xMK_)la{*H`2nzpoFP z=on?6Dj1F!#afbW>JMPl*bMX|=;;iw@xlf*>WX*AVG@#x#z}oplI5-zZ<^UTBt%-j z^_jMtMWqLF20J{X!ZUD+5x}T&kNWxDp2%s`uJ7QNa!vc_2Fm&Vl5S>g3}~m-PHZjb z)d+$OO6KtL|4QI~e&_eq7k-qPkY1po&)k5jM?yLO4-L!JL!Re(7+|rh1B}wu7ATv4@bkBn@4TBL$KD8 z+;KUskvIX-tr+tQQ;Xyb$+aG&1d+#$uXqtQ?)Px>)^iZ7#-T`=xX$e@u953*Rg>dL zksIB%m4Wk|k@gVTIM*xBBWaz6)AEdrtqZ_>)0ID<$xS7i5>C*hP~^R%+~aTJOz-<# zTQ^#oM?9hoCrs}PKd@m-Xlvn{)k z{~V6LE~dxH40zAwEl)}W`Rhh?AWHEMK*BPO7Jcybf1slMd$NpYh~y|f>K4CNLANPKmu3{M}z6$Rkx%48jZpk_yf%CM6D zApv5zse3zo4H^A_Fbx+$&Y_;pfe1QZk!Le~XPoS$p~>As zai5Z2{|^PnvP{|Ks)k3dya`UfaM+{8E;b*T9Nz}ow70td%DcZx?6N6>kMy$p=p4#m ze?t;MgEL23+d!tvEi_p~*Z}UPlkM`${tI<0@1|F3KFqr>g=zCB?9MwQ&b=OC6{yFk zNhe*hZsNBHaKS_Z^O^+#HUNE=ao-OQjdyp>M}BTyfrceFrrszT)6kNwx3+eKin-J+nCzRRGjFXS)wZ}Y&d+F{88eP zhRprY$ovo_X0y71 z2HaV()oIJ>D&@(NFL7R<&-Yn7##Am{eYqs+i5xKVUd4VyVaTV4m7=oa@#K(WXWh}l zfS#|et8YRhc4Kayy&65O>sq>DiKW z=Z!O8#;0_SNhE}FuB&d3rn7N->d??-nfxkyRGp^uBowGg4V0W*Te7|lcQxUmnHidn z&a?ECc2PH=B6BMQcmAyJ&to%jdn15nljUI1ttLK-f%(MOswFDuex;h^H?`krBhDcv zwADKLyC*gCCQG1J7ah2q{!TDk3fB|3g*bY<@f&^jsXuQBGT=vSq}oujeF}-~1B8@} zdde(R=(fVBP~y#fW#B`BgZ^vsBGt~RHU?mOhcx+Uuw zELZq+L^0CN06R@uYXsT9WB$Vd*V|G-zBHfoiZG^>3SKQSrVJksk^_iy&A=BsZ<;3H4@SvsGH>-yDV4PTOoNF@qhwd9G4#K z?t(C~G~X1H$%wX>JaSmQjO4-!Hdt<$9+rT0qJc&@iGAxNL!bO>W?v9nVpU+;5#8P< zZ9d;l1sx1_Q_p8A;m}~+pWezb@}DE5wO{q&K{Dq@K`)4iS=|~hl*r@C8&?jWH@)A+ zM2H~Op4k-ZIZzPC#a|oj^bdRS+S`dKnP#viFx&CE{R3-wcqCM^@k|alL z+d<@S$=hKv16|L>$}#smbtA!36h4D^t9MD!7Bp@orGIzuu}_9aMp6lVu*n$?hTwFdgC-z1@0pfikup5!sW&n7 zP=ac7Jbx0W=U622yhSP{Tmh<0Z`PoI9v?Ns1vZa2d}JQao2)duPINmEKu)mq+F&%I z>+&2<*}P#E3|uxvx?vf;hFER%_m|AijUEfmglBEHUwc&HA8oonoUT$!D0-FxJ1mlCs+#AUxukSAZOt;sWMQpjliwlpr zjE`$d#mROoY2AY^oN(OZSW_X9iKI}X!dU#{n3+3;*UwR(#5diLkWH0c0U+bj zyki#t+FvGzVGKT0)>sTGukr{lx`)zKe;0Bz5rWh14j{SXnl$+HbIYn9MG<7$c^SrE zQZMF;AD&K-%%J%0=g9_W|FONQl+MDUya$ChXuzWbB12Y3(ztMJf_4c{5_>6n#pXPloS)77&AOjn~EO+_9euSL}^=DKHWmKVLD27U%ZFE z1LW)Be?W(yTc&EfwUQIn4e*^dB44tthM*Y=ZP}GY%wInWC}Oi><0oa=ujw&55_B;r zrX%T0V2+JNqY-W1ijpy$AyFiVAF5t1PFEG{VUC(gF|Y>y?bE0=5GPm2Ix?ih##uQF zaF1yc1`;DvH($g%SusiOu%(!ijCy*R?dI#8mI}@RpCS2@eG)SS!^Yd@8Y6Srd%W?yoqQtH;!C28ukdql-pXfc*m0`&>$s+i zj+Q%zjRW5A47>m?XOhqIe|wa4h(YvSBP`N$932gakd@$(v(YMG=*~d{AW6?5S(IthChY{-LiS%g`CP2Z0%7GnChc^=XpGF# zV+yb!#Km#e zXUzHPLX>nPAhxV~Q_WxH@4Sr4GYpGt$CDy=sSukWRQL7?WuBg1?OjL6^_36Rp5&7t!2*8y48G#?APUMW?N zGq%{~xVR7Hg6$IZSt9$nKHzb-c5tYlqiA~j2Sy=)|Fbh1q9fI_2BjyihjT(dmFibf zz#%sfV3p)cT7Gw~!z2UJ-q$}n`uYoG4z9UI#LmVzDw-W$O1xD(YzbScuz^Fy8Oc03QyiZ6HB36A-G$(0erP!sf>h5MAH z@`O-v^~p`?q700`!{9&hx4!*YzaP7$fF5@BtIyxKt(Q8@v|Bnq&4$cHlBzxfUi-K5 z2p(^fX>;f0V}V{D)GXWu(5m=ez2z=l1Jo`#hp^6I5t@7qko}Qc zQvgp3*Vv0f*dTx>HzJsHZ*t4Fvze9UvA5?jdsBN_9#1;}0lZ2ixNibDetq}Btf`Zg zMkKF%#G&;#K!RN3x(K-&_L~T%>LAw=L6PPQaZ1MKo zz{dgkZqDfV77?1+N>+|rg`BTvP=cL>yj@*MRjqg=Qn5U!AbdQi%(R&Rh1J~}ja9Zw z3DOkP88oxwyoc0Fx;-TCWo{Vt-oYdX z5Zh?C=x}fT{aNz~rBx5{EgM+qf#5RCiL-IOQG#j*Z3@0hPOJn5rtvo#aARmUyCXfP z6;*}Q!5HJkP3xs23qZ)I0{r4h?r6mDEzztHWIJ?NYci3f&@;kjmcBeT?2l8iA-V}a z#k&-XFtC$3o>GwJ`$!Y6DP%d z`K758`(b1vy#2hY(JJTB8%Lx$2sWL<@I{1cq$XZp8bg;&RbcA;nKG&iQI-2`_yA-e zA)onjlhnpw+37&>Ajzg9V`@(H#438Nh36v!d&j0?tl8`-r(%nFdn{QO5RV*SQN|dz zkzE|R6uJLmP3oEBM@0k7PuKcv;oeog{CJ;Qce>rWm-*+94}Mxw=(z>-mIgFC5hMhI zs(1vuq3`biQB@!SQrwFjE)}qucqEIzL~t`RF+nSU1SVew@_v4Zd{pbt4D%AP;}NM@+MQMZPg^) zIk$#-&tTqFnuJKnHL-X(s%whtAo2Bh#hP`LRA8vwfQH-@t;!OCf+a1#lS9qo=K6-F z*5gZ*S{(eKy6<63z{CJu|6f_cdC3@z^v%jrh#7ysTa&BGS`79WD6rL8Qc0h|653&i zc>iL*|1SSe+I+k$;6O&s>+aN`Wf>z{Pn=hkMTUH^HBS7 zWR?Be=A(bjyAqta!X|cd*D4G`Q;iTmV<1=oi7t1CQIx~Y{GN;*bERxZgfujl{6bO_1lLyIzugn`}(?5$KKk-4)$*!L` zXS3P1mG_N;-ra|J;b(L1BpY1D^~~$Jh9B}|B*xoh2U3>9TpNq5nn85~3?Bz-kUS`iGZ3s^~oEiC&s_h?h zYz%K(wO?VMmUcX2h*l)C_97GrlQe=~a0HRp5o1613k+QTz;;CIMN|IZs4CXnr65KJ zYEdHHXE56FqRD$1aE3u%b}|CLG#U#IlV|LS@R*}dQX`UWe9J>urh;f8jH zJ$rr)`Fr=LhSuWW+u4;RZS%kT`L&_Ka-8A)=#``p&d(Mr z^2#pmp0+1NBa{zM)V`5`%*JWLR_xShg4%9BpbY78tECBia7FO}Y7Ucn`ZvS7rxjef za7FTmA|S=??)m%%Dq3mW7zh1ibW*i&l&Mb>-Eu7)RJK$^a?Z_I(*Y4>h4mzrlHT~(M!|Noqu~Zg0<=^8t+%Bd}q6D3uYy#y_^OKl~H+RoDn+@0wfixI;)FVSYp3I|)C1)qD_TFv2(DLZ8RIb&lD^hH8d*JcQ|~y(2!3*V9cT) z#X$a}GvCNn3R(|$dO>I)0}Vtp2@Aw@2fc;Y#06k$z1EiJotJz}6Ui%+Zn^R`kD;A*p~?ErTwp?dl6-x7~d&mwU95sw4l(O5Dvg(NL2 zHMjaj+|oU_bkbMI!k08bvKcR7^x)eu#fD=8Zqj4&7{+K=oa%E+bG(M=hI_1Heq}V< zVOw1z!2QQhG9h0qak-{H-gI4T?wAKYDm8G+B*5W z3d0Z-iIw>&UYM{jO^0}L=lJNhyU9+yx=VdC5{OHt-vh_)s1JS*%w5M&%MDBNjSIQYITlUypVIHFO&bvWM!M`2sWnMB$NPdmFxZ=NoN_? zKZXqmD~2-jnUjys)??IWTi52$0N!n~(>|*Z7#w#{yxlBS8WGQ3JQ4%PlHWBBBeUJQ# ze!lG~1cbuAs44iAaXR%k1t+6k_W`61Hy(KG`OXv2K95MQj`O+4o|z4f-aMTa@xu!%7Lu& z#k+VWRimk6F(o6+-0~{?0`h^W35EXLR{U^<{|fr_xk>%f9H;O-Jbcm@t=*wo<&7Vs zt>r>5&r3n4dD>Uiy9Fi=9~eySeA8Dn|4Trm;>Gx`MB??KWg#qQ+yCknHn+u3RnUI$ z8zp!uCW9`u0Ce#1Xc|9@O(-4*%*ZhMy&ntSV{3IID4|fPr!ls=Amg|h>W+<1VL%Ii zbY42WKN#5X5NxatzDIf)F^uHsPwD9v%Ut9IV%}VbS%Yq8kS(1@HXbH$2{$4GX-IFV zr+ymg9#U*%k_;P8N`(hLU`$T_)>x+9mXXn$oBJZHeI=7eeQrWt9?Dwr_hmSTIgi#&0R zlz1s9AZ}I?Y&B6Ex^o0b(LD}+n6SSB_W;18hsP1YmO0N?pAIw&U z=y>u&3JFf2WQv%;={OXwf)ya_-x{wK(8{L%t!hMfS7o3CVVUlVLn&83-5%8sFp~1* z2zaTg0l*irNhA65VXtRp-O3?-lDiG>>v15UKNdtoSW1^>+w!G)1BizE|E_P|_GNHR zXVoLk=V3S;ql){HKo&iiz`y_$*FyaMK#>VP5y2Y}S&#bk#-yf&``*UzG zXryju+|vUEKNYL%{qkj+TT05Y_4RAcQsP}W4&9p~irXl8TSi`zd#aEm+gK!JJ6D4C zE}02<$ujo(8o)fzOf+K4%nxHL$?;ONRLdX3m`B5fIlTTAt*U~2a7}o5?rbe+IGy?; z9sF-qydexV!~;TDg3!5qaCvuRfWtc0YKOLaq88cD>qb12mHVNSwj7}U!1}eGYP7ob zQ|CCTi`4^~_XrZ|Lf>VA$ZZ?l`UPGfIuj`1De@6}BZSA%_i%UTt|8>FAQV4hjuxqf z_|VnoQ z?^kT~wIRRx*M#a0+sLq}=7cum_fe7Ab6<>{r&#OxfreWqU$ts9%dFHW{((^`-e{RZ z&L(dWOwErSla3iip-nUOnq4P1e1y<#a`h|c8~2blV-I?bH!Z9(AEhNd=cd)9+cLhD zIj0IGU~a18OI2q0cS=J}HPWCs30HqSaqTQF-ss)oT%UH91fs}e@Xm>bxz26zr%2up zy;Snk+rI3#=W8x4lNn&2P+T}F!sXCl?|3OhVNN3ULu~gci>2c6sNk24>O?n|W*WAu z?+*Tv&I4&Qd!#R_oK2X8^2ySPQw(OE!N(XQZUxC@2$fdI5$UL3iY)2CkW5l@Wyq{< z%E?fo!?aDvhqt2YnmN_xYc|q-Lu=-Hv*Nm-XPca%-AS+#XuFN7hy(vdvw{y$Akh>= zR@xD~2;8iKPEJ*4w#9qNHL6|~3_HlE@+Oy${N)WYghA1F{Wff+^G7rP<~xm~K}Ahd zEBfi1vhI+Olg<;MbE}`jj(_8TM!!|(@>gOA$=j(FC4<%_lJnK?Fg~D)qf4T4Ft)AM za0{C=vy=hk#LdLD{!eSoU0U|9Rs3xT+^an_wbDn{wAkHnYcD_wEu3xPXUa|cLf)GT})lbZt4W} z&^J~7ONuLtW%yDRg*f8gbT(VfC4t}_d1U$Yv@HeMY3>0}cE=Hb`-niH+haU2=h_!{ z49#0^*G#FoUH>b`9YG|Fg$x8WZFX=}Pxw94d#8TxEc-4o3LPYNG%E2ckV&n~-s^DE zj%mI{PFJtujo2Q80luRUivg?V0ncE{agX?%-rCglHN&UG%tSB!q zT@OYVIALyh+NxQdc8jn~zWceb)X6s$S-0ONkCnq+p3?C^bLryo^S7t-H*xAG_m}xg z*g_UgRhj+scMPs`lA41kj|olM>wqJi)fJEpFw&c#Bx?FlYr~7hU zP5+|IY9#rd$YuxsKw#3Vgwb;dqY%DdOHhjzjag=F{IBCxW;j8ov6(Rpo1i_?qPofs z7sWi^6P<2uy~)=ROU2BZL!^wqRa@%5D~o&^owmgbdUahY!QCE5!A_$EGVTso8{9O= z`v`yG|+=ORNei6R`BV)`3&~;m#|njutKL_LBVS|G|mO;5pqIS z4kwkf6j9bD0NoY=^?6q-^y{ZDYp>HI?-QFi_GRC)pjeId%q1!zNfX zT+5>k8%CS8v09zqn1AWvb*_JU+!zBvf&sBYmn1@+$piY@KfH;%pKg)G-u-465#B|d z#8wxMe$2HgznEuY+>YA1rJdoSCZ6MIeesg#;q|uKZj&Yx_?a*ehAqf_ye85E`3e8* zjsF+|5Kv4~ry^${yTNQc1M(aZVq9mQbWLi$$wwv%#BhFje1a%h8r#dtC+sjI@^#-N z$K|IKS%FFYA2exeCnyT=CTS&Xf8CWHt}k3@1z(F4+XgSk5`V}^wVc_$npbyo6OaPQ?+QYm-lv&XhWKIpnz))?PCsVB!Z%qviko0-CFU zPMRQhs=B4&JZ+}={6vnlOS3EjXI16T$~0;xmjSWXuWGAU82VO^@cLAKXjVgfTa@#8uXkSId{zI`RsU`hLta&&^isASie?<2g>X??iM$R zh|z?JF-L#*zpy$hN6!~7z=x{2;#@4lz=RHj3*itU44Hx=pwctVi(o_jL&N^wlEJ?k741RE zms1QhsQ&>ZrD-(+9MwK!Oc%lM+~Q%Ue+TrDzrzZU*P8w#3gqwd_5ipj*-P|={)x$7 zTw*v?JtjllyVqE8tdXJ5!rHI3qS5VSQimUp>EmwKr<3pai|scH;DXlqFD{D3>Nd@( zOT&^-WTK5oP8i|M-Z$*>Y=PtEQ5M#w8okcOUlaRF*&z8Qh>!1@gW?;PH_>>?_DZN` zT#Fj@`rTA47;-`DMfp`o0fS(i3O7fLo6-W``q-$M&tdWSYoBhV=%6jrBbeoXypy=D zSvl)GQn;4!4Dh!+hnM*F`JLlG z!=~8p!&sGMR2p{$;55a9F*6v)Fg8axfEmmoTU@oSfo9JDa17=z-6@uIq=lbKWSfUA znoeH`J}#|eM?iLo-xwys+*%iU7S-QhclBep>&oB53&3-GzYOhwH{?#+M}o@{e6mXq zk3~pN+!|#zR=(~b;oN@>g=!ri)qQL-FWzJRyC3?@iS5dQ2cpeJ-?V=1AWAxMek<%% zY!EE#zAV{qw{M5x$$SorA%GXbpgi8_eamCJyMu_$jrTeDR+kDjE9(8kXzoD&Yud?3 zrZf#brgeTOJ2zttsm)3LQn?UYNr)rgtBZ0WI=%IF7t|2*`(2`ih^0+y7JNoODcrcb zuclO2kAa1VL?V7#B?ysw4X}Ry<8|=Yz`c>FdcUtyvTePqn;LnHdNpSqWRMc^bXBslw@)b9A zOZwM9!|gI6VNF|xxxWfqC?Wrm2~7Ht@&f;3+hmdNOMd_nZC#BS}Z2-443~% z@V2&nLWALOr}}`1h1=F7m&=)*nYB%%Vg%Y*OEV_n`fDO`+CZTeRxhIG zkKoS+la6jxy`t~rsne(#O!k2zFd!$U+|KFbbfJ(?y2SPTOkQ%kaC0Q{_EA>jqHs`> z>uuUM1yb(j1hKUI5DL2ty_Z`*L>ySUOyjJlyyH2qvGsya=^;Rx6I`Ae9kn`34f`8X z-BAZqo=bUh4#AB?hZJ)w5U}+P#*`bZxsRZ3-U2=CaSyl9Kdy5@ ztn{D+rf|B|A4H{OK8mLwqnKi(i8U2oP~j}SM=?-VV}l24*q)cN4CnsTOEXHpPVg=; zW8@}}?LMp`fGkdCLZwE>ChkdgFKd=Ajs`>26|5PVYDZ;3zQ=nVKkmv)vD5M#)Hc~k z%31m-W=E%lw0A$Vt;MCEta(*=LKviLa!AOkfAg=$`4fV6$*27P!y+%xL zlEeu97s8fdEQajF&=X2KUMko)#L8FL5zseNg^m{>Q7mCNX?Epu_JOJ6r=21>a>Vco z{OQ-4;x1CgN&4d1E7^kJM>-t`I!tXFI__7oo2N#A(ieGw`J9f_;-rMKu90rAjSWK!|-RpH4Ll-*@B%sb4=v{v5ECu?k z=xl0~)RHvm2bpKjcG0}~8;%G!Rs+o;tRPWV%6GIp`~d9bwJi>|Nhwg3J{s#-eTB}E z=%->$Pa~GFXO;NJySCWr^pAJ?(TpP~are+*d#grJ#R+C^j0cinqYax2?{&>HI*xVK zX5m#ML9r}^n*sHdSF5D=zZpsoVHM7E;WBo<`782N15C1r46GT$Q@L10C!LyNx6=j@ z;3>1{fD?3WX%TdG$zu%dk7pLA!f8 z$vG4bXsBLuBf_*c9(a?@r0=1zYp67~v~l@!4%lCBN?hHK@;}ZT^}YnF?HJk9(drL8 zPnxc+O}OESW3gP*|3Gh2NdjDxRX8ZgwmlN#)ibO(+*uJTsfTgQ!&(u@2^kVF=~ukv z%x=ImDLB6WT)%`$OD-3=@+zfrgcN6EvKJxBMK)6;b-f&uhG^r(`7*mte4K8%ZfQUx z%Zgxq4mkrJDDwjrJle2FPkycb$M!7yOA}*p!Cd#}+4%|$_twa@l=}^*Cu2_qjUmfl zqpUtq;)HHG-0_H}g>G$kHoZcYQ{_)HOP@3i8|3qrlnY_J>82Cin3<$~ssr3n2Fc-V z{F&yw26?`B33|c2Mx$Y9-%rqnqzxyaK-6%Jm&2)ik<+PTj-s+7w)X=!f7+56bBf{S zB+Ol*q$30{9X60~hoZK9lxQA(#d7T*Z0V;1=Qak;K2#X8d^TIlW+OWHtg0y$S(VD+ z`{WkrN@5T#_R=JRBF3iv6Pi_&u)mH*2c32`$2XC&!zCT zI^H;u1mR2x%{ONPSum4Wvs#U3BY)s@brz)HpY|qk`Upk0g2M0C-CJ}OZ$q+rgp+C{ zWN$U7d+4IV5kZma|~7p}6fiJ+@%|sdrJ7kcPW>Sr znAXB#h%czHf=Bzm*GBb6LA7`B!fi>AkF`pyU6kwYE)kix@-b`N!19k(y6r7p_@aXl z&%tn303vjT6W5M62RZ!u+J36Mi9)zc&Vw5P$45ASgK&~c#U*e5n0c_>d^y2=5*+A0 zLZyDa7Kg^0j3?yXv`6;GxCbxcG^a^0v+}$F2uDqwJADkXl@HnslVw?*u{N>AJRf9@ zF7*oA)AVB+&2`w-t$Q151-K(AO$t-)pl@iPg;|YXRwBh!>WPMXX~RT-9YitUwEIE0 zC%(`l0tutiOG11_BB^c!lQ2j5bNI1`goB3eOhh-sS=tjXDcc{sa+E0tj{`bw&Wl zJZYHgh}ipD+jLjKA()%PxD7|-8_*rLFLoNi5{5Yq)RQ+e$X_Rw7L3{La3%9H(Y~4O z4Op62@$%YJk}Y(F{+)AL{W^Lh4_feuEh@S+yK>#85a*`(Yxdpy1$TlKy0`tyPrrea zp*QcPe=yyg+mG)Tr;{!+Vxs@fdNx;zaTf-hoMx6Yd(YuWIq^eL8R1 z5DFAmhV-uwcR-!T#y6)LOo|v!t{|0uAi@IeTj8zY)OD_^l-%$#1F!*qih#Pum1ePIVuCNTbR6@#V}ItNK&_ui%0V^CEev>)@+#HucKD}%v*iGbs&e&d8jxQVWz_PKWNh|R zYdmG>&5LNPBTHLnAe4L;z-#-80qtuK*vo4R{KW0_rP4~E=Gx_jJ_Gvb60RqhZu!d5 zDZ6yh_M5)#@>mx-P>DYiU*63VYE~-oikzEBc<)>7bCaGqhRsP1%eMo|39q^$7I(Yd zBLuue*7yheC6@-K$e8IepQ(_n{0X$U{z3O(YEvl1xJjXnX|c0=q zDngtQW(<>cToAliA@c5%lbMZj6#8iBJ9EVm*|D3VK(LUBRVRsDXwi3TX{bEFhwKkQ7diIwfYY+c&&4Fh`KOpUhqdPYfIs7=cH9Wr7dSGLvu`N6l1{s z(lBK33DqkhA7r^IR9dkJ-HvJ=%K+K!rMj3|=L{D8?dK!Bms zz9DR=%n2@!;x&4-=GTlDuWcA~#BEq5DfzW9h^SzRC=?83?mR76ltdoX{^@~=NK}8I zM1y^k>sIOaaN#)T=#3kVrN__g~=T}$e5bYZC}d-o9XfN841=&Ih+L+fuo z7AJ6DV<1J%(|FNCgn^7PSK!A7x>7>IM!on+)F5%VM)URIGR3AhvnIT1T}0meP(!;esG_ec2+U}%{ILU#Y?qcan%Vv za~;HVT>gA|I^{T~@T`w6jeC{Px$D{HaC)J>8OtWA2isF#RJJ5Qb4>WGiST5qWMdaA zQ=32KvuhFpy=iiG{<%|*7gomkKIDp@$ta)O z;!X1>0hw^Nq1(=?Po>IlxB@XkeOOS~8?LJ2)sk{)5!5IvIwFR6b%G$Z+I2OR*aEK* z{nBhCLsiZgh2=QP-#l}D@pF1Tj z#GT;)4&Uh`EBv)cdNIE5Av&hY2RB$6hMW`7eOe6ym}thZd2A)n@PtsR-l+@(u?2IG zB0KSh7m2x<{>|Kkubt|aouC8X7NV>%v0<_vwkN zp1(0uE$p$p3~Cfzx3h!ZZ-hJMEt!Q)^{-U@2#(99^-s|1Y8lXyKV#{nd+h%Ewf(q1 zL>2gMEq<=0Rxmp)Ri9}gl*qx)^)qA{jb;@ymY##7tprG0B`+_*#l(J!p;Ut6894iOo_{rG$~p&?G((Zsl$mhmXCH@*x~D!@ShtGIbAGOAd2)TT zh?|}{`GrD~Lz{t8bj@E0dlKo!@+VGl{a>iI$!ta4m6T)?GPKUK1=Lgv`6{wz>tA zw_3@@+t3NwDDp%Xb1L5CZldaMEA=7?!&tKO^E<;s%5@ftvQ{PqN6-#AjBTQXZ?bEW zUJbTeyGrZkKJt4M1=vRYdJYky=!lPH=EP#Ty9pD z#o?AA-Y>PNzlB^xjVA4WnJ&3?s%Pm!S4q8lWUUfCKTUqGc^MSi33%FaaC6-^Yrg-_}0`AsC`oJA)s6HEf`KtR4&U#NQ z9c&ach#5#5SHk&vzs>WlMrC5AJQ`a(J7e0XkRCNJC9BO2tn&x-@xs6^j!EPsY+SkE z%)8)8qi4G7x97i4soJo2LyKde+=|`LOihPmQsT|9X>zH>I~^k9?+hlRD<#8PdPhy> zj$xyh5!5W$E{%i+?!peeLP`VpkW7Nl|1HYIRVS&^k?byPk zSLrAX$o3w_i57@7sdsP;ZtV&pp0#)Sr9ene@fS@YE=o7DoL{m8)|Sh(wFJR|i=zW5 z)8se$E~27{e7hg{o9-ihGVyYmLMFfe9j>T((l+1qR>u0!8^%t#RK&8X-MT+BR-t>- zuhlo66NbYF8}8_7aa*@qkyRY=tNw-zfWKCD>cX!NAKxrM(&Xp zukE0X1e=yp|FXHP4zc%>8^C=t)nNYm)Lu0^@l;37<-fV6JS1BeXz#D*chkpi9_)!5 z{&uF~cX>+sbnM_T8pINazyky}z%SUe9p1R8?079V;iS4s@jvX?6)?WWI{(LH#Zd$V3wa?@8YPHm8 zG3&BhSo=YcQ?@t&w)PCO#>R+2cTC82!yG+)A5F=_)Qrhv$>Hg5wH_f`k=JAku5S{= zrTJ8Hw21{fHR+6$JPTk-YkQeY#Y?EtNO5GX;QZ|%+2&IyEA$p?;*G7}VYyfb#rX%a zoQ-|8Fx=K%8%;FlZ-IAGKc@FJ^cg7LXN-Zy8y{J!7YkaS<7$TbxzouKn(TIGHbTrX zr$xS~>u@GDi#Q8mAS<4)By610-88@Jw$o4{Xm$s4K4gewke{CKOwWtf-(Z?jwi*s? zd~CCC#1n8)-4c-g9!KvPHVrjCztrLH^nJR%$r6`c zwfFN+{9z)NqrvKf5>x*VcY6yPVlZHU9-W((PoT6cyJ?x6OhHZup{Tr&(`Y7_eF;$q zSRAxSmD;L$gJ>rPW21+olwG*Pt_*|5WXt^yx}zbFzBr6rG11)N#HR6C!UNdJePMLz zOR^u&`5955T6DRIM*^QQD2?CD=L?zh@+tcF2v$FTE-KmXHjD(XKO0m1l$=K0w8_6{ zW%%EYITb>WW=Hf}=lj|r>JlOg(bBqcL`exwGRDZRE~=Xq`OAOkyC|J- zqBUAuPUinHeQ(f2r{q?}XMg#$Xmw6_e<7&+5}+ls+*; zFdMyqP2rpVrhzIQe`CV~O>4*Y>Eq^wPx~nV;3J2A-aqB4T2h(;U+Zu&ld8kf5FP{aI|TdEEtQ!QAIhFb8< zLMdeP2u_@EcT?>5qp2oan!25cJ4;L#)wedYn(C{s;!08|eUN@wJ=Sn&lO*5U^zfzL z3{oBFmC>C_c}cz~UuyN?k^6Oms*9QsMynY0LP+@@ZtK@@T8td}E2Y(yjSNInU4!`d zWbZunF|*6>Wv!uBWh6DV0+fY!Ttx4d3sYcq%bD=(I8osgb=RpU?dR=pQT4l@_t|$q z^4XR(V7Kt#F& z0uV0qCp)t;Rl2zmmNH^Mfm?2XhBQTixvP-8Jj!=9P9;KtVY{-_*mJsqHUDmBwIQm% zRQb$$*XvZiQe*uNfrHKfI@1w^Z5K{L;^Ovod0n>76oVpym-lB@W*C~#)FW$+XyH2( zy&Ev_M;@eyaHU}n58OR5h1GHrWrKkn7%Hua8fSkIYzRF2{!l1h@F>pyP2WBiB=$4n z7YgvPnl)245BzkRaH3OLic z@4n=~sM93sIScVZQmEKvhDVd&*!4!}Df?=wR6|@qSH_Jm z3)TCHAS-_RAK3M>^~#Wm)~8^rk*Uz0fuyoinK)@nxk|r5G*TgXf1hF@GtCZg$=L&Xv9o!mYX+j~PhvwIld%QiN+;r_;W4aV5u}s2Mo?Yr ztHO^AT2dQa`5O9kn74biORww2sL{C+2)(a~&3*Jog2ndV*ya%F8-8TXnGB=cLbLzl zrw*)Z5R`)2=X;U%_aosu@Hl|+Oc$g=zKd32o{Oat4L6~;8)pn61;nC1P@@tzihBL(t)Y7MU`xpBp^Hrddz4q8x@vaYEQ(eO^)VyW~&iS0m zG(`-~X6VVD1)`;|X9{K;z8t8MB%zTqJv1qTcql2Y1@|hL_d|ml;iH;}sE=_UA#Vn{ zJd`XeR-f?O!p%F$x43npcE>a}-Gm-61!q>eh*5rJD>0`zv;XGK3o^}|vpzrcz%gHb zoVYW7r6x|>Sb9FO@Ofi6-3}YW#`Sk&@SYFWWR@)BX64%UWU^y!Kbhj>N0+*c_?cL% zde0jafNnsh`z2{;92-ocd=FJi9hg9!TIeJs!vE;;iejURVv4P)cl|~Q8K=@0se8~i z3Hfar*-n0pME6XQTD-Oy#OrP7Pf=Uij^S*cw2iN6eB1q`CpHGaPV%Q8OK;cdl6OyN zRpR@Ha=Y(TLrYJ_sYceTtm>4#)(Kc|>G~6yI;%U}GeZ;v5AC9X>N7YY#z|zvm!2^G zaN#bzeWDP=VSajQ1pYn9FQv4qa5L;(HDFLtp39fKNdI#ueoxf%RgJ|lREzJEhZ9w2 zXV&jFizOn{sv8VsqB>cseXFh=;raKuMnCK)y-jid5d|t)g~_8qSTvYd_vO#SGSR_o zf77lTWaW_y2lMBev5u=07Z~Ty&~s#@E9BdJl}v*fCa&06X4*PDDq_eV*BrpM37Qxc z#TVHCy+;v+<6ax_82j&+UfAeMx7t`6iul|pNZi`tMd-ymebgb6w4UG0HZ4$d6;;iF zXCTzY9z+;&)2N*ECQ16osCFj*E@C*DWj&LMIj5zzS05{Z?eA>VOHkrSW}`10&&?E* z5-#BVGE;8q=cnj|+|_^=4UgLGPH&I6yV8 z-OUP>^xL(%i;u}!%+@CZa%8awtl}8eD%LM+pMzlE^>g=lNS_3hzusr-%qdF=@i)Cj zz+Ss?w)hl_dc?U?b` zPjNjG9U2$0)%w>Geu(QxcBu#>*@N1VKqYOZngm16D@ydS$og=bowT>^6GIkbIZ2S7 z2(~pMSgX@`-Lu}6I4L`YRQw)d=|0McKbp3k?oElVa&K1fP#2ob9>fP_87o2EW@39h zFl7@G_E@3&U%9!|Mf(OFPIeS+{$~ozS}?$}JB^10^B+RbL>8J9M>O{0DBZjsMSK}&Z?mEN{7V{RsXn-mA;%KbcYy}VdKD0>E!kq_d6@xSJ6RgT(oa1Y;f5&XCq)@7cJz^ z?qE(&*{+|!DgkDr=d@~t^eJL$4PEb>!8!c0Np1ehK9DJW?7B~d_!SFGhVd$YAet1C zwC3cN=ufe+O#1He*u!FRILl+c+<+Dh^BI!eg3Cnh{HrgK5Nh)80HlS0N8=HcQDvtr zg2oAZx!}r?xfFZDl^C35;TsTRCJ|Ca5{MYysT|jyPD6R!v~WL<$CY?0R*M|VDDuJG z+{G82nkLkd0r9-5uTXv!E@zxY9p^8NttJo@a13xRL6my5HmUw%;ZfKGyqZPM6?|Iz z4RvX5T!d2d{lhp9QT?AsJ7t$*MQK9pAhYiJs#AfUO$QD8kX`+<*TPhglSYXKqv_mw z2KpP7yk3|>y)F)Gg-zRF~oIv?19qSFLNL z6S+`ptr}*$eLe|F^}e=8TA0glqwhE!VxjDgJ1eZa%mSU5&TP-R2ELUG`Ngt&-Cdr( z@mdTl73s%9v)d(|{MdE03mx2MDHVG0ZzMPiR*d&{asn6YV@DGkvNk$&vVe98Kn9EzHgbX*5MdCA!fSTc##tgA%;_RXc27 z*xcZ)f3tOqWnI?+QGdmX?k&M49zJ${pR^zX!0>vQa*hLa zj;7kNdlFuji73y}&j48Ek#lA8_d*%=)~J6*94X*(RXmHI0#tGy%N>o*G}3q+ZWLf) zVF`Ux&_Dznk_-7J+~wN{^ScNrqTE&O)(1veK8RnJWR( zLpO>?@V#R>-Tqs}N(uESWix*n2g&A|^L4Xtx7%mhaP=~vp5yU!24#K`_&UcS_oDa32+$q!#mz^cJ%_lq90feyOAT*Oj@k4gX2qWhY%UV+v zJhtJFh(aHigUW zP8?$A#eIz4TBJ;PC1shCQ92PMRADJ;d)JuDOi@9kS#n=pE^QVsHSG9bj1)p3 zQDtr_GzC&c;-xwJmUs{UPM!h@y23b@Ss1r||JY)`Ya3lBabUkb(808)+P{!`p70%K zH?)=jUde`ek>nl2db47k+oX8VLu<0BZ82p}wD!%)4&0lxNI;wJ*L^EP3J>KoX-xAA zX74+;ZGa1IA2)@H&F|0*58bSJ7qH$4lyF#s*yw#kUN(7tcs%gg9)nIhW~#dt2#S`- zkbDt*E=5u_|Adq9(QAF+UTPTudF<(wUs$}Z`SJ=dzC=U2nM2gPeVEkd_`vtQ{LlTo z%)^_v17g^ylVjin)wp;;W4km#gTVZF0ps(g z3#$jV1;ITDo?~E3^>=odB~TMa=cPXK*0bVI`fl^j<@@FVOT%**`8$;0PpbFnjs&go z<8JlUF4O3E1zSrtd)-2*gU%rVyh`|Lq4z;fosXAq6aaOnbw)5Fv17`dgcKY&#u1BB z`21wFj$o*#(|M|;=3y#kbZCyIodVvOoHEkm7DY@OfO@_KywK!pY06`gfi?*0z3tm) z)IyTVA6}L5M1y?S#CBEX$lD>eDZXscuQXKD;jopdGL#` zlz&lTS}QI)7g6?TvB3#0Olh8M67O^cpZZ{pCQ$J(trtm_2b}V0E;#n+oFDFZSbW3$ zYM_V08ko3Dt5fh$J&RwnCZp$6kC+`J(A)LYKr6wqn4F)kcphGV(t=f zeR*qJ?%H!qI+4xL%(JYQ7N+((JYk0Lb)zgKeUpHl9#fZPL?2bIJzKns*Lqp)e$rKe zO?S3%G`(Wl8P~?z1^PU^8|?MA07caEa7W2AR+gz!S-G@#g0owc@Z4%ZE5BND~gd>HYzpXU;vkYRjTv|SD z?(GC$aD0&jr`I+!?KXg9eE(N+ms0e!bN3lnk68Cg>q}^hk-4_V9}J8Z^AfdNixW=` ztu&b**R?Kc3<{WT{+++D29w1|HFdKIuTH0_9S-&vf{}c_m*y&S31*~XiHTaL(*o1j zZ~~aHW>|56GZD{MQ*?My)cQ_Ro!a`6-B&QqXiKE^*b!F3CJql>9hPr+=ot)+B)IOlrN}h1dlBu~EF-BKd(wN_ zgI^#$V8rp$ay8pkqLX^`EXcqpR23-xi} zCq~ovb;n#%y)tX4!2xgls(3q|TqB^8q@OeKC)WvE&EE$S5y94BL6s&~{so?o8|Z+h zWrBivF)WjY0NpfNS~i*?_FY zlM<9ol$6pmzhE9>j9)N@;b5Lr0{9=t#X{Mb=6(cU!reIKS(vR&ei-2-oJ9km@rR6C zd6+2q3=CKOjC*66%*b~x&?F8s!}4o|HU`pH^{~9sd!<|CC{OLAia1<9&h5u{71zEa ztG@a`;Rz}eQ<@K#H!9phzRmakviC~*kl<@drg#Z$o3x_S`|7?&mryd^wFMC)@Nh=sdce-Zjv`) z<*$)!JPKXsAdFJdC!OTX(ApO=uCZ0DB_ZT81O$PIKq1-vfNr}2ZL@xat{ea^=d`3B z5>An6k@*-YeIbL^b*0%2bbbu>hV^!9G=5bw15cVEgz0sGc#ZcYgTi~@@y`jzlTn9ahv*N6NAWEXL8Ksn<3)uo zBdnfzm_iqzuF$HF{&l?1$>kw@I|*n4SRN=hal4))s0)iR6hMq92>@E0n!V}3|CG}j5;u}Kl5ReV_refppMMefWG!A435&pb}t zc|2?2(-24sx%>CyS-NIjZok|cQK&%$&+saQPSF4qNWpSjq!^2JO1XA^Iv@d;*lACFeWjuxb6*R2!> z&xxj^96#tg3O22g>NX0dR7UPDzX1B-LvXz1bSl-q({&d~ca4GYmj+*ytOUOE)<5uM zw2c)zt`~=suoER@T|aeviV62CeZ{GRNG1)U;ha=uIQ~zT{~E=#S}o$z@d;k})4UNr zRiXX?w{oP0&pD9qc|m$#6^u>0ub?ZX2LA)qu=v)W%-RqKf5-{gLquA>(eozsB5;=z zLrYZwpe6%bJOiyDii*mP zxtecF%y=naqA@uKeQ!&WLT?Z!gL7Is$x@c6~vO zkNju9n0}V#5Z+|F|E80MF{XQnqLq)+?7!73Tk31cXoU#Yhsr6k{`zT}o{S6~R|6zJ z5h1^q^I8~yo=yoTZwDY2BRfiFS(%nY^1v)U+sd3IfJ*qJnPro=#Q4KCfjJzy0iPY@`jF2@C5TaDte(2x)u|DB7jvmOFMqR-l=j{eO(Uhx{TJ0L z-hcbGHs~i5nB4}tz1){sLbSc?V#G31L2ITs(QK!Zq`cIeTQhGFfg5~*wLo+C!{jB8 zBP9TsZ_K&sr+Zh(O2he*Vww8-(dki7WM%@_e3)$eiU1&0zUln?oIlK))7;1WtzO*W0&6;+*exh&Ri%|(kY zJ@vEx5dNTSH!BMh864TqFt0=PtwO->({;Br^;|y6;d(1GBRx2l+h|dz5`69rmN!HI_r3hjX#|i2f?3WbcGrbmnA;v3ykz@^DT-2N9UWy_N(}$*`5lWmyyjE= zqtnBwwP1f~{pn5*g}T*T0`~xGm8*7y5e61@!fGeqZe>ckqASPDqjjv*6*~NBvW59M z7g!9es;}SfEhHI_CeV&bc@|(F0{AWxMueZy?}d{;@N1Dr#Y!$MJ$Tej;*JHvK=HSk$m* zxA~P(j0@w~tIq5qWLyvX;!xQ7n7ztd`a^^sqrp)9lJ!K_ub9UzKkF@N6f(`{Youdpj2cVE zoEEEN*#{-0$kap#EW|!@>{M8!MwcOQXrQv&3gulTy>RvoE|JN@<#@=#Msca5^lXj9 zum{SO$%ts;-F~;kCW_Wv-3+{xe%X)Z4$g?wL)QG7g#lLzSMg<4^EKHqmv6dork11- z6B^K_V~*u57d$>Psd8{&Ljrrg8N2iOiAfdb#bCd8s?Wz)wNcuZ0Z=|Y3KiIrLA~J+O`N4`xMa*+Ux(S-a18OAr|5v zCp{-5_QJfWfr0drZ^6d!Kk>YS4~~VW956_B$4|zXpL-~Xkop-Xe6S>9;24)AQdn$6 zn*t-tYyOnIw_VN4iI2Y(RQy`FahQVD5T&@<=k|#H^PAEd`oD5EqxO>`PS|x&!b+%BFek0F ztGB+WFf+bMIKyyy>WGh1>5H!#;NYo zgqvUUQ3mVDJ81W>p2&bkCm;CNyZVvGemZafLc~6chdO>-=3sC$8j9tdigs`K!`w+AGB}j@fbnXh$lb(vY|%XGKNG zyc%W(1)GykIvFr(q>K&hQvbB$U;-;F^p<`XdLWNAgg5B}Q9w_ToF61F%BgTqL~nFX2xy*n?UYAZggolB?;5t1eqPPcF4S-MH*-FTmY$jm zmmeMl>)YT}QNvv|{6EIt zGOCVd-4@0nKycTEySux)y9al7C%8*Ua0#x#-QC^Y-Cgg>yZ1ild}Ew(zxxALudeE< zuCAu(n)7+)46`4D5!1l3?;G(%OXuv83-H0TXRR~`irAWY!9?>c;sB+C^GzEd(S{cW zhup1Xl}Z9>S42#HbN2UJasO%n3P-JOIjBeMfL&|+$jFOws_r*Y%B7spn@%ib!h8s_ zo$ilU2#)qC)gY&heXt`Bto4zn7PRt+(qa7CZ0GHQiRS%654Eyuw`)vTBE&Elg~}4T zP+;<2*+xJZ77V{;0MQ@=&63x1dUO9O`3#KoiVc3=J4AEUM!H4AC}drzc8#h z-)k^mNsNQbTcsL-%y4!$Rt=cRuXR#yM_L2Xa`+KJc%dUlT?En`(9K+s+E4&g_Utn# zSyJ>C>bRwUhrOI|Fa5EW2tri>qb>HB8C_5sg%T5& z0LYs3Nb>D7;S|J}>h0N88_v%-7hGf8X-LS~&_Za(>r1g(!x|KjX^@i%C=Ik!qd9!3~`N2rqY=Gm`0&ny_P%T*OXkFNmrXm=l z``1FL?swx3hCLTAk1A}mVD)~1{3ESGM=~2VyqxfEBX@{%TXU!PGw=pjSAj1qRZ&7d z`sX#uaoRqiQA9^=ZjmN#mfUd(pj0F(j!`F|#Sfg;Ad&C0E%GE%4ibkf^JQt+3xUMF z?=HHl$uDVQ?ctC4-N58T-D?`#wMgD)Zu&%p5j7D;Pt&;M1r7AcI`w8sv|F;WNqN!P zi_%J=`1Kqi{++yZxmAaW%matr3GLrx86riJ10$maUWH$;n=Y8-xfwhKfO3V>-y>gF zzkl!R)7%(&9C*>!tlmF5XkHQ0KCGoStujs%D}40-mZpmG>o0b^0^rl62aSyFb57~SRvVQMa; z49$$Mb8)lc%lwdcbQb5x5Yl|jtbs*N9htp?ll2W-RLj&BND7H6e03>41eIsF=zuV) z>zcxS;ZV>ouUM>pdrY`}+ic>RtOC^({OttI6~v<^@L>{ zeNh$s?m#&NTGAukHOPuA7&@?M#8{R^U7>&;ELyP!3T?SCsujMIAUz_gL1VpdDH% z3^Yw72AbopNl;BiPt*|v&K9VmLkvBQhm0wxDUAi9NaHDtL*$pl|rI=U7U%bKjn2_3WHF`I|z~%IkgVjj=_N#gKr6Nm`R}+WPd$oU52+wsa?; zV*%Es!etfI07-(thQwkKII(U!3-Hs2ez!I$L_H&J-{e2f9oSQ}I|SdpgHWNZALI!& z#duU{2772dZfpI(-k04Wfoj?zjp57JB-7Wy+Oj2)NEN5Cl!sJaWdP(AKJASlOpD2ra z5HSTt?6KW~EnA89gxG2ql{uUuK89y+cp+~u@Js?@nu;s2_j)Yai5lqENoW?FcQ?Z| zz`k?t7D!t!P=2~BhxB4FQ2X~myZ+x=Bp_Gdftp}GyRTng(~Cn5AB zayYTUv6EQF=~7clVidt3cWiep4#|%Kz6G#v8o{qk9$43pQVZBl^QvSxox1By+vJjh zS;=uA`_g=v3#QKwVohIGlzeDWGP@-sX`?yc9nB=U8RZRCrWERZp+aS46l8ll^&}C? zWJgt`z@9o(q!inn4sn}bYIlZ!Q3BzJL$SYT`n>fJDN+0fVt!f*S=$!1(e5Dqau+AS zEGL=#1B_8@6MM3P5`$!p=pquQ6h7ES08$>_=JzdPqyZ3hK6|O}wmM%HgS@fU>j zY0#vo-eSFgDfdRtvXzHv79Nw}R48?? z&7M2H(<@Sn2v}UnaDSm6ekNX8Ou@08ADoKWby98{~jF?yycT9E$=bs;0_Q zIZyO0VhAerGH%^snA?#u<^qk`)Zflt~^o>xD-~yt@RBNO$J#JK=3I-q0wsVO=B`6_LgYWwBcaA&`lK1?vt= z-&i~;;LoYI-qkh8vTn^5MywOmiy}v+waq`v8PE{U{2S!XX7-Tk-U_a zDTWrHuWUF;)hY^crbWhI?eiN)E%rPu>O-)Jjq@4W7T(QhSiM!=tju}NJ!v$|@W*i` zMN+Bai4~r9tNx_mVSf6Sv_--t#Fu@@o2rk8`OUG0XvzAO{2jZv7}Ogz`XFM7v|_#y zu0l{0C$;YoT3@`LID{UOy^G(Y$7vG5iq98vx*owgfPQCzg$`c3a_YMpR*zW3H^aCw zFK=%h+GMAr%}rn%=%dX!Y@5`5nfP{jK+}&-RiRLcw8ogI1H6O0qe~5$$#@NyX>Z(p znkg~yw?j2bm+5z|F)_wS47!(}p4;*u0g5Nu(d+<*N{12BnWmOMQh35NaL*gyt0V{j zb8di8=iCi!gh+tXt^l^9=Wb`e5ONe}HP6RSjd-L%F{QpQk-8tb+nH_}G44G>>l})t zLPo+SahwobnAeHoPob~8*C@~#){um@a+8UFGcouX(v|E8ZxX&)&$9{gmZRyEu=B>M zl5KP-1_(2t8w1e-jTXpd8!<^>kOnZ~Ef=(zCvF(amVV?tC&ME*L3|7Z<&ZZB?HT4g zzMXoH?O|weT5M)xu;0z7OBYXtfTfS)HMitf&_Ge9lJ1{usAVpC0#cxj^N|ZKy>z!; zOBV2NmtYHEJ4YT-b#aeN9ojR97Nw@qBDa9iqhWAiq_@@pa;Bni%HBlDw(HQ@tq9Y8 zUy@<~OF!!M8@wmvp_>s%1I}luj~5a#S5?J|<&EX7Ki*E~6i(LQP=KoGfFpI#1_!FS z-d-1qqa?Lk!)o6)>UjvS{GNH8?m-?c8Rh}<>j;Tup29YrY8)4mfRSfm{RvKpaTu+y zTP1KJ{{~~%7&s=x4s4&-f?*<}k8hKIdx=Efxvh*$o-Oiy4WG1`3Z*;*N;(EO%Y%E! zMvH(ADW8#*M)H@%)`NLYu`g5u5+jyzQ=%^?ZlM=s<|oZymK62sCH zOYt5AW;TVO&Fe`Khen6Spz&3K{JbpIUM2W>;jBYM1KUtUs4wblbTzJpR?vG_31k=f zg(qI=mQK~Lm0?RDEB8ot4Z4k)(46YIZN@b5e6~CaZFy1qvmitkAN^YV3iSlaNQ8W( zI}05=Xo3@sU3$UM?-(rF1bu_ngUa$K$-aF_1wcQMzCEtLul@)aL-6)Qo)F@31*D$c zLnU08hq5KWC7!f?e3c8nL-i0W5%3v?w8`Qp#E++50R`z`XRX%kaX_%op3%O}%WL?X zMJ;e2!X=rf$C)5rt$lOv#P%0U1x=zo6}ju|fT*JH@L9o)ad&3A8&EqqZ(}?yb0y7I z$2qv;v8`*bh!LndcVL$NA9dxxS1mUp_ z$S|cu36i(>a9>5e%>l(MuI+T;m}{NFG=V6UQL^*LgpP!a6I6V;$jjNVa9`l?R|Uqe zLrK=(-n;^oS$KBV+H_+Qp1>Xvnfaalg(~@%LBu?hdL5-+W+9usdcF)%x}Hl5A^DK8 zvN;YVkz=Cvqwna@uoxQ*e}xs(7Poy#6N)i@rBtl~2cy(znhdIp6q%|#7bgMA96TNU z4Sl;BTdf}s2l}CAOlKy)S+q@J84poRH2#i)m{_R`-P_$TqcM@%97NAi)2pi^!1-iP(wcRCE;*N72yq#JCHBEjW!GNcPeD?tyEp<2_Zo{LgAN zoN`Elms3{-DD#43&jVev_9!bL({eDQm_11H^ zRaRXgKp(##o=n{n1Zd5X7f1AGg3dUW-h|#{dJse_bMPt(WzY!!03MS}1H@4ehJL5K z_@|8SoJUL)46EE#h%T7)-&i>)>E#-mNOcq&GU+(e_=AX%> z9Cj!a6$r}d-*CArEBwDKJC7*DaN?=|y z)pt?FfGX;%cMV4K?9J9$?W;!NLlE(9wNbzn8g-fBB*;1bhNr~IkHo*SU==TtiZaps zS>bf3j6ZtZfhlO*Hmn7FjE>|3nzr;AJ$I(^|-fXxeamR?t?7&AuISt4*TU6YvQM>l{nbV2u-Mg zjy8ps@?Dwp#(8}U=vaV-*kMD^p9es@DUc1bu)`#Z=Mue007|vWpu3PDCh4*4#Op#z z-pdpdJWqO1S%P14)yIh0|5`z44Sr(xx$GFREv+Z6cEbTTN0=lg=O_(@vFEZ%ikS88 zh&}>_cysR3t-4M~qC@({B?hwKiq1MO2wQXB`H1$dKTZ#93i{ZmkyQUl@|;1~BA&+4 z-v5DMO>72oJc>hevqS?FcJXb#CkJvhsy_g&v^u%-<{&x16@(e+p`|M#lwe=Q37b_a zTdCglKI?`Lg!{sFsjK9V<$=qBM{JPbIUQkq0OY!Bj<{7oC8D3lr1)s!a;YN1vF$@Th+lfKHHM+CUM zV}V|Ro!F&b1E#NUvK2a8)R6+SUhrW;oH+t(x>h);I(o#`cmYP;TvT!_O_J3N9LG%j zY5|;@QNd!d=0cde_$gIzSb+Ru(@x3iJ^_&MAlILxrMg0Y3c`Lig(V#J6Nx||LDT2J zL~6Scz_DQ~0CH+{t56$D-M!dHZm(_2`~ zH6Og7`}oD}bz(K}hm7mij#0@(p0YbHnML%nSF;!<_~8Lg-@@p5pOV^*@(|oMOvW}m z?Q$?n=?DFY8T9vQ1KoX=c&Vo@Y+HPpUKFS4gI-=-4j7L7eYX6Ln&7%yyW1c)vs0ju zpvNqNJv?_g3L?$zRrc>v?%>sQO(cc_H9VOe^QK}38nVv4pAm+f#pm037Pj^+ywi3( z(c$AcltSR)PDi+&@}MoXE!Cw_;kyp-ZkkQ3amEIZ0JQbluk;fj(vCw?01YGaX&cnR zX52~xV0z?Mo>k=)I?C)e)dltr*^z8K5kU;L8wa?g!9sJ$suf7jV042xj>9|~(m3;= z8of*R(}M%@5UGF6Q?F7N{B=y!UOgB@VHo;ySzprJVK`jJP6JfQ-*kVP;w{~_59%Gr zA=`TLXJ1?*Z!z$1HCunm$^XW4cSOgIry7Vij@MNpX37wbrMAVJHLc|bsDs2D3FJq; zIMo_!aD*4WkcNOhZ>YMcL_QYch-cgw(8^wBGi= zsbZPRM`AULtMbsn37%hg8veHWecmZ;0#s~dWXYAR(v)=;^7ELbC(>XWS6WPa5aswB z`F-5R`P&kT6qsNg(6mAT)Ee;I=^YDz_lOSs8Ju2~=aDN37GHe}7{~6X#)M>bH|C~Q z=15T_Rj?L`Zdi134)>Uzz&i&W%(*M&6#NqbF2x)793nMHD>xxr%>xp{7ZPEthIgD3 z5N$CqWGGyDk_ULrAfP*BS*&>|j(5bU5gf>jc^n0%jtf4cNJGdA@#HrN`mA0)in>p& zAOG{ZxNa5+*fppj>^PH4?C$R^*@GGuI6MyTx$Ouf)bNF$$gfCFsTc3mt&XNNSaJB` z!1GlRXaaa>YW`R=R3v>P#S^AJJc5@A{Vi-dd-ue1i9j!80Sh%&P(9rM-ck3LmMjCS zn{Cxeo}vv|ar;#6cc4-WP?c1&i43R1*9&;#!*Z$Cy&0|+>|gyj;_)GO9N3>cRUIW> zP4NRS)jMuHoF0yDw#cu;7&A$xr&VVYOi>A@&M9Mn7nR!zDuy2-sqTqgnAZ%*Eaj*I z>@|g76D`W+2l9u)03#ygN-6-h9D=X3lPn58DoCL}m1ilZ4?x)kp|Rh+3s|ER;_#eqz$}Onu|>0n*e7&Nt}0<+WWn;R5IbcfpPPSfh2_RZB-ZT5 zlK2SweFjd{_=fE>a1Y1eiN5VE3Rf#JLq|a*-lB;5uZInu11UXl=EHx{jcpJn=ygfH zFGERgAb>%S@ChBR z64GYXFq$I;NcgN+C9Hhm;YZaz1jSEAy57}rpeGaLw8O9BvhI(W8{kCL9Gb<>H*R(D z!Je5juOj$}fuR$OhL}RHYzt)4g$^i()%5RPxDq=5YWJPT_aN)XZ+2U2O`le8?z4%V z>^e4(`bUzlM^B04$rY}Ib3eyhscT`e8_1*af!W1lgeaZF+Qc|7pH#*v3SX>+OWbT~bLhB`tkW8@YgYT{AeZ-M8Oq^s(fO;S03GYrCh*1}t zpcDdD39gA>3L_X&5h{q)fpRU|_3{P!HJrtrIGkfe>mtNlEaIUpT|M^9koXJP^>7oE zxUEV=fm_qz^Ls``E{}&8qx67+G@Z@Y^=^3(QM#VHGg81|yk5Fd!&>+w^B6b^MjzW^ zp;NtR^3MJ!J(ZJWbs2&o6jxSFqKwplhUBSFphW3nDTC{kshGwv-!Hl|=?1gMmBIvX zKyhFFMNv158MrEMT0_0vHCP|$FsE?V-x+}0N01nt=Td1fi*~>_6y@w`m5ba2e%Ub% zo+7F9L5a7mVBuuyIiCPe{M|H#c^iyunLejKuD&c8=}uN%FK-4(0-gs@(mh2f2eV4u z&62dMVlyKYMX3EEp=tMp#H9#Q5~LsOL|AvXZ>h?-%ce((=X*v2u;Wvd2DVOk;~8?> ziX`y3AuB|3W>af32j>qPm=@~K?0K72ZRrtlH~^Zpz7?Vn!t8W>=#Tsipp;rF^ev>| z@Dnk>Q;f<8+{FW6N{`JJoGaB3I>$?+)k8@JDGs~YZ=~w4MNZ5EisaQNk`ahZaD1ab z@pvtUKhRjU;pg#q5~fh~k*%?L;_q?OypZ$}JXqBDVb98=aPZOj@iHGah-ja^`66IJ zxXH(o_3(7}_I7n@5448@+MP&&_`Sbs_&=W9`#+r^e%|#K8MME!+zaZre_RQi%tlQN z>Kl9zf36dDegN}3I@-M6*Dr53Kb{8t-+o{6^*ust9q-Sd`aeI76Lwy7`Q5&_f6jew z7hT?@`@hfIe_rnvRoxPPPR3>XyN( z`o4y}g;jODpA=Q`y9om8AD7wlf7~5!ex7V!8oa-JdfcaWHmGDD%-x1jT;Hvi4U~lK z&0X@pU(Hv!c)M-g^BDEKJ)drVUafOHKeulBK8_b<3qDtT%=%}4zLXJ)<$UfEekzrN zj0yO!ehz*dBMSJu+@0rt@X_a9_iVmg#N}O-eO{`(j)yG*&+59<=jB{s^B32L!X4_@ zY#xE@-l9#{>d#g8&fvk18Q`%mtpkP_HEwo(;WH)1{<9`J|rKn+v+bISsOW%&yaXJZy_&OarT?1 zgfrT=xGi}PPai9tfnVzEu?jvQBNF^Sf6vCJ4suLhezIayj7#-o3$*#GGTkv(qqL3g zt|Ag%7@`X#8em&wb`qC^Ree5o9eK0+`o3L#92=vo45lK+F)X?(|4tn|L{we~Gg_$1 z_Pak>{3L_#D$?nEPq63LzdwxYeE((O#c+B3`>_Le+&Oqw$n!RoC)StueK*9Sr z5921E)s9}!D#CL+Z(iF`s>8=-ujNqU$&kP>MVWOD6&TB>bHm$qSe*acAmq_yWgO1Q z2bcp_GTJ%qWcG%P>qfipE9B66ruw!u+{G@gX|zE=_D8dPfL*IV$8_;Erk`OT+vMfG zSQeV?rOe%Kqf@I|1Cr;w^ef5&iGH&G*8cJJ`Y0yb!Rlql%XMXqd*_4x#7T^>;A7_T zZ?A>V=G!?D4}&LZ=kEfiiw=1sY8_{bl?rhTglOJz&m*UYL{MA}qcnJ{BGUz#{#%*8 zE4`}=_68h1{uD_Cr&AT%&x8Ev= zZQQ?n5_YnlUS?ILU3+;ZP_)xT3>l_Cv}-*@AYKv(ERn3ge=*fnqqEZAb+#;m@O#1B z-!olOASAf|oq%_*SB^+~DXu<@TNm?s-M#_$-ZS}jpz%4&hti^vSc{2z;ZfkX=e?Wq z(Wl`F_*8qX&hbX{1)=@)39^y-8`Jk*k9KG>cn+<`EmvF-=BQ>+k%G z=in}dz~|o{{<``YcNsC}?r2cWh)+T}`GV&#_|DMr@)UO2QP5WIq$jnOpS8CU*NpL# zzoXp;p~>W<(cpbMJ+2gT)T5J%85Na!%ZGPcQ zvAwvmyUO32A+%lPRJ2|xKOg(t87>ug3uoha`1&vg}AuMD}3ZwaP$Jn6l6 zx_{k^o5_5HfT}Kf_ve{FEF+NLBTxIDE?LdZPeT&Z?7bPYaE z;@<5b?fM*LK!_k#Dm;^WxQmS-uo{O8l#*3Z!dnIPpM=|({-PCUK~XxsFG)%PBM>}S!(NL z&&)up2D)2yCS1N5|HoQoJKtj-Zo-O=%G>PV4+VbmPwewI;=2VJl}J~@Yd0HLLH`=* zc~@xHN>&VqS8&8M2#@#F^SiezxOI+4l&!q@j{}d`SI@3v$$hFaaqQ1KjjWX_pXo2} zYeIpQsl_lSgZFY%_MfEq3igBs8$Lg&O;@Ik+tZ2%LG_{5Yz! z>mzt9>qmY*uwb+LH*?j|k5+Ig4nBdn3mo|cy+TfXJ{HBn4LT~=X<2D+!%Yc%Z0~Ap zB7A&WHgDYQOVQmU?u?~&F+3d?Vb;I91iX?>ZTdYZcFlsNj)U(oybT3uW()8NbU5JLLQYwSO;Vd| z_$U%y!gV>99}&E^uKM4W_g-T$@GN2*@DqOQXt-q}3Rr%8@0c`7JHLMw>Svmru{d*iAaS#{a*{!(Ty;QO}C(D_*u zXW)N7+xby+>G$TsIsI8xc3@uzEJsOsmv|t3&bi+Rtbe={*ENa?1EL~&!<@iGj0)+M%hkX*Niv$aHyT} zECkul@v5gz0WOEU)qu3s77mA-e%8ZL11$yTjpH`?#138-i$|@zTNf;?lV9?VJA1VT z;eFfNuH>Nt@aB)EGEEH0MXYT(+bp@|-*_?SFS%o_iv2J6K2K)--|xZa34SUzFfh*ka*KQ^sM)hD)O&eKH7C*)J;9baf1ZgltGly&SPJ~Q&cmwvs1!=8P}Ms6T{p{=7cEjy3Cf^R;Zuc0zG!oz!k zzZT)t*7Q6$a_7cos?=EPKxRH0?GO+fFunBz`e!!uS(xpVmW#2&#{MZ0@#&u4~XBfI08g@fxBj->3RIX&Y! zCUDMNVA^^mtNGoM8KHUOP>m7&?cDabh$9Vmp&s%W7^j`toBX2ff1eU7?F+YzY2jaojn^V`YP&IQ252`pCzFesZk+q*iMm^uTP82`OX z#NN&YSmo~?j(=5>GyP_1By8^itHTJ~!49;X<=|r01Mu_zcXxk}{ZDs_PWC1$rY-;- zV4tGm!0t^wTmX6i1`&H3dnXkKBNJ1=-?I{NW&yDLr%z`l0L$OTm4U4S7{okWBvf3C zTulEteF}F;Ju>CU%SYQDs zfSKh#1x$euP+<`)_+>~+Zrpd+CK%rGyWf! z0(f=)`%;Ko+PIiH0T{$>fP)b=HL?E&oB~->J98Hc02@0e^WOviJ#!wQ?YgUpc#R3Z zRaKOoY$RjG=!zPhN;h7%(Dz$YqG!D$hJImSAgA@cq8nw9 zuqkMS=*~A{)D*tXWPcies$It#2tDvPeoUX2|sO}d+JyZ6s8 z)$Jf$E;%1h7w3poBb}+{{&b(avcJ6?ZhFY=OG{2|oUBc5?C?sbj7D0MH007gTJMb- zxeQBtit=Eag2C z`?rOjeZxv?IZG=^TgjzK|H3SOovg6yiZq?FGq9Jpvqg`dVGsdlp2F#%!(sgO7L^bWX{C! zsL#X<9`)wk6=RhmJ0jTJ3T;mQl%0H`#4}L?_jN5UWBh$6_hm`dc9m>IHOwmGi54&N z&c@j=zaX?=}|yoJjo4 zUeWp;6_8S8_-!Ivh6-xD~z*)<|O5pgu5c9TA?wt*@#FsE1sROmBu*Xy& z)CVEv&G1f2!=l(7z%5AFad4caSzI(3x2p{0C%=sSGFD_o_)^LqCSZb)LLAIBY>PK@ zYY%^52G3|j`)B}ehKKIEDbyMlz{Lx7U|De|4^%oLMn`GN`{Rs&<3w5cC@H(gDfwZFDKJXtpSJTmX9|k) zXyC?JTd9L*VZBHWGo}pDyZM99$c6||7dfvxiUZ!uMLmaGFu8{6ka^AyM=y9E(a7ZA zl_E(CoSSN6H^&&l2!0|DK383hYFe<(xuC@fa+y&IY$tnEvdWE08aE`3Psyu2D0_1i zgXwC(>^PAS_p0wC%UUDjeTTUpDYc~1V{?hd4G7|Ya5$3hE{vuV&U6&-Z2-XyuWb3r zNftRi=oqn}DstAsRn&443hJnor9j2l@=LWuLtAbqnbNX@0>9;`53VGtR{GTXryl0@T2JR}_c4o)ZB$o{J&4m~U_fo|LuRl*?_y{oct!vtRl@`bIPn|e z4pAl;{QWNyU6{*lWgck%1}auoPXrDaJ7ij8eStAy4mouA4VXyWko@pTWX>sf96K}C zRogQ%<0dX?;@J9*Y!ir$a*+(_XsiZe;~B5yBlYK;Fy+3~VH>;@uVsA-{?O26UGZ(o z6qpR1(2+9H@)kH%WyAvjuf_1;i27G}Dp*~s!P0F_A zU=eCe&!5)$V>o7RF+8giM_Tn&VN$~4%XoM-gwrtga$l%t^mJe8D@GK;*Dn5J1bLY5 zgf2jQ5`JG+BAB&U6UV?(K+-fA+6+lio--r6d>80&Gv|oZQU>yu+}du+5JiWvAdM1w8V`9itjwo z{W$rzv74TdWqyt^!PmHG9xj=bB-g2SZbihA_EL3RoQ6JA-?m|Y)v^T-mUQIW7rs~p zWHs7!Q!P!S?NVrufCB;?Z{E5OlW2RLVJ!;m5?m_gEJ~aV;9QCLP`}PH_t)n**G$&bkk} zV2Zjz9kwVC-UIX?&un6QvYC3EF)p{41D&r9SqGI)ba*pgR_2q6THC6x*?Yy;BvLrZ zKprtlEW2MR6nq~CiKc=h>Kz|lQrFtoquU(^hw*nT7IorGJC2P9do4B92AFx9Ns(f^ zh#?QK3ozO#z;gD9{PGIEbz>LYfi9TN8tF=7pnznmfZ2`6;jLns4TIhA54MhGCY&WN zyC@L4OE@!XAz1|X^bhr4{Fdt=Ee#1j{H#^+orG445zni}aEQ()Hu_s? z50#Yk;nr{uQzG1>DTBDv5!t;n>8sp{eaIdoYnvFvV^{*OjCc0+nH)G`WKM_u7M`JJ zssm;C{&x;}tvx6AB*DPEi>FA9WcMM^vyzgAHc|9 zDkI7uI()6fdjmfG0o3ujR0gI(-S81_O+n2>mFe(2$TV;cVlW0MZf30g2osu6_e~5J zc<9eIZm_&KU{hVu-BQTc=IguVM|j-wR5LDkKfIPh&Ba5LmTkUp(W7d5R<&W6CsU2a zla%iIvR(kyI~^l0Utyw&kJxm-&719Q-82X2foh)M!2nns&HK$@0IE_3d~Y|3Q?M#4o7KfFmAY3tSH z+bMbi75RH91cwq$NH_}AN<2;@X$^D+aQ0#}@LT_V--_U! zy=IMv(DhjBO6iebC1jqi+HZ{0f1$k*<*CQ`cyKM>;ll#ekhkgMQHu^@B>l=;=|#1& z!-0a)v{^X#uYBR-!s&fD-N3DJjnc^VmC144 zzIXn zQ1`sj&c2d?-@f4~?VZ~xrG~kK+lFINqsEYb-S52)^3H)Yg+>pQ=M#1ushXqp{#jqW zT=qM*LdJ z9Rt6fyMB%m8u=&Y7zLBi*Pe>|*e%e)1c+2<95Nat!J-=nu3sF}uxJ*w9u<(VEBqMi z1D8!-XYQ}AwOwDoN1@M5X!lzk2zJ$%OoNXA@=TpJw|Syb?AOuT=$a~8$8mn0Hniy3+O(nfuJ6&^waxr4R>Mp&_N__16-{1SujhDkQ`cZZ zhTktxz}(M&5RTt80Xgt0WOSw#sr9X`a~-)mKJ7bg9^Se?$3OY6QfEGowpoxmpT#B;M3UdD4?MIadG=&JlnT0nOPM>o zgos<}3PTPVe=hCrl6Tmab~tFbG>UE|@OkJOuBC4iJjV7tD?T-;lLXo&rbW&l_L`@K zpO25z6He^Rn~u6Q&g&*Acc|n?f6+4Ti@>_xrw1HWdXlZXfS*VdPV7b@n9|5S*Dl!k ze3GmP_+_7Xk_L-w!RCgJU|cAgjQi_ww)d+2~L!RSgmEU z+wUZ#5MCxPYA?wVD+?=P4;h3 zAD(%VPvl3OR?{C)w?!IR_UXU;z4HW7>+HJh>fe=j&A0b-0W5xN92w+^&ptNj@12H` ztLjaY0^JLW5M%w8x(*AP)XguMSf6WAlcir$Jt)zUF_qfFF_4%25=Q$TrFCg2zSv^= zQ&6YNc+}_=MK@JINXy2|_$5St1#>(wLeV#M=Dk1K)rv)8q>@`s>o|93wxL*m0;rsOHdCFgFP>G*&LnzTBugZ|NxL+uV z;Rp5b5RXsr4P)Z0O*|-L#noVhB&d9MBJ<%B`h~g{p(id~qbON3m7GY+n9Rp!WH?qX z|2w|vFc#G)?OOFMdvJ^MV0rM`%qU7ZJAdBdgrv-fdwd@4!#PyUuC;&Q$SPi^yXK%w zD{;J-eGaRR?l>u1R>4vvz6ThcYL+Hxv_=T7nwW4i=P_>fZ7gRw`bv6N0YY4zYy_a1 zQe>Lg=b>B>PK>)s`a(4-4d`w7rY|!`ZDmOb7tDu~6F^(C&!tHU{-fgRx^3&*LsU6u zDYV@aF7Dft_|ckB@`V(S@l-XwzVw902WTUX zeIbfp*`naI7`cdHe77HJUD~Ja5b|{)ttF}#7%Wc= z!*zZ4TcG>FObtb#a75O?ETm_&ml{inXSZIH&gDiGu2F1dEbXz0FHqMlF$WgImaQ5? z5&{RZZ-{Ye;e&T5C@X~0_?}(ZuMOiAN`c9cEn5AnW&?=(+K~uF6hEsO*LZzQlA__v z2zE|m0o}XM?}B)W#*~E+cE9ItVpz*4qLN+3rft=bKlOC?6-5T4A{YYT$sbNVh}3Zz z9u4%|$wNcPCVCof_CHWw=eU3gBbRW6@;15Q0sD_hCKR2Mc5Zd*J4sBrN%?p7{I*z#x`^l4 z1gI6x2-xOy6WrU#m*s(K^{+~KL+a6pE?TKrAsMplB{Xo}x=_B~L&yKp>#0+MOv3 zsT4Va+-Ly(oi@8IdwXfAI)@!Qec%d2 zpCBnpO2(bJ!Y5x z3}N73vuV^2XrI|GVg4;41y3WQKiRo2p!`h`f>-lG+;&2^lLd%v8EOglD`K>pGJcWUSxgqpz-&hlcZ zfkSqZ)z}PaDx-xuZFcizi~3m zNHpE3H7aD03T*zd0%@9a02${Cv5>-s~saD)BtsqiZ|&oE{gj1w+SM2c78gU=&Ps6+Yd7 z2p*g_u$~UCF;>?O$e~8%!QgD^^125IgKqWLb#&|7t3~Y*^vd;V5Ty~Ef`Tab7NSt! zOZ5iFpUHbt-Duue-=22x$&o$c`8({y&7T;(qo4Yue{qzkk3y_f6ORs>5kbyw7P6~i zC_Lrf>ILX|65&(yw|i+n?Avwf$nepP(jR*@g~9BO%xC+;yJby4-+xp79U&}$m#=LZ zmJQnUoKV&UVf{^~F_g|O#v(=~1c&@w*`kE-)$sOPBEwzQ&=?5Ib!?AXKsx7|-?sw1 ztuTK~>eE24wQyytk0~8=GkxmCU46U7ut`lSu?>B@D$VaDk+a0LkSYQv@bSYpjU(*$ z*ZN8o%^tzW9Kit9P$Ax(o`~hi>V-kLAG{xL}4d4HX_!3B=2x z20s<2#|-fB7|@nRMqXDx!KoxWg8vuT{~tv9KREpV8|=^YZ%F*VVgG*+Y#^xq{}22B zbL@Y*`(I&y1}R%0?H~;J*Qdz8Kc)V!bO0=n8u;JofPY~B|0g0h>|j=FK?l#U~FY-@-KEm$`&|=|0?>Q1i@dX;XfDc|4I-rva|kw2!eV&ojBa)6u-r) z;#9~|4!35>1=nC+5Aq~Kj@>g-J43=9p`42!t7*qSyh!goGCqHO)^2WBM3U7Mpjcut z&M9AK^!7R*5}l@=*)KEvI;tt9J1NJITe!1r&@uf?wXLZ^@=f&}0H>w7jx#N{iR{?d zn!U<1v&~%RA2GQ46h_Olt_?eDhu|WZZU7@W$)h`+hPn6gd8amqe(+} zD&#y#MAtKw00!(T(!wjbYGIOH`pgdX%*LZuwd9%T@hL(!gy$W5BdXy<5HQE@BY>(! z{vXEPImogg%GWKc%eHOXwr$(CZQFKr*|v=?n_aeF_1u~J=0!}rd;dDQ_c>?Bj+MDG zSAO}+T(x;((Wp4L{-_~oiDo<6W-9Y;(&D}saV~mGDp@S)vMR2B9uM}XAJKr^J{cze zsJMPAJ#De19!$4-rEXnWm@Djke_lc=>&&yk@MxI65z%xAHn#arLC6%{evJB?!6V~+ zj`DNqHo3&H!1#Z;wrb+4rVW~5-<#kBkITJ%+P*$e0C`W>-`T)_T)H}`*RoY@9g(vm z*PaKVr)G6RtaVXIstP%LY-(%|1JvPX8N$z0EO~2hOV4`xyT=cit;9Y5G>4BEcL!V( zt)^_R6hRT_(V5pn`0xNIsnTuJ+d@ia6$13UazPgPYxl|FlI;f9`93Y$F{-kgRLqB^ zV$%Cmz!$!{9^o~sP<_$gEt5cVe6~cJ#8&XB5vd{m-yNGZX>4#*bf2QD=RJbT>K?|< z4%iNrYqZ?LVL`W{owQM4wPP%s%|ta0p&KIl(9fR8yfZAdIDxB_RVcg8tevBnL^G~? znn~T?ckYco=r4?E=A`QVW6SR2U-5A92udpu#R#g2j~pn?c%8tcnT54n=7DI-z2MS~ zC-U`$Wz-Hq5G@V0?h(#Z^68qHP5_cD3Q}0{4$42b%Nt2U$Sb zecF!unoY@6Lu}fP{n<*%N}%BOGSQaBaZJHsShep3V-G!S{#X0;GWGd~a z0c}Z6%aHdnf!D?5f)5&g3Tq44RFACMPJKV=9wk5FYdsWVh|O!4{yoew_&+}G!jH)- z@CI1uGWFX`anu%(Vcb|}A8-}d96-Z}owT))vAsBLa|&>00l{4PFOx8GiE`-+d3Ytb0Y9qWfN<$!PB-187MGTp(u01on!<%3KuBT&Cm(?&;nr8z4ZRGmN zmz#4sX?Za*VdS)l5)6g~kpSu%n;KLqLeQU6v2_MZ89l3tL&tZ$0i@vz|FO_nFuOHd*A2#fG->&X@cL9{@f*eXMJA}Zk7X&O%~ z3pPl>aaWV*arE)dw^KuOu0~Lmh#4t%bdKgC3aKsi>iOb*w8TyCjC=YBCo?VI6;{nz zm@ejmPyU#HenWlr*6itEs0&uga5)o@dxDq=Gu4vka1D{XIo3jb!7}EuBXSY7dhs`N zr9pATDrLwhxx_?l3BYN2E(TH^sQylkTh+$kVA>>$yiHyHCSD)>B9l?8KJf3L9DGql zs=wC-`5dEwAwMinJ(Q&?dRcW6jYOFmY6UmdwkRfBxv+%gwg4!njr$bOr) zv(~deqJKPd0LB#13j9a$6PQG>a*>Qt`Pi6KtBoC8A(Fy=1vOhx3A`akaLSb@ z&BtG9F4P?4sWir!c0;C_lHVyXdg8B5JGx>#t&xkn31274Sps0;I%Xv)IrJr7t*o`5 zvW|+f;mVVkyEvm$#4a)ovn&o+&e%4MsMYfZ;+`oJnPA03yngUqL$T+CI4AAispGCK zf^|Zpyd8Q6AFWktHF9npV%m!USp^a3*!H#!o?2KA8*P15^wxx;zR>>1-v%gH3DTOS z_Sub!rj?-KDAy}mu!Bv#{k3-77|xA7DwM#8pg0LSne}sk7GKf@z6Q*kqEoe^etpPMmq?mqnBqb<%LDaKSS$KkP|aZfYVSnbM#B!LxyWfBO( z=&nG^^caP}s}pL8AoGAW;<$FcaJ75dc9pEA*nO$TcB)~sRm-F@f#q?5?CFZq{lpHi z`dlI95AfW@s0!c>1RSJXOC~DdSNyl-LyT@5%V3{s`E4SuK{}9p!y`Me^9R};GOImUSM1{fFQY)SZNWiCDrzuq#bm{x$d|^_Q^LRD4ATXim)&$luI$Wx5Yl z>d%KszmK;9tTphQocoo}w7<}2%II$ZGrLs^?y*~%Z(vW6nX!L?<1ee&1l`xuzjyU` z{N*U3>VwWskIsKX3f9C+i3QNDWqW1BsdUJ|zS)5Q@ZF|)mFHG9x=dO~Ai-j!Eb!E2 z{~fekk7{7GJjH;@zJ!FHIHjJ?tGSn%UEgBD;iiSQZzzZs6ajgy`rMiF4bV8Njoq4; zK?N5a$OrjLEQGssb~%spPo$M+dDy{<(*fWCOwQ#vGwn1@?X``&CS1o}s_0)505e%g zm^Bv|3@7!{u6aVg!Hxwl%_S)HpwQxp)$p1Uliy>U=#_F=z}vZ6z-^{p_aY1r+6L&zymjEviP zFt3Rin8%H0{Fd1;8XW|+9&7+fG3@rbCKTuAKwFdPUlyX(m-28fSwk-LSums=w$`TL z-TE8)9vTTX-6?R1O*~84go_wGv5$hO^Ro6941=8(_DcR9p=ut|pAKC#7f}fTdjsNV zQUw94Po-w@b7d{$oQPQeuh)rzBKww2$e={N=Yy5Ch3AUvzi*SP@`TE8&0{Jps0-qR z1+s3q=5JYKFOtOuvpH{vH5Ym~;}k^y{pXhxfL7)#`x_>h&4LfOGgPLFTAlsRt?wS5 zXlze@?m*=%qi0%sp~tW;Oc(m8(CN28LBfEhPRl6HFPz`^Z~X->#h zTH3K?ma1T`Kzdhm)~^nKCq7vs^LH`SuKZVxl}yEZv~j}rUxdG02xv=Ue`La)ttA~JnmB}c2c5qS;o^6Vv0N~1ar3Ac!kYcZiM zy;}MW>NGZas`aBPxTVqOyK}wl{%;3^D-4f}Vx!bR{7|YpFKbdu+e&iy&8{yH+pc4B z-NQB%+_LN&j3ypC=%ifSQxZ6LwLs5P)K%eq?yAEm|y~k;X)Y$CM(s8fM*%2 z)fQ^!fN@F!B&gm%x&mS1-rn1rxGNhlgrlqFlP0fzcHvRX^?Z80e($k&NUv#{qHnkb zySB|~-eM`ldc54}X1*$gJe%^eLTInUeQyre;J>4 zE%xBfwN;e};wAoC|NH7C2QE8}qcXtluV8j?giNm*mIzlpvNyRX>CiQOH=DQ8>Ru9M z*sI8A_$@c&Wsq+u_lgj!HEI}*mXWRzZDoDjuq_bAbuqz|zM!S13Y}f|SNjR;% z=?G|4FK%KvC6%Qz&K~!P$S#+(6A%>HoOKBZMT++Y;_FmRz7#rz|3_lj=lv$;)As(u z9k@ucRD)ND?oh)nw{_NQ?G}_X$}tfuz$)nu3-mF=yC_f$HHkicIBf^|5PLq~qKHIo z77-?mj#mQfsRSdhDZt-vHtUgYmRVri|9tjhkgQ`x;!`A%ythXz2&P?Xkmz%WFw8!& zOnsr#?Qn3nLAu65!=B19^;<$l^BWpjOz0*DyMZjpESx_5dc{3g-VbD_!VfwQ0KB5S z$>-q%HLg4XY4KT7a7f>T_3Td>j=E&k%|&LHCAO48oI#Ggh@wZ~{nDxWx~amOa)WY+QUX^8}P6vOZi^bK-;p}#b@pdJ6~6Bido}$QXW_Pt{xWoUjr}VUdtUQi`O_f>AwrAgV@B`pJBv{B zF827S%rq+6;o>`%MN7J`8;gmo7`OPoDv11g7w&QRmwBnJkvcEBXSh63^!B|YR0`0E z6aDWL3f-vu5-m{X$iI)KRWY?BUcUS_PH*NC z{StR7@6I9N#(fnx*lTOE@7^t<;4{t5_5UXO&ADfpCQ#)r%6V;C=;LZ#*{+0bCEBw0 zv7;017cx7(FAHeOZpNnT>6su~h}$Am3k*TzHcX!nW+2^D=*Cr{kMEcNu}}h&nJ}lB`FC8UCI;2PS(e+qRZa~EKM}DNWEGW$3Q9S3yOGEHP%qw^wqrDjU-RFRVZb0 zwrr}k7s8zXk%6ifQP1tiomqK!-xANH%%6#1R`3zZUdEryTOp|P-GY5+SA|qzYZ2Rk zsQL|YXx`XaKN-_ z@zk)o6=Ca@q&*<50Lf87k4eLc10@_-ebJuUqYw*SQ~{~NabPX+V;8QcEHfB%a>{*T!9e^P7zZzTKQmD~TQ z=RZOAf9lNtn+p2}lKv0E>3>q~|1F&UDgSo`H#Dxfxl)m+v8Q4vJh!OT$r~-{j6^jzdV|nq} z)qOhe&3pEv7FD2^pQ6gD>G27zzC1rERU$Olc=#|r#^G1mhF{lb+Q#6)PYT>CXD`ld zyIDE7R=%#D&$`x~Gq}zTug?vN!L6&m-0$y;muhx)-^Y_1Wu0aBUw@%fyw`Se-9|gh z%EGefcDBFHC;2XwA0~fFtsAqtKF^OQt$Kg+WQlV)cYL2N-S~RGK3vJx+3NgG`TX9u zRz*Gza?D2$UXL5U#oAq;Tl0Lrl}_F&+sgmST_^KZ``uSA82auEU4vh2>G}BH5AS^m zM1$F=ye-4^zCMlO>3-gjr8Rl$`Mob+xP8lh^KDnX+4))L>iK=Y<+xwwC0}%2gTG!@ z;rSJlkVU8r{JcZnf^LHEM-K5PUaQ{M$wu${!splaRrjmYmY1KOn;+-qSC?1sTdwT8 zp$ zVQ;U8UI82Cb!(mP%Zb~0$O+rat@pDt_jWF>oLlF6nI7|-RL6bPr-seP*E65*`_snv z^W*9m>bzK3rXSl8S6Xj5wT&d1I9bMLR!tl6Hoy~irN;YP~W z7?dDwzwgUVyxz|%tZxBsw-uJJo6F9bk1IFKkZy6mms*pzl}P@U@0&|DzEAq#9SORM zeTVc24VW_n%^dfj<{mYxuWW@}+$)owvMAWD1cgeEA0v*`c*-;BettdI`MQ7RTpWG# zeO)b6+Bo15dylC4kb!+ukK6JV&f+Co_ipUq%*eGyxw8#KE72b`vgPggzRLNn$Vb*E z9|{0~$*VZ_a&6(nzHcnP-d=tDrlR*GAL*=#_Jg#4|NOdg=58A54-zcVI`eLB<>C3x z-}`Al3qF5bn(1Zxl5U`lb}|jfjxAvJC_Z5(93<(#-J%iQjShN=9YzJcA2mHp(wTT{ zGrMl$m0;Q+-qJ8cd=tmrKCUjcu5!)GIzR7Em3D~a*eH8=R-5}rUUoKI zSva>avGyYir&;DWmaxw+@Yk8yyir&yZP}g8#rXHz!PPew)JyO7-wQrXi>|NRs$1}i z&Fh9a2{TKWpp}T#s`64rJ6(&<-$}+hLv~_gc|Grgt#v!zHexi1H7hcghC3haEW_ZB z(l{>eoZC6Ls#cL%)PH(Dbh?mC738v+Q@@irK5xZb*3$j_uxtA_u6O>}5MS6egUr)) zt`S{W=6?5Z1yA8()Kpbw@|D+(B*z|ac{{Iv=`+DG7L{!&wKh*#@F9PFN9x^b>U;!B z#*TIdrH(Hb*fbU;;(b57&*zp{H3JMzzMD6jsB~^^A+a91c$8oaHF7JxE;#I@hK?hs z`dwY!N*%J90(|Ro9y?T+u;qNaIUf1a9qB^uH;;UsUG0(QeLT3kc_vS~u~!sseI8tX z+55Sn6LlMa2IyteVK=@w@0LN{AeKAKk+b?$js>?#syak#fj zGf{eJsClWG5p9ls`&EZ_b*m`y-0(MM4KCOfZ?D>{$0+1!kPMxAcU~{wrF9DV$6dyo za5Ov6!xxDOouN%M|5%g^J?cbb{OSEZKKkJoi4xWh*`F_rL>$$`1m6PVuxBY(_fTW8 z-<_gKKi_g)4PT~Nx_XBilTCFJ6MYJf%MQFgi@SP;8iR!ey~(&z052;0_}yD~ddt6R zN{v(7HPhT`T`SH|_J(+B2P@u*2wJ%HH;xb{t0vAOoZHW_mzIh1>XBcv;Z02I1$)BE z&Z&fricpg15icLmm3W%!;iUBtz9Lq{_WrFp!AJ9P@#cPjNc2un&Rp;KQyzu~CqMTFPWnHT8Zw)IQQx4?%zz}&A)W7`SLMHs;l&L#SPkl1 z5nEoFax*hpgB5HOeW}gA7@m>M=8=}?uPSs}21D|m7+_x_X-Q$(hOPJLnI`U>-CFg! zt7g2Pmv0)~Mi;kk%WD$EE`O$l*EdCK#4v@};s~&C>np@b-pEI&CUr)=q?_I-3$SiZ zITmF_WJsBENZM+WEN9M3d+8ie(=a8@tnM0VkQ6K+m>C@yL2^jtQixx!-TVBji&$Dd zesH2xEnvWE&-h%MweZLKCCVBObBZRjW0pFBTz<%+?H|ECtC2XxB3#3G=ijCeLGDtnP$vn1MD{xHQ#ltHx z?e<3VaYNZ5{*0ZW|H8@RwX{bQ`dtipF@g*V$GnF+=-1)3c|mP5m(T4lo@~iWpsYhd zl8A3o77@4b3rit4*i%YJM7#pAoT(-g5DzEyyIO}13|Toiy1NBva)DPKgouW+!wFJC@9GDOB7 zaDP{qLc*q>;XrVXh8-1JU@R#_I#eHGAA%A~11O)zK+)kbD6yO6uAU+d5Wr`dXwCUR z#vvUjBkS3darV!lVjPslQY&J3En$1Ngfy3}7__zogHx;RC9;!#a+T7l8@>>uw7b$u z?!JBsB>1JL4PZtV6hp_2F|B~;sA$;>@e?gTMo2Ml@?Mm^=Q`e{&QMaozwkL}JTC;8u^jp=X5n@kjF@+Gah7vUH~Qm_hAPbF0- zN;uHXZ$W_|ELT#F2Lt#^cToTJG_tv4P$h4 zxlDi_{JpDq$FwtC%!4pqN@FwGy>jz(Ks4Tjg{jOUj=vp~35X7p3VL~B1;)+K0>D5M zf*}T;LhbHB93$sHWyqb%(9!2NCCG_gmtr&U12J~hRI>OrW=4=5!3-Ghu{7Vrlc7>d zR2$9+!z+_di>i@a$*s9mT-$%V7fm$OF12hTD0wCf68~phV*p8Wocl$)>4Fn~F|uZ_ zNoJ->8G{|)h^z5YgRfqp0Q8)rD%ooBKAjq9Dv=<<(fGig}Q%yEzzL0-Jc`zA}d2MK_YZM^LZcm*>w|N?U z9zz{P@9_^nh8h0ku;r_WRq;a!m?Y5N_>f$dh2nZa?FDH&uvs>o96f#@J3Yv)bnAq_ zTDsw0-x?iu3%-t0WnUrh1+8aUv@l>#o{yNh5d${G1It3Y}H!6d=_**T1cEF3!z z!EaH-vzNn|^ui3szR?7uMeoBsY8RD?pqa1oF9c(aMvg{vt<@iMzyyev&O_hU2M6(Y z)&^1w)w9sHj9d7zLJ`CjDMMLN??M1&ml%0*gW`}eZTDw2+AOfUmhKmFQjBVP0%SPV*05HN!}J zBSc9bm6bRZkcFxWQzIR+F++9kBN+ifGeJ}07{3NdLUp-pM~m@IZEO^1$P{%?{E6&R z$DUpJC2wP#c52*@> zfxkEz(FkYKCUzsPcP78iZj2<%0+D(1Z;y_}(EW~D!eV5g43-RAa@NdwZ?FJY9Z5BvefhyF|5iVbJ(sic4ES&O%+v z8&qS11ycHvsU@>xeTPs;Ye=(?;r7R~#~uYcM2(;BL7I&sl6f!8-CV$C zywAKitkn={vgF4U^!Mm7wp-{qH+x45K{Lg9O~Lb*abnrXG-;~EVT(j7wcK9V;3k}W zf8t$irv;P|)M+Ueub^3(r;%rJgwefSMeKD{&cB?6a>?>M>;7=>Y4(?1FcOr6@)Ies z0rLiC<~3h%jx9veg!D0ut?OUd8Uy?BbKikWo3-+j@eZ`mnCS6SzlzhukTiI0lOmW#yu z!DgF>g-q*_d!dSp{GKF8bTeJea0Ta}g#Q<6p!MN@m)~W_{e>FTum+)DM;#bc|E~_h zc4T)E2oB)2S}qKv{l4};u8eOSm$eq zT0(QgB@TSJ ze$8xNWj!gCK^~XGQIP`Tg*yJ~vJn|3(r&A-;}sgnr6gHA5c%>K-;1}`@bPI*u8Iz6 z@e+JFBMsx=sMkmlLd8W0{z3n5L3hGtic#)XSTcO1keh4-5C~!9?J@2=ZoGAgn~*Y1 zekyI%bEMNX3!8S?Nu0Wm86!QR8)@8Ilu1x!V+a^Z3;$$A401E)HUAPxv zuWH0`!pt~K(!Rq0Ij>YqIr-QXD*x?J5k_R-Q`Ld5TtN_TfjXaGcDZ|8D3Q_L|Q9MAV^|!v|>%wWv%xW zXh4ZADQVGQ7ziVipgyUjyolM|*{X|y?|iNJ@OSiFB)dL~U(@+Q_o#w7G*4z@t6SXV zO*vlu(X-*1@XU;|t9i$bOFA6|6(?>mzNZ1>Mt{1|Ri{gO;d0naM^D@i>~4Wevg+Q< zxj2!WQc>3pPp73vT1@jb8pb{79+R{N43su5&fj_lF5>wb^TuSrFqXwHEQqvFk@yE z8kQ@cnD)ljOepsDO%d>y1)%ss%8sR?xAqEqiCa+U8+0T63jm|5xHCg`gE~{b@nmXt zF(4Ex(62%D7jlVl$w1bW{*MO7#wS#+gW?ys6@*n4TFvefEE|mV3ALE|T0p@?sWK~1 z*5#^x!8mbG$EyB~DsiR18^|r5#3$};RYe91=mrg)KCxje1@6%WodKgDH}(vAz5+UG z9rkujt_lE~(_g-R&(33rl*Bq^e|C6s)dlN&I3V2f&HuniTc{Mz?Fs-uH#vH`vu7-h zH7OC_faa0@nB<7t)5dHRv2v|EnLP3liPS}h0R1qOUxWzB!JBs3Td>^KBJcRNE{YA3~ z5!^|YGa$+${^~7NEEi~Vlr{9jH4P6ZqHM&xKFMPlRk{3722#c~DZ@cXPW;hIi()Fi zN;tvj219Ag!|<%sj^nAp(*r6P>e*ANmy%oq+>OoLs=~OidVqPM`tT-D_@N5{(bax&HQzF&G;R8MDwus| zOb}~fp<_|z0ZH~SQLq>8L1^#BNSda#*SwqEp|MZOoZ7^a2&8R ziNsDZfFZRIa0$SVuGJ!>%P<~*!uPmp<@{`Cd|n8>kfz0Vy&%!jqM2S9^M65n4qVMW z#HeCgt$0X`t2FJu!5Mz6xNX<5W4|-NfPF<;FO_IeS;t99T%@G)Iu{{uPmMz z!u6d3*hwGi;a8^tK;XHC$pQD?;Vn+m9OoE)0sx>xyO6!6IcLAo_QUC4nEQX?_K6~; z@+DBLv<0s#|8W7e3Pm)KR~9s&3^0*t`-*-ucuTGmsH(~p`zp}X>Gr*1y(EKVA^7D) z&9MjLZc(It=Hz2rfjW6_lY05V71f?NI~Lu!?vMtjul+Ns=%e=`Wa{gm6cy%%d?oN8 ze_*riAbj{sfTc)`kuk?)xEBBXc?OGBBK1+64MAi_Dm$cA&E7lu?_Zlmf9g1HiHsEM^V@by1=5`)r zTW@e{?5~@*1U)fw>)ANE>;Li<*fB4u&$_ z@&+SFgIn=vlE~};!_ouO`w39a1^>-z$uU%WE*IutD8 z+63mTlHBJdT9;eYE+PJLjS$Mr>h#06jg%xiSvMu3Z4v6mSXVm$iD(la|p5& zCIYnuqwqn!*}s8Ob{8#_oA1;8Qdkg0aOIcJr8V4B;aJ{`JFgE=P{rPS;4I3PG54+Wny@haVhQBpTCEpAm6`mAJJjdvX{f~=~PP{wgz z|8s{s8OKgp6*Q2dSxNjwYC`++4lulCDv)&-k_QSHaG&2VnHOcD%!A~O2I3_KHUSvt z>Ml#HE3)*`*9H1E-Hrscc5^j%w?Wnkx+D@KpahSZ1b2}E)O;U75EfyWV3Yx{qDTdB z=cIL`&RQPwv*nYfKO5M`N#QJ{YtCdZ#O^kk1wrepXx&r!e(Zqg6W+Zf^vJ+4dHQ9< zO{%J^_UN`Xw(*x@vD0#Sb61&4b@%CNr8!ux(_&*Xh`1F~zIr>J84q6NBZ@E9=4 zGCyi}_lwE-E4%ODlXmtYOSq37WLU``f-{hGW(_$=6rm5nhfoM_60z(Da+pc{w&e|q z*VmV1u@KvJXmp^cO`m-J*~uuiAx!w4GQ@<0+I?VMl5^WdftGRIw2(>U%`P1~1yVDtT&rtvuF)2I=uN5WHg@piM@af|D zKeAdHlyNNvUaX{TC1&nvH5uI8MrsK6EgG!}0DGT)7nFm0WU zWpnQ#Y5VtD_oQ^Zj)s<%Qpa|{t&@Whg>8*&lW_-Dtygv~-V{taRs)Ok{R%Wj+oHC% zT~Xx$!6d!KpKHW-nNZb<-4lU*0Zj!*?sE8=`e|OL#DMAHIVP+C* zWitE+newU^8q}gOv{6DWGDwz`#M?CxCbw#30Rt_hWu(y{4IsR{M>5-Bq7fjP69_IY z!7I)wdug+NapJ3=C$>Z>#&?#}YZvS$f*a+<4_s#B<}tC~1jYHX9!L!JTg<6#;5@QW zmi!|qch8I{^N>*+ncjLnlnmvd{7oNZb28DoFN}cg+4|Iz}{Z<2^JWBDGgj-$+1#G9jT{!Y4wIofmR8W1?nIZ z8r?~O8T;;Dfpe=?Y|RC1n$`bmxm&mWT!5aq(|APlM715{IqvN&XSwbi5DjF2;j!** zE)XGfanL~S4hub0JyV>E-MT$NH*4Nt0xo-#@|Abow}sb{F;BwIsHT$Vl!B5GR4yT; zlL-M7J@H~ zJYElxTfc%(+m<6itn9VF+2Y5v^6TWlh#uu)E?O=Qm6dnqgd zj|0{wlfo4#nZi4{1mf}Skuy$kXV#O^eOUB9+w^P6q=!^~RWd)JA`1}D451%URY%QT z-elf>$*{hqo!~LKz@SUHW*=>mSg}2UjuM-Sgxm)|q^YClwVjAvT1&j;{IEVV`3)R& zV6im5Ltdu9zXnxhHFKbRNP)t+%C2N%q9ABOof|^1JB82Ug5>>UpYM1h7Khoq2MQX^_a0zYCUoP5kb+?4|jS zWYH3Lc(yVCdzL@@jei$(Kl^G%A6!&B;qDE!P@KWVMx2r$(2dz2_{R!`K) zaUZXW&{!YM%KwU?vLtveS}JtcnszqHGH6W^1>F}D&f$XDcfl?5sZ^x2o7AiFt4KVe z`BJ3vsiNi$LV)rZLJCHFLzjUncsKzbEzJirKjoIp>Je<^=C5$09z#+_#A}`(WBJjh z!KR}WC;3_?zZUmMcU1PrmL{RD$#9>i5)kx+?v-hrP1NWh&57_pRQrd84GJ};h-r&> zXB->2U~%ULP+#AhAg4{#k1NdIZf>SjkA@UOC{*hNdwFAMG(CU_E1XhpV9EdxA*Xr{ zrCDGmGl@|e^8Ab0OO%tG)xh;ke=8uP>oHVzOpOF5QwFI1EZyBWP#_G|t-GY?L@P#R ziq)F}VVHLNkzxR0hFW@vKL=|iXHu-?IcxN&lr30w)T}yS)DNipP7L5J*rmAH>jNsGC&LvfRg?90jt^6n*5&ZQD~SQRU8DfBDC)n>SK@rJ6}TLSD>y zVV;wXFOxG}HfrBjw|3C$m*La1D4hM-E2HpOX~{gQ%{#}0qcVF?Bq;Q;OrJ73_%feB zi7Sr?!@<>xKRS4}eP~`}dJliotdM;Ur2ci5%VzPoREbLrApTNJVYea3QO~yyQmx~l zy^Z(d4%B`4%y~vXz51tuB#K0Q@=vsGL#Vy-U$ou-KWRH+LsMuFlq_8S4(44@vlIy^ z!p+T)TB@~gdB&;X#tPPQ#3SM&`>Dz6Iv&jz3F8v#`K zQHvvojytJpAzdAvsb9RJw5y%V%-m;)6fV2z;EU!U8KN;(wayDiV2lyMP7-p3qM3!K zx%1Q=F19KAd!%3hxY!F0ExeP1LTcRnxcBNUwM_{QyOUUN&LKFS?a6NIq+ZG~k-3}S z)^Gi$Mum#-l}qqr%si`-Oxl$%)WMY(m{d6{HzG7( z;dY`ilIR)krM6ht9VP!z%XO`Qq{i-aMaHT}QxNqMXaY$JsZ z7pkFWRpB2i2Zj1DICX@?4MM$Q!IK2<_1C5kGQ}O1+Nqvi%9&LEWE!VPL>BMFb!o&r zM&{#7DjiY`;eTR=H>CSdzb}rm6Nm)ui^;6~Ac}tkBXUSuClXLf$I_j?`XW%jSRK-M zUGuoV3`@a92b4l`Fa~*QKA2{z5>-`FAI(z0oxcd63k!5tW*1Y{rZ<0~-07s=5-n3* zrh#n#L%~DGvY2*K{Y)@Y@j3w0qdy!{=JiqR6_bI8NN~QY`W`vZS*zt)KtAa0el6`o z!@saDe_Vz;`~YgWw!xlq%_yPBB#O zUwJ71V9h-@yJgW@Tk<|3f6Nc8`4_G*Gge^Gs(7OYZirZ~ajy2hj`-fN`!vD`@9Y~{ zr4>2Lb^L9*EU+e;6XaeGIOPz?d2Goix6qIKC3VOkOe|xL^tvbUcU&B8=}#zSjE)-a z?0^cZW2o6Aw^`K?Q3P9=;+mzH0B$GI)?-dd&Z5^oqY#4kM5gdrV1wy&0d1|lGQh3<~ z=0xn#9K!pcVQD~>t4tGD^pl^)-Z$KE(9?l#H zJgU0sRc)QI9Nt4S_ww8ZJk+TI_+-^`ls~{?viBS;Vn>UD{!WXgxRq^EDwSD8SBx!c ztXc!tpHb}PMn8y{&QPWTvOp~;Odz+Qvk=&6CCJ=bD7#rbVS4ROCei0C``CPPwb7(2 z0Pbi$jGXcaX_Hhxremj)?Pk~_C4%gl?j=~>MTO#I9x)0omIaGM*x(vP@*Ju^l@Ejx zGsBxzrs8LM**Xb3MftDpdNu3{UN$DavvKz+iPH)82dgUCU70y0_j`Q@3<7`tP&nBN!4Q9%@b)PNl>M#-up0^T&iy==k%ddn+=uge!abq)%Dta%PU>}4}R8^o(4VYIJ zjgHItGZK->cF#?3c$3GLsM1nSXg4#})2Wm6YaiL=!OlJ1_}4_7Ea}Y#?j*qBI!nAI|S`@gz^h%epY2Af3rzh#5$$F z>G5KQ%K2jHk#jwl6uQKq;BKf9f-50@YSg2n!6z~P&C!D6u0xUP$CN9x9FTKi~ z#%s6>LwuA;a*pZrv0MXAret$>FEhSLPe?z_pqHd}#NW*KKwCSX68 z%$U)Xn9y{&%w7v7T_}#b1J1K12}0nRyGXgb12WVx?E{u9yV* z>qjy-wlwV@M`9hg;gYi!{@5h~kEqXQ#o$X(3Xtnh4p&DV?@wNZeWuE{P)p|YUMXwy zE;?PmJ!Z0O|CK36ceWqb90at~*|0=IZtQZnb|~(iUhSj)RhH8V>1_$HKheE73&e2g z8*R#Cq`sQ25O)UQ^h5t#X4oxF-_{&kZOc9 zsO21~c}9@BBEofc9(=Up;QVpe=+b;V{UmjFxVsqW6J)_JWF%p8b3 zrT-66Zy6WW`*v^B-6So@*Uz?YiwaA3RNrG$vxewt&u|(CtI2dSka1;jrrKqzhfaH9`zfi55~5Sd(T$wUV_m41hWkLh&HdNtW}*+p4MHG%&rx z>XKvZl;ZTQ==pl?Qb~*Km)j}ffFRFZBTz*Y5^e%f?j}}J13^}b7i+2N)i(-Kz{~7| z9Qen^XM-sJDv2*?tC@>ykh@fDmbN>@5@yzXRO&vy=MzoEHU+yx)>g zX=tC0F%Z5GWe8t-zDY16^R)}^-$~Pe0%K#pL>&1YYF)g)Y+IV@2MA-%xhCE$jrQ2sSRm(G~qk^Z5GIq&mg8?8nd7HshQl zB@p!;`||F=rDYh*L_9^B-bfmqxnLc|?N#6J0S|!js5B^N-m9@DjA9T1NKMcU!}? z+xq}@9Go)zrAk!C(T0mBJHIP< zmhwFxe#Hcwm1u*CTBl=CM+t{Vy3(+(kJzXP!(wb{;|^|3(O`;xb_GZ4=5ZVDLk^rk z!S}<%<}5yJrE1&#>*-oI8=S8lc^~8rIT)N~PRy1@heH?I2@~xm+b%oQD_o0zHNBM# z?{sYXo29<$@gT_WH{#r9&%E$f@RxLB@xjK$#XUU;#w0f0%{>F{lBq&rmLM*9YL)kIXBnrM{=r%yTj zPD_k$ZP2(&Hc7V}z!AsXyTDU*R9=`Ec1rDKeCB|+Vq2;&s%VMa^Ho|i6_j_bBtVDz z6}ZF`5$Xdv+HdnMY>Tv2!y4zq4k{fQ?1bw-oNPF~%slNh&lRNK>y40)^hQ7rV0X-OEup(DlTn6;%Ma6D(v&xbcn=Z0upf|T})y?Q@rLxb^kJ7t~ zu>{xWI56dCMi0&?bb1&bIp@xXPP@WdwcBS34dG6F*<@PVIQwW_9$fU&YfIWoD=>*5 zA#zv2`}HYiG1;~%)q3FDM=+Ry*`XV%1z%DapbBX$7k=9V$A|5n8!6jpKf_h<=AT=ng4F$dYU7g`cZ0r zLDV3PedBj0+W6jxlxn{pTga>W{X4F#ZJkWDj-O>J!*)~<<03=9zrjHP*Ox|tae7y$?66v?|JOTU$|4UJ`A;!ysSV>t*qN-l+$C|fi# zqP!f`@f?dcGHPBtC*&w)ewAe!cp2&}R1GZx@*>3yK?_*u6N!}T# z+Y5mOpJoIm@#hyAtBOQwXFQ!IrdBCOy(CN6R}Ox^0SR56r(N%5VHs9k-zEzyRx#FoeD^-FgMAzUX*4$QNrT?tZ=-{iO(F|MPx; zEOfd?cY&a#HmkIb*djgB_m&a*ZQjCa~83ePv;v4g& zvlbMdc1X400h{|&lI`@a;UHu5IBXG0xBn;W}iVzKdo04C`913Ap6 zS}tVA^WX*+Ua~{EM3Eoi5@nK~zoOI(+Q}A}8r;j)1)atRe4cH05iayw$c8ICDDwltyZ<&`NvNA4lBbvbJZUK zIE4r2c?nECRzE&5x$iA2m9S0SG*YR~DaBfF4xEncsX&LXy})SiPwQn7uH!-49sPr^ zHE{YS{AX{1IIyFkQrKuQDtParhTQbC%9=ru(9fG%#s(L?Jjmn25Ssp4S{|ROs^G($In)u*@?JyY*rrI5Qux2&PKGt#Q;~dt7I@?d!@Qu z(?O&$Oaax>%D~{p>2|g>Y(}Vjo`TqXJK?C<;fD)LX>$rL5q!OulGzfG%i7W@%3Pmx zvVk#+(sB14K37J0GH(>8qu7$e$FDKE^c^tt&{^WYOa3T_19~Vw4m4p21^hpnG!6<{ zIxK_u?@G5xwJH}h&<|EC9ft#tg;GN!bZQ(FCVa=M;!(JrSy!1g+{;6;8u)E!6X#0i zTL+ZTMG{tEd`$F9m))~t-=&TKDNaE-x*4}*(Pa>QFFuz9iLe((%3-B|!`W@-Y#fvO z5@nb#zv>hpC;4Jsc9smY=s@4};qw&r8lWfwr*+=1wt}<(!e68gfGc=sy{+Hx-P>2f zX3N0@J|{Gv3o|oVsE$!SdNFt@6S0JdRn>l!(`<(4h~0-b2hTw@dxL}8zT4una}EQR#pS5aXym z4r5MWb&b0@3wpNZzM@gknaI=vGszGa#aatFn<(z@1QdZ^N7(dkLO!IDb>Q(&0>l;1 z>C@Eno)aG0jVo?V^EPf(MP_qzS)FoiAqdTY5GFv6s*cFf{?#`#8~;!D6Eqmw)7h^5 z`_=G)**<)m#zM5MzRt1 z+jQ$6`k*~#5}pOQheiwA-y)&VEhu$KczuOm{Ck^TNHSK?g{1KxMZa6sD3QJMW$)_1 zmub7%b=$M*wQSc>LWCzXRj{?g2Y4DmUj^UI%xfF%AMy_Sosuh44;S}w=YBF%p@zRi z%FfS2^N|)wHK2tqvX*91f}k2I;DdI}WVEg*LdZvQHR(I%v|KoCWXYxq1>c?!5@Rlb zv65U##P+%;-ole2h}7D#z2$dJCfSuE0(BnwWkNWf2WpKu6^la2N+_C^38iW5bbmFW z^R&92i^{jGk#0*O$a^O(UHSgF)!vtnATR0Tfk9KyZe3`#mPB(muFruavx~`5+l0AT zqodL0k_a>F0dL3Ra$AXBYBUD95mZ~V(lnO@l)nnJ_!ayp&&>>gukV}iikg2j&bC4K z(B`GBkjdh6-S3$kpM=Lww{_bf6Eq^Xh-$2`_KD#3WZnM)9!T!UH#?%RxsVXCbRDpPLnT^ofuLvQ2j|R1|(5t zD1!*leBP2yOGbr~?Fw_GE-l}O*QpP6&?oAnp$M%p+mge9yy=Abb@u$ZpM0(;@Y!NV zj^tNCT2?4QPpcl|t~-^oj!@JVS&jkQvu3sbyFph+$4*&y(YzXSc}UwWK}^TldnqI) z4I4_;DiMucd>TXvqpkf;x#N_|Z58b=T3hbmz?evmIc}O+K0Q>g-vrpd5}5%9hlQQ= zT1RR}xWAX~8-zv{%7HQ|$;U$3*le=1tKN**V$ETe@Ier=I>XG^605;aP|DE8*E)I1bmMs4$LD$#4rQI~LSuI-_#UvW)+5Rp3_xk4=4P{+;NP>A%p zH(O>-`9hu{jkMFs_qqkZ;yTWXbI#p;z&dK&aI0=O)vSovs%fOVI#omV{((z)HsX{I zyali0rsU1+R`bB1^d;3MbEGcE{#N0#=ygkmE14*b(Tk`Txw~MtfGt5}HYdgyn3}0Z zN-Y*8P&iU022=dy#rb-`ljB||HSP&uJ~l{5xRehL;E zuwwhC6ug7N+umcK1i6xJ0jrcYkb0$F1Z0p=n*{3E1YR1sVk01aD!RE(EP&ZmqJaaT z0S_yAmAPwhgc6JoN2s$C_d$S^krRXaH5s&k93r0mYg2jKpULbbCav=ahWBeP$^dIl z($=+;#HP^@R_{QqF*%a4@MjgLdHmsiK29i(`su~t+a#nT)cJRSJqpt7ObAh=>*htr@QEVF_S_Jn2}GU10^HFKgI*4TW6@{C{_i`VzC6B?VidSMae-`B7cZ(V&ZrD0#f}T zx?zxT30qZq*s=Mz{=*{EHAqLm+zH)iW1f6&Ys-`Y#vmi8Msb3Oj3qvc1eYK-{A7hx z88MDDu)2<(Se#J~FtrP+YkVn99I<=`{Yp3YcS0LB2ZgdW59XgHBhp|mVUXY3RLYRb z3@TEydD39Qc>)%ySuHqNC%{gHDL(TLOn+td)ww9lXa>^KeIrPmgss5`3|~W7k;I~# z-Phxob+jRouD32ZbCy+(4o4)U;2%-DW6%u~+XFiCkP2Oo4&2f(E+lFMJS8dq`Y}uY z9lq<*@$>_&tm84vsPPE3y%|Uozw*M=g0Vmq-};&Qc!KPckO#oO>_vbB)4AJ6TAm{Ys8jL zl!1Q?PR;fW4jvZrCf1%NKtUb6atJKI`0Qc#6f3|zw{6)SJEcOSURaNIBLVV<4k0|( zzH!+G&kREk1>Uv3BMo(O9_{zRc}uKHSG8@(GovzoMXbk2Oo{SvmE+XG(Gj60bg9;< zLg03^_t*92rSaE8Xgg&-O_(qoUt<@^b0;Vz(o!_s4R=tK)mu8UI6RUhI{m#L>?n?> zIeRY8mf*CRB7f%lLoLg&dz>gl281>jM=6PEMk>_!9p=8q(&5`U>9Ijtk{%CX$v3F< zn0?{CZ|7jCnbPP`{JYGXG@xuU^3-`A?_S%?^+O}$OY`VXp#%nIZe4wKv~cSsK4U+QY|C1uFcK1NoUcj z!W%YIdas}xrj6z6MHY37W>mS>W;a{ayXOMy56!6lX>#mIvT<1@y9bccWrKl;U3|M^ zu!;f`^f}}=^p)E{13O!u!K|ky6!tZo%<}L>!hGB z$GPCmyJ2G32tjcj@lZkSwNoXg{p8it7PaB3+SMaA6?S}f55izA z=>pv{=*eN-mW8fZ?k&(2%bLqZ(Kr&KEZe>Ena5Vx_&9{M+`ncxYC$h|m1`QiqQqDw zo?dPJn4995OwYN6C9Rq2V+lIftKD;k87O9&z zn)51|eucVoWi+-$qr-SPlz2}tuX<<5&WV`@Z1P1K_kRL?TjdCN0fiGq3$HA;;7`qS z-f4{0s~83Fq4$vjLwk~9(AO)hVXtiEIrn+%3UZ$f`5@^m&JQO(8<7i=wsn4iUC4~c zth9xp?7x_%m%?~15uQQ-t_LaMzuQ77Cy0-SgkeLG!X1Z*|1(}4lAi9gp$wo}CZXJ% z$C&=^2T`a1T9m8^#e+?6Nf6fP(w@J^I0F*$v{y%G$1ZMlCI%Tzx>Pwph={G5E5s3Iqx}`@SaZ;hv$WYVjZ8Ykw!r5F!$)NglPAUF~9DibBdd0_)78 zg;^q_HRHu5^LO7!*d0cR#8d%?5DG~Zi>D8GEV9t5`CZ@oYJO%Y1sM%#W>iPh&GRf$ zt7`g%eNgOVVF1f*^mA^<%=5{8x1&s$AjH1y~##3DEQ|&R_XTTRzZ^^oFP8>T~G_A0BM~X?6bf-GE0i5fnj-KQkvjA?UMXFUXL32JERV%zF~+9v zKp0#)4>m>`Jh<8dlo&5CXTwii zMHfiA->Ona+%o*-ydr>P=ShBzi2WO$15UB{jc{V1g#K#lRfSd(T_f`6dHNeK?z3g&KXZ!)6^HQ zp(3E3=ikGma5864>{2NN&1IZ*&9jU?(k7if6iREYt;G3fJEX_c7=q=zgVv}&05zp@nKgID=yS3h?HRUt0zjX-uA(z zIcX4Vv!uR8t;*8piFI!Ap!ocJFQ=LUE@v07l&i!yr!!nel=LI|2kp}ta|omA{TJ%6 zD=+5D@jxb~%_}t`m83x@veISS!&kUtm%!;~)=#3C5YSqRI~TDzFF=j@IMjdRI70|J zHq46pn^#KXcM|Uq(d#O2ylAs3*IfXg?A{%DV!T9%m)gv>X|aKtsQK$d&>UizSTpfX zSkPj%I5w@R%2`xSc$e|i6wlYo!QdZp@oU}OtI?e8jy*eC8& z@`neenY5FIuml)###ZjZLK;TUJkr^JI2h(i1oHM!)z?54>|*?2 zgV4xl!~3mk4D088h5`bZEYWZ}4Oi7K1%NQ}{0{&w@3NncWF<6@eJG;UeGCc6s-Fwi zyg`Z5^lpAmCC zKAi;KW_}r8Y+{C;uh&VO&$OD~@raj#_AcPd(?%NUA715MZm)aJK~;;rk5Ak`FE(pC z0qpuBMPgPdKSNk4Fd^EX7&vCeUiV4tH-c+IX^D4h)TOhMa6W2A;RNqw9D2(DLTXHD z&GPWelNGaTv0$N-OcJ;`ze?fvI1Pt&y}ESWO4I<~$iGlrok;iy&&_zr%HsbrJ$3l; zc)E;>a7R`xP~VkWOEDAEp&zXX2f?|TC7_hO!N4R7jBaaHJ2AXDy{&~ansWLTL@~s2 z_j&cel`w9#M{YD1cl2SVX^y@h4XE{x-~0$FWMN?BxLRfa*gWy~6QGc%Ce zyMvrkxp=Z%Hr>5x?RBZU@DCi}!Gq3xniiD+^a(_>cA!=bj9L&j8ViN8LbtghrOB-7 zi#LUwbtLP#4yKH(N3?B?@5RYBRL8Nr2Aw%r$Gz`iWHY~01{Yb8WK^juN`W6s4?O67 zxTblZc!R-ltWX89SvwVslr3-8WwvYsH;VU<`A)J)_POe?Uj`+W^1atd@+4rMG{A^p z0i`_;4!-Wle>1ORwplSO>x!2AjmHa|Wmv`xAR0S}PAY|l0)1#rGBC%}n1|J)&#K;A zOClA=u^OBfS(_&Do1t#CQ{gww`jgVSg3YBrR!m!% z$G!zNlKCJ-`|BxL?G4>U;uO@bz32jHmrd=!H;POA95kJ?jV)h_0;nEv~e1mK` zdht)lh0joB4?OT^Vip>5y8Xa%(=o<+Bq0cao0vpAyqd;`-#oc$WvYN}Y(P{c^|;`@ zlcPA2Vk}P7{ZVyro@zy3nX+-Tg{WRTO^rQ``6|g$u&bIdgvJ-5Cz+(AANX5Rm-x8- z)Fwpk{S&&y;qNj1YWwP!=&8%Dh{lRP{MOH_%s_HH&Vc@o2)drQ%Yr3%HZjm#cup$s zQ(lnbh0;)Q-4RM6Af6RC4mNauv<(_9aO9J4J|c}^b>IwVWhP#f#;g?suzNch(!Dv^ zJ&OM3Fj_c!lN!%-^+qz(qs`}HN_1HO>aFDZnBrRte&NvMXeEGkBtFioECzyOQpggZ zc~eB_<_3|iq#rAvTTS|8{XMyJC|PTfu18kElx~(;I}2Bgoi2pVy|Zp-f|YbS$x=}= zq>_qI%UDzjRRhz0b$9uG@DbdTh;LU zXVW2jQg4Y!fUngUrqBfez|ddqMc>9PIq2Sp?Nw|FTSV5*Sgx0Jar zq&9WLG=sCicUBuj92+9#XaFRrEyy7Hm&m&?_2pY#W#O_l4+HXkRGfWF!b{W$$kN(< z>&p-PIg7*|BH}czF<0-)Zer;?e{-2O+-_o;7!HK$G*p8gHJ6)!WL zrK)vapt92LIh9uvmky>}IW>rCwZTcxupJ37d(BBd#6XG`vI#`m#dYXUMB;R<8uWU3}$OteT`67 zbj6LxmfJA#ixBSf_C0u;nQU$-Q~jamM-VWJX@D6e6#ExPjmuq ziLn`T>T=WnG+S_XPojv+PQVSWc&gxPR&!i#?;Rx*}8(#?O`blT6UjHj3{= zH@@P|pZ6MoLQn#?!>gCB2*w0{DW*nNk4hz#h|VE`+GA7z-a?7JekyF~+pwi(R`r%lsHhaz!h-!vo<=+5Qg&{g zPAZxDE35DF-Wf-6J@++2EYCm2=b!He2s0ZA zl>0R0qd`cLE~jF1Q$!O}{ugCw_tmmU?dN^(PQA1td{ANhFsEuO5oYI#GsOqxz`Omu zh;QRNXrO?y_w{SiW>0%6cudU8>rhD6ELlxVmPpc-!D0wpyKAbY`JnzpPxZYG4Okx4 zUY6Oo;7E^y^zRv@In0Nu2gSy#1bIF71t*c{|5r-!e{2`K;*%6Yv_nH%|E?Sc6H(1# zN{zFNLWA`3!%KB_`fpXa0C8pb-!ewNU1NM-?tiU|EVC?4&0k_C^?zO)N^!{R5Gx6fWn4qfK zianTaP_R7U>wMjKpc2R`VLCaStFf!VM7Q{X3~<+mSSj6WVF9#6Ar{-8>3B86s&-Z% zd?7OZ@YnKLCHUsKm_^hvxg&Jm5XlCb1sN*uT2wiF*}0SHw}Q$Q%??BzX5D{)XfQfD za76kW&PTUUi5F{J`}zM>|FTuz_T&Ft7?ddIciSI5a)0i zH`~2dG?VtYhHo(I9pPBMbe4GJE`N@1*hbgw{IzPbz6~?4*j;74m+}&o08Cue-S9nPHrtTyVFdngP-cT(3|Kt+Uli8^l%q?MsC31 za$|Vnb&|~^rFk)`L5&#G!;qN5f{Nhivcc_~{)oyypIt!+TMe3|DNFTq;A`RVklZqn zD}gp`Xtcwt{)=~3)j6Jp%CIT5h;aD21Vlg!uVB|cg~f!2!a0wr*-@&OC?9~W60wRr^k)^k3(9! z#5zV&$@$S^qtqo(&Ov;1K2T|*w|helt<~r!)?}e3jfmLdsuB##R=77Gfg90D8A?gD zAzzrANR85o>-8+B5}k;@wuph%OR>tRMc|bI|2G?|Fwf((8Z#@sq1u5y_pz_aUcVFb zYu}@Kh>!MoC}lmCw$z2wRxc0(ZGysz+-_g-4k7E`B08OnfmocL$qR$pFeT-BW(0 z&MAayNTIDQD{Q;ptdD1_1wkB!?HB)OwrK|N;8Ra$hV~XGjPW*N@IKRa7G8W|hoMXf zB(!&J*&$S@f+8i5R>PJ#A`kkhBO*hbR_e}Aw z_P@eIK=&=UYT|!y`HeWJ?+x)NeM1MfM>Ok9thrR@lFnn$i13yaNSgr|OK?o}&P6&R zwT`6_l8UIuot;e{v4yU-Jm*_SpI95FDd&_BYZLZ)az__fiVNZ%Hb@N}N_ps8Qff7t zb>_KU&qIg1?2*eXd`fp%S~fk={5BTRzN!?6Q&&Fb%G!!&@zn$JFunx5zZ*Y1 zvfH1H@-C9Z()p1=QgecgKq=dRKs{vi63MAWLE96Kavnb4;Ci2Aw zK}o6N^!#T@9kt05Wi@nogW7eFI>#5vS|dGl<84UN+We$6(JATxzHVu)t!778kXE{h z9%jg$!!YpJOGBbZ^O{RY!2>xYEq^DvMdPc8#{?F_oF(`3wqZT~yN(n70#%8G5}$dO zytFX!o8@k@w%AyrB8GUUeY-_fsoy3Y(HSB$T&n&=mX>}+*eBdb`A*p3s6~=VE@m=o zaYUk;anTMh%$k_U85l>TuNihfvEqaXu(3J5{t4;}5#6E z1ZX4F=fYb4&hv7w3K&9@Tn%K6)PiEV;XAz*kbkFqMW1;f{O>#zeO*Ik&irhjR(t}^ z`b+IW>d?PilgbXnk+)@O(J*qrRc_^Ly>BEPC#*HFl`ZaMof&RxA>N28Fwp(YK`Ax- z9f?oReo+B-T&8q)xjD#MC!}|FwxU_8sEa2B(Z85*$-KHrWpW?6unN6#RK5vAd(>$a z=t!eXeaVo#KO>Vd)k}**$@aatnsuJ1HTqqI%M$e456@P}=(EU%v?E=lNXfiEt~eVp z05exMo3|-_UvYgHgfn+Y4fh!BbvxvUeBLL_MYa4oQKru-9VT zavu&b3TH`&44U0hM(I+DB}|*g(_4Dkr*S#x0IGXYD3c|MG$)TA%tx(=J7%rB*O=W$ zWvZ37;J+YhD$}8pWX|qROx8wJK;JE^343#ZW3L%YO&#_g7Z#a&C;Pft7b8+bR7 zg3gDgI{J&zs_DDZ2r@9N$jrIx9Y{jCp!kh4OjqcLC{OJcUg!_OCxQ7Vrj{r#gaFkL zw}WqDESnFgWS^17C*{gE=(*2rE>qs=kUcd=I^*QXqF{%DF~UAIX_R+Va9=ikdP4(X zh{h=;)Ly2Pm|QawG6IY>4t6h7KAlYZaN0}Hk}x(U-SN_-2hFl6*G+xA3iFo`Y${zx zU^UOzI5fK~$fTAZ3_B=ZFD+)bN>w5}4$i1xUlGA$ZmXO42O=CGs9sD_-)_0h)e#q~ z(C05*6%v_IO%`G(gzFB%r&&~Tv3B4{_TB{#&yGoB5c+(7RV&6C=kauo&ZETU{!*e$ zYR%*x#jI=EYNR3IBf>QJSMH(yHC#q*WLTWarQ>(FrR4kDdQg_WiX@JnqSP*EQnH~k z5boPgWFZQ-H%U%!m9yGcC&W7`>+36ILfX8Dxk0|g8eUnek*kGTK$W8P_4g{j;lV+K z0d?xwi9+>J*xv9FP?GH9@rQjXf;dXPBpWKG0s=?zjpH#=s#tE_52IrglVtxy2l77? zLim>x*|Sio-Z?eRA;m$#G&H{TMIycQ|H>NvpKyn$E0G&vghc?i;PB~ zwX(*y0~c=~b`18~ea)4dB8+sfmgGB8Q-!pQhmeMAX!cVk)VAUv!;F?NK&88PD4%oK zOFsQki@le0%tr*F*@*a*)#&Itn^2jaWSuZn&ED>xI6{NGx6uJa5&0KGMXPM8%hP-l zs&n4`gTM#}JVTM16EklEXAy*StLmAQFWcK=;onYm9|LJ`oI_`BK0Pu*)mLG5yPZXe z^l(~iM8}|Zzu75KstHXTE63$xsh?$za7)t@(qa7qm@#Y41OJ-;8fO~!1jVo4a{026 zrLI*fp$@eviuKZL7;Eh0zY?apP}YCawQ+AC#ConiFz^gkgQQLeFBZ4)V|+ZN9P*pJ zc_?~YNjzmZ!QLTP(sXfivW=?z+o@;%T*;0No8NV_k*<3e+Y0w+NG1BJ1kv7@jHjjZ zW{>)OxY(X6EgY&nj?H-nA;o05CWa1ko}|R#szcTT*=o!e3Qi#aSX4A!mmaJ`RONuqbI2a7p&@K5|F zq@8c>o%&Jp3!6Q0C_Nht<5r#q_pLZRGWZg(c?vs5W(x&Zu(9Z3^zQ$0L2IM{# zt(Xq1ecT1dY`GN?RRE=J4WOj?gws!Us%gTa8)Ilsms|)_>~)V6qzMvo4hG|&p_V2M zEE#asC=%~{boLk-v7ZOl2>k-YWqnG9pBSNzO~frp9<|l<*)sftdx-fWMaEoqrj$W3 zRMsLkYMZCFoEKZ$yKq$#kXfL6qa2ZU=eVP4EGJ$=uW>w`A9P<)K3g4tAkc>vH8Eg- zPgLNF*pI<95&$Et=OE!9VKf`i!&OoD_(`dko}no%6$U!EZt4}Y8S9Br#7-_3o34Gb z@hPfbV&omSZ=gS4(Z-dO#Qqu@GTV%egVx`onzX@^`Ul;phWi|)J=_CoC!Z))(jN!h z|JO)G6fzsKR{g)WvNdQi^}q8FMx+<6Lfu-n?{fMRL4#P)S+R>Q&SrO@6_i@{K~Eje zcQnu-Xyd`{k6I|2(r)$2NQIxIUM73&*)UJzh=UdN_DrFtKUrnXT+*1LEhJU1oJ@99 z`%l~i|Hg$k$mX`tg=j5pjYBGT-8>}7Oz~aS8{A%d@5a<7{*U|BU=O1pD`#J<@_9F+ z>eP6@+z)G(im~|{lO%VzUD|5wTkF~6v8E&&tY35ly(`!b7$9b_xAJ=Y@$Y-X_T4Y; zl3#J)f`Be7gR;kR*>X67E@BmUdHvB`MiuNsG z5gm~kfa*EIQJU*8d>{#y*X2;|6ZWz1FOk*P_PJ7t0epe0cwt50?j2xoI$MM9-CPrf ziV(Mtkg8p|1(-&ev>PHB>F#p%dCj+Vl(X25;^9YLp`Dr9OYus}dxo_>FX=X5}Y@T z=zG-nkA?FMppj5=veCW_CnLE8{iVf>KpK+FF^Y0_^7sW*@;@GOV~rAanuRop1hB%* zlhHB(Wq&{6c3feYwEgW9h<|v$>u{m(1?)w=&GWT(p80--5!qOg=KnR z!53KRm&p;8Z3@aW538%IO(Kv$hoimA=4au*YQ#k!9%-?UcR0kRtu{8A_8{9bPXRBw5aa3 zhBBo6B2yASe;Ica@)4Tq+Zz&y9}^qQbWUD77CFTN&09XmVS4V?s`DisRHE;U@ABo} zXy`A6D>CHqJ?GXfW1S(4_=L+$vpxobd`C^9hdCS&tm`6_Qp z!j7Led^GQeHJ=>M66t-ep1k;CL*YEp!p841%eny;T^?-*F{HdsXFvK{>!VP`0;`Gh znf!K?au@*f+{Ef4CCMFX0`0bK^>4yG6m{qdOv-seZu@vHQ>YB=GfNUy>&Mj~QGW#Q zIv31~53Zg{sU$G6KihYYhJ;eCDS?lI?xg9bgU9yet|ofwzZnuqefn4(uH+0Q=;Vd% z9t2NOaS2_Tg84q2<_e%%S zmWv0c^Vrq>PZOc37QJSnx9=b0kU>~yO~;GaebLPq{$NMDufy`kJ{U~>!dVGN7lHu1 zLVyl)pixa76iEdKHgL1Kikj;M92_{JQqdJ!-JOosJpBNAeDjzlKbQ_>pD*a-0{sH2 z7l1}`cX@Mb<@83#UQP5d2aZsdS%|7(H;D{Bd7#V^58+4)QHy7r8FWjud-T^`@+u$p zVSBe5{^%zOXi(2Be{p$;o8-y+tt|Lm`S)pssEAnUGzjP7r;;&)0k6VgoUWNfTAuEq zA#wLNM$;PieXm0Tig`h5bpYwi4$>P|dL#o6vwP)9fw1$2>7I$Kg+IaHI+vo&@tf(A z*N>AkK#L!c3B40o*J~RsAZ>a^zI-m??~jEgka&e(Y`6Pss{YTz zhD&@AMrTQFiuN?DIERK5{%!?6g{3NC{3&C3U)t^>s9KU&7j?qEj_pMRorW z1y5E$5Qo;wBJV`Es)w0MSfNoTTM*4BaH%ZI^UVp?28KUGRq6&m9We~l$ zQhRJaEQ=Ih?9Dp)@V8F?!R~5hqSs$iLLVMlFZc5IJ@)vvFBS4a+0PF3=#j+=_d3KF ziZOCD=--T&JY6+MX&vA{*xfUm?4I*>@^L--(sFk73FgdBuUvPx)-D!k;;4ar~7tXf;YN>0S91>KK+Ali?7}WjzdiX8+uwfR!{%Po8FNd{JB(TVK9+>!LK ztN*NU!Q3_$CFtk;9?fMZpo;}a8GIGHUSpI(s7RG#pv~cTsR|D4r~y#aOgH5{zvWBH zx8dQWi?Fs2j<|o~daX4EwTkyixERB)Ui!O!y1&Kx;)17+@1_bvaNNPQ0c-qXE8I`3 zIAdjD85CkQgnZo9Uk3f4a5RepK&#>E8&=()reI2*U!{r?INs6(=`St(Kk)q1LX*gG z^vm_4*OU&Ak&xX_HAvIpvrn8(RgthcO#79dl(5F;s4zbrGUCnya;~VDSCXk_j|;X= z+1*d+o?8a1#j(VoP}2Gqe$rxNf0MPGmz*(cFSeg&)Q2^-KOe8=#q){GudiPPX)W+J z8y4L7`#=l+KM?^Z4KW?x=FEX2`@A{>`dtA*lrDN$8KIGToZ?fRP#hulQuMRhPJ}{% zd$R|+cw?x}nLK!VU-)HEzC`rhzOYi_zVtio&u1(!rQWueOdceC4mdTBi5@>H&q$%~2e&OqL>EPV^ZYDW?S$*UalEe#<>-X!w@g>%`g6lX$ zTHh}%|CsWtOAv8|)3y5^$UqsIASv#Un^5&Yn&VL*RxfY$CW&CKMHwGhyjOCpLp>nB zmaFZfXQTP$=A*u@J~p%a#FkxGiLX1(Ccxdg&yP0ViTp__a;XP_J(i{~EwUgaS^i)j zGnd_1y(z+OufN2h*RoUG?M)P6I{kfAnFonqrJCz9S8ME^q>fuE5w^f*w24*Y2maJ0 zPbWno1!w3Zh4$154bDvD&2S=)q7z-GWxe8*^+2cYVY{$k8DUZGru)2=Dw?C3?R zC1nciG?(KI_8YRCR}h>$Ia;=06051mCrZKjBd+A=y!x@r!Q9P9asrH>%T@a+I9}?5Ur%a;y2%t7lmL``?W}kpCi; z`n_`7EpxkurV5 z-xq*BQ@Hw?k?k26&HBdlqBA_!^jARp%>-LeTQYcuL)VW+{iVOP`A(O>Zr$kNWaY9J z)s+IZEpsRDGu3tllg4jJW>$boWQz@-mG-9XXaAn>`P<7A@7>>^{eTPDdm5j;{guQw zjmb7Ta7V%6pH4VW&5AK0#%jQ>iisfEtq5%l=7f~NS&9}CZ zZe2}&v{KgP_aqc!Ey)gYDqCwzVem^p%2v(K>jYm2HI|5d{qzy7>i=Wxu7lzT8o$Bs zE{nTlaai2leQ|dU1oz?~>o)8_Cl`!qa}oaD-Tc(cVS> z)&$pYpY`(EIL_smSdxTZVvdL9X6#Z_0$5AZJZN z{@k;^``R14N3^XTuFBKvw-Pm!wkxI5a)W`dod2EH!Mi#p2Ae9tFE0`MN62VsMeXA6jZsfVleulP;&!Z5h6+~^rz61 z$U3Fv#b4nmVQK}h9;=f$<7qt}kDO=rPJcC|bPYSZWNESzco9)TrCzm@TupZMkWTd| zA{*2q{`t&3-6Q`kZ8trmIKGJzJ)i99BkGavat~4P-u9i_-2q9n-}s&;$+lvryV;TG zXGzV(@yGD5)zTx(iI!BkcL$TNqm1+0bJS{H<_0PJoYHqnUE9)jPI&lS`?VB+5XA4zPEEeHn+i7 z<&;XC`(q!dwduJO3^$DW!C$_}eg2?iJJHRw=sNd_PnK6AM>VgFXd3ldRJa=PR3(RO zvQ3!xcHn5`wHlxP2HB;9{5ayHTg(|3{nX3LVA9J(W}7c88q+elC#^0WwbJg!LH(u_Atoh%N#zVf1*K2dv4gYe{C2X5sJB5EjGd#iRUT|{vKjxwBve?TjjcrTW z|A&Uk$pK}D{#W_@Kh#jU-l}Lo+5WeN`ae|YTgm@{hWekn|LyMoSVQH4a{UKw{ZF56 z|F?|#9}QL7+g(=E-PGOke@Il>w~gF9|Fh$NsZ^-2@P8E4{|A-I1O2b&`UawMKzTX; zSHoI9e9-?j43z)uF979X|L=zXC!xymUpMtXt^RLMRf~fQ%E9?RpeppOYf;hv9O?fI zlY^7@t(pH0`2SB)m0rJq+OncwStKD%PLY|?jq-Fa}1F(CNCnR4P7gBn%~ z;xnW(zDVX5)G7CFr>K;cDagR`qpD_tBWVVCtDK=y7{*<8^%Cz+L;w6 z{;U)PJ{rGVv%MS_1U=V08=nQ<72E~gb|sx3(R+xUI7JPN{PA7KO!q`h=S+XiZuIwm z!HmE35B(q(bhll9OIQ9+RSb!A>d~p^tXJjH>1FON=zgRiFYtW(U|YA#*qHkAEbwa( z%*g1ZAn;zjzx3Be;J*>$KxB%m`!TPh$Jfr2;}LR`zAyFm%l<|_7jM7sz?9)VD!7MR zp4f@t1^N4jHRH2aQmHP{FXSTwR~uM$l0p7yQJ`H-#* z!BjypXeTm}Bu59XAEY^1K8@_nPP|c`59DIcmjON(y^jS>LH}M>j00bFdq3u`@e$uU ziGCZtJi$yBi}Daz&%_|y#D)Ysw)H;UYhF_fygVBBygog@{#i4WB{%Z&?S0L*dKINy z$F#Y++1RJ^Es^{DC4SFa@8#yfy7Kn*Y5fcDAMYn`qxuT{ga^K+z`Ezk$^xA*=jZnG z^lfq6^NO*%m&dc-=j)^1r(dU^8eZ?`DyGM=pO=bv>Kko3KUM6FJiD$Lf7(k#-B>TE zuSh(?mh|ji6(vig8n&#?0w^h=wpylY!xt6s1} zT(?Br-pRK2O?qncO2B#nhu#$QE)n-?t(Bq4A+>Eb(q-d|(&!88<5bt&)r$*6U}?j0 z#R@C3xh1tc5&~hOC%<{8RV?PL)|<$O-Fh~A z^2saM|DmO_QnsOfNS&LrYJ*7Bo`R_n#+ zc)i7JXC5NgKZGKC4>xzBy)Wyx z1^3jQPu(ZcRIF{e=FpUOQK!c}?3k{Zffl`B-8i2Jrw>`rseEs1t%Z!)$oa^e$g`do zjITxkyY;r?#zlW0BJEz{9>>n};CniP#Om+V08Gw^MpVPDads`Q6N*3NFmX)+Eb^1wI z3~PPb^kseT=B%rA?-@?xM)>i^6%}b;4&qzJv6 zZ$B6K&ws{NbM@@Ea&@lYyXme+nopzBj0bmvfpgsUuD`5fQ^>6-fQqJadF2oKR(!ctj+Ib%u-ywa@>yDZCn&dA;& znwhD}j;f<>!+e3OfZvd=|8=@ezosJ*%()~p_?B@^(UbJQ{PQaiJIm;86A7|*O;q^a ztoc1^6-?&Bn+t(|lF}aq8y5{deE8vgUT$?AZ6nQj-K)PpW|G;mcp>ox1vWXZvcK2w7L%A+)YNg1?BO&@CV*k1ClCE-mqGS-)*8N*o#64x6z!0q0?YG5A;xuZy&M`m#O;_>@W7zsLhNyaGSoWJ2J&^{?OQ-~U7(iAw!8!n1Lfb#$aM z<*yvx&_WO_I%^gHFOlktLu0xh!!04{4Jxc8b#g66|JQBH?&QC09)(rBeIN(cwW1^e zxg)cqt5u7Ro!CzEHJl(_ONV(Se*2?2j^gK)(3stOdvPTiw5Dv{E{o?f)Jdw!%|A4` zT3CqGGb{}kJx$(uipj5Ch&`ey)n?$qK!9I1r(w9X;+{`YLT zlc_rgUfWxemn@cYE@dU;6nc8}3&FwX(B}Ey+cR|uF>z;D_g4ohiKz-Y&48~yj~O4@ z(2dyy^!x8S>7T@v63?KsRFprkbfvb5_b%YKw6Fo!XfC$7hSj6eVF-V7Z6Dkhr$&mxDw z?;it}|1%&kCdsQh|OTOdEh3Q|2?P(z0*6^6PuPw`I-tx9y{ikT3C+H%8ysRyHASH zxBEFJh?Me-DA6WmR9=>`cu!EgU3PFw!UAi?N7e!?4PQdIq0hO^V#ZhMJ+p;c`*Uyu zXu#erR6_M-LhZ5^1~zu8 zh&H$i_!MZ;;ROCRsD*f8BviQ6i1?{*L82PSB&BQ7>^V$C1pRr?X(|UPd#d70(PYOD zXP*eEe8fZkIF)SnL0d!liC?al+Kg>qLo2l-Jk_9ZS#igz z{Llo$IZPh@;2d_05M?qRJt&fo5Cd-yx~#+xp?yo8?tkBZRb-6aB|d+sGpu4CvVUqg zR{qlMk1Z#bz?9-$Do;bEj6>8-<>3eZ`5Y8qt zYHHRJ&B6Gcl0zTLKFPa7flZtQ{%j1jmBhgVmQDC8mNpC0nNhY8-N;nYaID*fr43?k zvnG%`9D+9hvXX*WsfD)D@JPjD*fDZRP9HLiuplv4pB6Da8ju8?Xeil=ZDLk;;2eGj zTIm>2yPB7okLDjLtuIsRl*%EMuwU0+P~oppHp)RO2-H`k0Ab_aFak`Z2R-Y~Ru0Lr zEItQDg!;hA7^3B?>*n!iEH|?$^%{p<8G2dHM|uGVBA)2M&u?e<$cXDT>Y&q%Z%^4J zzgP04VyOcTvE+k!#M0_Z=^CCqE(?rKF!B`{r$i-{$RpMZLUF0_YnL>+O!fGbGcP9& z%9U5jL&xb`z2oT?4ad9tyv><0@33KfmwP{*eLfH01GASLV2A}r8#4hYc${RU_TYTnYW2|a(;+}Hygo>V5_e`m#Snqc8U!qu z|D)^+2T6HYA7m()RDpPD<* zHyM9i0lb4uDf=*WW%rPn*#2IM_(Wbvv}_@p_097`!tP!Tu}H@-0B&g&Ufv*ZJDiNF#<*wH(Y_xyO1t&cOxVC?kOT#iAI8_xS&2kqp2UX8diOWifX(IknC49CmrB38y#NGuxvwm{!pZl0i?GL?}wLbfLjcesDwz( zN>c4!N7}ef4GPkkTNJO`;e(`}+yP6liEwWma5HwZCYXgJoOfPwa#G0DN3L7CbmG%b z_P}M{r?x}N6da&>Vw36X!aLEW-k^-_Bxce$Zy$Op2!q{- zKS5lN4G^<*Jt0NQjK#zPxbF>*qokvD!=(4Eu~yURHxhNeEx@z^hCYfS(v|gF;fjl1l;5MCDQ|jgVZlrk{Hxi3n{w>WJNwI zfC+vAZpHg1JJZ#3B`3CNreXpNHQLR>UB)q4s0MIM^gtZGQl{2L!y|AE#Ta3a!b3>Fp`}GT?a|N~s4snpkp-4~rOG8LdrA&|sF>DyqD=q+_J0BJN zU0wfQqXHt``PSMaQlI))aZs9v#wKX=oYPnA6)cW324cQOpO8o#5Y^|2PhyUlMEH#|9u1^tnJYqKj$-e$=DpHFeLyFts(J zZ9+oMsaC9gVNULsFW)%vfsa}?AkeyesRSN-IH#}ukdwQI4(Wp-gXH7xJeLCPaq@2KPfEI#~cPwOrItEty z3$EO}m>oeFmAe`7ehBMXtO)Iv?wNch&H332U={RjCg3HHfNOK!PR0+lPei^K4p1HUwa3P7oHp`!jg6 zWJmb*1T$jgz`J|S&@FHcM)kS_Ea z*8^36o^A{Oz*jAK*8waQ4L5L}{{A2eKmq?N! zrJmkzgMiE_eoG*WriRuD#_vu$(cM}mfTpL_SK7*)#}r}M)|v++U+p8uWQr`fbl{9&|AK$pQ#tEKdM@J( z3E$z$*E~Hs#1et<%_V?h;^RA&SWWw;KpE{|$h7Bpdx z!`p7hAat@?`YC*;^hkgl1C?z$syTlc^;TrM)6|!mP6Et56D{F!h}^R2#iRI7=qn|f zXo(>lI|H-e%qm79d_2&eBaFRPi)dajVM`t`#yYLQ+A}gp$RKUcj;nKO96UHww8l=2 zefMb_y#YQF%u*4-q;rc6o8dbyi|EREioJ+JzeE$dJl=@;-2wvVurNCU$H78g`;2Vv zPO`v#WpDVslhAAdBm{i(YlKo>`5g(-x@?#zCkhZ;9~^+Cv4mJ#;|pIH0i#YxC)id3 z{LZ0XAWm|@>cKvrF+1$Mcjql(4K{8Z1(@isyMPzbVW@fC#K%0bG_t|nvpjH~k^8f@ z)7%LGw#0x$O5j>F75iJn9MD-4{t4lD zwlno5yvAwjg|wg6R5`q5MKmhwcv1)&{}wV>*1NG=eE&gI?v$(VKHGco~E?2_X>WgxBY$Wl2&=)Rt0ovB56CF}k|MSVU9^BbeQq zEz1O4V?&L_)#z?M;g5yxgTjg4-*g_%o^j!?F8t|4#X^**nvh@#CdU1ILfpq6?SnRH zJHuZC*hYd5tsYtE^?6dz%90yEjVTxf%^4GTC_noIMv$>GVSt7B%W z5uHAwua`gH%9X<2@l%w` zcF#3#mp(bhdG$f0aAr@vU*g7+#sBONcbzYL z+^Oi)(r&G53Wy?uvYh8*Y2l`Jn1y6o|H^--9V)aRCGd$EQut4=5Ar)U8+luG^dI~* z#PN3td|nbk+R|_9+h;RM=HaV5b9gEMjcUl`d<#7lMXOa zyALwnVe27z1VW3Or+&xU%4jJ@@>=w>(ES_mA$A3E_TXz?MFcV0{nS_CMic2;fEt`D z^JX8I1d(<)v|gZc3t}1f{2S5c$ZJ*5nW%j6>R3X}+@f zBRvy>gApo@oYu|r34jDfU+p@eYn{3c4%mc~@o)ShS|bU>L**1Q*Mg^0KZaE1rz}U1 z5-ll7_Niwk-~Qp)K1^a%D`b%vKThEl*LYiHaXIiV8bi-4W1W?uBmMXuVUz=BI7jrS z-oxlW5;rrNyg}gOLPEAb5`c!$1hG`igJ*5G5ipGZ1Hv)PoQKtqcUA`lE)B?QbEG=(d8h3sH!d#1?NbkOqupuH$$gQi&e zE=k3aVq+aKQKfXNEJiebA@S83^2XKZ5E=+WJ8~OG4Hkuq3aUW^%Y`xlT!6KRxK<5< z%zl8yRJ+^tXGhzRKs}4fZ+GvQ7(t&Q#vwz)vOmZJ{=&-z0u~}-mKwf2%T-&8dKD^t zU&iH7{Pnv-@C(Q@B+OkEwb6pF61~6JExDD$!p+q8I=1ZtHG1gZB6RyPQHFjaB_--x z^laXx&x+1#pWAvOx{An?u`sZkG`4(&;{GzeK^_Zn_bhYobPuq@RgTcBJ|x47<6+>k z8om8tDOhZVYS2(Um|dR|?Q_Q9yh?1rm%~!NA>8O1>{#6XG4R?s8=WC*TdJv}R2v@< ztzrG^O(U?xPqJ)}ZO=^fBiS2=le0V=09?^vDu__xRE z3zDCxR7T(;Q<@<(Txw30mo>R6wuPLLeo0wEnUR@h$&W&j_^xi#IIEtk0$D~x?yEeQ zX-fyv!>_zrp;bs;jCX=Sh+nZxnd=ay#muf_apO2-d&BhmFd`fsGS^vjEE>6hm;a3w zj|eiR7?5CU$%XsMQqvl39}GG`{AqRZtT;$ve()q1frFm?Y>(A$P27{?FcmGG5fXQ< z5yIQ}vWM|_y51m9M}ebLWVa^qF=4z6i^o0eo&hbyRtTPaD?x4(QnlR_UcTRO|5rtf zn+Yi#QzJF3dl?f6VOkX#HU|nsex@Z7&^YeY{v9`MfW4xIk<5=b{quqk+H#@#lRW66 z@RKo4<2JO>F$*+-A;0y5$5uy!)KPV zQEu$_z+LcEv_>{fH&aAhX+pF^bhdNQ?7Oa$s8(37MS!kv|N5a;>jFgy<&qM+o;nQbPT78>smyJ)f=U)qQ}Y-wMH?VWubyBP#YQEjIj7n9OF{^O^n z?{(4ov)-}PQ^wF%!kUC@-{s7zUW$9l<1a=n`ZKD?^ht;Eo?3pL>(Oe4t|JI*-4uWL z;TbSAWfctw=eUjklKJMIY zLUbvPi%PqDC_ConuimE%@uZcQfZVO&OF;m(ZL|V&vU&h;x>!0qyz5T~py&f|0CPbW z&l9v|fYuaztJl}ke@`D}gVcpP)FZ;>qR1!%_w-FxtQR0^@NG(5S>L_J8ZgKcT+%?& zuQPOF81jkNBQMQ^npg z$!a$bjb=WV_>~dx}OTcq$UF=fzS(K`4ax zWl;nQrw>pp0BmP)tEqoG)?-HD93bcwxV8MImdM8yF1BNRtP4h?447bG&?oSpk$^!U zh48<>^)IpX`p8W0Gx!u_mzuNpPn-QCNykyc{sC8WX7Mxmmlwc{L(&b&qwQS|fCo_b zmIQW?M$a;I$&wTub3w+xTS}@Ry5qJ^-)H+CoqZ!q@MeW7$b;pbf~iec3{P;Y9!$ZM zvgrno%D4)tP>2DB>P?0?IgXnI&p*7-JU11|xYt29sW#7F#|G%! zwBuBM&25Ll>eXPb9iE6o7d;b1A4McF&5fZG0A(H|zP_w~&&MnIiGnBgM ziKyqu3V%`b&F-!Nn{)|(sb1ra(J6rKoZ{R&=)riEN*GJqY3S)Cl1yqeRMpLxoCL*i z21uJRaP<27EFM()wfeUh)1iz-2$9;wkim5TA5`6PONFs~y^B?q$`RiH5>4 z_?&l=Tb?U)&V4+%Lr4DJXo-xVew^1e2#LAZ!Tx6&Rw9)~u*8ePqt^1Yb}C*haL zDs2=FOcSw@Sfjx`p7f*PF}l1}n5uIK3`OM^MYITFavML6&O7r9+GcEZ^rj*X%@MH< z9yYCf#x;oP;k~kwEHhoT{(IE^`H4{2J>(1Lh(Xaw?bA033e!uO{no5u+LUXJJ|p4e zK@#RTZaZxCNyNs4n&j4yP{TN1NePP-y3Cw6)$Bx>eG4@_@I2gB;%irxB7gvBywqZe zN>EegnK;btBWpiEKaMR-2vPh1UXJGW8|3LQ(8?6dJ|s?YdcVilBPslG$CV;Fj}R=1 zb(uZ;r_(N|2S9-CQdXu+Q~9X4oa)^ zHlPPiWSa4@dz``aVMGb!%D!@g(gXM@M&qE_dQI*7520z4{}xL+BI3xfy8yTXbQg)*@kqK)|kco5vTWvQcfD@N(JdN(6F9wr0ZUo#1VXZHLqg(VIJ104ykr{jEI%Qqc6SIw|Ug z=+M*}x)ukhA^!uY5&ichF_yh%v(X?SUL(2|3Ou389uBgA_t_Hx5k#mv$U*OYs0T)_Ok&~MB4v=N;5(z?z z2BBQ_&CG9Vk}O)`rkxV>yNq+lF+2A=n-KsH3|dO;pz#$>{$SBjBkig#?15&K>x-zI zAa79aC%4Z`W?>xrnG&ighG5g-6wJo7o=>d!9fU91*AHqa=FnzwLTVaDq-8@1oVY9| z>OcazGl`zTAJm~SeUfIxXUgkO3ko0Oum zz;cmjvk}6{;kR-&s)kGfKhVV6@7Oei1wWPcE_-JeHi;qfrfr4ij0s9puhG)0#Hir1 zPRHh0?y5I~{hUop(Lc`;l+>9&&3D;Q7Pm0E>j>G*X?N|{kK-J?$gVe85m zJ>uAc&a_W=;{{jwD_T}8Ia`OxVVgpKGLi7&CyLn^0o&iAEl1lyUT7WW-XxS-a#AP5 zcI$_QWB|Uy3VIhC(u<3n{O{F2Mt*n#gMrwZfcs4IK2cN()x%X=$x9)x)(A z*4iO}f%nhLpEz+Vk%mHP%yqVre9(0vz%{4le(Y+k zn@B`PcnfqIRc*TnYbVu^9;ni3STm=bCgGBOk3%PMXv$_*!6IE2wSSl$A^NLlUPFj( zA%|XvdZujHY~~Wbc+-Dj!1)s*)8bgWX>D_8Ahx>d*iCE?%|1$T>0G(rf>eg$`l5{d zi1^}48U@|occvS3PRYnaV=?od-#2dzkkWarPl?ZSBGSSrJkKnF2M&H<-xV6q=mr^b^PBH!q4ErgkC>^iKGs%*aZ^X|z3PrvE!{I(wg*>Xir7WJmBCds)a zQ8F~z2)m{>Qw(^ZUqr5INLn(-l1Euo75T$sBVP5wtIGRXYn}{s z&MdqIdYV-1mV#c00jFH$1p3o6t(VnE2fdMUuJnap!UgsH8EIH;$H|Z^A+pJ7=hN|% zNT=GS3QX0Po8)9TnnXdd`c{OWlG+c!;TNT``%c6dUibnUEHUj=IFonVO_M05K$>G5 zt;1&i^QHK60Je>~9R=lwd4h!iIZx>9BdV!fzY|YgI((_gui-2U_j|}gld?`YtbHLQ zJC+*MhbOfOMvDK)l=g!!c<-#I>3T`CWjc5(JDxf}#MOwEqJL>Z&C=Bg)xLyep9^DqNIG6kyf&;TpPMH3Ii{8SzWpT2{DpQxCoaA zx3T0@gmF7UzlIlVr!)FNs~)9ol2i>nIg1y~mMw}x?!8xWayEZ2*|XRY70L*xo4b(W z;zoopB3}5~{U#%tWFA$Zr9(KF5VBdLPpYwtpH78wOqDu8T;DX`Jt11Xfm}!x|a;iNAG~N zOF#c$azc}R9k31yfkgPo`;j)BOG;Sbh=cl}#>MCWxJV0A@b@fU+|sTa5+wuIr%WAipM!OM)l#i$O zH;tc$a_`xj$RVFO=SyTM{aB_*_#xVU z*cR`TZYI)d5_vwRxexpLvFeEBBp26!Dx8wc1j!m;kMg4(>iCbG#N6-AkOH~rk}$b> zBE%{kK*sN9`Vee4e7y~|F9Bsyj1GU;Zy0_c16=3cx$^MF-hY?uW;c7nDvcBXxJ{;q zSh0!9*n5yqr&h57qm;t?_-&*xa!mvKRGg&B4}gHnGM*1q?=`*nx7J#2>S-4NRW%1r z0-g+*T?sKmK$(Gz8!gCXuv6FNwrIz0g^gH#I?K06^S7on1?#MQ98 z7@lq(RL-H^X;yWQvqo*K;lBjH$}Ui(NPe)-u?&u>)e2pmi<(S-NnT(N{*7!#}QhCQw>|1%650s;d);PJrsgnOo;A)q2t9 z8<4nCokANgZ0tttiJ5c+PnyOZ$5A!!Q-I|JGGu_$Q-&1ua{X($76%;k;KG|pyl}R` zIzA#UubKUU+GQq5c^2~ZQe7YK2o)UfZeI`iQoFWsuXQtDLiEy!9{>Isgc_o<(X59W z3V7jKJ>LbDkB&q|7Ij9b*&2~!m)M5MTG@KLPBEEH)*o0rD^y?rV#u&ogPe}xVOZ~& z9&L}foIZ)Aq>lz`FoG?JA&K5@4%J>du*-vD&`rJxw0yo&6QrRCvygR!eGt;Fv|9!g zzi()D1#c>dvB-SYBjZWFO1A}?03<5XeT|dbp|V&rX~RwWdH1z^DKZSP&NKe@F1b*5#84A=ieswoO>O^xFh`jlP`34gDzV$!Nb+$WlnR{7IN9aLFOj_N$y z#PagOs#p)=)G#Cu*oQEQY=g&7r$k46f5NRnOZK!W2`|#i)FqEOX>@IS?;C%fQD=SV z*p+RvL^=Qk1eM7Ymg!pkS_*FY7;dC>E5+Jm77S<0 z!0%+MlT@BoaBs@glYg0-EV)l@c3%22jK5qy7MBr+eju&UvA{aN*`_CJ6kAI3bffU= zg)9OUC18x2R6gur`@&|R0Nkne*-uY7)s!RGj!S)TMUHrPT)BH5n(>^ZsSlDDk8Szp zC)I5@k-P1>1A{j!rpMr-TX6EFf~li}NvjUZolXA%*fY)E>m`r=rnW=UTxrlkN{-~O ztfq#yb=g?46cMDK6&&~{X#h23`?2O28zSe_TSj@w{)k(}AL`ubmn8op-V_$gyYN-{ zFb4W9XC=Rxu;9I3L)v>v_pn)X>wTHrk89>u7{zNK4v%9+rOz=rMmcm#%BU?Z$}`f` z74Y-9`a((5s2+Kag%L6+fvzl?_c8K{==h0R2~kErOm4Jq%x6i*O4vJwmJ`iiG(UmMD;K!FmtsGl@{g7u{QBruX*SP{SdDhi|KlA%y5^G9|`;-^<0J4u$O!LmSu zH(SX^_fjxt!qira{Z7?p_-FVWv)(=XliHGz7R#PEHv-qxVqD9QY8yQ6zd_5~5j5MT zY$_^WIDG3_N2=Se=Cpo<6gh$cfXb-yFsBa28R2&P_wdw+@* z>Dh^jvPGZ5Wy#F|$(bJvhjU-~N@!P%;Z?1#P$(y&fVQP#-x{JyIYdT{LESioRHAFR z?esniNXP-tVSC4Xokc1be|#=4L;6D4vxHzd`Intw0l{Isi~}n;rT-9lL zv;$p!wQv5~$nH-lULWNuZQfM;K41y$tE3A~R=uX9;Qw85pwBg38!^;gplgJBA6 zpO|u{Mh)i3lN||j1iX(!^gN0Q!592T%q;3ZDsod0E-wYub>Ka3tg)#gIxirvm(>$U zFaE@y1l5(qTuzi$gk>-8>u4oRZu@#V1>FQ`Kb3y&JpXFqGLQOwXxWD2^X!$!AnC-S zLY+ZgYWGmPPjH~8PtFS1K{=(=0O=o1UaH8!P5=DY4-T$NhN5qk8xoXEQ6U|cF;c!? z;2dE{5J!^%<_xS*!yuMVo*NX)5{rjsFdPHyX6@eq94n%QbZ+Rnenx3UD+YCigSO%V zV|OWE4L+^NJGCUwuxA@3I2>Hd6kV0%5Nq#!DPvH3AKdoRaA*b9i#K3D6M1yb-FcC@l4xNP24l`KMoZI*x=0w}8r>cpQD<@a;Rd);Mco=8GUY zK+-$olt^SFaaROXi&#FR+tANcgzw9#+Zejl60(f8Y<#SUgGElG}Mg7{p{iY%> zqcuymc!&iS5NeuB=v(BXUsw6LF;-?$A5X#i&~d_tTF9pJ{wVntf{lwH-|tLtQje#& z3vH;RC6yAOs2b7=w>n2*kwnl3qX_+SrjGhdMFn2+S7PKY6B?3`jeAl)ui9_tmSLQ) zL7+5ThVHZ@qbjH9B_XR*Dvl80+C3AbmRH7JK()kVNts$neG50l_pT$#{HY)mzV7NGStVbJi;^s3ko`MXF}IO~2vBtbB>+js zpcyvZN42$Dx~;A*#iSKT@-_neH+3)@yyZ$VO`t2tUhQFv;kL6TA` zuQ@A&9dEq&X*u~efgpm7MM4_IpBQz$WkPYK%5ol~BzuxlW6yq7V#UeaLTTj8jq%u0 zj#yAiVJtz}1E+(qBbdQxEqo)%4kVak5kRmY7+0zU>@f9@Z@v(S&a~%Qj}|xCIu#4| zD&-<1C)Hoz4$X2p3QnMjCdon3tM|YF1J@Q<$Teo!jjQ28bq85n#Q6^eHtB?1VOen) zxT08d{Ho!twqHVLcL+qKR?^D`*KNXZO4`3(mJYke$OCue0EaLo;=S6We{elNUN1f1 zmyRqaUVSghn)1Opo1zj`p;DXE)~)nXq*+b4@U{%{Uk`JHK)4K8>fi0>(viP53lwL7 zIHG5Jv3@8`4$$yBe#$&ji%*jU6jVCv%7dYpO1%pZkn^a01z!9w=>cd}(QJDF8lyT{ z-zWePfF^<7mjiV*d?Tb2H2lz8_kvCN`#8uF%;8n@B3+D1&;bI4ybH;$t`kf+fQHGR zXpaeNL3Y!EELd>=0MK{xsG=i0cZ)q3d78bBa)jxNMi-H4rz2yoRogZ zf@3CuEvR=B7F2_$cqDhjzI+6ZqhMBzK^X*SRK zz-teRfS^N!x@gQ(>BC%ZE#BLGcC>(TOF%{nf`$q+277r#P@}B2YeE+&N$_^QHW*vn_<0x_>B0&>5{LrulaVEwZRVKY|!H zc3ab~D{Fow;d6`FA&6>1$V=mhy|#y)Cf^cTdL*>A zCI@5tk<^Dtaj;sT+lAL0o*3efo$yl^_c#`HVMQJmA+g)dfYsh>zC%a8@f)7wgr^9AALhaPlilG~aB0^qCQu`XHg7_J zY>3T>$-h{!O7QfzHIQ3GQSaKidi%Tl5L^liy(d(C;Q8DJ7tc3d%?T%F4rjdtGFW_> zra7%nf=9ncPZndVoeNMpsNr<06SW?8o~#P+O6f~p_7&LLO3${4?+rFW&38>MfD4Op zw1S#Lkz7sK*RI;5rE%ebLtw>eQ)<2+H+%5{PMa=zna;L8^HO4}sQ%ho`b+Ml2)3u5 z?7*L+(SFLQv!s8dU^u%-*W7I7E#hD~6@096_dTPQ(QB}>odnx#TP+s0xi<0KFewo! zi#shueZu@A0C^c4Esdf^a~65aJb(PsZtONLk?=y?b;t-QXef^L=v#%`EG_D^BwA}{ z((#xDSWUmr*IzC9ry}5wg4qL7NB0@34jKVPv^77&Hi{PBxZEn*>5Pz3;9GAqM0|lpQdQmi8j; z8yN>5%tzn!Z2MG0g$<4np*K^+`$BB|r`{%E+QKrlzY(GZf;DB6^c)8R6&!6-&q@2t z%I9n7!hABMB#kVmXka4F`@H~acOilKj=6q#cb|4{_64L=DtzvS;2MG!=l)(Kv|xjP z9rXa6BqHet#uklvePOu5o^s~NX3H0YvacI0pUyXRH!=ufF7#bZLL5<8Xu(OK!WGC; zUoDO7my6G&v}@Z!A7HkYIm@Ap-=&z&vDQ~?KUjSklR_P zgY)3Tm%2fzE+qiP3Jih1%lBr5ggUx94g7oYLVr+0a%hiuH~@d2c|6?Tm||%XfO~BC zN9Ngwm z7Ios&K9{QL=x{o*hl3!M!ULn^Zum4;Y6Rq)9&UinA7 zyxm&d58;d82WEyg+Jo8EvkDGO+l)#TsGnWq87Z z&R6w&XEzLXcC@$Hj*I?*o*NJkqh<%kkw2haV$;3cNVNZKG(nZ#brbO5?uOl=c=^IEPtSDy{=NXwRZ zu4)DFdV`Pd%-Ev~>0*+lklQTA+LUSF3Rs{uU#zL11M!J2g_M6VYfeSu9IqX!_8GL(y(hvQy7vL38Yxb2EXa zI>Hp=6a?G{2On!`1#sg#INf4WQVvLrEO-}w>2t>*P_LMg>yjWC(ld$$;LcyzLIgmU_64jzp}&o%6?3^{$)ou!fI*Bv6=SRMv#jw|c>?6t@56k=(>%eD zi~BuF7)m&N07?Ngv$Cd>Z6B+_2XIBelhHNMsI{xl0F`h{b!-9Hv70}J&r+QsJ$w15 zObMqvj{q<~>nJagERU&7;fOz>if;Cw0wJA2U4Z$uV=I#Olbsqji2gNog+xB(O2f=0Pg$v7%nW(q1NK(7a3H&s$G zfSf`l1aA?H*)BV3QBGVOz_=qb1u__qKXm8->LS1r?PARQ3Ll#o9NTH(9{HT`7x#y7 zY0tYpNYEXJB*){)1yD73KfgOHpsR&{4WR&Xs0aRa`eX^HtA25|jR16G+Tx5EX%8eX zRab!fc&TnzFc)!P?oLc#4n1LNL-4BLugwN@Mhye;G0)M1bZwd}cj7e>ZG% z1NRaNVzYAZBoY|U>NX1bNDF=~Gq0d}h@e2j7_&;{93ZFgExKkY5(OWr#ZDvVv{<$d z@qI~-87|2&Nd~w8Q}?#oN@W~i+3}<7@ruDtriLmoLY{lHNma=%K7^$s2QVgJLO!>o z+Tf;}e^kfDA&n|jSR>CdHc(HEcH9Vi$p?VW^Gg~j?zF|m2xNJJ9L}N@g*crOb^$=c zif28a)x7Z4+|*x9l35AE0IbOv zoOhkToRY~=ZtAT~Zn*VF*a_FCAP?Yj1ptw_bq=y3V`NeAdHszDCVXyE%#=*_=BDAk6WC%#K-ssU=kRQ3=voYu*{`M1H@OD(&gE7 zs@|nDy?y19+r6CH}Rwe0-~pm4v**&VkTsbS43j`i z;QEhdxpo>r)xnz0E`NYt)}}(Mi~v1fj$e-*#yw@H3zY3*qAj$;*uiQ7KsIw2jYeJo zIGw@IIYH9)0jbEm;C&@b!-kvJPWSJXIKz#4F>NElp+`1h=7Zjc0oW}4>{&S z9RYkJs@zZ_ugDe5SSTvs`EzJqMhjSkg)0>W2gVMA1YfZf0egJHoMkUV&*>C* zfP5hxji@~Y7>}zUMqD5v_DJ_QejXy{2nS!Uz*!qp@Xhu63KqfeLit%(nS-YgxqAV# zJfmjJ?k$*~tr$?SGHH^B#Gy=GCh^Fbi8udgq`+SiOJLDL;+zY^vC&`=YgtMmrkSTg zZOF{?sELb5Ja*~A-_S;U44S$MrGC4Gd5tKe?-{_9yaOa=s;+*`=@IXQmw(y^tfRJ0 zfKS3ufbQ}Y&|0F7NJ0-_CPE+}ANIjdF2BMi_t)xVu(}Me9L*)*Z2+*GtHza*3tMIi zC8GfX27@lx2^ga4J>o0^==ZdK83shuye!^)Wo ze|os6pNm#$fJuX1My4}zw29;y$sGHD*r2EYy_MY4_8Lb^ElKJHye2FedA`ZJ*hZea zJ1HmR$)(jJwZU`j*_{9|Q|Dh#Q~IH%oJa??;3rDCp59>$O%VOzZ$m7A-aE&$7KvHZ zRNBDf>K2SjOgxt*Q-C^J(%XIn+uuRx+YmOh)zS_C^9HpKv9`XEk6ph)&BU^vg7<>I9%w0O0I)28J$@8K6Y5q3Eg`19c_NSA=h|m26+mM$8(76>kjq5T0O$*lJOM63l+Jt%IY9Eq zC8@VX6ajBrAqMamjLJ0RG{l071PaN-Sunkrm{$iXb4L8v{9) zcz1zDhXK@Kg6@PA0uo#sw07ziRV1=Gqb-Ojb^s|+N)BxzB0Lcm05_>B^sOS0$3|k856+EH7f_I>u6G9=^a3KJG`lU8HufF zAN~0?%mT4hwo)5K;|Z_}2JLV=C%q$I0NI63ley1|kS3)MLhS}Q{`_>WyH_eBh9Eg> zL;#k1o+z@Rj>w%m>AQ1KB)i4kh7-{Q$a)bGdQ(B0m~#-JcZZk&hs=9EyqYRPX~z&f zTdpuxlqUQT%&%=v$YmS+-5X+5(-| zen~Wdn?3td6(O-ZH7l5iq7Y_^jxp`TOs$tbe z@OOSvHKVAq0?c(AT^6!MZtTDejf7ygIP~OPYuQW&HMvk@#)&C|wJ27ze1EiDmS{^N z&^%MLlirRJYVoY%(Q`et0CotTjmusDB`(HJK;?o8iWs;mmq^<0-P<{>FE>P#Zat2U4baid?685fr9BIk)dK_8CA)??9iFvsWdrf z#T@Yv1VC_x3KHb<($+Z4 zvd8|9+a6^mf(J^jV{#643*_t@NE2t9JOIZ;4yhE>pN+Kb|L1uJ~er)*P_cXwt3W+`wQhcGzrk4nz3PC zEF~|+01-1E??{?o=hTjSmdErrQsb|XYihkEpfQNQGM+OO)K9v?In2|`5XkmHXoBrbWJ{LA#~~L;7uk+DL_!S^SR78`N)p_9v}k_v z7`N)iMv7r?fV|nQ-J|Q!xPWu)LW|@W}R1T~1YXf*-6%C|GxJabp4ao`8 zycNmOSSSNyE$mtI!915weFul@B&gPU^cagm&L?Lq=SInSMnrtBF-(JOibKgFvh;vS zb%`UffL)sSxCo*z^Vx+ntGiW80P9dJqojtEA6sX~Hmi0$nX&x#1dDV-Su$0PG;4C* zi|ntdySv9VIh4bXz%iJdHA=%Q0gp+tC^x_UL4CqtmPI+HM*|XO>(Q)?_R15_Hd!lW z5v~;k0oQ-sHW6P&RvIN|Rc76G)|08Q6&)Cy+N^_WsyU}6A94D16h3DBdi`3lh*_!vq4M1_W__L?CF z?t(iDlwDWL2`>UZfCgjE)iYL5k7IE%5x}w#^zD8%;(zA~16uU-*%-%#(;5xZxg624 zwiCMti>MN~Z>4JnvM8@;dt-UvD#Z^3g&ZJ)0rSu{M5&pRk`fg#4vrTAkf6wC7o0s^ z=cO-5aI5M{pMDvDIHuBQREfxUdx!$;{wkDWem)(*5D_(M(Of0qJ_nv5fIUEps9nzm zt5wl}nFe)V)Jd&EaaX;w#HeZ~d$WalSXH;nH{CZJ$)y+sk*;t;9LxcwaW_Q(bQvcA zh7e!|ZVL^DEXZ615NYO4xk)Ypn1n;F)~*E({LPKTJEW%92MG8E|66kLY)}KxOwb1Wwt>&# zB3{?~e|gT@K!UMZmmMzBA}2MF*fQQ%m^y?1bQlXhguuL-%&iOmOhG8Sl&AgP& zF)1kw`;2u(AzIyz@2`cqTF>y=^&oU=)E_{1uYqZth{m{81T~!S2>?^c^QZ&Q{wyuP zMB)JHLS5IwY@aoZU%O6Xpq4A6-9X)70)Cnq=d!k;HSz?%M4D5|bA7uj5$b+e>IeZ^ z)sx4mvyiSN`x3CAO%T-dP#}c>_*6HbSYR&9M^c8eh4;}Iku{?bKrBo?R-N+f#F`EJ zidTqRN=?Z!UomS(a8_Z=whqP-3i1XEC`s#?fCk3ivoO>(oJdN(47-_FXW&tW{g#xY|u@7%)lwdPa*^#@`m-(csQ~qr$#8(3&>2PEWI1+ zbtc5&tk%0LW7G)1aiRXbFV9Hbimvvc0%tHk7Nv0?fI?0S_JA{ap8W+eo_qhNfcXzV zx2WWDIfR(6wy-CVjlc3H1T?E)8JK~#>|u*+zQ=}En*rRo#q4|V#>^z+B6zE`0I*M- zTJu_a$TCDLmVVQ!Axs-r;~*@hGKg9}0D=q|KaK>zJu68- z!vX*=4kSly9o|koPKLN)pod)4C`f%54qz1_Cjz?Af~W(&Bf=9u!4hl)>B59hJoAPp zA75N$Vm#vpl}0=y^d}2=$%SSMO2%^)C_FHYpo*^#)5IT0@{MQ6pPPYbIKcDqeu*xVpIBrlVq?E ziV2bqbPTDBJnXL_5S!UkouN*EDI7LIeWU~B?vEnLru=TI#<|h484Rxw z4t5x@y1&e`0tP!~`>U_l&sncq=EiQUY&Jp!Mo86c%RLB5y8&lYJxTxaNoZ z3%&TEb=YMpNWP^f96<-FW@uiRNyXa23dRCs8mo!2vCYMe7~{y*KEw;4oA;xh5LlJ3 zVSTp&NjM1gvY{1zx{TTjMu-ojQf5K}ZIp$qS9+G`?y^mm4o@Ixw^Ev=6Ht(AV`W_4dEV9Eo4 z9!O-D9;8AfiA_R4ivsvq?LvjewAPP6_=+e2rb{{+is(40i%~t#lihj_0&|R%k6J#xUzmHB1;qnCm* zN_&cLBcn8RWthE8&x=Hj6#yn=!2;%38g4u*4Vpys2GYz|dB*vv#2ppSRAyDhZY}o( zHi=089?lf7AOVNEz$D8n`$3!!Hs4f&vF;@Q=RK=9Tvm+ZpA0wYIzyER&#wJ=QP6&~^z6bGQ0r9<7ji2R)c1()rx)hfSOoj-{!dRan0?$32$20rPb|_0NeV$2{ zAYDjmd-x5f`on}iLwgTRC8iTY^?~!)Uvt|PCx-;dgr|{BPuP~6KM17;xHtvGc+GbwVIf`TkzF5JSRx9?&h`Qm4N8*~@x`BshPeb|~dF44jBB0UCY?MZOYwd(~*}H?g zh_w6cDNn7n#XO%;2Gc7Um*&|(vh;-@GqZBtZ~2TmB_-q;DcC_7oCPm4R5J|?rUiDM zjWEbw>H&Dp?rzH;nK^{OA5!gT@Cjkurv-VVX*^1I*oykm8?sBG!-=TWP+bW`C|b3U zOLRsds{8$UwjPF0X)JH1frMizDpX1VLSyYZAp+0ZXiFAxR|t{iLyx4Ct}&-xKF~6= zLddMqh)zZ!wIG31EJDr+4K=FAZ~42Yba?Kzex7kFC}hkgPqIOM4Oe}B>2Cr7!f1^k zp^e)@%@3?)i9m@i8i81lF~d zc}r=hiHUezC*w?Lg6CVlM3m=IC6JEJaNV#9UpR}Q1j2KLM!`2?$S%&!Qnazk)HZ8&o{y~ zR%$e5u4{+}(u;kQ#%I9vpVL&P?It)*vlp_u+?pRgf)evv=O75H7R&sl{h(3om0 zh=+QeY)`)Br)0xR^e!`?iA5WEISC0!@=R0!Lc>bNk_BILsfr#*?%0MIvxsFhDO-@D z?tpaKUAMz+F)&JVaua|>91(bFjz+k3L?O2Pz^6baV@7W*PK$Iq zyJNQ;5+u7SlD_6saNLr)`^Hx!vd5Qv`K zL}n5#k-TLE2o27DkK8ZeVo(Dv+T<=rV#itA2C*QQ3;7!9ySD^$>EMSxAiW$DcD1hJ z9u>0`=ia!=+moCH)SY!Y_PY2DdD8O<6f+sKav3RO~E(VR3ai zFUl+Ztp|KtB3i!EQaH{r@&bTqgk}K#B4NyFyfIVt8EXao^Y>a;#+!lrLJj)_O=AL= zl!#AuR}N~r_}g3$p%sdfGmj)E`kdGSePj#_elP(8Q^)0?TN24pL7eP2z`P7`EZ^!5 zv88Q+rA!|PR|#wkQw`(RQ)UX2LL3CK?h!6(qf_T<>~RCtw?C&fX!K;RP=SsU~c zD^tr^;qv5()#GbQ`7e7D#_Y z+}MU&^jMl=TZ^~g9Fuk@HhP@e46Tse^MvmWp~Ww zU$JJ`_}V}?U;EaY5Zxdh`E3~g(phOAM@qUOz899-Gn1Ln%&bBwSu#6)MC?)#2Z*y_mqP9|_QmZyv zG6+=?Ght_0@P!o+wN(U=_!@}26l?LbeoN-$`p0-)Y@_^}A)CVhK&5P{?GIo04pPwK z1K-Y%@WSe;=rdyDHPeE+3~d7;cmytn$7#AU9N~Pq>RE8o-sMUWI70!hqLO-Gs(9*PQ6+kolj4I&&^Pd|*u5rU*FgCT)!1`ni0 zvr9&^5oI%W>sy#fG@2&U4b)C7xIv)0J2F9fLN~+B-(0IJb)x_daM~D| zb%6Xvaa6*rN5rChD|Mt_84tv09R;2B%9;?Yk)E2qu^69r?ziA8A&0StKbk0#NRza& zVVmKWgr~pS5arZ}3D5kvN=S0YW`8s@C1 zphdIDM%65fpA9pW?U}<^Z6acSpv&s#G*Rq%Ni#OZKK|yVM0$hhCq6EEh1?GP3|939 znyAi!xFg{!9O^Ga8`Ha0N}Zv`@AwFVyAvT7$YIV$EG|Ie%1UgT*Xd2vW^O~W8gb$2w7KlLFkL8`nwut@+<*_aE^esPb zBo{{Tsq9F_c+EaKklgeDNr%B8{W0qrF^2=&yvH3|WdTG)?*kuYd;7KCxNoERArn5g>=cC4%vLy z^$`RmMF34fmB=hT9Xpq1wuqwv_ZxXqi9@=#Evb5tO+uRlngRf+HgzN!_JMd-5u_XdJdnB!N0f_D*ovla#xa%fD9_sShFoZy}zo7uYq817U{o=#{ z7&fmE`-S}0=Hx0V(=%oSz%rUHuGLDabsn73%yNzfngR4z)vziFk=dT$4nnIz-J{{o zJejQ3DhW-6p$8_a0UC^CF)vkz3Zb2%xg>P~ck&F!4g0Ce@QOYDT5>J_z zfmtZLF%Ezx9a{5zb}6*DE6TZ;wq&-5cMDDe3N--qjDag(@MNxCEen;>A9*L>q+P4-;96f6C}co}Jria%=nyk2+^XgHnI|uA9mdX1bD~t)yhpEXKtEXY1LZm<6i**ytpb z{6L6(DCDq`T(O%J1k9F53@gKF0Zm=2jzp#pzT)naNCRKV{bBgfZu)T?Rx|L1Br7l* zAY}zBgIxgNU8S1PAs&TQ2xgo@Y1EZx{1^Z+b=;<;B2Yrr68cFQoJzxpi0#5mc-YwP*Mq1j&R80eXqrzi&wMbJ>P$-e=p7t;LjUTKHMMPPtw9_s) zBE$(k04mkGHaQSCE5R4d(Ee5Z%*gz#=GW~`Xxn8dIfJCg*386FM$}++TQCha-J~c|>&Qfzxz)3k60FWzQ8aXtQVbexXgyd` zs!V(+hEH0by&$~n_nHgdM!@@5cxC5^V)n~n30zaMjMl%yZFLVtu5VMXIgMAvhSys? zPw5nZh=)iJ7B3h#LNZPfrL$EX2p%unr-aA{^v4L;(F( zpW|SeDsL6ID`0xOMn4ci!H3*cV7h2*#zz{tVrdNv?Q*(kCX8^*Q8Xr^U1f&tQ?t%Y z%pUqxiYj!0d7qfy0xaT#L+CXL%>8m_Sk@_;3Bp_bt=k3`AZHM*S2u_xLZJcC#%$P7 z{+S5T2F4DtM>g~OMg)b+KCUK?M3Pg|MUtZQ*30!=2x}cMa^9%ZdYk%4p3uoNg@g`^ zSTLMe0YaNrK%o-DGS&$75Wck6k(n4cV`#xf=`JOR4IBq5nhk$6GFWk?bgcVC3$#8z0)g`?0puaKBkBalhfU(}E}lY*Hv zutnV`p+f)sDoQodYoe@T!h=|8(lobjs;Mj!Dr(3}UO{~O6((vV7v+v(zA3xv&s=1T zq>1Cl9THHY0*1bM1?#M+7_~Ry(RiB_=vUD9+)%7+~R0le1yMKgLS7fT|&lX?<1V& zo0h0s?8Tm|Dy;1AVabPbo3PZw$VOs<#4gBJUa|6M1A_-%z^oBJ;$9@Ok7hGGw%$hh z0!eeFCLs!Rhn+0StShuR6X4eSt8RN;)Hll zr3jMR9*L}&Yf!O{CgQ1vVGLz6E_-p@KD8-p3eql?pS!qXs&HBrmC!T0o08 zBQ}em8A__m2wXBwNE2I$s4D$L7|{=mh^Cl4q(87r5W`%N{idT@R{xA?%ivHNO$Ex+ zor%~YnT>We0z?7Sdh{`YEStW#J|oXr5w}=ichz4_)mERsJ`bP@Se)Y#($>zma>a8GNKi1~){JaQaVf#l4|bjZ)P0iT_%@C%b2sBbzsO=5@FlPBk4Zf!?mW6eVc3#m0rp1k zL_}STa2V{0V#tXWctp*J$Q%4KRtZA{->i)}lzMk)tenApdLxgQMZ^ zU0X)FusBKIatSfg=dyPGu7)6-E-Uj~3xgr{r+U-Bf7XN&lJfCrgoS@>goEo(vM_3d z(!pmkSZVm;+@i1K>}I%5J$Bbp482R5Hs=q{-Rw#Kz~7MyDI1xh1fU8?`KUL~UR*3= zV%L3^Gw`kYNqY>ae9g{Xx-+Ji?GY26-A`=XUHwJnP+-L-0X)NOQ>P+q`1V|K`l3gD%D{%#MIs>^lfjpn!{!MY#P(GAb|=i5%DrG%Zg`o zD$Fq#p+9|1VkJ%csANUqjHK{qRx}hmHI~n*vA+JU!3pt=RCHU+)Ps8j`Aja0JF=<~ z3J43_m_0)B2HYUo3nBaJwh3^OW`m$t1{~Nvvr$7ppi7`h^WPvt_E!@ni6%|( z(!}5$A(-nn?N?HW3~NN%COiBf1;|JwH>hNqAR|j7e*lg~c}rH7mr^4EiG%8-h}CIR z(-_1BW0BNRf=thIXO#4lGqf>AD`&cu43&vV^Q~?o1~GyX@CRXhsYhIcq$ETTJOh;F zX)>3A@lxs>ywoa;FA>UQd_7Vl(mQWxlkg(Q%(I(PL|U)1A9KebGb`#nGr%U}v{@y& z$7UGvN-u7v>m=5GR$H+MDVx|b&Gf6kZfQ4w&aBF=)h8juw!kPI<^@m*qc@>=DR-Tj4R_3Hx{}`z~ygd|p5m z5m=`{NS5KXZ0+z8#L=c3Vnn)u0%YyDo3cc#9i@$e>s#4<#-R`5@)D<^Ul86;n|Z6L zMv&o5ooYT_;s9_tO`6oe>34^I-6>+n-V|$_u{t6{(oqtT;T3`#3W}J5OVi9@10-}w z$MaH4gh8g`7AfZA!(apVATz-3SqPG10%B21?r=u9YD)oPs~8REK4yIGY;t^ad!ucJ zq-eoA)f;Su5A#w?UO7|xbtxqb)*aCA*hyKQ>Vt~bDS&9}X_K3*DqSO!*xQjnempWw zhJFa?beu@WFD+8roj^gR+uC26Ap4=-`c8s$zr4&bzhWj(JL)?|#TncpeH+`s;IJoD zz%*T?$X=3)IT45sft0->nn2q`*aYUK?84)6eUi3ljCI|RMkHcGAXuvuMDa5;%y>3P zw;#5jvSDVCZlrs%)^IH!%i4q7#~P21#dB36J=c#tf7qZ|EEGCQ#V7j1dTUWSMMG^U_Ux8I?4 z46~o2aWr)$adZXMU1d5y!K5;;qL&a+WHc3BS!_ZA3O=*~a^-6`ljlzI$q;UMRLu<8 z-&6y-Wj%;vC7kUsh9Jr7Cu+yeCu7{cSQ-egEdn4RAl)}sqRhC=ZNY#c8+k}U65cWI zT0qG|+FWl#n=b3PIW& zRit@qWEd;1wAp4IPZmH$nn&+hUqj3O<`z51x7=V%J?)FRVt9kJA%;EUMpJm$za=ZL?}bmWhHiG(aDhw}uZJ zBm?B9kJz`O@UXQiu}hv2E1%|y98+c%@+Q+4WxNy;mO|^GCKt5 zA$fr;YTy~OZ%n|Hh8E0_Wd)vH@Zs4jw(~1R@Que=SK#md&=Ei_oG)mH0J_^$!0TWT zsae@zg_FhF?9R~)oOyN?NU@9@33#^)K-ZiFvO$NjBx4k?7*7j!@SslujskU!D(6{Z zsnO>D0xnAnMEwI`^xs-=XwG4Ef1oY&?f~;MV*=zK0ts2uqCjgzeZ>Z>dd{$1jU3(N$3aQWO5(6#$=! zB6yyktmN4U0U$rAfoMSkjD>0yuOg5YIQ2}e7qC$Frime^s#-Qf6`2Sy@{HiBcr1Jk zfdLeqZHraib%B0m1)vrd!96qawwymANaEMfK)PJOqF+T)BrXu7Vk|OmahafW7l|Km z>tenoqL*~DboiepnrkYXF?D&#$P}c}RuK1>fOK=HNVi#1)6xTW$Qcf0!m^Y$*$u|l zhz6p*70-|o@rWr#(aCc+}w zoWd54v4|j9+wqiP0?#wm@+5#DU6c`d;N1Ym!dXy<>9M>B|lE|fqF!f@JT<^~5Yk!CbjW@z*J zl(8MacpW-U0^?EZss~8+UW0Vwhuu)qW_-9~CfAO=D@SC0)sZ%-`ypH1q~KfGaN|at zl~?`>g4=qoSt+nh;|`W1M`f6x2^Er^#8SD*GABSU5sf6lS(`LtR3sY~L7LhHQLsQFN4p?~ zi?Cv18QzMVgLDsvZE{T-NcWxx!PaMetNLOai{7*uLso<~C~s}E$p7W+U6L%xkuAx& ztsP_UJa?tyq6f+-Dz2;R!O)rXk;D&RdP<-SM0ko%-DM{-{td4JjRl6wT8}O}_d*%et+b&xg zS^quMyAdTfeVGpQ4{m*X znRZl>Vg)9m0Ft00(=WduntvEHY)2OnGe}G=1PVx3Mu2RqM8r>gd8B50R3Ta-?3#P# zhhbSqmIlGTbD*}Pi375@k4Rw%_u5+rfL-qRZ2SGrmU`*`?7rWcyUEV%xcNR&!C&bm z{y&SJ${AB2+spjj$0cO@P+E^jSJHr-g-$QLZmQ&+iD!_ULQ-{>NB=uWQD%@73hT+N z^b~gT)GbJ=o?MuRlv#b11IQ9RXl=A(2Fg}w^k?_`xO9Qpv{A#a*7^3|lK7k!lk*2E8?ww5HzwUdeRe)l}IfF{X{ zl%e4wzr5dGl7uj4g()OmiFP!QC*x-IFI^}bl{)QYMRR!G}EBc)h^A1M3 zr0GMxl#C(Y?9TN z?yH@EGvWn`KB3?@86XRZVgzilM4Wc4()%De2-k;Vu9@7B@D^bVn7fNC{ce_K);Ctl z^;i#t9%EXcO+uY4LlBaX8>c=AuL3!(MV;=&(Dc6!LQPuMNRAgMZfV~4xR{527z_j1 zHn-g=JZw7rB2*x#e@|d7Kx-9tT0(X>MWox6^r@FY>Roz@5Rh#kaMQu|MRC=aFDMe% z=*-`%5NQtFNMzOyRmfzZe=zDz4s5h4XZ}#7!yZ?RN2J>O1y z<#|>2rO@MNfvw}a5PB&an~~T7o+$>Yf5_RJW000pBQ{RssZP5vqs#2^<((}7Ik^bZ zrZ#JZfzbkkC>KG_FQQJeoF(6lM@@UqC*H>VA{U}At95WbzgjGb0LAnYL23+SX#rMA zZ9t@&Cvp*F5f>p6UYhh`a|!v3LFz1+Zt6=iPsEq&O}+0bI*d%1=|Yu#CJVK_@4AB= zPw$Ae@6NWCr)PG`GTO5sKVAgNA9DR;Qp$szwD@})K>9_n0bB>2d#;AamI!vgO4wBY z-YZhT*~2)od`M5h&)HQWvYi>?_U)^7>_12p(W|m+lqE_9k%*XF;q7^dv~lB^s7zN8 zQ~|=5RK`OjdAbZTLm#&hu2t5`FVgG}1A3}2RMf8H6LId)M=&^~#tmXfSk?_>-;>7I zWG(<)P?Gz;#yB=joAU&W`Ibh zp_5ds1|XC3mnu=8&BV_f?Zi659Pv#Lvio!Fjhh36u;B3P@x+S=Q>vvgqt9ksJO{o= zD({ZoK$hWQ_lkWvffFWn*p*?fr*i<33LqDhblkE6>h(IT1e&+c)G zvreFj`3EjT<^av*JiAg6wp~bMx|-23L%C6Ec+f5x!q+`IDwRND$1vK}bdFJ{f+DTV z14dmVB5n7^FRqFdS^}9om2V#rzkFx+B6MZeH{OI9)Kl_rc9HCn9*DRl@d46tv#Sl2ASal2aG%tO4wZJVzDeZ4K}YOo|$Y zlqY8VUAeBY-6B(#4xskqPXIIl2!&ouz z#Ohs>SkH7yKAIni?aW`4vy8sDA*)UT?9;6RTJi#SXhuEEF%f{ayRD&C5}0)bz+L8F z0DtbKsy2VW%_~k@b8VlU+EjnacZ^2>#Yu%C2=&TiA^_V6_nmq<06S<@C;CX-Ndqb% z*_gU#W*8UwHvp&osh~s1@*L3tcnK%Kg=hiv0|5TqRu!|Wm7xIKj+yh1@C7(?0l?t_Vj28yx&yyoOb4Jo!k-g?0H!R;u=7L#_=EE9B#+yWT~=6F2zLCi zyhg|m4o%{vA?$fXqk^)rVu1ND0f<$A-3AdrqX7GC)PNpY#(Mz$;&j+7@&K64<74q$ z0MiGsTdxG8i8Om}1z|@Cf zc{^c@Hc1R%{J^WhXC>*>Aw&TdlHo{)`@59)jULOKsr58muCZl}9RN;+*#-4+<@c3d z^vLhp7gm7#9F?}i3qXqkd41MUJ^09)q7psz9Mwub?B!yVt^Tm?y+kZTq8vA$S3n3Dn3j>X`kV$P~~}0N8gB1T@Yx z$&&>FieiAJhzQ`IK?A#z-7>zbL@{w9pwt7HvD6YHHzBN>U#OOmQeLn+qF~S-e|(9; z>_mWV8(O3La3GG^2LPr@!T>vZV+|I7@?$Dp)JwC*;YyRK}W>UtS^&rbI zf3j}Iq8!nIZT>6GFMu_%Mgk+?;eG&5K(N2s{5zX9er>vNHPlXCqmi8hm^^?d7^OSS z#~_hn6V90ax>x|aV6ir!e}H}2LqK*U^>F6CfVvvsG@0%LbO5kVeOLn)q5NAKo1&_Z z?7(M(#?TxOXjP<7u>jp51~|79pl@U9pro?_xPj1*;hpUW;N?94mwJHFsND*%oM@cX zB2?@Ww9C)*KqmA|NP5gY(* z4}fRqDKCyPXAAEMh_0DRH;nghmv@|)cT<{ z-tV%1s1d>;GJfPro3OTv{2^zRU%;guP{WWBH6E6rL-tFi$p?kx8;WezDgqeyknx&d z%AVh(48=JRcnB#*c^3o4Wps-2D2@KR=-l<`ac;8$q6WgfsyjszL0ZhE8Cls%h?mWMm{yM7IE zlhI~k8AWt1ACXyR3YG9M2!dVtWBjPcp)&~2C}RwTVsPh0jlYN~ssw+Qd70oq)p$iE z3o!;nIk{9U9gWf*$}SB0f2Jhr&Gs}LTbN7*zS{vMwvZ@DR+OmUh3gg?6)8^yzrVQl@_=tiVFL4{r2lOT9s7s(nnD?kNK&OtSikbwH21u{Br_vi< z_C6$FjqW^QtavQbcog0EKMewnbM-|XB3jpvK#i$AFIDlj=i-?JhtU|cllF5?+3$t3mAfS=qTSF`m z0U2`RfUil=VEz&6b3=603xX8Plkp{1jfc_20d(e89l%9aa;bdtb)+1b>3O8c36s2+ z(k+5^kk+gj`{`aG#J5;mBO|d3dfo1hfH6gYsVxDwFCg)|Rs^89hl*=&Wr7V zCDPhOCa>pW6bU|@aBdBe3;_F#rmJ4O22MS4g$xW`!P_t4TpJG`K{zk>GoydoiD0Jt z$RTI&~Z}a$&{b~BYkt^OMY6n-bi8hyA=k>Z-T zc2rb?;Mra9i`C9NRU*}Kp*n9W557B1uBsnbT1o%c8+ zg{CPW%rbT0)QMLq)t90_r!N7@K!bIsaOHB=NI}xodG6FN^8LP+hgoN8>~xv=Hf{2u z>&_TN#z2XPg-d;hDbq*r=ByaGl%c@wQLNUWvP9szaTyE%Q^eY&T5bTH+|i6h@C0mv zQ6=h4Mf;`);zFbVJT^Td#E>||whE{x&sZ;np!-DU7}hyQsx{h2hFu^1ol!B`=|3NU zMF0vZ;M-v8+Xc94%AG!LJLmNr>7ZVtO?46j4_vP>X4A5|2uainIID(=Uq)FZKA6D%H$<6$Bpt;m2e@Pk2<0d7Z* z%oy!kfahqJ=0U&_57{(2&q~X!G=Q4}0B_j|rF>yZQa(_jlqYd0>eN`i2ULA1QM#|e z(aEEdLZ#@IgstIjjJz5RR45jb26$#CnM3(x5ET@! z0H;L(jClc|Ynm;DP$U02VM+ye1E}zv9s_XbOn8fG1$$-mCh=>NXheYBo@1}v_5*;N z)=Om)x)VHsHOlX;6Wyg_CQzQU}C7D@QiwU$Bf5)3JPs%g4egTaujAfw%etuEj8J{Ys zL7|ocZUg!vLL$C0qu_qX$@~DQz>Ac3BMI-&^aXgXIanM3V1X7N@#+wOou?GASFWkV zYMI>y%FDvDEI$D3w4BG1Jt4-9?IP%%Q?>~ys}`VM6)KdsdtA)DLBs9@A%mJpx@}{I;?RtS*0^@3xHxB4u z+l}8xy)cO5pq!|%fd&S!PQhbN1m!fD71W*pol@+E2i-q`x5m@U050btz@j%z2$!8f zgn?xymh#==HQ>vj`-t)L#6o&KqFrR*P!TWCe!J#TgdngQY*|S00LB`4qy#+f#>FPY z)>2CB38oJo5oi^u;D>uC-~C=jitwWVwry$?hDrsB6A0)A15Eu1WNSI^&r6JbPy@ri zZb1_)tH6x}T5)#h?mYs#Yu##2Zmf`-wkkjhkm#z)$&P&hh;}u!`K+N0Xqz!}QL)Cl zoj+{+S;+Ql(*>JoirVu%0weXrwupVggZflh^isg{Ljpx&0ytd;a5v{s!|WM=B^Fr& zrDb_i{w*)M-tT+BoUN~G(FeBw8?bk74^E(7K{~f2>o(?^$B&60aW%u9rM7@$+S7Y1^F-Fidk%cIAnj`BY(;EPu%Lmwg$C$=$ zoyL@j5HSFggmT$hn6n%ouEH)L7ErM9#16FvyxgxX@f&d-0?1^OnxBR|u*|9hY^PPg zO=N+sfB-urCZLW31kk$x%ro?E*(NmO5^Vt;x_^JioaT4hz54D@vE#Mrwm#z5gw}B( zfLjCrJ9pzN=qf|*3<>TZJ}525H(IB z2|(Wfce@RMIVu1r)v*#(VcOQ zb}|k$~2&fAx4w538}*d*5uMA2H7iZZ8tTl{UL#u zX7;^25mk~^K8Sja?>e)i>UM4iJG_NhK$8i84{^E*0&p|H^8tec4BXf5^9Zq>z4~eN ziT(E$%yp9KmcApP9|5pK00QNj5&lc<3+OVLUYAiS(4KmGI(3X5K`_)<+BA{U;y&cY zjb$n8+?l+Xg0O;D;sD$icRV>jeA;ZfdkJdK8jnlwr{2uu1y~4C!1JsC6ZZrp5IJN) zV0D)RC*ZDxdwe%PSXS16Jw|_SuR|vQ%eD3}cW6zG8CJQj-AAs=%FdO9nJ2n^b+au2; zzm1;e>9uqn!KoEvH*^RovkQFvDi!UO$J8*qNsUDUd<4p3nHKT4+_@BU5uW+Nr*t7t zPdUZVHNZoYEP~S`_r|O)lZ$}b$}egmSA$ilUo17ON)3+0)^mtK-eAjqiUVRW;|gG2 zjntts1UTUi$#EcB%AXS{4VuUVaEuEexxinGlvqPGEW?f0rTo>{C9~s=G3~8A+_Umz zI8T(BOw*HQ0G&D}R*6Y%|)z^%$Jf*{#|@u4PgV;S2A*&rZg18fcjTqumlLXy>R z+6@ypV^-*a?Lt+ir~H1OnC7D=1_Ri5KEdW!PzVSEEK|wvpecV$CMc-952MirJd>X; zP_Cd(m4={z8yak0v#I1t0_e1n)Byck-ZD{Mj+H#|i*m3TLWUo`^NzY0A4U(6WbJ0p?H%xU2xj!hQ}BH%?%L4`8mS!1W7*-nY6p zxCzW564+_AK0DJ}kKOzX&0iih+dj6x!)%n7&{KIspI0Gphqz9T*i9$c9U`}88kk~~ z`JBl}4IKc0v#kIO-nk|d_yD?N0LSA1eALKQd}f>_u!g2a)*)+RZWomCuA=)=0BB@; zf&U>n>W1hrMF>h&p1UVZow0o1-h@(=8qn+Z%6)=>9OaW$l#$1j7a)^b$28liwXCfN z)9h4+fIgaB_7Z&O@^t2sRMgM|qXse3V~Ns#0cNXE!=rxIVEhj37jA$3lGhjc|MN>c zg^{7o`misnW;}qY0yrgxEoCrO;CcnXECMXY-!_P-xnX=}zySAh&rc9w>;PxF)o6Je z4_TNR!CMG0wNF*YSUhrWm(?QR`~jTp44_-=siC)H#L0^69j&QI=$MM9*}}-M3CL&0 z6^2)v;kbe05ciz?eL;8)vtospVVtE_C>6;w!onal=w_^Bl&E7Cux*lTJ2-+G3pyY% zjpTV~X!*SYM*0DkwJlI26@4&D0YH;dVQF1f=x7-aj>`aw`d~HIEy{Vbl&2^FG=Rtp zzRzX~7)|*O5bFOjmH2(c6DI;|QwC)qz0}$C8r)xc^_1&1_bK=Q(ZlcK(k%!0j9lyR zm$@nItSPOn>q!5JV)@LkBjcsd{8Rj$_zdOKA^>a>d{&UMS+)RMVaf&*J|qB8jPs!p z%8m*t^)4v4K76M#Eq!v>e?*Mzo26_O|H>u5auB9m4qlABHJm z=sQbcWBkf=PQ-VvY$oE{B(I8qk-s)C{Nm2n3*bm_uB3aZ(3>+B1n}^g-u2WndkHM% zxg!892yO}U9#3(+rPu=W9hp!zrp7d$sRUqL8o=F~E=w!Xk$InKz?mBNvEa2u=(|^r zDF;}j&-=?tet@0#Qm!UrEBKRhfd@+)?wl`q#H-4*BmtJN=KW!w0R>oEBO9iO{Vh-va_tX!@G6cZ^)IO#`xxDn7#wcp!3eT@e^|PlUUnKbH5-*!YjbfkuQK(c&R35 zq3}gHbr>4$zO{t_?=9+)SLQPk>;a||;?nc1xK5yUm^FSruY|G!NMNr7C`nGKn3aw0 zBV1;uwi%%^bn_Qrd%XeJJOE3M4B#a!_1RT40a-9N1h%6sUIG;W>?oPq(X9o5TXld- zqq#@{1Cc&ifTb!pGUXstc^_(JDpWMe`I%l!)@8+Pv)3>5VRDrCF`pH{02`EoCbVNL zNw*2XUvO7W+2p`5PAHXf0ZfVMox3zM`% zC+*Q~lRUL8U@9ag+zn9HK-ceiRg7`egc|42E;;yoO*o)05UO`tGXVIH805VY9>O}Y zJmn~p8O?F6_fDvkPy??RQ$nNb!ZwG-=nQ*|ZYSe>Q&Z>M8&yDb&<3mysTowD%u5;V z-a)w=ZL!OG31w-S3i~d%*L{>RtB5Y5q%DfjV)h@m8#!mc;r+Q9*p^0#T)-JL8j9>B zC=A9A+J$l*GIb&epxhm#!;C+yJbh?toKde;hx~<*_)M`>ft6O~%_~1Jp!6%Lv0Mdj z^{}S`>pE_%Nf-hUx@{QIgpB}JHe5vh3gt10{v`Sl;D(Yf7_}bx^5s;o|DmI7{@O2q z>-nxcU>}A6bv5=uUO(62OOP5{<_(1T+g^>!Xev-gv#}XZ0eAb|!MhIy6SQ~bkv(Hw zhT2_ktktYHCZqd(UgHeFbXCIta6$dj?+v)f2UG42vpWVe@bLOIi~x=oSv6N4V0pIQ z)`HQE&UV!pl3WXm_*VD(1ykuBZ z8mqEh&o~-|1#mtIHA?m$&##S-3^;e<>;L<2xf5=4Ximb%ay68*G7cuIl5*l_#8P*e zG}o4OYEkb^T)$U-idqhgbNi0A4xv)s**VIHzwY~JEio*+2t^g6F|MhK`>K|9sVPc6 z<`|@|DH|@rx6BP_FOR#%--pNIO8JWR;Kj z-Ba;S^Hb(Qk4DWkW#Wu|QJ#RHjKFdg*IS=!Rr$V|&B-a8aYDM~1X0Fcj7E}-t}2=a z5}HJ!tUXP6dPS;mc#z;z-)uF?H#~J`ai9oZnkyc&M0kp>3-rFsYzbESSBXY*%$lvS z5D$TK!DsBXb%h=n3`>zvmR%~gBP26PVX~_0X8FUq3ne0N*;&)Lljsc&fbd3rF;aIWtB4Z;up1u(oGb0vw_Q)g_yOzLc0R+x3G53?KGavxbWkpW z3!-TTa)y?5dWuxOj$HZFKGco2f2Yf?Ya>5_HtML^M9!O#^8)s19hXrr{ zerTl9>02kOL|XpLp(YpYT@;AFnpOVK$!(;~JjfFOZ*_P|J@d?%3n=fsKx+)L3`1W5 z9mMxb)((02ekLJxq9>j@&q_p^19>8LAWpMLjQ{U{aBU(IPM66uUKj{yv{(Y5wGq%} zp~fP!0@9?a4_>60VX4!VHzg1!>L;kU1&mPOrtQQLKxYf}+pY=u+6p+~$RjJ%gwp<+ z=yQ&^e#@z_Ms1=;5*q@@)_IF+iU8RF^_Mucg1s;m)ro(fz*BDu-!_dFyl)+Ek$HFh z(hip;W-rm`vGu;9U>ln5)Yz6iKt>|ezt8syc)>Klj3R+ar4a<>%w4ED(zAS$ZKjAo z??4UxcHPq74aMb?IZ6RxAH=(4PH;B?Ml1$ZWW z>kfdzZ%O!Jk2sx3zZ^%KSa}~KuIvLWdjdVc$$>DQakzIM<-9f2W02A|lzhZnIRO?A z0PvW3_vR-Z1nL$PoR$!XbfEDqD?s!J6STcXjR+Vnd8W6Q0zdRx6hlT^ld4rIT24F? z?*eFm`8_N%yj~3|GB=cK6Dr+`0DQRr|6;d7|CqVMdr}=?kN}ux7~(JlwAcbJ+M-Fg zDvx6h;(QufSm2JQy4eF{UlX#OW)x&5c8Ih9a$9iLIfRt_JXD`zj&uO0vTB*70-0n7 zm@9~EiDK%q+(DHkT!vt^>SkPF_6NaY|GxD-($GCil_zadXdyQdf^k&_F6*s_yh zVD^db#4j$+a^+~JIGzi5iwqJqGnLDFqfW+ydzWv^-d`g5oY_kqzq0|bOOG8^32oBc zu?Ywg8Q?ST#p$Kow@Q)<h5qA^>2A!N?>X90+F(?3MW%d8eJOKL||*rgLB zi=;&@36Vb6L7gW}1arxTd3aRmK1Sk`Q0P(+LH4x=s;Y-x*6Y?9>5GK8I!F$dGb{|;&= zbVA|?X5tpc%@^BYw$%A7gNS2bM$bR89f<(Be>3X4CJHVu$#>~}z{HoP2;%0W$YlqM zXdHk%c`}N&Bb13;=5&G)zJAwgw~xTIrGiprM4*-WEO2y!=ku<(=K>`5XRpaM8uIvf z%%!4H!%0v`74Q|XZfZF=Vh5Y*4y2orgTOf~r2^qT%AWzl@ z^M7@e4N}gp(&B%9{kyoEZ$}!sHn*@Ec0!)jtUfG61dh`KH3v=eE12GULeHsS0PYWM|od@XiB*Q@kb&X}BM1!ovv zYqA3%9jx;e`wB1+t=~)y$_5+-cH}}Jp9V%Ks%Rk8mnz+Og~fWw^5(Gsl(kF+B5U+Y zz{vyH=MVt8t5JTmR3(9jDc}LP$Kvixp z(lP>>_4Jbg_EI-@8_3g(-+L(|ZOM3~%i{7CBrSlVr*|@X!C7UK`<%}}JS!1dq^)^kq(-D91`zNaUdb890?->M3)+jX z1dbR#HI#SI@62{;{L8UR;Bk?FQVM_=`=%?=A(P0fRLB>Qi=LOH#Q~-^sgb~hGiL?~ z{Ip-N>N9a+Ujix7@rB6rG3bo)+Pu)Tlu3)Hl*q5KtC!qrlFD0?5hUDiK*&R)~3_ zKpGRE)DW+#fTL^TpYW;I2TTkyK(^)kKv0v*6Zx2&+n;mHdEC?|z%r%*{`>{cAx=F^vYw`x=7;>e%3` zBR5tju7J^|c3nSTBD=IsutojihlHVga?Cr66(AkSBR6`VT^j>*O0e4?53D@`rQC}t zkVyuR^aGfs$-`${ZE<;oh!!N~8ak<3o|!I`{X7XX*@XGKEDx}C5^%Knx{f6P8U&b= z|5PB7zMUMKu$zR~7R&(1HNfmjLD|iWR5u%E(vObWyMK}_)y{}q6jjUQP*WBtq&eyU zHcCRkV>ZHf18%pR4YpJg3t32)Hu|hCLix$LgDMyb!0u9^MgdxM!LyBmm1?6h$4out z039PdaP~EN#Tu@K5nI~WEp@hagVR(|tDSu-_W&?I^G*08t@e7B0GVlU&z6zxqEnTZ zhz6i5rS9Ci@~rj`zz$WyXniovw~RIbBq;hZeIai`*OYJRDc?vgw*sIUH58I-C}7W# z5Sa}&Q4Kj$MJP~5nbFM#z+Z&bnBwz&=teV&l6l59{fkc7Qd2|fFx6vI%wRK8-JF6U zc}d@klQ^D!CH2Vkcs7psLmG7#bY7X}VKn*p;pfPa9r&R`%(s~}BDbACv>B8ipSN@v5#Z$wcsm|{`t>-5kNfsr3ec~A zb6IgVyICNZH2%wxhCbFd{)H#0C&K=u`0%Bcv1W_=(ukaRbI zsYIj;VeB}=+n`w(FQh_Y6r&fT?FP?YjKLx%6Nneur3H4^QP)TFiJVtkZ| zr_{gfYj?nIyvc62;qLvw?jA3yf$5{cPI<10c{G~RdTS{8nHTN&6lJeO$C5c#`_`$?)CxO>b;h|NX9gJE=joyWL)?Mg} z(NdN_8SQ4>a3g<1N_HoevbxA}YhjrVP#&pLHW)*BmbGOh1LbjwW#*U6nn=eY zq)U-t0o}6wJmnp^p=|7$@(cmWYCc@^-JznoXa2aSiI1z$9%Z*dD9U5JLZe0h=+se$5A7YZ1ZDq}0el^k2xC#)=cFk+Ib0rjAA*4>{GBz;vLaaR#blJZ z!ocPr3W$U9j(t+rQKdXpLD?-1%JbPNo3;2$nYFF{wbw07v=<*z-;_>%pDwb@;!s{J zzcRz4zd3uBom_cDA#d6DG2BuMDZ2;EblgqO+Q$}``^L{du=g=OulyRzCt!K71JYCEL0n_>0)_zx#BgT#t)|}nsb&$$>53AZcNNLS6EJu$NY_V8d zCR<8;*1oJM3CgiDY2-{jB9EfiD^Z@c1)(`LvcZ;;$c4W{ASoDr{}-L3Ow`ln7Gt2i z?`BcQK7dmBwL0AyP}V3aXNrML z&lxPiI4fA{xfeC(?dKRiRRV%sNLhq+5cy=Gw&!DTH;qxyl?*jQ=sQB`L&{lPrm>1E=A6~0#?NxT z3M?e8!7@cGB3Vr8==WW?CTY#IoK=?LKs@;lU9(KAx~T)7*()>$5xx`SXMs!}*r(3j zddVX*y)LAB}b=uGXnN=auHkQaX{Y0b^k&P2%DJrxx zV_W3vT%SR_+SsQS%ClupWr#f4%^*F6Gm&tqj)cQxEN~ohvvG-Hw&TZ^HC5*K4dE%~ ze={bMvBf;4B5Ox7prgf`1DtmkG~N&4agk3m<-BN>ydCtCo~*hgf=?B;m%!BK7}+42 zGRm<08-Pd1kLu4b6eW+VR!6|SZmY)vEbG6F6HThjC z6~UjYgLn6w2>d`Z=9{ldhV!pTPMmcNOW4dl0?*6KR1uNj>`l@lAOja9c`M=}uj;(7 z^1PAAU3q35`CcSj;5T*!Jc$Ib5PQHqv`@Z=WQ(&5_i`mK>&sKvVK9Vsa{OJ+o8u3% zI9l!G-#`Ou{(z)EWRkYtt5jbgH=}MEDqSP1YW~;la;gXsCd5pq29zPx=RtGq}lF(U5*lg!&V zKSWvt%sR;-8!kZFQxA0&kE!K{nA#8#*`U69QxPhD?rNd*uFJTskdE3&n~m{_17CP+LYpq#YI+dD4^5t%D% zEBn}n$ezLqTf3<41_>ZX_)yB6_>FPgYeo-Rq?|)vH4+rrbS}HSDo^)rj8wTHjfH(i zZnTv&br0PdVE6Au3nMa9y9$?w9^|B%&D=wGyXCirXAsx$O|blhnz4>1GB01$A>?Lj z+od7xLqawglp^gb@YLP;Ct@-Q$kK4DBb$p%?KSHg=u(_o2NSudvro#mzQ;p^7LMA8 z>sDu*2i3VLZ0AUzcqh#)02-nk5}5?1P6nLFttZG0eP?xis$ECx6cZ6?@9bCP$QWPq zVF#9}cTG(5)OSIkokB+5LS@98jnE++M0^ZDX5`LZfaV!HYD{fjakLB)Aqd21Wb1vZ zw4@;8>FS^oXn1xM-s1bzb8Gk0utF!<@V?yTN+&%1Q+zZ~frnNm8bp+oOwaK>NZB_a z+n9A!4~3-+8|NsM!20NkIvJvFF^?ZbVhW7asYj5G@=@oMmWbbt1GzgkL71lk^hM-+ zc~NYtoB#nS^&Mo+hjomdl*l*R0faC?KrWzF+Rww$$C#HRK?)^`ymcU#p4y&7b=vqb z-!y^2Q=MSssc%T!W`rVB#yZWiE#Ir!bMf7Agf*IVcJbc%V>hyaFHOaFPYOEBXMrCi z!=-g-6PKx2w6>?33U>b{(CUrc$E<(e6>B|iL{GVmL>TlP!m@i<;Gy@U@RCME9 zgmT05P;<2Oj&n&BdL!v`db2GoXma9TWW2W{WOimN4iCRWfPUNPneL=Yfr1$1UOm#n zrFpB2{N$?V)gw_kFAI)lM#eDbJ2fM988~ypI*BTo{Ap(_GdXZ#7$8S%`w*6aW)Q%<(_Q@T z5KzuDF1-pqFNtv4ger1Tf}qNdbo&qjB;X`5!qhh#CEQ#oUG1GQx5)@BFP$5JS#~ti zachwiP#_Hwq_CAQ%JH+x2w0uJH$AHYaziSquxGCSXAIa%vq|@!X#l8q+hN;7n})?x zLRwoU=BUPZ-{gIen;DKEsaPG-UzYy(#c-FAx(_~sqT*BqtJStvCP$0svP#u=>`3{wXiSW!cC-zCg7%@KsI5(PrJ2G3sgq011z-g9XP@;wWb=8_L}s8 zE{fnQLc9}F2bk&&fD-{0u@X=`Ih%<#0fiAj22y2iw4wYNn2D1Bi6|?$t4?`Fvw-Kz z0Ji@l(9Pc-JCG$^LO%>5-Q3(@Df0w|+p~gwIvK)Kn??e5lAWSrwgOlklww36rHNqV@yUE2h9+BjT^uOaT)?`Q=KI zg1TQntJ)S!JF`ZrFkt2ObNmFMM!t&A3^_xkAzE`F#D?sdbyP?IDH|5-v?Y=Fy;>xB z<=p`4_v#$7h3p{(n4#FFwRUZoAk9cpM9D}bam**6{v^&c3Ijm&3J^xS&UKQ7Y`i7m z*xe5LfV|I4MG!_yZd)Z4OL*?>O7|xDDX8l|8b)6gWET+lP)C(O?wd{^ZJU$UcR~$B z0fa3sZ`VI83O!|z`PaXjE6xxAmbfO+&EMqyEutt=k3n{XM}+UTk&ep$g(^kL1_4=q zl1SIZfEl9H^GG3-O$(^bRc84)f86?rHC z>c!-!|jCLXuq^(k( zdR77+IqrOT8pJILx%_RXJA6PewjV+82#bjzTK+CR{=PFq76%;8I+5~k?j8b2#GZIU zV)BL)LCWip>_EQ>TL9aW10sCF6-09lyPD#C-#n=N8jC#=1a8 z69KG~YnnaYL#`ZyKZ4vtA@f2$4Qp~HsNR>mN1uoUDdil=xE&{-GWEgJ3Oh~`Qs58S zEN8UMJ8y@44zqs=ay!?ZBxPa~;hV36!3PM8GQ!*w!!c)}Pi5#nxY7N3&2KP|@ z0>}b`)hU`{n&{K;lj?c`*>5sk4(#Ak)(zo%W;7 zndd`#YPr7{HQZ3t@i{`Z>Iq~DNXI=40#9gri;?=uaPHVzgiZs@Rq~+#7+ zj+X!E3*l!x38au2D~iNa2!bqANm1ny6jazZ0hfsaaxMmSu=K3*At$|Bfb+jtPgf}9 z!@<6YDn%gW2O}E-5996Nqb@-fD>VwmQswMMkODj)OC9!e=ZQoIa4%v?R2U#R-3(I4 z%;nSvG{W~CIiJ%yR-w655Bya#%=tS4tYb!rD0`WF=Q)v@GY9Bk*8;Gb&s@mhQ>1rGEz2G7CbO^{y zBdK56AaMK(hbUV^_K>*+hZH}Si%Ph*VQ2YEq`fVWrGU%iSrYc|TK-jf6e8g&v^K-B zg_LOj`NHm;Aq{fAtq7BHvrJOXkiDM-Q|S73S?fY?vI!S=ju*vP(TnI_Bt+?DYx(_}4xlZOktWEUTqvt@M3 zUEB}}n>xFvLZq!AonDEen7XEKqX4Rs7Vp$nk=R%L1|ttm@=PA<}NHsB_3}0IN<fuB3(j@2gJWk3qd zjd!V<3(S$(CoLXK4{4oD1Symc(jAi#+v5M|HD0imOO1n!w*lb0mSd!T%=!hHZv*#F z{(|@+0$FH|3_uqYz+@ME5xJ1YHneSchYK+R*RJfrFlFZ=>N3n&=#|+on}JN*gM610 zf8QS>qC3}-)LwI&{_~F?tj_Wokh?`&M7C>=Y)zkpu#n{Irl-CFpgj|Kqla425+H|n zKA>;P^Wym1j7E_*#z1CKh!p?#;@Rd~qzDIU?-H1y=1Ex;VUz|zv*4?$lA8ANtX4-1;9f)O}F31Pip|BwIDEW&_LO{J7XiomN? zCeYa-kBn4_TPAnzQj*BftHa`^v@y8$5qqL$<=m){?2_=w6A@A^?Q<$aZs^8ERN|6DZ&Pss-o^()KX9^F*TeYLFNeUKpw?{F$ zS+y+sa~aa9C6HYpg9V+0mQ*^YE4>$_l)%W3rDarUD=Jc!nS7I~k}Q)`@|L6vv*B%O zFUx+%0R-$JERk6i@&xyn5;#2K5m+9H#*+eCWM@gytw+nupdl-s;w!k-VFvSFzt@>d z`Dy1D5dyQ}5_vQQ>x8Rg-EF}m5+KUbC#jld07(wu{1gF3_pC0i5{+V8|bixZo0iQU>5+*8oIcywLVc8UTaj083tAKQA!^$1Ism!0kkq;_l5<=y8xX2u!%8`WtI`(rbmG30JwDw z=p{QgfjtAWLmRod8UX@OD!>s7fTxH69)q2J39vYmME0BsWcAKkH!#6%$1Hf)88>)I z6g4p0h$jq-16&vrKb2b>Zi{Pf5OHT#)8~WPbxtv2G@SE({Yg0-syhGRPsi3003Be{ep8p|l9gAPb<#`Up$@3#~0eU_mpj_}PuNtW;0X!|N z4S@C@0pj`qcLCwI`Wny^cjm|^DlZ~)4}9@}MhbH6X_8fH!UTFLj!_d70Kxs`2r>q! z(f+2hptV5RbiTh}zgYqRdO_U#JQB4AiByzH61tbVSTxNM$Aib7;adQ5)|*}dNOXU;IRb&+zOQu#&W%Yz^_R} z6q3ph`b^KbD}js+=p9ZXL#KlDYzt&VebMBS*8`9sz9Y{32JG_(d!$}0r6B+Y;}M*N zR*;u62@HK7TeF6NF@QVuD8R@bf2EN%y)zyxqtX5N(JYS54e!90oUV5Aa0pq$ZR=UX z-5Y@IatL@g9#nvgtXt}vzUp*`52>L>f{^AmwaiF41D{I zr}$8}oZYI*bUrXm>jNLor^4Sk!fP5@(I_M->5iIQ2VgJ=ywO@kKESfIdW7`=Se9p@ zZMLidZmWd7bx>T*^XR?1xI-YgEbcDBLU4C?cXyY?-Ccsa1q<#F9D)URcMB3MygXm2 zd#m2xz4xCzQ+;N-duFS4&wQp&H)6U_5%yN|C_r|QzNir%`aOm^#J+UumQ8(E!U#CF z@oF+uD3nL`m%Ho@jOX-MrJ!dl-64=!1U2oWd>fSEj$i$^ItraU7HMclJOH<-Js%Xq z0E$yC%ouE+EXf!m&6p^omWp$m;WvmBO(1L`;pT{9sIM|+=BH3em>%5i+{s&bu5#)d zz>r7}6iqcSZI}uY9!48UnTdpw4+HBsiVj#RNO=ruTkjVR#b(42Ejs#Tl=9GrAK-yT z(>q!`vC#GdTG{M=+!pM2a>>NXoHL7&0Dts6pTyWM;OhOP0s!vUjRkyDV8T7?%*+o{ zB80eX;fl$e)> z!svEDcDAKDny_e4jUcBfmjkx;S_97Us%>$ z#N6W^-87w}4S#9mrIvq$>sWw}3Y#6$ft%UC%9) zGVf-7E{#YnU>X;?QA^@8)!LCWRSu#W-RH(bk1@{YokhGriz%E&q;p-_ zY$9`oa^Tr^I9}vs0Y6q<2p7rlQ^gl-{NbHa>4hJNUO1qI?F}h*Jo_V9kXGy+DpM?? zygaK?XgYd;j=8xzPWNY5P%mnB3YX2~_ajf%plzxEAb77obf*C0I6H9NdWL7styJ#D zJ~^KeQ#QnhR`tCmx#psXZV4AlGd8;MsV1efvHYj`6|veCSS5ghYdZz0U66Vjh11@$foL4rkvOV%U{&@(7p_pwpH~8* z@)XhsF9dj5%#5@&ZYm}Ih4;7pE&;%>XXz(wCxTa7Yy!Fv*$iTZ3lUV_3?*4@@BTjFj1JK*2P> z;$R-KD!Sp}pOL=DCJ=L`{B#ly2(pI7{Y)(;{N?4ibpy9vR`oh|@X^JAZgk%^qXx0g zMg;~L>jMM%tpD$Q`_9$MPaj5d-N@COBcjc71Cd%#G2=n*x+ry=hR4etrTqBcg>@Y! zzO|;f2H)oo-IFvKd^Q2r35G#(jAO+-fXMwI1`VZw=ar?0o`%7Pk=q}xDK_TC6sCTw6amdXurw1k2I2j9Q-XrnFED=+A>Iu;uNtw?$FV_g5F9d z21Cx<1(eGVcfxz>crUH}83Z4E2;Ty>*#?n(J27{wbydcQL4`3tdXqBy^5;+-MZEkctpunFaQ86ghEPqHygD6%R8OaCY=n+S^W>1rg|XN$lC^BZcNcy|bMs zbtt-0Qag2RLxZ?qu&Xe>(@VMp5hD_Y2Pxo>hI~;tE5Sfk^$~w#emRz2RINT8G{eCd zd_KbDE`)2Kt^n!1IbIkD@8e3f`{^!Ig%w?%L|CsP^UXqq|HKAWhX4As8pl~1+0R-6 z0K5!@sQFjki8wl}Ywm;<=XreWN5eTWK*8~Bh7(-mbS|i$3o(|Q6$}8nQ8*YS){-Rg z4^c$DR`l}Vd|`O$qf{(1n?zK|^ST4Oq@@5Dj z_745U={>)N@&w~;C9MMX=pocSge9>YFBMld1zow>Edat%C|nFU?nSiTXdxgI6L4z@ zV1G%lRr}0)v*RO_F^dE+Qu;1>){w%$b4ChCMrbLiv0|3}Tx8zYVMeY5G2+d988jGg4iL(R$TpHlJpft+- z-Sue&-!lH_Sj*BR;=`I|G@?Ena-GBHr;u$5EB94eMYIPsnRykIq;zQbWd#VxlMZu> zPzRt#208siL7?Nxj57hBIGmHN4U2Qz=R?iONvpF|c$WPES}_Mv_7|wt>ilEwP*#bF5#(Mp;U@QE5&< zroy?Y!vP>7hPcE6o9F>dLC}KM)ce_nm}Q2X0Qf%t%r&-aE)NNat@{4D{nV~vB6h`% z!^#pvW#s;96?A0h3_|T3bdu6j7C*V4h6B z+onSD4Tk*7omQYAjl3}`>S>^ENcjkov2$lDu9$+!oXn4Ets)q z?Q}?iz>&|Y2?*a!zl<~R6aydY{nrABh?V^92rI~Pd^e35YLR^NGD5V*9C|Ko!1eP+ zq@nf=doqwcOlv-PPY&9C_5S6jO_-vjCJ35RL}XK zx-$~+e~egwS>pd&5@UD$3v;&lBUU9~wF}wN9Z2CmK4!%ywuw5u1GJ1T!oQDlDsBOB z#f9R75*p?q%ij>V6W(Lw=^X?KV8v9* z2W=OrTmk4mXbKA31YlQTUu}KqE!+l$G!)l_I>HoVVSgGB>c@p+crjVF7e=9l8rM^! zpIGw9-|(QD%|?>^d912@;_(>b%Xq~mT1<&RCrjqYWl&ykSqSO#4AgNCCSlm|5ai9T zCf$ZIH`7#achw3-66Q&?gxQq>tdb!*UJ#-(I?|#6v8yRQrJz)SQJ^(NAsx^b5KgM7 z2T7gj3b^r&A!$=jVl#+(x-(T!8SFuN!S0JDea02#dtpGsd#YY8&sG=w_v5Seav-FX z9WFmtCoqHmho9g`!wfjEo)m)P3_M$qu{qKJx*qMxJ>LiSMJK2#{ zX9#3zqAyc}uh=k~%K>flPZSE-L#KXwHBKf0D+%}Y;0mLrBz8&$?e$LiUNU+E=Iw%C zJ@mz%y_Vc4{N$nMP1Ijp3Vf?Jf7(fV#{t7ScC}LAzk0c08sss(5i=q+~S|(wOvzM`#~(!jQocYS?Yg;_(*Z~ z#ty<9MTWZT6lM|rRNU-ky2Dw!@<1(KuHwN^5^~U-rev!KQI;RQ>JZO%;CJUXescwCgMA-rlG$YA*Jvnq48)Ij;MO=slJ9uGqSlKbC*4?3 z0R>|67{I+n1#-<5Ab2fsZxU#Yh!9|p3$?bN0BQm`dW6B(5rb6Tcdn`pN;sw8XZRd? zY!0mZHx)J%x!h(#7GlK=8DBE+;ijL9hxBGB1aI(qXD|K2KPdri)1?8-5jO@Z_9-Yw zi5MMK-2Uvuur^SJ?ow9({3(D78}!5!Y(^igph=nqz2X8KY{sb_jO8_wp?(7Z$tYF{ zWVY@#ZiO)xB{crYOA$5(N%0m>0eMB}8~I{4<=8b0To3T(#uR>3wtU4@iF zRdnWN!n9>e5va!f2$e5gI>Z)-e@L9UNV>IeIluG^4K$Ph{PVkg|A4;Ny{LMI64&0y zJgSW>LT|LKqgPM3%aUg+ErQeS-ZYXkO3^LSG)ol_ZwUj;(T4*MG2(n}f??qXU6E35 zICwQeIW>T=B&g88xm?%8aMX3N4^q78xB7Bd^b86bWaPuJm``DP>{s`WKP9|ZL~@y} z5d27~(d9MVh$Rvc0>^=-E|dsks)pc-jr-s>#u^fNwJ~EB679-{6;em?8Oi8tO=HS7 z`hsXN0-`4UZ$?lCt4;6SVuZvPpgFdc&hu29&eCfp7U`XwaE)WkPP2@;;l*si2qu=c2ypr#5R+88}h~Z4K!jl{LJ` zP6>?_-ZlCu!I|ia`-B5DC|)S}V&s7Lpqy(m#YTnLh?;>RX?SE$a?b1#-iKJS6IXxD zy-c&ED*SV=C23Yno8nPX^ufDJfdTRzEy zm9D}u)Q52Jmfumgnd#RN@dp|C8u{QsmUU8ZH%vR(zhxA;$+2 zHO&o_Y{3X}J!1-@H-X=)jVzOw;1)CoKc`%ytY#wMkeQ6$Kk|@KVaHsi7LYxIXG8}` z<2a12Z?zh2BgQW@K14KU7+9`}yNC*w^@{q-3DQ!4yMQ(v9bm z(G$e`Kh&W+XVDGcQ^_3+1J)M(foslCt!TJV`I+4lH3Tz&6of6*P(+9(@2#jX`dq+z zU2qPT;iNGV9e7c$#H9E(>N~`9vY0+&>YP=q26#}5$f9REPul1gSQaNm0Rd4<0u8H} zAwM{maExIkF+Ig#AQQU_`qtz47oGryA#w;^Y3JNFG2vw=l&$CPJkM#Q6bW59+uBRC z0&RLlAm*Kbpz$fr$K0Qi`Ff-zfrPpWF{cIyrfF{FImb8|gC${8r~rh>qz=J#U4Zv~ zmS$5cRSqGnGCCii2+0u68G6g=nG@|jXFnrVl^iI%_B#rTh`it;#uiqfNsC+|^^d*k z0*jF(#)|sm;C(% zmBG%$eF9rtZlbzedOucLpye<|mg(o~pJlpabQF9DD6Dk(rUlu^8N-B18TQDiUFnh) z#$HS4&Sm}0ihHCezL5QhAypg9=VJXf+B(E+#I`Ez+VnJ&TRcgB1`H;Xa)vA-FI7NMYu3xMT* zMcXQ6>(%_qW&lq`3Ea3zod`stdf-$BcrXJm8kzjlWO-S$zM_Iydf^4@21nnECG@SI z#8?3zs@H0WnW0|N$t^Hi$ow$}{2Nbn)Bu-p9xmP~(D@I;3%`H+IonAmdFJ{pbe{`< z0oboUT82rL0UlyqydbUw19RDoj7G}tvhz~q&uT171Y4Pm=FQaD#1G^I2Xo5XUU1mF z;-7n^T&@2YVFu~|0en;BUg6CJJy3$^)sNnR$-@ifkvtinXP_LSOBUPS=CkDZxiOgy zHQ@~tXS&@>&qAavXxS9~01&V81xW$HFD()B`ZBHygq##k3$~FLOF0aH;*xE)6(wN_ zc#FN(h%puQXUQLCaT(Z>32bAryQ2v301=mjL#;M|z7ieqr!OF31(g zx3}Ej9U^@#H{*YaHqaWVD-pJt5AVN12$^@{1FWIe)nzH@wz}b@!aLHfI&Kb- z+uwie*H%~5M~#uZI%GgbZjJ7oBr8~>YEib7g}&qCQyf+*l8&Id-J&itgxly_ad5uf zX0Sih6G6pnO*U0xH;aF8EIk^6*}~I{&y7t4u6PZb6Qlx;oDMGe9U!sN)7M`vl>EM+yR3THlHOMkH+bpS*Y|`Oh!Q=jG~_6coodiWRJiJP$i0c_ z_94b@?94R3Lss7`QeC1-<5k!%b;JPQ6bxsZ?=Dg;sOo`)hu&cL`r(MQo7q=$$1lCQ z#1~BL8gPe=H6Ce!LOQy|W%N(JFpaBg3EIME^C(AtIdQU3DXb{dj}>2(O%pyIjl7>? z5e1UQ2Y2%22jXc|( za_`&&OF6_;)f!B)F;wUa;P%1mRmcYDE-9ZXUIZjbVIW#=M?{`k@|oZKwmgh+WZ-!? z2ABRmtsgh`ghX1#FvtlWJ8XY>)#WSIwfpm@Jbm8{t5T+YG1n^OiSPVx~P%Wwmxz1Lzyb00K@=J}(u}2lR_Gab|$hhf{p=r4ZF<>3;5vNYuw_H{ArtF4Jk-vHw?;|qJM*ri38p=nU6+^?&ijP_o zVSGiLJZi}(tDbXn7C!d4$Y)}R7qyubdtzWk$^ou0XInLSMhYYCw= zx^pTUJI?H6e+O4B`=seUfb*yJ7P z`k_+=h4^y;^{7~ER7oW3F}Bx`BKJXI8SHd|%!H7F@>n6S<`nnyOM}5!@pPakVB z;xjdwl=SRKxhnDPkjaCz8xmpxF{6V(<)P%OiFGbKn&*0>(&jBVF`k^Ya$A}xN=XwJ zF}f5pIsaUlu)vo^1(zCQIvGg?g6MF%#dIRC#tGi#bk}+_%aoe~C9=bI07mx>0BZ+L?~kfcy9v|waR1zUYy1v>6Rf2 zI0D7|2*P-!k3q2a^$25eYWTG6`;{NyyvX{oxo2@6ASxFSm=13b(%^c1vUBaI$2QCRV8vB}M-vu?U~7(^H(cLztAxR}yu6lk+o zwU!s?7xCA!l^{TCR3}!fkOB-4x)}-8#_|xDiZx1d=Gp~&Tt+Nmlsx1*L(6QbWI2;M*WDbf@0oFN4 zFH0-qV!98bh~y|G%-JmbleDC}al;;CM9Sr4g!Jlzs$z^*aoMyJrN@eMUPAFyD4eLS zOM*%zS#6zuqQZBO?E-YMYK0NotxnNLR$&$TZ)np~nGW8&{pP>44xJ*=Gb^TN4g1r@#z!$w`OV8Z=+>eO`)^I1yPsOISpi@hV zR)F`8k+=2jw$dd_yblZ+C)Jo&gD&RL7IY(|OZkbOg5mTWkW+`1fbJIWHc>v41C*ui z28inso7???A1b{UHjB!@L?9ct{|&|9pbb!?TxTMrM0c_(7I=*lT1vMGt1v=Lm<^VJ zb!foXT6OfXX?!@tz8WmmI6O3WKmy2pvGe{Mw8#5(gxq{pVmC1Xf|H|Svg!=b>IJad zL)Ssq^j$yS$*j^EHVzo;6?Obb=%nU6-B2Dbe)-O-C6B_ilSD)c8(!*ohhV$g?*{4$ z>7)7xly9DjYOw9etdZZ)tj(S{e23H%o(vALVPjcXr)ZAgT5aoj{G3fYy>B``gKiGL za>WZ`1}~nq8Hv1qwQOv9RJpDFOcc|q~#ygyR;ZlHCm+6(CcPA zH;%S1I(>k>ML=K|ncpsV*cg%EEj510HeQv9g+>anZ6{U+E}i*8D&!ikK0m#^^AWe^)+8 zh*k$pe5RhKo8TD1lmjO23#QQ-uxnz6QJDk7%kPEm`zG3L*+=GRn89C?4@xOLJv3Hu zr;j?q7Or5Aj<#xtdPL|SCAzNX6-?b{h~G6 zQLzoC@M)~l#9gV& zFa9Q(_X0kf=725i;#2)iPEeaDOx4=UdG-&VkusKIbE7{O<{%4UIx`}{rjMGL(OeNU z(?a(^(5a~rWG#+Gax*yyQ9xlElT}{*iAb$aHer?PphDmk{)b*UR587gkbRNfAk!|t z9X(b)`h-mg6hEP}IJYFNcEbo)LUGOlkk;K5SPU2#VTlSel6$1E+#)Sl>c155rmEXMl zjSXWo0$zz1!rx46LM;q-Zc}O+i0#&k>RgTRtZxwyEyBb$c=eiYRct1yusm-TC?3A*WqI6Hy zvgF6vvj$+vvzA~#sn{L8i>#Fk5g0d?n>hJy(<1p znJWPpvqi{Mvn8l9$V7Pym8l0cEB!mumt$PXVVghq#B0{hA9Iqr5WvD|=j5hUglt89 z9v&|63ZD@G;D)OD9G-^Gj$>t!DLWV^wBYX@SPJ2aM5;4|rDVHL7Rf4aGESh>P8&`k z7*Zm37V1&kh;y+Uh2mi!p5!D?dTF=QX{HH+!qy4Q9ga~cXpucv`@zn(DJI%`1KZ!Spd*g3hE4;k6KV^&sY-hX}=Ov$PYTTis1>PvlpdYZ{XDi zb>R9jQyn6?=$QUa3nC&s@L|Kc{}Fm*&bL!=Jj#;pEDIju)tJ=eLb`>|6E}et=*ugv zO`(t<$cn?r50Q|_$d;5GEY=Z+p|GLn_{t#ln_x>)v*|w9x<77q`!I0= z9Y^3=Bz7jxe!J@jX7lV+5=_nZ3vlo~$fg2aDdRAbBw(8P$f+<1U*3;`@H3)l{aE*D zn|!w~t4k7o0Dnx1m?vxRNI5RIeB1t#Zx&8I({p$uDbDDeziRBd-F z*S;~=dhjn@>zH%({&a}A@EUOCq;RcKAX=m3L0IbQ9LP>N>&hB~2GR0KfG1AuL5xjp-m4D122 z?ZC_TZ-b`u8P_nvQS~{{euhvt3z30w;AIIx97MJHNGNq46YCF=PowPteeIv= zv-6G2mhCo#?=iR>(ndOqW6yX-4v!*7TTEs#Qx=h(Lq)O5t~re(F0M^W8St8o#3Q+M zLc~|8;WD65uhNx4Tjntp(V1H@&5Zf)`^#&2^#sA!tv8Cskc%Ae z-K`9rJTOP!l}`ucH(UKLMjti3QSFP_HrbZ}_QS@NC@NPso{o;OsmBytVhqMUPk;`3 zVX)7v)1mPZrif`q!?S8AX9nAt!phuOYoAMxHw3ZzFMm^+lzPBDwcrIT@ON7f;QQk; z$8vRcZ9p@jhzN1w=WE*&7Ei3ww%-<`1wXZ5XQA##nJ>vFT8-`UxSWlyZgY_-xJiP9 zG~Y4;f<}vpjc0#aWbDH^I$@CowVP^6cQC2aD)(eOWyXu&smMm7s}$tZWLaBTr04*)@+*wEbguP;xfTle>z7B)aMX0sz;otCc-|gbdl#YCBKlD~>e2T|k zX}{B?a2UQ8IoK8uG0{qvm_HiR!SRp2l|>U5NeaT30}uYLT{$}6rMJb9d~O|#(kYo0 zkR}UM*OMp`N4p;B7j7>jFUfHEYX3~@-nKz|u z&}Wa&d+X%!uzs$blpM=4+=HIlEI7l;EWr~~y0>suGM%vT`|1^?(ALGWUsX#maPBdQ zs|IbBp4vO+F4A-EH993*T8pV;uaKhNa*x;43sB}kG)lwijchvGGqNReXd`chc1evt^WHsAVP8aEufcdjv zqPj(}`MsJt_(w@B-qh)0nbQDUX{>Q!T5^5?F( zDGe^^uS}(9zmrM|bWW-^uaZ2Lnf7&BN9FW4WeH@|loh+(49Jkw-!lO4F0o=j9W)Qm z%NCJ+XV~?hn(jj}W6JN)lO9?d{hIP{ZBd#P%4WxElBPe$tJ+-*a&h!s(UjzxzNOnY zi?+PHYTQmy`j{6LStiXH;?04+*Y;F;sp?dK&6AdScnG5#u)o!F2?jqHQYve>V!iDq zekz;AbaG!OBQ!6R`4HT|)r>guwq(=qZBvZ>tJ&{ zmA@!1QW}*g0%Pb>N>P>{LO0C5L>!bMBPFn<%Xd@$c+fK#kAksciq@o$K(0kUf3RB&Xk{BUWPdAfN77_usFm z?ZGbH$J##jtPZ>m+)TH8>&WRBT~!5x=R>7$YAbCF!*Vc2o|k3QH?nGk{O&n}XZfwF zp(v`bnugd7;?1d+6y#RM{XPwojaRP$B%@TQYO1>Wn$~w#L~d_>JUCVj-xJ2yO~P~Buq&~DBSSF=C20u;6+pn`=PzIFkrAMI;ATExqng3v(@2Brl^C$l6pv`p<63FJ z+f!klThaxn;SmaK2qAx}2q_#v;>S5elDk~BI%|bA=y5xH0aKdyfV~2M1-BQxd%Vla z^IF-(*Nua;aoz=`E5!qs3%l>oJ)OPasGiY$@7~b&;t8pVcrK)rQ9-yV8Ec7zerA#> zohvkm`Hli^LG1Ad5}atnZgHL*9x#+)=Lbp*<|F8oHJYNm_oyEZ@-@Q~ESi55{E-nD z!CWrn25K=M^~I(zj?#LaGV|wRhxO~gW~lRH9CC(lZ6jjY@sc@MZBT0RJBB2EO6)7V z+@)nb2xX-?b2rRIavCQ;ngmfR{M;Jo7ySfHxtY1Mj6j27G*6&#U*`nw>C8wsYDxvS z1nqqEtQ4YFt{ES+EgZ=5W{9eUwazI=B4z22ePB759kFpPWZ>s&rK#k zj&w?zL&#qvC9H_0|E7Sj98B{ESX0nRKaJ(#WBh1W;`}yE$y%((TYg)GjEhwlD*l^h znqO!XifA0;?-hD{^tyB~DUB@tKI(}CnVRL^*Hi0#WnfEOC;|P9psoE}uTP@|{;mT|!Go;8*O1Y0NmXEsejT2d zBny6Ha-Ap%xmQzs!ce=j|56ZMaH@#YgH439@B<^j2Dd4Sns}pVx^s7t!2dZUwe`?^ zB;0r6H+1e{3@ca1PV}VDgqAH+^k&qpp38TV6E&w1jhW~sfybnQxw~T_?=JdP_tJPb zPENnWxm~im^xvU>&8^)h4es2jWJMlf5Bxp9u&1xPyP@ys#Chyrx#zU~oa2~x%OUg7 zQE2MITo@!e*5r|~8LuZc_Yzswn|aubo~+tgl_QPyQ)XS6`kNPJMD_P^yfHZbn8n% zxcDB!cKXK-_vrceG#q57!&~B7jZMFcePZu8KCNAteHzbu%KTGFf^+ilZ2n`_Sj-#e zZOq=A%!=&w#ns-a$KjBEB=4JivqfGYYg(D(EFAu;v84pA<<%P_KE0v#y}ByHr44NFK^#NX;|$GJIi zJ$;_mYbFgo;KQjQ42xsQnS46S)jAhyuF=z&oSGBs_*O&cY=fVwL)NZczJ}uL!oFY< zqLuiJbW0X{J#R}PgCk9=?JfJdk*MV{jEG3SkNdi9ysVEQS!NS%>7?N|r#893J>RyC zd@}Eg=o!VoS}|Yr88vuM+d2o%`=tqLsh8r(RmkySKpBaGdetP6`Jp`g;zV=HQ@jO- zJ1#NxyJcLG&vU^qhFZNZ_!%?z?aTJ3Q%Q!XW>3wULrXk+1bfi~Cu8;o%a@d$j7n|F z+iFX4i&fp^cs)ATY3$Z{7fG>t`}NYQMqPjNc(GXIy>`5d32CV{u&8p%=n-S4=y=@b zwTVrv=9(WM)U+<(>1$)GuOUjl(4hKA)Kh26Y{e+~^v(lEI%&_QxC^f)9sEXKy45n& zXXY7B?DLOltsF=Beb>3}? ziocsT^K=F4ftf`dY#p3c9F0uO!2ft9;=&4M|3{(nyCyKRn5V0RimQ?9zi&#ou)R;> zKTb-#_vH9zLjUe5{_fzvG^l#9g8wakpCTLh-`>9K`rjS{$$Eu7}JI=7jG(wS=^LPs3k^^0da<5--CT60 zv(UuG#u#UH;)^lq=12qeu@r>G!q4+b<%?++^QSVLNJOy5MX|)P8AK*~iRT!oqs7N2 z5&ee3euEXpM2`Q)rR?ij+45|y_uACS&ivPm;@hxSLR%V_fX3|K7L32))^7{QriotK zDW_&C7ZZ7Ab1B(y6I(*z`AR}%{)Rj>lOEBPTGeUH6M1*%_RF2$xX^I?t5y-366GPy zO4|`+NOK_s+nUwqo3n_a5wGBMw0^V=15XCvT9)5;%~{ai&%3TiqE6y{G4gi%{g)*>K7gj_vY(tp)Tv0#dc#RhO1;au zNUO<#$6M{8B@N`kU1K}-TJ{(1#i<|NAqa3R=SktcA#fPe;@ZVfKH(h1e_(@<^r{9X1-?A_ z!L;@Lh9xQPqW|Eb)~G9aSc@QqFmgGWjFVE8#UFw{Q_x!D@ryV&ETVg{I_qb52g4Wj z4)lPbtMR_7U$qxQ@nza1k<6Gz*aIu3{5C{a7j`v^C2K^3n%3bl5|d0nIIn$-<8ssF zibN#>7d_vBy~F%Bs}9uS!TjIi{Oy}$`bg1yyUZC^Q) zLMJ){Oeplre>kAEWyCg`_$?&(sjnDimrR1+qrcU+Xuxwk@?*0925uUsTs-4iCc;D{^OdIy9j!)MZ%tkS@S-+7hgNTpmnE_PS)v1L+p`?bi zQg+f=w|C~$E_h?gx3YBk=$tUX$KwxQhNpi%S5|yVZ*&C--tfo#Uh-5sEm*jc9)uD5 zOtiTFyU;#s-(JVzA_X{>ep$6{(x#k8j-r`1GQ3i*Il7Nd+Gg(!Y0=b5PNlFck?7;Z z>oS`i!eISn-6S8XH@O>z&YVy3N5uOIbfYLior7FVCRD4~+ourmO*z--kZN+QLs$+eYqD#Ud- z>@Cjv4CrjHwtGE+}%N+k%2c8&~~Qh3*-@1rJg z<|`mVa?^tAgvJv|!D4#ksjjp~4|Y;*o4b|Jxg+@d!o_g;t;p%%^%lwN-n!uU#v1Y*xnt9Y^7$>HteQnOf1RJ(?A2N@~UWA2h#82U`Mkq%DLR8OJ_KnV~(y z=^w=oAxRZ#*=MJ96(P$-1*v8tjV0+$!o>-wls~2#?b6yU9?63T#oPgArZPku%u2 zB`wuJY24|33@g1f32IqhB125*+z33eQ^F~lr&j9ukZ|#M03llin$>Mqozw2HoqyJD ziZ?aa1-BOUFU8@HpXGRilkGU|B+)oyvs9~|I&*m9p!<`5ea{?m7js~u;lY7%-msBA zNr`;8(LF|^8Q`-%NJc6h1W(Qgh~%sK0g*nLW=dwwkg$E#kiN2~{dhQ0s-C0oyo{Tl zF3;v8pg~yAM1HtiXU^iqPjS3Yj3`B@q%iVpfQYp~!(mzr&(pg>>8;ovDxUmyYkQvP zz^!MW!c+br_b4{sIIMy!9T}S|NKSd<^Rw?g_131m0@C2F40pYbZl6TwSY<`H0l+95HVA5 z;jGMOuXcX_^~-7;scJdCdvkcXe!i9HB+c@;4u|EKB#wBos#vLZp#3kV&CyCC9l-?; zPmI~)wYTZzfufR+4TXIHGgwqHig$u<;)oDo&wYamA}+gD4zi-PIziacxsc*g@$$=} zZFupvQle>jQbg=h)tVz7TLQjFT&~?AamlnZfTiFaQ!Fc{%a!ZRwRdN)cLY_5BMxifc6V$AT#QIiKl_JEgSuxg@N}`PzAYJ9(gc2ScA}cFawQ~E#}^zGQ5k*TR=rSLzKKVe!$ZSV z$R~2?|DyQAE_t|Q7naMg=r{ZAVj6+pcssd2LCra7U~u@cTjR9|50j$298tQ7iYniH zb$QK#b*DB|&VX$n@$-746%K-~C!!CDMQ3tJZy<_AJ*v2{&R0yu3$mMb_l3T1-y65l zhdFfkPH`(tEVMW0+=rAQW324VN6?5FnF;3ZwSiJk;w0P@;0~tj_CjxGnkv?faIPUT z%j`m>bkAz5H+xt;Lf;4)rL$R>N?zHXzPK$y2GX99nOtXcmK^esTt znuKP}U#*Ap>M1UBq@{4SjUI8ilOM=s3|}pU+D;lq1iU^Oi6+pxA0`W!RTW;!hpyn7 zo%au`VvQ&-2v$!L)o>OPn%3h^e*fGuR>#vDNZP={Q~6@j#wB8$iNVy)m<<-7Ba?f8 za2n&#F&g?!L7OZbO$H~%t$OGBH(y^INmG%-?~c4G!ndWoG2i2w1mnC;DJ}P5zOdbA z6g&z0@we-8WShgYNzjCqbfo0{AXW<9MHh*0xF&te>1&vHehy(AXYb^faQYdM(0~-H zF>v#9*GF(6l*QI)cnORfIi#_xXmAPDx9SLXQ8``9npTo`)s*S+W|^(#UoX_3yb}sn{KLObr6)^ly##VxiUcN&b1(>5mEOjdq3e|XZlQyH z{8NUps|A1TWYN@;WZ3R|$gZmNeQai_}%F~td4E8!`XH*v)SfFBmrQcT0?XM!zoDKMyTlMDoA$F*wR^| zHSH$k!#pxx3;1pIk&-5uu%ci)Enh2I#Rm1zwL7Byw!}KE`#Dd=AJ^bSkt-@=SK5uS z6lTuCOT2v`CYjjGEA4sF?i)hxVQWA#Li}(3B9}o~?PJAeSpG&%>nGP*QDlDex>yme zCEfw1A@0=)DC|xcx6SQ)-(n%e3!Gc)(o>4jy+)=Qt~;sY6oTS z@)n@@IhCE3F^iQ46B7%3Z)nR39`j=(fqL;7ZpNZpPoWpJF&!rE{@36Or(2JX-390M6bqK4#q0D<}cy$W!#FvMs6pC{w8^>l~2Y;Kbetj&HoC z(V@;1cmz*OhyLIODIpKeu=%-o5(ICh2^reHqQJwn zT-#-WWx``!6L7qW-S|zi4yB8nt<*{?65iAOr&W_nr(L*c$~4pG_K%g`g~tB*c=+d9 zZNKLYS2n&6rR`;2*uzg9aU5HAL1ux`CL9DN8;Pxo+Mk|a1*?0*E(9B z$JK^NfllC8*OACH1=&a}ZRGxv`JkR)ytTl!$1ZnGa%QZ{L!u+UGPadT$JUzcAF1t( zLD@Il(iv|o!#&*xSn#Lx{ZAx==l{2Z|9_DTcGiEff_LEXUy|`3&cOWtCK>-4```Wl z|41^JrR?5GiZJ-!SCRi*rT(vk1M!`9u!GtEff4^R?f5?dj{j1Pcfj!<)`9rmaPUrXTw0F5a4>W{sLP=Ikmmc8paFG4y zJ6vSoCV#{qaAP(EZuWn_0g$nC{`+rmOP>FHz{X3)`JYeNxXC#G=Mx?>&i_1+6M^lo zUj3GHG!>1kOpX82X+GGpld*C9tI-Er4)B}58vR|X`SXo`L;sgn^Y8z{qUvJg{71$5 z13npxhNTHugJI+10Fbe~H?=gk083in4*$Oz(_dqbz#?Yp?4)GsC~j}-U~l(Z`{MnN zhQr1RUGw9d?LoSF1$o@P~_9FRzO!PcUI8G|9l)efgp^1%bBK-;AM{e;tyv$)) zdYWQ)+5uR6?*tP9Z+H$v8gHn&PrAKT8zT<0B_K|$Q*Po;ZWJqmsw$oQ|2AWVarT4ssPZLSjkUmJIU;zI+ zwH7p@p#l-+c;uPu6^hFL1>drcKgWX&y@@5d0qzBe?F{QmhOICXZ#oMX!GmdA%tLN? z=gOvY!o)5@@6bjNHJ2qhuBDmOS>1@Ac{QJI`ZEvq z$si%LgU1?&9eXwzRM`e|9H;_VzK@Jr^GgDd* zg`rlHuplSy^|QtM8p?qQIakv<{!Brwp$NR+qr}G-NXw!|EG))% zWjgJL%1{`O-s>UDwpG_M9P!sRKzWt(>RaJB+v~gKs{PljAmQ{!+#xD866ZoJPoK_- z;oTwzU#o4YV1K| zJGeoC(zNct20JpZ+7r`gV>ub3P;t^5QOS6spogk1Ft(Uub0{i~i{iTNoUSz$=(^m} z^}lI?&Y=m$?t0yw8u>(P+8;ptP(XR+wtW*5b<|ybD_}5Q{-a%W;JZv`>H3l*PLi@g zZw3W-Fwg+z82LuHg=liaorD&VSFL+kET(B)6JC0RSF@+H@z`qemVn#EbVauOOa3S1nFazN;$Z8pk%~7~wJLdTndSs34d=x6l1hoQ6A^^%G z7wSY`*OjoJ_^aDOLhNilh26x~KC-0dL$&j+;@`dJXT+^q1b!ZT(bR zz#{voe22yGSa*xhjhdHF3j64Asm!dA3A6I!=Nj#QC7AqSrPrn06dDWjF-NV^R)Q_{ zJh}+0+)QQ8LzT0sGp>~L?f`-QS^sv7x9+%x z+Sr%R%yJM06OZhT$+abtp8C~OxclBDxCqTk-v%g{ahy7%IIy$IHYH$Vobzj7pFC@i zK#e!1#=dhuY8}yTCYA4qZUVIg(~!mIZ;8CD0PJy2ifFZ8+GN%f>Hod}{$3AJL%Nf> z5AfT#=c=nY4BR%hD%)3*Q(IYU5exY^IzxE)F7#oAkn6(L*s2l+uq)n~i>IM?Cix5y zSxy{4GVg#|{6>RynKvEbfhe_g$ysH)60|YSg%`lv8>63?Hb+B)=9)ZV$$?);WmZ@Z zLu;&f2}9~!=-S>o?E@50w-5W?ilPqo?CHPzThH#a4I#Xta=VvUA*6cireHlc(+@g6 z*?Rw4lU_HXe&VmK40*_YC__|jyD-xjbOXAZOS$b95zx47zMy!kkN;E~t1|fjQ$D(& zIT)jIi|bS$#xdTUHJNOtOTQ_@rXkZZpW$Q+SnFmm=P5p0kavcJvc{yNq;dl}#i&9>v znP6m>fPaqOeq)TliI(FRnnzh5SaxsTjF!?UC4Se_llWfZ&b#Gj6z)=W*KBTJ-hp1) zO!Nmm4>mhAPVO;c^*){K`)a6MjVpQVH8mB3o{TvgtAU9WBD!5obn`7Tx+Ew)%bsM6 z$|UqTk4oYaK2QOJG>HtXD7f^@+@SGBu?b3>CrB+H#{$}=P?Iks+4$iTk^&-k9|5Hs9iZ#=xeQlfw@o;Ut|mLgTkihE&0Jq4uUKNnX212_Q&>5^T=7g1Ubi_-|*@X?v z^KxK(O!^yhcl%JW`Vn?CuckBD0)9pm79BI0={U_{S2M;2Yk6mGMpBW|cu)>seF&k( zkK4YWilsR~Cciqs-4lBuPlEr^OXkju5-EmojUg9sx1oAJB9s5LU+RJ8x?=?M#8=xG z;*s5=g?=rip}*fdH4zk%r(xyZhN;STF3D9_rl~Ysi!hg5R}{5U#M!v+PQEAZmgjCU z@Aq1Yj4hfv+JY94hmv(TauLeAoH)38e9{+F(u@uLmFSnTq!L`f;Khq#Kpw>N)X#`K z*o}QB(!Y_3|C;E!M}hVy_W*0b=H>XSWFqVFU+j&kwVg1dh+0XL$3&eYMpiWTX6!-( zVOS0Hk7nl*37sEuVik~5q>Kg z&BG8NhIU;qI(2qo)u!vX%wk zSh#AQS~Y}gH^f%n)8l=suyWu#Y6zkRpr zEZtm^!BMYn&vG$6AhS?p3yt7ih(h$x9WHszwStXO&_xzi!rxnRXv|2=2FwMD3%(LT zb6uOu!Ug0!vB41x7bt&^B`1dN=uW9QCX(L@yPm2ZeF=Yy2fac%lko*yoc5Vr)=M zKopU6fSj4tWZV_n7D|8X{9Gq$oyEFlC=UKhP>HkK{sl4qYCIdUdkd7ko8gG9=v1wG zh3#+(hAS?pIt~-&fNbA!70h5t=+0lT_ZA&!phdZePA2lD=hre<6cbPaa^zt}twU;! zcx9zkcrr|lH92CCC+l1o+oV7i&?TXcKR`gYYn4Z`zmGixcAE4x{WQM>W>^S@pyV~2 zMjNP+LE3u$r@!sVeJ8tMuc;{hS`zEmFx1Qobs?5LHttk%0MfVJbjG))>{LjYqlPx@ zdXQKYc|5<^pC8@`1${YZ^L{V}OdV1kaV#XribHs1I5oqRM6_u3Hlz%SqV8YJU%Ne- z;L&Rh)Vhw9?atn|&-$nGu@*oXFJ3u%fscHb;qNTnUP8c0sjG-;D6*k9(?E|7CYs#S zWyZa7=c|N6NW9RalZ6#6Sp>CXO1FZ}fwzK#l|nYY8RJk|!f9N6nnGFBAhddKM(d%P z3y;QF;3QoP(%vyzrSNHH(E%x!UH;z!@F{5MM$8}R<6)!z`m_YHoOFWB$J&a_*Xt5I z1pIY%l$m8(dcz3_yD1lH^rTJeD`GS_=SD)5m!;!7=|pc$IXENZ=?9DPa^*B2g0c2b zn(t}1g;h7t_b~5?I>S`+()0P1-bU7G#*em|*)SL62ML;THtt$bmn;=Y7wMg?AJ}5@ zzF!XN!r)!Y5d5m8Hk{QcXFcTgqg{J^-%3iIqch@znzz#M9=5k?&V)j0a&2Q8ljJeu zwg`mu6(Di+K_KT*^<=gX6IaKfliK_puhzgt4AH5~R^RbSGD<+B;6Sl|g;$K4xF&Z} zYaC3p(GK2RwDA=$!C2H^Stv@K8O)0}qo(X*rwaa%LuMETID}jP@x)@~e0Cv9m$XCLb7aDO0^j21d0POrGCv(0ovo=hzWHt!d|nA4w{bhr zXq9oZNK6X%TvziFFK0B3NdMbrk(|CP8-2QhzZkjFd;ebO3m(cmR(bDI$PAdezDYT= zUG@?`@CI7BzZHW!byjKk^!E5{?DrAF!w0Kbz6lJ9PLy(?oKsiJ#XgLJ?mBL*yn?Z- z365s$nWYL{Y!A?mD^0UA123INh%wvHsgz<2DLS^#0jblha8F3O$*J3}_i%}di_ zi4@fYj$><3;#Xe%;b|+Bke;-ag_XpRRh!e%M~I3qrUPUt0@5pnDX72`R&EsYC)Qh} zoo{FpNSlX+o&3Mvw>M>28U>0Wu&eWrg4Y& zp$b@;ZHR=Cc1Qf2pB-CiLrKis+!~#MwzP-*=X%(6?;dKoNK@Hbg2E-ESWG0y0}=32 zCimN&f9|K&c?d@GsLCl^0@+vK=&&Gz{SEUG=;SbcIUo^y4?`a|#bfs$(iulgwK&vq zYdWbjm#PJwiz

7AZ@K#)=M?^b<(in@+mKBdC4hgYGd7xTvVPhq!RZEGF{wb))wc zS#CO4jsVJ0{FR8*5%;<%RM~X(u?h+toZ`{d&Pj7?k~Sxcv0ZnIh#dJ`-|`b43Q#M4 zNpIFA6JRc*4;a#ka=_kBEI9v2N0@7PqFO;D@*;9*r9~hUn6vfNV}m~yvo|jsw$+ez zHWaPIwb%6|zHUb3e6;scqw3p&>jVS}NO#v#$*M9A8(GqfvTLG$3U0lh1(J9ZrY8K_ z5r2{Y6H5BSYLKD7KBd2Od4&49H|1&t^3dmXzpyxv;oHhd$+8z{4LfJmhlv_B7DK5r zzf#9JD@se~p&fQ6S4txjk`P(zR}ZNkQ{~oOBCy>Hp?jq1{=EUFVW~AYE z8;o=ain-m|uFJyjeTdg38EwGb^f(dM=9+d|eR@5AEUu=GL2#~ zcBf}ay7YukjC`mMt3piI=uYrf->aby4Pm@B1yK!zV<|pcpCnRZ&}M)t!V0O0;E`(= ztE-6H_-Z>CGD(emSmv&Qk_KSE^wH^&zS8-Q_(B?>|LMhb zRVL^((kTD@)%P9?PFXR`FU6#mmxO>w2qtCFK8{tcnK^S{!-;$%V8#HaKbLr;Jjeib zkMgfnN%I=?C!viNL72w}uT^{I(^yD^=Xd@q_|u0U>&ftalI3C%y&^3HluKI=CV$ZK zE@e`7%s;{DkQ&+Y9P)E?QF3e@R123GIs)vIE>*z7oqJ^*5GHD3??C{pJ{ob`n_q}V z#3p#>JUby^A^3}7E8T~<+0i&TrlpQP3v`Ye1BD_HwbXkL=e!LDiXASOqV-~{t9W3a z9G&0L=4_3@O~h`^xL06>L*_LABYj%K*n~H z!Ka(Es|%{Z0<_);LE3prhy*Hmt==g?_7K|D1wqM07c&WJ7Z{)Pl(Q+*FSJ*gHXq*iDfqdGA~5Orl@vE;-Q6BVK&Fq2ZKIr+owS7^l$aDr)O-|DWN3EHHDz~zJ}Jk;aT!$MxpGjohd>`%&f_y z6U?0Hbxdja;8vjjGd&ulnndg~|HK(RS=_cxLOT3q5AcM5O9S#?|0%Q`s?>f>J)Py= zk{Tw|1nEm&%`{v#+}5bBTB zKuqB0`A(wSy_%*ty?h84{7jv?PA2Q65@}OrWc%*Z@4{ncIS27ZI-a##3d70Abg0Qjrbocle3Q!7s35m@)fxj(AkqZz8|_=SRo z9B}$(Jd|!~8#;!%Fk5SSvBCnV&dGu8lMp3VG%kAp0`k0dq`x*l?VDCgxuRPl0qUWq zxR{C}*MT?2{6b}NZvDv7N`tANhk}FOiWVZc3+1L>x-+HnIJxsgqH;V?4b=Z00k_c3 z1p>bMw|Yo7KqV3N$F}w0aV@3ZXLUx4z8TjFgxOg)Q)9gFxlH1h`6s04NstNj(2%1Q zq&cnQhAp#icY|UxdT~pxC}*yP<#XNeMyn`lr3jqsZm4K{`ax?mtIuj2Tj@HtQBscjTy9=h*L-f&g4 z_=zU(6F?vIRG4M10~hKTw~0Id@{e5Quwu5cfaSX<~9-rOf#P@0zW14hZqYnZV>vTZB@wCaHrk` z+c3&Y3+gOZbB$pwgoISrn@aP$ek}0~8AZmnL4~5ysclGO8edqBy78zOk@F1;vd8I_ zOG;dqtjk;5#&)Fs1HCVie;4lY^WxE&VeG#>zaE+ylUPnN)2U!bYx?;kry#yhn%ra` zSIUuii_+*Y1kvee=aA+8@ZeNwBdm*Fx=vpdSdtuoO>S44U@(nBBnCzPsw3LJ(On(c z=wK{1yReL4Q2`Hyec~&Cjxh@+h+{3en$Md)t8a#NS_K|ayRMp8manFO|A+)=Y~Ofm zJj8KKEVl(06SZ?Mo8=kEapw35AysJS(AjP*0?|JO?JJqKbp5y4jbaz?7A{fn4_e?Q z5it$%1P}{1N9}u`K!V~HUW6fXA-r^1*`e$$3Ju}sotjYAKs`KOoJY8w;=PP2R6Qr1 z>d!&g`Fy2nts({aQ7=UYjWZMs4ttPIp<)}CXAdmfxuoEY2KfWh>s6@20pZn5&&1q} z^Y^;KglyY|A1Q)r$H=l=UQ2Z>&lN_Bgsx3y8Vs%>UX6xczf?`=PJ_uDk z7GS`ycAQrJ04^`T{`0Mn@7XW6YJ<0;ZhpJsSQgrl8ezBQl1Fugk7E{g?=n)NR%NAt zVwKan_=7D|xh=xcJ_|RzI-VCV;*4h#y_I8?Ku=hqFPj}QG|5*g_{I_Vi_b%+A|Sxj z5}=)Q#J_gaF%N6agq8Ne*gDUhcPzqz8BM{Z4`7c+tR&*Y=CZ?BX{1G~9t_s5xNm_+ zv&W^TXG#Rpplz6#uHG+AyiY=V!n-rLy4k}wQ^a6hg(-H_pBuyW?sKyxv4Pz&lcu*V()zj>@$-g%QFsS)1Fw@z@yz)V*$DFQGc=6{qx+{N32Yzd2JDKbbg&; zr<@Mk`JX8-YD5;&#$3@Sv%;t$MZ~ZSmKBD+fG6$RCUEZK_*)5isC;^bd{HP~sP^nR z4T6@nyYGsp6w6=Pa0g$+=MKZYpZdPAGXDcPIox6*{@2lnlz!EaV1?;3n!?l;p_Irz z07sbd3*elJ->dFHc}_si$F1{dq=KMxzgt?ZeJLb-C(3?!-zX$_As!(OZ7_I;{a^?L zBsFJe8qmN8%V(}{om9PXAH9n;F&4LrH}fIr=S=D-umqAmhjuX94PCNwsi1bA4HVNZ zaQkHk&huvtvJv4=Ui{>}K`}3J_@&A$zjw&9oF@HIx;|px455Cs&hL+#3!}qnDf#Zh zEB5~orQ9TE%1_()$_s~JK0@6P&gx2&1Ru;-Z~zido>HZbB10^hB*#T4q!)K>r61n? z9Qvqe@p99I(=3SfSP~hmA3gLwgc3lNwSl)vL^C=Hl>Ww{Q{80Bw+*j6nJN) z%PhSZufOQ{897wPsWfU30|l#=C3mHT)1;Q3QjZ^Z4u6&AtcN!+Z|#xJ!RIf}R{xJ@ z2mTMtsfp94AM0tbe-ssH;ZK)lp3jDc0+nfp^@bb%h^a3dx_3p8T0 zPs3&&+~u`e*`pD=jJ6;22vh3KJ#f{9$L==ppK4C{~8~mGN*JLo67S-}~R92Y;A)E)hw@b%*2Yr3Cpa(HX;qEAjq7QNv7c2oJxI zcn>_*d>^{{t0smbYi~6RR5g5-PUxPCu$+VVGNOm{FeZB;@=d7~vv(}|L!;SD+~_If zZNs_=(Rmz3;hh?%-e3l@`Jfc;& zD+<#K(KHtNF@oI9Q6#a+7WF9+7 zI>mai+{ao8;TiR4F>O`7uHKD8xeDI7^u)0@yRh2@Ysahx^92${9uzgZU9w5PQWrha zy;BEzo0oMPQycfPCDaGqjy>?+UQ0iApsQH_2&+{P4Nz{Ip?p#&(% z?;cC*rVZ|->t^<$=8I0vnACGqE@sHYf~@5vhg9TY=1!E>f5I&bbtc5-fpjo z)+~tosI$b8b}i?TU&d4){)?p1w3;E&r-c*8;d7YrK$gYuuzFVIx*WB6Ij_dRLt|Fe zwl3j>+UL|dpyhZv`$YY^Gen6aAbz|C38i;p3PhLVLpDZs>!B-et~|BoiQca8TNPRV zgn6HCvq#Ib@_b`HlbPFcU|;sK`1CrS>|O+kux#wVGHjv7P7LiM&Ijk2ZO!5c;xrEd z2|$a!EMR)x2n>dVYA!^#PK+IV)A(@!W@3&0>;l;>h3R1M8%)QvwD;|q@8#sFim5R; zFvDBICDK?J<#3jbl#CQ;uwT{rg;QZX7{^K~{iyS~l*mUj>nefOE$1+)UEnD8GW3kSpeVn9o?|f!`(z@9pso<} z%YGR)*4=&D<-wUqH`zYQl=u5YOfY@6ddNvnpS#Djv-0bwZCgXxOd2ZUL<5M1_aw+^ zBYE}4(o?b+_Phz1KRVVRr}nD!49s1qObj?OCxJSXu9$c=x)+EhOdQ`0qt8R>Y<__i z8{wop?IfYuWoV)+9VW)Ni~FsSciS^MaI8LfF?4twoe00K3fk+xme*z*xa{Tn>f5V{ z_!B!U&i(`3j0nMrnfQIYP!c0%@_hs@upz8CH);V zX)y{h!s)~NPbD_Z(7wl+*wchM^5#r_G0U=?SfH3l{alzM`?W>4CwWenJ~mZdmp(F8 zg*nyX3k)t|OWI_x&4j4~K}_$jIL3isDV`Ek#KJzYs;@$CMddFn95Vk%NuOl>Gs!0> zD=tz?M0hkVN4K&KK27E>2-vHD!DIoaDq$ozezC(5j7)2z2#lZ7&d((xuV^gMkkZq^aWm24QNJ-+!L)JDU<$Orn>ejGCY|ij06fyru5MkA zD@+@_%+q^<*tOFmxXq-N>IyqNrZ)oiKPotLZLKD@!XP}$Km_I)!0)cSvO*ef9;}F4 zS{PG+-o^9gzSsSg+8-~c5Yn3?04_HXb7ICRD$HSEYEd6-P`{W=(M6S||0&a~KK6s6 z634N~Z?r{sWZNi#1BB-M#|oQ{+)QPU3s6SV740N=9GA8CSy>KqX>$H2Xbrry{t z0xZAD`(sN0AHN<*kb<+HTL98`-~=aU+_~xLxT!cr4SRg)(YGwCVvP$BAx$br4fR$e z{*SB;u(r9A{Cmm1+ltA~?f)t&t{SEzI<+jfYl;~X;*+X)_gbnqpC!qpsoR^7!e~2C z(8zf5EyAwibofrO`ogktuGW~>YtYdUGSpyeJ`)s}_eJ+UYm}o|h<|n0boe^SJhQei zWZA+%)VZ0JFOgKQhGO5ob4-8XGYnEd#`Wmd;0q>X;TG9Gp(fGY6+Dc<)A~pkRpskl zIN@tX*sr9pUqk)Lz0TjAI?|4)56)>NM0k2tMxxKHn`^_YgLNnOJehyiwq*2B|Du3f zgk}Kh3%Jb_UT}I-n~A>m%kGN*$z79Z`Ws+eJ|{d0RQsJaL;AA%vyL5(zDD`j?Fhp@ z)|B%sk(i0&)vJl?h4R9cZEqpaG#MGuZ|Sg>#i2h4?^Z z_#hE8ssr|ERyp4K3oS$)APW)A%J!bkTU=G$VTwmmjOi}gPxtoW`@S;E7Corc7Z|Xj z8$XYNb*%?)1i%MbQVzH@f6EOGS*d_S5S_BRXZ{6AAxA;F2;IN|*P4q$dH1Ir6r728 z?#tREUEN@|t57WRgLI=hH}09tP0YOu)8Ad>WschZjus=-=ihmJIM7I9181AXU;G4^ ztTgf@6k;}a#K)AyGwAi+IU?8L~9GJv$t8Me{@j@BHQ`sno}X)ir%TL?fuGz3F%%smlW{vE?rtcYU^cX<0a9! z30ll4A9ilX6w5)o2^!lA^;ML3jSu^!v$^nE+JQdezxk(@1+mEtL^<5B6p%MXNr!~o zriG3bkjJt?3>P@<39cuYU@0%x_?@w7j)nOobolU~b7qX=Chsp?)~#rit3#X1b4UA` zfgCQQ`$k!pXz)Okh*)GR@fbx^$&LGabpcf5B3oO+0k-#Y#Bh-uqnWpp6b`FEYz;u} z+vW|HJuNsp93gw%x3;~Zv!1ZnpM}(00d#VL!xp{TjL36F`#2K7p7U$X3bzsXfj{ME zbs6lDXU)ZjMwGk_z-`oeH!q6f`u$OsXQa~^=zy})X9Cp#eH{ngmO@$8 zeBc5|xZzsuQR&>|{sbO&aL;m!R~$Sm(M(qWa3Dg8@J#ja@bIJ<=>^>}hT7M{nZ^MH zxW$TAtS+HlYOAfGWGMeqZlnM+JNnQZHB2qXXygs#gCj^8O0yX>zx0%P%v{T~4d~5% z*#8z`(!jCW?Q12MKo~iYn}`lO@8uo==QY&% z&hgKy8V)uLnf8SR&{gtAL7Dpu;A)KziukVFk%{RyJWR)|$J@CX%L;D6^+9zBUwzVUIu@2=PoNe6K|Yj# zdjV;K-EG1wuTa@DC);<^dlzzd`E56sq=9+F;0212pU)C7#o}AjVUCH>d}G!?Q3~Jj z&Thn>Y6?cIYoFDK;WH=jdTzWR&laRS)#L6re_+zuyC)VAsdX*;T`0S>gMdBPOxI3f zEk9g#yybh8ER62RmN$vHfz*WhPS3xM={#|JkH_QjXSfu|_zmtOXcHdg*62)})7eawf9_-L z=KzndY04ud1MNSvco5R!hV~glO7Jq}eD|IRO<1ef$wimg>J3n%fMlPDD=P5yJ&NGuMJhlr{>mP-BUl+4k;ifm z1czs*;%N0b7P3vZ@Q0BMg0nX_g zqCC|tBua|Y5UN(l)zW#7^j~2GP3BD{mu8Ai>3RA4{P_Wa|C9E5m2qxY=Wgd)hdr$3 zpOC`gK6crBzjl|nLM+~-J~4k@AfZ)pK(n+`OB z7!5;?yz!%7+MU-iQ)XeV36gk!WX%R=z1x-`m(B#0`ayXdkDF?sAZyu-7|BOGQms+X zG945Tl8QG>O_S}PcJ>Qp{+WY5jK5uowrh2W|Fn|c!5+GIc;jSrWjRc{K)U%HZir-4 z1lQHoP*rCxS=AsV=kO?#q8R%UNMb+85gbfr@t$2!)Zw20Rs9c0YFOYk1^;WhOaw%L`Y_HMJrj;9a?<4c-AY;kfw7%jWs$VqIGaSlyQ|y$uWg zvh7B55LbGVR4N!JZcGw-3DE71H#^v|AV>W{6N8PBLK#f-?sH9?4_NXumnKKuJ( zDffkG0*k8Lq>(4{?A1eA9KNKtUIH_M_I!jXcEwjCacOQhV=qNlL4}i74X<;p7?hoD zi;2$eU^M99h&)!#<3eyH+kU3Ig=Q%nf_R^p*~Lpj(SNg zk5<%SGGe+F6LO2|fK9f;4KfO9j(GtmI~6RZrs$Dkp}CNq-;Axe?M+`^k2~DbKK}ID z^T>Va%V`+O0cpMx&E@2p3*Nd98lNq$uA~pOt)6{7JUm?Hl(%r45FIFmKJA*jPCe)X;l}-j;a?zSP;iob;of%h9Tn&|a3;X#H<^IS`BreF@Ht5bBkmbwGbnBi*3o(3o7(3YahC~8oRpxM@fb(tH4Jju z&>BOFP8{BUjDPYUgllDC5F`V^BXI+>EV)JmA4+EgZg z>E7K9c^{8T!wy~QACC{^=pK&^%-PtC47SQuplltXrNGpDbIp!#fe>}d8}g%7gOgd- zFQC?d{A0Z@W*$O6sc)*XYzee>vL6q)KwzoN)Z;wTVAP?H{dl5xkhN2OXpfu`E&x5> zGV}~yG-~)fs0OihKzhuTapD0W`AX;4Vp&N%-HtRi*-L>S>T%zQJl8bP=sK?&^s=&2 z`knUe))=cUUNFO!k^nkMS1T@gl_(wbc%b)NEg)k6cNzIqAWub34=yxCtSWYZ_cV!i zSPFS}vtXa!uoTQ=oU15z3R|NhTDiDpX3P!HW~6`D#-^|*7Tw!*8|Wo;Nfh~d>83-{ zxNDTS5UZIOt(I;_Gh#~4h-6e5-89}8hB4)SRbXnBXRh{_#o+PA8vtiWPTtC_b3+an zJTI%W0Z4m6giEu_AD$fRphnXLg7fyGn9z8D52N_^5*(AhjpVM^U3@rud)F}TYlB2q zqN3n~g%uCTQv9pxs%c;|FRRPnJS}ZGm=m3a&%S^@!7&R592qM;LchxuyW!M8Nl1@d zh>MMuL^Fo=DSS6|BLDe}ipqcA{0o98{6diSz7*zpPMqAC5T^U&AT5peGA_Ayc8nUZ zVxr$ot8(SwErQVV_)v&<5b9d{3X`*sB`cWknDeo!}&F$bcc{*uzT`G z2&q-SFY;gmdoVR!Gv^>AzwmqAJKXZCm9^K&n$99pkdQj7nrKd@bHc&f6cgioc(prG zH2a0qFBTU4*>I<#%jM9I=@?4?8qD)<=#OxohC!Z?)N!TIjS#Z_vGNiYZ}+y5vYx6@ zGuPski$$F=pUz?=i^42-=wUlx#)@OpqG2GsKe+jE+QGftwfwFa+HO;yCjnEuqYmjtohLS>H@y%00em56u2YwvBic$cp6V$V z;hAF~S&+wpCf;Cy9HvAJJWQHyLan0EFP5Rr$VtbVBzOj=8Zz8mc3V>#Avj}oID2Sc z6@NU+4D+omn(#DBwIsj447!i^LlFIBgUytP5yk>B_?rK%4{sU?O(HVyQ+M85K-kRG z8bIBdn~h|6xrekz{_K+LTu?;xV8}0%_ud3&qP`~>rFju%Ku~#=^oO|86WrmTNRFSt z)9kX4Cq4RF#Nm%55n1%G(;tTfb1F$U?O&z+1O-|Xy=^+p?#Q~ z{4Xm$BS2sWs1y}7C zXGr9CX9y-+e@~!bwyuj(Sugs5|D&^*yxaGikn4`VieI-dl9Vzfp>z;VwS?s%#(uAeyS=Vo~Jrbak0xi;6! zvw!%Y$grabdHiFV_-Qrxd4B$iwdIYt;B0Sbm#VECe6!VL5?b-+Egm9kM?6*Ww3OWu z36{64v#w5PtXg>Ta%Vn{FCYI}3&AjiF@eX=XjFBw7&;+VM7GL`uxskQP@{I?XL7Wa zXdTaQRLGoP!*byz+ztj)6Pf$QXhb|h^FQtH4Wv1qRz+(B-ct^3c2&V#NOg~+-!h;3 zgV^kzhi~5h8)O+Wb?~H(!2Tc@i}79^5~TTq+kPOvqPsyq{5@GK>Jac76$J&86C~JE zC&w9X9SxaTVcjR;guE{dh$GL&pm5&EMwx@ICMwoc{zK^`S>Tz2I-xX~2c3{9;;r6* z+Ijl^RDEjkAxp#=HfA#J0)WP(AAn(~7;`#S^EDVHdj9fz9sR!s-hvx!aYnR4S1GiL zzlgxz2~*SK`{0xrzD8#M{Z+zA<=NJTxpG>3|9!h<47J((X^f9IS^uWkjNd+ECNf(^ z=l`7?ZO?;0m7J*q<3o1iY{p=sh;vu;RcW|6*NyhD44KfKJ~6@YqHn$aUyb7&z(B|} z)67CL_`73RBzt&WXYl1D|FEX_-$idO8fqLVwbUQJ(UI|kwmax%8j=W=8m;-k!SL^H zWBl%RkSwY?DS=K9ZcE=!~{$c8j6*F zdAdyA1^C%k0t|vG@Sn;2)w7z0oIDZ&n99{+$o+L5tr%i5@YH1#ldqxY?d=a*L8Y}Z zF}xykvVQ_5u#+^ifS-LD`5sjX@{3%a3+>5;!ROD8I@T+h^6M!vi>-yl3k_2&#aRA2 ze74Jnm4%dcr8i>#hV1k=WM19Vu}LBknCE>_9S!OX^sCp}FEn7QQy+oroL`f{*{a&{N_q&x4-^T##u(@ONEoPPjrjf2tzr&`cYsFkJ@#E;Az88i3 z`icL?bbLUELV3ksO@*lP#Ntp1i_{|O3GRvRvD|Uf;N@UxAdUUW@qxCwMw1y!}Nr9I3DKtUUxW%`oUo&Xz z_Y7*B(}Q{-Vn@AX-d6j@`3?G8A+nef?MIw~G%+O<1@lcqJpP#)@*p))MnuET=sSNN zzdgSX-CNy#Qg8(I_mi@D)M1N9>F$|jl@NPb>9kP{BEUl_k_46b1gO2!JX84G2A?m!uP zlLJY@;qQls5+)W`0?DSLM2pED<{u~pzMPfuyeypM1-=?d6UGMG6}m<^XbYG%>FhK0 z&PmC@@3FEBj#|^;>Q#3olz#<&ZcuwUg?#Cz{@eF=8F1M*bZQc9-nEDE+sNUy& zVu7WXkgf#;q@=rc>0UxO&f?%a82=6U9scNg=MDQG3~limb0nuO>0rRb!{rNllU(Rjg>1$p8tf8US%bx9q% znj-~b!#SNXeS97lKH`CrQdk=^3SP!vLn^#4_~&@PS%JOQw$0w{kTtPko5KJeATgVU zwa4&A3?W-F12BbXg-C?3>LT^#sKr~ps;HVfMLwC6$cb;GoqeACbE4{#F-UJHU<52p zmdJA7KiB~+i?B6B?{{KQNXI4H=+bivnL@^r9Wf8?R^iSPi4)Hiq>x2;n~#;hg*rK>tKaAGAwP8hj@N zG0r$6wWg0bY`+eUMhnzO9fUwuX3vPwK{KxFyP}LQz$i=^XdHQp14(z;n5@=7Rchzc zG?O37t9+}9mSj~7XC$)(mtcklFMi^z51wtr?tTh(Mw2HnM(l?ZV)0ZOwFZT1%H7rul0X%dd*Dg(c4jjTp-3AJv zKPsqxoWLW|W^9AcKCNW&(>BS?NVakl_-58AfGIHgDMamU5IQ;a=?VT%y7(#KwLazd z#W((SAdQr+P!Kfquzt$jQKVIIbeft&qQ9(?AiQav|Eb&8s{;4EIdDu4&W6Wkximtj2~VE zz(=JyGRMf*hgC|&t`2FDQ7_A$)W4y4l+*#Us=My@PLW_` z~6 z$_@k%4t3;m{!`G*Ga$WYDxK>RX%jG;AI(TROY^A#7VKmLJ-|HRIKUF1rNKjC;9^mR z(Xf=I;X{-3}7psdGG&dlK}TU@B7vCw}?)Z{qm1%A?ZjdA`<4C=_b>lCF3ExTXQ zg05xbZ|K^=V))#(?CLt$c>#GSXh+kjHum%7;^D|ku2B?@>|%HHYiVPjaI{?SW7H#? z)Wt)2LYSD?ynFFBo0v}Vx>hm|$YLjoURH0O`HrHVD1oRh+D~ZLL7~jxi{wA^aVa_y`bT)yT22TaiIFm zyHWT~fq<5sE_ABieG0RUn3QLql1;h+dp=EIN!&T?Ia|s*yWGbtKjDwAKC_mE*7AU+ zPLxeZ7q_DZqa_}McLmJ8O5&qElVjw;M$3{$v%Dq>T4Kj~2||g&5nmm zA*GTKx^(tF#5tX3*NFGhy`QXKvY&WCwcntQD_#zGgB}&X%sVEf$5c}uOE^pJ!^0aI zquK{|Fq$;G>JJw1mz+#rB;`H2!4#|FSa}f2D-T!Ae&N1fQGxYTYzLM7PxR$=cJb7; z{qOx`xf|duYB5ZI74=Poo`nZ`QhPxoM0k{N*cnJp8Q~mTXpNB&^i{(s_h)#Tnj0VmDg|MfQ$%I1ZLHP17MpC#pBrtN`WWvinNa zRmSN~iDZ9K^1bby9^X5>IwB-H4U7+4WrPkJ>$BIB2|@D6%2AX7yXsFTm7Y_c+f5h6 z3VCR|wO$2qDREH`1%_KL1JQj*i4M37!*~5|j&dlfV4o4fx-dXS5#tTkEKT?DsxEwV%4e}3z|@OBVuYGw zWKjcxWqycbBIn2OE3*_yjtSX`+;^h)MreNKd`#wtX}FaWsQW%5WSg2;NmTIG8uR@W z^j>Uw#Pqp>HwvA}UcBW_g1J2L{9FBNn_@{>7LFD5963q~xFZH6Y-FHg)8QJqH|QTs+| z&~-g&x;rZ1=5f-kz^_V14Eu4+gjK>@BtWSV?6@U7CJ{D zm)3EP(GZPBi|IeVXM`n>4_iQ4eDSuiIY!2J9?NVvO(v;MIi?ex0Kk9)k>~nwV~X=hfPMmP({sk_hK7_Q)_2d zONxENtLA0oc`DY+IMCB>F3vM|F4nkAC7y_wp7_G}SP<*MI^s&iIZtuVrObwst+{F} z^@}F0O5$t96ybVv5_PZ4bZWH+)aBpVgtn8FPQGMvpbbtkIo@vRx?@R2JZ}kEf84TR z*7%(!KJ5NQ&z-dQnpcH^7qK_o6^kT5Gp6V61RJ}yg%!C zm3j3hrEQ1TJ5$1fms402L9qod9MGZU0Lf-8q7l1(0Wsf?J(l&X5GHBpYZseMO=A9Z z#vk|IjTiG9)(wCf!Jr6NMSfJ!rMTCesLuKm2fX(3avR^0`+)pF?0~FFApHJ|5MI=& z$*c;Li&=GHO)JQpAMQk*{#&I7VknnT!HJN?5gjS|t4yAw}A88P2v`X!n7G9_6Q#@kRmyDjNK z>lRBu>YJC^$-)L2V~vaNYQ=z|C}lx3c3Lrx5+?~`$z?2j1gnE0!SuboT0i`e3LMvP4RWA;j;)O8jL4udU3DB zL_gzx-K*mE4xs2P&C${7I8*@ng#J}HI~mkaP{K?774ZV1wwBSHociJ<1y5F;{C5?e za?wAQs+I%Uf-mPE)In>vS)OyqccsCA|MpG+?m#mSP?>oAq#IkSUz_bS@g;)1&(0yv$riVT?SxiDdZi3OX zfUxqk`%5U-?t+(?_2Wwm&v>8Wem?=7J05)nbXD{hj=#AC*S#MY4+nw&+q{dzm15gU?;~3R1vq3 zkosOus1*^UTWt)eRkUcoeM=VK>CK!s&Wo9%HTH-?FX2c`l5i$?R?_qTRyo8l0vE>8 zJ?S$7DoL}lmyv;i)p|{)#B;WT{LL{XgP)0-x&t>g9w60JQ!!a>lwK#aGPzU)wg-`o zem-y8-gda*a4+TKWL}OWD=?+t)QaZFdmJT|0UWD(000gpD+Q@^sd6}KZQgi0jXsUy4> z!7zCmXk6aIe1&D$6_2}jWraEybL_ZY<6i-O($45d5=%IJ(yIu}Uv@TlvQ2PfMo=_b zxic2SqN^~Pr4kHK>2Sy<%Y6k%36uc#X#Z>r07bu%=bc+(?do0rGFDXeTh<=P?;(Dz z6vIA!J?)KhU^{>E2-|`~yCNvX)x2Nn=Z{2^sch8q{ipEqZ7yF6?c(if)`>-hxeE$a zEGfxnY_4sF-sA^+EQLn*wWW5xYRa!Ha}b!5q_{<~EFT1J<@@q*rm-q5;$$07nEdI7fyUx}qQ_Zji?+ z_^|sJX3dQ~GI)f5QKdJ5@POk4N*O8cE%u0gz zJb6(K_C~qP4wi+`pEBow98m6U(@M?D^y!M(-mH&@>$2Xw+OQWd-{Ct->6b{|VfDyv zb>dSn(hcAQ?9oASCqx%t1Q||>M@B5+)GN6J3a}Xp8(}TOR)EHJ?4gcE7UVpRPDt{c zf8jJrk48y-FVH~8gMuZra*QK4q|EEk8_v4#l7QTCPZOO=pvy+8X@Zg~JNwO=sB9lE z<6xKyWwj`gGaC4?X=*%N@>$R9*Jw+^M?V&=Pj*r0c_YLXFLxe%Zk>xM-bK;N31j&5 zQ#rrHP4JhuZ-$S?K)665RyI(9zKw`d;Gmw=z(%TVQh~=bVNPV-Nj548zr+%m#jVMn z1y2Mgu3Qo92TVs-OVUdR9MwyVfBa$)R!_};+E*8gxBvs6Tk2eBR*_?b(0p0)j3to; z=+(x$3dfHmzaGqHXqtUk>HoZjNq_0Fvud1{z@0GF4Fl#{5LRvTa^ z_yTXB_cziwCg}mjWcR!!^VoxTtATfG#f&5k3&Cg|E@2AtQe}BgUDLy|6L0V;d?iM` zq5<#wd(#v@tXu!lhd848Ctlb*$5MeCSr?E+*vHAZx0Xn0y0tG3W%AH^b7&{e*3j2f z!@xO-7ygK2?uyq%!Q}4xV7jlbiCQK}9kQj{DU$2D3S@o^c8b{tIYe!tzt1YaVVeIn z`YD#=aT@A)Mu38nixqTLZKDTXqeEuG7kTX!oTO5{KD;2Y^WphJ=RUdv^k6^tRtEnl zg-nuhHh&)PBZo<_8y3c&L!6@U2-$ z^Hj@lSYeJmJ-I6>wGz^8EbGv+Zb+6~*YlC#$LG#Wf$3=TtV+9j`mNZp&`09%QG-q! z4k}2IqJJSX(yqURrHq*F;=6|SoAmb(HK`=MDKhlUnn&u3o9#2S*u?F(7UtWtl#k!}^DZlP`w`#K3KbQFF4IQ^l_p4L|d}Q9`joA*s z{|+JX00P*3Y!CVmy2~5oze*K~obH$*!^2cGcnp^tvRbtX>A<7bRc-N{y(!kwy$^Fe zF6wbj1#WA3au#HertI&(hL{(TK&+)<-!icw6G24X>+&vUH{g#p=gGOMcWtm}p-bSd ztv-kN_OkZhiO5sgIm3mL^b2jssM1b1ZItpEf>8jE9i}%Nut^!=>wmGwTp>hf* zC`l10rycbERJeRNNrNaICXiD_qq|a`c$U1QKi5}*mc>pIrOx*i=QXWA7F3_0Dpy7X z2NvlJu6LQdf4&I16i$8!aBdXg@Xo+23|4?th=9nVec3D+GZ;j0#Nsy zWLJYtOI_L|e&tU#rR%C_>|%HT$HHKBIGa#L^}TGg!bagk6bBqITWyqlYzSbwbOG57 zgfWDU8^Adb|9mix6BE!sG+ib52Ot0HI(aqCaS$^(#_EVt3nSZQ&(?p=PYw6x)&7NJ zmk6XxqzmQ-_GEkXZkFCT??Aq{4JZTEdHS(&5pS#It05kPOQa$tU>{2FX!QFCW6Dm| zdg-sF^p>c$Gm1IxD8%&1YKc#|M@RiP7Zy-$Ozv9F8ylQ!L ze)Z158YPH~n3WILxt<_I0c26IFWT>#_AT%8KJ9AGSQ5?pb{Sbj0=9nM-Kl8(8SULz zHQDI*<*dTWa*zV$6av`cc8nC?Gk|hesi8RdEHRHU${OeQveoE`U0=_AC6F^kk0Y&wo^?+ht)FVkRI}&$hzOZ2er>UcvRy*|FAqCu;Z5?X7=^N;c@3uCVHD7?69sH1qUw8)USrfLq|cJ?s;5h1+i z#mXEjT>Y|qd7@e>>VBj#O=oQVpHYWd<{ZqCdR~4|Yph%}dc}+Pg79gjRq*zc^VPk- z2+;&EP^(|ah0Aq(J-K#sSnYU1q7sEhs(|UD*Sy@V0Ic#WV6uZGfb{6z24TN*zkUCs zenDJtL^_i)YhdzJ{AtzzRB>CWF?PWqx!=tRHpO@^+%KhYM@4Yh&l7Ey*6;1|q zBzOWgoo4HGstr;^q2t_t;KOn$!*sF8o40f@x|J*(&BCpj z=Q6u0?-TR4TKLDvtD96JMsPO|azeEGC>#L}T$y@n4t3Oyg!r@q$!;ip*H3>!)tNc9 znX_bHvfLrKxQTU8=^>|<&0SZRuTEZ-b}7zpYRr71y9BUS`6o`j8H`y@ln2+#QCGho z`caDNXnFhJMb z`RWSQ`L?P?6EuE^ZP68R#vLAA{}LxpujhO)E(~C9&oC9l(?ox)NK#>|BEW0Xq%Wha zwRps^UpTSq3<;B7WprL(h?TZfS_REphT$>n#889?tlfX5dOc5j{Fq^eHLhtr9~Pnn zE~KW{ejx*OWM(%7SL|9wp}*>j!*=s20?cgl`l(r6Y~Xsj-lSMk&<;F?D>ZzPyl~wZ z@+o>1nu~myQ~gYw+oF;Af`ss$zI6qSgIRTUK)gOwJwK zZgHr(0!!hw(j#_Qi9VV@v1HAv{0Hmi5FJ%|Vm(7cG&e!po3gUe&KP?!AL1bFS}=DQ zt~ev5e2hz%mmLfLX?Jw8gjsl+i3ItlJP}v?HEH@mHvl<;HcUXuQRu%a;I$8OreHc; z6b?r=@A3PWsN-Yg2-2g;grPIj=Z7td#s031yAT`bm7rjRBbmrA=G?>UjY+L&8Pb3* zV%v=vVPMPq5CaMJ&YZpp`_xsjeUuBCp?nbxe8G(~-*Eb-jN)k81Dg+~4>|aZ0RA{% zq#K-rJ1Y8PCbNt0FA&Qv;tqA)53f0aYEbDhX@$yUG8c$X6rO^csFRSq)29I#?u<-3 zcu=WYypTQ!H);fk+`SJE>;?-V>BJl2#-K4#)WbE3Y_sm-SEo@d!}#U&9)^5e?QW$; z1~)nqk@#><%yP&iyW_hsfyk}JA9qV|^sQT9zGe9c<#WscJ0S2?pm?vj!Vsnc(O zPOVEgWLeEG=vJovy zOiE{8&HwoP`B_+{NYCgcwfMD<+4g*%d0)1kXb0;a?wnV2xroMYSBs6v?g=*$L|g zpTu19#I#oe!#Pt8ai#x)dcU2SyO4`*R-M{+M@LkS0E$RT(D0s@>?#OVRejBxH zp?f|0I;D?6uW3pL$vRH@J`4Y;U@*_s3HnnZ(uJO|BN{}PI`d)urPbgW8b`qq#XR12 zzqt-dGmrmdQtZ+FQq4Se$UHX6JTCUaw~9(J0k|6(b(hr1?;Nt2*F>4csv$oK##w0Z*y-hY0B#m{{3p>` zB?X$v=S7S;#tCa!P0yhYk?zyJ-yS*O{>p$5z?fmnDp#6i*~tUyTtQfOi^9kw_{UiL z!7$EG61Fy_ddP=!#`ck3q07SdZNlNDT9oKmWV^!FV*=P!QVGPa&~Zk9-?sx;JYqHn zX%TQ%4T+WhszjQ*7poa*0WI^PS;bt2E)g5=zqO@e52 zis6Q)FK784=jpRJ8R#b(7-hsaak3PqWi22&dT=zxyx+sC$8!17z6%$A_3PnEuFf;S zzO{|$8dFEs6K|=#^L0UHOpv*kt(HS@M}kaZGXe=jFl5{`Z`ZupQ$mV#D9#YOYx( zhN$1PQyi-UyxZ*R1!SQ83k(~4YYkua)>fpbqFLq>g5Z#?B+3XGZ1^x|K+9^HOWLxC z^@?1e$}I#(0VFr24cbe3sje!Qo2pO$?Gm1?dTb)7Xctb zkN$WwPQ|6-x-Z@#t#s1@DFQrY*#J>O(_1IN}5*2B?-$b>(hYWfs#s`x8$>0R( zc{9w7-nn**gq-~3izUAst)ZJ{`)u=LEqIOE>{;O>$p_#wx7K2U-;bx$bomKjiG}7} zPnpkL2G0qL$o+-QXy!1YS%yg^`HCST1E9ojVrwoONbpTpt6X{Xe$(#bTe(C&p#ASJ zB?iuTu&^Ac8U<=mL(TUR2batf(FQn`1U_7GOZ6>} zkN4c*DK_SYOhWL{4zIVY>ny!fnE7Yso!+#XZ*cb^vMUfa$M$OQg*w>!Vc2$$^iOt;!&@6y>heAy|JIwC{@-VfSvDQ&=2#s$d_Jr7^3g?{@~CQO$BRki^%w8nms&N81jUfa;YI$?1uYUuz76wK zv)Dxi6c~0q^j1F_{rba<$E}dV6bUFL-(kqsXDyO>-q=2%(#j)e$UF^k3<9VwA5bOf z$BfX%ezdGIU{_v3yosv5UQ#_cggP%zc{I&FESA(?ZY}IM3!c)Tuxgq?2x=x89Y!Xa zOLYWqHpP@!nc@0vttwz9kKw)h;1cOmbbkQ1z+1wZDX|6&FxcCZK)(rq>M1U;d!I9F z{Pd@mifjCdvrahkKt9~dBJ;8=dx)&WU4a3*D3%e{xCy5lYmL4n7K~_YeEklmk1XSX zPU!+oA`9It5RotY%|Z-B*LMHde0bkHKr{POj0(2pwpgW?9n-93@lyOO7d$5 zlo#C;lV8t1@j3bfT`Q$iZtt_!Kf!N2ClX(CV6G%*8M=@Rw+QiZT1w`wA6kj@xL%Km zzI{JO#p?=*INK<6*GgmoZp39)i^6tw0?4+8>#t95CkohE0U;!L^^`lG@MgLPN_o^= zTm?w~w&c!z1-p9b#EOS3=6mZJ3YW5a;cUPm{kZ&m;!ElP^{NbE-fu%ex*bBOKN#N{ z(&OELZ}*`6y8+pvo?aY#zLCtBz3kbSiHdHXg|frGpEBIJ_9MqXaxq((cjYdachStm zkv~)dH$Ug^Y0{s5#NDF#MZtz_Bg6Dgff;>k^xx_7rxcweQ9i06s*|-aJB|UYO6AdV z+?lFV4z*9@HkKnhBGCpqrA_a5-?iTZjj^FJX+#JBp^Cw&N8yp~iRU_2*r!rm$LMo{GN{EfW`6Crj48)e|w(kaKurtKmwO?K{NgkSe*k~gGg zGyN4=I;t0F{PH^npX$m-(MQ@8LX;#^p*B8%8|tr;sm zyBv~fbhsL4-A;x>RyHW|RS1LE0L)?ZO)N_Ae7W}<#Ls@M&z#|2XZf#2L==y#XB)Ey z6MRn1FiCk&X;L;ZuorAywf!vViah$p=~9!2g^Yc2(ql@vb)BUXPMS+BSSd2hmS^N` z)D%kBlA_PKYz2xrcM}i~!jE{I|4CXb!^=f3QS@I^@I_|rqTeK4}%jd@8&GLsE}WJBKKgLr+oegQ z9u9s?#`}jJEiKw_&Nhy6a~=x_Li?~tft|iYXWk_P<*JcagT|TB1bcg#o|WTML#~^* z0qfrsVrW`G*XN8Y@;EHI(yA7~ydoq*3=hmJO{eSf8b@&)=GT?vNDL~~pSTe@I#rF+ z9EMsmtpvvzeEq7Q?o66h(&17AA9XMI;6=1G{jA|($>)@YQ{k46LD8Hh)Sa0SKL>!* zORoEv?bkSqZxn=XWOf%)83j+Gl-nH0d^7>b4DpfT%KD_AdpD!$ckg#?i~SH(=)4S; z)Ey7X22K{rh!}Kx7NBO?C=yzCfW`?%)IU*DYKl=d0}1YaV~l3`=8+)QucXW8L$A#2l8{u5z^gbG0(a!oYE z-rkDOVL&$mg2sdvEnMYQgV$<3eIk`1ZYEA-BD&fHMUuNNx7f1-$mttDe>pwe$$Mha z&I_o)ePR3e#@B)c<96~5J0Gr28k{&c)Qb{Z^l_BA5?TRYILeR)vu z3MDJh5W3y=iBm3`#rstC2RiQ>lzt52X`Mb6U(kDa*&-HoSD8@(&WdBZMh5 zPzO9qLro|b=^d-5CS5vn?p51yklHdR{{7z%+JN1RM)oqtM!tC`Smhw&SMj!i5Z2HQ zmKsuI)%q-4u*c6 zbtDoCOnm?(vNXaKD{Z2!>=1*6HlD5rynhNGRiogDfFq=BaEGF~^Zx=6LacKl39{jK z)d){X0yHj?s8=RusZ^@b5_4o*EzNL*(_=$o_@2PzGo(OBE5IFmECkXi1yHVkr^9U` zbHr_XJ?xg_6;FAdp!11-Y7_v=iD(!gv6wpN8d371Nc2_{gb7o?DCLTOvba4b?9bH0$(%1hD35*ur z>_@%UcYfY-f7YEVn@crF`d!Rd5 zm#3}3Mvr@BWBx|Pyh~0n&yEKLslAJ8%a%xwOgoo&9QTG%Z~V??o1QGhw+o>r{FkNG>eC)9=Na#Ve2`zxc`J=_zKVRzUNRcEdh+S@goiFyvz;Y ze|y1&vzkVA4%Pw@`;S9p;kQi}YtRWTrDCmMKG~QkuPJzK=)fphIT1~hX`=g|gx`w; z4M*f68_qUc`>x%xnwH7Lg}ekARVS*&qxdl2;;-=lRTQfpX47fc)B44W^T!N{y21R0 zJ8f`gD)*~Je$bdBa+&9Z_m5QEPx$Q6;-QH|dZNL3qj4NPBVvqJR90_9fTJrZpRR4n zUg1$}E8aQfQ9z{2tebL3r?|D;bwKA4`@oDZdFXYfHI1JxnC|?8GQtk({%y^agFniX zH4a;^(n?cH;nZKN$`PR0JtWzRZen{sz4@ZiRUKJG;g`LA7LeUqAisOP@&i>0-g$a+ zA7Yzwnh?#fTPg-$Qz0Kly6kh9d+it``!r~W_V&l`Gy#>!^d|HAn}8Ht)It?+)bgRbN=kHbudDfD*MvqkgZkUnZWBj!$uh`+tw_86$z115o$jYlTL zu0TPhnxs6ctPAG$iALu~Du0jx&VR}{QN4NEDOJGJp8WATvGgy+z2bV{kehZO{V3qG zbKMk0wO`%&{5}|x#t53YMxn(qdOwsvME0}b5DO#68~qZgGEQP>3AF3fL5vIZj?@w_ zs}q$<{;9-=(xE_zR21c~fHRIKM7h=jE?j~yhMC$$Q2sXUU5$_`Z;|iLqK{&cvLz1p zQS>DnAk=#vd(+CPO;YSkmbN2KGzJk1eJuRR0a%X96l{v^iuntZGGbWJ*e9m?CWc1M zGZCBI>@B+q=38j@iG0)nVeqnYs#JX5R@+TT_Mdi<=LT$7NamQ(4C7iKQp6MV(}V-D zLJ>JCSv%s}Rj{-7sdMxvfpOf8ix8ul9;F zXz;*=8?m1k%Ylht8u@aW?w}<8>>2)lUOBfB08;}2jm8H$Ba6$Rzp^OS0yc< z<9D9s^Y#t4eWLj>1|Q8g)~Rh``r6(VLgmo0oZ;m-U;MF`Jjk zo0kQfm*tx%Ob#p*nGaqf%W7j%qL_Q}SB{Ck24!E)$x|QUtS0zqRCiUki;N{Ou?38p zu>&`!*1|b3r1X+^-1fg)`){7?3E`qOcS?}^->m2I@j^eH<9pTTR6OLgUb{Q+`q+Dq zC^}JbfnMP^r3QzJR06i3+@t$u0!qS(0rp5JAg{O~Qvlq# zmlHYINo)$TE2`mhPGGsop&}X&(BB#gLJfdu@R)3rQ}5Fk#oEuoq7gtuyOE%CkO2~B z^~PYYstN_ZMIwB0iXcxWsVo=Vu4dpwyh#T%?~fR-*ASmcFl^}flu>~;w$dt<2B!7- zw?romKp20YPm#_`oo&ImLMe3X1`rkDk440-togISAs=F1VGNfxc^jzna}y$FFyS** zA1km#i&FMSOB4Sy%@)7D%n2d&)2>A3XXk2RHv39Ft0zA0y$qm8&L@O97l{MDmD(#8k zZXHMfD}hZ$A+m~M6iCO-FD!siaH+|%!>mGf)z{%R+Wq`)NSbJBEYt0ssL|ZOE-ize z67+>a2i~`hmmL8aQz{**MdE*po^)DSidT^V{a@kiju+R7AM@{lBr&>RL2#f#B1~Uk z0Yu0*ZtgF-!E5Iq#YPR&Af1%o+t$Y6V^S-fa$c<~>O-aAmv;+2Tk4jFQ zmJQuM3-(R;c{sO-|2;G59PAXaxxu-y05dayU4!&f@V8_Uz@ov^68l)#Mgt>6zAyMC zpTzl26_^xGAp$*L4@hTt5~=d5bi=Vm<>5op+x`JN1@IJ~my0r2@n48|h;>HgojSFM zw=A6|-aLKGyAVYz{3{ua?d;A-5o>tEe59dy$D7+etmBQ*eU5wT4=%XEJoA=i4nB@h zj0iin^rh85(!9AA4cdpXd}UI<_vTuOPVj3EufBK4?O2qW9dK=l_jlD9i~RL55vBvt z(rEmXBJF&Iq!Q(S{De4CDS*BFFU3x5{J3o@)_20&e1}DbHm5j`cdHJVpUp#zWTHVQ zl6h$2->W^-ufsfJ0&#Cs26-GlX1@G$!|SHDjF4s925RFKz1#dwfQ$oC29R|XZ ze1RXr9g@uHbL{l>AN~ZMGA3r&unKUU|ICrYo28bai}KqJ!4}A!I;_>-`hhDjVyrAQ zHc~`-sN@0T>$v&tO~6p%TzxYaw=19YL#N%jP9@XipK;G}JNIfv_Qppe4Pnt}yn-x| zl_}1r<02&wmHyc$9eDJPr;_oz^4fdy@0M+~`Kp)zXafxPNFo;=u)OcQ5vNY+LCa`I zpa0~!0O_`iP0{^t{#Q*2>zybd5G|c+E2+zQJBKrU|8^!kSZCEeVq|IAL&f(7PuFhz zNs#-P_FlVA<=-PkgUC}Aa<|wkuDgrVx|^n~_3dTjZ{KGFXrJS3aqr6BQ0ZnkShM~8 z_PX@>yrIi~ePaz4GW>2U9dfd;GkBOaoQ32aRhsv%`oHQC_Pu8c!@6}EL#8d4M@Z+=0&LvQOOWO)60XXh~$Wi^*oe)1xlSpUZ+n4-zA;bYo zDjy~6*_I33qq^3AtKbp4gfRN!s-mx%k_`Lc^V>-oTRV;>ZQj{DqYO2;ii$ z;5PQNO1Zi;G+7I+WeAAh%3hVJTOB_c_Y z4ah8{Q#iH^t_;x$PBT^*)*IPTl5Jcf3>A!ZWcjyM|L~?xeM_9xkqW2s|6?pPC>Rcu zA^9RvREmIK0<-U_;dJE-B1Zy8PM4|b*uqUb-eRaUCkdh-SYjAFNV`s%RSQcF0mc_J zcR{DPp~Q*a2nRNTQ@j{V8>D(C(W>Zb2q4J3Q$;mvz23*7gX<+3rRny7PGdi`xb8N9 z{Aa-lV8&@uA~Sv*gCDaG+15$g>AXtF z_6;!}!1#1HP9{At20IejfmCimKk8*DOROdc)8B`<%5-$zDwG5~Xk%9aUUf9af1VSh=cS4uzZ1jM)wIMi>)Q# zOj?J&W}H^+?8N1Zdku?3>e)NX5vv}0{*_bfV8u*}II<_@8T146J^Xc% zUky)(;WMQvOT&}yFFK9OBw0tEVic-ERh*1370>vI2eFN5+2JXcRx0l~}$l66jJ-Bl*y|MLDIQB$jR`=^_$PG6<#kCDDZKMAuao+ZRQ z;Z%s8G-chh0zY!+#|n(T6_OCDQ~Hd^{iWQ0VH{|dCt&n2=U@oF!pt|n3|W-v+3p{j zsU@@~2g%LbWBtTDb_=#!mtL5P&?#q_g+T|S z0oIBlpuvR6MYqOYh$B=#+YvbT71@I-@CpjWHComJ@yy*L4bCNABmzz3^!O>-Gj7Jj z@dG``&sktrZykA!nP}iR{Dzh##}AfA)g9(^?<7jFKI}6M*;u+`b<$?85#E6!c;QJ^ z14it^x}k&lHqs@;>j|WSIc8M)hkE~qlx%l=JGl+be*cs`ZoHma&h3AL+~rE)Qlw$$ zLphGti`s%D!)cg*KS!&iHzX7qLroXHbfj=xQ0p#0dfM@HsIWHRQ)IiGbJsvmKple%y>7nFOWZ zp-7aN1^?>Pt);(A+oPs^*x$=QPl$CU6gLHoYu5@>1l<$y?W}f}n4;doTi+E(mrLNr z<;}5Vn09=3!f%^*Z_l~^Tlf#cfy3JAk}{+J_`N8$POYpVYjqc9d#R@%XUn}~BStvd zzx^Z%?|ow!^^_M4g;4Jry1N3uN-Qe{dQ4>ui8W+g zw5abPp5@Xy{=KOrvoll+$JK&(Z-gzNj_P!BB$v6cJn7O!(<>w6+R7~*o{*1aIAbsr zW(3Vs2a67CG&%E$CZ~zFq-8??rtYgzCO%vgI{dvWu!$TLWz1u!P@>MUL9y*D$~%##i8=3JeuE~gsl?fI$EFV0QzZC!{V zqJFJJv{P9q!JT!_V?9dJo(xQh8N9xrRRxD1`*D1GRh7gKzpV}O@{+8tqv>Uk6HfbY zygv+*2s4HUFl=J~3u>GfNs|<|&GL;FN05?}v71IHZa0Mo zM0=x~JZ`L`>rEgE&X0ZvFc_m>>m}xCIRn>EEOY6Rnl@fvU^|9}GO=_31*#)TUDKU; zr~WM|Fiz$&TJ;0K(2C0Sc@z|l`FC#GyM}LT z9ak@oRP=TICC}jblfi)XZPxJS6%m% z@veQ*g|A_2T#Xagt2paj0XEM=XztFlby=?}o?nz!X40;%kw3i;v|qc72+ObTmyI{) zdEIGzl7l(;1Y+|-TPjY_*{7Qe;35SNz74V1#~ygmXbK(rQcc_2JmLSfv95-hO#RhR zH2SU&iTM53 zxE6fdJuJ&aR)E__S97D@?d&p6OPmCzlgBY4TbyCeU`px!K#m(6qaX}cI?3-(w9i%Q zAa}tkD)EamJk5Byv=JE81f1&s$yA*Az*L%D2u)RNJp%i!SU-5!0XyXYL zy#g_kPd_5}XQyb*q%1?s-VS$(o1Doo5@MtEWEJ@Z#yQ%$YAgdtthMg`lmzS~(xo)P z71vQqW?dES&=xY~6P%7z&OYO&ckw>N?m{$tEU1?lBP$JBH4ifnrZG}kzW}9c!RC(3 zf{8^x=m9cc<$B(R%^n}njW%K z6K?ucG7t{J%={F@1U5)^vkLs=Dz?x^Zs{EnFDLYb@MrqgkGRaA(m3GKLCf&`{69`7 z&yG^L&_$t@Zw`n1l9i-~AbIPcRdYur$sSkmzH_YurHF_rSffiC5M~3d8y}H{^k=Vd zBoJ{FdtS|euB$KFs!;^jD8D%Cn6m{mZtR`gd2*=RiThv*+njf%y^dQ+ zYnvgFr;Dky`tIWs;xN9re@LcQ2+52+OYDj>P2Ylkj}e#8eb z9%qazZr=vQcG6)ooG)mclH}k>ZM%Lq21R1cFU(kM#dzHBvR3ub-MFo_1H1^TjP|^T zM@{J2j7Y@+vTCxa|U!8gUv(uRL3u`U^ zkE!nrhb!vZjxiYBMDHy@lt}azOteIT5kwcA=o2*vX7n;jfd*AmT*X44~*?X_G?sczwtu0m1-Ac{MTh)@HK>#bhV{iPppMV`lMI?9SEyaog zL54b+20+b*qd&aD}z6Djs7_BYV1WGQ{2{%R~KP2XSNUi zlNw>-@RLgrV#G4IrG%421;QkzJV>oR+qdGQsI$b3XimHjOcoUF#;^#wD{78cWX$$1 z-aajz(<0JU2eoKdtepz8hHiU{SDx?h5AlLl-->m$7c-VrvsbycuBo1-lZzZyLu9_( zW1l7{;iuRBY5K^>hZUSFsZ&1n;`_hs#9AFlB`dk+I#axhM!&PV4%Sl%jAeec!OZMD z5S94x^{IFgJLk_;*&*Wca%uQ?Zumu@VIx@_bGj*2&zp{ZTCT4OL*zB4Kz9XcYpIXe zZSMjjnk+V)G64u86=_!7b0D2T!6J@FV_Brme)?=UfM_&5>j~?|u1nvKW|Wf}8@rd4;zRV0n1|D=A{0L&Kn9-bGaUQct<=l)%Siymm^`;Jbw z=A@SBA;yJmJ*brX+8L9mo#mjq%(bchpZE~n2L|RhnM3eKN_hh8vFs`g@gDE}f%c|T zwNFq4zNX;|xi*bpl+R@8jQmD+oTl>k5pGLnDG#6FCe{^)LGZ?)T|sFn>0_Nq4nfaC z{W5Yc(j||FRqoBzDJ2;^O}~Tq>&$dXd3TZbpOn_%Q5{s%$Gf#mD4Z2N@#*fmKE`7d zmU#>K%h;X97u(r@yF>wn-JDAL-}EtRSw8WjO}xUNzFJmjlEfr^SW&d9{rP&pqW6c( zFXoTCth#BhtGRV96iPf{n5{P14oQ(fjKFOtE+9IXavhcs1}j~d`SS1l4k}cbgr9v< z82ZdAngO~M9`&0qQR*b~37Wf9xYM9f){vF2q|1b=Sr5RC$wAevXDsAL<)smcAEBr! zpgCYbY@VJvc;WDw0b>-sTIP!QO!8)!rk1mMd3VvpPq#n}vB|F(zKf$(kMv~zkG8W} z4b`K>v42Zn$;fTZ$NjY^oF(x5a2pH&%E1D(-YS+7+Lkc+DRkGwPPOe1tN_18dEi+u z?J3awA#F-T1(c_V$d9Yzk8D3FrP4FZ%r2;Q*($Oul{=#IWD93XJkMWqIEh3s6Byuc z^gh&?AwKe2`ZRY|!YsWJ{O7NU+nc^Ef8EB%`P6f}NO8jh1ZSUP6hA?U#07GO+mQ8{ z7Us2scVok?gIXxMP5yWi#XjuEjq=CVk!HDl8+`@we90a3{H<^8oXW%M&qqLKbM%$T zuXv;H(wf!WnnwzHCn)1prIs*VWLbg;A4-{{{^^jG9+>zBXgVl_&=Z!5kn)u8Yjw|x zuU2jH3W`1y0;)WWB41l1?HcfjSKbE$?Z84n*_R4-RBrH}>O@8LlSqoimq2zD819dF z4=##qJIPj;YNJH;SpAA)9tL{fFIwYo(i;EV2{Vg2lI)V6)|Q@6*?p2`I9LBVDaf}VGALgKlqA1!id^#nrX{}Pkzku@r((Af7dPi zG)^XJZ!z8>>fkrgkzvTsjHdIqDAl3!?-+g-`c(NI6=~N;rvgY@9$5i#D~GS$pH>*t z#fLYce9!T=6Bv14KtWGsA>RC0P}uy7BK;=!l%4e-K3{gGyHgdbYDWd)=sMvlyp7C? z7T3q|;R^bjO@!er(^?wSI2yh9*=yLmD55-w@`!viJKHmISn<*UF9B&A{1KQJRVEB| zLDKsqjB;j^Kq>ApS_Sh>u&tjbJcx>4w;oi}1*?qz?T#A0UJb!0cor;pCd~v)5Cub) zLNG-9E1sFnq*2%h+%)&w;B?`Kk3D2?w4C871;r{O6OKco4nP`mw~PN5zmt4)sDs{S zk?0eGjL#;TcNMe_M#c2VVT7UM&|OaDJt~X zA8(C~kOWLJT?fgx1?Rm3F(NuAOP12NsxWJYc(*+}}-uplfkM2YZ zQ-Wq+F2oZKcrHIa8bvEK2^xS^K{Jx?3r)u!XMw82kIij;u&)C z`XR5Q?WKj)vj3K9k}K`CVhJ(?kWHI1QtK_Nq@BK6X8sOR^hcl6E-F7AP^v2&CF3Cb&3f0HaL}kn0iifL2=^O;^#jn3Wr1sM1>p# zh4w_Nm_(-roL$+;XG>nS7<{=$Jl`Vt^R2sj+Ll=yF5ExNx%fMJ+#0$T9qG#UQq`XjvpDk57$gGbl4eL-9 zqbgZ9Sts}ZTB^eo9EZ@Mj1oT3=`9v32<^zD$x<-saN;FYQs$xpn;~W5Jx$^ytCE}= z!f(Tn5l()INsY1qv zto_;`>$Z!5-u1f>0*UM{Ep~^5{pJYj*A0vTf0}YgQTAM1P@(4$(F~Sv*x-Y^VKWCd zWK3R5O_GN*(c57!%ehel^rHg9R%eqV4@@NP>tvs8P>80O{(QiT8h=YI9En&J!SfzE zTb*LDBMl`42$o<0f1513cF^uM;*b$FnKSZA~-zJS1G06~Bcrcmj z#~3==a;<)e40F0HQ%H`k6Q^)8Q~u&cjZpU~u> zrwi*GENnS{PUo>R7%~XugU3Qxytpel)R%elQslMRbEU$RgNAzVcy7FK$DJ-FwW(hk z_8c!<&9OZ)`uxp)0KJ_;_mjv5jj7E^{6-aioptL3T?hwkpfJF563yD!_w|vgF|vg? zu6pe6kioo1L{;e(eD9%7YkWc=uN0z153i=!Q9*fZ&(M%}A(+z;%s2ba_z$XuT`#Mg zfk7%7Mf9@=>3A*2yvasguYPgmCFJPwYk>=2^;(cq_cy_gtNyqJ^Xfu~3_!Yik4Wb& zn19mol};{VS_1XriPIR)?1m6N3;H{c6QRnZJ-tV7&V^dDWBELHgcrU*sZ*kNBcuqK z-dP88DtoI#QFV*fq1b5L{*PWqNUtxh7QOj^BOx>LSc;J(D5!bcA}shY!D$?$hxw#u zh-s6JRy`Ph@H%BFOBWNTS0*Sky3j>iz;({usbr~5#W?~&UMnwT(MmR!j5Gg$={(Zp zyZ%HKTFLuf=cL`li@~kK%ojv*f5C|@^4=2H4SkecsTdjhL(C*Oa@J&$Dh%DCL+-aa z_w2C!Dd8*P$4s4uwLy+5J=hw?;e;r>2NH{K);qP^p>aq(-@&&#;ym(8qH1^#E( ziE2=9Ri}H=5(9UEU)_>$plNciH%ehqDT)jNOBI4eI?=WrhNMy_t@O+dq_X{wggP-6 zLOU9=;j(YveVTKwKU>#(K7;%(m!c!#{>9fI&7W6UOfiVEW^fnfMzAr`B?z~+70J>PpcX79Pi1M(5l)0w4` zR2RBu?aMkK)%yzuYy+H2PeBhk7Q8_Nor^9+s)~zeP7H)yi|`%77Lr1zV{S)YM3+Ii zo|fOu_J@Ynv@%&KbOit4_ z400Ba^B|s3dD5$0cW*m!BYWD^!u46bNLx1RVCNCV?9RBLza2R#!8Q)eGWd>N7%r%q z8Jq@*N>5V-cDQ};uO!gRHXd#XZ8r+p+Y=LhSqL3{h#K%fDZr~p4=>eeLZ}URC9({` zDx=ywe-i^c>nv1>ZB@|v$w_|_^`q)02XuF6ixMG+-=0R^nrx|NhefGX3_4sP9J2M* z3{E9kf|ZNPhh# z0gZXa)-1#krhY-pMT_lcQz#)+j5$anU5u`Pif-yR8l9?R(qiyQFT&Qo%eP|wtN({~9fKhy*%j@7Secm> z@Ti~N+UYZtx!>iZeMhhrKXc#mnIj1=B?O7wlMnfSw&cOqY6n#SU zZ9PR{h{5KCO)<1R*W@mA^aWlfubUs#nl^$%ZPdd$otjE&`J*)M%ujZ5v20h}CHh_T zl%Ys4$-77$r6-S-jxp>)A(UjnxCo-4Ozu6pCsj11pXn*yeWK$Lm_dvXk~SQ)QtyG_ z^bzs!iq1@X&`vUAJZS13o3$UK+k9E=s%$8e8rs8JJ{9^)F>4!$I8-pn3Tv=WM(Ha_ z0dWH~_L!J7AKm_Tjo?+h#gB@om^7$ZkHt^J=q04NW7c_ot)b-8QW*xN;N_PT59OEN z@d_*<_yAd5O@iMves{R`8~3GX>fof(8YnvXnYj`R4^cvT4Nb%dme`X22mg}(urZE4 zkt(Y1I|rUHh)mPdRApfJL5J`ep2Jr>oc*&xb_YGty3$Al+D_*9zqwIjmU%akaqO5 zm|s+dvlLFWiH5TH{JsI^0%0qGbJ@D--}^ALq2?rBwdsIWhO~i+5f}w<;V>KO6vz!a z+{VXzI+SaHFe*P-s|aU^L)c7G2(#tbt8+rzg;Do}3qD6G>F)Tk8q)`@vF0V@9s{=& zQs^J_;kfsAyS^rO8lXoc=U-X>GNG@qYD#90C%6<%IZUe{ne|QAxHibX%vD8b5}QKX zJ9NZs0BN=*yPM>42~Kul%}V695!Zevxl98|`-QO(iGnTBRA-9_`KkGk&5#2EhP_sD zQAGTKL<;=d`hEDOUJYG13*bEAV3Mb1e4B7tgSr`QiXnGsJpaiH&@_>bT??CgmZ#aL z?^9ye#$2iai{4-XwirtEc7f*-LXznmzvi=FtA|uXSEkr*2PwH3LI&486W;9q8-1s(NtgKs}p0o%K)D-89xK}Vs`tWXSI zOp5#v3*T)jh!{ffK9PC0>g4G&G#_((u;?O%@HP!M zy~^099QC(q#LGqh>`y5J;O?O`$aozg`3w#UN|?=ktKUP%?TmkTYgQw8IkRlzbV#hL zr;{pcSRDFR3N)@2voF6(tjcV}`sQm~$EltRrW~rd5~ST1i-^V!s4)j$WT+_a2rXg= zRdr*2N80hv9CXUbP~c?5j%je|1!cMlO?_)=g7c797|IX%Nt`t~o9SX%U{fQ>;gVGL z!(~aoo|J_}P~IG+z*lXr5}LW$*XoRGCC9x?KFg3Gqz2(xq-~W>D@0wpTr1`4p&i&F zG6x=XQPc+>l-W&TW@8iiGz}3gY-vuMEkq%j(rQY9Z2p%k73_uI zP0q&YwoBw_iEoj{wS4v^cFN%&m!6v}jZr#Sib8Zf0EA43n|6g!3~V9wL5NaoE$~|? z?1c((eoB(hW6`~`3Z{3JDP=$JyZ10pQ8;mm4PLT;Wb_VC){%m!RYlaib|H*>pxP?fe!`&+Z<8Wi z)x@hWK`dpY{miAMRMuN?0F*$eT&_Q7+)P4F@?|WwgL*b*HBgEQcI`nM@RLjnTp83B z5262zuXo3b+nQ&idBTy+=MG`QR{%pj#rWPm3smb?%=%I~PCVV<)J%iQ@?YN|iTr%;XM6I`YQ22q~2rqu# z{%&}EQAe(7)8gin`eg_Q+K%bKIT_4UsZs`@N?P(i{E6g6rIGA^xb)&OcUMVY%tMhcYLev$UeS@5> zo3?B0ZlVMgEcy3hP4+TR4UpxbF)0#^GUMyP7mQGtx9^|tTd_BW*_SU;4jq9F%i2OvQ zORdoqYncw~(06=Zls%PRcE($VEpl~6|3gRvu@+xH`5P&k0B_M5rxs!Mhn2xb`(iTx zGPS1ig(F;DxB!@XydJgLY2Yk;=wF+QDkf|KaEeRv&XM!f-lot(7J*3(o#1oq8pd|+y zCdGwKr-rchZLV1PbY8kWGdN@Tl+I{Z1_z1OfyZF6PHd<3!CX4mdW_K{ql@JPeu5kM z&o?sL@AzsqBG?u8qdy7?iHjcP(?4L_$PY0G{R?k{4$sXhmvb zyv7x%Qb)+0m?tXTU2aqB&XdzhYLDr6l|?4&Gh?R17rgz`$w}jq!r$oVKC1V!S=05@ zez;UJY-0ed1q$Ou9fwTZQfMKL8w|N74A6E_7Y68Yxav9?Y+2GZ@LCucSrt6nvdNl! zZ>dPb+qH)*(O-cFLK8bT+h}(sOFeOnUdgnGNGx|!o)~F&A zF)6~iBe?v9a$PEVG0=c{W_dbTR`@uF8{FS!93J=qWG!Nizd=3JQalekUY=!3;s65) z*oG0vZgZWsqy@j8Pi!sJh1uXw*RJdgVaqbS0n)V%i6!Z}Sj-8NH>9AeO*12+16~qD z9Gb(3+=AvdC$7#@3h?aF63O%$XaKM322%jx>twf1oyGz6J5|m$H1qv{{o+aRqQr*1 zfD5T^)A#o8*Brtx$ze8t@Y{xXEAsTj8G>QRSc-b|qZr6_ zF4aNXviZhu2&O^66fhO}D;-U=tS-Zx{E`J%DmY^Z59bX9%;1Z~r+A$@y?n<0mVihM z#y3mjx=D4B9O9cHLbB|QB^c=>kyq~tG`)5jzL7fU+BVh*rIiatTTA3#zCJ* zZ)sTSX+NCs$PtvVmvgPXo1Mo z=gV1=@YyK;UFh)x?!$zC{`fO~2#^;s!oP*G{QeYIR2em|Xm6YQ9$&cc>(m2H@vxpu zP3ZAdQmW^#J(99j&nW?^sR1{6@D(>|Ydzx|Kyqd(0=zW)>snVFf>AYW6SKcOc_jR~!H!~1a;l5}QRL0%p7!r> zj+;1v6B+K2n{a_6M~b>Wwr=!q&$7{s3|VeQWv!UeFS1n#d1oJe_MFeBLA=v$LtzPi#JB7$kQ}WkDPLPEV3_PWba0{NM zK$iAIhh0*hOf(i?TYUk*f|nvd_-s*T^B`Q^o~sSrHc+!z#`&(nX#x+R(-F%hWJ2!} zSPBteK5&H42N&M_-IbG><12gnFCli|eDpf}&s>|uO@GZ&kb&9^W5L=D72=s%i6>JL zV;Bd?0FnO_P?a^1Y{Vr&A{39rPR0bN(3h4JdgMcNgkg8Co}^suZO~QLVD$K7>zC0u zYW>}Uta4FpdX-3d1Z=j6-6H7UlbF?H<%goIE^F^g-Rl{XAA$niLADa1n3zNe-BU;0 z5kdEh526<;qSIQo)9)w7m*eBF9`;Y`0AY$HyVG3mia`sk^-?~RUAUl8r-BZ;l0EJQ zii_YfE(^B=1XBu_nJaTJX zZR>e#IUJ}&vrt8HAZ(7w*8?t`f%(1+@MSJMSPsKY&~~;Q<;SBX5WTI@lBvmD!bvBd9<8LIXJ7n6v*u;be1v3OaZ3D)!K8~ypGwzuSJiz za%R{IOntL4WaMlcxPR4!x=x6^3uB;eCnuG2=F+R*CD#Z0`#qr0B_YUwM*0t#st3^VVprCLT zrCwlZE?@dSY))YG<`KpDa>vQwG3mW$*_P-JuWxZbzZe@A!~Ie~TJYx+P@||MtkJ2^ zSf#Hm}Q*y-M6H4X3NnX1T~Yyic}Mlm1W}DyD?2rXzWQRQCx69zf6!DL(iEed zI$TnYlL(&HoXpNuSQ&Lvp*ry`%JfaoJlFyYJ=IW*DIt~9C)2~t{DqQW=RWoznZZ@H zvA?eb(0u7nc*FlyUtQ>d#CtaA(93cq1S0XWLdzc5F?n=(PCPqG@s%z`oKvYavoPC6 z%nzR~^Inl(KUM4#AvSX+DfO&>&mG(TCo<6}3=lM)cc86zWG*JyDdf$vRT(d6yx{;R$eDOqxq_aj;P`WxfOR zB%m@O&p>gUlt#indax$y8~^4O-LWCrF&`2kOHu`^CH%76FNJ`r#-7r$At)?!-PyK)#PZCWFOt1A z>CM<`jr-&JlrS`_bvOu34qREE!ubjRw#?pyzC%dsGuOo-Lto?A>`Xpaiy04lO-dGy zk>z6u8Ei{F?fCJ=TO<`Msn7CSmSCq~gL3HREBnJ`5tXY?TPU%hPljY&IK;szBVJcS zOGqltQBX0`tNA{kO>A(?8$)%U@jqj4|C0*t^`g3Bo z#w<9G;rZ9c$Cfmd=OcooRIpgbiZ`NFh9Xs|B2^3mB6~tY_5#*y-EbLgN*HkAfdoMZ zz6X_mD`dsCBLm3Mcu}3TTONAp_+2l9 z&L*M^$kdn%mG9AO)6zw}CZs#z!eO%Q+>9R2+sUWD_kXfDwYz|W{8S-RUT`I!6cYdO zgGi<7x1h(GjB2ZGoAwaO^I;7&ZXpfiTxw>u;dph*a5clY=-$&24xyr_ZKh(kWMdq< zecMASsm9TA*~k={%-yHTc_~1bMBW>R*tBJ=@?v&|O{ zl(L`16TLp`qkvgbAx+|)#Vy&Mv-)GS$%8*o#=Kd#a&#OVJ7ud3Ht5A+2 zNPW2ZAjuZ2yOADedhD;d23IA=M|%SGL#r>|M_m~~O|%K#CVpfKro+6b3ZP(I z#*Lc#mP3rPRm@-`*%N{ui_!eKie3*i5H%27E`#l|_{x^cGAPzGHQGw0iPqS9E77oO zQ<{18{m5cuvqoc0M~GQBi$5t6&!yx}{i42vk|4A*GDYHcV{s-u0Mtjt&=TuH*|VK~ zVBn0+kZL2A#&wavE;EFApulA%6v!&-4G`kKo&M&14}> zcgC}fpLLqohF*=YRFnF-1yqwkc@TRuU6itBgip|7d-t=kWFRoTL2|eOivCUsi#xEv zF8&mMTZ#y1woh& z_`ODxUb!m4;^#;>KS$gsR zL~se@Stwj!J^cj+%r!uEp0k;qd0=k!<=mZ=yM-E^Td|?O+HWf`7GzU3vhbYvwC!%f z<#A(%{WcRIYU^C{zIxN6oAS4F5w(V5cxWAFiB@c73a)x46qGJP6DQ5(+QxGfJZIv) zwoWr#d<~#_<^Ut~GXLP2XPP$6`jX|`> z`ip6?`u-_dA1L(nYzCd+UxICn?|0bo)?UJpXs`>Z}op(2tJjIPL%j}K2y4>ub=Gs{~*+P*? z?-)W_30(P7O9B1?l$QaQCUOKapWt8vaH?>zq<{fpj+T>%S$>F)FCzNB8bJv>pYJ9H zXNl&iG_pi%?e4L6(Bj{p2B}MB@%+uJ>^@XdWvT!2)U?QEP9~9MW;tN?l%K&uwN6oimv5H7dNttn_ zbQ_u;|IsB!{z97smLjEgoYk6vW^Jth%gCGEW>Yj<4|%PLekrNzgN5tNJX`m zhr=v+oKz2bZ*@w>r4kL*gPKV=)e%qS7;M=0rNLi)Jaz-A9k?nMs%R%(+Qcqzh%h3|LIUX;Hcwl=8&+tu~RIOtDMjs+!zRp=ehOgXPXdjAp^wa-yek` z!^u+Ff7Y-DQ{Zb6+-gD|nfD>~CMD&NB_ER+l87W!WjKoiS8iwcH`yOU2j6#4XW9c4 z8qV#O{+7)m#C#0O5+o;?aPr_k22_6e^0*5fEK)A5uEzY)qk$t$AsDsa0_X5sXtDns z#A_pce)J>s`?6f>xx4p^rbBG}$+n#Pep`(>J#or?$1@2`UpC^&4Od_9;7WX}-cy-r+#)B$`%lSOjNFp7Ljq-yv>oqf#Lk^m)H?_*cGLi(!Y_LZ_51I_^E+Yw>Jmh8 z>Nb)1pBdh+E|@Sq+V5YZD||7Gg`Fbs(}I2W(NAo4N^$js1e=-M+F~8d{GNPQciz$W z?`ewCP>_r$lGdhop-NszDbs`|52d~qTn!jWST@IuFk6>jucy`;!>A3oaEx2k1*kHP zbXc=6g^U_yPEB_?UzPS7)o|C z!96it;aX|fha=6|b2WP?`YHB1M%LP|Um3u)xqb-US|S$5{&T`n^yxQxtNR!E(-0xB z##fm*V5oS}@r?W*6_>V9f#i*Xm`Eqlhm9Y2rp7ZY5&-f*KyCLP&}V89!Hwzx?T2~Q zI|sY-8!!jxGS!VZh^>UBP+cw&JzVV}{gXn$Sbc^NB6JSGMvwg7IXm}BK8;OtJU%NX z{6+UR*F?X6(y9faZBVk5C+R@)%5X@K3MQus)uhY~qN;ee2pbShBL>Pcs!x9nsN|ox z=&5NFx%56G)dh=>NZMAjZspQmwY2D{6@KGYf_SqdohE}bgzpeb=bW}nic;wAchll1 zx<2!z70V^wskUx3{)ja|xf(X)ongG&W)-?9%jF)Amr<#9Ry<$hkznv2{HqE2&TP5Q z>AN4CcCd>r;Dd&4I|PaM5K9C1Xe??Us$xh^C3O4l4$frk_^aPq%+O6%VV; zHDk=G`eKmfGbg~@e>C)n+O=H$3HBamF52|PU3CWkbrX+`U=WYP#+c^PXptcVAW2(N zc-{cauJHnyQwWB+x{(d#!!Ru)v~FX?eUil{>bax*Cwb!=Qh?ZH9215y^qk77E>!Oo za8^kTO2|nHNrc+eM*WeKk(%-Sjl8h4EBLaVC%K0*8<_0<>JyO%T;bsKbtB3~-Z>tR z`tO1cOC*;iV|xlf+3^YZ*@6p2O_FFY_{7pfF}&_8?-y7_@BG}H!_6?wNi_V)fPDes z>-(b77B3+mZA1yPI*!fFmU=>&xPcyF2K}^Znt9(hZuMFj7%=J0iRHjEWBv3ibnn58xSS?|#~qet0x6p+Dn$Foa$pYj)F5L!=6{K5h3@0fCs{euCod z4mSf4fq0{Bp)xd;ZnFsKfD(XN!IWg{W$9sWw~i92d|tM-)Gez&0qteNslq!Wm_x3Svk2+&~ZgLr$#z*$~B4mpU=6R1c zdMhgovunxV)bfDvp*|p;^m;8-o%dofvs?m#PPaw}*$ahewAEBB2s|mA7*Vy?8uTxd z#ktG(2oq)c>nttij*QA2iIdUfV9jCKz`x}(;@tOIZ%aF#RJ-dW-%G+Hv{;+1H@I#{ z)03$#4iYvStBZ8i7@Gp2kA^D9&^zAon76cvz(k>8;X>KAccc7rvv)^%6>oy&Z2dixz<_9X|C0IIp`!8PT(TUqn;AhL+SCI zi1LMc70uqqeM{*utL0S}sf3W$$6O&Th3Va=E$_9nw!fP+a6Zg&k0REs1Av_jAyzPC z>(cR0k@#S(mlc=ug*sRVoHDA1K%A$XBs!XGw-z#VW?I~%GgW7dJY?lMXyZ|ns?Pbq z@DsDlOUi`nR2y}rCpj$aR}PS_iBu#)ObafgfC549CvfFa(RI)FcUePrPhK7Cylv)J z)M8__NH>34g@4W=^)7^kRP%khw5%(P@4%)>94LAHMCD>sFi++m-8)lnH*fmq({Eue zK#;r!eRr4s;LOz@+SrBE-$5B1OyUg&Em;VKDPhbRdcI-2IeOMHrqDTl*s6dgpVAnC z=GP2v;vU1<3oWiUfn{-ADsAdg?6B;sw+o8d%+MQ(sn z!96ep`MKEDRI!Jkd<27Z0(iQkx3fvv`!_SymP=5 z>Cy)b-PJ`Ob)bK=V~44gVLTIcWlXaXpNTi+Xv3q2WbKb-B6Tn%gzW?&`MypzG}MHq zP$4C9SU%CDU9*w@)Qi6#nQH%%0wPbMxcbaF@w0m zC%9E4rlmFSRSv3Es7PW+K;rQiMbrdx`(gxxN|=!F%a<+sIQNsc;sV@X!0Q++c;KmF zheBG{Tz_1?=BtDm5IBfZ*HWsn|;AvfdYNRFP!98hw4F zf;@ae_eU)7I3gVo<6*WSR#$L}%sKm>0{9B**?2x{Ua9c;LzrH2HXm+ba@uN?C;zC< z!2oLgVU43=n67&V?K+VSwYt*mgis+uiW=BhSp(|sVUE5SXeX6*&Ny}my__>oX|3Mi z#+V)h^v%55TXaAXeav1&7Zt#at_F#SMw5mpkh!z(CJnZEI+Ok=1GM1(|NDcQ_fiH2 zr7M2jVOTvi!JXNc_aXbOl<^1})wO)CN%6o#n6#KG-Q%$le_N7J!|H@`gCWi;@^?QS zMR7;It4A#^|Ldh+@1%4if}hvOFyoXXytvwuP^R!da?hBe#ZT3|ois6M-+nq01kONhPfuzLfA|=41q^ZX1zpVX!`3_ExXQ>mj95ubzt=8O# z;7Shb5|4dCxSp2Fw)n|BA_~E-aUxS|{)BK7uV)u| zb}6=rT8sU?F-AAq@i1j&P^qs2=L1;Yhw|TX#sciyGwyar{pbplmoX0HMIP+7T<^>f zUKEF%3%`k^zMxyrZITBw?|U?W)Lt)c(n(pImy`6c&n{Pb)Zmi7UY=8?$YOJ(b;w@m zd}_{9BSK4S7EK=9U|e};*nLMI=tsg*X=1xIAY;&NWdo)SF_<{470VA#!?VY!d3Efo z<#JTf$3Jkh!^~3BXh9mV zL<-Ql5g-Q+vx^Hf_6n6aoceKSue*ul+@#)hEsUG5^gnHpqTp?v?Wn0|_%pKa*FPw6 z(gB10d7WuYd8p0CPh9;frk+7OJVuzARxnx|TAPXBq$2fJw>#@p&%lMr!}k~o%gk?) zGzln;TsrL{xjO9TSY`UOaKv|{&tj=b5ffb0Fz-QjDy&>4{r_L-cK6i44tGQiVkiS5 z7P}dc1&Hp1NP1_dPvwmt5nc}*oF@mlXLS7=gyFxp9g15E<7#4pW;D(DmBt0kIhK1E z%vCzjh;C+NFsp~<6%%2*rkAzYRN85pT{vKa*b#nmXWlC|49q^rcBK(t6Xoj>QI*S8 z-5+l*q>-uhhhcHoD?EY?THkQux~sc3psfwg($)6RPaTB9s!JNL}_J5RoL zFP5Zfu2`enin3WHDRp_AT*U?AS=niIkD@adPR(Z+{gq-o#5W}QqW#?m(a-SuuH%S- zlLM$wovhR5Z!T8*ck1Rg|Hi&C%DAlDBj4DxEvmsZ`M&I?15Ec{=m1_hNS4)Uki0s0 zNs;JXCyOnCfEBA5lK>S9J3eiAOf5K};KOU#9}|YU$cWXNDhl1_-6_G-g6fZONIMsw zONCtyTT(!Uj3eoP!EX<1XtNSkPPpx`Lfc5kkGdLoLIFSd##`v9MdR^Ch1XDJiW_R?JC|IT~AX@wRFlr;e^=y z;UPsbXr{hII9=^da1l~Lq$~qs`~L4k>SAQI@7=nfPOXo+Cu~@?Yo~19x)uMk$iPvA zAVps{5VbEa0`q3vyV!jR4lVOmGxz!w=0G#L;QRX8C1mdFi%lrJk$n%g)F>E2DDQ*p z{FLH~#x$@0Pc`+J!GCW)tGJM#x}Hz&GM(2Q;hE%T;Oyl^+I{#x4jAx=+7L~Tr4x8V zMAyi$hY*xBdudTfYH7lSYuz;}dvTLODlOpi^1j=>Jk;>gVerou=_xzf&p!X(=3V%a z{Q0T;H*as2^Uxl?x9XYq?;{^lbBsO4z#eak>GSUYx}|_-ck;7gxi01>H+yqV=NY$a z4V=5PtfTXl;48Z}3+FF>2KK9u{u7t}d)k0H6%&obX){}0P3eDNC&rijtnu{xit{R| zxp_vSc7UYs>Y+a0twZ{6MBC$F!S3EusOA2LCgthQ9ir2wmjP-eBc#{IX)T- zj{mbfG-6=$JK|2Km3FznzraSyTAh!aU&&6MB5Tp_829EcW(oK4Kz=MNcWLln;;!9! z(9CTtSfUigj+^ZIG>BHTpk^=f^KUN3fT z-{(8Zkic_^gg}hf*~|U1?2j;2+C@Ne;?C2oXR=e7>_NcVB;?q2(kC;^~w zEI|T(mzL&-IJZ_So5r~Smt{l!y^Q>u$-_l`AfsI3=zYUgLOKa57(O2G_IpAaeANe< zBbDtNq<0##7;*a`5$H4tT) z^&`jK5i|~m(w|v0<31U8Ui2M5}6f;tr{J@e!nL5K%JZ~byL{QIt>up+$YSKnx!tcb*ujf|x z9&Gde&l&a>1>Vp{RN}uz!hfr6{QO6?x**A*r5?v@urCWBGO%)vyCmOGkajwgN>#88 zQceJjD`gk&q*W)0)s9Q+Lw2{#Qu4{7)o{d@A;rtBKpg^vE6YQw#*nrEA|2CKWkQiU zlX}imujMby12{`PWCo-iDG&Z*sJytG=^V!y2kT!}Wz3I9ba^av zH=E*&baQ(et>E3S{@3P=I9b}djplL6ZcPq?WQN^pjWAR0YY#r}HI?%>HE;kN7+UrN zLms>OW1{#qJC6)|De0^PT+RSe>xf$+%Ee4GsWbGzuLqDTvUqDEODW-c6%niWa zhBdLNys4an*Y{7>bk(j#clZFh+0@u&l|NUxTz=fxxvm?ZMU}3(|Fh&W_mQ+ec^9&0 z9AzB7THHHdp6p5fcU&8v-L@;W?jaR=SL^XuZiW^5U`eR8x7J?*>V|V(w%6+b3Kaz! zCeoH!mK9us?Iu^&u5Z6gq>B4G3*7jJFInAY(}lUe3&b>`IpIGcS54o7wEYBlswU- zEw@B^QXRd>`do&G++cr*Y z+qO@fG`8*J#A%#{jcuoKW4m$VH+_Ep_k4hJ?dzUBv)7tgGm~bV3*YPFAsXWH8=boC zun}G{%Xuwup%=C${%&XMgrt_dX*{&llHrGGH-9=pzpRt}-AKIgIdSx!2@f{`F6(HN z)H{p-LEPsPXBpjX-qOIZdg7n`-8RJSf=h0|&~5>BW@*9jA*LJX0CNzwP>kb~C!#@K zVS%yA{qB*n&;7qpb9@HzuL-qO$aEA&Q%tN*az|I7HlhE5wT&AqVR-LAymL=8S#6Go zaF7)c)8v?}Ck}moFZdF&qy&{B3{yR+`7adA#{8=Yki8OVH|clye!1~vG9|XgkIZo^ zEplMZ#wzk)qO;oFP{&Xjyk+&`0educp@&;VZ6kqDc*Y9k+mpYU(s`jQjUz>g6z;6ev?(l9F9dy&*8 z3^g-+vL(-wI?0jF#F19#T&wR?yJ=gqzBlK!QuS1#vV7dk8K~R()smJKFK-k(53Ww+)xlIj{w%l@QISbY(ar_C);YK z;1I1-_Q?)#VIr%{lU+fhQC`6<*E%U_3D3H&8(K>TYmpje)cA+eIg}3UzrPk~{a2i? z;dxn_-0$CLeUKVi%LTtat5_=Vhu7sQGGRPTFQ$S$xc%dS6!BE62{=&zlxcR>)QpAY7ej`%Bvf6#b zmbvTl)E;+S zZx92x0mm$?|GJ6)tq_Nk*aF|L@%G2SuWC3OW>5M<4yFwtp921vmJY?f< z)@68j{{|Kuc(Dc+uv;@0;ji#g!^^hgNCR&vh&0$39N&m|c@UD6$XxSJRK zr|o0Sn<|8lb&(&tMGo!8>bGHYeoJfq$R$GSXUOKWKi@Dn8Kqp{@|k=0bi7y)pU_>* z7;581d|B84voeZg|p!T;w{ zy}eW{8VR(DnODI>j?(x2wno*kgV`w6up_6|)v;2i(hS5AL+JN0RJcb<9=a?;ycXGV zr@&=S_TOAHcPoWngvyx{tghMY4y9Pynf6;Fu%56BJ2J(!W zOY@R=G}@Q^L$^_%O)cL#TMsHXB0L;_qIbELmOH8&m+Hs7RW`mQr(DEtdO$F~DEFXi z=&7`$I%yVL8@FIlt(ucV#iQ?&Jv)i4k|<*0oX#KFw)Fyt3N0Zr~svlL;bNAWPUZ7nbz-hbImMDT)7YuxQYU*`sdJ^*I@M$1ZkcQ){U>4-4)#PN_YwIXOq z=+#t&%L#N(xud7X&ro7z%(pekEBl9T+Kb}{S$7mDjJ=*K-<2?33-Zj0I{)cN|aqd8z>(RJ)n%(rDNZ@lX` zj$81y1lsZ8vvV5J>P4eikg%qF&KY45TDcqkifiv)w^M#7g_1@;vcoNr8=N;KiI?c4 z*qMn4yV!-6KnswF8)+vr`XC;U$(`#Wmw=xQzsu1eC%FjeBF1{j+_M#IplRsJ|L z92RV8cGDR42N!p1Pl7!r@OK`<*o8tKP6BE(XMwL$k~`Zx=UI_?DY5I+IW6+6bp^IM zyc-TD2s8UxhPN13=0nsP*9PT(9n@YQX}^x7_TI`Wx1jkc!7`}&O&s|ymba}h@Gwd1 zD}M-2o2##WJT}<>OL=^zM588-*Lv=#F-9OR-ltRwk&X@1fZ2n0MH1(tcE# zWjKLx6&8I3HY6+oE3F2`O()8qwkf5xzUR;&EHv(O}|X278_ICsY5gC!BR zqmBaL2B-0@XI$ty_))r(TY4CJ@Fps^>X^~0r*G)M(xdI*lY4q+9Cdw3=D#VhPt(SS zd4lfZg1|(%D~rHJ?#zg>9Flkzl9S(d5zSAvFBS*i?kHXcdopcn^@NT^&|+G^@8M(G zh`r=ZK7|~k1A!>&N~20%F9f%~ThELt)$AKYkIwrnT_CLRVIAIJUG@`LR_Yh@@6|hJEbzZCU#2HSOCSz2}7MHnyj^&v~*?8GexA^)m zczhB;S}^h;bz@@Z;Yc|wbDgBUpmoExs~G67ZNdNJ^sJz8VoJ6?j2q)-y z(+VC!fdS8n8y+)%ehVzvb?xR={w<;TcAFN6LCK;3y9o+CR}LrA49`~!uA>Wr zjNY2i*-Ud2JX1Aruv2JyqXvo=`3t#Y_+PT)YJZE5^<(-+N&ez~Dz%<*A9b~sbZVCk z3h&Iy8xqQgUDP>)HWf;C=k8)VYNb>}aW>$}&c4;GhTyRa+A_Cm<$2Hx+cIt(J$rP> zT{9nIpXC))yVB{Kbat#Hw!-kbxwuo!my`GlFeLya1!^Tp?Qm+L$(ND2yArJ=y4f#J zlSW`o^?BA{wdC83hi%~FbzFK0I|LdmSeD%OyaE^y2m4VN;D&Bss^f;!dCq0j8^Nbz zhYnz$&t<|pzYq7HC^B2}WlT1uPPx@-pKGKYsx=CM9QB+BHfPJoQ5mg@)|n_*8YSm1 zuJ4Tb1Pi2`)GAydIcq7O!;Vu^W8WK~(aIq=+r8bcJUtgU6c#vO5W&FMW^M(TF-4t4Fsxie zBp@*{MR8l%l)(P|=xzmO?#3?TorOx>ba49On2qq?@S)kUgpBQ2m+kkJ;hAP&}GS1q68mB=3WSEalr zz6phW(bN70$LPUK-V4J5#-H~EJ=mi?OsLA={>M9mz0q@FGdOUEB##V85&aFO(CN*l zoZ7*?Fz$u>v_|V}3cE_d$|zGF8&BzwZsdwqk_{1>ZU61$M?U;>o{f(KHKoExTf4YA z!588hcQ_x^NLMHIpM}Gy?k(2!;(J6K^mC?x%cf1P));nq!E~iwOk#xuN*G?ovHWGD zECUvt)4IDQn8^-F)(IHYxo$%mO1~dOT<}U7Q;4O{}RcBeR=ce5vx~sweZjl|KPCM5TyE+2r&I zsKyXDUnRGlU?9MjAuy$bu~j=Us30Mq4{(%?^}}4`zQyr;aPLZoLtU6@Taq6^FyYFRbTYqn^K1C<`FSS+iHH@BlGCC3e&J#h^8wxV8 z`NpN=)T6_#G@oV$WJ*#TTrdG_NzD`Wg$*aPc-dy>F5_KfoYi1eF&-A=%wS|H2y*3( za^ZG42xJzX_Y@ufB)Q@#-pa0A2If}r2S#;+9)@-Iu&xKB@EYP4 zYs4@6SVJ2+@IuO51H#F~_Hjw2!aB;@Y{KaQOU81!Kl)Yl2wFy5sB>K;+Myl2-5%fC zI={%s)R(ZSKeGWo+*8jTs_hd;N08{KQ{>Cl78{Qqr;RpRGk*p=1>NfAk4QEol#vB; zh0Z=mugM*6qw;wNGvycNWYA8PHhH}4G-9!U#eO0G6M{Or{YN`mmDg}=&LUJ)On!pZ zBAS+7e%)ja$xSiSZ73N3P@rKu3fCwW+LR#^A0g!~LZ*Z4Zk^nMaqebVd!Uj>f>uR{ zvNB?jLoS1p!2q9X^x2AW^pLFKr%bi$=q6f`BZ;M;3l%!6;36JG z*w-}V**Io)QMw@8b)lMeFW|(fXUzMyV#>Dex8HKoi>UFTQG6K_PH1IOQ(mG#J?Jh| z5erQmag;;@FBwK$DX4N5?BmLGB3T=2?mko>yW;E+R#sQqB;DvRu<<~!Rgb0Lu;^oOFs&tDmQ3FJ(y7#TX z6~s?F{EG!fiM<*~385bknARMC9@ODj7K>ONx5+i*VbqvuZMWfe{3U_<^O&J8)z79= z*m6Och&xpMLj$PE$Vv0vG&V}H)#OW{tWmqDT}Txyw3HEZB`($;83yLFeu$GMk}7pm z_pI|Niu8m?NTo@mp{(u%*6f%x8?>H_%la)^VIve8`cq;QFsaJ*D=wKFgCGik0* z32t$#S#!RvxbEgZjphl0b8EaUr*32*@K575<)?F%N}nba-LT}NcSfQCe2V6Y7Y!@i zB|^aQ9t&5&YRbGELXmJcBj=dJ;gUgy(XzN+yl@y^MT6kzzqtn7Ihl0HrtqkNdIQOX zF5_Vx$I}*GQCH8>L{D;X!FPtCvUUR&bz}!lMTlENc!1k7+7WwBO_+VM4=J-Y8 z-xVlV?Sf%3sivBJ`wq|Rx2xUXbsoQ9B01T^peaW_tRO%j22!EWlm7N=^Wp=rp%!wZ z(GtckT_vP-kwP&J*2mLKL{&y+9-=k+iu<2YGg@D%m}ZGHD51yDi~DC(+(zlRSD)lq z7o(Et2~iYkb?c5EZ;c5}?i_I!Z{v5FOiVaIWNQrkJ5}#8^`~9xX1wrijoI(HL_SJo zr_kH;6}0N?_NZs_%h9clmErs|a=ncn;UL%(_#5 z)^G@+yvY0Tk!sL7Q;T%Nv0X7}6U)(qFEdHS;^fkK%;GTg2pXi4$yE*7ZZCgxGG7xK zjfn+}HIkg%qP%6ZgdD+*`L7fZ>HsQps2Vz6RfpR`(G-f-9VKWWeiChlzGVFclc^4Ccrhrj>|F2R4Ht^lVD>Q-ad=g&1>k>9fn5atY8%L-+8si zZ6r>D#apSBS^@g{X`$E=%2+YcFzS%S!^rML*3ObCf`&T98ga{XK%64A=-QeM6Q7DX zsnr>Pay;y1_D(q7Nji^RSW0`fNmRVF%g*#qH?6L=_3mVXfUfeOXTSPtKJ`tUTI&Rk z(>P6};qQ`Y8hg}}O@LX-vnPc0QhuZ=-f4XA%chkW&6jztz9#x$q`~>`V!$VuQfk_% zvZj4GaEk-he}2*n^U51E67FRm4ky>S8Pn~L*!c||=Glo^b0@gq4k4OMr+ z8Q9$EReBm#uhyXl+c$lF$|2{Lr-=13e{S^+tvEg=+?MMyi>RjhO9nZ_?44wt4n_i`CViI~pwhFi;?r_>Qa*QsO@gN?vJQQ=jJSqyLM%}h< zr>B;;HSqE{0dC#>@0h{5U^YrLgwaLpEbI^taSmoS$Fv*3ph(Nqr`lS6T6Qoj>GVE%ST`z#YA1X7(C!Z;y2L;=>; zxl9`f=<^d6b7B{XV>yrG*zK2XL@@`&SI8eSGdC%zmLtb_i})1Pqr}~*6w^?v{BVkC zFpK1+WPHtr)BudcPq+LBN8|;jtq$B@TSk97!q-3l?@VkEnJ9M_JeMV^D+FCNOBKc0 zN9rk3%dW?};Cy)sQciP0^i5X?7ku5TN%fmpt!rrA^ZPyOR}IR0JVuV(dQDD;QHz6O z6G^^@#FytM9p6v8%g)=Xtp%NCQ_GA3R8{?B>6OG+Mb*WN*$_B`D(*j9tPS~!WLo*F zEs)nzt+_?YA+98f{K-t2$YfFHu#-N>$UbDme<--fy?yT3t|x)`c^XQhBvaP9A5_P& zWz@r=tcl6sgurQ!taT?zCp<_Sfv#ajEnhxAY00e1WZ0-P)@0Oi)%G-)h6Vq*#l-;; z)YS*1$eos0h~ueTMGMZirw`EN{V!?>!v$gcDt97tzRaD6b8j9a_e#T14X_f1@CKKL zXvd9&lf1)>q~Ew<+~FL<&Ze}Bd6DL>s)mO80;6Z2zdD|Pyes^^AqhVrbR7HHlorMn(*92s<5@6Qvk{^p&NcUlN< zQGc4_Rp??^_rC|O_X?JU^!QP{`{U6*ep3h^OJz--6H{GHMC^{Zy(Jpm&VVJ%bs6eq!Jud7k;dy#aVfHE1+aF-Fx;wAW- zGWH+O>RqR1yNsk20#Io?6-e`NqH8Roie5GmRP>!}QdMwu2gkD^?5OvV;&l>58DuJH z(t|PL2^xO`#P>f?k^-p7J|xB8tx%tc#rJ!b-rkqVZhE3eKbXiqG9q84P@iV_E=IM* z8N>$_#T{R8J_JmYkItA#wSBXe;kuL$n zNGctPz0rwXH#ut?%O%!EgysH)kpS;bxm1qeVG?FWyhw^nC0#m|6fLh6a4JO5EY%4f z&r3d))^R?)ahLl0cFA{_p79|=17gfDeAFlcw>wU`GeHB15+@;FSs{Ow-B+f|dCHb@ zp=D(~2pPCz_WOz4&@Y=gfHQCgZu=Je@2++?N8HiXtK-E7wo~h(YV{3qj7T1e5WICp zky<rkE76Sx-i$o{;fVmDfuW|XY#)C^tJwg7%o~%RB+{(;C%FKME=#E)Jy0M>9qMey! z^UbrLP2AJZ{Y!Q51!?b6*7`u+;`sj_oPSJ`Spk?cVTOL!f(Htl=T2Rkk5g^e7da}J z{Z7E=lYyjP?vKr}QO?DeP}3vSxrEj+kI|xk)uVm!Q+bDDW_=3dJZH3#$lIDXv*w$p zuaZ)@j8(hKy0?T|b|kYt{ea^pWnqtVML`in`D zJ|Y9H2IWpaL-f6Y^%7QZVA6RJEJLD*Bk8zJI+X;C5Z$n2*NRlS2tD|Y9?Sx<@1{k0 zAm4eYgXdt@yn_6^6mr_omrp1_tr&(5`_Wkk=ycXJ$ z1mVZ)*AD=>DKWVa5qZb05^OHiG}wscr36MbIN(Q0K^bUh+ zp2eT&7Q4X}7C(5KoFMqdO~i^}OVN=QpyxU(6Hl~fo$N&}`omTFhqH)N zxHPqC39)IZfy?|MkBxh76NO?nJ~gIzfC+&2dyc|%qFxiYJY>&n;t`u+0;$Re@5`6?F5mjliO!1!kzgHg7PBHB={DIYl)MV)cT4IG0mv1(8d z-5d^(hfa;V`9M8juW`Gvu7%9F=rcx`dzF%%cL{f#E+!{XKL5}e@Xw9O+ zTZSHtHJ!t3)S%yEBi3ktf)1^FDsE?Blf!>;TViGi94c@`tK@C0`J;0n%=Z<$7yJ)+ z{}(WV9cMtSnrd#!P7&C$g0o)Si{@yvL=bp>2WX8jF5mjGPcHxg!h{1Y1)3!%c1TTI z5P8ZXelvYmKv0*dbn3Y&B?=(?{AFF`?W(C?kC-E@aQ91SD3}8E+&3t}qw5_3NhafS zwz4`?A#i%!mA2Xx|5{Nu!fXU<$G}Yp%x_kKa2XI&YRaK4`y_q*(kq-)p~!ql3S_O` ziF$%0hOwA4k}*<6L;hqc5z@bC&@`gO!^q~|tjF$Y#ebFN6nD5%m zIFn&T`EBd{o`&m74>PRBWzGLX>^bP4k@iy-;!bbgc)NV?!d(har;J^C5A4ciN}K-) z#`hE&F9Zr{J?W^*-n_-%_R^@O_KgBx1ES7HTk5#3QHEw?-`=BV;h%>=S>{EaA zW}tD!XtB&G@j~f6q4PGZ-ql{5TnXWVyVLR`{L>F@{r;q&G!Zj9%vwhs3VK-}98suL z|jO_ zfq2f4!9mt}?`}BK+leHi!9-}KJPcCFXw>p9x^ZrrZT2x|NNs1q5ky|6;G0TS)m-5q zL4>X(oM_bDD(A+ia`0%c!J#$g)P+w*;yEA1)_XmeHSbzQ5=qvo6nK#UPYzvEW&DtN>q{4k4BS2g z1Z-ktOk%{H`H;lD5La#>FB|6Zg8Y-<=2Uw2R`H^C&L`?Lwn9VsmDz)3-r~6O{ASVd zXZilyYP+_LQO=i~>>jS29(p6?pwJooz$)k$9k6P)e6E#J28jC}?2LmG8v&Dt*6`ud?MZaEahOVxe=!`&OoI^QO{u z3L*2v3`nf!l*eXxUM3O^M)_rrkU^mmqu#+;og~&wWC#ODB=`yUdmSx!(s>gs7$wy{ z#EYN6z1OA&B^3WszondFS+8zXOZSr53j((ZY9c@-w8fAiSF5HhXYS0_$BB8W^|O#; zlLzj9A^wtgQbKKTTb>Fl8o6%iZ(bOopN9x5WnsqSiRW zmgi!Z=UlbqFjAOcv^g{6vj;4v8nx3`3rKD+z{Em8(e%b=fKMaDDt+ zfA)3YjP(zKPwqR%JW|-Lu5`vsFoHq*i`)Zj_;hf)r(Q zj(rdfn2K+QfP4kR)dZ5R8AY*h{I(LqcVeRmjJAZu`_@thtYaU1n+9xcw&TD6Z?=NH2O zJ!>}4FX=yk=M)s6QItHoK4vHhr|RP;)zG838nL0)_vlmbyv#4(k7_L$mD0VWu0l?1 zh8pV_*uOH{C%?WKD-L)29=&x8P^z)cLiD$h;(u5WrRLj{;r46I5vclrCPRTA1RrtV zO+bM>=5vN`n;?xDAY{FicGe^2K4^0cr5|oHk8W%?39u(dyKotVrT(3G7!}jqMikgV z>V*?uj%q5TT1O?jM!@>nR|qHbKod(L6@1R{uxNeo4+N>%M`$vB zh`|q%>o{tmh{(sUyAqN7q_v?uXr@w;oTONxnP^26CA#86WEWhlCJC7+veJ=Mc~A;) zTqzBt<^>5uK0Jp5EJWdtCSK%iq+vyL5MiWk#Ia|h((vL%1rJVi6Oc1uvwFT+D0lAR zpUrS-j69y1qS|i%68jw#e`2O@%WFRN7MZIcKktB2LqIw8YG>z0IC@LCyYd=<`}9~A z(txIvedah6h3XRz=M|pxG_AV%>`l$xFGnot7HQ&#Xq|RuROMxiJAB4x+aI&m97?R2 zW`8ehMQ0RrjxgU^Zs!lxd=N({Iiq%?!S%g4T0%iJH73nW6>cJ3jCc=4eFU}C63lV4 z=7Cg#9HO6lpJY@h21hwVHDOeDPKiD#ew4W#LDS+P68}X7da(Xa-^*R<{A5!no3Mm$ zAqCZ(+Dn8?zQpwSpR2zF$@FAdwS{Xy*s&)HYR|o|j|JLTd9C>TRUcBM&ZsMVjxeO4 zpqE}T5@Z?-BqT^QfiyCsa6eum`adF33AA&n2x?t`pa6kgjE$cj&U0F>IW z9YqS)qPABY8JX%PHpPb=t;3@GK;HY z*3g&l0Ki!&4Ck{nlR)){m2G-Skl0}V%1Iw)ct!NC6m)@h%C6#}Rd<-*blv@J-QRne z{LRxlxeqK>5L4;sWa{XYSva{ycwR4n%rF3IXJrz43eq3p8HPjZh$IzKm2#dB(!l`* z-8C9^>>x~9bZmCej2#IdRU2VMoCm6ZmM}P-HKw*k;?gDS z^?^{(*1DZmw-x-ffsN)8?LSaw3Gofp`yH_Uv{!1B|4ep)A^SphP!I3``^v@a)QSm_ zKtk&8$G%|?s?q>n^XB=>Qilziw4Q8hOm)ELIH_^BCoiod*EWmSazWMp@@3TGWlmdV zO4prCub`4ckSrL3B0lTsp!U!CzU*!=|1HXnH)I&&7oq5)XsU!wPejeNSPi!AhVoG; zpYN}A&?Xw9rL)`|oG7z9K)IL%!o{mF0)Xp!&}J2?N2kv^#Os#ZB%X|kbecR`&P%cZ z+p6F8QoAeQDHB!RG_SX|P3-`m@GgUgYq+sLNSQTiyAfv+0t zqK%hg=~w9Xk|`HuN<0ktuDZf!@(Tth2HelTLNtAB)DFAc3fbi$H-^X^k31YGC3DET zKM2;Gb}iD|cJr(0qzpe+KnD#bR{5QE%6!Tt+^QwqDkOQ{bb6C1b%(gsLMgRaGD|V_ zI$xeK)DuJUk1+}()*MVrL`&jGx-fZko#D{PAWuR`d~oo<6e!ZkSTN)JSUM5=&c1Lw z?}j1Y_&JZjXZ&`Vgrp`+v;p4)b4R0sxcHrP3#m7Zm1~4TMIZfHnfzuB7NG9iV(oYO zG-Es(3YrOQVJ9|8xtXqyA%WnWpOS3XmBE%fwkOK#RFZO<@0-YewBq(vas(3UI0=K$ zgM*uhL^YV?EIeW;)7^%s)P`;v0AtGefBlh`eX%#VXI*e>tY%Y#pUEqP0&i&4A&Q5w z-H9sPMBmc+6EX3AS+j(#!>V+FxkFW?6vc~SLK_BKJ$q3|rGs(Dx~yVYO*;1j@EHyg znLM?#1?R&SJJ26{C33H*Xzx?iz2&lBDK13kH(5@Un}9cgo2EtPw-u@R$#Xz4AE~Dl z6m=`f4uz8n6o#Qg?v;Q?gTGF-4cxK4R%jK8wj*vq+nbhwVBo1ZAbBHvq_e3-Dry#p6vpO(i^d$xnIvP*RqXrKK{K4Ej}HWTZr_}+%q}b- zaDoVBx78pE0)QV@zyw&)g0Bu%Lj6<+c_!GT+IRGo-;3-3yY*yz8FJ-6PPCy2+oiY4 zZJrhFfgf2Y>bAT_=4=KO#LS7Y`(`B2Z=SO$LDO>9{2_8tGq!zyO&Wa7c5N4EC6 zm^8*R)~@ZffV<}YEUzWFVyeAPZu%?j^GZn^Ou2`e{KVtPn7=@fGRxubGnBZ=RrZta z86cw)YW52z-wCb>2hg@w6Y)*a zw{uaf6~Sr$SQ(@cWr<#squ&fUUZdQOJac}%0{f`%GJ&q;@4QL;y-ylR3_zhM?q;>u z1}yT78NEc8AYx@AEz=O+kgi@sTJ@m54DkHr%`@bF+Vt`YIg>_jn8WRF9nZ{oU4H-G zG?5ekb73*C=LD)_62?yjtSTy#FCl3CxV>)qM)?n@Nkd+GR)>D~d_kZePrZUeA56TOKfZX3Jl0FUA?q#%S1_FP9hg(;xqGq|rX z6Nz4fTtKMWh<*Ab!*8DwgH|H1i^?~)BI&<5uDzIgB`e!)lx&Y6?di`%j_paF0gj%> zrTt6&(r2lo_fd447?!`l=bhbW;{OK-_M7+yIr`EAU`RQA7;uL*@24Df?Lrbfa67f^ zW5rTwSMn(6zGbxe5VQz&m4=sb0M}7^lpX`=Ygs@?U4RoSl#H-B(y@Nr6^^kAZRRCD-|chh)Z zVJc}N>)klNaps2_rWv82+5MyVV`Ic>Le@`4c1qtnrV#pn*(~1ll9;1w$TJu z34HWF<)~IF@y^~C^0QTg5O>kIR+o(YD%mrLbqcF6huKt_6w?Tpo*wqIxXb4tV~$xUg5^8Me}G`%BrGd(R0H z($s;OYP_P|lktdnN2}_aNICNg-f}G@{&Y3?AUIhl&~)Ucvy|xe<4a<0W8B8I4C0|4 z#~?f;v7sM+y8TUoK9TpI9Qm)8*)*39AlRAHR1~}sDmOEX8oON2)Mk6ltQp*EsfpI( z_(dzY68}?jm2>!!)xekVu`v#74B}Ev+zaPfxuaP|}^f?OeDu8JR zruj)p#4Yw22luK?VXQWZ5j;*_PTILc=W;0SQ0YsR(y?sgk6&nlLK%%RGnl-n)_x2Z zk>dU{Tuhy(D##X-qhW(pk^IT#9^`l$n+z9xv8nRvZRA@FC#25YAJi#S$20--b(t~l zFE?R)gDD04e3Us3uHipk?4sXlrfmaZLd&jA4J`)0_V-#TQV41nMo`EnL@pU$Di5RR zSewBy?(DU0csl-IyML+_j%dKul*QduT%x!p-scnSQNo8@vEQxnNOb0d22t@Hj=?-L zQ&25PjzOpoyUes>RLCG|xWw>F4HY#S1!qJ-6iwpYdYUDv5_6xPEVo_2wR@?4obxxV z^yZv6h65+XVX^jDlLK8@jddk5cizLhhWD!5>0DB|*oGg$m2X+-tsf7c4kp(lUDv#D z#lOqmw>dDtt$Mxa_Y#&M9^TJ@3~lAPv$XA>G~G-5}i|-Q7n(>F!1WK|XYMcT02W?(XKj3g7kn>s{+`Js z|3qZ*v`kl2h*(}IwDo5X6;gdvJKL%z{JzdVz76y*SKYrz>xBO>B$|RMm3i@bXbq^5tE7S7n@H z+yUIopUt85(y6D70x3ysHMEE_5q`O+%;Yw;9}v^##VSttjWMg7I5$Im zH-Wvf#r30ZtD$y<^xd48_)o;$4iSVRsRB*80|PDh2R|lwB#Ey8rPRK`9y&iss8*b^ zhVjiiA4O&>Ou0L)rxlM{pTw&1SeBBkxR`KUG4Mxl>Euf;6G;-%V74EGUbqO|Ng9HF zP_{LRMDxFZnwbm2nwiXlGV&VjXY;8q^TXF#u1tPeNBDA<#fDS$-zhwLC)9@U`>BU- ziGi`(O=AE!3(|0rso3*g-X)|38UDwFl^@m&eGI25lRKN760&0D9xx>3mJ}(Qo2P=l zk=WcG5RpRF@SUSC{Q^7wZ>q2xAn2O!)*O$z30y8v7_7VbJb==$e|339X>3$+@RK(6sR zAXoHC8bgn-*|&=3v8fJ*u~h*IxRs2tUYKMSi9sr?rbKY-Mhi1^$l&W9&X&@@XH(Pm zxSiAps&8``>p4?*O5sDN;u&NkhLJ%5k!T+O4@hFmMFN4*rfvthB4X>7yM$ z^a(Qz``j56cX(W_W6Zaxk1__W(FeCbThgOKz*`hfi{=JnbwOJum;RP&HOF>(&!m-111IPY0g3yyqng|Yz!5-NULQAF%+ z-+<+Q@P(L;<(7J<<$I@1TvR+4YH&8AZqsrshw+Ch9d3D5Z+KNV9#3^$Tkd%su6Z4D zEL$nG%=lh6_x*+AG_DU#zMtziq3_)=UG@`cJTATw`UoeE?;U*3VMI#EiZ-PLgCNC@`R&<(QI?feYxRI?jh>vELJqsyZY zrGHOWT17i?f)q)nrd4_Z{`X%J$yy2eww?4Kh-}$LX56=aHlxhDG3g#$?Hj5n{alKU zOyqJ7A#(;USHI_!^f z8F^~g&s^^OrS9e7)o4<`u`_VDN7S={a_v|?8m@+K_iVGU=7LmfKSVzbvaQf3C zl1(MQhj_+!|%&DL!bTW8vWy}_jw*=jq5q6-u5*R`k4~I4x12I-_RU2 zx&!LCcQiXsfIu;|SUfR@r7b+b=T`f05f2$v!y1BQQ@itLi>1w}Q8}1m`0EEK5GnVh z?buJX^%glZLB_u+X~~O(w>KQkH~i<&QR6p?Erp(HN8eIY%SWcT#(Adx>w(3<3}Qv_ z-r%e4Ts=hhlEvdTvr-0l<2Ib44hy1306X4aJn*>@5#Z}84Z1<5dnmY!s>|;cTs+I1 zcS~RDWRAbR`N~-s^ed)=#6#mTBZ$qDl#evfymdG>#zXD7>B)Zy)}pAm6YCxp?ih*c z{YOlj^SP5L=F;{Q<5Og%=&9_m+`1{@Nj=skp&>*tuKnAIJred8MdIt*7lDJeOA_!p zzWr5vpig^Htf%j$H+YWLc*gacynDsGC3-5)BIoRQEERYxTaSP1x=xnx>=E(oIm|0X zRpk&|<6lPOU;e?r{Ipe@!T@5w2^I&fUCPWA&uPr<$gO!Tt+d5j9D$Pv-oA?Bl~ThF zc4Q`1i`nZRaoIl11aO)@rv%BAVycQiw|fjt-(#};FuC|-SF53|whUHlubFUhVlyL?IWTo|?AVXW{Jv@mP)=L0euE7{zE< zbR+9b{X4pmi}s+^E+GnU{BpaHT-EI`1nh_JB`JaA!<7x__rAC>JwaU`!rW}HX!~dJ zck3t9ac-+0pPik%A8r}ck2j+1IE*yKMnyYx8a*-X&GF}wBL|3Yu2AHzYOfo*mD zM|ZMC(w%_ypEvSyrCogJe5aUB4!tfFCran_zrX8uwAi7#{cJv{VL5~kYqYlGv{lu^ z1hx`sWe-zYP3E1r;tuOg2TA5h2dUL|V~fVK)pns9pWa?sN=@&%3@?a>nKutrYfZQyS`t^XY9RBUfXD4xb*GUuagzpK%^8aQI}_bZ>lupq%YIjn3f(O5 z>He9CZdTEL+~s^6Qy>vagvd1u-kxbqv0ILr=z8CMN*Hrn%ry(aJZ5|J?C3*RElkeF z;}Dolnr-N4k_FsDiF;@Wli;cnI&lndAh~=J$d>)W8F1c5!Xmj5Paq0@wEkJkuNm zYg2;umA#MwN>`Yez_yUt{H`=H*-bhi)=z zO-+H!!k|fbMVj2=NhfL&(2Un=64eNF(dQmZmhg5i+g>$0q9yoqOSidnVz`qO7?EDp zeIFyFbH^e=cZ5o20p-X~NCeCFR%6RS%@&?fKWuM#5X=rx_swzl%L-=MfS__D2@J9Am8d~gl>8)HmI)g*lYWy_U^Lzspy!e_G#7bkyHSoMg435-S`gO=HU)r zA6U)0g)jf{014FwoKBg6S&7`~Jwt`7Mo^@iz~l+>c+oS2TwZ#;&Cuc}Vg`>^Nt(Q&mB=i8GU1X11d+ zt62MBSuaiyoFU{TbzV1Z;o!kh*AQTsIRW>gEn#|gru{s75_T4@Y2L0`wokM<^mlGk zt%Xmz7t5;8x|d*#0De(@er>&`o&Y($apYy({wb;o?P*n`k)MCPKwnzWZb!3)28xSV zrnR@qxe&F2PD%UpCyn^e`ma1i(QTjJWq%_@L6jYG7*^&Q#TS5nSb@&-kq|NKp_H_qKh@l!~m#F&+@KOL~9 zt?g(9-=b|&p+i})&C44$W>ZFfWIn8$c!lXTD(k#l?qa{8O-4S1LB}Ywo~bJAjaG=b zmK+j?q8*3sDum7hbQco-F}GhPv$mIG{_@i5)N>6Bwskw-(L>2hZH3IV^sG1g$4vZ- zKipgcSO%^r8Fb3oV=kV{_R2QC%fiz)Qud`5e)%KJEZQ3=u8&$6`8pi#!@Pfoz;@jd zXj@8|4)SM+d8KKiC^=DriZ+#&mN@a>Yr+oYKI{YX@Y5M8d!KmUox~<#l>7D5ZGiaV z>**f4J+%YL?9e09#nwe-BGG=fnnK1j1p9yU5e;o8h(M!5rC596v5O+7dK&d}CKp1! zQT5EzLLZlZA7Z94_2Lt}ah-%I!;V|UiWp`M8LrZ{?!j|&$C*_EL;Sy)d+VppeivYo zIH&5vSrUi;jFjV1ee!rwd4R#Xq1=AesxHY(rfihx>{I<;r(TQowix3BZ&s?oP38PZ z-2Ny%=;XVg$BD$cxayj?^)MniuA2%v>6&=%n>Ho%pFgP`{%=GCsREie#iC@YMF<`l zvkJOk+vIe}V^cAj$=n9uphW+%LOy<;TWOqoHG|&AA=V{(hkMn>q{X){>r%uq{demf zQKIfDf5sx6B&qe9E7;I`OA*SlY(7nP6wy9-%<5UCK|x_DD4vvx1@uV&B)s8vk15OazoLW`%64Q zBFY}4$C4ygu!1~ z0TDj+<7tX6P@Wy+lR=ze8dY}BQ-qdAz>=mC_s}bQs`37NyJ(;Lpk4QRdG2pW!e(&pAlMhO z{)fP#Le1pE2BzW}3b|_bGuBh8oJdG3CB%vSX-`d3^$-p_7(c>9Yug~e1%yO1iQ(ua zx--i$AdAh^m1^4%0A26@N{TcoZB99IYG!MF6KIM*y6^ZaWgw|o$wdauYv>wr`9&32 zSkqkd@Dum5KNaVvs3`hpPuC0`4Q85xIXze|TmEK52it9AQjG70#0S+|Mekj>FDm=O!tw3OA(5!*r)`!I_uM7x zL?Dy<+%^-iiWU_8x#aNpPa2Bc`L22GYFUAZe2b8C<_8-cjD`CcN{`ZyWp#9np z?QhXeki>+vO7-&%B9$lk5jAqEOt@ZT#tq<|Z@8JBE6iT0Va%9bc7!vC-z*Y(V1eJU zCsA9N0W%WBf6o(nndO?Plu9+)30^EMk?L61D&#QxlT%(3A;W%l3>6{8#N7`r6@Kt@ zFbPXk51X*=-+bU{JnO0kC6IwiE%}(WydI^kw(7dwHKWKhqb@^Xtn)QBNL0=?yZ|@t zvkICd6LtPB`pyu3xq}Kk!v1QG{TS}``iQOLXy!xjcwO3O!#NoaY-~e@6pO;R^pA!FK{#tkb_v7n^RBwlTc>v462I%`}LywfB8d}6uIC^3( z;^w4ASkZ9!$0^x8miHv8tg4j|QiPUdT3l)%ja?dfL=$F0VM^FT6j$ zt8xF1h^FyVQE`|(|9H6!Tfepn4%gOTHJ|b+&R63UDxcP6yA_QT#dzEY?^-H zb{c8q9)Zdlv$&5Rf+yvEsNmm01#Yv&tQc*>?6tlS>W}v!-wnG1trj$$yXkRO36I7y zBIlR2Wsn&Yl$|%%JPsxIGNdpeQz*^L!(He6rUOn0Plmu_6X(3|Zp&R8RB6-3kUr0f z`L#R<>w06>y5!4zo0!lMh#gp2TgmpCec#Q;^@3pBh9>-~joBNvO_s({tp@c7HtEJh z9PKR5AB%Dq4;oCdB3Cy%N?neze9^axJd}R~7orM699U*zm@)q3V0=5I6#pr6*g&~1 z3&NM}XmCm3B|zvOf4-@SrSNVg3}gCE$muA!iWZ@VACxl-$nkdN5fD#w8AP(3en>G8 zzgFVwlH(Osc0QjJv0fu`RAinKLGXD*K(=gMdT8tSSsrDA^{hTxz0(vZfbZI5r$D}z zB{(|0w0~wJC^0%5$LRC!W9zo#bGqLr^5yFS)`&8hwtJ)|3e@+Z7t%e-j?_&DM^(&m z{tW0w@ZL@XQAc}G^yd{WXRcTtsvnzft^SF_dFJpH!COxN+*3bpHuqCG9K2nX%>7mn<~g zo1^bGeD~Df`%&qW)>Plm{_@Cf8)|Jd164oa4?vI+%xT(V_sw&p1n~sHEI7P8EK{XT z(pwVw&br(XyjEc_(Hgv)zBpMqr01uePK5Z7dMUe0{rEEiHGjfjBk**RKMTOV_iAMs z2G3oKo`&tAdT2tgHf1=OxB)MZ`%(v)&Az_6htgyBxno!IGp@mIRf;w(-vo|^^xWze4lmFqRd)HA}6v1ProWZ zl<`C|uqmL7HmxQA(H0CtVnS=yD#~vNs6y9ehWEQz?q6?#SM$TTnx4;R=cz^cCOJiK zvagQvO=VW{ABIh6^qGhG+>~Ok*fW?fbexj>Onr%;(9=As}0w?`#;lw>*VH?gl=5afOpyYLpEe8))LU&bHZEbamP33b#4tsPY;7r9B_#{Q z8-8R&ss2eR*(EAv=&y`!I7-f>^h#Q-JIFJgRTNV5Ff+cK=332Uu5X9T)R)F>DzhltWY(0{b$*JVaa)ZBBug> zQX%wRcj=KHUCD6LvdZU(@>q2wV>@FXm(hc>@yLzAHWBWX9E@`Sl8qaZZI5H}H^t=d zWu+YY-zZ|R#ITmm3yL{8JwC`IE z$4$pK+KL+djpC@tA*2MjQn~&*RaOhv&v`qmn_&^ler&Q^zvxzfv5gKfBE#~}xg4_4 zbaPFU*Rq~itPrwFqIb#W zNrFnz!2nrY$0KE^{V8#|$?IL0AJ>Z0-$dsjF9MbNONb-H_0XkMhndUysw!S}Hd3Y% z7xkBhzR>p6r@`(2atioLrkIzf@i7T0O;A2rAjyFT_T#{kAkFw;x`jXsxTIa8A}<6R zsx{!Zn53KkIyR?&89TR#01}Ov#*=`OOFY+{#JS36OV?3(9@3IJ-^=Bm>MYpC&UGd# zMTGoA+>m)P)EQRP8E{e&C5=Q+l8NX#L=9Pg87X|nLp~{dhmrdFTMGBg>$!sjNpefJe{-q;AI*08)+YZmY_x^J_njf3Ua~Orx0olr_ywcmx>GL$?lqu{! zy6CyXHu={64Zr2|Z!DANU&A-gmp#d+k3RJhH+JiMV=^>cdhY2)P#Km`D7bzK`Q*dxT!z^-(i&139JcP{x)$1(KOXk3Kiq-=p0cAnY z45b60dalY>;%TWfCCrTyd)Q>R0WV?ydF{UwKQ0Jx2>M$u>fKw>JK8*@Uz@3E?EUD_ z+|Spu3O~Jpb@vo*K1(#l!@WTuS-H93Em?Gl;{Q<=`H#iLQS{EDL)cQgE(Z{A#rGN( zdY_lo5CeNX9j2QEwlf+N4rWG<9)V5XaqVBLm`wDe{j$ERDV#CJ>1$cx-?hTS9Et~* z|LZp{_=2Kut)w3gdIpE?({AvT+G*FlFpSe~$@ZVwlncdT-b~K-VTYm*n{AphYpkwHqtbCw@pG&{RJrClIi;=3e!HY6HoX{ z({uMZ{PmWUt)!UKP#Q23hFbkX#Qj$n;m5bvin995fxpAVF>O-{1KBbEH3awj8V&m$ zJ0)Z=)qc$^ak?zwnyKE~&mBUnOfTRD&d#Trw1? z^y-%>3SQ^$m+8T!q%mqO4(2NkerzFj)kJA52@Wa>?zIu)9S_|h$YJQLASP%a<|n@c zcxsCw9t`C)M19~eW7ap7>qASve{8nSc`#S=Zsx74KH+xJB%Mf<1hc)o-<*R8!syVo zk@t56B`;vJG$-%49KBb;cU-@j7>RBbt}=%<%S%J`g3Z;WixQcF=1vLf(ZD3`PjEJ2 z*bl;77(>dxEh{hMmJSt=qur(u`{k!DN?xVQXmyY*#&@wO99bmkxK!*WB(a)oTegB z4p&rav*ErM6gmD|##M5~c-ZFH_Q4Jwg{NW%{Zi0*mEk|uIohXK&i1tqkCMT-TAK~C z9#b!>dMy6aL?Rhjc3jRv$C3|TqhL3Q{vYfWd7g5G{k#-lR9RDfmXA$cGX0EsR|*dR zqQ>;Pq7kB59Qm@aq1g!^8D(}xU(5~ocTt>F%)ccvO0JExdgV=G&IX52Rtz)>9 zYw``Ux_E#C$T=52{x$6j=lA@gpW|T)9&p1Ra5t~4;xDY??@N_7W+?BhXwR%@YxRw# zT6-Ly*)VU}Fdx~fIszz7M<~kxC(^5pYc64P&5fa4Cb-8XYU%$ttf0+c)`VnXT^2^F zx?Hi?&RAvpsaQxUEr(ZwWjo%lz8C=Vihi%-mk97gN*$aDr^&Z75cqDK@4!;1C`q`Z zpkjHKZkZ@F>#33}3RFEjrnF#m_E&hfcGOokJGdm0rLzTt2%f7hRW*CaX?Z5BUguOq z^8_~pC&aGjZE){Sy`Y#=8v#yuaRQW+I1F2?zT&zk}sEx=!Y)K8tr z_kLO%!>sTMwBhB?vF9%7e=>PlNv0tIb?r*W@~?@ayws)KAgK^i09_jSCUJX?h9 z#O0Uo(`$4l*!fBVR5)h=7<4DnHvsc@qx8G(2Udbdp}hA0=;0h?Ze7yy)fLfUG1gm# z6kac*XV+}-F0>nfl6JX8=Q=jQK8e(@0Uafr4>-R^sQN{b9yb+tG}xfOk4H>{wcUr; zUu1(kK$4~ltbnKnIYz!^-~&Qc{+wY-*2(>X&~p~JZ~+{hqY1K*ij;7u&FoTth4l|QW*YfW>8J30r0piC$W<)ztG$9nhKD#&=Z1s%HWmC#NsQoK;vzgY!ZzocLSyO*_qywig_vmy| zoH+6auN*QGd)y6aCvuEEGo9?w-w&67E8!B0 z=~5@_jCw7iy!#JIlr3lZk;(nI&ED^73!%QJlF3)u`Ch5sDbC15AG{RVGfTLOlq9v1 zs)(}sJcr+mAMs8NwO%cpo;pTpA=shvu9QUVj~sB?pnAgnn$_Hm2l%vAjzAaKr#sb` z?8_sRKYB%D3H>-)4g`I-B8|&A?F_7S398+`Ii}03N@n_ej6B2XUOKz^j8v7$F`C*! z-=e^LxDMuWg|`j4_5z{VD9wgp7cT!Bp8r|(kJ}GK1Y29YsWu@<@!F&<1$K!W$Ye+; zJ+(pOpKzrgUw@P*A_%*{tqHNoxyemJHo{-&L%$_E2BJcDoLFj_$Goh6KqX>@OdwwP zJ1n-ix5;$dR4*Xw7#i=y0>%dG@jC6vYaHw^XbpR6+ymDSd?#8d9`AMkl@PLUd?RyP z*AAgGp@M-%B}7KDws9YC#ya?xyybgAK1RfE;45e(O3!_xqU`L=IEkdN^>W)I_*Ekr zlDy@|+vKzdqR+$EC*u^2)GF71ajK7B>VJL~yVS3E5>y5&FZ`a<%T&}q?-;V5v+o%G zdnUfKqL|E7(!G}t*^lk`FMKr7hNfhc-BSxND7MeDkp+`*ULYTQ$L3INuYYYHzx=-H z3CyTg;a|;Gsha(Ov3crz~7CPbM=pkH2Jc64^o38s>dvJVe^k_mU z#FS@D_is92f|Y3Z+Azz0Y^=`_VwOU;Zwcku(9y%8UVh3gD^@`#BV2FML+*I3|IO_^ zbbGbBA7dS7U>)1Q9+O>tY)rK0)%UI^Dp=%s8>JJMdM3a0 z_0b}My*ztSp403y<#lDFTjxG z5h8a+IaWiZj2m<&ICEkWgJ2<>CoPO_62~iDW#g!1wFjC0e~*b`zIZ*3#IIn^)klmM z0&5*~G;e(Nq4)}Q`+fA91vBM*7g22BTh#t}#S=g(FCn0TQc~nB-5*Cm36IZsmiXfO zCC=pWb~O=-a`2XWHO@8jZs6tFU^OQ7<^DDF&CRIlAmB{(FppYy_oTjOI>sk_iMhFmzI@QUPjW z>VM-52vV0rzxo0X`2^n040#k)`Co}G4Q1Pzj&W4>rBU6PhPI>-+vV;2J;n5332R9a zTOJ~|6OS&-NLdiHJ_glXr>=OEE1L7tt-&&I8{$$iVIE;jn3CmV!sDgXJk;+jdFc1D z5;M8x^XNUc#Hh^g_62AH;G_~!5^*1E4@$hUUtUz#fdDTXGSyY>KrX>6FvDus<{uo0 zyNQ4IhD3}^iW_?2LOnWZx8-0kY!o%TxrxrREevRdB7u8f1pgx+SR z4&ocHwBaM0Nq&%cu9bouJx)^MS}Sm`fcf}0nTh_HSd&I_Q-_=@7OO2PxD}I~jF4qjP^hkaEYUA)>%Dx0jPf{TxIgoAVv3C#o$7qLVoGBhWmrUe zAKvf$?!6KB@%|!-FIAxECri2KuT`fq+b@V3qE)0+HGh%e=*G=}ngV>9cO6<8#P94!OU{m8%lLDy=*?H6LltD}KP#KHBEt@A99 zgFG@__;@FS#3S=(Ur`sKc+HY2rD=FSYuh4wJuv?zmCCadyCe(#Zq6lY=X+N9u4KCN77uQ&TX9ZJJhZeBnv~CpD~O z*#&>fKHZ821GW0!De7$nJAY;8zug{IH3ThsWS7|=+AC2y@;rt<~_J&P~sxXG#}Ck z9};pn1QV7wp5OIC#8Lt&pWBJfgppWEzzmY_ZAv=9mwNKsY1;Su!Gj`-iDlAs5+Pnj zIQs@P$=5%)1qK`%^>MSTS1&IYL2LU%<*Y%JeVr|4$~Tl$o|ARQ?Z+uEnd@?H&~#}| z`+@8dD%ca!h@N-R>l}L^wk$ZcESOtO=-^8Gh%N92^Oq#RROSIE&BPtTCGCfu#)2$F zB}q&!9U8+cM0L}{1jEN53cgK7tM|N{h>DwOi3()t5ov7h2icXpufF)6_K-I!Ybbi zlr0mYr(!UsIMu4X50ok!eLEr8&uZ2#CIo0@LFAv1C{JqPyxCtl9)0P&bCIlExD~cB z@GgVysrY7n=KdGkPS))X?~j}#={QFOOAR8<9qos!9XdT_t=cI$tI{~eJ`$#YP%pl7 z*tMF;vTp}ay7d@=4JP~~SZr=s>~JlDFQzXBc}gh-H525a{1EO<3#bJkQfD}x%w^yF zQ+~+SGz^vPYJvPi4tVkgZGo3W0Co2Dgs54msL!dW)m*`&Xm|(tvoG%ccjT<<+92izKDY@~ zE$!ma_4>1U0NsR)l0A6|C~&nL&i20hp(S}4czibYtsz`xjc#7QLy;Wc^eExGR60a% z@B1o%%7^g~lf15QN8@EW4>dc19M7?}9$(&zJ6n2vq0I$432;V%3d!`%{mn^K559~{ z-`8>HV^+DJRcOSagB*5~nk|Ze&sQ}xslN(L|7VuR?wHq$iZ5^>J<^6MBaG@d2x7t7 zhBVs7A5ZUWmA=spEwv%2{bag*vv~FXm$pUs`yQdLP)fp+#xAOqb#v^sSXdmEEQ}QS z+*t|SBYHR{L@wh5a(o}=;RsiyXqo>4PLyS^#3n36Hq2FC*+Jkf;!p`MN~kfY?Yz}*;- z!bT8cQW9*Z=VP@q>}tku5T!^#FQNwHCd1@@_$Q-*&8!UB58`NYtOJYG3!%QMtCz|1 zitl7;jKN%#^XE5o3V>g9cMn4kSr-50k;&aqji3|VS?D%9j*N1mkg9*Zmu}6o{voKA zzP_!3P0%k5qiD@Mv15?DJ}!NvP&vlt2Qe>(z7czNpVN;ZHs)`-Fmpfg>hwfzCtM$P zA5rm4qibeSgY|q|Rv0*S7wt~ZG3=XfCNY)}?g8X`Ta}Bfhf|meKN%Mi|2zKwC;Nyv zY5LEjeR`o@Qr$Riv*eh5GZ0i;N%slA!21}#D-d=ZQn*X_ZjO#j_V2{s5(RQAsiGy- z#0Q1KX((KGGQW4I=h&sCd&sulVpS8F0Wg!&icKtCWqslh=cqf+l zNu{-KS*}rUNFOc)P1o_sR7pz{chuhx#p?$8{UU#GmPvQjX2ZI*96T(f+byKKF0JWP z*S;v!-6+(x)jy1FncIAt0_e}C=mnSy7f}j+{Q0WUX}5y4FxBFcNng`?*2BcLu_m zf)OGr1zcPO;)Iw3SSHz;wR&~^^nrIEs|c+yizGSk^CU$E+*rH$498JDh(gS+KFcu1 z1WPGJ%T=(({I{Q-*av_3uZsLne1bAxqioN#|E+h1L)Dj0_RbDH)_??KhI}FM+>9h- zCRz6MJ7u5h84v>r{-4BQ*l)~8UWDZPZ$odj<=3yXboov6Mf_EZ978(tNk&V4n=()CBoI zCkVe`2@ta?5RP!|+)LI-_U z=C1PKBa9MgnP^P@({n@49iXg=q2)!NPL;)t>_&?J-rMgV(rHQsH_old4M6Q=Wlx)+ z-e9ZAy@r=tcr)P%qyilI#(U13RmF!L#F0F_Y}r^cNoxy5_#8s(rKpv@9q*o!5ZOx- zw4is2@lpY?WPNQR6xeF5c3)>P}mb2DQVqumri1n@K^}@$yZhC z7Y(ykskd9PANgO^enUp&Qut$g41P}XJF5I#h~3izsRFbovc}*omGOWI@DgH@(bhmL zAC*hT&rhP4@fX#I`yVod6m&igh?(sFIx=~}UYNXVEg(L#{mP@*!DAGx>D83d9!ZEQ zql5n_@}7K5G{>DkkissN%R+<1Mo!_Ll{`+E2+lDfT#2AqNC_{`(4E}I=T+NjMhPFm zkh7Wz&C{Rr!O+R)bzweKbu9qQajzqIFH11wTEW(rCF<0FGNX@h%iw|J$;WUWdxvwc zewG1UD))BhD!9^Tp3B~MXmn*@jZY7oN)|bk7;(I6edyH+h(n3q zHJ4Y5xcF9~rOCN_N#cB988IcJ9saRu`(-jDGo_eR$g; zSo??b5u7>$5u29v?5oTq1um}{+0%h7mYncNT2J(IB235G76B?XE6g*3(WcEh3-9j& zyQN=?<^X9~YZt}Mrd79^Nt}_b8!92rmHe+e!CAQV@!`vKkU~TavmMaRSS%3%-2di= zT&Kkj2_J>H4ADD}@;F{MF>KxCpU-&K8zyFI&MKQ?S9XzRbI{?spwB#6n8)ude}2xp z;}`=}9yz7}w7)MZk7@sFC7kX75^1A?3`|pHNb#>Va-83}pu%$vq*=$9gM=eHD2*$u z;j*=BqBA<+gq83vrYpW51jJHdI*!kLh)Z;gt4*(_O$KRY8)-4eOry<2wPAQhQB+z9 zw6{Nv#|Ud@l#3nnD)+P7|6siM<{pWb%()SgEq+wf$OEMSlig^u(nfs>nBct(vO-H8 z{vUpJo-jOH7xnoOn}Z*s-c5b^B{s(rO>?!{c&7C}+7O(vBYUJB4%t;^+_BGVPSDmj%bERkCgxPGd6JtP6M+_wp3~P# zl|tk$mqmeR)k}TVXVr_pFW~Q=!Hu7v!KFHUoJw2lX{k3eOJbp#*#fWvEGDptaOGq< z$vTpaPz6D9XQ&pnj27i#l#&}{vCQ4N=>OVY^+TZ$*IU!M!!(QCG>dDyync>}i!{(? z8pv*WD6=Ky@oD(rZ1~`A*j*1G9_782;tHi=;mi@$<)pGpMJd0{IqYiEEBa&W0c8VW zYJ|R!6dC``bR>d^`ofz#7N@W3Gc;Jd$&6CT%M43(g2;XUKYg%TwH3;DI~YHj?;O58 zjyq2)HxiceQ)Urnf$@K0d&%hww7qhB$->URrJPap4Pvi5t2cl^f49Rh-)d?XCz<1*r{}yOo+#GCqPXkBqvFG&eBAyP?Z1gfDze;Wre1W%3szr0)o4ovA6{r&Y}A|`1fL%Sx3)&fZH;=S30S2H z?E5?wF#~ED0%=28hwMNND^PR)05W;9<_0*Qv;6jf{P3}F`#}nH7!H21`tG}T{>kU@ z`eH-1Z3*~%3b*+(CdY?lPG4uaJ@4lpE65Np(A#xU=HmsDxnfvu;;K-Vt(0kPUFV-_ut0gdWxHun?0t?dx--+XfaV^$Q^;hspcF*>Z^{&VA@^IL?@ z`F{_mD|!FIF6`2KXS9WfAY>Hwbv8UZeGWV_z-#u7I*sn@kfw{oe+@9nS#HRy>~;jd zk3g+Ep$qnT<8@j^Y}W&fu~Oz{^3Yq>=?T~t8W$Jo%i4WW(BO-7F`3wN*G-e=RCYK#-nwq zvve28;_OUH;>3}HI5Gy|A4^!))N<9b7c9x7|4X2})(Ro6MisLnOXic3MyZXpBpU#) z$0=DXI;IuUmnj>ZW*k#?e83PQXr%hnQ^)^@_v$5(-}2Rf*`#Oq$9c;$zR%l_Nne7s zLNV!R(Vf+@#-^?QfKd@%$(7r5Y4R%&Kj3Vm0;Z&x~X30j47%jztrAdnL*>*0pIjhAAKQpEQ~Jl2WUEz(kP`IC%@ zm63K={ef-PnG!_xos{|XayUyP2T$YZwpq>1EnSz?LHZ=yX3FBIa5B0}I>FmLD`Cap zyj+Gy*}8KTd2z4>+w(${BHS?t&ESpPc*lOYptZlCBDx70q`x?Yn6~hz1wF930sM`O zV$T*R@qP)I9FhLZ4>$b!0K4rw^uv>oaT5Q9tw$I%Y2?~lp3xDn0O;^)V0X81K2f)& zQGc$LN2k|qTlV5%{@jh@Xn%PTU?5vwWYAr2(QR$~=O14Tcvd)69fcmePqROJB2V|^ zaut=pqhdnxEJh(@3Jv*eJrT%SDCbx?N-bQt==mr&wi%Q!sRSFq8#vVe^= z^G$5J%u%~jTB~!w2a%>C5JR^UQ?oO19=9f!ZD>sE-_HVnI9%|DQf%*SOzD^_2W(6e zSSts7Ofgb4#muIOS*+@Zi^ztHHu);g5t`pjrx=W%w15vh{d2*v;4 zbF~{@IlUwAwKtWRd8g}`8}g_(B!Yc2uAt~!wOXf3!+TS9a>u>QjA+vXzjD8 z^3{36&a4R#Y`;2u^P=67K*RG~A|kVdccC!l)V051UX6)YTkL9v<%}RS1%ap1UXd%$ z8c>EF_S$nE$-U|dQ)*}h_kK1g6v8R$tHGH{yj(c)J$?ZRy}Is49~36ZCl&~>ptz=U zet?TR;9~IMiOGwlX&D_}e}d;6fIA^^fTZv)=A6K*V_S98b7>|^k4|1)Hd(dlCOoE~ z0X*Or@Dp?3T=5(4Rh)hhwu!USIpry-2CZ z#B7WkZV|D#`}i1uB!3=zu3lcIT8g?Zb~Eh>oa?e#k1|MVk15 z?3lst!pUa>o;!xv;BFL=IK#>11 zmW@ADMBlLV5YCl_#lr7I$q0OUy+#Rxkn{CpvOm|&x%@#j)K#-`S67iFa%A2`D+v#u!N?IC(KNC|aYN9J(n}0_e6^oMYWGKwnqmG8l*NV&n_e!g1 z2!6TCLy|_BgR~(>kDxc&fHvBI*YVzWO1Ay@6%!AoxO#)c7{TYE!JjKlE+|l-+}Qud z`u%_7zYFH%dSrPmRiss4F|=iu0_fvV?_ zzfC7PQ;g5PQA+Z>9iU1hptlU-eGAb$boTlOjY#xGe?rZySZ(kk^&MZ-_hjnl4&nS` z!&hv&XexbYV;bng=K-1KV`c6jTy7D9a zh__&APsD`p?qEN{H5NSZR06qv&@eN^!z`DX!< z_#Ewfgu}&W)Z!Bi^+EqVDqTvfleR+`kxrVXki3gG>eshJf8K^J-m<+F{4}uw1$HgX z&WOTgL5fA;Ui00sy~gM|jUE7q*AuKM5ZTJP7 z-pj&PMKlSe@kAx%3)Ht!=*6%Ea_@|di^9T>EB#nXYbOax6g_0=dCjL?@(Gb&KEw&8xXA5f~PagBj&ShF9W0@2%NKU z-J8f1O}Si*T_KOc1Ob#CAeOD=M-)7hPEPXs;Szeu*d?-nR9)Rs zVg4-zirUHk*9fG(N~Qi!>wRUxS!;JF<~JLZiwBgu%+xZ)L3j9wz5SRqTd^G-n(mZ= zbcKOY6Z1SC>46?z6iD-5YbC~;`0|Gy+?2G{{2JHO{yHSUGtsRQwnW!MhFFr^t`NHY zplYBzxHmRKH8Ij$? zZ2vH$csHXMxOS@<;L*O!usIv4ndg}w=b1k`wvKbF+2uLs;^4xhtFs;jgImf=S3Wrp zA7+8YkmO1wS|rO#ueL5f6|fj#O{hG}O%?hrlN`kV3JSF-&O9(O8x!{H zE!Pl+d}NNfR@d$+ba>YX9zS2qUhtCLCq@8hiyGK6NYSQ65;4M7vUBVopgg3n=sr>? zquXF0R`+;ryy~*pr`n|Mj!iSu>w>ZoXB%2|tg_7sO*)i9c?CP*N>h>y+{g#97*B07 zhNRaXC9Jo3F^jyW-9K}-RCge|s!QGH0f)*znW@D8ZqFi)EQA4MF2N*vn7+rI*H})lAznv8RlJ z$9I1v?+3{QdusQ2YpEFP+UOUQMk;FV*y`H;+5OG~k&cJ-5u=Pga)sZ$3Gvo3ACqPu zxvbl^0K_Ke?f)al3j7yk-98^S zSQo!3cYw2F|GRRHBh$aL69ZS?0-lN{-KSkGIK0!JF6vfBTAs*owFh#t{um_$;U6b` zI-{XS-~u%#P}BSOaZXi-wa_SM-}`r)v3B%)bN=Iip7K@O)Iap587322Kb|=C$Bo^V zn*H_iF}sGm#j&f=v*D9vF7uIzctNb$!a;dkwB1a6UZ2>Ly7jNdr;B!(>%y8YKE?9$ zP*^hF*rt$KCil)>pE4LU*IUw;e-seB#B;j!HqvSzDuOM1=QM^r$gNd-{mj-$nv3Y_)Rw zlgw*pQW%-Os=qGReK1x}}hFsQ0P z`;vu|%IlosqEdO8thr1)1#xsNaIo}p0YANG+_WAhKWZpbwSn<$&U!>fH1 z*(1sFS6}IRRUKbF;9CW+MO%s8{^#lGhuM$4tFNB^bxtjK_9J+8#xj_ok}2U8KO|c1 z5TLcibS2CTaMFYslOvA(isB212+uLQeHFDq@*>s}`Jpwh>{x+6B)>)Qjw#I$ix^>A zV9CKT;M~#Zn3~N3dk!ysp|-RkW;O7@>$77A9M%>D_~y4M3l3l!3pu$VNkSS{pXY=w z8K!kt;|n3WV`>wjBaDb372rZ>P?v28{$2G~jAD=s2K8494iec((90CoKhuwI?W8;P z7%PzLcFL}UykcO{VS8g@qXJ@BR7k zGtpTj(_;Ii(_rndQK%nBW-mRg;C0AUJ+n8(b7cFN{m-2nyF=N`wHZxMm-#f{qk99q zPP*1uxvkn4Vk{GAd|a;YcYVC4e2^=7_qr^|-a#?I!RV@xCkzdnOApl^u4}>p z)GzogG|n<=Gl$G}#HF8053dFcog5IHfA&B4Z6fy%8k{TS=fL&pGQv;rqPot5I*kM# z9R<(Yf@(ozxK4{5xvW{A+=e3o%1^lb+C6Jr0J|u|xv>=C5n7@n zlH7trnN>E$C0^$>^AX2L=4lJg5g4(^;uM($$CIQISogY9y2c}VOSCw4t=%|tw1i6t z<{>SPe1BH3XfH&5gh55iCWw2*6%3}FKq|iCC@ADa6&64*&VRv$bH=4Khh>f)8`?bx zU7;2-{<;O090$G2K{CK*!!JFoK@!r-jHvkOAtL)Qym&N>q~O8(@2wsYWAPxIn4+6? zB~G)spV5m`vvHf%a*LBpJ6B~-?f-M)Bi5>)W3s69o$1k9t+@Pb?*=!G(Fq@?vN4_7 zdFwBb3|CChbY)^s%63GGP9SsXGIYtcN4ErqX%s~&z2VLM+J2$KFg8Rs(*6S@8Qk7H z9sjQ<9#L)AyBA4OTAv=eZotAYXX_hyTMlKGW+(ifh>#DHpx3YJcR><=%&#A|r$}e6 z6F)h+0B9KkjX$`=5<}v@ibAczX3f^>8tfeiE_|_zv;0#R=C{CDkQi^<#AJ0C;5%tN za{26+YWM76P|jfF(c!)lhNg628&={lS!DC5DhpjIvCiUt%L*yVVnQek*1oF?Un=>Q z!(H4C;i7K@{X(b7QfjTlA-M?Pyawolyxodvf8I~`huVDQJ~1XngUh3hz8^d4S>wCc zG*30$$|0NH=y_CG>v8pKx!64jCX&SjJm6~mG=N{jN^{Z^ zHGX3N?jU&DNUG}FS}`lr-l+>x!0-Y-n1t+>nC!D0W|iQ* zT1YYieW8@HzeH-M{4)b^*}Rje?Bb7CmgmDCT2v2W7F^};k7f(rMrovkBO!q!Wv#|# zf`_FUzK5RT?xVMI;j!g5W#5wwDx zBN#>2(N|2~3}}a9pOXV)VQe#y`DeK8d#c}0Jkw$RuFjEi@<#`-Vr!pYO0_?k%Lmc8 zeGqT|#xcV20dI})`2Gk!Ty7#ja{RY9R)g1Fa;V_8K>OGB`9!P|V@UGQV$O7nwC7Qn z_$Xj=Y`1%%h{?W_k(zN$>olg##IP(U)Y#2{(Ox- z#NIz({WH7jTJnt(qWmisIXva)!a?$YT@hvMWd@a$j+Y%3lKj$TIEK`K-f42KvOJ(D z5sIa%A=htRI&*hII*AMw%4g|(rkH}s6gn|U;a&><=2FG0T9ks{@-0e$9`eD7^5x^( z;~cPRnCock^7*k0$Y&ai^8I*0JICs+d;Z${P7-+3kV2D7edyv*>O~S}D9fu)%j{K` z4Yf+p1v$*p2&{kZ47fj^LQ&4i1h54m&BNtL=omV@2qtkY8<8|VwMeoZQa6I>0`2LQ zrZW<@F@Y|c?Jtjv!FuX8?R?nm;lv=r^AM~V+mn#-#lgCKHO+Y7I?+iop5Amhr*?~B zYWW(Y;`>36&>PwO45x%E0q=WD#|LgL5w4Fw!jV9zIq9?G%0^q7VuP2Y5l&p6PBaMzi1$O@LoXD|&tChua7&5%xhV{Pl7HI`k2UtqC*HRVnMu5FT9>;^T4JJwh!867 zJ0BFv*3P9jD2)VyN!ViXn`_-EbQpQddiNO1HzDscy?EKQuNcV# z7!v?|iL6%yLbNx1bZvr5Q1SRC8?1tvk_eAAI@Xi}uvLfS+Gj{|)v;>*M$o zaVD$X^I+QFsV@N{4>g1-?6L>{RLU+2f+UXCi_qp0p0IQWne}SSN$YSqfbiWYM&2E` zgaa#IrCXD+UDKjc`*$S^?AP*luTsS%+`|6|MJ{pBpl!uVPqb`HW6vu#(#98UC@?X__dfm^M;OO2eQj; zVW3UpfdO9tGvyKtmc=x0kN*8t1-qvi-!4qQ<7KQYJ4NOb5h~DQ$XQaS;~mw8xgtBI z3AwUq8(2$28zjI(7=H3Qf#@qH+wng^D0c;Og=C@I3_nTy0r$MD1YMz84`emy7C`E% zDZ-RW#~;Vb`M-X!EXqg1%88QFjL@lO;sg?4osDHlY=bZVs5joCjGcG{kC&QvQW#B% zZ}y2cYZG?Kd-o1*mBNrm%0LU(##ytGHtfsZkF;^jp0&vxW7ckJdMAd`GbFt~a!Y=; z_Xq}O`T13-**IwrAwW;b@)yrU0y~2h9|P&6tE$o}hlVAF;voaWyvJUi^X@(XtK7_# z5$V0rKBf+)nU`6lp*;@k9fn{*xf`^ZfXBO%W1dI`A*(6i0<;Gb`XfX^w`AMNzokH; zkU|t9MYSb=V*;CS# zDDg(8sRI?Vn%ThJ!GL5^EM4#Ve|e%!=qH)VOSJd9~%()iPdA<>y9-V{)vEJ&GX zf~z=EJUr(-spVP1XWd%LH~cT~Gx)!CJ>g#{5;>M8nlN%XyM9|J3sJ6B1_4`4uV{jk^DvYo7i8_Da}o-?BN|E?A zYEdO0$7-ptCY$wk2fWAE@kj<%JZ|U028uVQJBu(k@oQzgBOH-8Qc{qdhX}ofqjz$r zq8wskl~T;pR>wTWUs97_7D29&ThtG!N_A)Yk_bSf zfH%yRqkm^FGGDW2fXiI!fb!&g2kk7jchLiu; zO7p7_8O`hV#+##m8Qrt=;q3R{>7X*)@2Qm(;9$6;6!d=Z`d;4s5i>C-U_;RZ!~eF( z`2wQh0f`}m>bo&9u*Sy|#E71i#(GZQe%#Y1FS$>SrfSIIukb6>wQ4v`6Ib%sPWuS? zJ9IEdn_NaQWsS+o0HeC&KedF?IBB0std@5D9xupkm%(}O(mq!EGgrCa;mzM>50XzD zd%|~N_)~A=-cQkPtf_LXwg#=YUI7f=Lgh&oKkg>Xx6ZNZe;AbM51yhKC+2{D+?M|U zy}8wxZ2j^0;k^6@@ZmvY^xt6;z5ogVqvaou zOTVJ!-|SQLuH4C7FDQEJL%98Y`RuBq@!Y=zb}RHjymG-l!CLS`8HQ(=nsbq^lQM}U znbuKVe@(`l>EPzBER}{Wuz=ef_myk!r(wrqiNE?frM?hf+0uPv7|z8^4Z41&CC0se zm&^i3hv=xuBQk6K85li*=*(h;dRb8~C(9lO>+K>{qV$7!IO%Mz86NouiQ3$!yuP{F zo6O09iAiQ}c>**Vte2M6-2OBYgP#?k$ntBKZD$4tk_}rc1lSa%gefCRruTc zSY|?IAjBcmjtegUoITPe0|$No@i1r&ywHMKbHGJAj|jzLoT-5LN$=(V?| zYM1b^v*^3fRRmgo{bV6y42Tg6)=**Rp=A8ik3{QwY&7b&Z;_Rw+v;Ur73R|!9Hg>T zJj?Hve|~_Dq~BgB^%!1!^ZfDy{Ngyg`0wR^?_}OyIEjzU#P$}^g$aI;V}y2i{0OXJ zGE5o-Lj({}!mfNEL1y|A@&^j6OoN$ZPy{QX+-rD3*7A}v;_jk$xyqIbhotL2mM`RF zxz%=(`r^@4JVWQ&+4>H;Ig_|t66EKP)<vp1S*GVwS9zBgY_{q4Ly%U?0^ z;-#gu8Bky)gCn*`iv9UzVF1PAd=6^z#mmNQ00!7is)F~h$B^Ey!)k^+ASo!Z>#=p_ zAKPAW8K5*<#Mbk}~Ui(MnL2C#!h7MVU3KC?S$ptT&M_RIXXZu2eiA=2^uVCI2APPpH;7-n? zlJ=rT>lXIznwGpp*nLPF8W=`GJX)98=}waq^WSyPfc9>KrUL89Y`ODEVBzF!=|WoO zI}bd6E`+$Lip(y$=bU%fhd~eu#ZDs+{r!PWAkGK-Wo`Gtj!~A9sRJ|^;#uc(CXxkm4NkgP*|{ph zHk|KXadz;XtXmKAosdpEirpD&$pF=h7Oj|;uFD=f@Q|af`}^E9#DU@OioOBGWD=J%t#>=Dp{1N;GiIp zEAI~fsW71NwA!UTTD9b=a%J8#XgZ-~6PJ7xLP~s6aX2LokqbSp&)0v?OMs#~ZeMI+ z(BUl3L4+jFvx=v1*I^OAF0TO&Mlj+4QY-~$>9o~bULx&jj#ul#S!IH}SC}l{YalF5 zufFV%$fp&UPZWP_%yfSBBNxlOQ?1q?0?a>RW41*>ZDP4vR!LOe5`ccahw%FJqIQW_ zuUU|L?=)Y|ubi`LomE`>s2SQ!>f=`3z}98{)->P&y;ck&odj-g^vBB42DcG-Ml?X> zk04}P8w6S^vupIUPXhEYqVHK`xRaUHwIStWrVbE0;07lLDMDj8tf%O!QgkPf)d7Qq zpEuyi_n+ptWYYeX1r3J$OheH?pqBB@mM|g{2yz|ykOujXO8aM9GS#?^3>Z#i;j5Zo zA4W(9fsHc)#^XIXhmbx&C3NSQ=7DPc^0o*Og6|xUys3lX2)j18lrT9*X8(xZ6UOLS z$FR|H#!3kA1)gtkK_(1T~`)#i^SGwbOKeZ2A_CHdDpHj)IwySc;0mI8CYYfTK#d&n!PUbvm0+Kc(JgvcE zMpbq9Fi)HrKG_U=^!cRYS4wg9=lRyc=JqSaPGFuL6qV}( z&9`-DO{%_X>IsQwE^|bb-g-;q^h=7lyxy^|{`7o@6=NOFWz5@ZcxhvMO}W5-zmD1C z?D!AhqU+@HV4evGJ#nS6&K=S8yJ7}uvy!T$y!L-3_%|meg*wk@b@KS?CHj9v{XDi$ z-@Ql=BYTHjp}UAas*_1>PAH(6H-c_Gn~sSTxVa~+J?ZzH@nKB<^Y}~8{;{njczY-5 z?M|LX{apB^7k94B@g4P{F-tJg?5Dq<6QMFOQZ9j*2D;uMwpQs`^Nk$iT$4oN|Cl=V z!@9=mBy@?h;DTUk@ra8FviMGi6o{3ZgEe$j0bt1>?xH_0kzwDH*-*B(9%+ql`7pns z$JDu(($gwgJ$x}`I{q|dJvFzu2lLCOBm_DBjP@a6b6TRuWdF;N#n3_W)j6PfR1m%h zS0Y6(#bb^(?W?seun;rb%!gW^;ICX@C1}v1JO2gd^kNSzRwd-l&g}!-B#B zA{ezMl%!u$gI10YNT6x7k(9Bi(3Mn>L+BoT;2(#dCum7H=qQqvTMW7jys*a(&Ckr) z-jSHl9u%7Wb>$m)1GoCVdCbkU43YJ^p>uWEHOouj`p@2{2nmI?p07ZT3=9%jeUy_X zFy?!!Gd%*#7z01qZQuN&>lG|r$Tr;mAy+WGuWbBOh?Qto6lGqOLYICUIjKGskV zJ2p&5l48h(Hu&yY_ce#qd}uj;xXe4=m0Ld6zh%s%&NEuheL!Q4Ub`P# z&w-tJRm`;{qn)Z;-?Q@exP2l1EpC2~%L=sgyU34TAC>O>=lj0@iDj4E{du&uuYzrY zr=Mh*iGA2NeG&em({+WT@iw$1vh}mgBpuO6{aVnTi(Bq0v%suF*F5>SUOG4%9!H#B zsn92J_*XKkapswv9oRDE;7kU9C5_^ze^E6_xEDyt6ikt(V^48w7OuxeDp%rl34aZV z#bkw%MP%kPeVy;GTOTApouI47;B7MZ8=Q5Hinql_Xuy{Ebwtz9^t|=3@84X+Oq6@w ze=?6WaELH~a(=GR`buZqqWpE&U+y$-*dC3LG$JyhdI?Dmrn6x%QV zpu3C+i7Ql+EluB#2a4Y1j*z6T0O8*r-u&Rrm^(Ql)*QM;i^4OOVEUX^@*(c0b=E;G zP1SUmGOEWLJ#84~kJ!wdP+);%NM`DQh%Y%`#EVz*p8q@Z-=)}UB{$2g0#{UJdC#Oq zfXrQ~i;i*2_mLbE^j@*&0_&5)WzxIRazt#x?Mlv?hVv=%pvM;O8k%ujT=3j4=$bAX z9Fa4nJ`GkMZG3SyG;~?E3m+Z-GJPQ+l$fb}yEY4RvVe0^t#0@#(Phc?o{{c%VyK&o zh`=u|o@JvG&AcR&E9-g{%owoux!!=!Hf2XAr->zUM~x&lkIX8+X-b<_?%KpZ zUQjlAFJDka|MLUYJc__9`-#mGuakT~I!uVXfXd7YeW(e4N0H@g;Dy1Yj-z)heJQ3M zJ$q3X{$UM%eNHJLR6cj7|0Wn&=lY zZwU~Li_us{;r(-{4sD;HX-z*Vr18O?&cA93o3pJOHDi?6x=uY8Z_64G%VbQhGK3n5 z65-nIVF0x*(NJtePX*!aH`4}G`q7p}1mI|64QDbou1aVb=TW00%1f|Lzx8uY5CUuX z50|>*5)dPXSWZyzYU1BuE?psbIbE#8Ud`t9AiPAk?4UHx%qlkD^}O`*YIDuxC{Y4V z{i!$FL@AIG1>PFEws^Xw^krs}xnLptRzT^Wa0k-^Q~gU7q`UBiu0BuF@Q-x4Nh9ra zJs#5jnA1vbY$D7KnK~p>Z+2#{h;EoYE=%8M3WGMay@=N-m#+Mg2h0t<{5DL78C@ri z4Ts+NhUrL#u1=@nC`9)Ii3Zb#@{8s;ghKnE0rg@Ee)Ozy$5H)$4 z1P^@y`)b}ga0JKiPgsN5290c)kAtoT_EOZ0989bh3S@kApX+T0nXaE!@GDc{M2#s^p#Wvo-LD`d{#%aa$fBHuHXmw14qfQ zb1HPTX?A-jlB3Aq%K4o~>gs%6=joh4fqXvo_&a4hQ|+>i)tpZpDsIKgbyZs&vA|Q% zNW0aJV$|nUv#%mKk8FveBDrDoZdUoCZGf2nDg&C@aJzF9hJ55&oeG9m)7ET{=0+UV z>2(}gJ;esWvaE~13Pel|wo?u|4 zNaO3*tzA!4OzM7ud6Zz!(utq z2IzHSb+LO^w9~#66Fgg^z1lis5uyDFv!`7X$7!=5aMjq_zSHAun!f6ISS_IZZhMu< zT&5XSao5>E(^PXbst=vGh6V7g-%R^0!Lz%N?!O=JzXy>dmzK!W_{p&)H%;5G3i)78 ziSd<+Etr8>|UoAsF{L6zST3sg1{}N{o+tfb<;nV?HGwGETwWq^P`zEw`Mj)refv z$C-{P57B*H@lYe`p_DS@JI-TPWr7ksi{9#fNO{xd)x(_}WZK*QR#)yc0P59E!tB6X zLZjB(iz++0&s7*E#ve?+!hpX`KwX4OlMu!1gGnx8rAX*1tppdi2keN3+W5ENy5ITF z-hbF05`6IUqp_*Ib1d@}wfYk{O&46n4TsmXd`Y4wceSNW z(D<3YkI_hL^eK^cm8xOMLr!T+Z-hpVFpBi_d&x##sVlQB4zukCfY}y{*|yQ$Qs;E+ zeuLsUTB2VBB`5(}&j-bv3mt)_(?Hp`nK>Z$agh9Nrt5>!C`j!=NvkNaTIEB#EhzDf zAm4zUZRRxCURK_ zkqlHEhDsKYf=jcb{<9b5yrAIT-XI1_5&B4f73j(nzqn6=sX|q7gd?e~XMU=E{QTqY z_2(@bWH2RZuk5~f&x*j#*ZLl>q!4F7V6DIa5)lHSo0ZXijZn&8KZoF~rtm%&{hE?G zP8~TO4l0}9j4BC4w;`TZ>eaga7#s9qdj{Fd%*{9fwU*a0mZ$~N2DZZI#bFea>- zyIGC{oCjH;36mM$APTZ;Y$r~ld%ZS3~pnCODmdG?)yd*sI}^DN!*{p0J`o@=~I z6!@xJ&}^>RpTn{~i*E^-TLMW{YN}M$w`W}iQVZ|0E5t`3f$+f$U(-BJGD9tln^*at z&su0DLd<$3wnh%JyK{hsU40<-akC7-cnI5T4SpO@08#I@E?nq~|C15|C!AiN0}!_w zu|VWLtpVDlx~D>YR;RY15|89Hv@W{l+$E|;v2QVNw;8V1k9CL^>Uy=XogIBL^+PUe z8VMReKXA0y6T0gW0ZE9lY2)|)$>K?FXU`It#$|OIw1dRVso-$=B8` z-#z8^bBzXS0Et~T+zD_YG2PWDXMKwCAt!mZwQ*TVuQDp;gW(!>z7+O2A`!xgSHiTh z{@q)!UH}5W{&zfrxIQU#FzGU4@H^HQR0*Z8o?i^x9XDTe?i6h_uTcAz4Tn+BTs0Bc z?~sEBDTIRBokBcBwSw!f7iJR2N82218^6qozWos*+zuh82}&Z_n%(@l>akHdV@)+a z$PRYhYQL$PeE|z>n7ioD*}ZsftN;|@@C}up3HBHfq0&P&6?{ihGWn?69&IwuMI0Dj zEcToJTObo(JUO_)*Z=JGWjC&^@i<&svny&9W?Xv(J4ZEHe7nKE`G|$hZfG~|JPlX^ zN$h3GT(@?N-xDp_v)0p+EFnsoQ@zAtugDq5T^A(SZlVDW;5Zo9ZRFhJrp42`=voZ& z@mDX>kNuAVm2x%IB3@w%k(w&bJNl+T%#=c!gR z78-a-0BA-_n7xjI``TfFz!AR2M{%hg=dZuAeFd|9A0lC0M4%dTd_Vqa^AUsc6otA2 z86Vq@5lOjFkCsj#9!dGNYAZz7PX~cipGs$YU1`yQ3HCs zg`l`9xQccd=5M9cHO-Pv1^fob_iw;OeV3J1fJIVM-q-!2otrp<^(%-eVS>o4 ze>`$+Fu<7Kd3WmeRYE|2xlU93vJ_@qP>7V&Po>F`$Su=f>r-9eU!=v|>35LK6;wO{TjuSDpCIS2z z9M2D`$G$Oiuh0BgJ_Neh16e(mAA!ss?eRc$TOgMUfE~nr1;l|=-CH^D^IQfkuEISu zO{HiK-GA=|Rokztq{ytAU4Rn87{>ZK zD_;rQ)P8#bHO*=F=PHL*2iU}TMZ+kDO6-torz z;ua6M3A>h)FTWlL%3?4V)0&_Z0L0c9=mSz?H>Y8A5*6<6y~a;g-ls$*$gAqIiN*L^ zLgXW9CsL1f5I}#G1y{y?G$VEx>qGjb&#K|LCT()OB1V^ zYSp&$0bw>Jo)105=27_=a^_aOg96QD?8KDlkD~FbAw1!aA;&D=l201g7>qDpZ+-35 z9}Wb&9Wp}>v%tB*QH@~c4JW7Q*U*%9FV}W+W3#`ZDxw_9R3T~5SXhP!3?341WLmz^ zcg`jgz>Avzso8Kx^v33>vZl$FH#&Fv!&93Q(zCHj@uwQ%YY>BIfotmyk}hH9-m@uu z-yMYpv5hjMm=M13DxCE?nEcTsefjo|Oz@pP7|PL;4@%tLGNR#Oxf}V1r)l+{D5Z!F z!fUDUk&h$$`P#JuC{J$`rY&MDBH7^)0^q*VNX4w`E7`iSDc{+0T029lpv_ewCj$e@ z;9NN~Z6j|dqql3>w``WxJ?Xp4+tQFQ!^WjoG=GsKhwjbw5*7`{tK_3APv>`TK<3kZ zq*d=I^!uvv^l7WHdZbXP@V+}9q?THCSQF^<`mzPFDgE}K(AY9WXYak6$8b0>NsxGV zjV@ytM@m`L(|!!5-6KQ_!6*5*XrvqR7RHY%d~3y_oEyf^)~l0p@;FxvX^e0QTf!PQ zJa4hVZD#%^ag5FGk<_`{m*Z+6k(SO&mw?;M4WOhnFjjt6Pb}9)V5th6Em2VALHW^2 zT$M5tQ>ICCV;l4^90dB;0PtBO=&Aj8@;}$WC!}At;Gr5Q&7538NamPZYJ=Z*Ntex? zF6(516?CqMQQRf5v+W!C2`f3x5VUB#m&>AK>igL>$! z_>0x^`>9JFwbBIZq8SQ>fb9ewke*Qs#aymSW9{wDt|!HDmY_c)2b=do)SD1rX!$Br zB6NaoGNSl?mhsaoF_x%CN+@GVJT8{+hpQLSw#b?6J%RY@5-4w~Hps`ZuZpI{F8lV$ z?>+_Yh~Gy|ihch#EjSpFu^=7XEhQc*;8tmxuMTcZCr&cw@7}by;vNAO(uO1{T2L2X zIu9kTS?g~sRwzqC*Y%WBxK;A8tKKjn7_ul-+|W7TfuAbAe3vQ{Lvx6z7~QB_=oc(y(O5sO zExPkp%0@n4mv&WXkjVhm;FM+Q{yO#il;03Vze|dqr?RRf#hyyVu;7r=W|l1fQ}h$w zUM<3u&=Z{aJ0Ix8%BFS|?B&8~4}7CjIwt8R39Z_|%BEd_fy91TqpvWwI_u|`BBr_v z6SR*wlr<{2WDB8P z+S1ek+tOKdJ;WZJ8!aBaXb>`2o}9*x385}2A0YyYdzHE4`O$=+*!g|dEEnJP)N{)^ z0Inckq1umw1v$YtKPnbK9V`C*1sZp=2VrgU&DpznA@_5xUE{7Y<0^@V(YpCWS6Swh zjCNkenRO5Zvs+!#lSj|EQ5XdhXpNd9SDuKA(>YL3D3F^WQ_v^9O)*P;l@FoL_iXat zJc)YQuB~c7BlVR@%?zo|J`O)xLjhGm<3(HdFjZ3pYLA7+z@BDnwS}+|oGaNB(~O_> zu3qJ9OPm5nA9L6Ayvpk9o>yO^7Hj6+!%-f&4d#b0d4;E$u97!;vi`#wQi~d5i+ECt zX9aQe;#o)W5b5LCZMRm1{BU_}gVpz?36S8uWyfHSq1hy`Z9YhUyaRm1=#1%O4v~RJ z8d!L!KT=^=tRt5TByE;T45n$GTX;?VqrYad!qtymTFh0L8%yYlk1L+;!+5-@ZLzVj za}lQ7#1+Y)_XmNXe{XPD9QLz0{d&7QfxgA{fAjGc^XaFkx$ zl!!h@7pp;t@EABM@^5~hR}`WY<^8~%&fR!WeMBZl$p$3HiV{eHaK%8$grXsxG5P2i zFv`D0g;k;X!m`2QfKPTmQonWRAaXcH$m>v?^J;oU@t068Dd~9m+0tXHy6xV%Vdup} zUZ*it3g$|5U$qJHZxg>BRT4AAlNeTbYG_Q3F7mitVq^5@dqC2q&D0Usi)Nx#`P4WI z*m;irdFR`2Q%0s5JQF4vg2XC6AA((j7x8s21e=W!a9S3;fz^-5hEV@~Ew`(pBG*P_ zVx-g-lG*ck{W(gO2n2rA1|<#5e2>&hh1JfHk=D&;%eom}c&*WR#}5j9bXbNcb_)A| zl_baMU^&^jsjZ+}l3MS^=}=(>tT`6ZFqNj(>lTNAe*>?a=0~pCTCBN5UE`;r{Dzz) zjq@m1<1F*z%U9Wmk%JL94i=8MIZV_w2W`;Zfh1T$bxxi|gVRd+=%a^UG4tQ0=44BG z^k~IBFG01F&BwF+)qzp1_sE@xeVFU0Gy0u}%#?N`8uIszMJLBIKx1hI9Z8_v5K2<2 zzg$G4(|n{HrRqXde{Rc0uEdvo^TYgE{{0tI?F0l|%K?SXe zx;O7$I|W0aUo`LSlJ7zM8(Q|PH7MopkJBoy_85+aaufw9LD-6LGHO-#tm5MAiP|*H zDv|N^^5lMblJo!|nc^4hf-e{Ge8Z4}-w0i}9&)RE?4#r&-1G`*-bHPHhJyX}7L8h2 zpEW%ipWk_k!B?N|71B61g=SSeMC%`pS4dGH1dQf}Bi;F&OI9<@eK#T+<$Z{u$D0DMcSuu4hG592fW`O4H5~X0 zUa|k#qtsu_lnALzPKj5>6hhqR!UwFP5Z@Dt%@A3U1>rL}Wzdm~qa2>y`EC;HX71iz zW|Q+D4g72Gd)G9?h{D7GvW$u{s8+hsWr^CVX_+2Ug1U{q)^xb`Nn)o{BkNvAEwRMf zK!#~flL}6glc!@t2{|CABbK;NSUE#jc}+-hFKvPER4&?`AFA`4=M^}^VM9;-9oeQW zS_k+dVA(^r^ZtEK1(X84Q4bw8EGf&7KjaQ>nHKn~TdcnMMpSXX81N;JDu+-MerzUu zJuoPu-wWFm5rc?ZcGq8C#8@YMz596$7zfp7eKt7`sq+NzM>Iv)^v&ckBi7YT3^7+w z*#q3bed3%gP0Gu~*Qw9r!Uwh|g6_4^gTh@;(qTb!a@eMC*!ENVf1eC+qBZg2x?TyS zwf0zzj5xacBwpS#OmCZ4Y@45Ko7ZfcHwy>>)}B67`)5^iXH~anVhmR}NI18y5CjrF zRf<)H+4h$;xNJWXw7p09Jng?}U$K`cH>6?!r4N=9f6ILe%XrLBQP>bT>^*`G7~?bt zL~k%>jg^MWySq9f2L>@+jMGB=I-x1?=6s7nn#Jev(_;LnDzzuBLYt|8 z)YnfoV+zxGF;$y1!OA{u!zgt~7xsg1!aeeb-~0URu+73Z)OoQ1H07cJAF`7z#;`4S zjCkL`<&8N_oN}K9+-$%7_T%*&P&9*1wLaK?3Fvl{su0I&7{w zY+5>Ox`(_S!PUr^u0O2?r=jaB6)_G4s)#LQhf#BlM^6HW;zz$m!%8y%K$d`077rT> z!Ux6oGudnd@7Mx@`w^&l6jiaMF!xtDou0>h)XL!B1C$knXmNpl9dhkhheWp(xOg5^ z|9tdzt(;D1%=|3s0Ea}LXJaz|EV0|$ea$eK?|g@Etwa8rpkk{GR_2un)GHgV%V8eI zzrz;RhzSHL0|55gm}^beu4@XD@^T~k?8@`xof%|<&u&S4!E7?Mel|x*NKO*b>f|YK zIt^-VQo5aE_cH$c)&`DPfy>Nv=MTeoI80S5hFdBn+wKz4da}7m!+i9Z2-V*cQmRx7 z-&l*E@5;WIzGe17@&J}@`A^TOO7T_VP_#}NQhJtGO0=wM#5KIJEI8QR`V9RVLNQk5FF#>;OEr-A!=-Lu?} zXX_qAXpLJz`e*AsX~WSe%}!u`RO&_dHxpv6ZDaD{0~qtD)--$)EDXB|zGA86 zhk?K0!63{ryi|$?Eg*vZWljKk|4hQ&HhgoDBDoe9cMmjQ6;fib0D%SaPal3F?>Cuf znh*ROwhnaG4s`Z-I_j~NRGDgSgRw%49ejcvd<`H6y{?APS%SAwx|3}^e&R+qP)HOO z+i2_GGc{$i1<=?7;1&6(g*`Z64(|=qKL7Iv0Lz4;F#lW7wzExd+c1aWw}HzK5#N}dw2&rcamJ$h=b@mbyqrv0irH0+ zxuNLGzoAffT9})z_kL%SomTVxyjz+1Mt6RE!ufBW*MJqw4+N%3W?=7ldth00;CeB{ zO_aihmv@cVxzouVf2|?B2l$YW9fPH86nz}LZ4yii9yPx#&#n?cn+ZFlcPr6KINhLB z?>x;dZTiHUN|pCAp-H9Ka`>RPUU`~1>Y>z3Zv&nt1~Hjj!|amVQm55|J{?f}Sp}w{ zEiG|?M*uoFwa`l5q1qA9sBjr&&9w#(-;QmjWnuO%Y6b_wQUrjM-U7w$uKv_b=8wHW zqfQ2K1k{@yNh2VTDNGk0e@x+jiD5aw6;yRi$D(h@n@5!!^XYg!JlIE-w}L#AcSqOu zW5*Cu%;4jf2d<@`$Dr9!W8ETQ(D8b2YZGHs*75sYn^&b=wO3mXvz}tN`ejDblcSeQ z0$#u|N`r4aQ?c>9r|N<*s+FfbNz2t%Kgt5W)c4P9@qORoIo@W~91N4$k;SjTj>W6B z>vh1u6pte2wj?bQghs>vb8EjXdIV#A?W-EPH#L)8ZXIY65(*ot=AI%W@GloAKvMjs z#TKKzF?hotOc*qd4;wkKto5CbPNX51eiv}>?pcpP%sG|tE>|>0M?imac=KMTN1Jw# z9)~t83BDtQe-z;4$Xv*#)x1d5(U>iuD0mR_8KO2eGMkM?ai0xlz zQ4J<2{TCS5MW;JQSv-`a(Dg=9C>WquqKS=C>wGL=0p`S!6*&#HY@efDM0}dj`^5 ztS-JTnf4#@UXq+fmeOt43?$>tqh690KdO^K$VV$iQ-(W29ineK?hESAgJTtYKNkh7 zJX*hhGXw&*%AISQtT`=SJI5}B)J5FN92Zt7e%M!UExKv&DmooWm7CJi)N!}M6_c4( zH)k~~wZa@#m|7oj}&gBiET^k_K`#i1|8!l^czjDQuzb6|_ zm_NIOSIB1W_WU{BVaQK5t`E0EZQM)_<@;Gfr1QmtogF{B?Cmhr&4`Ae)N|wo z+rh>E+!@1$I562^csAg=>?$2rJ0@CZ8=QwD@zv=w^Y6}Y(k^TWrTW!%5{@J7mcBg* z&%5r}OatGyTX(ivp%xjy6q3eD1(Tp*V-&*VEe)A^CnqME<^#8Fx?9)H;H~H$DWy3q94&1q26q*>s@BCR_=}OR7tFr}M^{e(>qmPH5ce721adtCTCZEVL083~ z#+%kg5TD%NZT&60tNVfa?b3(xgE%7fbZncHLhImacxPoMq1%93!HZA?e)ZJFGyLU6 zqPNY06t14)+^(`^0$3i>g;hfk22%_jrnJogUIJO~RJOJhQu6C*NR=@COp?u%nSfST zYSO6Z@F?z73sbEeqL=k<<+VrS@rGZ3(mU}>Y_@7= zeQ$Xjo0(rq;05JS)-8z{>Y>ZVf25S6Zf?_v`L*7$@KT}eSxdA8ajb%sL;IgyefCrS@`Z<~pD=Y$VFq&N@zaz>&i%EL6(6~h2AUu;Bfc9 zkZ^=lbFD1GbaYAlMoI3EKB-BuqkW(_D6RD(8c+~ieSBo^(P$aLfB*K-Y0`UYx?p!v zR`6XI)>3*#IQsd%vC9I>!D!VleYGy1dmgMiD+(23%yKsj$ao9}Yc+W7tzFRVj zg2Tiobx3^v7r))X-m`Rt;FYd5OwHLR?|WN!>Y(nx92KsF|?ced`j{^x(CuU1zhWu(DIE_Lf%E% z$+EiE%Zc*Ij4yPehLhU=f_?H~xKm_0Z_BsKU+oJK9<_2tTnUfs-jLUWUA0!*#Wf53 z>uaw$_GwNa3Tf?=#&>=tJxv|;+=L@m*1%pI_pOruMblM)RnbII0R;g8rMm=4MY=)h z21x;F>F#Dl>5}e{?r!NuQo6gl8{YdD;s3sU!!nPz>^E=j%)RHFdp9Cha{4)qs2B6R zWmoUR-REdW=dLN{@EeuTKByJ+uHveI?GM0j z?r|})PSXmWXl7Y4_TB$PZDr|$c584dp-CW`!n2(gIGeHM3xDn}#S-iBy8ep9sA4P5 zdDP1i^Gq?L#K7oZ^r$r^-x@}j;zx(|9(~kgnJRp%K_rq#s=7@T3uR9oProc`k|bsIMgXbx4zs9QMq_Snc2I z_O>4lLoNFK%UwP$LoQB$=SC)QuRTw4WQk`-;j{fCF115g50=E@2v^v9Ud9y@y4M!! z^lI0996-?Z@K?;GnA{h;)e+-qOX@JVyVVqy$nU?l`5Wf6w~seglbL5t;CP-7n{AR< zv*%dcSqj@#FFRIK5CpU1T7Dv7(V)d*=>RT&k}`@yT$ngN{c)S)rTAJ;U~XSGgm$9V`YH2M$yl$l2l zc;-VK1n#P0v-Xe_n_iDqdCZQ$5m9{4pVfrhv@b^@W?wI6!+hQuL*FK0jw_L(d5JzTo=Z!Lk0> zn)XM?sk=zUZ?RgBQU5e5&SsgUL>8SD4utDwpGI}v)j_B7t=dZM(;H>itJuC@iG za_!j{L&`Tdj?1-<^)5G4i_CvpdcrDxaDBqi{UMofX8DsK&4tSCeP(}t@YGX;%_R}& zCnhiSXTtIFv#yn|%q@ECeqPTfaUec;W;jP*^j6A>Pg88`1)kT#^nnGQM=pLa$#P9 zX41VXlfp>=HOyX3B=56JM&H|UCU2(-CDS!!#5m$l3%z1W5C3d@e=t4C)9t0Jm>K(g zYGaoYhCz9SYB@_Afo{iS6OFtR7gf*Y=+)}16%yrn0vI$O|Did0CaECbiBY&-=l`%8 z-AMR0Xh+IuZT-b(W9B{!rYv6HrAxZ*1i}qQRJd3HEXr(UuCw5`OtM;AM$@{yD0nqI=q>p?dIIl z@1zU^{bocG6>SnwrG8?+it$nk%u*k{u;^oWfORbg_6qQGzqiZK49XbvRVYg5{ch(D z5$r>=WCE*N)8F>A7MY#X zCEWEG)Rj#YgQv)KWruXgO=Tr?H-)x$Yg`jNT=ImL`5&(&g@1l29aI1K)#9mWrC;+{VQHj8-6w(Gs~2f!XP})8jF6B&AhP{=_R)bnCfkzPPKg?$2i2I4M6s zFV^hXPwA?L3SER^*$^Vk%8!Ma-+mWh@2n2w_p%8(RwLVm54%c+hazTYEchHDIU65IS}mwAtq#~uC^dE)RA^YbUD1x_(|UOjVv(E{-MlB9-WgfOA=mpp*T*lPT6o_tAIS<5PLoCfqSoxAF%R}!Rpg&EmL^rf zJbh7A3vds++h#aTl4}uA@nOD(8pS0Zt_l?-zk=af-7r*kMKN|4L113!kDNE*g5Rmx zYfh1f312Ks{Eq!yOChP?kZ5LYRe0?(TZ#-8Fa4=gVAhkSVea}tkSf22rd(R-Cu`sH zo%9&ku~9X?n0-B$Foo$Zhxv^!9nG=NEE|;)h%X$$T;7b)kpE3J^6@iiYcSo&BY&1< z=`?T>?9<-*rpF#FlDBJ$CJ!v%E~bzD666$EKS_L6HVP=)xYQgIdbG9c1;*P#kkeZ8 zqvoSH?`|^0rGoz-V!}CbP5&iJxDN*!7C`LDUvTVSu`Z8D8KlU z{`-f?%Wdj9WhrhM)tBY{EVFd-woe${maoi(C`g$~x5f z2xyKmj|bDh5^nWX#G@drwa(`W>YgEbdq7wAXJ-m0Nge$~maP+ZGnQBDGqPI0z)eAbKO?L``mF&GUCc5+L#Iz+K{iS6FDLb-{9%?od+lZtd!Sh7&%bUqTcTyqc*|saqrbkxz&yjie8Yfo-rK$w z;}5oHF^D(%tw7u_XbrLUUmE}MVD*o~7bZbgvqD21Xv`f%2(J^-6Bq9gfGt;65sm}? ze_Au9R{vmr>*MmJRp)cUw9O93klWc$i}VCD=HZra*9jLGU2LC@p8V){s@t=mzmdi3 zX-3RHX+{2?lSl6ut{Oazcm2Xp`;Wb-w}F=v_Ks0P+*nRh>Yx?;JY&F!0UPz(abpMs z&)A;lta$@`VDfl;cuFpC_Lk13V8L>bySzte#4vf9D5~iB{Du1-!-j$2mP6~ zo+_|C>tU-a>n}E|rki03~uP(boKntvB(fX;+bM&?>Qu z44yo>gQLV`!3f4Z#>wGT4j#b|I*SI(CDgk(j4x(CEnuWT;btz^#V!b{SSFH60Wqw% zZjh(9s2lJYRLNY~b*2s@FN|Fa9bv;XJcJBmdC2n@I~!*ek(kTNxnK{?;p7>KC;C@ZC@HJJ;J2v*mOXpZgsx7<&>o>)yW; zL!iQH8^b_(T@-@!EfNn2^gx!k!w*MBSW<0&nYo!fus#e{XX-bABjKyD+3^JBp@TpJ zY-E}RH{lVQqh={7e1J#BR%qg@*RQaWNKU*zn7T{?6l5)F#^HP~E1B6J2gE;VeiqQF zR`IG%JD8AZ+qFG}->Vl1?3AkJeOcuE!)lJ-@cInOa09J)E0uR1j<)KDPp;xG{wft+ ztwVzcftwa!UCkqtmDIoMn5-{jK<;w6_0sb%eqP^Y0ARjCv>g^>@na64_LECyOZV$D z+7%`ybDIu=jYMRY`1B^V0x$C_AHp{Cl+d>1Tetly_`@*>5=S(zaRUFpgV#8p|KIWd zNy7hc&8&&vJg+d%&$;H!>TEKJot}Ts%6IkyY8o5GvSe$_bYHekrC9P7#cSNEIN5ch+#)loR{!Dq{q(HCH}^-6qF) zUa067sM<)JrIp%ly{%I(POzgmbN^s2PoKlQqpBwQi%Ebo%spW6fK@quQ6<0bC71

>$Y5K$JU@d~wpeP=x}lxk^HN#At#OJ6_YYCMqRc z$_O|eJSbs?(~ZMjJagL~wTm;(r5D0;2O4Ns3Yi<#$%l?Rhy`SBu7H#|n|c)^`+8zZ zibjO(3Pzd|7V}L&W8-T28m4~yGLL=ZDvzqn(ObIg=8evn$a^2ooO3Anj(^cQ@H_q%CL|)<#7(J! z3xNhGQ_pA#$MHPR2Y(b~k8Qj`$Z-AOaZg0ADdh5mRxcf94$U;&wa=EVe)P4d6D! z%NI;;^mW^!ADQv*yg0G!U(!;uHDc6O!q&`tRX{T7&;L`|w#GGz)K-*H<&g7J)T?Uq zML+?z;+vPbU|VvIbIoG>hvb}fS@op5$$Mh`#`1~ zfjd7D?XF!;O(H7Ro?VU{6$^Jv8X*fy_CRKhVrCaP zyl5Li$gqk|oWPeG+JbN@=?OLOe6>gH*|U7W7&#Z4E3MV|My5eGakRjFSu zsm05?t#Zry0}Su719J|Z$=q|-po(SY+?zy6_GQX>?T$s#d$^Fnj*NJG4}C1%f`(aJ zUW$){3F+erspI+S<5$!@m_smfrV^LpxO7iq=U-GB6nwbfEz}!6E$qwJ@mASaEEF6Z z28+({-feQo68djpzf>5=*fT^oF&S2+-zk4ZNBU`+nzxgJMcdW({rOxkc zW411uFpvdD@ds853h{EDPHHS`7^amueqhHVWciI@y_0C4| zFlHwZD9_J^Fqg+K&I);`zh`lXke5pEfu$zzy(XNxy(9Hm?0&+7mq$`!vogMs;R$>2 z$GJ&PVj`8&2jI4CIH+gJO$0~{_UM^X5kJTkgndwdw%AA_uAvgf-mADH;JPFbWsIYk z1c^bdfrNjCoj{iA3z%xud-Cu;v*F0V&kz!|foDxk!~HbPzcUf&#s)yo@#!6$)iD_cjW1>+_{73`yp*`nPvJ>u%#?_g z#jU~;K3nqnR!4Ed_Ivpy;E)e4GBeyk6m(Y>JN5x(qfuLqUC74j)HK$`4THbT#}X;-eTdPF`K z%c9M9lg$C}wHs}2mi+ICHkV_9M#+I4hnT&&R}1J^gKUsyxmxEtK_Zo6*>vNAvJ$hO z$*!LSU@OC(hHYUv$S%gS4^#c(d3%u-TN^`B@4(W3iZrHqA21Eu6t7#J4}E17ih9-2 zpj6#yc!Y4mN!5wq|6y(kcR>etVINluX!H}7AChiD;Mia!gbw9XS?O%FK>jt4Q3bp9qI7>@3(Mf!U4-y)tGXHe%YeTQO_-C zDCs#^`mJ#1b>_!^DT*-fK^ko&ouitIsm|ZoSmf%>-{yC6^*iguzhKtfbq3UKo$rrb zXCxrGH6^=bgXZ@B6x%f!8*G8(=-v}M%f1=Lm5rNbg%v-mKpGyab+o1E5W~Ahqg}qc zij~W&5MCKD8W4iO$yhXSKbPuC~G|>^EiCLnAI!?&5=#@`&7X#NG2J+rySzg?} z?Ewgx4PGXjJ__Fte2wil+lmT;@8dLZT$ZS0BZLu=I29f_f>T$lMxX+28lYR zUgUgpE3^2WULdKD?GBRBJ6Yj2s*%RgBAz+A!jFn}rJZ>arJZ-TM~Urf$qu(lBW5W2 zc3*AsZ-j0cS6Im-7_s1@bF}&JnE4FRe((Y5gy|kD)>7ARw@x_>_~}BXoZ~rugx&30 z_YM5$CgXDiYYAU!J~xf<&zpZHqVce9)k-{UYC-(- z4p@4#K;&7+4NE(E=ucYYLmJ+6Irg_*MRQ(x1=_q{G+#l+tC1FWBOtdPzv3< zLJ~mHawyZk$knXnoi}zEvEy^#KT8d@Y3o13oyJJC^h;hGN%?m?oFr@4JGZd6C2MmU z)i@u;9qjSbb_qRq!BTZ1&j*e4*Nk2uZ+?c*cNVe$qZ+@Ov8U`}^;HGo%epmw&xfOx zU>7p(spMYTgr*fBjvE0sezWDWVBy6p*r88iwMEZ<1b#XHmJU0I=0mAy@RwY{56+u` zhJ+?AL^$-4K3U{ZPOs9L+^L1q|7`H``(jmN8&0A^eLRlzQeuSFfYZ8D6URmq{02o; z?lo#@K}#)HIkK$>_JBBi$&n|ba(Fy4wJmF6M26;f;FoV)II)?Vwr5m`ZIO>{fY*!r z#p%XH1nc5={j%3WeDEM!NlW>X*D5O|EJwrfRDdTXTlD$X8+d^XBy{;ryu&}qhz`1H zeT{}s7!=>ozXlU3+$DQrw6fx~;pp1xQyci(VRqf z0QtZDcW~DG1L8|~>5~sqzXZXDu>VWoiH9a!HEG^zB|vw^pkudMbI|_Vg?A9ke(2uz zeQwx3zvCy|=&?`lw1ax-6v{#i!4Q+gQ-5w2D542KQusX@JfO_ZRcxO=vMrK55iFBW zkQDQKXlh$zqte1oZEo}Q_p2#@z_AP6-&l>H_TxzAv9yEwW0FYl30~(_dzH=*gRO#fTF$IB{qmd0U-rY1m~ty_ zx-(Wo!k|crJ0#Eu>0c0A*_d9!aVFj@!3$E2)GKN#S$v2-0Mk5XW}vy1(C6&djorNu zef$0kL_Q0=v~jHM}MAejM=bbI3IROi5lygb=8(=Z8@U1He5y~ zj5i!82a04e&zd7^3_bLC-}kcoj6ygbyzO++j{fofj5t=4b(7=juGp+mbIRkRu0_D` z91-QS9uAzI9KPk(`bWFTey1-xMl<0k@to12LJ#PN zA6r;%A6&3K^bskNvzS_s%EDyk3X8<3kYaxF=Rn^s?PG3`#q_N-g@5b~hNz2!PI6_o z*WBkWW>LhENs(|<85{M}TkY4p*gaFnZ~>ff5rJ= z=t%iha2ewEJs)z6;Q06gNkwFtAqseoZ`>oIn8f@-9!#~hYOb}?e?%D1PcE)Sb-orj z=Rg>te)7eZU~QvaGdX3ctmShq*;BVMvjdjut{?^;*t6n#PW+p|0*J=fvwg_m;1l`o z_n(#rtY242IM6O>i2AgJ>V#=4hzHP1k-h6op{$ow_|~M;{r=wP13+@%1!NatX=29W zl9h31gSl&Nx4GCls@CG8yeZe4MnpuE0(Ff&nXJCtdjY3kkwfH@>%T1Q+D`<#W-=a( zdj_)LxS5hVdP}zwPJG9!XG%B3b>T8NiY4jwx1q_9iL!FECd0SM(8$dj7kZp5exJB9 zKL5QoNpTz)AlUr0iSlWiN<&2>2apC8T@mFNjokwBl7q4tCkAhCjqIby zG*}%)zaMCc*Enm4Rg#W*kINQAZpU#U4#A%G&&F^~&{mn{=knfB?4Q!1jpC&>;P}m$ zNvA8Y5J$Lp0UYm=v3xLCLk3#^KoGh%$fkH26o^P$lQtoSfZs9H4k~*AWw~#5AuFy+ z_YlZsW&$*ZK=Tq!SmykXsV32Tu?;yu0%d1%+*n?@e+l5LGz4G~Y zbQCWzQCJUM{7JM?ypE^`gC6>W{c_J6PBxC~9sG2%xu|vfNs<1_RaZDa!mu)RZQ60el4F23r z$8`6PR^*Y^ccuXcXm;;i%Jf}I(FIU;!+&*`vIiNAx#6$A;nzBVnq2_rH^sI|%J=K7 z$_2m*#kl~ip*Sb^&Hb-npFMOU5b7xEJke?WMmL^%YnVkcWkX6Z#LhsH2+!4n8Qfb# z>e4o-C@rKkp94+$#FbLFJSCj4j=56JpR-<;X2+p>a>we<9A9eg8LvM;vffuiu4PT0 zSHVq~+cD^Z;@m`0v80CX+(fJf+(b&`X>!~|l~S*a-t2d)F35Xx*KnAN4r8-{SfXS8CU6XT8S#|qtf1%K3Sd1ih)^zQX1mN65nCr_fBdA@?_u@f_gujXJNWCVso<3EUo+j z{%$egD*off>=T`QDdzzqJT?krlbw%b>4R8*TRVpTiA{{CaLR z2#;&Lym7<>L;anpjRG`KwKxhsv-kZrxVnUV*$)AC^_byM`r_v9pl9Pt%DoK^Q$ygi zHVij39=4B_J#XaqG-98-MI=r8rtRyc*Ks2K!P^x@;Qa&t)}tDz=WB5diJ51}{UvBM zuZyLGM8BNtWO<38AkQ&;Hu7;l3{iRW1pD883)d0#tE?ihX|bFy!ShMHg0bz9EePB3 zr1p~gt}O;8!tM%6Z8P=Lkl?;aR(PPFPdi=E9(3^bxWRN$FCP#z`L`e#9zRaa`C3d~Ey;c^lChrNoO{$AYa^ z9|dy%ND2)(DV&v*@Oep_ZJjK$5z{{HFfkpZfGyoy1y(qpdn{2}O55~vQTnKcU^_c2 z164ac$q(rI+#ilebX*xKe8V>_2%iB)ZucakT5)~0Rd8^2Pbm@k5v3#ApT3B1dh;-m z?))mx)~OH5%%a20lEbWQnZiT*nb0jveQeHxzE%c#p?|lGC*PW+f4%fe(M3calE)rX zucbE1$$!k?y`ClX-qM!PikZ;Lp74EA42{s@x5(IIZqyn))b5Ab1C*+;uc2_*OI+PC zYn7S5K*J=c8!%{0R$K>tNe)N!f>P-P538GY0_5+8l$tzd^i!VeXdXtUS+wCFHRB&4$Y+Y3`bj zihy#y7riE;xL9=nH9`|uN{%9$xgNbtjneDEM^`)8K&fnr{EMm)%wMMJQkFg?uJKmz zSNk!TmIzIr?P*TigXn}?Grs!L>Wnn2@R8Y0pMo)&!`DiTazQ9Vc7(K z+Pg4YN;-^4wuBk+*8USx@3~~R$>~|mtd|#T)qw_dBfQ(L-gA#yi-P=;=;MwPS|t@c z+1BfuBV`@zb<$B*7?Vu>SW4b3Pu8x(g^8D2Mf7M zB#Q>0$`Hu(9DH1{-uh7QpzkPVTLDj8elE0n#H}3n67I!t7B%(hH1#bt^%*zyIbZ1y zocAV9XsuUht)FUjUiA!3QnqhShzc(I_rUoNPNIC~IU;FBgAGJa6r=F(_SVi)MECkm z(_U{N{*A;aKE~VR$-jg>&;!bwc{d>fjG;1-bK{5DvQ*9Q(IKiQ(I`#2YEJnsj#U@p z&~Fd5XkCiFDNI&4Md*w`@{fb7d-mFPG6<{JqD3xE{k=5VcPvT7C4T8JLbJ|*N8~>a zOx?~)zM_E{NGf@1*v3JcBlMk$eqM2X7*vV+KmAv>qXeg${_b8m0f3k==a2f`37nhS zQr&XbcHiC5M*evxM|h!y4UyeXm7|&cdmXd&cgz<%P%V!QQ<8==<_6cOvwd84hpv6^ zueRB{bNOiAll)=%Cs(RxE0vc*o%pcPP@@`;Gwa5(C+r<^C@~uRh%pU!KY{yqZ{V$MLFWuZ>(VbAFQD^d zzIEx_O1!xCp){s1{9o&Jwaq#j5n_;uM$&~Vd$~OIh?_PDldx#jc3xY&s3O8=Mkb;! z7IJ6c6n!wf3k(`V~ve8d!R)FhNkJ+CDeut0mZuKXhqDWMTrPH*t z0(cTN4J;bzjgD*o=gpra#T`a(B*6IpWN&3KGx~!RGU@buwgPK?GYhk&GySP{e3sK? zIa53Pj|U_>;c{O&PR(PSo5Z~OxooxBS(YGH*R=C54a(uo)6;pqfXYdd>q8(is}Lc4 zG~jnJLPb3}Lp~V;%iN5M-0(B!kLla#g$NJoMTYt5oq3D{JjWbJc2em@F|xE0&NOkA z9O5uVEW<-zf7-=zQtW13%K&1I^Dd1`wnoxy1|IssYuavdFxDKDlts=<$r zHYsstHqBCever|-Yt1t`%(&V$U41o3)tBQc2+sPzz-JU71^=2`^&l#U7Az3EKr&TV z2fYw^0{};L3+2ZU_LIVLV7l~f`6pEVmJuJ4ty zOab@~mNvw=B_ckfx>VnlEonc>i1PY#HI$<5#*n-Sni1rwBQPVArWth=+qlrAl(~>M z3@9mG>rll^Zs?d@#bKbq$1%Q@zMY*qmJ5G5m|%10N}$fSNeqnU9IVY_JnR7p`4+{r z!Gm3OE)m86akfp3e%W1m9$#)=#ocGi=>idN7nB{P93kmKR924N#8h-Gwt0{3Oux!vIFzB42PWWD1=N zQ!EZK3|x|`C=h>fN;8uQ@V>PC^{BzoEbMVoLNC<9eC_PYK6Xv5#V>U3Bs0c>D8XGW zsoR+Fu;Y`IJ>|&;Q%hXgL6mRKtlaj6P_2RC__Ez`%MspK_4FU@8~jUra{vNwaSmSu z`FH$(0`^#d{r}$b_;6-!Qdzx~vfcQm{qyG0{CnN8x{zGQj;lh-yYX;H;5@JYvSC-P ze%D3;qnWfV3ySQV!84@rs;;#|1olDjtB^s=W`eN*CG!JZ63#370sXeBaBY@ZkM7S& zTrU!q$=A1B{Dwda_cdOZ!s9I>B8OCYjkH}-EjN7By}#MNKwo-r+i&1zQE=|@ z2G(}L)Aod=(%Hl?@i`3C1USQs-6@6wcqc`9BN#EJv1@Zft3aJz(aLGUNq;iU2<|#< zUt~54eg5G{Vv66dtO_f63VMH<@*@LXmzRGDduWg)Su!~;$tc${s7F}0T~!9|eSfed z&B7NNWimzv>I0<{Mk$CE6j}tm=v)BqpmiV`^G&+)Ti4ghZ$6oWyl6Nc5Z(l$*JXTO znX)M2B%f;mM$vCVvca6Nw=Qr3;~Sm!+nlc`kL%y``ZJZw%bXr2ZZ2^Swb_tMNSV=7 z33U3n=6}qsNX!9w(yt>o#B}_xde-{r+4v89tP8Lr@|%vE&lggcup^2M7nTYeQm1Z*Kqds8I2V9aAD}K61av;mMP^3f> z;+b~@gyCugn!_E1WNqg8FaC*x>h{W}wuD4|RJDGAnD>1EbMZR#s^AylK^{%>4^>$} z+`sO{b4tCKmgcxhz>k!L9S59g))u=$ygLn`x{DY`PYsP3gk1jeyrXHu$0okic{%ZynNLjR(Wqf z3`f88nxB2ITPGeGs1WD>8)VVg5hwgmtDHZbpV8Ei1oA1m?4Q{sPt*nLKX= zvtv~=GH&_e4ANp3dgI=@({-&~p}<%F0|)&&t*QNc&7HZ2euCDN zflAfY{b`-XeeVqrwHHIDM@4Q=sm7NXZD$K*mdDhD_cvPDHCmV*;uFe$_6#f}!?YOD9PfKU8r}7s;pVl(Adu`I-@akeDQRPXb`4`jQ3MKUt3#I$)<+508fC=$gLtkY;2C6;)k{t<0vx-D{FB%3LQ)ACWc?QJb zYHo+#UrXb5h21gI%!Q;=hP9OX; zy|Z4P(4&bvbr{DNbJefxJ|-odh`)X(8`M~{yIPFA@+Ob`{I~VgvlhqGQ0C%WU8Ww10d7r^dlo3UU9;jf{k~jPXBW2pJ<4j!d+O{+aen ztrxUZl`xQWoXFa(9EvQpND#c(hPRX`uSEMIAx- zt<(s4Q*~X-5AjSMRA%1kIch|-&7lK$@Bt4qhD`(@&n(+SFs{GVZfK`!BHKTd692_C zt<Km&LZGT$KMPkA$AR>H6shtV0$2?3&HS?DrE$%W*XR;nJUJw0;9)le5S$xr*<= zoUW${3Fw-1@!v}t@Dmaq!pjgm{afAI04xYnA8WdJS`p1s>JvPVXWh}U^eI$-H#7TM zeWb|NPbg@TqK)~On%$3h9`%QbJA>E_l4`f^r0uTw5LXU}E1`i)#U@zrgXH;9vJcee zZ)Fo2STqLkgtC2g-C_KlR%W>RidUeH)8IDn1=Rd&jXwHS+|69@9jA=t8>YDD>*Ig> zgv$*?emZv0PhdGN=C4I{dv$6t4SKalQ`5EVy7l>F{?4WMYEg(=a{?3U*s&y>o*Ktn zG4bf`w?6EZ7^?B0!H532?%jp5UjmLS=j)e1m<%o(q%qOzp2GQuAu>Kdir}yR5XQTb z4U&oS$-AGucRwAVD=yHseE=lzcOeWhH%%2cOlhk-L(8E!jb*k6aIYo^ldm2$&4fJ_Cu4n~%?Ha9{7`+i6mHVzM ztuR~~3`mQ~kM89hV8zo6v)`9oC_d`4+yTz0N%L+PZ`bGs3T#cfnb-%eye9lk4`{T? zbU2StD69!3{`MG4ApN!;Fsv6z%LmmTee7~Vj@0+snUJG75H}{~xPZJ~50108v%^>> zROxfQ`jkGxaWF5vwoiRCF6ThLKW2=iL4z>eu-kNb(*y@B^g;XY7G^;%6eL8)?zH;v zn}5_O*mwWNS0ln=v)};orfIFp?PW;Ml=1?BGO+^JWrX%H_u&t)P9>n0LQFjr;G6Yw z5U3}J{7n4K7``{h{n*0l0U00fhd&V|zuh)qwsImpcUa&360gGYB|gN5f#8q=yi{w4 zg;(0K@~?OPHx;kizoWmzktSPr506}+8mY(1abMhul$#dR+-Tz%A4tv`xFTf#^4))l47Y%#S+&vGkJj0gFcZ7vi@{gC zhf|L6ZsZw~{x1)gH;;5TtvOs0(Q?7L$(!Xx0_Iov;RybGw1_>1XWXy(50v?xDy}`R zv5EOdX^@(*qVxN*FQTYLiZ(pG!d$fcMQ-<;e@VG&`G@nMQ3Q?NNc@XbT(l5@5r)q| zMFUMWcf;|y-^tuvG10ttGMq{>l9FanOdVA2ET3;jYqyC{LvFjyK?IK)e|*GqC_vN! zxOM3kC{Yl=+izDPQq6#C4AxrrdZ_FYi^cP=K7cTn_U5JjV{y)+N}+N8GUjZLJ*`q> zs`KlJ^|-v^+GOnInNYwvIbb66%8j_7+}p%&*C5s7u#%iLxE%d+^|i_8d9?0%3pRJr zk2)i@s2Hr0{(o!zO7)OnvwW^{sVj3Smawy4l5}<|)me+qISS4_3`=pTwf|nG*Q!AK zq!cgum7XTK#M?;H+2P1lF!heSmYUph^n!_j2I>9%Hvkm7ln&plv~MH|Pwec&Lk!@` z1%sSA4&Llv(!G;9*6Ma9V>b9S=f@H8p33C!1j-;h$_5(YG8B4KWT!R zg-*grrO*o2l)b$=alJAF(@yWb*|F**+vAgA`QR3{)(!JCsXST~gQV93U z_5|_|fTQS#28<1!O50rG5!ra5fDj-2FoxsVaH`Qwvz%A7^*g4OIKu@wX=?@SDeB=^ z)%7;#28&jG{B0+)$=E@d%=FMz;}$P#9%$lQXogTt$H`#HEm-|+>&ozICKTUgAvC^D zOEpz;u*SF`L~RTIJ5!U6%lV`N>(HIA5v6S#pl>1;%#_|(U48CP)==8eP@u@nT-MM~ zsT%w(SYM>7x>_pib~hStYJT44WmaP~PWSi~s-t=_{v67(Opi$W$ZuZxkxYXnEt$OT==%p ztcXPg##^S-2H*2de>uc^pM_3S)EW9QC+v3(y0E19Q%N_htr&$3@X6Zrkw)~AAk$+Y zzbw!!`SV)Sn)zX}0G4T*LchPcDEV~M9#_=f)%5LUAmhdOVVvsN-YnVP7~9@B$IT3a z;IHIk#L55D{`!k8YT<{g817_FF*mFC-635j1#&Lyi^Ne|^-^TZap~u=HG`C~oVtN?_DPa>jJmQ>L+19q3`s&9Sn2R4%^QtE!-3Gf0o+cb$#awiJ@h(TQ zRl*)&oH$bL-fsR9)A}Xu>WLvQ!FrFXCdKs03munPyoG^Hr^oNxpqTP_hX@~V|t7z=`T*58+~qBw=g zk1wb?wC|spls;8Yt~gb^fW1A0=kZh;Zz zeH`zm5E`?H=i^oK)j%TRV=vD!kq8TO1Q~T0Ehs<`VF_P+D$Q&Jib90aA3Zw%TJHF! zuR(QigR+QUOU*wzB`TH)-TYymf%RmKw2q}|UyTzN(3T#_2u}@Yj!k@YYA>YheGL0s zuHF?e1JrHt{23mroSWrcZVbTC*NQ|R{z;{ z_4esSzKmnB`D{a#;u-Fk!KfD3&Rg@jA#qd3VwaNPmc}o>Nn!|%Au1@#LwWE8q}}Vj zjVR@1O}ZBjqZge{w~9u$$N0YHZ&CI3ze{+RERz+|qHlbllkCRecSL23%s>R%SUSwN z373O~bz?24$*9zV;{qP4!FW9N{fv8#G00b7$-o$BC{sn?@v71SY33bIg7fAqc}1)U zJCx8+jbK~7UdP(+${b@Lh(b9LowJ?C0-bQ#lOjTk@938VdJrgDiM_QE?>03?ink&k zt*L%M6L1KZ>nDUN00rHN1Vny}_~jS736t+aD6*N*=woO)+8rpDGBaq@Rw=SVE*>i^ z-r!B{TbeIcvmI)U!F$|610gsmYO^K=7W}5o)-SbQQ&wFe&{r+K{MNGj7ZK*kXpU5k zbk<92fhUwtpMf<{pZvkq;c0o8IO;glqWRBFH&6k(XLh93C zbi#4oPiZl4;>K@O!9GVtNzp1VLHp>FPS$4IWrI?h1PC!HdTRjfK|@i_aKnk{>&UEj z1HjhPSeE?=wU2`SB152%9q%`V*BVRzpJ$hBuU#H|@Pv!4Sp4vt*Vrx&^rz>amm5ks zmJ`m*@>K*nQ8_@j__ru6HR=o40AIS-{)#;QFEOli|D39$;d-+ZPnQ9V28JAYr*i`7)RM?oq{?u7++_Xaa<$Q8BxDw6`8L*4<9PVzG&r};3 zX70H=++d?I&&}*AqbE+@?D`yxsTzx>%=LVXjc)QU5O`C?V4JFj{dL-S`IA!%&osbB0g#Z#g;iEOSHCGw&Q231v`H}Peha#Q5k9| zNR3xgkSY)SP7bo?<=jz2Z9Q%MjScyar>lUf;`_S(5Gm69*MknRSN?gq(6NXPpI;s32QYrV(JTf@Y?_w2LJIs4EvacYa}O4A7eFpAgDm3nSb zf;sa1bAi@^`W+xU%5zkFO`e**g*BiaABy*`RgQ!8*>4%>6VMjEvJur}-e5%I^C|z_ z)*YPTvF$+@%{k`8ciB97<(=e)bu}K);%fN4_fhSjc9n7S?YE$gFy9xdqZr3#}@&m0liq^$d4Q^yPoWJ zDNy&Tm4X{HSd3Nl#8y%AadKUs4)n3WD7118wJ79#Hr1aLty+aV2ihaK&AroarFC1_ z+DO0<-74u; zX*&LPb;f?>g8;%$)cNfz!U2V@JDhi97}4iZ8@6e=^U(OR=S<06ROn<#=6 zi_s!LH@c@+hgpSAGkTl~m3))CuBE$aR$gkPB;bn;0dqYP)pmJ`kF_&(*np)ZJ_N>i z0h*U!Jn5kbs720k;6J_y*C+hZVl)=H^OHl|&GBspQmeZ7R0AfYcquO!P0Sr~4|ktE z(Mop)_^B*=!IhUi8*OsW_#E`bBd2MQW23XdanR9bd1Ce^Nz8Wt%8Tok6LkfNz*+@H z&ILV28vOv@?FB|H;P(M8?h7Ai-7&aiuB7`pMXPW1DXg9tZ@1Ub#;|&$tM_mp$=7&+N!vo`Z z;63b9wG+(ycFkV=%WGF+4bEQ{X&+&K#SZw3gLV7>ErGI_wx}wxMqB|m2j&y&Vsj$c znAw$hR({DAxV1DV0J4#SL|!S#$TCg+Ad?ar8bv=dn^#UyW{tx z^q-?gL7;#VV1F}X55HitgDg7o`HrNJ$nPkKVGx zs*kF!uR(Ch4oLrPxMbF(|2FW;`9vQ!`7fK}F&o8jV$P2`io>-!B~>0Jon3gVLpBwt zs-|?@kW__gKdQ zGnq%0`^0WR?!p<@LtN`xM-7Hcj)qI*OrhpKKI<@c+#(F!SfxUP%G_^rqweEGoFxd{ zhnd4KaVtM6Hzu%SsU?ZYC6rLD@NvphFg10?KVfi#`C>c zz@XaDz6oi?yE5kSoNl%NW=otDYp;}LbGTjPaLQjI2o9)P9%R)9oL4NYuv=SL zWPHhMz+_gOWJPxJ5iuN(eU$MXa)#Fhz5DQgp|?NOVB0!;01%~HR3l_k74v?G?!D0e zg!)gsD-^LQBjD2kUl3BooKMm7DcbscR+h9;{3y-5XKeAvWQIs=0EdiSWZqR(=2Sc5 z(=uN=II0_Odgz8;<-$h8YSSd$a8*T>-n%U4q)$hCGfelo2ev2to5elTRrBpIIIPc8 z-hc%3tYWDV`)`0>K6W;5mT-0(Y7G`<%)D)@9;Tvzm%>6cGcx~owZR5sG#d1kp5Yq2!-u0P~=v9{`(j3 zuU@a`-VD!3_I{*l%x=p6HKZvH7ze8#Z}`hKI@n8HTYjQj{<{}VOSOcqrthyJ5j|9~(V zgP2Ptzg5CMr|5?OBR4-yX$=Rt@M)=_i|$JX9(tdTjw|hbxN!xLs0_!I=xlZ}9&mYAG z_%oMb&}JZ#f-Hgqjm^jqI^7_5-9ya`RG>7yZGB! zj|P+>>s_?J3hJt*w3>;`qspPlj{vBx&d{h)VKV8(otUyk4N~6sj*ZnSig^et{Lq)%6g~^w6i< zTxV9bvh4p!xrF?ba&eIn-%lIC=WOFMDG+WMJLcmQg^MlqBM_iv#$WcWXGG7EPO=1> z0+hYi%<^ADknepi4)$(-GD9`V9<^WbRhkN0ms%2>F0_{x?||T-zE4f=@t61a%N{T8 zzG!c##rIhk2})(CZxS()9JF(_oUD0nc3%yI9>?QtGqQ|m>W7s#@ff(saH1MC_2??tqxvA*pIfV^fFBL)hlEz%WWyUsEm2@7Mk1A;v7uJ zh7=6#7+=JOxbPR6x2CF9*TsgM@5xB~D{pR#-y7(9uDBnowO?#{EfZVQeW#apd^lO( z<*OF?P9`PXZmnz6k z?6yB|===XL2ioYy9BtXN^PP4NH8X^v@`fuX#ioKm6(_pj0Mx`S%Md|Ux2h+U45@UT zyAx))0Q1G6O-oQv{CDR9T73iPA3|pjq3+EO;=kh%sQZCE(Dg}6_8D^Z8O18B8c98j z{Wx6Q%x}?g`FC#fkpJ35@(^h=Nqcb~#iH(ORoOmMi_;C93i1-Q{AO@T;?GWoM=a;$ zUNp4}3L!OnZZn;WnT7!lLbK;Gx_pMoECLJxO{R}l-LiSXdoKhiE}O|dZ81AKmn%=v zlmnL4&fm9cb{`ZUVEECT>i@Y7OBfzCpWT1_xDCTiXYdOt%oxk&Fjc~?;m~&KK?b#A zzHw-ulq(&_`k%+JYI9UeSlg{5`9GtE_NIOlRSoti6N&o~_RFb>u!Q$t=$Ui;5CW9! z$~)_QOLI~!PLMwcOJEz5`e;trDpF>-E?#5 z_7JbCp#m~5bLJi88Y=b|X$C*#x>>yZx-xLx>o`mOay`oVa_HCKvZ#eY$iGt+%&6T5_p! zQt8Y`urtagSo z1^wvQvV7_1U~;8~*d94ch}2)?we(X`51ZKD^m(-kTA>TU6Tx#(rcLmCfhJP0uFy!) z^U!0%WB)xU@vfC|@peXIpI^uf(D=bUQ4A4qp0M04nD)f3`|O#{%THH!_h~VXp{Khk zI>RDXQOQvLs`l&8P|eUTedD{zc7Zr^Va0KA+`j8vf6kXY&x4zT?N*nJe*Ig50^(gb zMbnt|PtD4e>&7F_PkRfb1vEFX5BVA2Dq^5i4^j=6Do zjN@#?X21gN(}JDm%eCUIx$x@^o|D~Ary^xqy)thD6u)AoRi9-_`)D-LPhT)$6jQZb zQ(DfqJ`s_1{`UfjR$O7U=lnT^CLOLZJh^sLh-8?*FsvWoW5|!|+NSTNNN>6ERwNH9QZzw}L|LGeo8W z3qmjp809Wc{y0-0x;;-~P)Q2@4mNGslTc}qWS2L3sf5zx^Jti+uSK8jwb=y1r+p}R zfd~4ycdrV%5|EO!pNm&IQ@10Y`$>zv{)Kxz>W%)7Elr|^Xik`X{$_vRl}Dm{tW$!J z3J_*7Hs~KKNn$kjym;=>zDO6M#US&_kA7}KKJB?$5IaS7dvtg(WCe_kKA;(cb=J}? zsKYT}anGXpQ1`}zN0 z0;{@PTv88o1cscfd30p1)&@8Y_CVVD^zkup+t(h9^5`suyG=eLm^7d^<t*6_{qJ)}#E;Y! zVjQHm0TXUq@mB9%j?XHQ%O<`uM_Qpp#(6^4)-2Omw+_mRyv2(0s>Ymz13W^)$R??T z`Dd$aaX-Gty%yN5IxZMxj7*lbVs{}uvk=%l?Z^=#io9+*DfkDj4Q7L5jkB<#m8N+H z0G{tBOUgsXnvNE?3$t^axWJqS-M$C1 z{3_2i&Iv+SXvk?Wdfw9>7!3|vBSOsFa^#R>9-v%+%S!wbU%(YI-h zg1Ik*9kv!{u>`4W#oE3%=O~M1=jd{?ExzU5HWE<{={Jk@?~cqfkBgFKyqyN?)48qh zw`AJ~_TG89c>iV0p}N=~_^qPpavh)MZIZ7yyQAqc7vIh=35(Xq&fAx=259z>Otqyp zEGI|810Mwhzy@O^s~(cx3xC7=(AJ`($*BEpIVC#RyK1jKf>z=os@YCufj>LDg(x)& z2Z@V6bytJO>g^ldhQcs4k8Jislt%~Wb0${T z+k0DYD0d??Wf?jQfdV%F_TStsAKU}ajP6yf-?W~g-9{P2{bkAe9t>nxp8mnlh#CXg zzQS1{JiJsw2A;d|^FAljEQ@OXv*51o2}Ln-cCc9;msp@bX7E`(eSTYF)7~hA#yc*f zd#H2n=2>l=N{`jxfQg5{lX#ZhwC3weB?{t9`YtKKD24!i0uDkStpfn6G7ML^)V%T73W7u zo=IRaIw^&cNQ}l`<%oNp!>?UNFfPjeK-#BKFx^3qb?% z;gS1%ugIt*k>BUVhkr!l7i^u-VDNB10`J5r{`1{sPigFHrGUcweQgagxiT}oY8c%y zeO}8w)Yj>^x?P1GrFq(_cz>}5WZXfvz@B|zc2L@_K`3-@|FKhQozpGJH;|T!6h3ri zoProvI~=B3locuWemEdg!)$fGZ+(B?`uSlSbrIVm!wz1%f|_2nCgTEGe{Y5F?jr8n zJ@BNrV)%fSmx;Lvt%Lf!!p2;mN>%m|M(+?U?77VJVus(l^Ci+H^$MBoFz_zWt1K}^?7gZtW|DDKK-}>efiMV zm0HpRsOvFKO)>Q>E1Pjph3+(C%6TA^!hn3_&o^Ph0AX1;c`L$lEMk3+-nQX!yYI@= z3FpDP*lCo!BI8t+XMW>sNPakw*XJ`LMtpv3pZR0bQdU)H{QvU=)Oy^6z;rDd@!*$m za#EwCB)87)$_$N3d9BL*BmriW+vg-qM^a^)3(0O=5~vQAb7v_6Ix9Tm@Z1Ez_-j&A|v_u)>{XJ&9;4ww6gvu0)YodnRWjpVpixt~5W#Kf(0Vcq7T(-wy z;<|O4I?w$&)dWcKm`pifYJzU7x-;xsQQ=KGKq+bLRuB`!pMjwse1WJRodt@lfxh2& z=oIZ_+fZ|a+Bd%a2;9k5bKwv?K)hcY!L+v&4tW236nFW*q}r%9jSoYAa94;DN<=@@ z7RF(4f-)VS&|{9e$2kj7+`5*-@Nyq6>;{eK%%DwD54idmZEzJcLh7{It*anIG)_P@ zN)(fpkS|+mb(h0V_#Bizh~)Oe{6>}7V~m;6csjfyQMhlKeDD1sp(|53?fu*!huPxC z<#w`g?nz#^l;j$(mr#&{gPNQG^!F@P(9o+^Q1ty45({m4;ejpjMtc^ zjRfBTqb(dqv;kGA^>L}rl@S_Rh{rfNCpbNoOzM;g;$eu6Kdqr{l^>zupY5yB)-Kz; z@jcLIcjgIf-rP(HFqqDgALFdjF*b>~qL$T#zWtHe^_3}EtZQBZu^d7E7)HWov@Z1V zhKbxK^c?2~1h)$#9V1E?8~&)ymX^b<0^B;fYYpL^o<~<=FbLE-W|w_v-ZneMvsXv$ zoW2|m9zu0Z|Ax20yv2M;Io!Pb{k>DwUWFuSaVy`!Dxeoc(R+2A5 z;h{C-2?I8HJGPgt)V+pSFK+B1)D)d#l~`@FeyegKH>|dCSm8+~APs!9VlbYDVBjmK5h#wjL0^B%aDDGIs`aBY;Ww`dlUcu3A1}QzFSBtLJyv3J#fJ|c zWL(&dS4-MsXePrX@^&Dt!$7xoL%DAv2ZvI^4{w=-Ba();E7QgC=9#pboe}MZDz4@C zRs5FTW}%C-?2EH1hgL}ts|tRd+Y#I~_H@xRQ&WdQxevA)pwhWq1%{8r}>w?}WD5mtO60w)DH^UcqB)Ebop|6V;hXAd(OI0nW;?}a& zil^{+Vu#?Xi#Tm29Gz)_t{0b7jK8iejf=4qL!FSvTp9ENiu*% zaAw2f_EgTv=}Gyg0O#K0`(6H!k`$V$x%*b%h|q-i_t30V-M(>BWn}J0veY-Z*hUrm zetAqMTIXZ=`#InC{i^aR<37&9%a1SH{y9GE)js)~J1NloiAfRgJpT(K+5YK!#*>=L zs!wSZ?T)84I#Y-pUn%7mIFDa^ZSGTSzn&VQRtW{B;-zu6jRj(N?{xtvTYD?op z{vg4iNt<_!}z4(4`9(D$;s+EV3wIU~rtO@t{ zUv9wLY^!XcZcsJ(e#7*lE=P`wiU}P>UW_s!vd^)hma`g9nP6B76qU9Nr4ms~?m6+f zP5P7YIHfFcd`dN7<8Gr;r9N>o*;16EZLYeH8@glV7E*kfFxOh@3RT&0SG^8JlyvlN z4Uzgv2S-BX-Tbap(Z}%@%lId+5TbX02~x$hUOsKBe)8I&fvgw9<8{?d_2hn@HZyJ@@_b@%A%J@^p1G>6+mc~)1B0tlZoz?=s=7Uu9&B z*TjrX;@pBo8rw6l8~wUFZ|3`&$&#}m>L~`PeI&Zai1P_G>{D`>lUS>kvOm;4z9l%X zP)`}BX(CxjydshViYSJ1AC~dHD6&zJPl44e$rk@rE)KIDUe5R zrzO|RC(=G`M7p# zLQVSJz5B1s(zD|7Ga=?u4XLW2Q3rv;a^vhR-X%lc^xETqn3P*BjVj_u%$K_9>m&*5 z$JuJ1Bfj0knR&Wq>_hBsPw0`l?z6BO3U7ZOAZ zEO`D_M{$B9Fd)`J|G%t262sY%GIy%%NIPCWB2^p zWTh^tf;YF9jW_R3aq?2v?okufMJVEy-BI=AiNMN?Pl9HYaryLL zyf@wq!8}dM_wzj8Vy?_xx-IZ`osgaR0{KwhqVy_tvQ4leO9X$cGcFis#b%MsH7@vD zClFqsmbPi3Ml-?exNeF}qx`Oap*qrUXWA%SFR%Hd&0KGLsLCub%z4M` zS{u)=`r?aMfG`i1pa=4x+FT*y(GD-hY34UUp=hkLp!t$;BofiT0gCz`-)9AdlKH6m%WS>PF5vg=;4avWV(gEY zNp*W4INhve?Nal!k|Cp$KZn5w1U{eel1v3X<3MzT*aEAbbVVs0eb=1}$3FhhSwqOR ziVfA=QkKeEO-7|~-iNxH4|RuQ>3>juAC9#^2oCs@r~|DSC^JDZAmtn{VS%{|${a7+ zs_%~{_Byx(j@(Tx`=Qh|h`rUm#&coD$*YN`uDI@>Ww9dOBSpM7C9ay_kF~hgxxD0d z#+$xupiy6MX2O9~Km;|$Xqw^>cAjUHqGtbT#CS=HdBK@!668S$qvNAvSQW`70M2K8 z4??Q$K}uCC9fZ`t3xy}}HCNH0N(JHPhui`BJ_*>3%nT6R_&Rz9TWW^bLN)V6CI(y5 zc-PQ@8|?TC%=msanqy04_ltriMg}10LEA~;zPuaieEz66!U3)8hn8Np4&U2uLAUNl zPutQ%cS#QbgF)T*o#{(2RZctd9d#lKy~qBeH82ts##FU#Bp>3y*s8%t-2({FT=qV5 z3dyBW>(S0Oy-IBpOU;D&2)p0IRZJHFOK7wyzOIxdeuFE|tM!JDhVH*F76_K3qb8eF zy>(*$Ue3_95aK2SPgo;^mF>yh#R+N_$s5r@Pc2Q3NF|hjZU_b zeyzu9H&KK)c7Vfq8dv_?~xYov(7sn${z$&La6F3i>^dz_}Xx>WhosGjc*`3-5dMTBRlEcls_jGOFkw0Tu!$A`MM| z8R+9YfW?K=b$h!maf;QbA7j~ulw%n4tS}sok&>ObR1C&`F>>TRq$m&N@f9e~wNmd- zACX}vK=C)jcc+R$x_SxeCDhA2ZQK*A1-#)Ou2Mvh5mLKrxAcPfs^BsB(=J=^AkjSV z)(8a)iF4z^Y2(-lN*0oO2=x6dP26f+hukD_*bI)yUE@~YD?y>Jx;|jdIAdZm#J!9e zHcuq46nD~%%2OebDFH)7V*#@CVySXD2#9eZe+nM&zH~gp4TOS4B#&1R%S~Ckzpxc&CcW?xH{w;%Yy{}PiS)Kd0 z&czMfeM?Fx4=P0vS!#MJU3SyxB28+U^K_cLJ}0p!v~-bHu{Zj;8_;uq)wsiLb#7g< zIX}}v#aQoNx$Y^E8$9j57=akCg7-U7X@{;LE`RBzHtO44P*Q`CL6BDMGp^czD&%pD z0j+>=+I+>fX)>RIck+@Q@Oelz!GH5~#fPz?9&UGiz~iU@m(D&4>`T-$z!>aAFEf{( zF&MA;x^URjH=t|g-((B{n-UHD{^AYc5T>Td7m?BhCi{M zlPW@`Gn$CFdTJM&%S!7zdo9O6oROSiENo?99)9(d6%r8$waS6K?qxLE+5)kwP-3pX zY7ytYf;#;#_L)BHpJAfnh^cNEL*MQMns?X`U@~9%n?afma3dk?KD5<}Z)pQIb7uN)sE=W;j!u$^dT;t&&$^azabAZaZDZq% zVB(DMGNj_-C`1BC-y{MoLy$Csk@%9nJuQzYw1M|m3~S!#wy#QWF$rEB<8a@5XPX8F?{CVofvv1_M1&~^VTDI?(= zJng+keB-bYD>OfuDxD zFF2j9jS zBV_92R_Ufp|FDq1501KcVJJkZ4tD7ER?O)NsnNS6nrX$^2nJeP{TPwrWYu5_3HBosT-oVaMT9NT`OqGt}b>!&e;7-QKPQ^uhO{IlgAAfIa(is$b7vJX2(xTa;EWwAM1cJdJgE5Mz3C;El74JsL%Djh1D6?X&X&k9z;$bLEJ z49}_(DI7xjpJVurUpArEVzC}d+d?l3KafHc8drBJ(o@gz!JU3R3M)yBSeYQ#|Aa=~ z7GE|loPYe0r-5@QO1v$AJhyW()Lu?U@r+9%49kabqDdvXrXgVE1H^`bYBY}4iyB$! zaxI)Zu>pVn!;HZt-S&;6v4cA$A%%TQE%^adGTPveS)MlnSFw9tyQM(dmqNapqXCs@$`UhHXw z?6GEb52Ju!Y$5fbQ$^YGdsXFKA-~|UD1DSuqh#Vx=QozTYz})(*A`^-f__O zr*mIfi&LVoPXU?cQ_1Ut3LS4(r#Ex9fcnG~OP($B@dkIF(d=&x^f?+

=_Cp zgrRA_S>OB_lr!=j_^k&vo3#*mCZ>1Bb5EVn%e(SSPmBB)l&r=Ema~ zTpB&_#!-{GlF}r91$ie7d2*FItz6^Xnj>1B*jL~g3?sJJ8 zZC?P8vkTT?nlJ~0Z*(s(=d7Z9?TM6D2weWWg2b}p!X}A@p_0fjEp%`u+kJ^W68y)A z$^)$k!6mt_!;Nzcn98&U;Tz8ZqSm_kx(fN_9*vf8>w7M)8!j#=m&*;;`Of^zAW&B^ zy4+*4+;h0x6UIokE4s$GcF#wi#co%0b#B--X1n?sX%=`(Ph*ZGM&?dyfP zTJ3AAz4Im{!ikk)n_49ellGme;DAIgb!_~7u*=BY+R%i-Y@>p=;O3^@S#yFB!d(DI2_j^hryVU<=8P7>s=5dT2LW%Q5{&H`iM#wH`FEcTD?{EYihC zLaNtIooP=`-#CNj=3v63_sxd}>WT8NN0^gYWf*|vT3>U^EBGd;g8T=`U9pbQKKP@r zWV}pQut&gHE@qAsnEsmnOy*e;XE+(b62|(;Bf5n^=<`-eMbb<6C%q+j=KbwRLodD_ z`(I2D$?fESXm#WIc}%o;g+fXWhm=Fq+TPhK?ak9#f!`_`OciiSw0Mc4A1Axb{d>8| ztP|DK7jk9FZ)DWDjA2-ZX-HuGa;aYbSh5G0&p2sa<4YRzpmH6yc)uOP)D{={n(Wdi z5lY{rs+H8rD?y*Vot`RY`fRU6nbuo#X^-vXI9h28BHv_5a1b%T_16RUKIAja{e7S` zrrgA&lNqDgXei6dIO_R_HEzjO?w%oAWE07Tk6TeBw+#{yTqi; z>9jAE$84}I|MQ5(<@=9X7jzQ-NW}OD1m}&}_?r*C34i>3iaJ?|#W8pEfnI5y+whwe z2D2{u^Y?=0RiDvQEVYtF_lAG85aT+}RC5f)ZITzm7d8aaJC2U38$^UCDLpXB@2pql zSuhoG%yj*_taYV(xvYSbkQwO+tYG5!=q=C-J9-x*qV^lx*p#Aj&2{Q=_ENYA&I86& ziH=?`irj*C_`a>bad=lH_IXS|zy>a|{*?Yrn1t?`U$a-2R=IRhXe(LI00D*9%*3Jqrd$gMRK_DFGT* z{%1<*E<$l#Zo7*7WDN4_?JfI{haZ1+5(|qgHJ8$YdpJg+a@(vyEJO89E?8Tq$-2*o zyaK_O%vd6LBRw+n8qr&lVO=VLUVK84?mwzu*wisMj_SgzkGCbM_y&Vw3@~ch5wPGs zB#g-j={e5vVait>``$J7(}jW1ELOH-uZYsa!~4*QLHnPug8CrDSk>S??a@0u-|FSIPRtttmSSdj`5GXZ%+{*9zVQF58k2QAJPAn{j*+5 zRKYe0HJjlG0c(8hB`}_~7?#Z#w)0D}uYHtRE~u6YQvo;cZ6m?tD;v27e!0Ub?km+H zH_w`i1W-O}*%M0O{^vd))|Qu@h0tnh8CAl0xg>R5%H)?Y$kLw1Q?DkN6V~Bo3|ux_VlnQjQe4$bUd-#DX5B4i#xtY+Z`ijyRi7 zL*+z$#P7F^!!l3g*RTzNdi9`zMIN*e&Be{PYhrn#mao=~a3&=RIY)9Xi(6FFW-s-s7mD<(_Ps%{q*0;2(m&Mre>Y}IYE~L(ngn1y_DXv zVdH7jicrkwQN3l0M$?BCpIKJpFI` z-vYCGR~=3h;CJVE!4 zIbd2}kErU`po8NN9;EVPO?X-%4_-X*FfAQJ5`SnMOf7$k5Je2`AgkEI@8Yem8g>X1 zUSl0kHvW!%Xq{k;{%&=IYmn`?XyWIHin5D|^i7gHZ6rzBmI3JsQZhDmmc&mtm~sKm zI7@ZE4Hnq>Xif$q-lV^k-%xi8j27_Y`(%9mVezJ9N7BH@m^IRzo7i!fCl3I+*t&{4 zUU#rHX2n;1h}p~8vivnLekVoSWs^pPpz`mp*s=Tpo>De1*bv-xZ$Ts~#=@WV zmC*I*qw#CLYdv)3nG#%mTl`TFS5;joP`&i4CpQGwvqv!g(zCc>cefVK<6YQuM72Li zYp!V7oWG*9)RcOZ&R@k@0J0cN4Al2ptSH&obT3=0p1iq_)jV(WP5b-*d|f0L`>MY= zuuA2U$P=}|{k5U#D|ZzB3D0l5|BfS8_%ISWzt~eSNxnE0*ZPXVOkLp*qYB$40vDD5 za_0{`aMgh1z6f#j!i@s%;?&9qv|z?p_Ef@Odz}?)9Va;fKq)~DE{h%nE++h%5gYmR zaOd!qtAuS&UfSzA{cCT>rKQe_QNgr8gkFlGv?IA{RrC>M^a!mh53eCrG>7c)Eq0i@ zXTs0&qW&V*dm2+3T104n$NY#X&s)ugj!NBzjpDX{t!ubLjDq+ObEz9aHBNsP+_ig{ zx^Dxd?r)`9aUKj}Q}Dc()%sz9H0R8%@DyMnijQO0F%i~2Cz}g7OzzG3U7V?6HqF4$ z9I|z6Zi4uinkoz*Pl1X5`Pu=69s8{TSKx0Y8!#UpPCE`;p^x(!`467k>BpJr{bKGe zKuIjLx#WwYRH*VMhiCPqZX(?ufJ2Dz-~|~;`DFoQu!Pq?)nO{OK71ekm8QIB%o_@$ zm|T-LC+}EgcAn|K$*+n}9J$n=YR)b3sD58|?WEE{S*v^QbYBZ9b~L1(JH5^qOv7H^ zi36id<8IH^9j}~rv(@It-`@_WXXXqUs|T!~j$di7{vst>!7@sXa*|{A1<=tdtN{x? zJKVZVSnVwOuFhQ}fxLt~o-QsW+!hqQM{-QOWyYC>%H^FOGwRF_;a|^=Z~T#+r9Ko3 z$Fm`b(($|iJqt}yWb!_@xCLP|)0vg|`MgW`Q$FGFXKPc2U_ z$zA{5PB(At2qn(foi;HJQiAsI8^vQ#quK7dCtntoDCAm4~dM)dPkZI*# z6w#EdhTe5;rd?9jQw7rnlegiRv3;gjIxC!8wgLlivcyhrRYRg%WyEB@*Y3>ukLHm~luR0%VsI=;wQwGusy@*- z^6*xn=!Z#f-9zHWFYH^^a>Xofy~A@<*KN^Wqd&A^;o_nHaq zVdp;t8xx`hZ|7Sys)hQeR0`;%Ho8#y8sU360&@Mf?m@ z?hvact_{2sx@ibxZY(t%w6VnR*6O74ft$5P2_4-e%nMbqu+%!{z7p)=Hp;&=Da$S- zxodmpAz6XQ5`QV#gbm@~QwR_gT0zN3^)OW%xu0aunqIGwCv0*Jwhn|!wgVx@I2<+y z)IArN{WU;G`8bx~pLwlQgd3p;9y`%Z?q7@X$HE$6g+vDoi{{e{;V$pF=S&vO zFSd(_4kEG9u4rJgP92Y3U2^^R>d#Qgp{U81pb_9(Uox=DhXF%*bJ0mEL`L} z_X`VY4RU7RnKr}XOoS*U9++yD&+TGx-ag_m*rmBzJuo|8`6W~t;>Ri(9-KeN9%_ZW zOsVIhW55&nv8fO+_jZkqenVljBW>3o$00x8KA)31Ub|tu-B?8&Xgt5wP5VL7f%|Z7 zh~{4%M7;ZzlBjPAEuEkIm>Pe`1!WI~ldD%4`b2J~g6RG4G5RM&)C7YrNFdHb|NQqclaR{x)L?;C4xPG zhoOwP(;nEw4`zh-sD5HJf*E(bI+qQ6NXbSh+G`IFba56@@NR5+x?MS5*QVGXFNTFe zOur-O?l%(PEf3ev{5t{``Ci-fa6`6wk@ekwUS<(Ud6)6Jq{dNmhHv{xm}t1*lRYIP8ml#`bYHJQ{bxn06VIHcmlxKwuWrQxLf3Ey~$w9 zv3H&E;>JYzlIhaOvp+5TPld86Ddrq5{G6i^Ea8cZivTL;xe|f(1JopmjOjp3l2oO< ze0Ev>WG-X5mn-21*Z|0&3)?Grtd1c%Tw1=9zx1;8)Wk=9&-1(^g$Ks-?TWs~ZL^M7 zeH5e50v6=P>sK#zy@{UCYUQZwpsgRRtf~I-jZj9+AZoWAhgQx8Vx;nppu=vmpu)h&1M)ud1;7C(A?u*@v( zMbL$2hi9!p{@7wf1{CcGPAps@I;L%shHp`3=|B`%OP(t}F3lPRyg8cP0vF54>PwwG zqu(BTfd^!qL#RlY%ktx)lCfx&W}L^@LHSEppI_-7x-xj)DgRo(jJWV|Z&WgpZahW4 zNf+o;Km|Mf#fwsdjUbiX1Mlq84TWROX8J{+d~&Sm*7>Wu%k(iep-DB;bd#QqKd$ky zz02=s-7{vu|Igs9M==$}`o-?39rUh!%y=8^j-q`r(TKs2$G(`%mvPSUWB;~(@wKOH zgawc9#0{Cd`P-xK$11KPKdFh#hrHtu4rvJg;Pij_C&i?x?l~6^-(~>dq({C4h|Ju!Es+@O#vb2}L7)z*w+{Q(cA$ zGgHDL)8B5n;pfPhF7GdA($a5!dfVt@&I-YZymHE7^}?EGFTkm)FIU{^v!2vUAB%;$ zw7qYOm2Cm6!oD?Ik#iJw7SMxtH{79pFYibH49nIHJH-G^L!WjRwQaKS?ov3-{)O!ZnA_tKIAdq3i)liuuhqvHEd73$C4e#*Ak9Qe?~Ra%S=PN%)CD-yn=_yc;sDPF^{z@^ zPX9NEb2xV11w)2?Xb(k=+n_V{#2J`jdcGv^oJKF4%C!nPQJg!j*sQJCq%H0lj(Nzx zU3j^_IadB&EXzgKEzIl+^K@&eDvHe|{#-vH!n^?q*hP3d;sI$MuzLJcRm=*He9kQr z#BKCpJOSV4+4=KRUdCPql+mLKQpVdD^kX z6QwArI84$U{OO3hepxG{ElQN)G)M~WIoWgNsH?YsW7$bTjZNe&Ma)0^$-WCOzx(2d zKiYVmyx;##@4qkII`QC@liAA1!q&hEO_UZ<71m@Ps| zZql3^s}5bK?nX2kt0o~_Y{p4^P7&N;8mTMx&1;_z#c>VrF+gZ?0 zC&#^PR8Je^v8R7J@`bMHE4G%TA3CONypr>>!BRR>=aF}jIdm0d1qm7DzQtxAZ#KX~ zr+|yo#2{_mXdFN0AlQy#`m$$1-qId3dNu4$F406i`-yrrIj+7~$$Jd>3R(@4Igxh_OEmYFJa;pu=-2l< z&QnyT7B4C$tQLQ@6(rwa)o#Z3AJer%)vsR>u(fg~D#vF5Kc z#2v4w2t&+D-5gSfOk&OdkWl8xXUo8st|i5a*KJt(Be#%mnQ=~k^77K{EqAp)yO{sw z?nl&8SHPky);QWzE|BbVcxs5|f>e52!6&vm8e*@V7KEaOONXJeQ* z)cr5pgx{kU%1uhmj;-L;9(HX|fZKbG{WSq|DJ@{w{`k{kGfa46FJA4WXmB2XvRK&S zdW?wYIH!K~rS2i=(|Cq6YZ*z@Y_jQY%EK^C15Q;(sN-LM56JBOsn8MAsLhKUKag1m zu2e2HvSNw(7IDv4NHAcYqC8%Rb+;>mN#vlV6S``}gI>&nsm;ra(9T<78ffGil(Htq7eoOj=8-hjzCCEJAIM`vIKq%-I2n+W=3Kf-?8vCm76n`Z^aOIefX z4IA<;(2x5#@#&us?ThBfI%3E1k3Jr|a_1>g|Hs!?09DmR{~9Qugp@Q$ryvc|-6h@9 zB`qCCP`bMW6r{UFy1P3sjpU^p?mHmg|GhW!=FKb)d#!zE;GVP3-Yb4c)n%#u^oB91weIJ#8^xfUL84}NTQ&lxghiHxCF#YTZE?bog zvZt%d$vYwE;8+ngmr5FQQH+}t%>|Wim2J@up?mxpvhL@%Tz;}Fu)rs#tNC}-8 zIQi1f=2Bkn4LoyR@u4XdSl707>2$x-R6x_ZLki1I0vGiidR(%g09NpD3Tm#8)2krw znY$w4SgcaNK1yES{e_{2Z?gnel>3#G{NtoJ&Uq& zQw`MqR6ZA(3`^)Jq;MW<5TyK)zZM3jBx>w+^#iQ)QhPa`UmrA)Cg;9yZ2Sr`J2WB~ zfaO{3TCz&U#r2fuOGL~>u`76QKl3t=Coa^FVmO(eBIZ@jcP4WJNvZE-R}%9y9wh@ZQwe zQl~n6EtbiZkJ7_QRWgll!hK<26!=9R%1p8@+7pSg#(idU7G`Q#zmk2;n2*L(F4Xqj zLIfY7yra=F6hSJ++w6s1HQq4ac)$}PGRxLGL-g*UzvUWHu_yPEf68K^$kDcn%1VeF zh8P(4i`#$sc7k64m7g~ThhIoZW;oP~LUM^n*6<~r1IrvPBkkReJqcW@v*%ZpB>MTH zR?KKqxc5gPCVvKDgy#n1uh~Y&c4BdH(%fQQe%w8FgDR;}uh75z%4c)+A7ZC3{ZFeG zVrSUW7I$7vONX^t$PSMYbeCt35MJ?4V_1qaj;H%?P<&K#RkbkIBu?`@4yvNg^;nOs z)*YVsMtQpNPj64g+N(YqvGb`^ z?Tol4Hz&NovZO+L99`rVRUt#eV2u40+ z6A6@i?3+*OARYN&)tDx-gO$-5n;{1Q#EO4U)qZK*UcZljS}Ly50F@VGkF9FTP>m6- zIXwf!52R(is*YMKp7Kh|(i$A3ARPk!z0vF6u@^_La!L4ZzB36~h-O5GC`#k2UU6s5 z=plJDMa!&aKhdSuSU8%2l*~X9EC8nc$BDF&#Q$ER>ap9ff)$$L8||xFc?p9KOV`3Y zgC0KnRP*G^S=G^Z5Za_ZJum*QndDX40q0>YM^ka`b3lz!HxSNVWVHPYq3Bdg@k@_uY&kf^sCj=YyX@6(X#R1NJI0V01qK=svi-}<0m7Sj}DlRK``Ow zU#6ST8S!>^|G`#Qr(1{E7yXr!>Q{%K^2Pqd&Zoz)uUj!BeUCkXi4 zBO~OXOzX)N6zOOuhNn-itsnz$e?O*q^7d8 zOZwZC-vWb)ik;U_w}h4tgz-{dg?sFbY+U{L`SRzggr6pMEx(#$>B-oE@VoXUktMVR z_itubnk^1UJtH{FSjy5(7k6^s@kZP7PnlcAesv;;HQ$;>K_9@yd}*ahC(N z*B7#J1v8)MpnXo-rvulKCj*Pn57Jr8Z@$YY@>;7(TmL82l(t?=kp#0DhTo(0=Y&|d zecje+PnfP?wsh>eouOYWOpuQMe&rGEK$kpWEi)kUn+myp!?Q@l@t_c3R;5W^M;U;2 z7tB_hOr#tH)=nJ`1mIhoME;EN6@b%JKOArhZlQkH6Z0col^9pb7|;9l!odJaaEtv= zUU*PTM;ETp>))s~R_Ak%%gb@PVi5Whb_bM5)nyK7IJQ$B** zd-`vH#QA1>>DB1PtK0R^n3qqd?k^Mo_{mc;KG*EWx zWpWc?xuiZ$vcTx^SuE8-*mPOCd+KeHMzoe3!y%B0u5BH_0?J6i_nM9Fu0?=Rc3@AU{N38O;q%h4>yxW`m z-JUAumA)3r63R_xrI3&LwmWTs9nwGRtx{7CXodPIq_)ZoMp0#9hV>rHJqz@=8+`Bu z31Aie_(ZxV(AYNE7`d|W^@l09+sD8xlG5f&R-*T|)o$hf2SYdzFr(*he^wjZu#4HE z>-t^b=gyH(+_f89H+U1@*2_V}iXk1PGBtf4>=TVI*?}CRSw8@O zz9E#)6TjXA-}9FJk0<_oW9ThI{L+rykC9cW73dn-@}Tyc)aQR)UdzvoWPNqt!w-|! zNA?_c`{4 z5%!AF-Syu9_@B{+(b^AFuD<87jn|k&w~)_dddAh!EElGUr^Yhyc4GSZNf}t1LiT=V z;o3tzZTnJ)6$VJqo0>pX6jK*iSD9XMc3+NR{TiRJ#HYV_-!Ko3;5XV$ zSKiPV0Z+cw9JHpSaVv#;2)wB^jM~~AE;}2Rvir6)adegJaD?I?P1a;KAT(RfEopW1f=9;gp9Ax*_ME<0*tn|K+_u8VfFCVD)PH96k zzJoMF#^af5MetXc_=9t~+gOTtIHu9c=8$88>veuFE3ChSf{b~U{RS{mPCp*m;b`?j zmQ>O)>4wN$v3(xSyftB#1+3Uys5uVmUG-I43K+7G6A?`2il%RA-MKX8e9$u)lgeaF z9GR@UlqJDrB@4#vAiIAUlhaA*Q>t%z=j4O877X+ZkCLuNGhgPG{%t!Hcr-H`1)c7G zN(Oc~jAHf0fhGdv0;)+J`Ebwxrw3<7WUtxF6D%D*5tF-!;!aips90ZYd4fEO;yylvqu`jq6J$RcgA#Qw+XD=Cwb@J9X zJw}dhY?e{JtL5OSNUr4S9gO8E=>RsD>89K;H4n|51T}VI^xWs4s-SO3_Z)TUpH*!t z;U=Gh^-k!YQ9Q>;SeE!2KzyD0U{eJMho2JH=_Srb?ksBH_`gp?kikxjIaQmd3)z^X z?dnt(6OR_0#e9wUQ_eD7}Mps#jfhO2et`O zc0_VccCXy~0ieLXB0&8do)i(Y!7u(8j0MpYmr^O0mA&%#{i5}MvPcRnxXW6M5M zPFqm&)RaHj0bCX_q@w}0Hp{nS5Z?j+-cfjn)2YUVe7b{%In0jvwtptv?h1Zk8t z`wUAi5xa2oYJ~Nsa1=gVKj0$a)sf<>qorGELK(hs@^ zAXKokWf3RAr1H-Vu7N1)F<99^76&m360FmHkNJY#+KR+Zr|b?IAz z;03>|18y}1ajrONT0- zuDk-~d}^HvDp8Wfc>*O0`E6j1ZQcRxTIr7P+EQxTRq=@6zLI@GOHrtr)9ym%M$-3S zbW3K4pomMHLtT-@4bJ=()1NcL&)c1U7s7|@i8HkL#m>A!_HJ-IXCi;p{mougr&!Tk zFe4SG9j3U#(_?k?f9b@sP@Y%T$!L$X^Gm-0?R<~EYp|>$;S6X(3PTT&3<2I);cCEh z$@YDZD8tW|Wa5;Se00N#Jj2Wv|2+$|>p@$Y-?1U8 zxc#Yvo{lZDyS{|d(}}BhajC_{2uCh8WVOx7Y06iHm}pS?8-4m4rqW|jsI;7XhnvYa zKfrdl5hen<3Vvi_TvPv^IzNNOj4uCZ^R@*yMzF!$b+);{hgF9Z$jgU6?=1bJS~c-w zJJXe-9n#CqZ2SD{Tb7kBSSC%$gaphL~A)Bk!p2_FeHq9`jZwQDqZ7snf zK4=GDr#pqtetbIu|FdcTU$*jDkssfPEe$*bO(|C1+go|$67jOd7vwjXpts2txW8Af zOFTF$p~ukP+^1(b8car$MV50hNcB5I_~Gv_{PS zLe-V_!NfQmG`)h=EW;U1A$K!iMCrVU(lH^g#fj1(=ynn=^Aswpe>2TTHf=3Y#T~V~ zMc=^UZlY3nYP~Q=I*|c^7L{Heo@=k0NX_C;D34N^91nbI97~Vmz*~bH@S>HzthX#f zlnehmw`=}caswfX|i>e(ekS3F#e}59mOOC}>Pvo}oXp6tDfapci z*DTEV8MU_bEEz#rQES1v&VMU_NqI0_B&L5#VR#M-sIPKA?1CJ0APr*L{{)xp|dlQ8kRtUBZ=iQQC4 z0A$v<4RxWMdgZq%dd~nmw1XXrF&m=Disos1r^Vknd>hj{jE{zs4)od5Qwu+1*oxD# zL`ReeSh85sLn47{TdPTSb?Q>dI50RnD_F~<^39wc(&e9E{D1<^h=z)YctrD33=UbP z6_oH?$;9`keI#jc;VariZ0N!8=$GF&zNe7_^s#Hi=g;7cxOkgC-07f&8{K^DjDZV< z<;Qk`ECL*F>|dWgKioc%QW$%C(VO#(DF*nYV1#DA@8Hm51a2L)m*$1Vm;O%g3 zZ{G`aY)94$cKQovlq{DoryprET)`&oXsFc9h)D+B;d5dC<>EH=!J*UV87Nkf?M`p>nx3jF@hbJ~U1bI{+k z{5?Pl4hLjIG1ydERvlX-*gPyea9z|CI@yR1v#?c~v@j zqLIw#-aT2%U{Gi&ick`EupXp~Ybd^u96xe^#S(#OsP8WtU&AJ+VdHmAiu$i1l(6b$ z82eRYA}sl;xF}fH3wMI*$y@70C_sNgC{;(ZlURPJX|R}=KXsyLrt&xDk)v^M8>TQt}5}XWRg{} zRSQt=vV+P%sQ1dHet08dTj(rwz=T@JFV(JVXBFAYw==2!H+j zic>?DZ-Q}RRX$A68(sJVi1N2MjC%Cl4A0nk^>Lf_fAQZYZTU0ULBbgb6&vth!vf-| z3!;UY(8LgUn6*D-v}%mkVha>(E!~rT0WC!o*FfI$Jt|bz?<$#J-+}c}hNb$6(QE5W zUiVSPXqahg=OT&5mDZ2C4A{kdH>}P(@*ebB!|E(hByOjC4yB?P@gq2S_Q8&&BT~2p z_@SL*ryXkdOXNilZf8HvgT=&n+0{O}c0_Kk&@0I&-%V#hk~gUIA*zG!!{J8YnEuDn zP1mS9r(tqkx+po+ZQv6nd73Qg*8YHF)-<{Db8`x%AV>DVF2Th0Pf;y&hv|;&l7~T? zHWS3}4h;0gyFE=CB~SeVgAX_W$j{w9EY!G@)Rj3fZTF_yB8P&w5^pOlma4(BNSLH_ z(NnXK$Nt%PkN;$kAtI;(j`h&|RFxZ57mED4IQREpzVf&IfeTsiBJt%&m;9GX4WR`A|JMkNy&akUH}D zFeWLEo)lQs_>E)jZrnqmpVu9qVaYq;?^jioPOD>gh1EBJmXxB-ja5_t^;1vve|Xt5?Mn^9mD{iHV8O4lj$F}{zVQh!f6@GwfxKb~ zl^_131;oKtJSK2ViuP7k2}Z_h(}3hxZ8Kp{u-=lI8tft@C~x@(LhO}>vC zs-+G_SvRr+dAzz!TBo1V7Gmu*)jBqHaOcKEm9~2#;P9GjndP>7IP2+zQKEPbO}Q29 z0!a+60yA@;mZg^PYq`$qWe%!6S}5U{B_Z;=nJ$nX&G-nMTpXqY_a*}WoQ44m5gy83 z+EG%zWy5Is$Z+=qY1E2DnCcpZ)J$!-3ps(B z>zVK#sf?D}?URe3<{5N&EuHb&msRhptKyT2PhPz_GT^`PSnr^!L$1JmFLAx)0=nL& zlIe!32ZZN;wnak0XJ?aw-r$(jf&CH%@Ug`C7e(OMsy-ucV#}}C0)(-@d?wM?V#Y@( zG3TPM$w(}OS2k$kl_e>vwDg{hGR8}eTOwTe{IKYn`Lvq(X7CY-O7WrHyRN_9l)6Hz zRtNYZ;0;UNLekTXJG!bOtBt-sqx|3Nm5W7@0C2w4yxTD*k7v}i4mTcUdU9wFbZ6X{E z-v;aCbBBniI&E;(9(&@Dfa* zN^|=uMFJL~KpTwzOk)1V;&)#nW_6}X?()wpW+K-_A#K{Q;g5((41tFBlwdmYy*-vb zW#wK+YE<&FCz_=6x*5$ndn)1s*V2AJ~NiS<-eZAlzlq&o1LV0bKD67_*Aal(vq^>K>us$O~4DV*qo5)F$Fn;%cJ9IlY9o zod&ZZN1JCJGrXvccbU*Tss0c!6Pj-~Rlad!6ngP}?_!DW%{xH7kBIZ8P`V~aM-B;DJg|E@I85}iX7JzS;aDWtYUnj~A$zhS=IdYYOv zpMGOdOG@)tfT4lTzEmeN7#gJQp+?@`lp3}CQqx0i6`aL}V9~(qZ`A^%ijwZF8;?0c zM@HYvDA5_U@JaK1#n9anSQC&TiA2~Q`02PZ^m^l-R)(k}5x~}S`2HRL9##MMq@cee)4_r@$293Sa&hxs4JCsF=TWR_WXr+VeVq+To+mIw2uRo zl9=oHOQrak8wm7)4=#6}mQVi?uwcv|D3mqz*NjT>Z@TiG{c=NECl0lNExaqd)YFS( z3KC@Fi-kWAObYF^$Y=_(;+y>n~Y1$Fn4h`DDRe}}Gnhxqe_3;YN{GoT?YUIVVL9MYU5RzuMM*Z79 zNmk&~UbGQL7uIo?`B%ip$h;$Cl-*KELo2F7WZB5~nBx@6ZcP(KAh*r8B_L>1tK;|z z(3WUFzJe{ul$~oOvdgXfma4$SnsJTj%r(C^(_d|$A=#&Vg+FuwQJ z=auW)8Md?^gg(I)CYAj2zVQ!U<4lU)E|~n{qn8O66_fQtL2X6t!KFNHE(EPnUBl14 zy1Yp~t8)lnWn8Y-`FQ7S1C*Jx4kfqayaUHGDRCECo*)FrW3AuJ9PMz7oH|^^41!%_ zuAqHf7TQ?y+)UlBuMIoKe|;5}ESpMP)t4ztYwsEg)b_VgtNu+3pCYMx`voJ~&L(22 zr=>M+_-~o=o^mIv@N@`wW&i_@6oM(MXh!dc8l{JW>m1U{2$YXumD-2br`nu&Tzh)B zaHNGF-o8ES3VYOe2YRdI-uAi!!_B5RHiBTds+p8RFEH3W{l4C`u!B~L=d?ki;Kf{C zk#Dbo%7$XoB5o00KDjsjZ+g|os7Jh(uk%;m=qZM)SZd&hl86pC*OkF+US*T|%HIB{ zu&Y7s9MT4!NsGNmyJqq@gm3>_7xiszfeL8iz7vta;~Ken?KM&!YuPcqg6i&XS<9Dv zwyZY|rRVMWK4y4Cr4FLmE8^Ydx>G;Sy{L5i5-~R-@ zHFtms73}jS9c({Mo>RJxT@{SKj_zNL_}5FC1Ofs(P;vC;=%Sv*4MpRl6Thfp22R`f z^7vmhDFnWj1al4!?|q)@;f& zx{SpioXE^ctm8Wfqj~UBMC}bs7I#e24SyR+NM5#S8`gJm=UiB~FNfR3(YX?F!$qqm9DIZJRAIcL*6OMvsC2EsazY@@`y zrxtPfuC6~=b+20B1kpyV;i`mNSglE42kFyu1L4P-zSiG=@sU=M3IvKhOA_KK2=?w5 z0KI7ni;N4n5BG7~sjDwaXhcDx_}3g)%(^6d{;waQ%)#$~uW8A=aT+KGQc|lX$7%nZ z5?7iOa}9JDZogr$RZG~CM`1_z`1VZxWTjfZWwGw0ZhcX`rjGl`pVKYJ-SMsaiDJuQ zC7on<(Gmv~^stwc?9rSuJe;zrtVPJQ3QxR-V-)&Ns}_ITCU)pAFG}HVJVW?-hbUUE z14dB$Ec%eLO<4LhTr{1?Ny7i|doH#~eop#os5ccygn6A}O2|{AuP@9UW9FP~9zZ5% z9q~==NfsG`>#B`Mvh6?I4ux|co=$gAxJCv~L=D77?D(p2K=r7fZ^72f*;i5{Mny2a zF_7!UuTj#Jyf@N?K8ruQ(7VASRSgLIoEfvE649Rb=E3s4a(&-pUGp_@)Uv7~?tRoa z|DsHljrb6qC0&7jeq+*nQHUIVe)|H#$Pf0h- zS82a?^>d(a>HtM^?c0#9 zXo$<^AIEPw*WQzkVB^S9TB>iStk3qL6KE~}4jbeh4LYOw64Uuw_R=Ziz1B<7>#C`i z{PRY_>UX2;VjgX|xD|^p2HWvm3EC{*;>lcnmrsy26LyUcA}h3Yyvt|3RQ`JUtNSR{4G z=!b^v_Qq_D)}Vfyj8Fx!UDl464;q3W5Pd3$b(a7T9Zu!*jfAKb%p%NTxf?Or|2}Ofu=0dlocD1nS*t6pVl6^ zz_93mcWBXe4#>cQ+IxvdNZtM>u%F&Ow0GvBXk6^K6 zK#i%%X;QF?Y=3)d8XH)IN5Fe0JL_9Iod7`c#*DwpN1ppOI%fObXyxK)%w1NGBs*XH ziRQyOWt(KVL^T;iC8Wu>&RsYq!LnXpQrM-!C9CsP;jv!4W~pAyJORn4c9UbhUKQ?f zwCkLZA!?-n>B6bvIcqtkPhySyYTV-wXK`THs%N)FQ}cJ5^MnmkHUO=bVZ~JAf66w>WXcviCDqSi7{iTXEu!gBhy5851<&n$koR75TD0;50S&jHd_D`Tp;k zcpOr(E5~u35}=9_Xp60~NDaSEP2uj?oRGd|KB#sRqO;k%s@|4V=rHmq`sLAf+wF{V z_0tfzFnfI}O!fQ!dL7!)HWw}IhfcsOD@mhB1r216HA(_$b#) z7f%{u*%B`cI?h@&xwA;a&^ZdV883)60-Ppyl?SrU!1=AtfIUWL#o1a z1k=FiS(L!$FzXlol2;8>{~jLH(yB52ZTjoQF!#3{{fBu6jyAvxu?H$$F?z|K@>Z9rnir`v*Su_3sY!r5kNam{`YUdpd!oOZ<-Mo3R~c~cgp|l# z{EY!{(@ed|Y}^Mr$glf}yiD69p>EIP4&fM2xOg-0J&vgI zsGJXYYl5NOI-lhCmfh{KAPxroSMcpO9Otml z1*e~3C+-EO*TJmL@#Tz*iG%5c;MbkLy1o)lpA#WX2z1S zDI)8qf&8*a$3C;Da>Eyu8q!tA96Oy;e6H`LsKRg6v^UNsxio7~F0k$NJ3`EV((W(dGmQcRuyu$V$fGvUDt2la7P7&U#B=*w;JfqGg{thsmeJgwo7+hCE!7#}ft* zpPZmFq4(kR(z|4Qk8&5sXG|y+CtF_KX@h8Fek-l7EciZ{CldL?{UC_?SDbYN@K#xs){39_XOWP9e@;;KCx}S^7J*oRi z1e&Ls2DCDZfOS;{UyVZMI4o^xwex zf2MAqhqdIpB6;Le1BlTCzPt``!v>ccY(d>YgEo+3Le3nKCEfHA){t%+R=;7j&cC0W zsgO8A2E<&cYYji6U?PUdAqr@KFo1B zFqL!N_>5Q2@kzf=<4d9K%#EHurI@V|fpsRt?6c2q1~m0~%a!s!liMU4J6V*8&1@vj zTO<-vWSOQ;Tg6Q?*(+=&>RjR{>da#(Ou7w1&Uxc+KII;9)L$hp?8@q0-_y>+01BLD zIRm4$jhpie#~$3rS@f?VTYNs_%d;O6dbm{IzRsV)%-0N5Y0H1X*>9k7q+Y3BpqZs! z8KW**_h0;j>P`04!1Os`%|x|g-{Hpm(LEh*^dH^Rp{dk4u6YoqYxOl)5P0Nhfg$zJh=3_(6w9N6;XD( z<|mD;Yd5uP;1-#awb}c>u87-YL2NAB?R;YU5iwKNoolc9T}nY{HJme|v;N3M zrAc0qn-i?)Mae)Nd$m@GH=LFZ9gTi-ZBk*Zes1OA;XRc-T*0`$WhR4ECQumL4!O$p zwsJzVfJqm`!o>58jpruZj(HULj&VbEV+ZZX#bTg@smJ(I65>;5_y*6Y^ zf)t@PaL;Tx{Z=9s>fTGoemnjkHGHtEJ~c@WOoSCLwofIa~-k>|b#{R5gZ@VIzj zshq|Ied2r~yZKWr&os6g4pWnF>u#-vlb18Y6q1W`cAmR`N1Pa`lN~=x5;$h#Gy|^X zVGJEOmo|htn{RC9?dt8I4ch_g>c7?V9dx##jm0(^)mjVX;=fMzd>;`XUBTI0)neV; z&T=&ep-~;bjFH&V1iA$P|e*-|3qb(S>`-6GD*1?&vWBKpV;#9>QP0eYVjO(?tN$uX^z)EX( zowKp>UKe6?FtK4T*lSSW>3QlHH4?>4fcXnM^>C(ScJrXPfhN-P)CZ%nm~*{g@D!S) zp>{mtJY<4ml#AEe9z<{k9gb2Pl*?*y>KIGV_AUAIkq{8_3w|an+N&;S(7vphVNdls z9aMyiXLvh*QZt86!sQcB;{6BWYo6Vvr8TO=MJNA)MolN7FePp~5b?wBCI0D8R+8qz zH-h@a;LhC1w`sEqV(^u+9H9=@JdKe-G_Akmmb80qi;Qt5?K$rWXHqEeTcE?+R^a#R zyDC|lBak^DY&s)|u|_W{iGyj4o=H?`Cc3x{GE=Mu8OQU#EijL@^cHDZU6#l9KGTJ@ zRcd=s|IiMx^hPKWMUR_n|NXikU%Rl@?ydbR@IZ316pdMbfsbB27OwfV^D=+_T)eQk zSTOAuSP`Qm8!kjtiJ;?^CC>sp@J~%C&hyix!`7oizF`+{oIBJT$a;M_Uh;@LISE8g z1Q8+X8~-79lR56aL&tM~fMRO7dFzRqpUw$(tdQeO17ayEVwzSy{cguAgFwO_lPQ0L zg4rm9M@UyqWPG9Ed*J68)TqH!qTU`*@zvP4;)(DRQa`x2RrT{gsf_!w#I6wHa(vdS zQmQcYK%4}FS*vF*P`#ohK7a{m!ARZ{&rC?A^s%;$2NG$}**Ic_;w_NMlFEHg%)rVsfG4cR*nhN* zy)l3IgNSxeKg+Zkg+||#m(FSNPgj?n%1#7|y}8qltvbiz()<^H=chyy$SyAb7{{kX z3-^rvznOdH4HUjoPzva8giRb?saZwnk;Y0GCwszjkfjcx#B2No!=q=6_eZ0}S9!f* z8)XeSi!l!^dzNe_HaDK@Zq429LkI2dv7xa6yVzA3Wa8BERC@kS6%;(B434MU^V}ZI zjw7o54w`I(Wfm{=Y{$vZZ9SSrD~gg3(FycEw_RWKuKBY&%Fr4_$~xs|gI8?igU29O2xi-ZPf(T zR@a$V49EE|>N-1b4nJKnJhzWnCX2;-1#PTz4%br*lXpI~^+?iKme$3w)VZqIOU#<4 z)l_ZU`M77m;VEj@KT?M7?IsLVcFWTth)2mg!v*}LSSYea5XUT$b%sNiG+*|2_>=KU zPPanNS!NV*iHGnf?x|5d^%P#>PQutN-B$KY+mC{(U=b-pdL(hMCNxU%b&(E?OYnX?BK2wk;B9fJpdebHJ7f z8VDKW(^1Oub+%@K&V@Kz4{&qbByr48W2vQ-4{v=JluWn!e!vxaP|EeyvYhKHdh_|z z_h!~-xejQT2pJ52ItHN=eT$sOkLN3fr~`$-9+x2M2xRj$A5oQ zkS3RvVTYE?9FRzdsAzcFQ!Cp>2GWgKE~AU z%tkg+Ugu0+zI6se-LH&V;U!PPd)^cIIvlbD@fTV1zz~r*GDG#A63rm%eYm1Kli^6? zn($axFHbb=Hw|M0nNRELM~Q~^5qe%=756lMz)_A?HP+f`FqO}qeIJexo@bir!b&)E zo^=+#e{@of*V#t(rwi(2kAcm+#?CIoxj}5p?XO?yKj9Q*l>+ihr?%S+AZvO>Ug{hV zXWui#A{*6V|Kb2|k2Cy;UNaVGGG$qa zvd$S&tV0XX5${ds5CZMWn(|9Wa3_7X%tEB~Gndzsc=FP{Oig1OI_UB#mi;uP?aJe9 zn4z~;-LXOJS2bSUGwsoX8#%yblio!#TPY85VLu9`ir{+AC;oFAxlA$m>-__ce{z38 z_y)Q?UgqY8_tefKM50!de8Lb{m4|fqbtHSZ1pSL6-|7I7z~WT#U-P6RduV|u%n7n+ zo6~5q0ZNgh4oD-YGGz3fZ|q7{ztNA*+apPZMI?$5#2JG672p;YdF$2AePsKqls#EW zRMI@kRGmFG??O3mT`4z7Hq(Odo-qL#c`!2RalBxpK7q~D@It;$5V`MLKp-+(40)cB z_2l;&ow%Ceigdpi9*3771?qT>twD=A#Yqx3UC+{w&I9K2mpD9TBFajdH1p4U{8~Kx z*_6;-pjF1byGkh?W1yp`qvHW`7wyO~CIAI4DoE9Vm!Utw^J z#}p&_Wez8~sPLbAnS;_!yxl8M&kwypmngHQEgs-cdkNqYwIEW2{ryGLer`s);CEI%F^ z7G%~Ejq5NAJu@%x z2A2{%I4Oz!x=}k<{S6OW-*Hhi$tOK=LTz0Izi?RhC?rW~zh8^cwK%L!O?Y8G(%E@+ z9@$mt@Vn2V8`~<_B4e|Q`=*}-FaBs(Q)A-G-nLlHhIWPrR_JW{T1C)@8YC8-9^P!$ z!gOg3(P{4c);gb?8syS|VF7>M^YD;We}BfcV}l^lVjmYM)gF zVsG@oU-KJNOLr^8aS3bC3;(2%9*O&TOe4HWA-w6}CuGb4p8wU$5`}}Q{`#T_{%2pQW{1J|I3z*JjQPTUQ0I3 zV?gwLb`1fjMPIVfK4B@$K>+7zWXBt+Qf0$N}>laCVo|AX$E=;#@aZ} zYbYEPxCt?~qPWc1R{o{V8nE3~^6FmE7*K|q|JGwE*>h>HFLlR=lv6~#n90a+|6%UN zAK|_(^7x&#o#u`KQ=Qn^4Yz^IaY}@7g}WD6!v=IyZt-QUK+IFav9>hQqdNXSC=5%g z1^$3_Vv!?Qlz+L!vC@#BNKmCnkS=L^GEzMtT_8GUxQZ0mI)M9>>BUW$cT)5K4g!S% zi19O!dr!eBIEv#NHYE#tSmCOVIkx}{zZdc(D-LXyJZkLb*ME{gaFjmQ7sI?q1T{%) zsdV}O+^>bE28X$Zm2nCq>LUWoM~Ml_WkyI~1>h*DCo#XwxiFOIa~Uj54SK*D1VQ5h zJU8-!V~f(k>(m8v#B-Q*q)uYOL8i;$0qw_LMgi5fgLJyuv@4ZyG;O@VR(DK`UE%`j zt5WIPh!i?dERHxlZdtr3_ z8mur|ei$JjL1Q0!BfD^Lta6kZ-_VwVDF5uk`wENnk?95Vfj_By*Rv8PI`p;YK^Z0J zUUAOVzvZn>4bplLYjDp*NpP=LsaBcyl#-^h?S-s6Jaxz9x?=AtH{%6rBB2?oEo!*C zaS{pQzlap-I1?7>C=8I{^G_7wv6Porib7EO6>$b^&^A7lw0Ta-xqnS^=pQ$R!vCUe zP`}_+$`^ZQRWlCN0Cb|OWgGNZy0cn(7kMSj3~5eHY`wFO*>%1qvnN%_%$V zT)mu>X}KrI=htP{+xT#`eVhbQ2m~8m>?>Xp=E61a&&u)6gac{99r%;&`2TIE0K|pe zqA~Ip(*=JJ%rI7^>5SfJB3VFAP*JhnQ3=x8 zwB6C>t!aVUT=iyT2YI0%!qBb**1!T=KO0PB4E9l^J^4>V@8r4G6r+PoW1pf|qT#JE z%9Sw+%-HXS+3?a>?83O?x)%w!GWLTpuMn!fQN8(skf5?)x@Mgd5`s?X{ba&M1ddU@ z>5whpM+v-LYSUy1yzG4RY4Y09wRkz3h*59PP65RD{kAiW=?%k?Mx!$G!C^t)z@<)B zxmUdX1e7`LgznCMIjf}ln6JK+DkS0|Sb%nReMNYddYEz%oC}`q7@0&H9Ro2;g|~n zSBte)GDs|Bw9UKxlCMDPOFu9DT*k@9z|S%4wkZB&Kd`Dh!Nl7i>qH6ZCsg(3{7E=n%L*ijtQ$ zhz~1gC73<=o#BOl#tNW_F^N@7sykxx9S*9z?VaPfC;DD(-g|o6`|G%I+CAQ=+fE13 zmd*z8S~6y0)Wjz4D$R+gneYn>>0V_OM~=ZU?zkWc+Bb4^+ehSG3W^zhB#P@@4YZiw z%>G&?s+MaX5B*5k^BuO7cn+&eTTe7dkY?^r_(LrL7zIf->wm!PUfgizRq7M${zQs* znRJ`|7s$KK-U5Pd{kMReTmQdzmpc}e-AzD=Zm{U~k&s=$W6$>GY@D?AfFTpo3>(A7 zV|>tAgwtZK%}2p-X2|o=LYwH46d)Pi&K#zzj%+g0MX$Gi`XWIoW0Gc=j)oTaIlN6V zOb1T^3Wg?4R2dQTv+0A?LTZ(N+kKi1?sv+Wz2=qoa8JaO!7QbDQ6}w+-&v(IhT`~C z{GHR%4etJjL|#k6XgOEhzRLA+r*$j!PK%By zT&Ilhj%t}h+)7qWI#jjD*Wo9EB<8NH@gN!H`E==OR%B35pDIlM= zIFc{>vpmXk?}oLj$vT()3^yk69_5Wpk0Ar(5Xk{V=|)OQT12|L zq?D8vkd7Xn4w4CY+kNb7a6!+W(HA8W~|G?jP}bnN`)hTO#j zr+eDh59D5PkNyin8X#GZ;B)8Dlnp5sGV=c5(}F1ho1+^!H)MyzEs#C2D*ShI?f% z_$Ya%^sP!X(Ij8b3XVAI=ZED~$E$z8&$zIXoip9;K~MQwk6FFrMh|ZD59Ia|&Mikq zW`Nl8)eOUOfaBDyl{eAYD4jsDZ7}(=VED>I5aVEE7u>it80p z(MyGk$wQxgGDNB~ls?WuG2tLx2?!t1r(9s-?F^X<}k#v7*9VudtJoBqfu?C3BylNSmPOc2^9FLgV`x zf2Vnz?Csb%Pa}xnc9RHAxZM~+70y11z`sAK-rpi+lSr*gAMmjX(Y0fBX65PrPFHa@ z?Ih>(e}%sg%PzOLWGRlJTk@Zn8Pz%^GNTqpIn#mz+v>woNZ=wE0nd&tkb_m6`;^D3QgDhR!(bI* zmLa?9@w{i)7LeYsXI?m|Yf{2qRE5@R7PHCzJcsg|R!mD&5ssLF+QM;U%?7h&3~LCI zGrGAesj=KG9B}c8@8C6-O|!&x5Sru6NkNnhf*7vH+grCL>X)G% z!%qmT{8nE7=x_)}y}@~TL6(~lK$?q@AMD$Wt*VN(NfoM)9eAFC@$2shqwz3a}CYMe&IZ@B(GBD1v9y!0kuY+&hu zrMPfio$2O*3|61#zh+*ULu0!{qaC_iIKXQ>)vZ00bQB|9UQmNS0Yq1)y%e$4$PS#ROe zpYl1!#nq+qWn)bCH@oezMBqdMEOXs&Z+H^4s4dK_?wiww3FcX^-gsfSju=?7VU1~J z#u#@n|ElXTBbRKd_~r51A%5+a9`y&Khbo}86c^5kxN`LD|N57WKaKG-rYMMu8J-v= zhE>`QDt5T?bC5vjw+H$YvR*;(|{+qaNcE@eOcg(mP%65anmxM9)Bc_1(m*% zAlXtPWmRQH3AtWNMOMaBS;lznVWe-YeE*Zz7KLSo$D3KQ}rqrmGkgpTtkHs?;HE70Tw<3T8TP!H zjvRQ~1;gk8>JWh|Um)sjtqV-G*dJC22h7kiqiD zZ|=v}*|~!eZyS#Cp#F2=#k{fUX6}A&uJvrnb+(AMg}kwG{pVh-a$WZW5%$HKfAgSt z?I3vBfnLTzKE=;)tD+xjhG|RaS*x{{0M9clSb8wyzMf1{z!7c*!VF{QH^2i_sK%vYdCK!IpiDQtU}ttV*30 zcl+_T8DjLJx*$|Hj5#Cx$ZV~5x?spZC$vhNU}cCElqc+dqEEPo>o0R#L&@zc4TvUV z*Pwh;`GVd_TSr-&f}2Vsk1d-|J@kVZy{x;4TtHmpkXe4gVx&T5B&y85U3`@^ z)K`2Y>V6#kbXRcjCjH|o4|sP?=E+(2qc9q#GE=75ydGWuWXLLb^RSy0yhP`yh?jxU zfRdN848BIeZRpNI>Z~#!0DY{!JW>9PKANL0{m6FBZog`uM!}jj(bkK`X3?W8kSPtr zQI<93zCva!+S$_T5}T|LqlB2@m&Up0%=00jPlk0#A0nB+kR$_sAuEn!E~)oCX9FQz zfx;p+1y*%h*rU(RZ-^xb_al5gNpf3Y|m=mGd2W_GIH|qAhi+x5GcKfKj@X zUR60NTl*D}#vzpNkM)5aRDR`OEgI{|;G=VtOviEyVN*R1BwK0gw6vvg2?yza2@&Mn zR315b5xEd?JOvO)J5+N>K=qlE$x#WQYN4ECFHw->HZrPIv?=mshn&@dzjcHP2gEaG#G=tDqfEqqsy_JWiBE zEqdDd?$yKROqj>Di$S^3{`p&6q(=ha*}t|c3>Yt_;EXv<>>fxmGBqgE=xj#Q+{i;N z#O6Yr;hP{+4 z#Jd6A$q~fz`n1Lz40WVnE(`yJ7$5eUyh|p1Zth72bsOHnf$p5VI!rmL3-e7UG4yZ% zXLB7ot)2aK5wQ4acBTp#X%8yUR^kTUk34wR#o)<(!bQN3C(-(O_kdkgvE65tkl`pO>%$1h_+2zJ;7oXRhudZE)BP1D zZ{Pm?qi!x%fzy6GTH==t9*NV`+r>?oFJ}*v<%|4a#NiO>#2>@L*Y%d-XRJ#VoJ!nV z+~+*Qhc_60NR+ZY#xlmFLk&?zjeA=o9%K?CePnErxE0TW_s>(&U6%Ww4^>Or(TOUO z6MnwPJObX@%e`z^|Jb!{jM11@=OC8J!CZeM8lSso=7dQ<)qq!jsSg|8eu3Lzt;7BM z=BXfN{WNT2HX~aW(y=X{9>ah3(xTV&fO7`AuT&gdVEti(uWb;n4BSmFCm-IWN64l( z2P+LZ&#&&&aeXcrda&p0e-TTP#W?;Zc9TgCTmXohweLC8COMe3BWLx=`6O%)I9VW1 z${a%@11cs}-5ag(Xx2H^z41iHlO>zu5OaBiSFobDJzSjMHRvg_y&{sHvj@z{Kh&5zZ+)&ksC;pD?}q=DS<(#eSMVGIT8 zMFZu7|3wZkyY|LK&wy1z<#3MArS&wut^#D7yTC#UF3FE zbG`@@<3p9lo#N*c6n+Bt_QdL%fZ|pr8A}CtIF;yVDd}WK6Ed(L6dfy_?M}nVMUfYoPF#{+qANzu%pM*^ z=D0dN%DDsDOAe1~gJQ*K@-BTX+H@Vh{__`Tr1_gb_0mQb zXY8JZ^MCH}b~olOVQD~hihjBEh7})VH#?#G`YchQ#Z<#iXHr-5C^7fhhoT1S71lI& zxtG#!sh3m_xBbeE$`X}GSW|Y6g$>NPy$(8r-2nXa2TRh<;7N}G1H|y=ZI}jv>RwcMXFLW#Fz}ac(K<0Cs1>56 zHE26oiLu})A<;&-`O>)<_!gn!g_NR0zT)*#zJ{Tp&wQ2>TV4u^2)lCCh+9F#!%YT8 zlo)g)pM7+FS1ZvioknXLVC=$h9X^dbPVaWE?@C$_ z#Rrh>fx{*skJ)2ufV{f8xqP>rxp{D4|NH$V)x9*|x0=(_6wolEH`k$7I$?m9%=k@K z^{rgpxCX%w{NYWA%$bA)rd+vEYlh?s)Yp7b)(oz+9THLDHtFxapY}WZHW_|+Oc5{N z@mdC!q^6px;sW~JsDfwe)ivu07<7}92e|?wgNaD+p<%P=^~LfGuTP=xM2AECT086A zA?alq|7T_*$!pJJ7voGR+G;wq$i_hCjKA?5uM3WOIJ)I;as#!C!);-X2SQP47ehOQQ2lyOjRmDuVGmA&;eUp-(&I!_l# zCm~jBzZ=b$=oedLZ@raPjTYWX7dn(qvq>0PD>At{p8oivP#y1K2Wmze<)hA6>fpd^ z6h7ZiTbiU;bmFVz(2wzy&(R1%(S;~BV;td$mzQpw%}N9NtpbS*H-Y_E(1Gre@YGVp ziMqsr7xjx%CQhnXL&>J0pJV_{hQhq#K$`|0os2)@@7sZuQ}$-d+&RC`;#q|+L-7iR z_nP2vsYixR!%(TN8PO36Q-+Q|md2sDhL9+#sTnFb8K0l4Tz8k-&p0G~)Owh@QC)Dc zNAUuAm=p**fM-(!d@T!_XMVeoj4T>&CwW~~ZJM8aa&m$5M%4p64tG^v-g6x}rcvp6 zXb+VAb`9pdHr<-7e!`e+y~}kF5R;#fMY{d(Ma7*v+z$g>nJB``r`Gvsppfm zge6SJBZNY`B_9Ft7)@fn{0^@+ho$|VBALfVD>L6%(wPUPdvh6`?isFjAG;urrw$&kQ(iyR2d%}pIA8d&`4<7TM36xPzdw<^7_5cMOA9V6 zBFSz%p?&N|vwqT>I{G4ZH0M(rjINL_^P*5%1nmhh0B1vnkteyCkW1+c{VLThvE;Mw zV!guMC0@ffhMh|u4D)9~IHiy&TH7+21=YC5I(mC6g_XqA?lPVbT`MFh>5t<5y#n~w zCbvuA)k6n1W&<13k1kiW7AST*${&%2@5!+0Br%)n3)SC4IMx)`^n>$p>rO*yqaXO! zA7=L^USVlgIQ&HHk}mg@4Jb#-_DZ-TMo#=9d7^ zBTuvOt()-dH1kiBszRISKB78tu0UiqWplUVmlMz)6WG!JAEYG7ZgE1n978eh0Qa09 zx1Kpum#7GTyp;(ojoSwUV5mqY1>U=Eg16_hPrAR65}kEE>2@P;3l#KtNZi9(N$2rU zB)&`VqnxV`-zf6;52h+vfOFA7X9?Y=kd$QJp!f>;&HS^;;1UQ*|7boOz^t^NeBto) z2}PhA-}qXjTcVF1H;jWKekxe|^3`p33cbrvkgqCDs29GIj($vBDA#xPn4T$v_U804 zm#&)*s6ad~u{F8h-K^gOz5`@>9CT%_`lT90iq$*mg75M#NV1&i(npL8_cfac6aVz!>kHb~oeYDv1(gvPO!^ zM}6pFd=jChXzvlQ;3}c_mV%Af;Od+qbmK*ZuP;sFi;7_3t*-Un5@p=%!3ZrL0h0fw zo-A};e9654HKB|$*V>743sa?rPl9$14O=(7xu$?BH(u3zXw`^Q1!G~Wm?9l~?vBXI z4h~xjIxs9fw>zwB-hnh%JT<&p<-I9^al>5o*Xc4dzUO$@?TYCXvVK@b>j^v1d&&taKZ5K?4D?+WE%HwGJAZ2@oT5R$-f>V*M4cN@+6p5sw(v zg6IcR8abP#B=*h=u75~~)iumwSTG;fj7CFp!L+<;BzS zAMC0%GL{XX&;Q*JTKBG@+TfywsIlh0ddd{)$2@v)T||T}YX%UE{m^nw;&{guYN~&& z3G!mC&Ot4(LnUZS$fm?8lB_J1Q$Y&Za#4|!@cuE>*7%pYllo$QOkTy%G={0XIns!f zR`sPcrJG7)g~qpWDjLKlXxrAC+>|V6(f^l_#;X72H}eUe*j^NN&gse&`FNeSm}aRDvIk;B;Km%;zX8Tak2M&l}Hd&M$s^7<7;b-9qjYJB?gHh-!!B zX4q5d_j&L}0tDv+uOR;DjG6W-ga>ta;AKr*pq@&qm5}Xcb2HnLv z-i&B6+*d(vR;(s-s%seBj!l+8@iL@t)w-FxQw%`!I@H#yS{IDQJg%()JYZJVOw z%kXEaZpME@Y(U|rpVrab2lCj#0exoLT2L*!@APw|$xMR{DpBArefk1^RtO=)AQa#npg5^Eqg>7=`2j9vhd)!=HWa*^Ul~fiNTbu9ZY3QV+ z0DMbM80})Q^wCR~Jxz^VU5znY4T)xrm|6zMfeA+yy;HWu;(zaA7IBozvnlFY^jHnQ z@wnqK7M9mLt?NMEEg?FUj<%c!V6%np{KN_xdydR;@4;mX<*vQLhp9ummCOL9@|(d07<`%w|?kP)|XC#)EgFxMS zxz5Zf@bSMfx6o!j^lu5j*oynkvqGCwf3c~i9?{lr`!*vJjL_zHhBdWZ-%47H-Ce$z zZtA>h$Yg2N0>0XPQ5NF~fbTwd({hy|8YfrGwDcM$%Pf>pT3t;V&+`+{daNbpzx?rO zqZI(pu@hTcj`q;Sn}yTq@Mnqtf+j5_(9~^Og^2WPj*r$1ndqj!zt#<(fEks-Sp!cS zp3T90XCt}h6LA&bti5wEBWWP)8=Q5aK3@F{I1y4#e{cUK{$$!$Xl8wsbAA$T=6X~s zW*<0oNLG;?ce;J~{&QIR2;+aLqXkmy?;a2g`e#$BFwyor!V_1);?@(58u*)vNgfa& z?q&rigdaCNg5icKN|2rc*!H;H+3$wSQ#r5e zyf<+COvTVh9j|NFH*n2NMO3Qi*PR8oMzH`l@fUc59;R2OgW_2Yo)Bi5Y%C1e3K`6xEykbN-p1kL0;qvKXc3_g3Rs zF^KD)3crojR`?ql8J@<5HrQW;^E?e$NpUmV;Hk+y!rllyB{_N8gpKxd!Qdu5Mke{2 zqwaP1RiIvIKC&#Fl;kIy$wBBd@&Evz;GMR(MNCGUbtN;yqhk?2GuCgVN2XIH( zFfG6WSy&}_gyy*YvLUBxt{Xl6J*be7mN|MkvFBwnfB|*Eo|1TsZQij66{| zM%!Z*icQN48V%PP>u{OWBV&xw7PGk`tNe^Av$>{Hl0S$QL=*u(VRpgT%LDQ@OUb%8 z(;$H7WA13?xyK(-!v?#2vAf@0nz6{mg@_ACh#E9y3j?^CjfJRW!6k>o|K7Gp({QQx z{k|@Z2Uy?*Rp>|Yxa?#u2@ZX;w~hPa%Fu_BwkD+s5e7oE5$U9WrQqH=^inW@$bHjgX17 zJ_nA-E*Te7@KwBuAF z$ubEgEE{Ah9FBqAfjv$J`ctBVR-V+bnrqKhc8L90QLgO|L_F{p`$1iSNg1zRJA=v^ zo86>d%ZI}1fCLg*1KWz;co$qZnrO1>0!ObmQ(IaO9#9;C=b|qrlrD@~lkn?|iqZw? zFTXy{cWtW$6qNEXq+CQ=iWXjOUia%D7q%!|ku}`D@@Tu+*Ya*io1fl0+nggavbr|1 zaYfVknF=?t>b0~AoJsvw-+R#trclnHuBArbJHajw_afg>1>P8C z?g-+J0KpM?Cl?7z<1Z?lJ!@_I1OeXIy4MswOQrjQ1~!PAk`!3ip0F{O)P~t)MHJDU zXWi;nu^vHR4wzm=X}qw&Vq%V7@NbOK~3~(Je=1MZae!0e-m%GaGWSlnDRu1);Gzo3b$ z>7O0>6dnqBYi1hd1>>`67%W9y{?Ujt1lz$zamE)o8 zL49b24F#Xgo%X2(I$~4A_*(ILBPC5lluCcX(_RP%%Os>>%u|OXE(|-H$2>K?TFOC1 zj{afTip{@#W7WAUaQ14#^o!&)ucNVcMwgr9@~6wUA>HM?0kld9I3TV5+MhrevZ|=I zu9(7vTosoOJK}@Hzgij0hlp2d2br!2W6tRz`WYNHKd%unY~Z^}vR-(;=9YG+ZS}w( zdXi%1sRuF{-K3g#7&RC3%iTmSzlZ<#C72g8orjBE-%K+v;a%loF*<@bbjKBRQa8DC zHEGgjm#7Lhoy&kmy7*7f3led2dI zPAY;!7_@;p2Y=D+2vVN~ePWl0S(endR+2~C37!6#sBAcit7WWx!|KajLZzk@5;BT{ z9HM_hvLT~qF)B}y4`w=+YquaFiqg}fH^6l<4cr=MRc6{exBNiP1TxnV%IASC!?I%Oyf6#{!2#`0&Rm_yE0EoR6FJmdBGtY&f$AnA zkd!$AWM~207wn-s>9N!Ni7g{B#{vs`o6r=oV*$|cMIuVwnv=B{#Sdag_<}Azrlo;Y z@m{y3coqMqEO{Z_=C%wTH2H8VbWJa9LobDcDvw`_UgEonJYV4-3C(Iv!`=3%i3m6= zj&yoIDqCux+C)5%H-(Qp=^(NhD{ZOGgs|_ZF@!8uIha`A9lm*TKqk9(djj^pn{>OS_67Xz z?9M$oS2vPVFTY=6d-Y=C^Xtj2ea`FmA^8+V$`*2ed}dBjd(J=8V?6OGgfx9N_R|zE zOtjj@^8-mB`AzkE!0;F{L}yxB-!WUhSe2id-px;=%rF>=mAy+i|C_Q6*f8x7H%QE; zEJ#1~CvjHc`gz`5`|Dp!SoDd2;6)PjqmqAW$MaaNbI?oqMUaXKN2q#jD{9n6LeN@5 z$~fiy^kmj&9cqq!v~c<#!GDr_;p{QR4fziUBA6Kg%%9Q4YFGf3<%bFHBQlD0&Hr$nP5*jHRL z4D@L(V0&&i^oY9)tg0;$ ziB-#*HM6DcJ-@7VZy80-RvGS{8$w3(i{5N=UZ%G)2K-h}diRrmSso8sLWS~!$t`$L z13sMgmta8TK->2g^mJmf*3I(}V7Du3n;GTh%}YXUKrT%zB%Ytt@wU(lfLlyJac{d}c?`Q^29wz|odPmt_2HIg&6koC1o^ zVjLJq3wAd(R+bG4dTHaeT@~>~{89=w& zA_=hz?$<$VsaE`!Yt1ikS1{b+(ck9L|8w>#nm$#p_-)mikJMSU(sN=CQMc^AYTGk( zSL|R66n%!0$2-W!=j-ooP@AR`Pm4>-)Xo_CTw0vok1ya~0YOpo)s8(Ny+oR}*VRIuQ)ELE*ni~2+unIjsY&b_cQpN0=0c^_L}l0RV7tx>q(>dta^$kT*t4a| zN5n&?c-qb)PCNrA1)LH`ZJ-#SC54jG9gJSZ6;OiReW zk8Z5g?y|v!!S}8+4S!T4fo62!G$rkgqul82h08G)g03KV>U2nyLm_8$VeMWqZf<)$ zG%w|W#1Fk{-&2cNsTh~*xPi{r%tZF23Jo^5ZFOIj6ab~|>JL}>Y|cUKubibxbw}?i zaAjyyhC;s2ZwGy1P1SCw*KSBG)zvN2CD@so_|8*hYg1**s?$*azJY$KtjK9KDYWKk zDgLE?{Ctif^-|^mbt_X#U@v$%Xf;AD`d5+kp*pQACcY2|gFF-kN7OgB(G`RN_C>je zI8ek40m_aQz8^mZ=$K9OTXj#!V%_id52lot4(cFYi~0z*YnMq#$(=s3?gpsA)3#vh zi2Q4pv3t?k0W1%(e~GQpvu4#S#e+wav0KklU>mA#v!7>aEER~$@XGvG9Ytimo$@5lr`|qHCqGztUm^0b%`@M|8zz4h+wV{PHT& z()(1caMnaF4dppE zt@=!_!VuKmW-u{$_SUkYx6P!UHuVfXnxJ?gtszuc0Oqk0rnTC8A=>SCT}O?il?fFZ z9)8o=q0+GuiDe?6AXsAcz5p(!Va#7uan{J6C2mxrZG^Pn4m}BT|B$^VrILu2N8TU7 zVjydM)ZB*F8wN!G0awRUp=4Qu)n>1S8=il9TlsLX?8`XM$Hx^DKRdKK{sYme<65^n zlyrsqKW$On`6^!dP(lo*_j`diI|A$2(^Tpn(TBQxRDmYf{~neQohvsf z&{p>?v=Ne||BC+guMzPold?cHJ_+|V$1~WbC`=R>Wn?FlnS|1|Zg+<~rq3t5Pr$ze zI~ok3E1_27ktHGjj89}R#S6DqGx0V`!D!_dczOe8&;A4U`9(@JSw2_1Dw1m@D#!M2 z34<}qPm9r~M(eHAeXgif+phcUR0%IXu=_{KHr%vmoB#F1$Y~5xe5Y|%kqxN8!?q2@ z5!u(olaSDRQ87RW2U_=Cr8DBuHd;-tk{_8+d|=3)v5-%EM}_2U3NVe%se$&2S>qlG zF8_VFgvI*i4dK$8;~N3?ma%e@0Kwh#gLl`V#o<~%S~prW$6baQcgrDKh=qo2g9POI zXdZ6cp-s=f3xi;)Pax+ZX z4~Z$y9~~i%jJv>|9dF%i*-bfJlnd&964d+W=zb!$8u0C?GuqV$^e`7G>wZFttWpub zg8}LA8Dgo_3-*n@i0w)WK!$+x72uoBnR<_u-lbt96CQ=Bt@j2Cjp%+r1-8$-LaeRw&J$0{PC;8kI*}(7pow zOS>v@F#RW?Kh-150b)JmMhviVaOj9C~Q@?1C#G+#uXYW~w5_H*_6P<(X#B;-s%A z@I^wWjxwS^X!Zvy4uWa+zs@fW_fC-XAmuIei9q|iuTqy9mo6hussX|-B&`qcbs-%) z`laa{UYd;5jI#2HFF0>W4>*b7H};V6*H9%T#7pc}Dd<)4*F;ZH49P(sXcyv+6rhcy z4xsB8|M*AdDiAIok@L2_z}vh^XKB_vX5Mk2 zbXbwMV<;?ro41G(Nu;ceBaNAlZ>r+Y=C}X;Fu_H60b|q;Zw3R=ZB#485T*V#EsM_fVhQZW`<>ELPt;b`CX>eZiSHM zV`a0VXVmbI=wG*hSIQzy?BW@kttcucr~!h1{K0Y8FUWI~r2{|tt16OGn^BWnh(cwC z|ZjV$O-hCZ|v&6m7hBk9=*NZIdO?~2NW0rErd9wsx=D1+AGUlLRh=QFZVyx#jC zCCM<&!h9%|sX^wZ`RIb1lo_GC*_=G#Ku(_Ud_6#}tVx)oWO^ZVYJuhHYBuFTdd^WN ziG+$~jdrq~-(P$6G|VBFGy>KSHWttoDO@X!jnG#_2V*z)NVP6 z*pmjD(W#H4c4UDdOXBqo!xH}JcgyWK7!8+;bz*f~_erlqs`>mU;}gEm9`McgDGs%7 zY9 zeeQOn$1}Wz86-}Ak7RxLzW#+F2k*TX{~`(IJ9Q-&$rfOxu|#fHRc&{r#_T~!DMze> zWatHXlAun!5&0CdyL)pFrvHi1U01MZnc8 zTAL|1i%()XQeN=-B@+0)?^igf^VqSg3o*_`AGDe2LthUko4CA@<7|wHx{J#u6lXMJ zWh;`Zf&n>6f#mCW!@r=}g(mWe>9yoeGQyz>FPK6TBZ){lzF+;#q{c%)k}7nQIbY); zIDJxJ4s$Z$GkzW`0Xi#p%c%+cu$a#ow~O&krxOKc3I!$#!jl;H=(|fsMDk?YNGY;8 zk37Qr*2M|F?ns18nTJ{|uc#KYdc|A)_9K#i5`H~Kt zI>xhBOHKL*foS689rgKYgpa zMOy)T`%lBqZ;FC4YU~H+O6V}A*B{3O0lXKlDzaSeG+R%SXs;W#G9YZBM65hiw}0q5 zgBg%{^M#*DZg=I8{gvk7I>tFaqB|PWbejJQv$+lAw^i?Y>NwNe`(oqm>)F*_s})Ae zz30&-^a98*p`Io66i}$r0*2iX5e>VBMB;|$5>>Q{{tUxJLl)**!Ogfc(H0-0!d9{Z z%IFKS$ZXE zBWZdfjU&i{x+9U4N9kQxma5elqduhM4<%#HV*n2Hld!f$z0R&+J;>+Of7XWmN5B zw^G4qsL4aQV%?zKw{H^3`laT4Jdv`Ddrz&fLo!uZaCWPJmkkaM`%Y-3J%m3yt5x)n zA1I*3MkKTph%Jq4FO5qdSd<=E^m{zN24lM^^&NvFPr;FA!eqx_Y%isSx)!fp*F4Wk zlTcnM(bnF*a=`Z(KT0zQ+}~Lu=J3L%!r?_(Tp>2prj{x+H@+ux!q7J7DXNaPR zW*}{vqWu0#+S#5e*9t?*eUrwwgPt!I$+P(-U2pX5lM>(0=Ei^E5CR~Psz#8x<_ayc zrCd|rnm;a)U?8+N$j;<4~Qz!Pr zw*E}tD9IC_-SLs2K;$Wzn8q=&#tE^fQorFuI^@H=gp#fFop0_sd%6++yAxuh78!aC z8~V4wsw%$n1D9I6b~}4Kl8Y2*Fbp(UJHxUVCj*tqg~sI#MCqLBx_wcfD|QQt;J%wF6S=G#Q+aeRn)byp88)~P zCGOJJq9n{d=oMpqnuJWm@F$A&)eK9OaGG&hCpOILb+yzb+r;d|b`q`BlDz7BKOx3Sde7#pEa)Xcqu$4;poHxId^8NICYrVz!;g<3-m2*B}GG2%1Ic0b7TQ z{DKcZA&di+kzeFHvl20qIezg4{0T+vNPp`l_GG+&d2;+}*fOw+6m6MxuJ4$};I|$L z;HYTNCqI(Vw3XnXC_3AR>?|5d;MiRIOH)qU!y9`KJ(*DOqp**6bKenabpkJOD%oWe zxPS}9eZzzu%)kXYumxC86>}*eR=4Q5*+$nCo6TUB3in1bHFAu=YuonxvuEOs8k6hq zfuDP0l-vSYv7&@u)3a9#0@*_2I=yQ9jF3@(9*>Rw{guoMb)zW13Wec(30qyxMHbpu zzr#8GOy@7b$>skMK&?YLk62S|iSUJFmR4L^|6Bg;^y)rbs6J@i^y(|`R)-^#+JC*n zf0~8WPLW7~I(#!5v9E382yf`S?oJvymaGUm@*(IS2UNB$u|bySl?>ujDS|QRtxtkd zKuILNddn_mBZ20TtGYKl=P{RYhaW$?GB-G<^?R6RykE(PS;?sC6%<>^_;xfB?P|_) zG$MU8qP?0ybu{wBmBCV>*?6w?Y&w0N>U92rpn|^xF>IVX}j(eNm-VzICT77uVa1n zYu=u_JgQxm_ zrXjzBti)IP(Ck+qh!_r^B5T0+e^}8=T{ZAHphfKdFsdb~vu58rHUt4zFR@!M+- z`E+E3U1~`VugG!u`-|%TOLTX>&NW&@EL&$itz2pdd~|D=rv~TW*%6fUj=5yVM?ff# zT7uY(i+P)GjDkEqQarr%;_Fqg8fRJx5Imkk`Oi!u+y=XUS54gGeVXVu@t-Ha9Bq9d z@yWfN68K_st%wQJ;2?v(cSg|{7Of)TjKv}=i>1ij@rsWDQ;x?HBO!jTc$p3w6;N4h zChY9Zz&|QGvt$Eo%(K$iKBqAS%tT{d$D2FCU|fwMpPP;BzU;sHQ2)S1rS_)k(^sW` zopf_?88HR!%78RL%$|NVvSGN3sAwN4a;CW8Xk8j{&i18JdFat!HVa>bj~Lco|3JOMRc>*8@L$%i z_m9MyPC>88Oj1AEt3)@}d<6{)iw{>m;22j!Iw9cxQ?N7c7geBYh6&SK(bl@Ck1PHL zzE~o1)NUv;ej>Ie?xYINMFjE?V@2>N#XaDQ>|fO!VoUFuVmLnHm~Tj^2agn?#Z=>8 zXl)iLQK2PXag^b>1Q{r9#gEK1>Z;^5-)K@%%6M@W-n85hcNv()HTrZ(@twl}V31wp zm@|_6!imkXD}^=0%nNa%gL}SeA8r9+XP?$}^m%Jhv^J$zkAD2bWfp6ig^(#Q4!37= zBcJSlNvECUrM}|t)Ae{orGhWtZ{|{WT)FevFjfB_*?a7l1z+@#h(XHrB1e-~6w|D| zfpdpAPkATc`l=Zg*8$>9mj0?14|RY>o>V_kDs8ybhcI-h9skKXXox4&*gh2znjjZK zGf*x4_DR@2aWVM!^s{dPPYEI~ylP6H?6=be;CL?S(Vt)M8d$f@hdse!_eN5v(q1SY zp^8qt5sBu9vHryYtQc&`N3FP4-FMHYDQ^KL^i1CPPX>LWEtH-Rbh=F^y;G3ClI)29 z%8?rG8)WYzp7&PT`S*syFTdlTE4R{kj!5>kiSS)2lVSnE#nCEg#GC|^+8Y6Yh>mrB zV?@-e@I-k51C9iv8S3S34ipo5)Xqvu&m$+n?`wH0RJUHNDxO^rAuR&jR+J z-}~TCGD_iAe}tuc{+vE~_tg*2P2X;t2*()(vmP>P&Fk8Hm50t{zdt0p}A1`?;NC6_! zhqo_jFCE^vw&{xTNH}kMaIr;}_v{qavA?x8^Kjmi#9I4rHyM&o!`7FbKHm&WgL3`X zat39j-GF!dCZ&99a-ZQmD&?u$4t6u4rAQK94( zlkVV$!JD}Ly=;IPiX06UH*!OkWFBN2CTNWcJ)*3i(Vf?M`H{T`qO9RqeHBXCW%P?2vu!Xaw4IBAm78$UB6f+bk^U@1$iVK zpVZrJWaS0q)Z3pbVv%saY@~fjDe%BMWVNJhXY>zYMk27?yM{M9D3T=+#2SWp5;yB`pRbj6_ zZWiGGzEMZfFdPtVp&CP5#(C^RBS8_F{_GvDrUIVnE9$YJE{gxyn65vstx-jZQ-Gd& z#q96^RuQ(@S%*W+MTy)6`mR+ zbz7po?%5Tx74+S$;evVZdt-GTrr!QDFaCpFp$|87*LJv#2VJ^}}Yz{UfEN)f?g zpB9vx8rJ6$75?znwtE)-eL*o4&Qt6bZB{J83zeF~RvVUTbHHC(dLcOKA4Ti;i4@Eq zBVS^^B>aT^M$6J9kpv7-=5*SLZO*Aq~q4&akrKvUOm!O<|uiIzF z{hs(O!f`|Dql@^PiA^0sjpoz28-tkDyM$GXKg7?dPkdE^T@6-$-`TI#f78c*6E^MG*-l z1(9x!q;w8S3f7h?B>##ff41etI z?94p#%zfXFpwhD9+`g=pGyIbWuqvspt1MaNLftDE>d^2s;of^M>inLN-0I|Dt1Zb` zcY;H)HA(d`eAQjX4A0q+7Patm41kc^z_>(o%aAT$5>GrPH+kVL7FShY^3`JVHG~awsiR+aO7&tfARc?q>wxPRKGOx;bzMfCVg|s%g~e zhm0GgD>2)$7+cy`RXR09$H<7dF0H?{*DQx-Wu1!k5GW*__#WlnHQFWGv_@wZ)}QLd{C zVy1&)hj{vSg6+>5+`0q>y`6qj|CRQDi82}iRSD1*crmo4PYjF{oaiioUb3@0Tw5yk z5@0??${r)NHjq@u$l*(%_eM1C63D&;ijR?C?eOxDC5VxLzhSi z$@_}=eZo(1U&|7_w(9B1@g}9lIH0~4{{l6j8Pcri>nCgtr+nIp_O|Qz!;;Dspy|Jv zMN&ZV(Agmc2R;-2P0`;?>SQ#00^47e%he>D)09-bzO4SkCdqseUFa4RufS&}vkX4- za9t(${hqAbY8CPO|GegP8(DcnzcljbpWu}!$WPIe?XVcceJ1y`m1fU0n97Vw3tqK_ zH7n6XyD1KpThFDx+qj%9*h8a^14{asV5#`*1W=sFRiWx%P8L96ocy>Q#PXEp3E zg6DMS=DipS&)lGg)r|Fo#dHHbyO9kMC#EwR_mOV}Y{Rq02ur%SpG-2uDCz% z)@0VW026Qd&a>e!dsG(@v>eqk)%U^J%`Sv^mUH$aNTSL4bFY6am7{t_8BlYtEbNjS#_sAT@g1#vh5Gwa(AZ;O9lx~Ll?<1dfHU0Xzo`F=n z8qxrFc~wTzx>lrC9d1#H0D za(-Ta76zhllv8v3>?oa@-jC5yNGRA5kmPW1kE)4udKYu#je;iCYztb7-<^4>y>ge& zVRhSbls#Ryk4L6!5s|8;P#IboASmfvl^a(X$XoiTW} zHpUJ5rUB-UB7|xVnNo?LbJUdS4@w1@J__u&C6YP-WX%`5odpR@-@Z?o?WyL|AX3-F z&tD0zcsh{(Lmo75xwY(pLRWt1aJ zyUJo+E*eZJe^5PC4sqVsTc1ldI7h&rfpYaGn5e%q`;wh+-THGuz)5Vv zB($4oHKB@W^p{*1uLZlC%)N$^%h&FJgZH`j Oce4!eL=Z@Y|TL#U?)v{a8^py1t zz-C(+%cFFt8^z$49^cR`;fc{yD@&EK${?K?36?#o@81c`;pyMc2o${Yv$FhgK;jhH zsoy|KqmzL{U-p8T``ot*@wpx(KxRmP#(3fPAN?y=>4&~O?qB0<7375zpn1`Pkm+hk zd4*$rr6YaCkFhqoxnywVfoeK}aUV_ZpvP8T>%4XPTgU6EJl82S+8b)li)l@N_Q^wX zc#*U)S_?!SOcg$u<;MUGj(@5~tY#-;S0Z~;f}mIUAKSZ3F= zBxT36vxP~`Ah)G>^wa

*!-&@ zIET@bJByvQBSKFJ_n!Q&7Pp%Xo?tbdn+?RxMMZU7Ew(YSym{2sK~057WH*Z%at#Z- z%BG93vTkfFn3^#_0+n&fUmq!RB@KDaezq_K8l`KwSJc*X8`@RBAfOkoYbp;*`bWuo z9&LDV`dzEM7&B#!RDD1}A10#KcrZC>$T4_U&5^!MD!1FR&ohePK zen|}yvgvsxr9QaHUnQx)Eu~iryWpz4X-o zPp&!a+u&{zN3$9QV>gVv=fSBaMKJReRWqpk*j=KJm+r8}T5U!@%b_{T0d!O=RhN|9#>BflfG2pk}F=ZUzv`;RZm4+Upm z7?vJqPu^z|F0nA&l6bc_tRd(!@l?A?U(I{#h*k5R|{k6!ujz=dc|1-Cx|{_)y7Pm`R1Dsv5-H6N*1yAk`t*Hg=% zidR21QqOg~sEtv@b_qkPC&G4Nz+Qc}L^b*AnL76Bq*3TC3Mn5+09Tm+!-^^+w}%N( zneeYw?*uwKv>Rcx%##wg&ps-8e$lOp8ShZCfYH)mD@0?`u)94oXSEOX?J7uWG}F`% z16U#JVjowmBLrWZw|PCrag;fZF(4OOt^F+}_AW%QHvL-$cL!NB5y*_cjh%)gUcdE? zhvK^L!Xl58NsKq#43#LFzV~+~jHF+eif&c+$4(^nP%wMv&uMmh3%CN^kZTF$c?xk0 zo{2I2oer{6PnD4bF++Wt&kWdjC4QoI|EpWd(?5M&_jn(E#=&Nf__7js_N3VW{B zHNm|G`6m^o*4LTXbzg41J3Z`N@R0XhclKQ86h5vKIfe}RY;&r3uGa}2D-H=wS)?BI ztEEj3u}qxwr(I)jJ~1||NzDRKV9%^V@Pow<{`*X-U#0eLFR$QiT*JFJU)U9xNUgWZ zDV)hGaNEvL>6=^7M@pQCsv{*%|B-+|;RcCQihNM90X%>Vp)f?6aVRqQ!{i@#zu3BF zv(!`yTZi6wA5Dh32B5Na3XP=S4{BHN<%lQsF~;<2#Q|(QEm_f8Y(Il?%bjIBp5rFX)TBsjf2~tG!(_BaG9jeZ#{y3aTQFgk*sMbgt&N$<}vYFqXBb$Vn zpZyeMo{UK2`@UZa$Y~F`?>{9W5Gi#DT1#A=i`p+ur))jNgW1?cx<&HV)Ud!GU}(&a zPE`M#pta_7H)^WnVK)(GV>Ir@AgxCUD*i>qRJwz)3)G`D6#go{Et8htn$wvam^mrE z)%RE`uIIk%6ZmxoQz{)NmxnD+f)~Rfea1)bX#i#@zWV`I=1K?{`jH2 zfw_hG)Kq8vq;tWRy262*6qNysw8SA1x-?%ak?V1vGsxwx+VOPGdWA}l1#nx#o#xAW zY12dA9kYkvuBo9MRlS*vSgvs+XvxaFC?e~y-(&PskU7*942909-h98Ss>-}*av_M* z?+rs0BX~$+JU%)WN#r6#Xuh{4lP&f;TNv))jRtwdgOvluzGlXT{xVf+Efko4q=}TI z?Y8e1Y}MIM14Vk(;r`0S{nNgv>-xQk+D&8A3e#l`$hqv!45ZTvTG)!)jM0Rl-Hn5) zNW^B#+(qkhZBv{EP(r6Y2PbJZsZ@2Td;c#U(2WUX!3V}X{0nA0}lk#rZvlwH!>`aG{h{6N|wsZk2GHWQ@A?N zpc@!_d3+*!tbQGAE2@G@q0u43J;d+UM=A2sbFgeHJdChahHj`1N6DS+p-8^x;D7!& zMI0MP0+^VI-Yl2$eF#d{z>FRuzyZh;jcO203AjBh~;Tk0v*q zemN^ixscgwZ;VM{G-h}UWLp5gYyO}YN39MSrxYOy{rZGJoGAD833o6Dtmr%ITU&!N zo}Biiwvj4N1_f{52`rJZn5{aO*%mcHHwf{>5AtfnxOuOr`!605VxA|!S4-VckU>+! zK!bY9IHP-G_rF^Wh9h}k3hlInavp1gq*snEgDD&vPg9(O2J0l&=hB_`hxy%mlLcJ| zQv^09IpvP6HDd;*{!D4g6mK-H`HTr^6joeLo!ltI`QX+ld2Q3Lh0UROjmjKJReq#w zSPlEo$r!5i?F^76z67T{UA%!SjL?M%<(r_VBImt_jYe=jk|m13i;Cupiqsoo7~*jb zEuyeMlw^6Rb9qSm$fEK3_uV2NbGEz=L8tv|1J-R-^jwk#t+>Vh=u=W!ZkcePJ?Hyi zOt=D*-Ky&=mSwH3a4hLo$y|BWXyLB1hXCsgO$6{{u3M}}eeU^{Uzb2b%v5OdNc2R8 z30{e7-jwmOe1(pFxsFeW=9!LO%{X$2d@{v3fV#p$#I_ zd4P&rZw%R$X^_Y?m5STuZ81k^I#0!IJ0_(sX05kv__6RnxWY!~F^P!am!q96+l#@z z9ZaNhaG;_~QYK^4keTF|r*IQ*KBnXt+}zvVF%CC8EU?*}EMk{e&asYsnb)@ZTApH= z*KwdQ478>A<4N4mzr#HhZMU!Y#{r)BwmhiWZ8i_QfT#NbxloGb^M)&Uv0qCVlmQjo z0976ifNuP7^6vzDdo22Xp7J)KPj?*gm06%)0+nI*PTba&S-np}@oka#=+>HUXwGby z9gL7VWy=S8u7YR?DHbMzun)mJzDqQh4pS|;w^ap*o+0(aAHa~i{03*k?A8MUmRjfP z8fObHk|65D0T$Woixl@77Ie>slpY44XNQ9X##%Ar*O56vUvX&1K_W-3W6MFJPk>Xe zP&s49Q}6Es>9e`13P%>&_PgzW=k>1Xk5nr54SSBBL3}SFfTGn}wL^yqa z4f=hPnb!w8fs2y}h?7F{lt)6cglT?bc)oq+_H6DEPiS*^hJ9xDEaTN}@#SCZ70>n+ z_tb|HpD@=!KN(Ju2GMB?MGxABb3NPrLIDG!`uod-#_co z*ibXpV`W2@-e55d&$73o(~qVRpzN`chjN$_Ezj(r~hzr(6ef- z_OHy#S}e;rVSMA%9n|DK)Z_(Hw0{{TBfKnWf5n*pX)_1kNj3k^?knpR%f|I)ZG0VlI{h4W99Q@f-GCE^8l} z9UPoLwWz62PC8q`v!Mz4O@OU@97AaH8jXHtOf|M>*U4@sQo&=kfv{zVfu-?1dHgN) z3D83Ohi1>X1-NfRB|(5Y??g-3Ex4?wQXei?Dy<{Z1EaC z=5{|(@n>xy7^8Nd9Yf#aOYXH1_3KIN-L*4YemQRI&h)_$ki0kbd;f}P2iG91u$<>)9T3bP3XJX^4*V4VGm;~7N1vBv)l--#8dMHW(08in`kLI zK8|(xGWDKR2tDGEFy|Ho51m#!m(@=#+=+4ZEoW7kJn2ak(T-uTzA{xxE9|>97OPad z0Ah{`FcJ6-UI9$y*#EIxT6jsY^bN7^MgLG^gXrvhwS9~CB9o7r0&cIaBy%-fOa?EA z*<#RAKeUjZS52loyz7XkHqlOBsirVnS96S|0R7CiD%`@4gh1(Py`-)Tfoq?LX41$% z##_;Xy_9Uv*Dx!6h!*Ej-({Qv5<}L2Ohq{kJPiXHsi$w_h$75C6jvW012xL=5_4P2-MJ%|K zzTi3;a9uPMJyw~v)G_M9_kR&@LN*Pi^=*|^c!Ke%wSB3}?)~R!mrerwF8ZEIiEp3~ zuQ5iBq9Z_5ReHY}<#xyF@A~4Vp`9T0S#JXSl25U;X~}8wFPK4BbM%)+-Bi>B&&dO0 zNl|I1&cZ{%XYhNy2^Qg?x}%eu*>+)TRmfR`a{~9@?!10QS!AwRFg;;)X2YF;LIZ+i zX+76>6Ox)iz--vWt`&FQ57VJGD}$XWKnOME=a@I!Mk65HA-V!-Cx`dX|4EP;r+OX` zg3`n z_XEbFr6*VDsN6B*$OdfaoHDRLc97V0OAx{gJ$vMG#chp9y#F7n)U{-{;aDE3)OkP# z-1;3nQKJQ9rh8`TPhkdftbQU3`0=9JSwEn@db-aGByj(cio&9&Ct;X+%_$URt z&F-Sw|8@leZ{zMDC`NY0BZx$Gq(bpAgkUz?K7#j$O&x#62k1L{MZ5YSM%jWfepE(9 zRi=(%C%Pf&X-9tN@8_q2nytP3Pl++#iJ&qG8jYXMJ+ywOJrwYppvY5L zu*ztS^SznjkkXX%*y-HlDYI6~%gK%G6;5E%+{o8XQ{;HYWrSKQEw)&x?ee8o+ULPW z9va0rg=}AkE~6d&ykk&PX{JlngtiaOhw`T;e~!M3lTSjuHiyTfA2<=mOK{vb@Q9Ju z)qQD8xcfWbDa+dvTe0UMt*@GGCPUtOie+}S=cXNi zj1VEs_2iRkiw+snP*;U3jBGN0%e?liE5i(Mg$;J3yB7T)4Rf{$z`Gz} zPZA%qyiORLNYC&0V@h|v5h&B23E3M}wuy5wZm7hc%}V*hy4CJx$xy8zSf)RESLJ5h zFsW>#F{wDgtp>ObsB3ddO(~9WtCSN`-|DXShy^$Kf!QML2BMZX9>3w%CPG{N}uCbCj zdxdy6TE(3guQek~36l6PrG349t2LAO7HTd?A~x;=_vl9%fb+|mAMvB~>>myr7SKY$ z#=TYcmtv%$f^n}vHpsV~_S3VSv0a7F->l6^OgLj}3<{5fB_*)RYd^iWE+`)?eWM|m z(Y{XM)m~Uj;B@lcad)eFN}kEDbMCQ6u<9G?dhp;k`@I~kAc>;i>61%1I}W+7eC>e1 zF9XL%X~txFVr`8R0=s+eb75Dk$=w%!T7+mVhE5pAHe^$u_7rj)KBXT$x<#=Lrf#W* zQhN%}R{Ya_p)ZUQ^uO>cAy88cffVbSXD+;T*|IJwZ!%rzK+zo~K z22gHj=}fh=y?>4UVXupG*@pK&*uP}K$p@?ZY*ioQw0`9gI^?689=sfRIq*jv(<216aUA8XSopgZ z>D%pu+mTr91RRysPQfoq?G*UG2I%9y6QmS766GQ1!rH@#Z}^WXO_K67VBin(_xS%= zsC(DsZpg|1Xw<{V*&1v2gnmCJIO;1o&TBaY1>X`=Y3l|jQN(N1NG}0Z&aZS9)R}WE z9w+KT0;rLL;4eT15XRr4)H=vzc%^$&EJL)FtdiK8_EN3i4=0U8ssqlh&^vjMAiU-z zU%ftVGZ1StpjXa)rWK6CSJU+AVf-zdOHBn?bH=6dMz}s&r@#99OF(IFyzvr?P$5e& z^30Dzr_EHQL2Krmv_emV*;bp`R_^o5)vgmf+Eq%Lw%#>Xak|`R zokVfFb5tEDCHr%ArW=D+p8?K>q#W6paed;`O{?OG}{(aPO zCHi@0tEUr>xG;y3ClM;YEl+e?Y{n)?;ftyGdN&kTO@AoQ_HBh4E?Kxu0nVbA(}TXB zP@y`&fa4BgfoUzhIFhvIO>1#mxoC9~heifwYV0D{_+|zm@3Mr(@ug?wg`%CDi&&^7 zeK>2rr^r`naGx`}MfJ~k18e|3dT|@HJ|dzj6wRE;Xx7Tj_vuzjGQPh&cJ@x z-ejdMEj9cQWlrQA0&#_D^R~C0c=I@M3!q4Exq~=O2@Purzqvepjl_VT*O({m7>ZDT zl(<<<_d9wc>KU9yy3G)D)kEbMO@M_hwS<9v7z4hf)0lJ^@5SX1w@z|Mty;$wf)M-4 zW57pEbyhf-HE;hlpjz})+ozAXC<9W@Kvy7s3{Vdi{>*y=c6e@u*Xk&;9 z_rGs#XGG$|9pHQz@qC5is^sgjG0firW7iuxVC58cq{Mf)s#B90ol`0==S*$mbMQo? z&`$6zi6n)(P=jK$J!o?vyqHolE{Ws`s$og6me7AlrZ8iGr>3&OyMFH!IlzvLN%aD^ z{wrK(V^7bWO7b4}bvPd~6U0pC1fTr`-k9_0k4H5Brfyrmx`nWi@ZYsHTv=a4@)+j0KT z5#GGT^vgqSY4=yDT2y1XAiz`(HP>Rf_*Qvk=+WDMB zoL-2a_33fYg{O*#Y;iz_#EnoMohFK=Uoemc>I&wkVf%v8QQZx-yll|rffh+*^eJ{J z1K%MrgTrzb-{ITj?k-$-Uj`s|6{mru1_`84$7Kb-Nq7^Y*B+pL`R-B%cSU9bZZjSKr!JsqDg_u0!jsuj03-#i0S_7UC6NUF^WM=6B?w zA6>&rA^dbmqcJ&emLlh7xg9uyBQx?0xlY5fc_smOuC>SQBi&`IlWu!C@cOW9AGE}o z`3>K2#H?}l01e|VmUoQqEQQjypK#ti-i0|8yGS*+sWj+H^d)E9CFj^p!p=^#lsJLnMmUQY)aoM z2l-2=c@tHAKmRp#;0Z!!ZgVT}i9+gH72LkA&5hUV`sgORhTJV~;x@q<74*pOh}qz) zR5)!>M_P{n?#UO2dgJSl@hrF^D$OJ8#iEjSkY&L6${G2I?g{kSC))@kzf)uvuBqI` zp;&Ne#Yb@Sx?YVVE3iUHO+J|$)dEE4eSBGwTeCL{ipcXE3#xyBaHX!EGCd}4XpaFJ zYf<~N4^3k{q6zw+OW|_3g)o5B_!laH%}9R13PGMf`k;i|@4L~@nS*;%R`Nd7%GCn~~0+{;`Fzf*((Z$%7G1wCH`f=ZtdTP1_ z)77pBdG^@JU9_bE0sW+QaRxa5LQ=yG2fN9j{`g%w9l@z8BP_%Vz_PwQTb-(gk98jd zYwB#}f)mfVj(ybV%|IlA3%XsGMs3z%Iip?&z>5qLu)I=+<4LlfX+QqbF|^ z`>+N!v3fRL27t{Ia65c$g_VxXCsrW}?yP4a24 z1WAy@Jz=g?rLAT&na8uEp5z)jK#fYL{MVqKB!$XB>@O*&{-V%@wJ4TQtAs0_L%_Lv2htarpPw&tLl(|qk z3N>Rn;)6gbM%m+a<>?(ze`zv6>%L*zEt);_u1BJD4*t2!l$4som%L)qUH9saFQyj2zRLwhl;3kWOadny3Gd*;F(^(O1n z*oaVQJ`TVVoerMp;i80PP*MPdv3VOAkxaBloiYD-fGz1qIsD@aXYqrkPqJO=r%7f{ z45oHzGg&1BWWt2oFk>?qsp&Ru}HpU9;A@5&2wmO+pC&TR%282+ut zx;NqPpPdz@)h&#hx=VT0BSof)ALuta#n1QDrQQ<{P0u#UReLp__dGO@qURLnv1elL zCG1h)(L?bvj_jEx+wxi}KrQ4fqJqPv_Q>ysBK50*}BY7H?m zhqTg5R~uoWJ8?g$7DXBB{|}T+npll(@*v{Yd>Rm9f1A(-T(QFg`&STGL#6}SyQpSs zPmXb&zvXcawCP9xXY%TaV(biKZ+UVN{aY+YE=+eh!oe`$FP1%x;aG1P8$nhsGh90O zX`2RMd_H?W-X$JF9!ZgzvVTv@$nCQs0iC7W48;48)hhdsU!2yuAcuoN_S2Gs#6=yZBVA=!X2nhI}FHHmPe${g3)nEg~G|c-8a%I*!;ym)iI_PEw7jANJzC}J! zfu6^+3&9%jQ|$5c_%s#Ij1)hK-9>}MYlTv`zM{MSm!?9*zVv~kvWH)$^24i#1vy#w zQ$1ZcWM0Q(0`#xhrNor`aHGT{K4wI6w3Ec&|2MQkY{4@ zQeW}#>zG%~esaa5@T}LOLcVhSTqOYB{sJX$U;4*_%@Z0c4u!q;l5`iHNfQNljU&FM z_Cr*PEZcc-P`K%Z)@AT>{&i^+PCLE!~e)tXj|V9 zyX;Yr&S#0DR;o#(T<+&qPXe_*r{5O&+Fy`bJ;??21PlwJg=H^&!V(8E0F!M0Hp1!8 zQU>id;;%a0&oY*M#&T9(&aya}l_ zkbHl;;uA|)F%kgwimF%w!7a?DSA{e!(NR`i${hZkb|eGjk|8Y*@&v}(6p2uISp3!d z{M8l2^ZPUS-qPLfe}LP1ZPUb`VG-|3ENV(&U~Dl9?*@{~C|HmE@_w9<)VS>aCcV^@ zWyV~kZ*PPh)?acnjO`JU*T`Yn&h+7|Q1gS&XaWGd6{51YhIskYD+jKZdO1M4JRN&k zgh-KCZ}pW~|DgQG{7n08wU)OO9;Dfc7JsNoC1`hInO=caz^0YCZhe=e_)E{877m?f zw*d=5gg${TyFxMl^&PnxRp7*3A@+==)?FZ@3o4|sGHu=?EO>!4XB<4{h>72AWDpAI z#)p2N<8%zmDFW##jtaDmtpsz?C-6ser`)%pH@%ZIIb_{k^bNeM+63s}B^pSD6VRzE z2@yP-6fM2NwrlZoyk@gQcI%*^os5)V9jCHj{24;j@ZBxs6+^0mhpNT@hG=(@} zZ5-;ShU5O$hXgiEKHrai9+Bb6^C;_8vJzispaRwg=rstCv`{|kAdw-kB3Keph<*GB zVR+U|r|m{27`@lgu`8;2+Z&&1{i3>{L1KeoFQL=k- zD+MQMJ%AG9*Q=ipNp@6u2mfqFQ;vNF&I7Mn{?)Oq> zFO^&(y$a$cw7v-PzTEjEQpBejUN{#m%zI?;6&o;GHE_h+;TCpxJl0*@8oidN-4Bx@ zqj^5@D!v4_*i7%heg`33vXVf`5q&Jb*-KX(v++Guivgf>IZawKbvf1DH5S0D$3XY} zoUMfcTAzi#)o$myQF`_1`TS^#86o`$%A)zkd-`sWYs zmNuu~LCZ${nuhsRlpgKzxuUw;D>DJn4H!*2nDUtd+j$0a1KD3DMjO#dyBbkxQk&2fE7;(3vA)V@e*$Fjd~J|qLOc2y zFp|vT{6p5_o((2ihKD@;Dv-=U^@Bgjfzoi{UY66315GRZsdWb$N4}vqH;v24ji!{N z(C9?2=x3$SRGOYItI~kqOvPRrztfYYSCxSW&s8OYp{f#_^0TAPvQL(L^-HLP0w;0E zX{;U}3R*pu`1>hLx9{bAxX(q-?}3Gh34=Pl=U2)1HuM{eiO9VVsI6|tpJ-mO?O3+| zG}t*W<%SvhTy^9i(=J>THXpax&KZ#N7s1Ujav0=aFn8aE8S(rh_d9n}abc zk4R76kdY~fwBex+4`T3@7b9+94y2v_)fG?2=B*GU;TbBIyczD;0q-7#fhd*nvY1%V zM!?gdfTwk=vsAzWWHT!JVVM8Zoq(s-;z4?GWKrtFR7$_0l`rWsf4|g1&Y3n1^Ar)y zjC!Tp8n9KG6;fp5nEk&@OZKJ|!KZZB2ZJb$BEvIb+oiUqk~faL7ip@MMr&WZAE350 z2R4e1LrY=|pIc`O#<(8!nfw<7@-HUfhLuPmqo4XSNazLmbF2?gS~inklwH(lJ@m_I zxs{@J7`W4t@|zF2q}mRmY^X`H%7ZO0tb>~^nXeFguEYKG5&qD(u;!PcXTe!AY`!f$ z42wHubUylcsTZ|Y^PCrwxuN0-LukXh{@^L79D-r%FAiDa%z%6}Cn5lPrSsGYULcxH zs_27vuT;lO$1Mf6xyW1-zX)i^q~vERe^brb&Q)_Ax8%4rZ&FfBaaoH3d5)JHHIEjeztyrU^86{sxaM*_(!$pz>6Hxy@$cdYnH|<#XU*|CrtLX8 zw_3|xzyW_;4!2A~J|H4gz+EiGCRSc5WeLV zoOa57VYXnwaf(J=MZWvw>fnrv1jxmBWik(b%RtFw1Aube1PlaSvT$L5ZBAz*Ez~<^&dig-`Dil zyRpJnSj%)vi{~{TImKzcynVU+M0JHoL%WMLdSnlRZAb|mnhzQU_#$9mnsYuh?XtV4 z*vn(yv%a7=VMj?dk+Ok zvC^}UP{t;miDogV$_TALcB&-W2PcaKvYG>00Y=*>2esf|EV1kzBLu^%&BZH(JpcOh zS+x7-ljG`NWz){Dn7|n)(HO-w0$n`>eVD*FCjNDjF^Y85Vbei_Nv1mCt0w@o%xO$R zC(LAEq71Pde6)k4IE4bZgOK3ec%134IMc6a$|Z1!mAn(H#1nC*6L6;aX*m8qb!z(Y z7uUEKZETvC#_$qk-&Ko{ruHln`s=xKLU>WsbH8<-;K$0?c@B$@Lb0sfU;P){%}w{n zk{|NDwpgb4ZaRnlA^R_9E`|)DG=FL4{B)X{mcEo7^%c)rVoy^J)ZpUGxsgRWY3@RE|H?PNn@Jhmyj=@1+nW0WtyRM9}K(Fpl zyY7yf#}0H?1}b_e(z&L;!gRmnV*leVLfM&(WRbrEFC+wG&#+oyb9SG!Z_wTl*@8fN zUjQGRUET}2`Y?4NsSs@Bd)IXsH{4Z^1bWL(G_`-#P49kaNs7E0{9_U)fsJ2!?~z!5 z0yP$M%KHm38Z73vvKqM%iZJQttRd_kdDyX_*8)9vy*HP1?K}CB!`h5gZDFMM>#+R5 zhqaYn0SQLkAJ0lAe8(O}P>DNMj^dp;7LEcj=9j!x^+>uYnL3xvS~Q|QdW7LNG7Dk2 z3?3AG3AD$!_Uqo>s37F$(GN4^gt{kxA3btSO8&HS-&c)euB7fGYu!C^Qw23r=h;;( zy}P%jc|)-bq}{-JkRsR64rDO``w&n>M6M#^;S|frH^`K-62C{U_AUB`0O*6|W*_cU zpncSL$=VNr8wf+Ly@Ew$Z?t4>v8%=NLHK0ln0<=- zRaSJ;7hn8Fr-D;l^3vZWGfID=%{LP}gChY_Mbk=T2;MLIZg6aiQwTe1;DIus@Q z?~97Z529-LXdH{h7f`|nm`$1J)92P-##Z1{ zPnc99!-WM(NUCQ{OGdRp7XukH9_!f|2@g*fv0fY`B5~ z6X16T+H#RA?-4B>r!;+zfcqEh*P~vnDwLM4Kf-;Pt|8Pey>A^ z{n-eeOAyTUWYO;PvJ>&2YYCSscRH~hsC8u9_!^}(`FUOYMC~W_V<1A!vSuwCr=d1Tm zYK7{{Z>T{n_RO{V2|KC5sbA5cc$1%ygnNh69F8VE3?r8zssZvO#&ZOR!V(*-3Eo^) zQY)s=T27wrUTPqFiS2ALa^WIm#~AghfcLu2K(s{Ze4DiEDwRerrQ^iKLjNeEuOdD+ zb6|QF`)1KY_UtUI1j*iPFpqpdo`j4N`Y%M`RV!qA2!-JXv%Vq~^|c(j@-PAVphS6^ z&7D(Ewd|5TWFX=@9clC`(1W7QI92!aIT4Kc7-X9{j{X{N`BH?|?Dx$AY7vEy_aqkG zldKc`T4PdA)EuKHJjs zfNAl|F};r0m6CbWVqyInQXBbz#CpC-VnGC#<|}!!Va@e?iH-aX$-J6X-(CtyFzKp> zQ(!HRlaB9`v!l$`>us{s8=LC|6Xxy>LD73-iOh#P0v#pRp@viZe)@EN`rLj46_yYs zM9zh4%F2|+@|4EPR3v|rn=3L7CMt;-L^0-(WBwr<3-3C`o3b+@f9?+~t?d}+Cf|p7 zM|rnO+%%hXVtq>*ecg~`mon9aB*J^p`&`I2>VZt_<6!B(-u!6_V7GoWXpHyHZcm$; zej&U3o&{F|)B^`TdT~v6c%FWEPUXJtB6AUrHo}eYle>XO3p%5HgI=T*rHb-p3@I`1 zcDp|c*~i8EeK|V{1HSMj_foq*!gXJdu9H#Y!-hFn*o=R3vgm>GHCPJbh230hEQWhG zFJTJNSQvA{?>A#ucCox)7IkY_B8o19vXy+|$>m~P&c+E7ej;B>m-roTipA%}T@%A- z95Oj&3_}Q+IhH!9YRizh+DUb&498c5X{u$)fdZuz(Evese;QuGc?UnGJ^1lH)t>r& zAfSZnBTC0HB%OCVlxO#*^sV?`4!%{w-tkVwrOLAmLLaC%S6Z0&@Kml8pf{XHPVjeZ zBLuOXlvgu}J%@Lap#S09iaKSmtSO#-(X~Mm9zBu2NAc%st;XgzbU-m!x76|rlMFaY z2kPnpZTDo|X*#kQc6nrqeC@L&7OvA_ z@Zod6Zf~}$g|OyxYFN|eZ4uiOfCV+5OF(byPuCjGrErwxytfxv#`8)_8X~;&`@95O zK5e4K%h8;sR>pwLv{}bl@HOq@t3+Dy9={k4E z-F1)mew?3(421V5+FEBq^r)8jsEdLrMWQ@b_cFsz&#wCuBb@+Q*iGz2EX_ zEPa~H`*yf}-yIS6uDlEOaflEnH4Pn)CCGy~{{$1V24>@6hm4b|{aly*nrIR+{^oXl z>DyLY){N9L<9*Au#4G*vL!13{Ci+E+CTjUXSs0|9ssN?wHEwohyDOPg>D|3TT1vBS z+DJKbIqZP6v0C43$Lr*-J+;m~wXVIFD{d*Bdx@QU0+F+Sy+&c>W0Fjh2*PufM0!5F>xFeSk__22-Sy7ACwa|jNqgXR z8-cM%6;$#eSlf7c!YhC!k(Ce@;na~GaPE+51Rq`9M2ES$B8}`uZkI2Ve^;$1zT3LMEz0Tyr z4vF50rfFiKk@2#O7&mCykS#lU$p2RU-WRjPtRhB^m5a&Rr~xoW$vv(TGAj+ zAaRAJXyu^B)$ECP7{L#x7#wz+Im`C8kY6y57vX~8ueIqWWk-y|S(mZM2rU z<1)lO@0lM~)+Mqw5%l5Y0N(E+phLrZ}wuG;*S|^w`raIj(-pwQPZFzm_&e4Qz7uk)BWk)<8#i+aXp*3c4#&M8|WpLw^|DID!{ zdGyk#hTwbRM6FYEQUUTEQ%fagB~$BYf&QXS)Ef^6v7f$wn)VLXsStbPy@!*PI7E)fXLq$DMJ)q#`drHBgyTdb0o$2Z%aUnd-OBQtSFRqr=+2o(| zcfh$6*KpLQf4RnbHE({_-5l#XuLaO>VT z4@KxqUuJe{f8#7vdp?=-&9*bYmm#o9?5YE*vvaNaP2KR_agNr&GM1Su5;mXn6v-1= z@U!F{cNgdIzRAISK7uV`nfzl3xT+CDKDcxapIw@6uRN1;?<)08Jj2$4vRhym?p|Z} zZkJu3Bc2x~8=pm6I1&I`!EXzEMT&5}gWy52gfitmjY zS3vZede<68 z?iv5!&Ybg{{p`J;XQJPKUEtT@XgF;MR*)_cJ?gE@+*~IcrNxH5H)~KZ^O)?dBHGuPRif!wOZlNZvEfUP z1FnblDe&_llOsFNg+it-_G91d_3Ny4A74xGL7!)u0~&e`V0olnLfp$3ng`RZCENRN zSwk2yi2Yn$;3Xx^T5qRY`{;tKdCU1}%L|$Ttww*&O!o@vuq73Jgs-Zx2x=x-m>QNW zLvT*~m(6@eVJ1H{#wGJnf_tktE*&6QCjhnHha4MAIR-cM2#yL#48v~ zC}gR|fpk@@sFH^cuWV(xB5m~Tq`jWKLTrb0TVNTHC@3(wcw=h6wAu`w4v7MWLzFIi z=Lo)-)97(C%>Bm0dhzxEdJBNlE!<79-1m}UREOd)`IEw<@4x-MN^qJ0xaEI-y*!G4 ze&wcoY0!U3rXl~*E^Ij^Ag&BQH-({0NpJF1MqyLV8v;T^8~E<%!Vx{Ln)vA6XB^Rf zbuT2{7yepdr=mcoU&n{21IpTk%AIKLWg-~&75DtEJd`QC6?>!AX*&4*uJ~nroBxCO zNcnn6`676y7!&Ez=>bsYr4fzqCa5A|GU1~~=9+cB4?%7uUiX|9F-<)~WKXU_Sd{ry z5hP*CJ7>)9VUZzkr}5fmA3}ZJWz%~Rl2>=YW!1}{EIYIQ8( zz%caaB9oND^_JA=c-l_L>g8+|cMzyGAXEenfdnR1A5(W`8{b*L)J!ahS%$h9q)HPEIB)g_55b zcb>q1ft_Z#oCcsK53oKlvSF+ z{w8?H`(qQ1>;QOMS+uN-)W7#<0M<`xt;1`4wOjX{dI&EA(8eqju0Eh zDnou%s+n0A3~4;oy}@$Y|IbFHP zZ{*A8T$yg0+r*w5_*h!$f-t1?e|)yyvhbP|P4JI*Cu zVXt?`o&Cm8a7n&0;(cYj$at^#DvVo1e5{ z-4Ngkduc5lkuJ5{nAXe*QPgvf;7vd8?pV-;s9TI!m78TB}734sK)rHG+YzR4Fzye{f%{K-U!2J!*1W> z4fJ?yXW5ZlVA-*k#bR;G2bvOczyS(KcDsUH3Ed!2jq2$5y~Nc@b6hn@}^mJO1hImrO&VWdRN6*r5uTqe>&QM`4=$ zr`dj1bcxTuxoCv^0rdR9&Do~8q95_Ut)B-Y^rMoT*bl2>?peNY*oE)$Pntt<39T-n zwTi!nKzedY&EkoC`f)!868Fl<6)ENn)47Us=Av8ME@V|Th#ec-Mc@~Pb9D9ib1+;m zIDBaW=;Ua>KN9^a)S5a~8*9mr4e(e)x0D3&r7RBUE8d&H6(_P^TG|0DQn zdp0`;mZ%UF{q_f)wxa%>wZBFp`eP!LCnJ<$CXaE636)etth&t=x&v=lkZda-Z7sc)nHJ3xmmN3r)ql zt?KuIjAOQBuMAR4Jqk?wx?-ZxwGIQqm{RRV^;BZ@FdHAMR++8!>2;BQechmRq;(p2 z?etBe>pMRj;TydXLy^G}CF|eUZv9OsN@)(VhALM5acRFF_N}(C$)q?>FS{!RlLF<} zI8WMiaoqHhln-MS5RqMg6FZ$N^P?y=lR1_Af2&M_9pI7pE&OcM`@B7S6^){OP1I&g zNH${+9c^Ij2O%y$Kb?OciDNmQW4T7>G?vRfynAg2x6?|z9l3U%%JX0ejkSs44HQq} z;G>V9w_VRzSAvV=*=PIo4t0h@l!{6B*VI>^K>i0tbEXP?@N-BR-XOkvPbnRRF1gh@Sq( z0V1hvPNbi%dM_-Lv|xxHkfqjV>3i->``2eh_{Vs^w*LKFl`3jLcR07@gsfc`?Bm*U zm(BIWYrR*qx6qM0Ya6Teto@mSeMU}O5Ud_Y?~F(oIFf8K@5>8kk^!4EE)7|QtsXL^ zn&0Ix`>cTc2U_}{?|)KH#8Nzdg(V!|U)>pt`c}vaYFL{>{X8qG75tW(M0U6aR$aS^eF*NTlGKw^0W!WodS2cW^6M{fWc zozyPafT@J4$y?X3x6`jJIum;LMHkJKg7SDZCulV%3bYg1Z0dHL3SZs|^&D5wIC$>@ z2FxI_{-cG{kf8Xd(efePjhQx8r`k~5kMw(NJq4F9lQR@|)R*3wu9Lq;Q7k_)jjHVH z({8^g`{woN4@jKg)c`9~PH)~++gAsN?8dm5mC^TJ_LdrcD$qzeaq&*(+&gK5j>!+A zW7CrjL@~+WfQt;jF#HXY?h@eXT7n*_B~MWb&yL85ipT)+!*&Q%Tqgr;gNpX&F-)%K zo@{5fUHFseErnk5NKm1qLG#@!$X3&%NQnz2uVQKw)Kjgn0r4-?n;XoG z@_aBBe$AfyrI)~}XLcN#8sGXyg@FkHXIXT)b)PUsEr7(lX$8ha+ufI;VE>T73Y6PrjML#1yeZzA^sA0|=BtUuwTB(oYr} z1cT~Jt0VX;p6%+8b#Q|TLr;Ps!za&B%v*aJqRH(aTlLVckKrna#Jq<%zG@Ab7!fO~ z9a<^aR8BYMQ@W?OtCQq`wm_|EI{f9IMDG6QCH_%3#MFK%qW6!;#wKov({RXZcLk-i zUfR`~B6BqDVn-lpJOZ=Jr;L%2nD6CL&bMx_@J=uHNcg@V31iZmw}g_qY1H|;vL3BVxW}<^6>{&F# zf?GnMmYn29;+kDR>X1ax*6O%U1(VcJV%;Bgj>s6o*`s@9A@1E3q)Ofwys|3Z@#yFL zvc0xIKME)70x`|%Kdx(UXxZ$-kjgW~faXe-`brcFTZt@5UW1~{5~1OT?~85-$`b+5 zXqf-a{k_CQek&Ae=Gz+K_?f(E=XuTER8I*X>mpcAg+vG@JuI;FCU*StgjDP}8CMxl z)`KHihkwxgT=C2?Em3}#@$?%hgWv`r_*veEv9Umu&M)TJRJSj~r|Oz;7AdclQ8oms z%TSY%YmNMmu76yI%EEV|-90Uv+iLWo)9f&tN%y)Pk=eD(y^A3?AIs*Jo8j`C;ZyTS zAdN37l@HOtQUTjI*3zl`o+`y4!0Cb#D&m1tYl;>fx3em;B%bge3NJwC$Y~=NdM~`P zywlYO4ZDy5#OF_e>;!VEFZ456XD?=k8QfYOUvhZAfFCcF3nb8s$DAIA>f28h?QX1q zo2T?y#4SMugx!Q3Fz(z1pRil{YNO`LFq8D7O9#y}^AbNn+D9w%>5)0d$_pbXOa*2s zfUGHJaHr9khjm!6A+3Gy-4_0U6lgq8PDkpNGI7@n=erHNUAirp;}I$w9ow^iEvg=R zAOZ?Uv$4%gGG#S6G9>pkSZ_xCZV{J{oZNo@JqYFj)c6y}Y-`U&eCNGLa>shD_|2@s zg8@&|@D?6*L~2~IWD4Mv8@c*)D~qF#$x$D|V>pCzYn6GcE6z35}n048oyCJ?mW%5Oy-rF#17~@ZO*4Vv#|K0RP z)%vDM;bvH0?G_Q)bTd8EM}-dAK+<^l`5_8MJ;v56Yoj4ms?&(Sl|Lj@y#8x#RaY2J zlm%`i>*MFVlTIsbX_{o`LcxMHpU+0}m3r>;ve z6EP1;kRLoFxV%?+a)qGkZ||u$%r0C91WZiY$J|G!6l4&0pci)-@?Inmf1xpkvV`Kg zjKX*LS@`(=zaS19-N*WKEIWuqMMly+%$`1)T271OD?1m?m-~ierv$8$5Mxrm<>2L^ z>mMBK*C%9kWrt7A^P;)DE5h{pGWv;(^-cw1DCqY-Z_=`-O)}9tsQ^7Q{i40)rXLZhj-La1MwWU69_`lVl_=c7Ka^pV<~R&(IsYn7{cYhpT@6q@f+TJ4kra5GsX--c={P2@qe6+myuH} zWI8FfDRKATqiUmTl~%Gy$*r@)YH5xZP9xrw$}E)1{X72OzwD5Ca!63^U5W!QfSKby zzn>poy{`2#!|W}IW`4_z_3GKYn`AvJ-{)$kCR;x{CR`JiraeD9kfjT=1M!8?56d$c zHy89Y}_i9-7$>7THr*Wtpb%H_Fpbr9v= z4emY#@mH#zWfxgJ7t|9HKS{Q-hTixNB~>Yp!L!^|9oO>>i@(Wq6=|4Ae@j;b8bf8KAPYUbb$I zHuR+74j4bDf|QpWqHObNk-YoS?!AA8elktY?bMiL?jGv=+#5_g z3*LuZmFb`debtBVL;Np(1^8KzV*TPL)2M6zbiaWRih29M(wUQnutzUWQfI==cZ)wV zXbJ!YR&aX90|Cql@oB4FZ$}x}aCi2&29Be8qP{^o$6IJAb@dwV;c`SL_pz?o){5EU zTGje;gQF|b{Xc!9k5*f#91jTv5We4QMlm$(Kxry#U4l+fQiDd#=-J=w+eNDS>Lg85 z%;SxZdPvG9QHWrku0lYOEuo879)~;A#JnctU-K?_o-b)=S=REKvYyDeHbDyXd3?flPqwag%O}K zeLvnvX;hQ9As|^+L$}swaxLr;h_mBV;~`8XXT&TVQC?c`>_*aGt11lfu&KwB4LH}9 z!a?bqptICOo?B@A*Q!We2jBh+q?ixtO#p}EB4!`&>FKPtSj+#tCIpWQY^X zQTD5`1YiGG@Z0qV0rsyfAm;g&@FM%pr&dq^cr|#r%{rV;y%D`5N-N*N7qv>;CnBn6 zH*!F*u=Lq225*f#_y9|ZB#+^{V4%B$Dt%&~NQYtjo^JP^r0;JeH3CfP$`P>To74Y+ z-Q4F$oQ3))_A~SgwR8)$gDuwh3$OHC{m0Ogb6E6}4^zCxfiAbu z+x^{){aqDzw;^}8zRb*zmT&jV)Z8`4Gbhf6O6GJXM2-b_lRPMe7I{3NiPyoa#fi!_ z+{tFCP!xpmzCO=}j*qOxtsVRe?aJu(4}xdc~SBVm|ejYsxupxoO+OT6Yuc5c3RT*6oM zY~#E)%-I+K^!UZvI5CkC8!#uE@LO7^pS`S0fQ65)o;z@hzAO+gUa0S#n=u=hEts<{ z!9+A@1iT(lUS40QQl#jsZtn_W{>{;~z4DR&OhnC1Mj0ysxy#wmLFoZj3i@*-_4c%g>m&~HOb z&wC1CjDU+5=HtK~=;LaMfJDjwuh4xY7JQk+tIblKz~fl#oPWNC;lHL7skyZ*_*NF& zW%$y2xOwil9NwZ1v(ZNatK{}1Z8g;lgLG*TA?}{To~?cH+Ap@mD%(~N+RgV}Tn%*J zJ=weD`izFIxxTR$irLykc9ylx2wt48Q5bJ zeDO!nX}v|L%eBruvZ9fwS}vc5cKFAIPkNEKG&CfTqF|L9Cq;^^S`Ky6S>pqi-aVh6 zcOmY;)j)A+^h%fpCLIf}J{u}|5DH_wpP!o(gHxVO49z7NO$=TX38Q(-C9L4A0r)$( z=`V}eCn&YM|1vyAo`nh#Q4&+GTq)M92)w^G@bQwNT|7|uLC#fKZv%mIL|rZSBCAq% zEXnGG-<@9|8Lm0JPP50l_t_Anh&-e@J`yz0Y49TTrQi#lz@m~b@eOTul$VwzG5Xa= zl|A^N(yb${Ev^G)*^kc$R}R>4#sBkn4JV)&go=j%n=oGLqFB$st0I+(Dn@E#zkH|V~ z8K>VJ?*k}A-sGOzp$`2~{Hi7|Qv1zt?e_7)*B|IUDrrt}DlTv3QNm>Wz}lqDIzx#1 z&y&K3WD(^@Qk^?t>4k-h)wSTEMno&+`GY(ZizH(^Mw&@gaIVwEouA`N!Jq?ejrfa1 zOf@_|5`Y)7BY!q{HioI;wDd@Y$)LIfg&eB7S5vujlzs@VqiNpr%aDenJdd7O__ilG zvD>@ObC2tv*OxrajC!Ht&O=JmZey6gEco7Nn{tRK%<-h1{F&mJIsN(r-=?fS2=C+% zZ=jWzTywz41Jx?FS}rP4$y){m=1$ikkq*S>R3m#?a9eObhd+2(;GpyrB^m!kXctI} zd-N)yKBpcbFn?V5oAb`O5dC8hOy<|ffi(BBJs?f8f5Pk$o8L^>7k>J6`5X#)TZ1xA z?rq0$u{{1{f)kvSXOgxzj$+%Tii&)682)&pY4Q;IFRaM<*oRIJKkkmc1AsA6GyU%B zh(F8)N~>>&Oqah&dz3N=^U9CW$uF;Jc(8!6W$BxW%ZLl@!nP3J9dXt+xbBgFP;FNI z)@P+<`KI&|n}40gX!S$Wx7qcNHVSAMl#dosTsX7iM;iAy5~c`J3UIzzHllXOYwUs52ps>1&@pqP&>INyfCv0`>O{I-mX?s0De`aHgI6S8$)>I>*~_hgv>II^Tw|? zG2KQZ{hnDJP8u)wlKQKRMnN_$v{Qdh^zGZ_COs;AMfQJY^Im~(gP(=n)b2r6#2-6! z2SQP=1SxpGox7kV3DKLhA@;1*A|dva)+~0eht~(;{QG#nP^6)#dpH zN{Fm)$?HxM=S2$z%p+%@OX&5zZe|ZlJ;$L{Nzjwji~Z6hhO$86K9TfN=AE|(CX~st z=JI&^cj*29xE5!4HD_rxb@?=Pn^UA@%98LxXjO5eZ1GCXZ^2Jwth0NP;nm(r@~SQ5 z_4)=C*?toCR%Fj_(rEB#6rdO*#omhy{@ZQ39VriNNA}E-f|r9&yJ7=OIVDN~j zm6f0QLSq{nn}iqC|Al6cie@jDhV4e*yeul4s{YXBJJ-0={|usc`0s@6*j0f9fEnaO z5Ayr9R>l;!T1zV17ed!sq`J+Gqq ztSP)I-F&-DDzi_dJ~#`c8SGg&FqM$WsnG=RI?#x}mAf*&XxNkEMT@`Hs} z0;l-y+o=Tup4nM-W3Njlo9Hi9V#!k&0ejP~zfM8IJ#dc>fY_Y$YeH=7_YnA)TZC%Y z=ykPj0iuGbHF*dc`!vn0*ydCM(m37YHvRJ?xFza--q?%W^tz#)?mix9cGaQdGl<=; z`NDZlE~xYYh<8IReIlh7LnSwP%Iw`~!Twam2B)8Mgzr~zvOzat6$?{&{KevIVqfR&6O zIgo_WMc?)%V&!nnWSZV~0vV)SG&Ey^=I@(1zw2MQkH^Kt@_eU8H2Z@uOQ~~0a!~^& z*U=G}aVY9zWIx6tA+X+u7^0L=Cz47O2MbE-58-dclXX{(kKW{@gsI^XnI4V zdKengOBoe1g%7I^%VWxx&^@G`u#W~D?q;~tdI+xo!x z5ZCr9=~y^v?Zv6)XvOM~rX^wNB}BM+YQug#g}L$h8hPoZy+Uw{HQ_>Sq3Cnxcjuy_ z8?^LPYn^#pF)`fT%hSyH)S`(KHB7Q*rHr`Cu@Q+4>@{x}fLk3sQa=WKN#im5ut=S@ z$k4}i%7ZyNPgiQ6)u~s}EuL%NulIGN3D^qp7Be3IX_Z=*k|lF&H;>RYSn2)AmD4#& z%==aQbx=Pca}!e%mtA%Djd!5h`bfa|rt4mXh8UhEyG}ATJs-psJ z&wg!UAXSW+ZEvH1;3-RUKznk*r=RIYpgQ%{WbFV>b)MFBEs%B4>pd<;_#k=-o~PET zoAj_ODsfMwdmM^L9AZbLLdy_*Y(v-s&($G)>5cgU1~a4_dy&cD+iP1Lt?bFhNWs9G z+jW7iICCSwb5dk!p~D#!(<7m{UMla-4=s-~x7cni6;nEg_UeLuEcj$>1g=qTP2`}$(A}_u>q%_lgI9KH7_0g2XAPT7M-)TdjI0Sw< zEu{P5&FSQS!>^F;Iz5#;!a@3zT)Wj##*?m?&E=+3=Hx%icZl5ddn)^HFEvFOXHWKj z8?pxrp-9Ki%C)YdPbnRVqE9n5YGDZ?A_XEMW0~Z~ndDBE!3)z&?rv)CZs6Dk7~+Q1 zT5Ea-fFUkA3w|VZ!66}u=kQyo^8{RPO)UE&OWkLNUqQNGM?+B2%s;;%=T1s3vVgYR0_)I?jjF!Oka) zo!hVeE9*cIoL>lqRns^fJ(vB(dgeQP2`s%5TIuh#m0Et@Mp(?xc-0Mcd=UK4ot*UD z9pfsiU}_QGRt`ge0?3UqgWeY?5IJs*4Z3FdC_qaeg+?Oz4(tio_*0DWrtYLyNW%}T zFR0~Se%!)yr)6um^t3t+d7h-;nV3=JjtDq!rwgqOl3iF}`S1h-EveGbfn59bgn#2F zgBceVa;mtva`LYU9(oaMI6F*6C$bJrXhkP_n?427N|E~J9Zjse#0ZZ5XIgN;(XFWk z`N6U@37)O6g<~d94N*i&{xy|zlZ_$29HzV87(+ONBLU`eZf}&3iU{$d=WEhkp|Dxh z`Eq-UNdcfn*~KDWU`1E)@aww33La%eTdMxTz`tuX{pn1tUpFyn_=<(ot0LLnT2@fP z8_c0!N#8m9VTT3tQ0l(R8>p8y-!gemt!`Ifrq)UC-c>=$AaHr=@lQrTTIknxJrM6U zTHt;E6Fq2Zb@N4{SnjaUC1B>Jw4j7_nF`c5t#?dMhcKtQEan<)4h4%Hi6C4KeDuz6 zifV^DRUIqqTCtONbI1PH%11RkUqB;uz2SGXh2E`t6A!e8>USgH1o$?&|@mN_oi63)9{ANuw~PRbK8c-{`qgO zq`vo@jFubKKQEeEo>6d+2x$9M*o5A9F~6ul{+-wu_?qq&>jBA>e{;|MIg^(LcP=() zXEnRjv5?dtFn%MHeaoN&SBW+fEW|2lngxULDgM*ff zyi+*$NRmq5?}rT09VT2*y*C+6EGt$oM&V>nTd(1tIQrKA7ig+k6WZKH6iyU0?|(Zn zFGQld)i)sx-Qec#$WR1_0R(XmE3=1kctG7MCPAwk?0?lmnS{njBKq*@$NT z9ha*r{464D6Prz9S0XxQ6>qja8a28dxNjfs2d+@b!1BWo_QQ~Ze+T^`x)M6`2mw_v zJ8+18yG*p)2y_G}5~%fiynK|R($0qBBAQ!x;mwrlp@n4>d^&T;HB*|>OOA;`3d&S! zLB`K9+vEDB>S79cxEa*AWE@V5-;x{3C*`e9ibaZWGm4@Ws)}JvF+dIyIyEFvcVLKw zP5JsD8}r&Wc&ML%-(}cxbtCiu5TBo(QEB{pWRk3#V_}(=QrJ5Y#;K~N`(J$bb}z4x z*6YS6G{R;`hyT5q!y%TEv_8FDB;&SxzQY;Le_`%Lni@ z9e$n{%5!#u>+>OpjpV`oU9{N){Sop48GL0ZCR_r8};D_fMcX()h>>_CCG7@n~U&O@(Ua*8+PgzTNv^cmKu?;5Jpa-~H7~zPArO z;hOtHL^aKJMwKC`KtI?eed@!KpIdNK^<)ASxM|=pHM1Av1HH9YK&PTVUtM-PF>k+^dQVD0Jpx|xPwB%oM{p#cww%uL5$jB8*KV3@$O*+tcDJg1tQ z!^ku;1+9_R@(mg1Eb70m!~$H|F0Z0{hZlvhr!hcq2=U&x?x8edpZt{k_9xor`W7af<7SZJDTI4S9Q95wAB~U+7YpAD-lxV;7sde{t-leIr zRmvZbo;v+dQ_@-2T)kIr)BI$%AV58%;Iw$w^;aFpCkNUx0NGWOzyH!Ig>d?)yv#i@rH zrW{6zdGvh04sj;+l*g7^-bIaAZ4(y4pjFSY+BffSO#Z02|CK}`;-Tejo!moQ(75pV9qSS{R{S~tOEUYO(py~4vg8$IneI& zyOHlowKVDUFTeY6AFbTP!6l?CUCBhgq*zhfR}-e;`Awp=&P)9CeA?G@JXzp+65xbs zKSyDQ0a6>Q{~5XgfqVvY9^-wJae{ku4Je~Rw@JhY7TXA}Pr5A|B1a@-&`I8jiWcTx?=>;F;#`c* z=K$U1=i%w|m6?XW3fl*Xi)+6Dr1Jz{#GWP}R9n3lu$f%@A2#c2OYk~{j&sdXJ3T?t z#Qz+ms|Q7{qnCZVkV4a|d;JFz+(N#8%}=3Vrv&*k*zUU4vh?B$u#iDG{$&}zwuK`a(oLWW-=#$glAr|Ea8BqmxJJjv-)Ds zj`K*D(8v+lM^_{vOroFXrawYPF__apf;HNprWd}^f3GQy;a z97eh0DzJZ{&=q96muhFJ*CkbpU2D_@M-1ePn|n3A>Q1k4ol7mWQTY|1Hfb{)V>6sm z4Tyn-L1^dsg(*2VR9`p`;SYjLz6+6>g;2ihghd1S9&u1FPi(1)QukB3Gy;w4^Qp=n z2fTb6?V9I9w+r1+M!@d8qgArQDL#zpZ*>=ANWj6M(L%u(y{kZ=70X+_j`ZAOHaW>R z4-sCsOH8BgefYq*o6v`BfH$`1!gGF<>qAOBcR{?+ocz=C7{?qM$N!FUEgf<$3COtr zyF!$ooTKH;u3a0pB3bv5h!9GBIGklE7&%*ky8$B>979PnJIZ9;xH7XKNqi+m$? z5+whNoy6@qN}=ECFJ4-zl=tzXWc57$cV&@_fCm%7Kc=Or zh1LqePCgb?LEB1TDtfUkhn{+l!eXwrWi6tU@4)J~%i(2&hy<-xS#mZ_Xv3+yK2l-` z`PX9Rw4%reNPM8+&-loIGmTjg6cedor4qaP0FelmTqQST#X*6Ue0?4 zmdOsk;aOXgvUfT5qh}b|=J@a1i}GPXno#s- zmoZBUuF%>6EWP>@5z)x`dJ*tG|`zq+a~ z7zREZUhTPmM7)`yanlG9lR$pkIfi}|1uiqQz~XI?rj9;9TCfWqU!H`{L;RsHrOQoO z*ZC%~FHLsc@m1Fa+6s1D16z9t&${jF2J8jn;@=zPKs*&%>3yZYz9JHMm^TdsKyC0L z(|C|+3t#Df$Zq@oF- z<>xPi(J^Ji)F2Q(L_pk$kud@rXE7JfX9p?i6q6O0cQsdnU<*jxKAmk2AbO$Qv;a52N~WOqdAR{f!? z@}R2%(@Oi^kLAY^SZ{))a%6G>3NTBi@bd#0Ht(n4O#Gv<5=`EBH(BhSVKd9q zPYp~mJNMbA2b+pp%?@lu8SYs2>x_lQkDN}y;t;82oUSfYq91mr`+1~VWs;$5HoR-V zHvi6S!jxp_4rq#$7cks?^zR{fzy<6MB1x|%1?(zG_CH1-p$+WX3;`m^v4;n)R$D5f&&~jhpkALF?uo*MM z%)VJMH|y0}|LTM(9$L8h3ASf;LPLQ9e3GG-;C;kN`)Gvk-$D22MW~E{={;$ad;gJr7m}Ca?N=sytG443SI5 z=f4A-35un$+jcZEonx=5Y`%Xj%Q_x+Ul+>i6xD)5r;oyg>^m}2`+X>! z%b7TUL9!E(JeKJe`_QY`t~sAOCH8TH8<*Ogm70sc zpW@}QkF&p(z&FG_Q}|{ki;C6zaD^W!(prTJ}Otjg(l@;lkSAEPF>~YZ|2)N|5|daYyYfn@j4h#@e-hkw(z}Ytz4Mp#0wnf zDHreRt9a(DTOiZrYdBSJM#JUSerpIk1?-U(wohP<%~gZPgl%}27XLZ!^gNj-B$YM* zokHFE@YJ?c<1K>x(`8zQ|73eku0oWr6kt z)#%d>A8g+I%^;qK*sl~^{0pvj1B!9?FB#HO(s&*s8v=_*!Q$0N=&={e{3_4?da3rvIWhibE^`2cfIwElM_HH0TLXJFW$zt^osqQ}`O?yo)Q)F4yzL2}T3 z;+B9kf#ux8zZA!o{sTMZ?db4_x$RTi#o3Ek$YrL-*a} zFs6prNT&MGAEUTaqf(7Ncr<+`V%eW-CY8}ydECULt5zwa@d8{hojP|U#gfeOxnbx} zL?v=WVRy6P_26#Z6A@t)^&LfpA^f^G5Jr;aL){v|W4&x?&S+*p=dIgI=%;}udqS)w z-Q@d*EWt)`Z>vjobFyOC9Q9$dS$%=8g=EeyhpafR>dwmw=0;)rr>?Fm=${dSLy7DG{lXLSEllw~}8cl(fm>S)Wa9H=Gh%o)U{CvBe5A-Hk)r=9No= zb0Ne`ts_)Ux!iEMxTkvrRRG*a{g*`YH)+9yPlRcGlOfZBSqwa zR`4Gl)hL=hSVLmA`!K3Vf&yfmV411Wlj5DaMl)M8J8b$ELhWEqT5ey$*~QK$Om>N)3b|8#yxO1+xx7Mv* zC;jMu%1*(DAnMNa)d&(SG3ZY}>b>2|xO(Ds1=oFzZ~Z zTGvT~#iVk_L@x3!w;P|b@a_r8g(nzd>=3u@M2Q_XBZ?eXdwTmS66(F>u6DwU+YWmG zq?yXp|LNHC|CfgU{--*CW=Z|44YEWzAIjN1iBOFHatCU1WBbEiJQb^ys%;lz9`pn= ztY=@?jXxC>Kl}V3(ZR;@Hp6mGaGXy4c%qSkDGMiN*DWC9ozA&;I27QmDQNy&q(Em^p(Z7JcpPwoMT9C@R%uvNIj40E@rIwDi;BUA z99~+2p98f{D0^AgdUiC<+9#0`;T4nJg+JEM%7-(yaG$#WNhBI%@3l{lfhNUJ4oAD3 z)nOdvF@4VYU&XSh1ovXWe-a>rB++Sgs&3kBg~>$uV>@K+YwCjy?F?=WoW#~HKyz~L{W@Z8EvERaMz=Ez6%uHR97_}8_ufW&x z-q7;sA^b19?YaTjW3 zjzhTmE0BiB>`&H#-?+bscC|<+;fFw=w6 zZrV>Dmx(a{*-(Ope(`0v_m*H=lBaf+4JpWBV}1y6M5nP1jjc>N?Bfe!UozK!Z5ooM z)V4vz7t}UV#x0ZCeHuf=3JjTwl=s8E6(fxW(OC=mg8Gl?&k~5JF1L;%9$WUsX`}{x zlgFlz|3Df~va($M6%D&O5U*!$jNr@OyX`okrGh#xrWCR(`0b*nM!`3XKN&F!n1y6u zE7ATspV+a*T6*W@z-CTZG}HE@?!R1<&$4sL&v;Yl)Wwa~1QUVNCXj&2^j?e;dm!-r z=#fXjG+12uFCT1Sa_&kaqS{`Ukj>tIwLiYabCf~bd}MBH`22u!526*)%4wyXH?)2B zhUS>9N13a__>uQ@n^Pw-ONU*?=CfWH*PjaCCd4m ze2pPvnZ;=jIqm^!uy}i}xmT*~&&7@C2}=8S#nfOy=#M1`(KRyUkL(Kin6hx2$sEu$}7Vfm_8%;3&0o6>e|%^HVD?m%Y^T zYLBfT7vDk(bVJo{@z<&+DE_4gFd2gps6cK7FGJwYG7th7Cybv>>Z?xazIlGibMk4C z#Ck!8LcV+-Leq&Ycm|-6o$KNS3}7-Dms79Oqfg^k6_}+ZwYy99CJ;T+3YbHsx=915 zf+0)-#H0SE(So)e?bqaJD6+K?)V_ZdZ2oq~4y_U24;rFng%o2B&McGFtoCL0<*+B9 zpN}Oh8Iz(g;@;y)&;wmtjdx|#-??&Zs@#+-kB`tj0apU~-Ak6-Yl81>aTY35*_!lR zKNN`;@K51WjQ70>chxms-)~1?Itbe;OhHZa)C5s4!8rENscH0O7`~GJp9Z|B4ZXFg z>%f)tMUS6#O#6m1@id9Df^t!Bgrl}Fmj3eoDUz!iE>jdrWIG*b2Kt9Qz!$!{yj6@>*okfs$m%?AfG29_Cmc~72y}f zY%LJz@6!koT?+fMedO{~@J_9_3NJ=xigJrhQTOIA#Bi7Kn;C*#u&G>2Ip$A~ly`(Z zMG=TQ=4KEfBF9r)ik!;n!_mvW0t(0Uz+!Wn%VD;nIhO!rn^&TMa5d5noc$^v6;nob zz(#1RR=X)mBY)buJ|>6YDGV58n>_LgBX&s4#7F9zJmNJ+mo#}~9!8u%z_ZBQjQ&Pp z;1gK;&?yS0yb4dX1%|)vtn_~8TG~dC#*0cE4qEuc2*)?rRB)MDX3NF{&w#{sag9G< z^M$JAXgpzY)vBV3Uttor`wW~secpAMLYDyxFh0snnafg(o%$=@Rbb1=+0x_Kfim!t z`btG3sDzGRzhJ8N>BARS-su!L!T-VsZm?jmBn?&x)&B4~U%AZZPVfwPOnw39e1?xyHCW^LquPn?-`!*M&1HmuhYdpdi1ur@b^8Cu*IPhU^+oTZ zKc%E41!)iv0g>*IR6-i0Q@Xpik_RM20qG9u?l?3Ehwko?6H`0 zuHz8S-g~V%zd6@8+s*Sk%`ssTkm}>Q`)eSeT_4mz>%TxxOxiQ~%S)W1JvIbl7N^YW z-x&Uw`m;{G?B8TQ^C!SW78As!>tQ1M50Q%J9jBrFx#MPw)|ac#(Xz{F04tG+duHgN zW)m^Spvv^Y9!M2n-6VtY1xE-Z4^822`@66T`61lm6TfCoqO^j36*p8ec79hB?WViH zeppJgOe6Igk+B}7z3ZfzvzMkUl#{bQ0!?5VwZlP_OFW1 zAhW})V+C@Xa_saQbRe|#;dIFZ3Z*$lrwBtI(vA@2FzRI142yl$N+anmqZPV|lcDWh zv|Q8S8O~aeLzHi!meS!P@MybBaQe;BIR|<>FRP35$$#(2wGAOiX$fIaJ=;7s9;1hB zAGODSv<;H+%d|6E#@PCQT{B?Ol24tC!sJCF*KRow{T`+MHLe2+-&yCvd4lMxh@jas zE9oIg)1Md5<3yP3b;A4qaa|mL*gZ%YcET#IfBBa&QtaV)P#hfkxuK?Qi=Ca|MS4L zzJl)Ht2BZa6`!0sx{8>UNB>e)@NI4nsKVtqa;E)# z&*T)piDTDEViQ5$jSb-l>OT?7%Lr1FV)qa+5An&|-h`05bt6fKk^4g->+WlHv)@+yGYzlEH!D-?lV&2G1OQv zu+74?azuhMoiGSX)1LtHNHPNo9(pX|<+q(xY~GhcFg|`|8e2y6=Ths{aHj ztN`2scElaG5b<(Gu`)(PCY=&2Ibuzmf;Rl%AOqa-!`%=RJ8<4GyWLsO$h&{Ji=4$y zwCqAV<=s8)R|=9oyZGLZrtb)aWlPtL`j^2t3T>QNnUG?DV`=1!fpFA;se1(*%9*oE zBh=4v{9fk=EI7xk?&NckV5%kd<}gA$aP~R-4L2UEx*L!HOXqVab**~jIm7Sg-~7z%d7I(6 zP%RF7J%@>lIc)cPEHUk%O}yquSW$0m9O%UU&IWlDS+G_jZ(jpnt0dbA0SMHo<%M_MDq5^pckfAg>n z4qI|~tI~PQ)ludY3?&Xu9?cU>=ox)ae)C?rv%{;G7FbE9XO(>On&MpGmX&SAVI&eH z8_9-pTYg32l(8kXUtU1VQc1Pd&o;GW#O; z!=rZ$Z%M|25|r0xYiHxAUAqWKwfsipMU&-(DSk$`=KcBGpGYq9b=yQp^>0a?hpNMK zp9CIyOv^0>Dk>Pwc)@PoEWMi3`geC8lIW_qxCGG(?J}8l{{+pt$)a9upzPmKzIDaR z_;?>VIcPSWp7Ka>?$*TUs-?vhC+BT^yw`&{TTdD6-+X?#=LJh_s=5y+^|9Ac@kUc~ z>lIER_Ply;M;x8Z9O3wl=VOvwXKneK{eA&kf0Ak^FNA1Ao2|<{ByHEqJ<%wmD9Zlz zr6p@b#j=s)TNi+({jENwGVC)67KqvzAxnS`1z0Tz`>cgFbn=cBVId6i7jTm6E~Z`0 z;j}ZiWe}$7DH)Hm`#Ji}o?{NN`kNe-DqhW}*&nJXVqzYZXn`uj-oD5b7EPys^~qf9 z<8#^%^R2_5#d+YMCmE1M3s}!n%s`#yQ;Ztro&sU@IUs9bf8D&s1pkhMsSdngCkeB* zJng~9pSLK{h1a%wp1~iLmo9w?Um!wQCdvCgp>>P#n=YD8j!`aNEuJHn!(7vRxMDc- zeb)OC=^xqP#H&9Og&gL}S?_!G3OlPx)KK*3UyM)N$6;ISVSGL4uMv47%|wyT0JO8K z*JBaFhVa*%0xjK4{{fT>637^+R~Xi~*fGeE_I1vW6EJ>+o6OmR_;bV=6aug>~(f_W!@|JUL zM?74-K5y610+8xPD4LPftFNhYe@PhPSrWA01E$c*zQQy&xAdAs6xw z!d_caWQ;At3#mucArRjs_bnpqQn0n!`gUP1w<%2xV9#oW=K0>0J%7cyIm`LdoRCB{p7iGK%u>d$eRRXoRCGLsTs|AED2Uie%{ggbe?4^!T*^ z(j?G{CT6ef9Ghpi4%cG3U#xHQqdE9Nm)48|y=6?AaQYq+djyiF;K1T=h0No9!Kw=9 zb=W_U%gm$-uBg;uaSp$FT7XO!bpAf~zDD%k#Y2CB?;s$0%Q^( zo`Dwf;SSm65!+LrjKiV`;s!vXbb9;lek|Bl%Oe52zOay4j$?m3Rw#%w@+#Y?lInON z$+fr9WgNd((V`1an0_?s#QLe5sjJ)Yu-s%C170@asgL!*6~n@ogsK`&;=-GD0B>BZ#+#7#-zo9WiyDYlq$4}izwsg5q)1K{TIO^=dAPOB=T8uT#eEt z48D+Mv}fpeCfLEFmJ$G_v`Ss@R^@s`R(0@>=w|Fzb&%ZE-_AqOYBRe@zECViqq^7s zB|XiPskgr*_0b;Mz#r1b{y9ogERO?lzeVKS%U*?S+U7YfG!+e&6m?m8IWen*meASj zU>Y&dbSOb`1!CA<#E2>fswpw8Rlg{WT5teKdg`8IFN*vjpfznchx00zF&%xJy;l!{ z=DU{6FNZ7VJWug=xov0dzmppbK~dzm8-8)8bi7IUS$s$uucDPwx-Wxd16U?5{KI04 zG#$U;1P{|tKDL5h3G$0B#eX*PicfKbp%SHghrsaPB$7@MDH|JQc6Y|okcd%}i2WIj zLaajZr-&Sljouj>nHd|28@H{a7a4Gvr|@ip82m&%&(Lf@#xTAiPPisrxF)XDn#Z$$ zMQtI4{CPqEfvTe!ogJY{-`m@7my3g!i&2-0iR*sseJJ614{3zFwuSa*{T$ngdaLL1 z2MgOrvGPXkFC~HErL zqPjDf$hRY3;>ckKmnp=ji$BRs#QpR?1!}*h1bcAnU-CFyN8d3{A`^$~>fZ;#z3x}W zO8Y?~W})kV%EWdH@?0u9_F!dy6n7=#-=@#7vELg9XFp94kKvIR#K(iAiT1y?iUR(; zI@@J2XB1wy7wvO0%li`GU(XY;xC3!_Z#VEnM$^2P%^`b-WJw@v@qz(E;!CU5jdxcr zQM;&J0mv$qu%&JI^y{~rc4yv^e;7Kgj}&Rno$dC0%xwhaY~jh%q)vEUJKT%kbXzv1rS_$>!N_&bd|;G+{e%?v>PtSf*Y1 z6V$;ft>Z0GuMzRC{23grM{28jwP$i_t8!|`S*gIh9IL^_H93I(9TG9nP)vWZ?YBW^ zADO&N4RQvf+ZDM@*cCP3d>cZeWf{P!Fgy-YKO=Q7Ur{|z%xr?cXD??}WL6tCtqbmNX(ep0u^3uj13-%&j0nlM! z&3-VY{(Tom8$fOzD41%&ccI|dl1y@#dBvHHarB9oFeC<1@V0$OVm>}+sfkw&JOYX?(Rc)|8V{}pBMywbl)er0$;Pm*dQ*pfxz}ZJS&dh0*uX-{kA5#(`9Z0Zlp%ou{ALW( z;R;46nRzkW>ID~tenBNiO$a0l>aKaTXMybbb=%ClH+vcG&CV~cTk zb76j352{W_(-!ocW@Sr2Ut=P_;OgTGJUoKQ~Gv9B0|xUkH9>{ z*za1zZ<5N40c{Q9UjNS1PuGy~uXcvU7{=@=8?#w@cs$P^c$|M-Ot6pZ7|m|LYnz4U zYUVL~vrn+u7wax7nzgxqj?V!*PGezUPtM|EfrDE6#Zq3`wfpWSW9RcK;CV%0lGDPSIifTnZBj2Vn129 zIA%0O>=K!nObmXp_;^1!-PtK*VFd?Y$Y3Xkn9LZD%<0rJ@qYg@tJEjmN z+#jn;pqh(#Ca3W&@oPA)%sHxLr^_5kRH>8n$mIO+`k|RcrTbzn}Vb&QNf@ z=j~5CyQO`OfXRURa>&*Pc3d&^rN#ZkXWbY{__{=K0} zuikX0I?nSJY#ec{82-Z#Gr8a=*OtneM{U+=EqU|AJTc z7^{%#(a~?LLQ<+=!cRftcHcyf5j0`^x6Zjk-xBKz{=3m8p2Brd(lr|@2tmVrCm=x3 zQW%n<3ZGxTR-jBrrVVe;W{}twdyC5QHM?reU+3qwf?I}4j1>@nQ&|gQYP?6%V^GmC z5tg5+%oHW4UbxdorSnujQkmmL8xXDSo3po~2V){m|J7J{5A;U#SHlj8hX*J34QR`` zzOP(LeI}Ilw>1Yz4k!0HJ6sAs6S5;V$^EMW+`CsCCT+c3^~S0Nu0zfqZ#@I9iC{QW zQosgdME}M`Ch_@Cv-t1@K$+1;ea5KZ+{psn6J%11VN*u^A)uYvbt%SZy z^Z4*_+;ghHBn21wm-X`JyKkw&uI)x1*KV-R9ltvlSob7%7!ZR`#dQc$R{@ag(X%Mt ztZdeg%lYburCHj{5vRX&Rtg+m#t7ldP!P+M>xcJHe~dT$UFm`aF-NQMdJ+Tj=e~-; z0x&05OYQNr%R2N%{U44*r4@&X2wkO_vn)SS9OgZZQ2Tu%D(9CEZs; zTroCdnt!?buTJf+rbWbq!@NXexdDCgUw)q^Mq$MfvEKxvM4RM-Lk$y7JEvx14fZkMA8`g_B~gG)ab1@p{yIjVhL5;fPpK-C>;qWX)Q ze>sP*Mtj1cc<>A}vn%Wj&J5XpQ)lvRK5XZ>p!j|<46pYpp~p{Y!$OjBmk$#e$>nq1 z1S*#!j|Y$5**V{Plb`c?_pE8R7Id{208)nIMkeE8v8M_q-l*kGbSB=kCf>ITXYH+_)!tWsqJJ)m9k*3UZ6W2>H;c8<@R5QS>75t~Vq)ZJSof8Q zu{TXwj1(nwX-<6*s!86`i%ygx;EN;hcyy@-3u<0C(*xaI_o`0lrHCyS(mlQ51bo|j zF+7GCE?x}XpUsS}mcP;?e#Mj=MnW?ySb687#{pE`dnTxYK} znb+EWw5hDw$^J@EWLA5dLEY+r;sf{rOBwK#H!-LiTdpTK3?XihY15zf3ol%Xg&y8j z1*BjPl06O7iTSB?CG(z1CS2$08Ysqiw$FZ3&O69CZ(5@jbJyw}C@McTsGfh6EOIM=^l z+^Y0KGele_QlH_qX2{o=W#24?-o?B0tal~&!7-v3niGAt2MDqVTEJkr^^g0q0fZP) zE{*G=yrOa5Ao;jQQ^u+tzs{CXtP0IDG_*#v+pKj2Dy#5gn8$tE2BTFaE6@u^Re$Og zLS&c`^q?;p;R|Cvet=4QXi>s~&Yl5xSJA>DlkVi9Ba~{l$$z%eNbtks#=C69Q0%Cm zau>3!B+3SOy#{zPB|xx`SO|vJ7dfViU;?gEa;{S3giTfAt6vaa7tEV@Iq2i_XAV#n zn}x>VoS9cU{9;ihw2P-KpHK?2_Bdq*w-rY7UJqMnTBx^2Uz`?=S0wRPB2JEvaV^Bq z;*RfRP@6c--6YorD^pyl<73ta&l;wfZ%pm=n^)}&srO5t!Vx)&+5n|3Fc_$&6Uqh}|!e4*EzSysb)k)lOZk9>+q3GB## zesnjtK^%==`HwNh30ELYk`N{*UHu?-2-B$ZF^S~(0&852;#**9tO;d}d$7)0PI!<{ ztu7r|jVKkUip+4!s7TEnl+6UQDk(6w?sbpGqJ(%hZd`Q9R6L`nj- z34U3+Re5Ai{oUT?QvJfBRu(Ux7lc)-Jb9B|skoNPktJpMV}f%QZ0$X6QY|~{S-~ah zVBP~6H(@u^;Rc|^tQ$|wO(%nbx@1EjVL)Zna!vDntMkS^-97guwB=sz&i25z>ISly z^yCf!+JX&nF}(|&bFXuD=eQR(9PlVHWxlEi>5x2uGagK_m|+~|v0SQ&9e(doA<9|p$;=3B5~^tw5X zHB2nyxnt5)kJfPbCPO05clpY_9lffm#fhd4uZS)WaqZuCJ}EQ(p*uS>X1z?t!BO>NimznqD>(WjBU-Gd7^oRAKpmf}qHZ}~ zYNBaw0x5R-Q(obdS%?yh>+MJ=i~ZxXqhREBUi;Xd?={o ziWyG`&#OS3LI%4(o+NtFXe(EfM)#!j^~FbvxQxuAbxGQbkKlWKQpyF*#s*3%ld7sl z#$6_-CADVEEJ>^iHDRQ^iJ<;LixD}Jciuj_WZ#>f+5;xu{zxm!(GjNCO^P|0_d#n6 zrOstCkDS%Ym5d)KwH`|?#P#dev(h54uYX$YM{qoT$W;?g8>8QG^TihDSY(2NpetUsQX$)DNZC9&$Mjn|D!Xi7a^UR~KbAa&_e zE}+qjW$0;@|JYQ^dyt?h@Bt>J#K3LVY;eX&Fn+XhM{`ud=7>hV5j3^<>Dq_FOcU4 z%w?(W1tw2;U4&c3CgHRH);hm?a&Iv~ovW$MZPq*xMOPG4R_$;pdBEOSCD*_FIVHEq zfq%*L71GXYivxB+&z*ke8(HVMo7X3Ifp3ml5(9S=>TO*Qh@-t7yWoKXzlzvR78)c{ zhH$Mq=a$&{aHgu80ozgA34{ZvD)Z*K_x3sFZByDp4>{LCagp@Xvu>!+w)g?XMP;6t zm`dCHrv#fXnZ#u?lqbUr#V@C27p>E-Av%S;MYI|g4DEy*ruTDc$Lv?X@EmuaU+CQ2 zTTD9?0X&F7)n=pU@j z%5-R{CcM3J@R1L*YSt^`@fG}t1DW>=w_oPx8o#2Myl}hAzzphYc*^ZTzJ-T0eyf*x zYZ^(2^TH;#e2(_gr%wHIy@9nLfoW5!uEDB%HalG$b&Vq^|l|#--YU?!FyUxS#)&bepY@TMC3^A7J> zZ~LHnmi^=XuO#4n!*#2?aF##mJ437&tSH}sZwR%qf39x`ioJ_UI?R2M-w=kRB#g0) zkLxdhx;cQy_a>=7HYp^2D1t1U+=b_=wr!}iZRqd#f0;^cg}yyoC)c=JjFdC(d78G6 z*_^RNT)V2(B7<))`TCOXi25j0yOo&NHm>CGK>&EYM}tqy`q>?N0uqTka=J=kNWW2L zY9-v6Va$^CKlEKqPMk-F37B3rl%s2ca-j5CD9_@~FZ1f^Us=XNUP-6*KAvBNUQv4` zH5Xr6Y{ZU4zTZ|%k;)K?AY^;LH)x8(tTCE8kU{ffGox(3JkcE4T~Hx=wxs z^bu*Sce6>wu!6k%wBbw!#=$f)q#B(MCf>5pNbiHOZ?w)ckel46Q^z^owLX#?wu)0{ zGm9NMQG3_ZW!`#0R$tA+r;(;JD^ zh{vaMpPKEg(I*u6x>m_=bhr}f*-dr6cvp%0gt!*PxzgnA{@V{_b@Awp0*Hsj|5itZ zh5p?b$llp(L))%LsElf)#-*B-&N}oxiQ#ZhYy}%#A>{oSTZ_87^4Gvv6$*k#)~$8! z)!__VJMSY*GkX5rOhZITRvR<}dO`eP#ZXu4k{=diin3^mp)>EjRm7)%_t`=WK@!Cy zAY6VHq(Rla%$>Yz>{(mVZCfyq@oIa7YxT16rGS>J;enQ{`qPm$n(SVx>>t^l`Y|{o zxt8JMLt0X@>Y}pra_12tPj-kdBpyCh8_YiV<59zjYv>l6A>YH-Axn>!Q$*YDWJ7kU zi1YBrEg02J#8(q7@I3D7-uSTa2H3s6CLfUEUg42s#jZ23NYnmR=ZNW*<3?w`D~mCp z|Aj4WU=M9tRt`HV5Z{39pB@A4C-kFnrQ_w$=>kE=)mpUgVV@|Fmz zAc`qpim4C6N`Jgz+EaG@$tOf-wYvK6RK%qJT|5s{YY36{91ir>#pk217)s3*;=JK)(y<@21H)pB~vno=*hZuI|YH+zS`{Zm(V>=p9Sz?FEPQx~pjSE7S??2=JWs(7) zjZ2rm03;ZYwv6*rm_VN5wZ>&}m-8$+jPa^s5=p%m|9t)RMVQV(Lj5AQYs;86AH1+* zzE9_XN zf|kFXp8qG$Uci#SuQrjY)sD0a`T{1-V`Wsi`NZRE%w}9Ce{b(kWJ$nxD#G*{&t~D( zu08LrJ?dFa;#o~Id44`8fjLeX&tCv2SK#Y*z2GF>(CZgiEOIr~QCQ@>yoeC;14-OaX?8 zG-&9qKdfbj%o*^_Skc<%j8|$BWIOenl`u5XSi4^`-9r{GoMtKtj-_O7%g|2+8PDne z)0+KMHBAjXdRyI!jBvIi?CE-<)OSy6@6Kt zDAj}zNC;jOf4TQK(rW=|?=f$x{q6}bZ0SLX`)I+xlYd;(rD|-UH-k~fne~xL0KVY@?WK!t!o_uxPkcFIa7NF<4SFK;UUHq{SU2P|Qtj?^m$gDCk z`0*Y3W$_}E{AQvV5PXon-;Y=bPHgLbxqgaMG#fWnzT+tlnR%8RULhP!AZOp_&&eb6 zCZZgXJ&`tcL&G!xVMhJw|_-sby8ecZ+)^$#Z?gmM|EOXm<~= z&8GWRn^INf?m#67NVzH2Uu-u zidO6mCI4G7o6gt2&S~E(ad#KTBzIN)COdOGv-G+7WUZx$GvVN=ZaLjMZNZRarn7gr z`>CFj&HHbZ>Xwq#h?S!T2w%Xz-1{6Yv;g$?2saUa_c#|64-)o~u#m=2^tkSznLg(o z?s>{v~Fhoe@bsYmb{EQGX6)E*S zikq($_eS5i3SqnXczTf!QW#unLxxamTmhR5ZG0n1uU%1q;F}Yawp6Y`Qj(pEEct)lXTjK_Zqd$WL!A zdia81<0*O!wTdhS*Q)1S+sM%6)QuLPs>hRG$=q>1(XUy8PY~0}Cg*|YRC%IX^<9P5 zxD))DQ;o)Ev~AHB0*fVYR8#lF_0$lhD*Su%Su8Ngd+#kj745kX?5L+>@*BNmtkI0u zC6llCt;eNwv!kDZvp1Omt~qLw%(PumH9gm^-k<)h6|UY`4K;w*q+i$mw7^`lj=?9N z{G#ivn=T!8kLOEX49C7S4U6>-EZ3NYP^(Fd%3YhS<^KB}_z6kV^S!sX%$`rnyJvX)59a4UUdKN=F!srCmGZ<%{I#>3OtegEHm(v9oi zCpGB?`vA01f)A>#=ZOn6Ly8`v8a~6K!gnLezhJJ`9Ep>EaE3lckni07inje#)5z{4 zTtk9+A69SUyj-3_eui#Brmyp^UO@RdsYz-#*CJPRaQE9aGp`npMWmgUX9WbLzZi8( z&c<b+z7zqo(;ip;BhH6rat8V+vfVm<5rcR(tI8oqoV)m(U3?* z<}ecwpcERzmrh%WfAmK4IV1*rHi((6eZ(p_{G3mo{ioZVEF=NJGfE~sUX7*i6yRBJ zVZ{!0w}bf^B@;cEx&$Ivg=d7Xe%=GK!V{Gf`Q$I$}=@Wj(0qRC_-khY-F? zE_uT(fnEVd>#mxGA2t6wyj7e!f0eyaYorX$DDb? z*HO%2{}3n_o87G&;PAwa8f$EG;QUd_{?;w>J;BXSzkA#Z7W#Xnn`aL@!vDE9G?iyd z!-RcpF^k=sE%$>aX8k4#>QiS=_YUI6#^Molk9iu_aexMsIi$6};l+7xER)4=EJ+YC*0 zFq?Isz7d}AwGN?2E*Nv&KbQ<7e{?FWR0M^u#2Bh$k4ykfLc(NzDPeqNTRwSlTsPU6 zP=hvl>x)dxl#(TOi@kl#D(o`r3$jWV_9qm^@PdvDBGWQG*OA|RSl8FwH$_Bx{oI*X zZas@jo3d73VQjoyqQ303Jj#GC`wJdL--na>4};=^stnFt@JyA>A8NUDEu36qS{18{ zxLo86NXnI;9?$LXct33;tCZC^seojOKNEFtIx%TFAur93k6}^mom8I4k`DCZVgnb` z2MDvXI&W9tyQWLG)_`Q8spEM5Yvql$)5R!=OLSbFrX!GqeI65AQnd5r;z|dU|N89L zB(-g-&nmr}!yIW8utrg;gbVk>uDgy}ScS6XfyKwIJCOaTf%_3P4Wlz}Szdd=sRBf<5gJFx{fj}0== zQp3#FhPLyREJi<=?mHA1l^qHChv}AB|MB0vSH68Hh2HI#pe%8c3A0yPLBfcJw)qYf zTmv?n7D`cesAY~x+^))~mYCY-Sl4S(VCtToRs6P72RZ5G%ilwIq-B6*Dmh5TO=c>J z7$n0sGUiLbcG#d{u7i}x=Na9yP{X(#MG z)E3)SFO}$e=1}LH^15Zl0xs0;W`kx`Gf!oD_PdY6sz%tAyj*_%)E86z>lA(579vSe zM94dmrpviF_e3I*wF&y3BWIiPkzy!bdXJqEYz`1|N9-ZG?bKmAdO8pq3~dldmr#|S zp#b}Vr|(nn&ukk-bShwejOKa4)2fj4pGAl#;U(pv2qeV=o9uB_?kFx z7*M_WY?@NE;woT7i|K%HOtqh;K|%tuZ-#6;1aGx}MlheQm*FT`({e0>!}+Z4EQxk4 zDc#XZ&lF4F?q1y8U5IvdyjT6+>>5yE(Y2k?tBTG-lroD9^B{i;5IfJCD0?tk2{AYu&7hyQ%mNY#K26lmN8UNwOz^}zXQO5c4Ey3ct(d~r_qQBGW=*X^9hR?2e14v@Lq z6S;O7{c*)Te{&$QXh!<6o>0*QdVD?IGT4A1pHrsbu;I3rXvae8*H1W;yy`zBO6pO+ zp!dPZL`t_?c4K`#dos<(E}s@Y-5IX=Gw!?)atqhHN~-%B%-YB2Lv_U-g`OF0dH{{y z&{9BE8@hE1`dH!feQ7SYG+;aL1gT-r$1P3JEv-(~i2nUzK;F*!Gu;#AOV?35#M_9>o(2 zdtHXbImh=__4fw0Fqbz%qeMO;a_0nuXmf5lrsTytu!FjO0lf*FA@aec9X@W|iQ0$> z=Y7!V-2@b^{8`Ex{iya$D}KqJ6D0Qo75j|Stv=HYVxfEtVP!Yt&x1I^DZ^HxIv<&n zev@pxE+ouSl=oy=SotRT2g*VwAH zT=IY9ld-d0zo28`uF7-sQ_;omoxp@gj@%HLzwoY37Bp|-3T)fkNXj|K&#Je^oaa?D z=LFPK2@U>uvY!`p(X6LzM^AD11%x?3nf)+ewD0O>7pz$0N6@nz=o8t~03F zUI{fgcWpyWpvbd60(|`YS79?SdvW2WM@hme6a3Shsg8n!wa89tnCDo9pZlXXXFvDv ziEI!KYH-fp0e^7=u?8lqyB*s-j!Ac#5ob#V*q|aUx~Lj$H8nn&11>9-Xlb^@%X!?V zRHE*;MN%(8j2R~l(dS%{xHSV~w6=P~e%Yn_a&4y&cMHpV9~#@g3dZ0 zMm$6nDygc2egX{iJDdU_HsVjWH2Mpcu`6pA9O;GLH1JsRJ26CQc zqRgxYI_eO^N!y!i&>b(eT;yK$O&8=T4~?iq;haPWwVEBGQI-h^=N2dnDAA?iU5X4t zjgXbgk5rLadLh6jW+Rafx~d1=kD)CQ5l@7ux9gLPUhlNKDEWt`o)DGR>$$lVF}M|l zOjci`4yfvAg-$j)yA|;Q4<;~uPHl*NgB+pnbM!>IB)k|pLyxw*o*p{b1=q@_|Ku5~ z{>xJAh6(7Su{@t6lxFH->{&P8e3R_seY$o}A0xb5Z~_ES;6O|J7Fa3>;Iq(dyy>BAL6fvTNRwHWcXsic89!*GU6K z^-kU_%{g9+%2*ds@?Jg7IkH}_nsXc$l~FHLK0Jt`UPoTTWN-B2$BUyiR^W3A`jxxA zb;iXkorIDcg`tICAeLXiwewn&xYEjF%(>KjG9wzq)E_|Mu(&cGDrFanxH5j@o_%&e z*@Z?qyC{FEIF@1O8T%*iTAsjf%L_u=e^!N*$+VmBFm!qUOUR3(eyk#3&8K;~xXOdF zGW#)-<9SX1&d)oaj#|Q(ME2IdK&WG0W?)q5sg(}A0XUCI-unAu?oTP)g~cp4`6js? zXW~23_wFHmh`f6Jz6bi`EX9 z0(!M?By0S6J@QdJ6#~Zq#-KQ|85;rzs7fK51!4>eu#4akr~bwmJab{T3?^OYafqc^ zebW`!M%rzFwf=_QA@;c2p#NK2qA8Xmbr5e{+ibC!koU8t5Y_-qpo*1JVds^Yj=@`|*rMeTh_=*Ea|P)!Ki7uS2LJ zHi{q$r!!?=Qn9|1a)uHa-r6Oh(Ds;ILc}+Fr0?R?Q-f->ehB*S*h~I znCe5dL;BA%_rgddDe9uZ-}Ra!7Ga}GPtuxc;R~mlH2<)#h2N=OXLh(^0u{6XUe=4QAyd zCGn>p`<|g% znE}@;la(tzKg{prFU`Zgk5igQe^+BLCwLg5A5_rx(tPh*1!L+hWr zEmV;G3FQOot6Evdrn(Si){zMy63_Z6^;%tq(!^-;aFp$*TCi#!j`8zD(e=7qTL3@qn zp0?BTBvr1%XCJ2LQD^dFTJAIV8Vx|JE-P5#0ezbc+vxB<9^S^lmqtO$`YgI7o`#4o zEuMyf-vgkat$h}~{3DA~6>G5Q^VR%qM+nNN~`8nFYJ-h() z6(TM`vI)2Is0S)dET-B$-^%K@N!c|F8${w+yHy_~n9JNUktx5B4 zT^^C;^$As$PnP)9H&?tSBhxoM^m4X?Cmv=VnDM&ua>auu(!hhk#moaee*VLQC@E(f z;WWY(Q^V*#Jp8n&g_}6$dMLec$iLV|*>AEGqEaIrOD}JF8at@`3 zJd`X2NXQMP+epwMbLflEBC8mRAUzDU4=N2ZhaotKf32gA>Wn@-^-r|;E{i{5F<}IJ z5?`$!w5Y0K!{vfcpY_xvUP)>T=m<*{G62^Xzd^(va)R<*G6B-@lnnm1k)}u|7CjDx2$38{m7k(5v-=6yktfn z3}9QNj;*nHU5TvgUZK1}tQ(FnVxxXi$IjS|n6NkNrV#+lA#5e2cBp6tEyiKXC3Yzw z-)FexJ12FKO1P^|pMA&d=Ab>&4&UyZww-lB;Vu2YsRg(ualYEnbiufS@6?6fPmH4I z5lsJTY2#2cBn}YYbw)_5<_I2l)?qWlO}qSu?*>#4FBQ6#!F;51D|Uo^_RZ@_G3S90 zFq&x7QY@3z@jOry7|8znr&u02B5hsn*iN{=8<+cC$DqOeVkg^pE~E-%qu0 zFo1k&B{INwTA)0@ck(bisGv<@pfk;s2B3UL?~B;;AMLhD!J$u+O_T1gME+hjx)+P{ zm%BQ|jwopRFMR5R1azu&l)XR2LSs{2@F=Y+GW9t3NZwOEstSjc6k+41y|N(fR9tx@ z8rH^RNs4Siifl=GqMN1}MDT+y%&wZ%8=t)0l5fSk>zBtuj6n(U8~M!xhjq?W@O{sn%mbpkO!eLh}OKaW=u zj#rZX6(2%Ve`+!N;!bGW1aZp*an6H`am8oU$~R6SegKBx`$^3y-`a;pe$jvODbplV zV?1;JgpKT#boQ1jF$G)k%Vki>m*bKz?2{r=|BJ4-45};Gxw zy98Uf6PyHsOK^AB;2I#fySvMNo1F9ASNFbmsbPTc!DgQ)b5iQ?NVo@sJPDHo94<^0=+Daf^69p+> zSsqi@Kxp_kp*JyAX@gRN!|J zwanK$TTC)uV?WXRi)j>VaQ_s6gYLf5QFGIqnW*J>~qK7Oq()4_>cs<+k z5}59n(hok_IdTR03RzG+6FwzXraa9ewOS7!d~Z{7s~F8`v_<6Z z*Z;P#p`Xo0r{~Hbijm?=Fp2@BIC|`2_IP^eH^44NiUT|Q$RBv}>8ITY0R$PKvQKc=0lR*i@f2%EFp2K zAWQwW5i!+t?!B;*yL@S+0R_O0D{>ocpo-+j&tbKyt3bQ26!Fe}d!Rr%x_(1XpW(pp2_E zHc-sf8ZQX-4Zw`;&Bq6N`2n)L0u_!2-}mde^D`Y`-ne<%9eh8fpYZZq0Vhx982Wfx zsqv#OVy-n2ivIf#UG{`~9I&G-k9gOaVgj&4wr`np+7P(n2|@x5{_Sn{4S0umf}|D_ z-nt3~<;^N3n&Hd4>X$0Z?mVlkni;&!pHJZq zrxKg1^^88VYKpxO9o7d1iencg z1;8f>69~h4oOkes(v`~FSle{FXVE4d_K?5rg{FxsQgj~5Kl;D{Q0mp3Ye4UeRwllv7E8_~s{gH* zG91wRm2_wwQ3ky8B>{iL=WbA)AdOGww#AlkcW6|4my8RcFqQ(n_6&CAAHw7*O;6`< z$U48~m}Pw7$<6qprDbzlpJu&~P;^A-Ka{4a{+|OR&zHyh>;MA7AH@Nwggy^tIx+KpMqK)^?;izh@bj|74SGP*O`H&3J4X6L*Ci+1eLA*+xpa0f;dAfNw zJFfN7cXZ?C^Bup!&%nJG%q6lC%ZY(ogC{fK>DxKLtLm~=K{mD++bE zVTgV|_i|q8eO`GZR46b+@><_=Sj78$;UdQWh zHk0XQVo$gt`m{%nfg_i*WOfHhoDgqSme3`Pa~I9(lZ$L#V{|*36({lRAYA?wK@zl| z46rp0O0)l5CGer}BQyq^|Lc@v9l}EF)~OEUJVc9It{zQ`TlO2|E*=WWWl$Hd}o#C-xP3&e(xz~5% zDfvjp#RJ;ffXTDoM@R+ECaftWz%8nk?%iItk(GM%TN$zkS<6u*s%W(t}P48LE z%IA*kzAdW$=}?cfSLaCmMW$oi{JpQ0Ovk8MK8LKh^lu7TaSC4$Y|0WRAnRuqvf~c7 z6G)o!)CwbwbZdEHpgHAw>TN^4Aiyx9^m5QFdAICvIe%q>^RhFGJDwjgrdtV^VPVTW%IPxde|vgGICCbJ3@E?P9NLwHvX28&Sz6bE?Ii5uttB6LnBNv)AG>?0 z)6R0F>c!sSRLf^0+eF)kR>DE}%E2hf&nStM(!=$V`^#|V8ad5Rb(+Q6EASVMwO8&N z44vn&`xc=fYCoO|eF}t0k|3k+4wH+6II{-q)k4veDImwQmn+2s<-6WF9HazbRZGr3 zCae=z|BkYp<$||eV8ZSN8-8;R1hklX+(B5co!u!v1{O5Yxmn4$S;0r=BEE<;m+T`H zs-^N?xD+F35-x|_-HfT5-N6dq=~CG*k{@b(A~hT>`+f^hF@u|=4DheU*w%=zVgN95 zoJBYNzgr|8QXffBGsi*GQ^yBaEKeUdl=m%g+Wt^(3%o=?0%8VR3{0(V_t+fw*nS*H zpRE>9{$&05rW4zrbu#gcsq)TGF2pQZyhbjr%vnw|zzkPTGsJ9Gyv91N%I|o3AsH~w$dHqw)H2#HM!9Xm*(?(0d1CLJ-IGS*Up<8q8(IeXwD%06a zqpr}2T&#NCERKqJ*=&h1e;DzRCrCZfMvtMr_B@(^@BAK8c*95lX) zTGNinRSE(xiRS<-wWS?;Pc!)A9%OO7fJ?vPw)1ff%mqQtFE%&nGwJq{M zw+1?R##@QCOt9{V*8jjKw5tNvSh6szYk9F8GS~ye z9W+Yn8REpRx@U>8-Psp0uzS{FAxvHv)_Cu_678j_J!A-8%=-(9g001tJlDs+GOH6h zvlBY2{;l-n=OM;NGSNME;8r{d*}c-8P4hJ3dDh4C7k(>g)#jFk`E^Nxb0 z>mhC3p-)jLpP^8Qz|YyXYQsxY)IhIl5V!!7deX+!2`W=z!0nl+n4bSc2^N3QL6ov<9FPQ z{%A0*c~sPtm9y!WiF=2QdzbhRul^6$G(+KV0Nh5>`|!Y?rl-c<1dqD==;s;jHJlSD{<8+~zXpH5|L0(Hi1$T9UeXz{=AJ zb~PpL>}CM1;5UPcQH&CW4F3mAb1c;l80HwNaG2&0Z-DV;f_-lr&P9?VTSwOKDt7bc zjxThd+{Q@H5{uG`^BzmAyr@8-D&ucb!Al?r^z(Tw9-zq5+>Ly8fU7Tp2e;{IT^bGn zsL!B?zIf1Ew}|{Y&{&5l_R0X*zyU=4ar zC0g^P!OD~^9dx@fZ!K>%i;XxR*#8!daGe(95KE(nKNi~AF}LSJo!usjWp-&&22n1 zCyG1)=|)-DC$;$bdvoX$H`UL3Ms$DBDefCS+1LNlx!2gdR2t}Br^%d3gu9srl)1S*~Vw(B(^Qt<$(J0az7o9ryoWWjV` z0DBm zvTSw)H%+i?G+-PfIjy<%`{Hd1xoO~sHz|9Fcn#ujcDVNY{!aoPRejY0BfJ7v$gB#U;J6UQebA^71#NJh*US-yfcPKHM)4v}4y<&M5t$qe=el*j zTpR1}vyC?8miiInG~VB3i!u(jM@_jce#CrzqYC5w&+oZlvEr1AQzvuqXH{BH-ztqi z+@5tmzym*)Mw`ddm!g{$)0g_16@R?Jn+f*)+c@L@6e!j4>R!h%Ss`{pKT`qq24MDo zm}K<~>72q!%o2z{vhshmjU}?*(2c9hz0-M>l_fiEet92s)^=kUUkC1WH}U^FI(N%5 z9OLHK4%iqUMNjAOH&RE`IM6v_n7-50e|-8~A8Mw~H94EcGoHFanBZoB)-+UY@n6*_ z&&=qusJeY_kWKK7z~lznzGK$DBQ%M9c5fRc|7g@cYh?`D75`-SzhHyzO`Z^V|}!s8`lOnKPI2@U-5%( z>V|4L%D8gO0W6qPoK+h6#{P^xSR~yN?G{p>~0v1plz}F}F z)m6B6ZGgpgkD~t#cGnwXQdu|#(tkC&{-$(J`^DlXK;@kF*{HIDt*{v!qp&-t{Shb9 zky3I23$0V9^KDHt40&V~N+0M{4^RB~3R6i5wj=?$#?X2%>rtJ~L3?qMs|i0*fr=@=qki{?eWV`x757 zzCgvoU3|fag*$(PHxqnWE(^4zpSWVRvC=a2nmeB6J%8CbZdp}H`%2R1svf*@$3R@A zFkGc>q|!z2pMKgK5)8+)tLS@VMLHV{u6@iI)luITCj@IqTKD5#qp7YcP^+VKiBo$L zzs*aM0qt9ZZD1v|jd~rg}xi0>AX8y|eR_-$j}Vb;^&| zkRTe*{;(6yEhQq7jyJV>-1oU=S$XX*S0Qp{Dd2$cQ%`=PzRN}9XkMOsudc^s7MzXQ zYkBY`(*e=hW}Va02o6Ui>&%~#?sN@ri^e*4NWoLMVv1xxc)vyW$|Pf`6UI^Y)Zw^wU9#q%@z=TODkEeanP}oW zhp44zD}}6G4A5aRO38Bi?;HRwPPpC8kiGS~Fqv+)Mr@aho?0FTN?1rsnq4%bQ}VaH z!83<*VP%1{2gHZ$Z#tyEfr%KGBmK>fHC#O+k8r5(zEI>p!QsA>K_u{CSSKoSGqV|e z=D7!N3=)_%SiB+-K7)qH>;_4YKoy|l7qjoWS*R2G!6f<79QMo;nRDrEm2^YAwCLZ{ z!bbYRGl2wibT4zXm4B!z|Iqoj{&%vE0_e`wW;)v1<=XFx48eMRI3w+N{mpf?P8#2- z{L$wn$|j}C;y}9=T#3ziqY*ZtgND4S0dP*-o`H`?%+g4A6&0N;NPCqW_;h7?2NY<= zDIOBC>he2<&8$j^iz$l`r<$&V(m2fg)w1^MqikQBGAW7gNcexjmLq(ILjZ1z4s`^ahh zX&Q63NgWZS1g^?A)M7kLlmT3WWn6^8qbmeNA8O)SApAf+WJFgbbWP)*3H`PpBTYbUl5NUH>v5vbF z$?>CtmdkqKPa(2e?V-5Ap@ZBDpjg~Val=#a8ah+9mOOJ0j;dy0`~WeVjo%a_fm|bT zkJCu-=p4fh_3yLUAwPf{85dG6FxW&JR#3W6^}|-016Sg09Zca{U8YX;`>NoNcK7aY8p#vVkFWrmDTZZ?ohmwh)iuv1<_{smmr=<(cnl*fpZ;xV>-do*@0@0}Z#5iz zf`_YvhSu%!cQ+A%eyixi!(Br|dv*Eyy-`;akub?fZ|JSkUrp)19GnU15cibScunOU zcsBCebeXf0?9!8zKhkA+stIl6`)tZS^d(**0yI0=%EJOdYEkM969mV?ltgqLI_pg0 zA;CPzb&I+LZ93G7m<0+K$AWUFYBlNWN=vxf2!~4y8H}Tte;iyr#*J0J;qSB>sGNF z0?f8Gr6HE4ew$S==9+GPqfKd&wWsb~lIhoy%HYR_VyK{A<4~6?08zc{J=I&t3|}Wh4_Cb2lHI=7b$eB<3wwD7n*`*6>zDg zg`*mS`URt0gZcty6|ku`g>N)(luJ6!^60tMgO_sLS6bxZ19TFpJC(}PsmwvqLF(-K z@8QOMy{ACwVQVvcP#Andc&OCO>KQpEZK_nYV@; z!oIVqGO`YjjGf@St!;xLGl*y}1emN_uF)T#hdZyEOU0hu9OpKKq15ny`fT-LHf=B1_WMq+7c#eAT0#Zlfff5m#@ z)0nznJf4p;c(ewkH0y>HEj5d>DU5P&?ZYJ}+(%Tm`dx`{B6MHfGAN|i7kvI3uTAha zx;QBhG{5DsI2lxHXaA(g1X%ne`SWb~#eI0vmdlQZTD%r$FSYxTRI~tYCCXU{SOfim z4;!zgXR4-W%6Y@F6}(4o?2Z_m?;2K!8deb+R^#NpL~{?0maJz9vz?6iIzmz@y@Qu; zqY})&fs<-G_&SJG410q}QkuLqP;0xUuGcH-zlrLtXL}tgyB)MN2Q$u)It>giq{kEt+}lj-NwQ*gjZKS-*OAY%#xAf3__mP0*-AHWiqy1mY0_vqiV}8 zVQ^G%)K=LDGbx7(u1N8p9sN)3#Rz%+4Zki~W`6H%hfi^uR zaA7b#W^`fj#~ZwvU|-JyKs#U?jH1!QbRH|6QFvvzZeX>7HbgI4Gfbxgo1j6fgPWj% zK2#!Fb4d3_!LTZehM<;h$+o2+H#6q6zhG*)HKvyCrAbk^6E}^uU6<~xOI{e_tV>aN z6E{t`U6=Vrlbv;q>8wTKvM%&`qBP;T8~oE^aITDv?f^lqK@?f>P>KH5-qX@j=GK4} zt+Za2enj^*j`w~AXvZBi@2_503`H`42hevA2=5iZi&H$Z+R-w9GR^ zcbk-Lza9^N%m6_>&?RMwJ9C1p7eDtm%2;2F;wunCpAlE$Yt zxf!Tf*mB!F8h!?XMgFVL`Sxs%X1y&u6=M>uSu0Rm=%csS;5dSYeW?*sE zZ^dbxP<zt7@pjliM|3GSPKADl=E`w5phqo90$LsOebm zBlFGQrD&X@`$b>M*fvTrClbS82H|b=vO|ZQ$-ppBi<&o~1I8M2-QMP5u~wu+ZBR)p z{&tuwnqP((sdk;UE7Yp;_QiD9?PPJx&&jsX=L?;%+K4~7kVhs?jo?#T6_|%NBxuH* zo*2R4C#dT2waF|@_kUBQD%ViL-0m)nUOfyjlhS z@ec`aarAS60|suCB8@q}dB+D;B6_KR@Gs4q$7YfU@ci7bx<2Edr^E_@{AkmsO8A-V zW?lfa-e1&i-O54o$7juP9Xb8a1``P>kMf-jr+}2%bc~thd^hAZB=5tR#~P;0H51d{ zyAj@RL1V2?b1-p5qgk7tJ^NB3d3q763hJz+0iVt0*Z{In6@~I+S?)tq9BR~+M)4O( zjxW8gKk)B?xRrwxG)qA>u@;3uppb|8GjZt^mMxZ&4#$X_QBuEgW}ndPG)w;Dv_RFL zJ*zv}v(vtMTba~p30f;-tnlR`lsS@~~#(z4U)KcFph|wfbm;Ep} zfB=k=5P>`iVT{8a@|gGfk0RNLyT_t%q2`l%45%TN^0aut{+LP2jG$z6AEOT%+s{8g zv9&@%;F+PQ9$_t3HwKfUNyR=vZ=A?-;`7VG{#EJf!I;81k=Z7W;hFlo=PF6}bif6! z0x=14h{RyH`~P@#{+vy78M!4C7DzFgomP$AZw?S<)d$FF)o?1O3*jM^bO3 z$;Z*0`dYkQIc81aes`S$VBMK z$pFnj$e3darR%kkxM+^;@<;WCQl(=)(QkxEa9ng|Cnyq{Of-yI0x9fMV@8;DF5O#$2F$=vX5OG;-s$e7@y9P;K)JHe%W{8QK z_e7E(`lLSre9pbk-`PXWWUF{KT}6tAu>{h8Ld#{n_vg7pXpd$@I6rvpTg!rxHcp8P z^`4DFBVNKPAca3JG$(ytzJe^P3s0LhpRfT0AJVJD+mu67w!N(;{aVjaLThz!7?evk7EC?w3ZAe#fo zN732q_&luC>1Ys85yv;GWZ6~Mh!7*~rIxCMMF9t1ML9kMpV9_Ui(zH?Yeh6dG~!>F zkj;$am68%YZJhYKA!Ah~x=`K13&ho)?`STmY>z*vj zJctpIEm!5QhjP?zJ4YV?o7>YgF>*jtcmOMZxTOUQ!Sh#@uIqOe3!JOtQSXQ!(n7jY zc6PEG;i4CueC?tef5c?`WK(Hl6#s5gtnA!?P*G$;qvQXu{_8yiDVHw1mdd!V%?pRgU2$6})uaifwk<*q0P;Ubx(7ZHixbDoQLNg?WTcF3lwwt>61d$~Rj| zepS6#V2?CM2+}S!CD6lX;tMk#nSJirZ9gu&S@dg-F&KcBy49fZ&)gPU7!wkDHlCV> zfu@6|PJz!zUk&E{xKBz-m`C~m%xe_9K*C4MKlq!@2*>+cruL?sdiy#+^qiS6ul=^o?@Dq$d7o&lH-z%H zrzw0-Q<9aYK+lBLpXCeOFFJc}r&X^a)stv-_IB%igY>FHG-zd6&*<1t0Fh*XcjFP- zf6cQWW?o>$2y{aToxt^LYwjRHFY<#YDRH=0JACB0t#e7K zt34j+;bi!A9P~Fm|CuTOD{#u?bqD)+pSk#gS3{4U__5QkP)t4@Ns4eoW=0N5e4%a_ z6}u@9UhoMW(mCue)WLy`=pj9()BY5dWgvG;P`m_D_k=Pz26PT-!S01ThEXkJcgA&b zpm$qqaqY}eRqfh}Gj)62K`-P?GLvR2ro)hR2{b~+A%xh0ECj6lPavMWQWD<2EwB4* zth-4Q5~q@a@I4NB|FQ>;L$D9WEw3?Y-&78V2m=)eE7&c9KAVF5QrfqPBr=hjHH?E+ zkSqmO;mhJ6nzs45=Swqo^y3|SzryKVDSU`=*t}sP~1ox+j4OcZblx*Sa`ApZxDfh|l8d@VxfCqA$T$z)oPv=}ft*Ao1 zM`QS-^VL&1`*Oo@=a(+|_YJB+4a=x=;lqU(u)B z+VlQ<*x~&DIqb0U@c!QpJMG$vE=#;v?R#4Lb&?vA2#^Wn2R~1IhOjO56F#V`3wZle zYi}}2TFcN2WEys&e~F{Swa(DLHA4R4f4@KX(n9oVCU8MR_W9xT&f?~9?1?qwJPtMo zCvkTA{X6Uk`?UVVS&K_$hny@|uAPX&sQQXR0HnL(X4u%NO_`a`m@Jlt`#hu|p&)_D zbgrowa^^dBSmP;}0c(70!0{Y8|Fjb8v+)G!$0zY8w)*F=rDDSzXWsbjK$~g^b1awa zrE~dZnWm!VJE;WElKIKW&m?F%)dk}~jfFImnTyY9M`373QlU6t_>lg-;jIB+V3$S{A*bq;epaC{eu!V`Ox?~ zzqET&mkd3P9hm5Ym3VEhD}BDH?{s)p0MCodE}?KeR;e#$=&H4rCj1KXh>Q$^%NhlE zY#}LGV>17-MVMUWh)E*B`+7Z?K;dsobSZXq&71gW_g;wyxj8JEa(Sn$=g#KkuBEb{ zdleQfDsJ6f_`Y#55AuF5-`zV~ZTGI#UY#0XI{dP#)EtuLO>#d!*CUUevu7)?19Z$~ z*sBVqC@NwLC^BUoNu3=fhVDjL?RyKeuxP_|4Lo>ycgWAfBUZ$J4i<`gMSK)-c6E%n zWZ}7Pz+EGjjfD%g-jV_`e&s&J5i`p`e05_?cN~(j01pG;vn?W>^Q0 za$UB_Z$5P}G4P&be!$mf!57gG0tlt}{{GEXw`zhN870-QJE4WdO^QtoAv+m15>cd# z?L4XA)yJpVdPm{YZASn2P89i?gv=nS9oOSq>}uD=6wUgSC+ndW>W4)|$mAtU$9CA| z9{j0>!8FLP%YI+A^;zR3ScSh%iK&hDFq=_yH*S-QTT=WwaeSxdDNJWDXAhpNN#wfB zq&ESFG9nyX@`tmHwtW2J;_~q|(rg4Wl}MH>wpLJpo##(wYKs|)TPt1Cr>S3G%wdl$ zE0rEg@9>w5MY*LQj0ZPKA=ATO?dg>mK@y#R3v265!E=APe$a@hu!U9=nYuIM;|&qi zMh&(^vLdx@e%we|3L(=MQsV2sB3B=tvCeBepJ`Nx!hIThLLY{5xywme*>1g!GyMV84E+I@~?Sv_$M#v-8 zCf4Ru=W`QqFOr75?vB$Qw(<<06yD!kbe2-TE#LgCBdrdA?{t7>4%Y^f+O{>qJs59y zFuu1c=vV|30(l7hRG}g3Qad(0gx(oR+R0atmg1{k`2@}zNdj@Xw3kBrP{k-`VPWF72IQ^aw}`|h?VH|tcpz8 z$4|-LjU+Fw(H25Zob(g;ifOiu#WkJFgx`a9q_~DRH0E~rU8>LYvdxgp-)}KXMDFvc zs-8yRklReBvVmmr$1ku5KU&BRhP_VrU_R2Vv!e1I8Z@g*s;UDW)>1+ZRJ_dVR>InK zCUT}R`$_$T4>Shvl9uPqQ-4Y@hv#R9HO6}|cV{3hf_But~h_L;;EZCJhv?H81hlO&3>63BdA2BWg z`7Dd;7817){MpLWCq7(<&MEn0I&tG>%!1wf7_XBRUIy_RkzsoDy_DYBWhx2~N;VzD7XiAG>A zzv!Roc~+|6aGU=n8gSnd?;si}PziazQcYF`&+YwbaG;iurvTiHNQl;IYgbRwJ2Db8 ze#8Kc%)Ud<@OOct@z#%D1BoOTW6CUB@^()()=DW@=<4N*$Vb)@UURWNaaT>d4kuwl z)vcVslb3Ly{O^%LsIYdS?<#_~#=FR@yIJxR_AQ=Kt~g)MYfsFtS#mL()j@qIfEkAu zU4(A=)oDRr;iY0Z5zz=6tSH$?Y7_bhS8kOrffJ4i;f+&lOY1W694ey1XE(O{rC^&R z3zH889~okqweOeVnCAk(m%ep4S;+o=IFiO+it=axxNkQhy`yr?!iQ4X1H4KVDEJ8x zGT0>vz2{(2%_YSbb6AmO)&HC&4&h|9D6Z{lb8!llkkQie&zdTU_9Tfc1#Ut(7?`5E zxadz9D#=je2(QEF$E=1A_EU+sTe3#>RY?qX4iu3{`h-@#l1j93NQ=m&(xbOeAn^~U zJ+46my;4t>yM$(*LU;Cc@~p@_&Xy>PczgH~J#Cy6VWWq6Q?aRP_QUP=^sNCu**}-j z^g{*a)Qmy3!%V0D7UI;dmS-)7foG67P%++nl0zM2&0fkb zd`d!g;Xnpq{vIWcU5-T? zfy>X#zpck2I3F`rVl@33mHyNg)e4m^w{F&Gg)nB_g^@9wE4vLkJ0Y5G3^1a;4w%~0 zlG^p)^lxCuWB<}NF?3Wpb zoSU16?|&=~a@PN$ZmPi|mO52XY#K-|xoM0Cv}fEh-Ia{w#eW&RqJ z6Brz*I>)WSdYD!e`q}-{>dlaZpXxA=U%c7^7Zx~fXT?mi? zqN=YT0IAz|fFR^D4ioG0<^~t0)f7;N0 zB9;?GbcXTgPDrX?s$sn7V5kaIdsYOTQ@4{%R1bej$hlVN=(;*cFH)6zhnialDB*Qw z7YGs2^|g&xPY?=B5Xc!$oE*UeopqTE&I5`U=vmH&5OlK>O(KgVg9sIPejm8fhB5bQ zM8-ObY6~ddC-dWHSC~OS7;4=Y3b7zy?FL+8T?aP5l&S7p{y5?;?I!tzaeAu4I~=ud z=~u$~9>;mb1IQ5$J3^Aa@0kM1iH#lM2eQn0J-rc9yNokeRhVXl(`~S)gt=*Gk;s_= zMkY!+3P^u1sBAwB%bYAC{3mY_AfPL2_lPiXk`w{mf6I+vlKcnN^`m6)E!2|;ByBzq zC&EisSErVQ2zeJIoG9dRjuI>Hl<-vLn99J~(b1K3&ohK(&)g+6R4^a}009-ayZ-*I z42}NlF0f}jaXbhpEppQaMM+b%Q=t1twdaO(d z+9-qdkbuYs_Pke$I-PGHsGv@Tv3sEJJs1u8>RodnPJtwQCPrqI=2ytqtee-79T3e` zmg=ik0mwt@aMj+v)A4jI7z7XB+PnM=Vy!4RifJK*Ch5Cj?E?L@hI6S; zdAhXcH@vjn8OyKs??>fHcH!M7!*a;SJ8`d;>@QvZE*m)(3H2b~Ub#aeK!k*VkXuPv z!;fxIH{F;<3^A^~{9fA&2#Et7@A_u4&mG+7JAdu{dzhvhlB?!IiB&})87&~hvfRT z(1DP#K}1hG_be)Mgyh=+61<+`Drl@M=sZ;*;W$>2!I7nvmpR3#z{eav3Q!5|W{kvV z^cNPv&pexzHM;HxMHcvdB&6vx;T*7PZ`TuR3osup}4r zq7WPn)gO5jfR`EY%eZ2`{D*-DACh2u!QgdNamUlG)jij(mY*kyV68>fXBwy2`!;7a z@}c)r{AE6od4oa@Kw2g$I(3&smwfY?hw0({Hj{bxPllA%yNB>V_XLTN$rO3Yp~7iM zy+l#?4YM(wO zwxB~UUd;4SFL4G6zl%Q)iPF9KE@>|RA@X)_YS_{1=v_dP7UG#0UAX)Jv+uZ96P@sH z6WP_@la%Un*gbCb+p67O$Aq`!*@u{wW~t4Mu@3HJRwfVn*B&(EslnEXSAy0;vxFQ4 zHLnG+>M^6O3P5Sl^y62*8fs#4Gtv-~1FR3P8qScC@o;`pCu;krx>Z}TttRnHYPE%5 zvRvIV@;1*X)`SI3M-VGsqklH+{5(;Av2vu}O@Nzk^Id2x4+#+6^qX70`H;h)#C~&a z(a9Sp#U)JV9`Dy>-G{QV(O}Zs{v?@V@rTFf;oCw;<^%AN<8`x=50n9P13a++k|H z)%-X7d|VlgzAh(r>w$0!ZPZIv2-o!$?Z6ci!{ZjZ_=DW8%H*kBg6P z^^|qh6DK2f9{Zv?j_R+)WNStERQ&p7zrJv0DRHGq9ppF9%O}SihK$1HePc?Vt7-0Z z=t>zOc7X*Jd(+CV5xL~PwupC*Y|LZ%%IYGqrtjp7MexuEzdVe zB!52$NpV*ZjiNDqDU3wF^#jXDGg!YS!n)=Eb+!kFqwPkT1Ae7?kSda!WeVCvF3@Xu z$EiR+sdU&R=b9xx>~02gx=+%}@As#rZ4@1sLidinUvOn_fJ8ifrHQ$-rz@)ZHax=5 zcjc;-_{CqZ6GN^SHM5Gbtqr?Erm=%8V?gn@^PZrEt=f3GNXM7VY^#@mczkQjaT-*# z(bP=fH0~<)m_gTUTv?CXYi>q4Th|h*S}KND;lbs7JmdN7L?!f;IYx@MG?4Y4ZDX-E z(=IOdb97I)SRnPz&n9C7_wsgKW(AvruWLEAtF$k=wy{aQ^2^+<9=MJ+z3)9No*Qr4((_wlU?8R(DmLXyJYwZ=YiR1W@{Fi3#zlN! zUF+zsFONzxBD9vNR;G7ls*lMAKxQT(MzyaA4gRM)i9hp3mh@S0O$q#=IY)BGzSQ_; zcq13*G|*T!xcCyT!)`HC+j@^~+^ZS`BS_}g)>fFsy`#GDnS(2dql+339RB$mdVx*V z-m?i2BfRKq1^HMCqkr6p5=S~p*5->hYO&-sgtmVhjqX#P;~=LbGunQF4L6ler86S% z_3nO9;>ypN2-vAdaldDkuznV*BA zeCZou30ib}2E^SnTh(6;jbOtXyr?sH6MoKQxt>s;)z_Fi2Fy63y!hQNyL9cK>qiGCV zpL*qo5`nDm>^HSyL6K&dh0z-r(Ka}|MQ6oa;%lmum>@@ZBPSrH*l2BA$W5X5{O_>4+(WihCEU%pbl+wS99e`?=ffQ}58aA&-BHztx=hpk$QJ zwPnv^FtVqaZX`(6v)eDi7a)?3L+X$dP#k>GAhT}J?{KpH>sFX-X8VE1*-Hm)E~Z*j z?e@ISHj9M2=X{Tt%r*0Rowh)BRN^RCJomFxow?R~20rwubPrujm^m*XCVu;*T@XdtL41H2LiM=rZb40=Pp zs_zbQ`_v^rizj+K4{-ok)ukTx)loO$nDf++#c0QO#*}6=7Aj;vrugHrj@j9Crs@~S z*CwJK2KeaZk{<~4nX@UIYiqqts+*)0yshQhoeNM+*{S%w)Yk)Kh19PoN|Og}pOF<# z*ZEfedOp^vA|5b~+~8QN&D0^%W9n{)=lU1Uemu>d_yqqPffW3Ka5K@Q zm+TtTr7_>2l!Eo=jm%B2Z$s9-^CC7_=JSG|4Zgjs+kL2^uRD2P_@duIb&0k`kHzqO z%T$$Td>GW-L8c6>VgKI3-SLox4i8_@Nyus>r5IQlZ4kFwS{e-|aAYwPKbp8C!sSeK zJ;==Y4(Bmfo#B9s^2L0twzWI0!}gv>DElW>lWz!k0&gMW?>KC9jscjvcc&dW{n&I( zE>k~J;Ygn2NJ#k!zvtEya)~~g9grxRY!V{G9tisS@(4Eoj~hIxUSqinbp$-fYBvgs zd2xb-_*in`lY$2m#m)4vj0PBebHQXQ=(>01Ru3AOUEIW@E z*a#2VOlXiV%gY_^w~tERk!%~wB`&Oun2LNjtj|@e_hn#D+&BMt)`YE*)^Xug}m6(p#66_R|f`NS2}o|}f8R&ei3=?6VDGYZ+EpFcka{XcZQQ;aT5z-HUKZQHhO+qQPww%)dF+t_W} zwr$()o-gO*PbQg}%c{DqRI2jSvsN@?8)zLM6KkqBM)ZY1BbW0pJ=d8eORo=1@A#+i zFI9d;5)&4UJJrrlk%h@}sZ$og3>+obcm(m>oYpMZt2Zj0&{D;7Ygp05528Us*qh<6zb>7b39jzp*0438G`DL7s`i ziY~;v(mgNnV#C`U>_3rxi~DfQ=zZ*fR+f#U^XW&&GZpaHNj1!l4EmF@7S%&n{TWx8TDm5j4O%|>;xo3UNE&SOOH%(+uCqH zKGn*hKq?DV8SW#>yl@ZCLOo_h(gd=myLOuH);wv2M)b-iUF;wh57rTR`oji5tN0SB zltXr?&Ixo z{hn9RLiE3zO)YU+OUw->9COZy8wW#nqq zvjvt;H1+ey`dbY5;K(6YBATg-u|2`jUj=k~JD2ZwBa#TMX3RTGqrem3n)A#_rsgo( z3siiYEnCLJqR;lH*y|c=?jA>b6F z(~E&{?N=WYap71mg{TS0+iM6+8~C<-qLnduQfDYbl}%iv5t&fo5d$$@tWmm`R5!QT(#a#9|c1l9fSr2%)p~W{W-{P}hO_J2)895Db*iBG=p_ff7Z!70c zz&_5eH;V1idR$NdaQSl%G5N~8DAjHEn#7}EGa$cz3p_TiDG?lhN*)ncUrKNrasR|~ z$tSbezv_5~LuRk10MnjLv<@DL#{rd*H_Z14yt)X}c)d@lW~;%0fG?5|m#VX{l~|wR zYCnWQ3{(6-j(!24q%& z@Z32=9iqClGjF@N^y%Jl$)NbT(`4q>sD>l8skWWo4naY`he`94M2`ts}ew0n{ z%ihamkW~Y0&6~4rs#<%L7$Cjh_DcMPDl)Y`+bTB}{h=IdecXhMdDRHp3mlGweO!a4 z)~`bddmu?~&0@5?B>iTf?9Pm8B78Oeu}RhpjKT=iX$Wni-8Zpn)wZ}?AhVa}qGH^p zF-_2+VF2m!mpF!>eG?r=DNv@nJMZ!*)3xRv;s*fWWO*w!I&{eHaKg`TPSt3+>xmJP zWdJ_6z9~;(wMGkr$l?(nR(A51b%GoRE5U0(Q=EUV3@V@ms2c(;T{H`?dn?%>36@+= z4do89D3`QAQm^Txcin78eHJ4rT?uBm(Tj1L9*y57IAqX%1cw%t!ADI?_V39jWW#!j ze)It)SN^Koea0oa$hCO#v(DDR=3+Vx6)^w)_=Bj^Twte$I^y{Gc*xF*ZPTQckIZb! zn3!2fFDR8a7uypy%Mo}rIR(%OG@}BOWS|$dx>H;gP`ZZYgjAa%xXVLcZ1S<8;OFci zb48=;=VgpyK5{*}qJRpaY~ja*g$(>SA<7%K@y^czP2(m$_(c5pD+f;A=@qFL`qqlmJV(=pw7|7K`i|=)&Bq) z)bZyKhKo9>F`UjDd$; zAKRk3>kiHv~_+S%2X$8)ZZw=nf{ z&YAw9e85ADm2S1Sey(kWTJWY{p_oU8oK(yak~pJXntmPow|->hOr+pX4dN(>RBMWV zdWJVA?ogIN8d5oKP!y$f>qFZe%rImQKfUC$J)(b$1&(i)y-rx~xXi-LWP1UM-CA`2 z=5`@@&8l&XZ!9gjQ;I z(kdjn2ykb>uqwqE_@KUcFk_-$skt_-W}{Gmf!C~o2_!jocjsX|4hS^oAfOrJ$-}IG z4VH02nm(!lmz1rt)ikU5@LL0HNjt@F#UMXiZ-z(&pIXOV_Q9xGZUS^S{_7KX@}jgc zuGI1HGvEtRKAhS|;&i1C4(Auyy9sH0R6*G`(#V4{pehnl7R}zw8wsV@{YisHIM*Q< zW+g)%Ds<`F-4YLHnj+Ew_J-a@1lN#mF!ha)xF%9|qt&n<$_K~9eXj-N=AqYYOvmSW$RH)SmGud^F-09%?t{6$if9EqbLO%Ms{(g{Hl3?(iw}N+tT8uHdszXjRARWxA$RsX=u-4y6@(px_hvm5rq!kGcmp2>+bAiXeC<)P zyoiW`o}*E?m`+EnSIO777|Nl3aRoK8u3XLY}o6$Kz#=s zu6yKc{1s!Fdb%*(Pnqo7jOaQRMzG}9BPx(Ritzmu0~phcY9bjgB#JIT#3zx z9MV*IYbud4dOV!@HF?XU$G*uGOzcv6T9>RrJW2B|?Ak*nHp4aLbdzGWv=!65^ zW-YJ3T+&W@s&vvFZc5#Jm~!|$;X_-?C7*50~9X|`~VLYT%FepmbNX6e1(!h?4Ti*kD6SS zc0IYj=dGydSW%zxo~4n6IqXdefe|~8K{kI`G++wgNiQ;{n^OQZbgPl|j5)5NwJkRF z1C73LYl%*x<%FW%Nxk(Iv`@%q>h5ur)I&;i-qe=&{d8TTK(5$EwQR}mHWq@D*MDDh zT!KQelO2l2J4ap$@t9ySn@j{1>OpNs>0(3sB;tuZO%1NEsc^dItmmQ}uxIw7R^VeW zX&eRET45NNW!X&ilw&YR5VgpD*{Ox1;@Ho1uIkdT%_7w&lBwGxBR)p6>hVF-MmFKf zS9DJjm%jo!X%}50(;#g|x%e*d7hq&ZJ81C`nioD<8M3Bic!`V@#+CXT7-V(mB!6t< z7q8k}$>J>J-b(#XIKx*p35cVqvenRTJW3x>`vSW7;0reXybBejx6sPb&llKk9ePe3 zz-$rYpQ}*eH?cGu2Y)nB_ZSG$bZM{=zZS`bG2P|nw$Bjp#b5C4Ia{>06L- zWzMtU(Tv-2ei~hTY9l?-|1xX(M!`N6_)P_eZHA--5|NmnsXwclZeDz2YEs}Tw#^IZ zUjFal>GaB$O$12WL`aqk%bFT`u828Tmku7JAs`9OI@XUk*;NQ8Wd=7V*ZM?Na1AZ& z$a5*Z=z?E@`Gs}>IW10@Xcr!PhLeu7;|Q!b!ZsJw{NrRGwWz*2olO#{VzI8z;Qa!? z%P7WFB9KHlb@n=3&|xeVh9RZ*I_C$B>r|Vlv7U}vDn#5_x6H;|A}f$irAyPZPP=Bb zwfkhCNVJOJJ+=?s^~`agmkn-{sa>z`8xyO5Z{uzZtFP@5tYMU~I5s6y2!g>kCw}>)Lx}!IX2aOlXn94_Ic!7DIBhu)8FdzhO z*>X{!Y3gpO+FKvX*hn_Q!I`@2!!`azEbix3POG|oTBn6Ae_;dTC_mjkxFv&CR%*w* z?&@P({8uEqc*-Wh;qMvHltVc%k#>(P^jQtD29&_0B|7Fz@9RFv(;J>VzgN5UN zB57tqCMIS!*8ds)?_o6)GYbdH|Eq`43Z|NMj!qwq=1w^*Re#XGy}hl?D(G)06e#0J zxp43gEE3h7@@81Ot4#$rk|%9uDkH=B2Tu@IUjGE6@Ogcu^W zg!bct0RjZw-QC&ayJ2va)}@mZ!1mw+v_M$<=?%>}>cIBgCxO)B|MO(6tj(PRZLA>v zC%x2Glu73q!-DldUK5(?ho@Jd{|Aq5Xx^vd=ARnKEI5sHbyrsZkOxld-wO}X*FSRa z-qza%fC%LL+J|N42;1NZ#N{P|R|k>_$HUAg2UJagKl;}L3BsfI!U?(2&rty4aUhK# zn7x_bid+x{)rCQTye{r)e{`pEh+-Kr*fGMlZ}9_q2YK-tqk}?Fmv->4fSiSX_3~JU zuxx%@ZgTs2L#;1?T;1<}5E_CxH8p?i1_zdr$`64Yoxo@$e@!1rg?}Z?z(W6cti8Xt z0p2`;3@L!t2Dh-^cmi6=NZt_0M(yua5PEiE6(#(SRd5Uq!pYvwLAE!+j=;hDvi16V zc7D~rID}94fHVcC{sOVop$+}{&O1{usyohmv;3JsMDYLfiSo?}bk%DB5WwPNngYHs zJbjOQCm;c*t~{6QRxb*4%eWn%6Sn<4}N- ze<2(N60Qk`K!B*fgFOBS9`_;%@Bo$nARIsdJ^zXWD|B!GNOH@36f{El&g`K^QFa6N z0R3gyw7+0^k##>9K9#@^3~#ET)4h8tW}W}7n7jZ)X3F|r{{33yy`Vq>zA=21d46D= z{`kxP_LcQ1EQNem+02yn@cw}16?*=_@QXcufc&hsP3h(2mNqf><}``1 z-B2UT`PYzYCg06rRc^%xXlKx@FlntRpE4>XVA!KL>}D9RD09T#cY01Fr2>P=@!nse zB6j4N8=|fDYCd!D(N}Z-4RM0z zA$`(!&e<}+?QY7(3i`|zzCJP=FQ_$NL_Cj-=g!N72E+4PFM>`|#`@M;L-US;36GZOjV~5ljX@)1BZkfEUP2^N5Hw5;#_85Yrr*I~O zEyVcla(Ap)a7-!!f=@J3q&#q#r$n)$J9|=v2tF;YnK9@wg~^{e;oelLb(+Kk=paEk zJ}(a)9sjlqDNnf81-J@)DnaWTcz8Ps`0(0VCl%*8SBATUkHkG_S7_ZyP0n_69RT^& zuqo6;CO$Z|8g$=P+-b5Y-?WCIzomLMuRY>cPwjQb1wsP@${QlxH%S7EBGxl^mC~kb zUxV{hQi+E&`_L**e0sQG2(izDTKXIdI?=#Hx34_6Z;6WksLtbAcju;*3t%kZ*|#2C z|E@&^5OPmGyva0iX-yj>Z0ZO4zUe1b`E^7@IP`VKypt$Bg7*OJSV0cCK4wV|gl2Na zHZ#!l^A36gss)8(0`ha(5R~YUY0Tx;6QWVnOp+kd>BNZtl-mFg3$VP*v{jEuDzJ#w zRlsh@mg7(37m&}!k&U}PrrCc0hbdktJe60#OCqvguq<|}3sUgRaWv3d)kpV3y}L-D zXH&@CC{-FvkROT7miW%bDV?$ydmB&~wc;+RJFayBs1O>c2gL188Lh1+6lwpwr?+TH zU}SciUbz79Tukf)XYG<4bZZbsPd!aT{27~vGlTfqDA^ut;Vw(Bv=4H}jRX+Qzhg@!kA+&JO zjwqP{94$xnMdZo}qYDu2P^6BY^#aY`U|M~PIB+GVjGaAD?l?caT$i(hV&`DbH=}27 z5jS~7A?VDHtnFaSqnk|WxosC%A&9^Hr&=*_a6~)(n^3pJcz)m*zC$=iFB-3&WZ%;| z(qR6eKQml@htReOoLFM)O+7$1RPVMSEu_-`d=0hJ(T!d{UU0<(DuH)lCeiPR4UCP} zyERacmdr;w$B}9r7FjEUWeAADfB0RoXpnoX*HsyOY>Hf7{Q_57=5LH5W{#$ES0Fjm z40D<(D9s;3=p;SQ=*|aRBVRaN;csvMfEEYCbKUMJn2yhQW?8nvw`vlH{lhy-_Uu&w z;O`b8+@1*%EX|^75_~l|IeTih(o&-fGPWvJ0hDIX`?Gre_h=eBY~ zbl3p|0Y+E!-{+dR)sFx1q=VXE0yVqvS@eZB=Rc2GI(eZ6b(--7wMh01>D=X(Q`M*)Iq05*077G6J2e5A9BVlv^E>Z(gfNtj| zu^B}R0bMZdvF$&k?9#Z`uo#Z<3kx<*>iB_y9Cj6s9-(9=TI_xeWv<1;F8y>8;ImpaDw?4GM2e1AOvWpfnC$%j9EHgZN^CTN@T+}*! z8oMUaFf6S8q5kW}vGH&O0D(V5$UWyX%<1VFiv{kp$T|V$?Ba!$VUb)+>R!z4O^6k2g{`J zYVNdG%kSc?3yruj+o7Fj?>V?}O`%vi^zN2>|Jxv;->hy8U07faz$+SrsXw9Jz7`zz zLY}ZTF{}K;tfMFy`zK*_pw3h}MZoVNx&(N!Fn}xqG7y>{X%&=2Z?g8lY0IN5@xhBN z)ciWM+FoBgLDB4*%B^UUC6UKkcW6n;;!gLddzqYFbhK?;23ElKOEwx<>f$4{cvTn_7 zi=ul%g^f7+t|fm+3|&X+ds3t2{dd4IiDUm1zVEF;L-yY=;6XO}Fh~=TdgQ!m$mF)6 z3{PaQgV|@1V=WDrdWa+k^K0+F5EbM~O4# zfhSgHXpPX*MA}MKr1tBRUU%;e)U+--=7!}~HrBlicTi|UEuv%M^^iB$OPXK*=dkQ@ ze3ak$nK9W1fFl)^gQ%C_RIBx`9sb%+fa-6;F!ka<+bkO0Q86%-+CUNVCUZTvs=~s8WNeg%;wyhOB+mm+%ovSxlDQ z;#~Pme@D~0WjZe54DPGQiB-CA~@&dY3l zYfvO`mv$1n0B4%O;JO}G8C^VWzoIyh_|O-sO)@Drge=4K+~;J1X-u3`+d~6Rdpdaj zXb#y2pqOoxMHR`>oB@OR3RgybxA9=T#m92uLZ*REldto;P*lr~pq;YEB$46X%DVJW z?okwipBkoy9CO-Fc>}1Pwu5A2-u|rZ>kSXQ;YYY@h_AOhc=hUi7M3)MU5)4>MpeM* zsJ^X`ee^gr>gY6vRM{!7?)y-!*Ic9LR_g@`08Ckc`*7eUNoyegl9g%KvVw|7(Og<3;WD3<|{*p2n(pbf@SZUUv6)u7Fo zvTDl$ZMr~xg2(H$>9w0_g1Y|>w_5{CO4|_Q!tN@S1uK-PwFB;fE%X%WweXd4rscwgoYArG?d#v;IWJsYtW2k#vG)aDrs;$X;NPn9RTA;5c z;!40joLv!c!?LAW$Rf1(GDE4?IG`T^F#O{^!e2KMQF43Z!vjmOn$g&4( z1s)^Oq@rMvo6^O=2=~bVW<%8g#6nn7;8+eYzBqPm(C8;HyXs#+hBQn>C)kA!iS$}z z)zGy(+NiQN?KV4+H%0jEXgoL^T+nO2TLIG)Q_Ac{yx*{ta)@Be3|grU&9dheZd`5p)uw46~F3GU9p7JteK1 z)AhV3t??N27L??VXrfeO~;q|20;@H{SiYrVW0Hc&UC+g%(-b~j#|@K5lGg~2Sf}> z7vJo~^W+w9A&k2xxl8=H9fV3IIJfGNno@Xx=o&ap)Xtrqtb1VqQY1T5q`l*d_Xi9e zfx$gIWar=+|Mp1=^+{5r*KV@YcZw|HskXAH{|oN1#xFjTEw>7Y{nh)le>2O>`y?SN zwL`_+3u4P}n?8e1Ldb5(7D%V;#04d`?oT4;sJO3C6GSnyaO)5hi(6a$fwM5yP1B)5 zm5-W-yF$^iLwTBC}=4AL21X?Ht<}el)NYf#=Pkkl=8n8XW0vCqVgk>G{K)f=6n>XAXb<%v< z!Ia)DUzQ6ih>ZrKajsv&5?l|-Col3GKK9jOVJ&|~(dGtVvhJ{%wZ;1OdgY@>2W=#o z?~7&{7ek)A*(#kCeoz$BjHi7lGq-(GPDn#j^H;Xz?1M4|^wH`*KNA&SNtiCHfOqM* z$`lQ6aG>U}{HcqVjpDlzRecl^wuGd2!rkoBT$e#i*HoU(4LMN>>!mm(#L9-+8yv?j z)f|nzmP-!+NyWdyuq(Z!9WpT-S8nwzk^br^zr!}mdDs|2|L;*ws+%JmMnq zmP;%aiySx6RGl-m@gA$Tje;6jk}0(K zQ#%r{86k9aFL;P$oYhEQC}f+OO0hnjYf2!hV1v9{>^tZQ@eS3!9Lgi{ez-5oFE#vZYKlKzrGIDqsqxy#q!1; zn>{w~YU)U)ZcY6AeK4My4m-^t7j{1>da(^q)5#pZYUFgR$;KfNgB=-V@f0CtHW4;R z4R++fW3v1!{##H?QuOuo`87DiFzQ%hEyLrq`+3iOnAgu%Y`JJhQ?6U>B|cDckKzcT zM(IP1vtijFChIBnnM=eQ74jD;`e74ZS(x9B1SU(5!pwxDzo^z6C5%M{I>NAoWPBRX z>w7sIH(7RkB}t$y_c`<8V=U@}*L>)aw8@2!Pys9SbE+H`qX!o|2L(|ztkFYdG9!%o8)zU zs6N1%Mtn7O8O3Ug*eGGhzA)dMt;mgD%U-6;a>R7&+5`(YSFcK*!_imM$`P z*|Dzp0%dKyd>&DlpRz!{nN0ya%rWTvIWn!svhZZ?!a;TOn)y30wuPWU9YkI%zOi57 zSF5~5O=&mG$~$kXF5F{&Tua_{JtTSmw}w??L=2k0YFT_>lK<%er*BYX%!5>=hY0RC zi>8F#*iW+8k+Q~)=B`ZZ(s)>ac%ZsJYapi|EXLtq*3=v8^Kvm$Oi zycw#H!*xV}Wm8Bn&7Ki1>SL&6LVI#}fA!XV&@p}EQ1Xp?2$j~ZDyvFh zA{8i~s1?<5YW?qi$4kgF5F8qve^oP?_+X+drWddHmK^pgU`rz%@T}e*As5~4mf&jT zD?h0UjY1zk3ss$ys-Oy>v{CopKZC5Y)5NX~w!Ey!2u+M5aBi&dobwv;{2Kav{*mrY zAT4tli!_jmojZ!}J~8cMeVV#V(x1D(Llmte(5el22c^=gC@uN6)5aP9Hm{FTNq4i% zawV*N+`5Ty;_c4gxeU)uUDE99P?Pe@X$Y}c>SP2ZOLn2X*ZBva8Wf>Z6Z+ZWE!0q# ze9UA`}T{bvaoVI%ZvJa-u4vtUlOU}Z>bQ2 zHAL1XyiYthW#@_>N%5HYd7Pnja!YZhjA=ehe}UJV9Vh3lGJ_AY__KHhx8X7W14N1C(asBRuSs8bL>J`bY6R40vGf1ffve?EOX<5e=vl7IFMhmCn%iqpEQ;e zj5-cCsbVd>v|1WzMY{EOaH($j<5O=GezM&Z6k-UXjXjqi9ye;?t8@*dB$v+z#MEV0 zoT5p4Jl1Q&?p}j*Kd6g`;rT^j~y{H~KewjRIbLD`@iIu$&-yNXF= z9o#^`q_+&9!6Thv~IxH zDuz)$trkvGBH#u2=kDAh1p3GizkVNGh%42el0585NxsUzVwbSMySy~J{Fk*>UYKJu zbEm$4(l?n)bXobUlp~o_SGY2gEa1t^c8crB%k~>^tZ^npGVjOl>K6agedWP%xeR3t zk6d$aeYH$YFb3go=9mYHJX-{ro4I@wo(vMc8~i1QY}0r)d)!5q&#c)#?Ol3D=V zSC(mNHemVH9>k2ivRO6e)YC%k*)m(5mpVDi)!eiQTRO%77cpOaAJApSt8BODr!-u~ z(2oKLa`irLR^To~LJidH9_5gzf1}1k%XBi!oFMpi6FD1d;^Gp7D<_sr`IpUd22MgYC-?LPms$`hJu-Kp-L7XIjSXCIV4GPa%Bpg^o*e$>-ageEM_vZ-ckKl`Dqat9#*RR9L0|HokBt1!+#`;X zqoa;3VnI3AxbE*6E*&Ag}mcd+I)*trSjH>;L-I)Kk;Hs7a?4lP8TO~q#)xX zFqxRffZiIN_WYUo3LTSQPVoiae+bd+uh1mV3YuD3Ma0Urj z{QMB33!K(^!0BeP%Z}O&zu*T0tVlElU`sGh+?3*&>hijFsEQWVjZ_q#V>v$Jzmp|{ zoh+R=>x)yk-_{h}#Ec;Y26B7MUYh!J5O#tp|3>i(Yn!jJ=ycMU_SZDgm^@Q)GQ+IO z5%Q7qYSf$04HrKM1(xZ9UP`FRaE|~Q5hj|HhZ{{r+?3u`;dEx2qT38C^yO@?V|&ix zFTV^Q4q$fOZ_u6I%_`S7fF@hpNeL{6qP}TWcRCm3Q%N$!mL?&;<|?BI97?WBqQA93 zc_;enH|^uuzLbz`_)_zw8;U!kUGbs})k|9eo4S0L?8=E%dsUp;Tt#0(-c-!`@-;Peds2Np?UDjSL@iV~F3(jGzrwnVgr>}y zcS4q*2G{FAe`Jw#(sf1iXng?EvH8hqaQ_*(dzuj_sP?uwnuz6l_?j$-)@_;R8#3g@ z6fqC(Q_814?8ByE5R1_Q(T4tchehYz`@0?OH`Qbh8;blm%Bt$;@#um(yhlR|l2=a; zds)-nrbY|Pv$zKH-gUG=>h`z2!fYw(#^Tw;6NON*8HASwq%9>|oECt(`foXTR+v1c z=Y@16EGi9(8EX>M=z;sG8qJD>kTn#qt3bz{VoxZve1*2XC_E6ZG+fBNT zY4>}6!!FJCp|%r@>lsiy09l++fmgoKBzu8PiGPkCv4_$-LVqknc!g-1(*Xz1bmDvU zAa&U}1EY@rIK&}RK|knQ>LbGtwPAw{aRSj;p*CZ3QF|;7`IV|UEgu%YqwM^Q7I-|H zF$%t>sw1a1ii=hKv{yL@V*LQJTQWHPJM2}2XL$16%#4_sy%27Hxd@kHo9G4SL=X$ui6Mi_ZGF3xkKL}cY!lpaMpej zZ{GB9$6Ds&BC783tIV|a4b&^nFV-Fcfn%il+F`$ppcM6Ef|z})C;b?K4gK7gp8R(M#!&lOc_hqon8>a zn|<~JsFOaZ4b!Q~tQMdAv!uqm%hXL_CFP2eV6BIv7_-ijWIJ-)6;+hCI(hgnO6Mb+ zXp}(DcM@3#IN@Z!Ww!cq0p?j*7+ylq{(zWI_{hlyB>`HZG&PstFPtvB!REzRAA!J8 zZPyu>%E8`aJ<`9jzdk)|0+N4Z^Zo_{(Aoi)t$woY=lQ!P8Ub0?uoABp`RAWWsq=(^ zmE&HJej&HuiwH55rFVB zOsQ;BV71Va2h4>UdCzAyUGexFayT@v+cqzCkY*kmEcvz%-AewNDHM+4P2Xfr0m_EV$sk?y;%W2^TmAKPGi5KED|$bAX= zX;|Oa(yS^@zha`Yoy+;eN`wtCbbyjJ+N=I^Hp4nN2)fuEZW%iher5j&yF2v$P{zJ( z&%aIHvNUkYQY-Xt-eOh|wFz8gK@O;EjsnjISMAGeEH80F2NCoaK}9D)(k&m?C{Emf+b5Qak?!`k@}^HDivNBBG-$wYn(Jf0fA(>cpF8oWEV)Lj2mg}rsda|6 zzTjx2N1^zMHNJ3YX+#>W;s73S9@&K;A&UBHM9VNm(#{)0x9Y^xEFfls>-1M;k^+dO zAua|vKEBz89za{h>r*Pm7Ylr@sZg7kiXHB)Zv|>`{5Ygd>&Q&+6&|y^C@PkO1Fx?G zenfcV^$Lj^us4T^^4tqFgddqeN21ail^P*xRB$_EJ2yv5QSmTfkO8-7LoyeqBES5J z1LK|krVa^^R|u?Q%7JMfNx{$Y*3yBK0)1^a7?L$dFnE0wgrz-I@8f0V;dC+Q<)a$G zTmEkFf`$A%;yVp}DA_f{(HSL|4DA3OW(k61!MW%q($e~*Mbs=OroC3EO;u$?px!J}2zf< zNt6=*5yf;KbJNU}Y1$TR=>5M(_mSoW`#5SMdAX7NDzS6SivU5J9zWZ$wY|7o6b=xB zj`4R{;X%2S>x0C+qC?P**RFQ&zd59i+jZqRAHE{{1)z9`mmEwDkjbt~j?p@~?V-lX zR}Oo4`r1JnyMv=2g{wPX2{@XX<2(jV8{)j>p(Mp;?!UPAi*I;?;7+ zJqmB!uZ)UU2!QK_$0~Eg_1kj2^&6(dzI92FrAKBc)R{heQpgad6)(m;+sI3}o{iOM zzx#eD$#`#LB6fj-RN-mIn_K@Y8oNUUj>5^+0Dxavd_d6z(674j%v>3ntfgDivMx^& zfr_%iHIIVAQ8So=2IOrZ?KyG7_e1_bx8OAkVfL%le-hp%hhf|3>G9Jy_WrRk--*0f zTTs8W;QXA!+1Xv>XZ1sG(hhjFOy?qc!a=9){PfXWlu?96O>Jfk{Y$vbT3a>yNOJ-2kanv7Oa(U13XySk^ppbak+;_7mAjz<#NLit zfDVMgkm5@^Oa9yk#xE*u8LZQ{S5KLR2gd4H765roo`|)QkoMzyj)cm-@m>D)hx}?x{jBHfT8BSVTFQ`9`jfXU_G)I z3V=3w#?ZdY0_c-mg^)0=3U2b(%sYTu#cm@Ao6_elmi ziv?gW873iT1D^JYDRVYeE1x4d>-h3e*ky3LE zD^3G@zFgVPA9~bvIshGu0$UzVCam_}dg8j)k~As+*~c|g{;ybb9ZcQ5x)9d!lCPgB zbN}R$d(Qs3N%h6#?OU@?pz843#($8}u#1pm$H+s7C7TL1=L~B=IO!C7g!D!>8Nij? zc2+(~zi|78)@=eJ$>v>FIw^FbvKaS~#`Qogz-|+q+$e%S*@g_Uq%9Itr;h4HYGvoY z{0O~ED}b1MAyZP{NbVU1i}itl2K5VHM-w9P!g%#aeKS)>QPzao$@*LmK?$54wVQC( zQU4n^$)@~w{}s)(;36i}=IF2V0pM-5|3A2`f+e_9L-&&!G0?~qcxcPxYNN%|p~N?c zFuKS;mE{MDKT})xk5!Kg4>n*T?~g7F2>L2DSkB@Ep|p?4lPA2j-7OyaHt=^>J{SS0?LU67T~_ z7nX91-qskE$-5QQVfqh$Uv53rtd|HUD2Rrxy2=o5P~?m@R}QIO7zTu>PM*aedMr$B zjJPJM`4-{_ztr4RJV<3EX8}*ROy}%9PCaC+)#Ml*Mv1`>*FGGZtVAoCQ9%-W{f5561qvH z1n)Cgj*Y8mgBUb`2yhlTKpO$h&)q_N53iw((9b!E6X-K!){jo^hYn1rK`TtN^?djj z0Zi^co^u}dAH1x+sv4u7(-ip3bP-^dBuV08zQWnWPv>p{pY-2(wtjKOxsz4NW0UZj&1&+093H~@b9YL;va%X?B+N})sL zg=Wyi!pbD~s9qB`1$VHOwW@#1K*OH zQhHY!uF+t41gr484J-!s3MG{>Qu1qV=EZ~3p*zy_PHY|+PE(Nhp9cwZKFVDHFM~9&%;VMIS&zt2*L4E)&pO3` z4|;(^X_o{o^GQ;~x+ft{BfMV<$wFwOztsKOE26d&LM8o3$i?3R8JJWk1WA~STC*ki zXk*$TA8dRL!%V-4n&a)W@$ZOjnNF96r0;m%+gbwsPr&|vw%npuJCs;gvEb{rK5Xzu za!SOpZ*4-2vOC@SRwcpMVhQdPQ*E<|QxG&m!)LykeF<}FOXC+W0@fl3gtBn!(9PD6 zCA%j)$0sGljAICG#}KB!O(?>QJl_yJ-IzO`o7<#~9j{MUVYWiRD%;xm4g!{C3@v#s z8Vu<(d;sz2@o0ElY9Vgn5Ftca`f*n=mktH^i)BsfAa+%rQtO*7tb~}?3%O|&0nQoh z`KQgvw6U;;qSq0fyfWg-{NbO5SI1oQ&t~%LGPg|}D{=rXJ7-d;avmkt@y`8(v*&Gg z12GO!pfK-Q<1M*qKfE)!MK!Dv5g^;eTUI;+1<>TGLVlaCeI}So;FlS!Lg-j|txK@* zV#nt{_ms>s1}Td<)iOJ)`r;BWOTe??iCXRyHyL0di1Q@-0RLm9!#Y0I-8IBJZEUfU zKN+)fs!Z&TR24t?PnE3FiYchxKGD^Wj`Sj5$&)GXUht-aB{=P{j?!1)Kl~snQhlB~ zJ|K*PHV7GHlDH+HrGxjFWh4)aIe6gNwbuvL_bogU6ErLriI#$2PR6SH7fvP9j>I4r zT7Ky)#pr-(;)QKhlFFN3f}6!#+-R;CV=ViRMW{E*Be`QsO-kTLuqR{fPoe#FbW%q z*gWxTB|bew-KK=HPq^!`nCd?wUa5}AHes9V4YMa=!*v{U!5kuuXQ#eIG^DRwo68IY#Zx5CJcwRbZk_4inr%8Xf;LoJJqU@sM$dbN zj(qJBYgBCr)J@J0F{n%EAu)_s0mghaBu_jU?1odpwbT?)ljPOxK!T~%B6L=AJZg^q zG8|)Sxn6N}|LW})?Ka#~n>^A>lqs>=R%>^7W3gq(nIx?kXuV+$8R$W>(d6`AI$AYq z^@G4FjPd*b)B8A>|8Mj@Ru0bpsX#CjabHI0Ux&69Zwfv5^S@A&yOgfj$^AF<%HH#m4tq(24_m z!>e#m;Zgn&cwED+qP|MzX!Ya$^O1o)m7^! zbamf-U9U(#aMZ)d_p%cjMK|6{dksNM-6cT6us~3eL17|50ze3e6kqgX9Mn<#D++%s z;QkweR1E1SveSrSaWJ=6FR8@e^UDC}LFo+CKqNIZ;`ZISgvMa@U?H{pK&+CXdBf&E zV+>>@{1Nfs{}6S2{|ywIKn!re+y#!F9v%+rT%7g;+t(uMoj~|k|8W_o2Xs^lV&_ZWt~htM_~!f#8#?`iHPW zJPm6;#)ALYsjdh0ZxQ;Ie^!5}7FAriHjrV$zB;ghxew{H0p(DXfEE(bO9J3_|NM7Z z&{qL)Yw@)8UhmWM)8)n_t34xj(>6nl$XJ5XUH|+j=jW`UUBKBLI)rllSR{F_W_vEC z`%#}9z{@Rc0L@vU|2XvGV(E$99=K6#6B395LK{Yp9`fk^OjoMO#Ed{5%c*JtyYdHX%908`Ote7zB_f@FN0&K!pH> zxW@YWp2)L=`7DRs+0K<_`pE?X@u710$^2Pv6x$8abGPhJ1NI*P2j8z+3)=tC{%;1z zYrxJs(#bd7<2LcP;GgfYyYBFhZn$`Ncb5-avsc@1U?N#wQR2EA?@H`EriBoM{pAz8 z=WBft-T@Vr7x0#1Oh+Xx!KM_dtv;9kKUhh>^)wAyB z(weWtcVD+YBJ=-K#-Wo#rZFuDeD3%e(vR=ff=N^DFjchVb}>KluxIGqw#Pa z%``X~)4O|LBEXaN-OklA<^H0&p0ca_kqu$X$2^nmE~AM}?UvQud_+a6OR)6B>_$7z z2|>9aCk(y)iPTbALeT47v2U$OKNMvRPmr5(i}k>T@g$SBZ4J{B&-u5GX*KGq-_|kPpRw5>~#)pE%)Hr|nR&0$Nb! zc0oG~4xCgf@-Maq2Z+k+3uYGH&hCd7R;J=t4Qaj4Nb~#aw8#+My!u;C$1U-!wp@5V z@U9myvL|5uQ7UcXowjqW93{j3SRElPti~5ef@g{N;g^U58tS(b6*s1$l3`7Y>}Bv3 z-;$)Qp@GIP)1C&kemg?ZoqWHr#)f@uI5??X2xRIB9?IpsO4J>5=v&metuR~ysOoxT zJ6+*EcC$l!aXS>Pqk*qHTavYw^$pB<3ZKPuN3bfko196pzG_Di)UMx#0*&6rpA z3#0!|Bn4ZSFs!zbAr=1yBq^CfmJCFNV&UjZDse+Fvm+@irkKz;pa;HNH%{+bDRXgLo6N-d4s%^i(z#pQe zLZ2Ju99~AEjLH%PBBB9h}k&Ldb79R&0iTnNs+=rnbtKp!*3X4L3zA%eU#+@?&;NM3 zk2nmhQLT4jq1kYh0Q*qdaxrky&pTEnW?G2V%*) zGmwYY(m}6=N)BG+QFgugzd56{dbN~XO%ykqQkJN2$EMV_Jp)Zs{yvWP)F zhXzn3mm$*pMC9{~WUMyeSeuezfc76P4(+lPE-2u!NC+Z1r&ly*H=398PLz#2O?rAM z@}3-BQ-yyT#Kj|*j3-8|QQ@eTN)0<)ls(KmC@T&Fj4qwpiK&cr#yC^cYz?GS%#$D@ z#vsb|C8#$YSe>rSRp^Oz!}k}P&6uJy*XOwt_%R2o>LyIaB) zz0LWje(zg?1GQ@}6OLxAU!FI)avIC_JD^hUWF?oVVy^Cpj z`2u&4?IbL5zN&S?%tO~LwRQCUe;*SWM!mFE47<&Ha2SV{_vT!AB&65mJ-?EO9f`@A z-%SG8qN}!dOs8JCv2CdrR||mLn=8``)02VR=$@Sh5jfm0%GR|M0BRhLmuk@VA9MAl z$_gaiC-kBN(Y8RmP#zRrr$+4u#ihhLD9tNzPMbNM=WrcSVC+1trpRDyWS+VvbCM&Q zuK)O#c?k)6<;4+``o^qV&Z*m0ebEUKiOU#cl>U%^JUb%=dkfRa9hZ@d8qsF|cVbIe ztOU<5Jfy;Ile_+KKn8Mu_Ws%^DM>Hi2eV)K#@)CzW^uE+;dp^?!t5{qmW@xbN5A}9 z|A=NHdh(iIQ4afQ1eR{Pb&pvz6s?$vygEa*O5FHbXkeF8zM0Ea%T_#NGT)!wCAFe{ ziWX?;#WkKdW_?xG0h;rIl%ewVLwbGn{jTP0LXYTpFAfVTpdV#)QV3l_#Q8*ME1Z>q zZd!0@SdzN&=}G%$`Q{3wcdseeUS+az%ELOob^LHQjMwI=bY*X4*U7v=Lv)rPtb~hhVw(x}iq)SR2z#ArOK~mgbScOYkw-W(?T^K(EPo^3g>_sI zj1gRC=7u>z;LZP6TDrOlsTiqtI+lF=qu+YZ*kMc-;q*CNL^Hu@M@9?!Z9EiKgsO^6 z0b6Aw?r6I_Mv~@&&KlHZ8eBq$M5cKkZvjr;LT=#*xR%CCc4aS0S=7^_(Kts*f;=>A zOoOIUnaHWZWO2V3EMd`0fxkWsiDy!F;WtImuD~FoJc#G(kjO;CaLtbF@s>DVrp zDpy~d@t;QDqWq6A&d9YI%@z@MOMTM%sE3g@Q?VgpVHy57o@=Qy3{Edbrl}J6Y zGS}{TX_qA=5?3=+HcU57vY9~I%WWObv*Le)rMIbCPlLK3UK(*0G}S5K_8(TZz)`FE z!M@Ho15?6n<0F3++JwBq3}QI}NsjN$IqjjWTlT&3N;|g@{V~C%5$0v<6!^auPDtODsbL5y%RoaTy@7%85$3HCerN&D4w6f zJ#fr@IybnlHEo!^m!B&`56ITqA9$;SHj^Z`Tqku^Sm6er+|Itqf@Om+z%{+r^wKT* z_!~`$kJ;ZN&+Fvr#HP-~<5usaLS+75zAZ!K&mf#>f5l zZc<61Jv2n;5@t(GxJiSP0qrlYv%K^O8sZ7f`^aSLd|Ac@5?_a@-UYEYZUmKGxV^Bl zj0=+lGdW#wG~kHCuj6?=7UVxO1Gj*tBXTWx@)9GN{cPz5-W@E*t^_thUjy;6GwOgI zF`OXc$&CW!` z_EP#JkT~4({`Y=vS+z-4S#fzg2{6F{L@${&`j-0$IwDI=tl^ET%XnS-yIGmg{e_#W zm}!^=xm^*K=*AfTdHZBVHi{o+2FJo$#%B!j8^Y0{N)Q{usg@ow&lTA%5jo~l4niZ3 zUTg;AzYV|#C?rDSfxvV^yA$NVgc>e`&z`{f$sKQzz(LIPQ4_ZN_w~xZo$_lKuOX+g zryPyH=IB{D?sI)}A~iMso|Vs^Ht6{oH@s0vZC&?eTNJI*5wX{v$*U|KemqMF@Ex zoy+>adSn+VbT9n~Z6s$)`JrM}@diySl(GtS`lPVIgC>#Gl9@u4)C(=_HNTkE!Sajo zQC<11F8wLYp;EjwoeON!Gnab2KWy1JwZ(Mqz=^do*ZOFO#^rKF0*8;_EchD#u-oip zmZ`bI>%9_b93Vc-L7BW))>B!=9qr%Ncu42@k1x9`-eq*bg|Bt5nK*cfDunpoNjY<3 z(>whu&X_jZc3Ts^ro4GHaqUX1ZEmjq$2{flk}Igj)CUJxwI4sE2p#qtx$B z-=TAF{;JE}o5>1nhAHv4)Kn_#k61C1wFl-VB>cm0Ed%0mX6@aR^fRYY-6N63cBoSq z>+-5kkda{#+~5WC8Exb0j4L-W^GjILh$HNp*x zKb$b7SMxPBQD-}K{AmQ$f|}m!1c1y-(cj`-!X{*cSgtetd*Zg!R+y0|1Ne#X?S#_gEU%gp;j+ff}X=snISk zjgkxHW~KWd=E&Z}^^gyP%lp&Sh0A_V!$AQo{_K6YDS9$Rnii^>{x`)YnD(98i8bv@ zXFsGQ*H)R5FZH$Yafmfx z?mhAQ!%5Yr!bK!0P3{v!Hwg&oo#?dA_9x1k|M)yQWS$>zH6_EcB2zAkIwx&n{H;Un z_bAiEj`kl-aB>EY2}#un6h-B-)amY?@_;uMc$Cvd{%#tn&?-6S+u7IY5G2jUj=Vwo;2XTR2mjzNiM0Lkbqk@rP{hg0T5yx9k+ zIO^g_wO@*Y4jw<8bKjMyRO}`Vk9J53;hNB<#VsMzGV2J1cSpk@@2ly164a`S~5M7$z}i zsLV4z>^=7auc2D;GKj61e&=r< z9XSo#%Iad5Ufgr8hjOa@o%TX43K8k`du&(UH#OF#y7aei;zL}=BxuF16M+a82A!zp z#6Vd?O%_#}#w|q=@_6{6B@oU`m?PutKVDCH)o(2%=X@3Xx`!VQ$@5&W)Hzc$1*SBb z3MKTo^0470|67_YD+wgh>msYWQ2^~B$|)`IZ}i{pOs zle884@V=tDj-8k)H#58qXa_n^=jNBV$*dTi%b?9aLb$_ct|+EtwSds~@-KQv?+g{& zz&%3rHvadrpWdH?a2^PvDqX2|9&DdfgHMi`@8C%yk-sjF-U6jC3i^?oY~SYdbJ9bnlGHLIq>h+{ z^@d3ibeji$^`eC0J>XCb!>SS<34LhnTIb}PKlsMO zVAX%f4Fln9uN?T(?d3Zzo$^>)qV_w{pawAfq#SYo)}sC?SQ3%^cNw1@NF!-ivuC|+!jnGhynVA|-)YDTwy&w1 zkCMF2`#9UEb}qo07u?or<#J?1r4w=Hb!X`;wJWiY;_Hi2Edahaue#cbuMN{}9ettJ z=7NJdZM2AQ;*sr#$IiNPd(kdHHy_VVKJD?WqkO_G!?JlJ+BJSPyjYC_3l1R24b_Ef<&I;S*8SN6_g{29 zSgdt(an9D0&TMnjoTKZ!&;J&?yK?ZV))BDLO5dRsoRA@#OV$w2@0fh;Iqbu?&qRwp z4-oPtNvz#BC?9p2+2SiJtpUDNx!#mO+_0x{PJerLRG}-G`WX(d+(1qx;IXB~23x^~ zBzs^_)dN^4_O1&}YHjq-(~QAyrEjNrbGD|xi}z{-CUs|%q9{AVy;-g#Wpi4yLWyP5 z$?!|ewk@$AI1Dn}>zs1UZft%~Jh#yI{Bj?z9B8Qxw{Rgg4}`6k@AR_d!7%FXBX8&a zb)pv)Ihmh}!D9Bxb-X}O@n0{eKj#3-$+4M#&JAqbD%ik#rT8<{p?UQ*Nl0&;APj7t zK5Z+kuX;OZ(^!u=60Y8UYL}&Dj%24N0{Y6TzcW<*b-{-7U}awYkU(XAZ6!j{=Iq$NIJZ%mdp z1psraWB&k&OWuo%-+xSI=(85>@ZV*mcGFxE7@Gzt10zevP*Q&Ev6@s5QY-ak@9ITs zj13jzPb_lC4@$pHUU9{RGJ*=o@|k6rUq~-+N$}~eqJ~Hv5vcXmp;i0WzSC+RtOw9 zc384ossUeqR^e9;ETuTk7O~b&h7fi$YnuAfn`vRyHL$>{-UElX!FSzIqo;q)OwVwj zwXww_YfeGisHF3EZp>BoYT%7S>FN?}+<2zH(m6b2?MmQ%k!=6FykPT-hwYU8HWVnh zlAdJ0KR0>cdP?QokFC|#iudvwB5zYbT`o=|AlOav1QFm0=4>nYp*mcJb%YM430cIC zU>`QgSLd~!eKV_YF*iTt=g*>#*FYV^@rZva3Oy>kCZL54Ke?J%6e+7b*LE~mRTp^E zO33#6)ut9eg26g0YknOwD8xqZ z$q5GedV2pj*KEAjLUmQal`7P~Fc0I!OkjZPO|no_qh*x0F3fj-q0{H3w8o8bP7F-x z8ARU}pZP{TeZ`SSD9^c}hyr|4$VLO^t^=vPT%B&U-p3d&B$1jW;N)JzP4?G|&$;D_ z_Fl0aLR!qD$O9fX0-W3z~ zK;LydGU`r-R#)V(q@T7K=XH6~G-xR)F-rUc8UH@I_GP825NW>ezWk2$VC}}{R$`E2 zeIfNGFuoUa#M{F*pa815>{*6#%YJw+*1)TDt(*TMpG0Wz%C5(4#9fTqpi>a(?_qc( zy@KtqAjvuqWZJHk|DX!r=C^}x-kY^p%j*$y8!SrtSJ5|c5Bu&KG7ytBwg8ggDHCZ* zsaonH#dzM+xWcr3eW?It^PuOmnSD6Taouicw5t&l!l9 z6d8KG9f=+bw+)9CxMwnBJ3mr~?{++x_T0I2yTA>aony&@rE&5=nz3WZsL4zIY&USC zI$nA+T{f{entq$;$&tx{s!+)(%E-!CUk+>OaP#I)8wIA1wY0lsRlYtJ>BL$czIuN? zcS&p%N}aX`#jcn}%7{lml-d;~r`B2w)du}$8peZ^vp7vqD}1HLUV-6%eXCzZtX0%S zxJ~KsAfy+t|0LqajiW<5d<{P0t9Rc#Nu}^EY0HAPj(}LqM!}gL;Y*qN(;VuLG=S4D z>=mEZMh1lcC1`4$y~o?N6`-^%=m@&lFSgT}k?}aClBZcE_j6fj$^Jz#wb<^WK2gCX zPZ(U8lF*N7G%koEu&ffB;!CCC7I=!eEYebV98GI)Uhcg#Grhw9<{xsM!NB#0Kl2PM zGNW0~nUwPzFWh0f({5(ysL=Y@?5gNatHeRAs0VQA@zdXXYYFk%%$h5g73sGR6;)wJ zM*JEQe!|_~nHdiv)_>>NRr^!Tv*y6~(M)Rw>a^RYErzrPo=<@)^m;by&)fy(*htVS zhEXC>5YIa!`s-DeJh$pz>);v z*d36ee3KTx#PSivFmxDd9i>VJf?t-l5WWXSj8Y`LCMR$*j;r1~l^B%n&F?aMP|3{_ z)eO6G83;p@Jj)HcKV-~c_7goQAzb7ZMSl^x_KyfjH`(A&<}DIuB-iRCB=kj&ZN-fe z{8;CM7iYpW%zU8S#$vScdA5!xB5qtTXC3E%xf{f$VBu*pZN?@w<~%U{ z)8|P7F1u#jP!N1;`dUFVmP%u&*bkgvOiMk#7&&s7aCfu=SdN`xt zZMfFipRyFG<-Q1w=SiCWFFo@A7dHP#kK|zbe{RG7=#fk;oGkxSSb~|Em5u#>r$;Jg zoc~9U#Ikm57RqgD|L;LSBa>-3xJSqY>?v+&!wyp04gQCe>}b(%%B-K}{uXq;HlcW3 zs`u%f_Bw_`C`_lQZz;^@mK;I>Gc_|eL<5nev975HU0LDM{I3)(EgE_hy=S(WXrd8E z1~D!GXp|Qua49TgEVP~}(w-^Wo*}3m1LOVwLL&K*AVRPw zh)obw^&seY#6;@9ait_E8L?^_5gy1Vy9q#DFdsnN{QUHa1UEtV5Q(sAAd$fop?=x^ zH|)Tn_kRMBlYnD_K6}(BJ_)w@r$`B^riO$BAYuLsqK(XtY=q`V>j8&v1hw$j5oWj| zlIbBt0RQce_^+GCShx_>V%1;wyN?~e@*jZ^7V-{c%@1vVqAErLJ7k$SxE*qCAr(EC ze`gSZAEp%#DWGUO*Q+2ank(P&y?9)6}jG9%Lft^s7z576JHi5ma1 z0YwTBWTV$m;+d_*+d;w;M2L0pNqzXQ3OwjI6!jk<`nVtM{OWL6HE0V-gBUj75|I@^ zuxDBw+ko=iY%eH8KwI9IQV#kGq{%Id8{<;9{1W2c3Fz&sb`6*aUFDZW-`r%l>Q68? zH}FxJPun}N+^-GY4?h9<7F+^|!Uml0vzKii7#Il!eOEeKzJa2*9ENWI{+o2{JNn>TJ1#1t^E1b)P4MxXkbMT!=K8U@7tV6? zA0ynqiM*w_MGQGqWBuDZ%0L~bhH^w10lu;3HIg3K zT?1^=__4v1on0Wm9VFcyI73nK55ki|6} zzv=@Hu#AgS;Gm6=>H@!l>b|4D#IgaSP7|lk;`kJeDxx1XfATx`1!455hF}{VK|d4r zOMBlKa-hyzPqpS)6aonK!qABPY4pk25_rt_I|c5zze zIN0%dnecZ%B{L#~PG6N=FWpe(@h2*<3|kFjLng`2A7q$MBP$aNr;Wzp)F|*X7co{B z)i@7lQ=_BeD19Otb4U8XFLCeLnRlquG;-)}kV~ZQU(Mj1Ben$AuujET!HYni9Gb*>}?06ifFO z8&bvhg}NQq0!E(JE6LQfs$F<0ZRRDhUMaf;z>DJV930>R19mHhbH-PE+x1-CWp64;Pmh)r+}=nw`*Fv}1WD%i*OtY_e?&Pl=l(lZ zb9qgh%euZ--?vFM*?I&IGQ@i=+;vI@zEW(Co7E!y_aZjoIZVYHrQu1=?wG^*Z zKd8}n+YR^_RTtzQxE0~QKTSo5By2Oz5b)u>FpmIfJh`PS)DP|Xre3J5dP*Z0RJqCw z1^dor!?t4zi6$yQ)<)@lMI9%};gJmtqSbhA_Y!SeY04JTEVCMBeo&NOQ;faJ$~$bC zKHhIM^9sBY9}%8Zvcq?AXf%YD#f$0(6YhLG zi&1JqfNQNPx{v~nF-8$qlud0cMl^gqIh#l%uj0=fucCnbA?hpzoH4o^$Vg1Krl?8oNQD6;tN4m{OjLKlsSPMY2Fwg$xKK_506(?4*(c{?)QxSWUqYC~K zlNP}N?@UW^<@Y7NAKYbd(O1z$xw&$wuK?N@g}FKHy_h_JY4v*QpuFtBo72c+;oO#v z)u#5yirm`ub$={7D@?*V>%6r9?!z{}%O~2O_~b00z)sBYgj45ic(M|WH$gIFEevEo z6p0IBiE%#VWIp4p#WRKNz<=;?Tc}oprAb!0_=!WEuo=v}(`lsZ4&yYfs!dqxq zblT{1Up!5zZ%uIX=0=|vzPdC*<3~%oL34aouZlR_{(e(|;+M+ab_&(gdccEZrs#+Y zqu&pVETu1~n`o+$eXvVzkBSoU762#UQHgAEag&xJ(zwk2eiMZIDFQ*Ud}pnYMtZ!z&SP62<^I??FY zBYvK@wuBN{;(IiZUpFZqYnEY4ahPGoFqG*{#)M;>I(aBx+;gkYXv(YE|K%chv9CX` z8G@IDj`VG9;mtFVIa`=^f9NU{Xv6QmLMk{deG^~~JFcy5>ovU4*y@BT;qXOIYJLsa zZOUQXb)X9pB~qOJg7OqtLXW$nx)aYb+zr`r+IcyLPBTHxo+ z^8f=qo(?W!KvMLP@NY354Z-F^{3EXkGi}B1<&LA#Ci#npmTNskrVm}it&*##UmC?-Y@1) zrjFL0uTYijm=?#m6`nOxT?YFE3uz{mQZCsjK|6kTr!r0( zkh4V|Ijx;wBXr@}VL*zmxM%wN9Dt+FyTB`nMlTx*2O`lBTSF;-RLHLZUd`%2emASS zL^~5~emhqe+FjK?nsyw?PB=7U5JnW3UaE@-^EB~Qyy)Ti^(|%!ZTje8u-K!~t8MD> zYC|iSDVBRV&9t~XDxop+0nJS2G1K!)j|HfIG6q4pe;ACdWMPQ4`ixiU9QEjDGc5#; zXI2y}z|R+6^T=tcB&XI=ST2$LoN!ws=1%C6h6BH=v*Gb2JR{hYj zqkej7OGGl;kS90d(Yj@|*-A7J9s`$(+R%T&yC@>q^B^2_yFeOZp5Gc)876kM%nMtGXpDW!}ZL+37Qe6*1V z4E{hUrcgF0$vHSR>6PD3-xA^uwB1Sc%%$6^{_PfU(Ol@nP<&N%;o9MGUH#4t_ys>o z1HnHYEbC5wf&U}rhg(`F=NiK!Tj&*xeC4pT#&#}E_p5U+Vv?03!_-We9cK`H(=DuZ zZJN4g)EidfNH3E38MQ7M3;f}@0sTiku;Pn`(UVkY8BnJwY1l#$y`-LGCbsp0Ya$-~ zuqq;wk~a|w`Z=zbN$P7Jr+=Q}sr-<4a_;#F-PjJdpoF7gd#Vt6tiW8X50 z6)n$c5*Njxdq5WY_^_F@{bpWR>+B%h$0<>Lq%jeQV0pBbDW-5sJ1W9tE=MB{x$`Oz%T9K%xMRY zSB2^@D&Vs^P7eB@cACw`QInGc)Oo(pba9$4;P74e*>Tr(C_*z!lUaQgx{Cr@%B%|5 zx{Fcr=3OeNPH!>(n_-5rL09VsIhw=Gz%a{7!dvvLRm1jr`2v5iQGbJ4U%M9-$$yGk zkp=uNWzX|N9noe2x*GrZSc{?=PddvhpV!_5;x@rA0gencG_k`Bkeb{u)TBv`-p!_GhLX}W!4IkgOezgnX z8AOW7sJSEaqhkpdIYSH96rr0v$3av{5e@ubyA>6Q`B=IZRlAq*tpDWb7+Pcm)91RH zyRrFQn)AAeo_nRNodFR5wwnE2G}(CD69*KGqJ`r9&-`3 zPIuy*Is3(n{@Z{BUfsE#fV)dg*G>v6vew3U{wTu|A464I>7E_{emqd%G;M_sqPmY9 zWBy?exejmP&qtf?qahqkRp3a)18zKS7Da?bTZFw4Zj(uL#_#K#plvKhY-{l^&ySMd zN+d>)i9Z(ZE1lEwC~8qu5Bj@4-Cc_Z9QGm_cem^8&m;ZnhhV$r$nwNEE!)sn zLP)55YBApboNL|!?4s#0a&D3i4LJ5vn>Y+r72iQwn6~qlh(!i5ih-;!CVuPm&{oxC zquCY9;5!7w@*=MCndgq#bg-zKF$B+MDGMeSMD&Wr*H4r`5c({gqW(FmQ5DcIBK|2_ zna`42R3S~^41!v8*TB#G-Gbq1=t?N8)b+3_b6?&=)w)myxCRxK;xaUA*mhrc@_TP$ z6-u_O`NND6mcCJkb{p7H7aJb_Eq-*DE_Mn>w|t_HD6qyw8og%yLyj487%c_H{&%Gs z)PA}+z1C(6{%2Vz?P}sV>ovr?bsL{2Xe;QL)mxn@>we(D2Xt-05VR>8#2eGgtfA3H zfE2AYn#({5z^NHdVzIhOj1Z*k)P$15)U0!>a}&s)qN3!k*(QoPY;J9JH+(TyhIQ!; zv0b>-fw87N@$&IAQOKUXmVQ6Wa%pCp=*?1Q3rt*A;{`7FMjog7_Ff7AZSaZiSA{EyL5GeX!d-n@k9E)|PXTRT(aQwzh zveBebTO_DVsyiPjw}j=_y_DznGj%lwhISYJSlBmkV}& z-F`Ok9i=h98yuAr19$U&djSfEv0JQA&qFn)R+QF~6n7wt0liG>MRLjMVc+>UO~VPp zkV6^@sHtO!!{OBB>mi}}DDKQ>u*qWCy!If&N)3r`mN9eQNA@LLCufz{_vUi1v#K}K z@_g?Y_J3qdfx@~M~68Z80{i$J>~MrpZpEEjyRdW4GA~$Ic2Sm zaITqG&H-5p^+}d6YY8|JNc3Tqx~%J88zy6fZE&66B96k0C$ci-g)a*@K= zroURgL`aq*DHO%5>u-M+GZ{8+^|o1*gIE2ULlC$}H$P#=@vxScx8Wupv7$Setx^gC z4vFsXX0teIwgVtD+(ezrWy(xFdbiF40^>MwzR}vg4l53p%k)BX9x1l1Og3BOOj-3e z7Z_`>wvB}}jf-ZpmyAO>6_l1+w*bTHK+*IqneZ2GV&*HYB<=fk#e~hIr#{@sEUNAF z$qZSJQ5roMCv_qWuLr^gBAfAcuADF+#YrptNA;<3z$OiNyINB_&@7jUCvSA#Ztz8x z(AI$(7OUGp1{5kmbc0D^h8pD(GNn*5?atYAfRDrd$gt%YenBXf*~tFO{tW$!kr4K) z)~f-1+}~?qonR?wbo;jmJm)T7zEtMB2y6%P!KreNwk>mOlJwXiFWuRvkL?J+TY}bE z$l=&9+=j}h^|+$FsoAlfqIYZAoNaqFpK%xI-}jaO7)Lm0M`XOWhR`{_Bn~cCIX*Xs5q6xxCx~J=*BQq z_(})xCG}~YJTJTIP zabZ-aophP<0nbvuH_1QN(6vrNgh}4-jCQ*25#ZOCFNco|@fEORbrd_CIl~0kIF6VR zj|E6F%FI7B{A?B7qTE#gW-2<%yRK7>1Cp#x$AAQiQS|iRoZxuL} zCz7Tc(=zEVMD|$kN{ZTKfu;9mnczif%W0i_@?r11G$!K)_0Z+bW>6N0WS%I)y*y6cy2?Q?8rPLFzRe%$?Xt&CO5;Nn5$fri#oiQ`X3Uo4DCk*Ih?y7=344 zRrG3;lXbz!{YG)G`8UGM+uxYPz9@Sw=X!#WZPD-onFSExoF)I49)Wa>UDA!=zyc&I zzrZl1-zt?6>MHgUXpMKcTO&H#IF~4bdKt2m{Rt@j`7lNKE-znmAd)zb5Z%en8AqOK z*S>h)k{Oj#+y)H5$!imHOyGUyFK3N^8%ucS7U4xGWpOVNswPzWkFQ*j6JqAHQ7f2N%oZi#@Y#BF)*KVRy5Oq z0x8Jjg`Xu?47Y?$dOupGPj5jd|1^KliYV}`v%RQVo?DwTTCsalBsM$yfwN_D560v} zj+LL+SY)Ts*(cxfG5+kG^q1)%Q-e9P=fP|g)ttz4a4WCxFj8VQiw+K$`nZ05LtJ{cT%oU>6quY z!>s^Up}p2cZ&ju_6xrZ;xDl(CxOjHKw;Ym9Iq5fyCuuOZqU9yDg13y3} z{a;IA2U$3dwMiTyO+7tG^6>ge=%;<1EW>uo{6L?cVk%G_AE^AHX=>NTfxX{}+@G?zv2 zLWUdXr~9t0EXPQ*A0nY2BGn1dzH)7>d2zsuA`J!J1^%7qAbR93MKJpm;PHL4Kg%Y7 zrN+9+(}(1xUkz!Yy6mLPs65L=7v84kO6RkndPr?vd$C?Zf|m}PD7X&aMO@}nrkX%`@aGX7*{X_+lY9gb6^MCCFR{x&Z4dhZrbz0(H1dubO3JWb& zi~*KNMl_)rqllJg=JG33*1@Kcy-1~pI9gjJJq4M>-pluE0H3Odn? zeUwz0_Ye$ny)VtFtj99^{v=iJv@)PBV}wk&!m!b}Tj}Fen5E`!XSUQs)VGZs!BG55 zqV9X4E^LH*isV4pyA0|+K_*oF*I}5DUU#Lhhu!E zvq;_7jpZ$Z>d1Ka;af?0YB3?zMPA!n4h}}Qp~2hb>2qU|cNbPW_lKdkE_Zlr&?UWo zUM5oF;$y zw2G3RAJTNK(?hEnyfZl}oSCo#VycQeMITc+^|h&%GwXlarr&P=QdB<{hk^AS-IkRl ztzi*!7Hm_Z4_IGnaftvC+fL+XLo$zcu()&^+Y`G$d>{-=Iy9~wo9qYOO1vVYN<@Fl zm&2z`9}3R<&u6yKFHLXRF1P>@9F$8Zy`rDEtdy1zREm%2aSnxQQ|nbdXEzmD&>EFW zKAY*4`UU#yOB-nFF@9FD#L0Rs`HEHXHut4U)RfL!cwgSXFpPj2;zHBEj_ZTBCzVdb zZQN;G=G)7W#q)*b0!PRjvM+BGKFT6!5%^i;7mo@?rvsSm2OKj zah@$4RN(}1beI6%K~banFiZAGbw2N)ilAihAr;zEuI{;LHsP&fFtY|#DHrABJq~5@ z9`+y8e`CjfevdAohNu?ecpTI|3bR}CM!S3y6mB=GY3V82cPi#o->4Y$jY!(Wr834h zDHTOmCkMYqVpD7Hu1}rqd64yLrjQB|vCh+=~t&T>Q&h18RBKYGH6cIlfY27j?l<$3~qx#~>rUdTNhbXinaae8k8_lUZ|Je|p{on8>~T zHyFu?<6eCmROsz7Lm%m}M)Fl=wH^WwVN1a~j;a`%`n?j!G<@?M3Tq6bPTWr0i}mpM zRj}J3`f2Zn#FkFz>}{n^U?LNc@`->tSf1+ArUFoOSuj`W{0(Q4(7rUe3ZwJW9k`t* z4B0R|IT}h{X)hX5%ujT$)`;lvBw0XsXcdw1CSg#Hct}f9R73}Z=t%P+`;cw@4alLW zQ^(0Jz?oniF;ln#hn1Fyr)LKg4O=f=PIUi=u5${`G-|VUY}>YNcI>2M+qUz@w$rg~ z+qP|YY$t!$U-M1XRLvajqo?-4uBYyMU282!O*)|tW+7nSvGQF+Y{65LzPw9_^A^P6 z^hrQ&M~U(>esG&51nkq>LtDH(o{IM10Q;I%lUw&UznL|8G1aNM)EF_E=2@dn`ZXjMw@xlV zSZHDA<-SH4rP>WMf%%PWlE^EsvpCz2a|iHBO{sP>qYPuK3az8@i>NE@uA^cdex(S> zn-P|q7$)>eZC_{s3SYMX{16*b24f=!E)asC5V(wwLymdZIC2m)A*R(+GmK%7$=58B zr%+;<4MjXvBvna+O1m|((^#tsEeFceYdb(v^MY8)Pw@1g(;y!@SEC}=@0HsQYl29Kbv@UzkGPsv?^!NKX1 z#$3}^IHRBY%IHHi@~@O*fq;AjHp-U6WIsx+Tu+|UQu#QV=1mwxI)QG3=+v()x2DCM zj1#UZsSL+b@|rttqZX1Q-&D~XuN45ofRn4_ zHdw1?%N~rzTA`4x-wUr zUuKL5*r$(>c5YRPYs$Td_yH8msON%glNw#@qG^9X)a~De_ZmBLzeLq_+);pgdeljT zJYj^<2LD$*>3m(jeIOa%4fG8jcplGlJp%*EY2p zLJLqesk)?Cpc3etrV;kBug{uqce;HrEb_Ev<+}T)$c)dT@J^v{^!H>4!tlHOhRkx7 zlg)zVooGe41AJ%tq@-m8uPmU`MX*VBFVXy(;X(_c`F6Q(`&g>$R@At*z13~fwC=rF zdK01TQ)epSEX^ii;`fH@N9&S(l58g3kv#?<{sEqXSc6GbQ~h}ictPcp6yd=s}P?%mbhHfxjJ~Lto4$0vzPf14vN(OFo$!}j@Z$m(5RZ!rc+|Eb# z4IZuZ6*iTcR2zuU(B7yr?OynQZUr5fc1nGt{#(hfciHgrv|0+o=kK|3Y;~3G)s|Zf zl^KUxP>4-pP^|r9ws##w$Q|=JyWf%$$#p{3_rAy2v$elLjhn<40Vzp*f@u$RTb9~? zWVqQ$q=1chb5VzGCtLv)y0UPwLCn`YE(2mauzCfK3Gy;Ey9MsN{w{FXYuN(Pw(rG< zrylZclZxMEq5YUs;kI{~=A#Wq+v&86URgTUaCy>b@yYZ{9+e7Y(`Cl(NfCiIrF24C zI|EEnD_b}!d(^gFmiks|uFpAiUNh^g-Da+KJ1m{Ok32hbIEDZWbW%vdR#{yEL?19s z*AoGJQ%qLmn8qeXnq9qXTVVv{eSb`~X?G5CAhZNks>7?0@Z`8|_0PK2w&*8rG^gea*#GnL(ot^{p=(BTD*j$HRA>G-R+it9)`;%U67lRjCl~@cl@P zai-qC@R1kjuJe7iA?tpVgXjJq(X^luxF z`ZX*OIXDTdq0%6R8^$O8a7SBou2dBeI8e^%x$M?|DW@;(a>w&U}Urg3{jIz*D%6 z{R0I(P&<}^l31I3YI^VQo*z3cvBkRk8)6_rSyW2i0bIU`g^Am_hSwO?6so6PEQ~cFNVk?w9i%gtVr1>@cqRMr?Ze}l~ z;8;rmtC3$0?x!cJcttb0mZQu2vC;Ck zLpo_9v_ zZTVgF;=?B!7kChK;eb#bq|76WDH3pQZtCs;A!~AE?Ct!*;gfC?x_|rnw&#i4Su|i` z6*P0p2!77{z~uK_-Oe_X-mGsAIKL%;Q)|>UF4iNlii@1wr@arB&*ldX}ofeQKi$z&?e9wM)st_8bz(xqXno`m_w^Q zn69!)`eVFYdB?*%g?f0UHHF3_4`IUx60rb3%BsZ#Ze!Fr)U;%Yp#QiorgRH~;F#a; zcsGk(z{fp97?i7GZo*Jnl3;7~9LN2b#F1IT_;;#V<94n*ss}s!HOC^luEf(l?#^q? z)mr+|hcdKmI#xVb?jt0n@&Lev%ID#q65+^9urseL$Xn_S9Qt8hAc`NI66@&`l^FSmX)K6W z3bJoOv(`?8vkPXXq~d|9oU&?$?3uj$VCAdsd|mfDURXn(nrr}y931_Gun$i9sjmZ- zSZD*(WU(n#@3l8BQ@Uv0F<(KP)Clzf#U0{ljfn0AeIH_*N@lJ5&vzj;axs0I*@CfHD?vN{4`?<0Nz-^jDBgt7wO2sU%-nQLYrs__%XPQWrCjCHg6uTI2y)_QhBK zXHr;WlFG2vJ6$G7dH#gVUtDzAU-|v**YrpA&VmxFp|B2@O0x~{e;o}>wlg4#11Y&+ zeP;sf5kotq{-O>%4w$$EJZqYI9#0w76fJXtKaaPSkYM%Nn>S`d(ZH+mG zgyfoE%*kIQeChik!)$fju*u^7Ut8vix-G zn0~ebwR;v^26$5>J|m-0Je2L=3FUZQi=0xG`aL2u6>;DTMes5V9JG9d<+FA^r zTcN;{Wd;aAoOzM2FTdtANQAI?*D7IjP0CuI7&6!T`7;XI;Z5rkA3~YZdGJFvw{r-2 z51&%+@ykhMYq?U@yk?o%10YTvnWhwQWTBzCdw#Qv9fs2>cdK7$RBXWgSsIZZ%ty`EMTjf274RvvU5QX>o4gDrj1(9OTSwRQROZQ*(JP?xjmia7;sR%q~Gi zR7CiR3*kfy3nWDJ#PET^O;C~#`8zK=H$6YSD?hcG)+bq~>)yHDvwqK-gI@X)x#}wz zmY~YNNEEva1meLI^^_IRpg^GS1B5_;)YL$^Ca|9Ykl=MV{agHdlEFhi2glonNK5o3 zK*HO9EJ=`s*cHr)G?1V$5`dzl{e^^pkt9C_LnYmz^FW4R?O>OVKr4umnGk_0`4*N} z@$GK>JNSd=0E_V)Gy;Zcx;3)^~;Nswpo65K#f1_Vs*jOp~Z>g_`G;jowPhCV=Qc>$nX zhlo{iO(LEmTZVnweb@*g#C&%6e8??K?t543LcXf-c`dYXccU7IalnYTwUxkuZ+(EU zkI4^pBCdm0RxlW`j<#P&Jr2SAa|qXPpjNa1%iDY(MLr>@f#)>hp>HKiuXb=HH1qVa` zqA7T&hX9`29~is63z!eNKtO-%8{~T@iEe;fD|sKtzFXZUp?@#r5G;gfyY~Rd*AM62 z4L%SY#Ku5ARUZ5lK`hWG>K8`n`q%od+YbIUs1H~NIsq2c`_r4ZsbeL*Hrc@X3*p1= z^s)M)%BrIJ{gRbuai$PnrA8TRvs{$ZElhtu^Z^8N?u z6>wU3bbk4ndHgE&Lr6CSetr3Y38++8SgL+zPiRH;f3;UOUdwe{4qhMN*Zl@$s)`BQ znG0bU-h9505AY}N2{38nbHV(*m7oDQ4C;fPz)AGE#1q`=Bf`XE!hw8Yy7Q_kmTpQ6 z9;(IlQmNT zWB*{37zvF#EE6{=<_6dk;dAt1kx%7y8Z1j4`*(3q8jU0S7P{L@n+5y)1);vepg$oS z(UAlX={640)B1L-sxkMC0Lyu!{orHHaYeP82Mn1xGph4;v=R?AAc-i;&IEq z?3-q{13e)bI#CDa49M_pk`b^^Ms`4HS<&SLAxAMyg81)3kdseSGH7)T@?2X`hBY|C zN!Z>@uXwiN!vVTLDLHbATxrkaqx&zuEvP`1QGUG_d3Y>v@kFpvQoG(mlX^lRc2-u5=RkiN1$c(KKG%XU?o;*-QEPhF6FSfMHRyQ(QI zGvKh_-xBcL&K?wvJJXQoO;=Gh$Z0n@>#CAr?a4l#D9#b%lNB1#;p63Ig0U+%Wtx;p zUmn2~eA%m&k>V1cU9E>hFqBGUX)Z6cA?wM`xC7q5F;$Bd7yjTr-+AwSCM@-p=^mTU zQ+xdR>1_dXIY*Wze_`8SuMInqarwQyH;d2GG6;YX?xDE0rG`=6FoQ0R{PH1%en{Mu z!mCOxuKolO$B#+Qim_#5Y!P^R^gGtzS#w>tFKMwZ8EF?0FMW{(5;g6{S~SSpcN&WG zyH`#7%ouryb1@9|`@8t(k%2v0M2uZ*9WrgvV=HwRr?kt&dKWl85_EM!Ao^I(g}0Le zz5*c7fb}I9y?fF#bk3Wbe4mkWLu0>-K`;oTAh6MUlPzfXMjx?vdHwiNU|DN|FjdG* zOz>~Dp|Senen=nEw(#l2T*+&>FpFljZD5yOu3N;Iqc*p{a({A~a_~-deGRM`d%BqW zn+(kXnq=3vTpE!zdk^Bx+4?S9e>vn)G6oth19py|8*FfyT)BlCHdaB4!kkw#df? z(lwmeJ(y8`C=<+xgU@BJd3qpK*_6h=P3u6AnX99Dg?dD?5b`xQ_In#U$#HF#Y6tLQ zzAQsAOu}qrnz;D+lv8_yyVE)@#@m8o+ZA=SqR=YO)Jj&;KHjy*&@g5g@R(kAF~&?u8bshKDoLCWH3t z9GPW;!xPgxnjG5y@(?ZRGT2vMqXf`>Q#1-7U2B1G544Z*!W+G>A!L!aUiFhUH;iEi z6~AI)6={gguEQ_RYrqqdVMNurrr$1HcGiw8!Ifr7`&JW~p&1RTUMILQvLGUj(~wV` zE$#(-x}z(T&$yRPI(90IkqdF2INgJh@^k}fT28*~s!98Q@|Uv%!EJ*VHUQwboMQvN z?E*(qoh(c*88NtO#>!=*=HBs;@~97AyfW|J^^4~D#%Jctc2RWA^|nYGD85{6apxH_SC4YDm9zWD788MEpJ#vb zMeOWnE<8BSqZHV=X=$CdMV-jyEFaN9E%1?2kJ`*;YyTM4gk#9)ULdrs4|#M3XF6Vb zHS-2iK=@|xj{ZmFP1qQSryiy=~r|BfXbmF@bT>OAaBz94Vv%0GPpqC~-U;n=Wrj_Yww zye{wZ3S%X<4rH!u+fMxaE;%aA_q`S=ga3Q2)gJj&9;XwVayVUtAgWy9cnL=5 zzF}fUuJigz^0vL8F$vJk4sas=YzjVc+g;&X&V#e87X9094Vi&3uF&m6r^A#O0`11x zmcI2OuZ+8KNRS?N1?vrQRn4DhaHN)sn84*#I5b@(27-lO3cVA{BIBMfpCmSZ76*2j z6@An(pk2iMj&=IlBS#N3S5jJ*+Qw*&y#6<&Lrm?Spl4yZ?4 z`Bp#H)6e-f{CfjzRJFJCDcd%>7iVM_-95L;f+L4erqia|dC=qLJfI&iq%#)!acq+C zI^J@EZ57oyNQx5L!kDi5l9%-P+!Vgr^ty@Ze2@t0M@Pf)HVEmkGU1t6vB3Do%#RJJ zml^cW%+cF_8vrlUI5Mc}+P_$MA(0LbJ@3;QIbM7-oQxb=cez-cUuqtoGt6b*DB;N= zKT2$pOEscfP^@z?7N^s}0EHs(Ec@Zk=B*deXoub5T3DTvLfvDQr!2)uOIy?=F@2FKZ=QGDjPH4e% z_>ehLADV}Vprct+|6pO>F3LMyHz4EMi-h+0E_E%Rz5>M&9XKmOL|rv(p?i^ z8tnqBW=9JX|=K&UXDsm~yz7I-qbB%zI0`TypSdlz|(l{cTvC&}kxnM-Uf{$HvjDH)-PVKN+ zMEeJ|tS7SBOoxKRfsw=jOcL&GVN>{EPdBaWP4EwBaEfb-u@uvx*Eo}EwteZ|Uo)6r zfxggzG4lsRvQ=;W3x_qQSbB1`aNjJYcR-$3oB`DDH}2>bPQ|WOcF#(MW1snif9t8C zaq2JU?$-_>yqXThx;#6I%ep8TRNSBHi?7}8d%`o#5F~xXZ;3oSjuQy5oNZh7q#~b? z^W?=LGzFu%T=RH6Mmgt=*_!i)`1j}~d*U;nQ`RhetDWO$U>`dKLiyqogu1K*t%Q(nRr5W@H{hIjTI z5o;MlQA$es7IDpcsKYs)l&N%DvQ)ne^Z?$ze5(N}U2{voF+n<$NXJ16XwxFQvnsj{ z3X4%CeoX`R^Is7cm^Ci~p$@??HU7!oIrP}^X<-KaXm#!8OWDh2QyxwF?&>#v4@8Sj zrQ-+HWkAkHmCt2C(*AL0+szQZVv!j8e+SU6vd-sy2jfr{#?D6Hq*Q!|`J)`KhmDr;b|2g!xM9it({sFV9_~sZG$wxK=X< zb;SMEOsba&d=VBZ`k+ZI>l5`Wvj7R+Z6un8z11~xU?+lMO*^~YgzO1JhSeOme_5Nk z^i^v0_JztBu||DBs%#O&3$s%gCf z>Zx(Xq0e-c0?QW%b);ed82}JPs-Dyv#c+&qMXU&|y&Gp>GvE3lL+M3nLT;1*Bqb-! zMly_7EqJnBuw8b>?{MzK+h=a&2Ewe$O=gD?s;_rLc&GV{A?M zp);OBVt4w7YjDJH*&e$xJb~G8wRP=nKzXG&^Er}H#(dbWq`gkjp4j&u?$+mr>k{%zUoSObpRa`>V#60GzMMT(AM5oT zjntr`K{hcfZ>pi1+4)+HF9gFjC!#b#5)v(dwADsK~=KcKqY3A^D!FpLS%a6UP z)NXfz?PQj3SHLcn!nly%zISAtp)SPmr4jvC4K-u8KLIuQr$zq34SBt3ZQYO~;QJbCNuzt(sn#y2QylhnLsLSBC z2sz;E1C&>r`_Wd?kx=T+t}RX~xPdly0n)0m9`3_=M=EU0$zm+TThP0ei`$%MiPB$@ zB=7agSKgVbxQi#yxh|yThi+B6fQLb;gJx1*4`c-uva9IQT_5$pby#i_^rqmTYY!0% zdeGY7rmwjWZ9H&Ne<`^ecY3~gLmUP3-=2ec0)B^CC+9C-pf-)UZ&Shi9iuf|XJ+g0 z5Tv=bx@JTg_6GBn+7p;MPV%+%TnEkU@b(a(xHMSH8s zs-s9tuWdyo+n|(-t|Y7dCdlc|BC9B9&BSVumS)<%2FoZ*u7^=|ww@_BDClx8_b+tJ zR-ka?2ARzg@$1UWx%_vo+R?6%L{Z$-Rs|?mz*&uI2 z8MwJMW^;F9Q3pi@m0z7|(t`5_2yFJuc8QjKl&5I)@UTlXHbVMp%1Sz(6-QVHA@xKndEWNt-U8VQh~7mG|}b8 zggZ~^v24HT2e-(~Ra)?0F!x5 zIMcBoS?%-9{W5&9l^PzGM{NQP{5OFPMqctCnr%aO!TLlDWlqZ{0IAPs)qta^Wt%L4*p*AiXC+5fMlC3vZZtB7vZM@0&=ie;g z=sCK%7mavb0Hnh>e=wy5c@BTlJL(O>*q%jtsp}x;iI~z^zfK4xrm5#qg?9nHsklu~d z#BM}khg~=ZV}ljA^__3X!9Dwngg^)LpeHvjsWWb9B$;&jPl4%Rpb{Kv*N1RCRlirL;VYV<1>r(%lzysTZ({XCh=QNN3AW|9*- z2UY163G0@A03*ZAaxq#=4Nbdj2Qa_)gzMrrLsUnLYppBh=}L{CsAPw+WMVJ7Yr402 z=HByS7{XJV9@l3`bNjicJpAb3^jB4d3e*YkdX;D<<2Fu7*IjP@oSykt9)ECTz?muB z%!mD|OB(rFL2iB_(ACr z#cy)lWK8rW6luYlGpEMskk35CbR?yU6|uh%cOL7rarNAeH*lz8XMYoi-OD&G+%X|I z-z~+To;`+FR@G$JK;xoaCG8!0;5m1jZw$-t0s`?%(CqYB;>Ve*=__n!WIsM#K5&9{ z&BMA9Se%|?Jh3>9a*OXpX|Ik=^wlkCGV{yBN_?k0hyJ0vc$QG5I2Ik!mwz!w7;HaUL4Ty-ltd; zrS9Q3>0J63R{Ht|+=)Uv+NOQ2q-{){X9%@F)En%$$n+Dg9QY01?`Z;NEuP$0RFGK& z#zr2BW}*V39TuE8QfTCC1szeQgF?b30Y)$*X_(cNchJEi6ZTXFaXXUopwX98H!Y@e zE0}RhU>Og&v5uU7XivOa>Dr`%6&LEwvAvc_?)$TZ+phtD+uw4X{Tl z*qz_*D$S_u{PNKki?~VXUX(%L8I36UK96ZDlFV z$YCXRqr&-@KFw+EWH#(E2&$^&_YxTeBIL6qi+{}yX?rAE;4Uh98)AlLbJxFO`1S_U zlF2#wKok)=vo^k#ZR>TPn2S3|7y!Xqzm9B;B$srB%6t{oA%$b>0qb;NPg?sg*$gI- zOb_{7j|MlQbi(`~+`Wd#o|L~XtS@wG9gBwdX(_V==lMyJlA3&8a{7Ps`=jH@Nqnq; zQiBajp!wooPITvVB~?UyHNe+i%>Oy#RcI9Syen zG5WV2#+k2LIiVUzI>8NXe(b+If8_H7?^+)r3Tn?UjiFuiQ{v>4xPo^5xPywuurkQC z1$u)*RDb%Pi?m;S^p0F70(8jE7dj~&t&^9WbWzJOm(4BgcD;0Yj^T*|MQy ziwpV2^ra|wJBIe2hb;>6eL4$+#c9}&{Pn^l^b@!SP3+=+BXa8bBLJG-s)r}^RTW!6 zd8%T0p66d{R9wkNju*Ic5F8P%SLYeEWVN?R?8w!Od>ntSY;y}{i)v&v{PA-ft^SUb zng|@@UCd`=@N;987T&O7n{?UL;fRpN-l#4v8_(xEQpPIsqyuvw#wZTmQ?;nVRN#+p zlG-e9bwckvrnp z6ke$-L_@?7&7()1V7$A>k+KGALNPE-`c5}so4H{flPnASs#{$;AU-OuS5_(rC0sw0 zCc7PYM~}6&i(fF|jGluthVZ4?tS6`pSb`32bMF+3FJP-&vT;0zi)Xg9ATqD_bCy{6jyLm&6YIq z9)Y5RkQp9}Yyk4&P@lCgMgG$93|Fw=k)&^jwhq;qxmp1VlF?5ew%B)e#%9*t$~TJ6 zsCDRA_xI=r$68Ft*7OiU)*(CYh~?j(eXr4^c+LscsN1Y|snEeZrwG-k$Do6c3F7;X z3QdeUA>M5xZ<033rgFJ3(oF&B1TDrz4e|twmAlmHA82a)-m`^O;$ZeGK1|3+&|#1zEj;x0oPLxc~40)n!zKwj+sdm+3@(x))zq35*gA7JoO{SPo$U%mF#|L`;m z%@Ed((_TR^gH;O@-ro`;5McK23eACzN9-G=>>C^%jT@e-x&aIG{~4(Vq{H`L6UZ}_ ztqIZ{ZTE9HfRz}4N?=*_<@rq)H0^#ua zQ!-JlfktT(oc#MI9_>L%9KC&@^g$Rw0*Q%*wEJ~}n&|dl%M;;J2@OJAL%E5WfUOGw zc`?PKVqO133~W$h9ojMhSd6u;t(slb0Y zYW8}y4*QKD&Ukq|Kb6k$kW6E7Cpzh=ybU5Tkm>xznkpWuhu)StrSq@XvT&-OQf81PoXFCQQxBq}f@3=A-^ zZ{FCJm_>cp&p~x`D@4%nZ)!~D(q5V8_b5;s06i4%-flgcA=F7Au+0y72X`(JA=Dkj zC!plRKJ7;^^&e#bAb{M>_*`lHVt)NOv(?Ea>H%mHrC&fx*aSep)x*yHu(N~w zXzIe(WhVhjFMh04_c_9C<3o6eu%_XCrUqYL5wDN(kB&fF7Tp4a@P6t}5bbWQcZuW` z>o}$c&sXsw_J>Db1bK!M19XtwkrBbz0hN8>`0ws|VpLFOFV^d?;2}U9*Vi098sUxN zl7T<~A|u+XK7rnGxV__mfjuZppn_2$fBq@_i&a2>WH^vV3_!S-oG2H`e|2T#i_rhp zzHbKO9x<9QpncQ752=p-ld!H&|28-22lo{8wu48QpZ^<_s7sfh*nyH$6c%6{hitjE zWoXCrqF-3|mUO8f6Ueu{jja8XnGjC>N&nL`?B6e7fV8r}2S-M*|H)HuSfQ7?k?C!X zcLjLRQnzUs7m6mzGTjg9E#&cvy`NI%w(iu5oIl-&N>N&T0A9kAP)8Lw;rGn1%%BNz zAR7*VZ#TX!*e5LIM=;>w#Y!10x_wxKAF!w9X?k5TqcW?q6o24M80ZGstnEqNa`Uvw zjJyWb0XD@1gUeXD6&mWFx;B$3-N=;O>Wgn}{|MpZL8> zmAV|ZGEgaK9tF8u0tfBE!D}%QW@HT>)9k@90Cq|a>!q$>QN`i>1h_r;-BdEd;{;e1 zG*2|HX%y+e8h=-#1fsqaAua^XV|VlISWOQ}QP=rXMhdWz5<-N*to!5sdA%BS=h!J}PZGcp5M)H>vS#oH!)&Yrq*rqkK zl}Dc)pcyCT1NkKg><9L|bNo)FD2dQ0vKgZTCa9lOBEPDPWB+B$NH(ZN&MNxrHBdkf zUr=$5Tav_Lt#9T0E5Itl=E84kGS0AEZO!zrg>KFGJJ>hZdbz3Ko0-In2?gL$!^5vx z@p^`6EwYVdtZPo-?zHjYs`11=WTYX6xg>t=@j7Dhyg?1v?=CL}2lrj7igzXaVj282j_voeejNcy6G{Z2VeQ1Z~ zHJi1c^M~e>iafAT@N5SbH4UInsSyKL5%!g2IGTmD?#+2-VBr)y7(YopRO%%8q8gdCX8_=V*^Pyyrw6 ze?_2kbPDRM5pLJm1L7K&;3{+z^4jkTf4-?R9`rlm@_cc|jDXS#tZ}u+m6|9{79Td9 z?2f?{dqQGp&R}+dpQB|xhj^Op&2)LjoSao6?hd+PbmlfCy={Q$jK)_XIcb=W)(g_I zjJkkvJsP=!L_cyAioM!MWTip44I5(bVn{gM{0cz>eWh2iZG_Hp`c-$bh>lq)Pu0Qc z07M5G)XQ6jEG8$OS01NPUiF5>O)ZBK_q8y3gfpAn?^Pw2G4H+QBsNR6rDx}a8r5vg zN=Y+8ZE`-En13^tYUa~=Qd(hdVE6BnHi(QrSorW0>_xLUFU6}1TU;lk!QHnQW8{LC zp!^`5$#;t;(rn7$^l{)UMo+CcVwanRKq@^vrt|x@T9?RjZR|b+jr!*4cO=ZD$&S)B z%C28}D7iTsH}4V(nkY0}47pM^7$4^5wUegN*VB-Cy|@4!n%lir^Ay1+UESJN9540{ z=@Af7%ET3*Vidm#9Qn7W0IjKMV@!If`@v4D3{OxYt6`R4YcbpstX}EwW$-r<4#*s) zk;O1GLhLyNhT2_Oy6dSwgFB&`3{2gIQfoZ?^+ad^CS8C4?%!_Zw~x1gVtO-QH$9hosP)AwaWxd;6*j!pK~+d9Sx#tdmxk1PbLUa z9qZAKRIXOw$+^2%DY0oH8oVif#0!sJp)^uvyf;kio;4Iobp88?bE&t(qIH7&68LD^ zEw*N(bVY3@SIWTc00hx=#ywIxC%Ib{uAx$6qV+{79pm&E9tMye^^@6}r( z^1o<~_xBRH%bo|&4~J9MVTmZ-Vz(-GU+wLsEn9l7o3{jya!8=5-CS^SMptD@I)(-k5ugi+0$%f|zK3wq4Aeyz3hFix{2#Yo=Y|y{d*1*M z`zvtzbpapd`~4UgE=nsY?H)|BIo)!g^$=#7#4Ie-()XSa z=DT@@oe&Py7i?)>S5)NT_iVc;I0P`4H0kwi-jBbhWTDUOxE%<-zCGe^O+J7rVZUIO zW47bXgU;tH$O6AI`_@O}BlRH9kA2}QYEVt3vSTK#*um2R=%DK)=ZZTqrc<6Ek!DyU z!qWmb0$GNpJ6d^dgRjqv8!q39b|mm8d!77cY7x{)GqV;3*Pui< z=z72M9V|e?3ib+5-R5^?3}yi=U-UwWwQQ!&AecYZ&H)JvSm@@j+_T!H(vZ>FcycCaTMkt+*^1YZ{FBFNmV$a`jAH?rUJh{h%K<{?FDU-T3=Ln*=_;%W)wpA0>qGaz9s64 zv_hSTwxgsHkKWwdjeXPAYzTB(@{pYCNHtzH1mi%bR(`_2-u9XHw;s5&mh3ZJr)M!O zp#nYKJX2`O%ELCr-y&J}J3Otg9LM;g*>()@Bxok=_^#qH_ohA7TayYY=j$jk-b0_J z=DaHp`PVZH0`38>_zT;1+&qJgL?y;b!v}5+CgxIA9O!#)_V4N zif1;3peZLI-cs$F6Vh>MPncP;C!x6!N9No80%;SnFCl;>>)HUOCdz!H{ z%Fg7G#zo;Lcy4OLM6_o9XSgH8Gj4I-N{=~@*6#UtV^^__b(7T81Lsc%;p%J_-#>H} zHM6j4deYdeUGCFB0K$X}|M-3EZPppAiONfz<0u~o;#?Wwl-ur!#eX|~DT!U$>NC7O zYTVCIxK)4+%~f2$Z7+p|Yl3QXxEbYY+W?~7JngraePTP9Z3&EwsK})JALH`9Iv;V~ z`Qdid`AJ1ckX~03^~y`WnklSN-@6$8JIBQ#6Ri@ zh&;CWZA}s13gfnNYeiUTqFinVouQ+;G(O-p1{aR%l9T@NiyA30dRt`RH%~3JQHe-d z@_$Vhd^<6}Bg>0Oi+%5Q@@0~(*Ms?Fi$bk8V^wauUUArLj$L_u=X~A+#Rab{(-xYbBA2(b z=nSnmU2-)}LEnArD>qmH7=n%w?bjepimOTRtd#rpQVk_vU1__T++%jRIALdk{yBZ* z|F|k0c@O3y+BaS5by#uAtJ#ge2&^kB|4c4Eg!Q&dnyi4w+5!qH^Rv19$-`sgyVuJ_ zH?v-P^=VDkQ-UA4y9Z9z*GCCRdiFn}*=e$?vbE$=Wj(?4M^ZQI<52!<&~#uGWh{5k zCl)91>D+7}suu5M4em0qL&sNoHKzFpot>_~S3sq*>|s-&%Aq=pg%SvwZlgs^S0(|j zo)1%QoNmcl&#+CMe6;U)14hrG+$}8^TMK43@G)*xCnHc>r9pah^sc07_qnZLYzbOR za{M^mPtE*a%42*y8t?GM(pQE&&joK)GkI+mR#cbW^HW>0jmjzMMEgOnFo@%V zd4^Pm$mC^=W_;Wrw#+FlB^8OPXQN+7%&|}7pK9ip%&pAiW~_^-cE1QU1jPY-Dd+(Y z3L3n2t7_?0psvjGw}W$n5Si-1NHx~?ookqzSp$5zP_RdksF&>79@ST_x!{$)EcdgE z>AL9gdXmyrOI-D@#Ac$@^1sf+a`B|%L#(cj)tEVORL%)0Mt{#T_z@AvFEmSd#dEW?Wt?&fK7lgp~M}q|kkBbf0M=KjSYY0o< z)YQJap%sp6H1G(^c{N`-=)1i&(w~N|Uzi{-c%$s@ux^0XPartPlob6ufhC|msku82 zBPe4R4wx#lt191i`c5_PO3=5XUus}r5jN7!Orl1aIn5s(K zV$!|v^u=T}Jp-)?&>)^Ozr3qi>6dCPVX06TqidJa;>u3sQR6z+@YhGQWn_8yq`eXb z<*yesKZ&Tr?3_P&EZ_+cM1M=+WIv*&`kpxrXEn~SBNgRT6mB@y+(g63wo4H4AFwz{ zaBa)yji$sN{7z8tcHtRmsU4LUWxNS;6q-rq#T~sj%#HYLH=7|_v0po1SV2| zjW4=>Qp=dz`YwFQYT5PGELw|H-{XyKx4Qk^ndL`rZ=Be2l4jq z3$3)!z<1Uku;{ax-hH+X3*;6h)#2?g-O^|ThZIOJ_6!a0&D1wPpd&bN+IM-Kf&puy2WoKDrKJ;SosD(Fm=`6awY(eZmGU+FLJJm zD(eeiEN}XHc9cAiRX8+kMmnn==U9mR%!G)vk$n*+DC|P|`7Z4db1=F}syPx@jn72D znMa+6&ta)bfrOG8;l^h4BI@{|V>x!4sn8TfB$6xF>a?RCw||i-Q4-$6i6<1SZ|W~c zBr7(Ty*0P;8*Ly}VzEqDT7sXoHzU0JtfpcW`QjMVRs~|GMj0))rhhm*y%XhYuvZ*p z6L({jyc@9xE%4;JD0>{v$&c=bZp2|~{rJ9bO*Dd0?v|S6-}<>iRft?ZQ|(s%A+L9R zzAFiO_40_`2Y;qlIzQ>A<<-xMPg7dSe6qYTzjT$+Mk=+g=AyFT1~Eo#DyB(|M+LNq zTch9);CTIHzM}tFr*C!$nn$zv76wL+V^n@_K;@kHxf(6PH|`kj?fXubDcU7XAlbI9PtyTl%f5*Q0z(DFy+v&<4ShEd8%J?TsqWT(1bsxuUN?oVaZTrf69k_2ZSi8pf z{g*Vj4D$Z{oz{%2De=i%BN1x%{_CZ-f`rwj9I~# zte!_B0i+C4p9FsLH6@bwb-c8kdzDVXK9|ky|3)jRtzK*Xnx8xQOkW zjekor#XWSc4X`2q456e3IgFT{ggf*JXvpwOiP#L4!4m&;tJE+sX5oDrBYwAzQTvN< zt=seIl*b%eem~oJK&_|Fp!8}JmYdJZi;I)QNe6q9`@%%&CKTCC7gz6(_qb#Qp(CoF zmEtmZ^Q3Ra;zZIWOL+FSk2ER>9wlp-SNU2_x(;oyq0Cnxw~W}4MVXL52=1d)521K^uAg) zU$xKLg|Ol34C?FclS_FNKF}f9-Je)C%l%;*Lj17aH~%i{8s|!n2$j%gK ztMrr7xB$KiC4$Bvn#++4xS#WRh*V!bTHQP9L2wBl{95HXQ9O`1b*gf}A}DC7Z+|EO zoAm51{Bh$-;ON9;{p%p>JK&5aW`89;6Swp{?x^Z3qn|Y5tkS*LG8YlpGq0HNT`|zQ z*2lfL0apF(VFpyf#KO*IA6aTqoPvmC1r8$=INlsXCoZ>tip<;(A5&o8(B3Gk}GZNOCMJtcFajrz^q}WRGYF|#l7er=kAr=aDP2=H(ZH5 zCE~9C$fuHW4UKVYRw#nk);yUjl9xwPzgl>njKA}tXT&h%f|1Z&mr{m0;Mi~ZaGDw~ zkt?6uNSoAgiC8+v6_r-##ePiikm{ly{TF)a#_Y`KudTQQieVL*HGF!i&Zp{%U+x|W z$LHQvoaT3|^aZUG&pjG^sefFATAbu3IhVfKpP>`+Z8C|?B0!91yicvJIH1DK{5!Jm zs$x%*^2pqX7S8)OI_%cUkKPK)lOML+*VrbrTe5TM%bVk(mOn)2&?*}~o$8T@VJ68J z7>zb`KA)KMd+##5G}f}haf0|oZ*G_sM>`8MPmw}~67$5`y9WmCT7Tp3rZ&8zncjT$ zid;c$eIMg8D9}>fmpihEE&iMMrEhr74Ol~+>iF5hM}f<#e!r!y%kLVwiOcNv`7m;8 z>3Z_HV-f72xm}H)EmTpWC)~R#vFo;AXB)-K2vB3v`=4=;MoB9jITZ_~DpaYN%S z*fqS5U^m5?qe>i#Uyzgi@-N6PiwgI{gNWF2;pJb6+9T2%lp+t(bY3-UUBy#ba2Oi> zpp_!>!cNS(!_hq-o5uB~crOBTsaRPo0zEo|_Wcu@jDK$doNqEmXOI&Cd6k$J zxZWF*o?K)5v!xBxpuy>}w__!?z~yDX^$(n*rPtKhW>^KcK9~}OVqeUKHeMc`+XtLc_C;`cVj9Gd{-kH-v1FbU;bc?P?YFkmY zm^;e0v45T4r7g!i7a;UpcW^Y2k0ro*P-n3#FX(fA?VXw_Vyqh(yqJjrc=QRWgttj= z7f8Bw9(FMPm5Gci*FWR*g@oP)Dn3Kb8%QnVZ588GU!K|MA#(DlqKQeK;v}BW45ANHz=rKX-Ay`SKEPac>+Gp(YxrF%l#T$%fGf`!aUQoGEgny#Y zeSjom7dto4lD6?>NHTXn9u_ED^7iKzk%s8pg}iQvxoIN*X}|Wp1e^T8ZV`WlqVWLE z*`B&(v#MY%cGt7SUS0au;b~B5-y^I417kqKsh6Si6ca}`I3O?}Z(?c+JUj|7Ol59o zbZ9XkF*YzZ3NK7$ZfA68G9WQEFf=v_FHB`_XLM*YATSCqOl59obZ8(kH8?jpARr(h zAPSKo6n_dnJ_>Vma%Ev{3V7PBv}1Ip-PR=>8x=dbQ?XUCjf!pSj_ssk+qP{xsjy<( zww-+SoYUQJkMs4f?)S$v#l3WNT#%`0HeaBO?=bFfnif+S-U1IGJz()PGEj0U{fEYiDg@v@!t*%gJj<%8COh#bs3h;wCmG4hB{Ld1pf_pbG51{Wta(Oy1Vf$?PDHFEx^rGLf#!u*Xo8Git6905)yZchKyGBg1g10C(G4BY?L{tIU3 z0Q?sXXGfro*?%#h1vr?P88{eQnK(NBh53v9&vgE)Pr(1yy@8#bmHWR=+x{!-e{ldh zIht6R(!((^|E+1{^tZMd&<2j-pGA?hF|`FSG5*_c>}>ZxV=g8R{~8eGKRZM9mw$wT zv8|1jJHXh)6plgG*6D9a0OkLk%JlzzBL6o?{NEz*e~Y~TZ{q%^M*rI-{(rsC{|PPT zY-J^DVEuOi{{6rJ{=P7_0BOKKZ_NKM*T5QR<^F%j{?9};lYcY(KY>U(8T=iCppDsI zDH!P)|Lp`iiUHkBjOBq&M&k1$jS)b{#K`y`F=cb0 zk)_Q)LudVW$i&9@KbilP=U==Tl$8{eL?vnd^ELffmi%AUos`|}{u28ieaP4v|1aYo z3?U&~H-IPI4;BC&Gdl->je`lm!OrCUf2j5^7^eTSWel7gfNlV-zb!K|{eP?R|MC5o zrSl&!qBcgh#{X=Il9Pdr@!!SzUygsmM$QfnfA##=UH{wg|Fr+L;wC0;CPr{8i?&AG zfflJ5X->6RIYWO$wEBCQz=wkDN*a_4^L?vrdw!*cZgW=Xzt;rOH%@YWwz)5y+I{Rx zQ6G%-Vp>u3B%563;d_%%^?&7~Y>;=b(;WCS=$0U+ovB57Ud>ByL1?lusvhk8QBc$^ zeupBM>|k+#xq71VC2`63MJIiMxJo|^hhx{Iz05d=LWKG zACD$G29}K50Lv%olsM7JUEkrp!RQn6)rH*|X^*-))Yc2ld}Y!q8h=3&@%^OL8kWb{ zB3>WOz$C3(3g)tc@I@xpv|L!g>)2U3uY(0#^Om;(I&pW7EmAH|`p@`g4Jd65&yt>0 zA|oiKL0=D~loH~)+BNg}SCh>x{E3GPv`ir~b<@Mx&wxHs|6xOv>JH_V%xIPiweX|4HvSGa(aI!+x8 z)fu3cV^-H9kXGUK-=1zND2Eyc)uyq9+>-ERX_kZqUq(k>-+yvYR$coibNrD^+PUom zr-M>o&PP?}VqSUek?wQld`0B}@R28x#<_{r+5>V>iK@oE0yWT5v zM%O$i!=Le}N(-cjUC20BXCHJ%P7Ff!@gHONeWjY13rNZGsxsS$?xbI89 zOruMD?913S%)XtCEvx)dW$G`SUD-OF-iP~C*edi}gXEO4do zf5lf2_WkDWLL~Z`;^F;W!Ic}DD2`k#&kfv#P7G4hW1>bIM{7cY(V$#}`RI)P0WIoc zge#1F(UKj#^+GMiHTud!hOVltKe=I$XnzG--xD?1X+4I5(Z6Cq6xot6N^Hj;hY!KJq5Sg)tZ{3tSM;FFAfdy&zeWS>|N-dt$^JrvUHODVu0A!Qw+o8n!0fUd@ zg(0!&nLibx9J%QhYZ!*-$_1SHmnmE-5u;PlZhu#7CyFW*VXMS(cmnv_beGTsrgPbn z;4a}O4Scu?ypZwR8TyyApGA_Yh>3vtWq>~0;Atnr*N2g!AuMu~sbRGtrVB})gcdNe z5`Rs+*cL|jU5f(#IZwZ*MZ_y5FTrX4aDQw)32DJvbA$H}9-2I&sm!Rj#hI&l9?`G0 zREAs?WKP2b>HJbh#lvi2I}tjoQfnAK?3L%pXYrn7Zyg54nN+KBHKMo`n~|+Po0Jl_ zxArb!i)G6-8cYEQ%o2!jKTPriw$wD3{eL(9RTl8WPM^+5{@C+_)oon?JF0VT<)e*J zu-!@CiRTe`Ab)#ju_DIkJz1|rb>Aq}M+LhcxA-|T_u@Lnn_Mb7)~5Fb@R+j_qT=Y_~3;-Q3^le34#B9Ums`0l7D&} z8bA7lXQ^f`OCt>Pc_aF;pmUCSKi6!J|A#b@BYWF4YHO!9+{j+`1C1g`{&#xGxb*O5 zay4)mlsbft&wU=sb#XV0bMAA6Ac`&M{o66Oy>Ib%5RQ(~bnQU=4O(}-VG0Zg^iXcl zXFZ<)vv$R9q!;51Y1N=y@Uy6-0)N=07#aUuT)4i2!Q~otF`pc#RFgDg33vL&lYCUI zm}^YA;uou{#=$vc*DiRv0$S%3YBX_KHuI-Jg1+I5a8-8&ARoz5TF_8ZnDJi`D5t?WyYf&5WcJ{qIBkyxRl3d)Tkj1Z)_W$Eger-fL|j`c-WORyPm zs}4iQ#kVql^KSa%%CiCgQ;+XU(gBO*+jt#VQ%`pk2VA%GM$St(qJM{CRoH}@^$4B( zc-gZ6fhBE=~3A^}ZP0`mKt zys6QkX8i`yZu#m_5XOuN)g@B|m01BEyg8$KsE^v>5|mm0R{I9f?@Q@QA-Eg1v|oF^ zx9!bk^6N>QJ5qHFC4Yi8{L{8aKIMoTh;nU_c{V`I0pIENIn>baWGkLLy6SvY7Qp2ju=7QQ+_J3UPs^Sb3#u11!ejr_+ zI&LGu(E<1P=Hd~+ZdKNh4`#H+<&sSIDBxv4KjfkHGc`E&pBwq4UdpJ5^#YpA$TDxPT5q{W6u5Zu)@J2 zy{J|`3p~QdWZw?!4u{A?v038_cXk*@Rd@c{<*_*k2kR7*dY`Ub8N$aAf4^XVqiXEZ zLJ6#WIF90(OE0pnSX*8b+C%*q9g7+ta5kY;|c^i zI2`|~L`bR)A08a0Wq~Kl0S){tg)3qrs+D&S37?On$W`8OmWWuK$36Uhb~j=$9=pwa z!HpoY$&@aM+GkT{kT?TgkDQ#wiz2>|i%{W=B-rAf(ow0@dbXT4>CgGyX4`P1OPDHT zgw0A1%zsGQ)6uZ^GDy!X12TJIVM8HgT9*&RR^6W{!g>q(WB%|^+GL~>-B3EFdrclz zb(4E=n4%#rfUiJTvn&>a%&a_zZRea4?up1eCz07rj;yDhgEmT2W5-%CW+H^w9Rx(? zaZRN!-Z?W*kxcW=XQ$wgvbYr9pGH!87JKL~=6~%OdJpU$$CGUwU`uq)ACpL$a;GSy z2G;8|IGIm+CZRGxj)y{~)#A4aywyaS)pNqS-De;-X%ahkh()z;*%o*SRIPTNm%YDA zxT7=0owI4FCElhz>R~a_V(OXCAx+0WpbAPpS zYe9nDo+^Eh5>h25<6Vp$gP>1OdPS6TRuN0t0P5M!ITbe)g_bfjj0FycZYEoi*c0B} z_BnO+Rn>LqvJ$lj_{mo#5B8fRl;pkJOI&^l$fs}|gL}XYl8>-AN|hkYjHoJLD_a22 z3oErurXPlM-+I5zLI*yFwt!?1B!8qps>G&lZSR8w#Mp=I8m4Qa_^5P%1>~>LM6?03 zwj6gxJPVO&s$y;1XrPHyH3k3FeMDj0uixUWDo}U%bB9Nk34!k~hG<4?G90a$1h~3m zdDkgyk>FW?p%U7JvTIjb&wp zidvehG|W#^^p12rb*nYowxP1j;D49s>B-Zm^;sC*@VF`*)*Gn$cv@y37iHk4!tXT4 zy9+>X{BGSU+(`VYP zBYKs+vqrymd1a=*yeTNT*nf4ty5gB=0lnIB;&T0)Kp1~?nOgz^88LZG&4$N{$X9BN zYdLd}+9(*AO7Bx=11pJfw5a?r*96u%G2!G)uxJZGrH?@BwLaE-Wh49~bb5y$9K&;R zYRlP<=;|sgs9% zy)n3vw$_IGnEeA^aeC*5zFz?MHED^^)l&;@&<0m#a0;E0_C4%qo5)u|@_jd`Uq}UK z_lQ5U9$K`XrLQ|SEq_}S^lDi`BhntxY!kCV2gMor;dp^?p1*wKk+9XjxlUB>9Ew-% zrp90}c7wF%T6$$3xOd!BE?pzh)}r!6$roVn?Y^k*=AmWIs~75c4{K^@`r7$1DcT~E zIVY&lVQyr17BQEi5$yo8bV(we9T6f2?u7bnxth}bzz>r4>3_R(Ny=$?_SE5O=g^L6 z+?*xSG0qV5F9<80-s#S$-}i|6^{uJ=oEGNL`t1nA_aprrebNrcQmo=f`;$o$f`q_O4}O zyr2V0F+GZu(0_#nKVHrF$#k_z``&)DOWNd3aGF(sA=*TvYvPeLwGcSVPn2&MTv(cC zsX?9&sreM235G`(ky2VUo>}ECXy&OicDDHg!W^0nbk@(%vBQ@yg6)QS4`_?p5whxG zA$PsSuUAuha&hd^K<2U-eqG1OUCxtga5nGTk&1Y4k$>fl$zqKs$u!(Wm4x;U0gpz| zC^v1lS72blHMaVCNTB>2R;e0;nm_|WbuFmDU*kSUI6F!co1>7S_g2o8lh3b)xzeh$ zWGQnW<5m4+F+L#ogl^Q~FZvnz51eIhsLT5mv|pnH8~iTeuqt~b?Dm>GRB zTlHspfza;HSK;LGe@ew!8+E=xa@_azi`MxVV{tHY$iG%#Wd>Yu=R~H#_0Xde!^Cc? zZ=?Hr&%kfWMUF#9w|?$0dnh1kDvw+$!D)oR?0*pZ29)BLwR6WmDye1-e<NmFZgZJB5sM!tWSY;z}h? zbzR+WqEvvqXs>*PBU_Yanrujw{Q*frZ32XOl2%}_S%3A- zd~4X4u`cSxly_AVKW>Oy!++Y{xL+E?*-TJ)=x(gceSQM{y<-A^@KpNIz8oO#fu}^f zndYznE<8uVDPPK!*8+QywM&z%)N7gF`L5i7V?Z~z>LE8I!+VA{2VRq=6I>{p8UqvA z&q^DhecgSfo9WDz>wZ!%2d8JFQh(Be)$uBul^S^YqfVZxN))YzE3bYN#-%&B^U$!_ zBid$r4Q}AP#Clrj?lnT5n{HNBl-tde@e3h6kP(0AcKEDA&w0|NT(9G34qfNfv6)d5 z8W*Va`=ZQ9g+y=oo7zrlcxC}M>dS;8PnK%@P9unH^UaCd?BsZXvRqb^1)qMP|P|eKC?WG0?)H1HMWwHQ@VaC>w zZ&-~?W9anxc{And)dVKUgP4~48#VsppuIqKJ3>HNcEdUJsTJdQ!NoHiwPk*t~^ zDDT6I*HdS+S(|!+gw8psM#i$11HgxF_f^1Ra_=ieD-c55El?=EjIPdH z5#e75-!8T0an%6js+ZK}3b1m!*PB!B8s;b~DIW4i^lek~*B zg*Na!j^0K+s2n+Rdt57{QL{^MJ>SOe>BdPF^r;^hgrUC%!`AwqqwxL5d$J*wX;bZVC4cITKXKmcV|_iX(TYk)RsrtH*9Tm zD{eB0f>vnL@~b{=NR5-wE@;SRYAhY1=SW<~4k*_4X)@7RvAN$3i$hqkKouO`L{zN} zE&-TpIF`(wqCkX*?({WmS`~da8ebDqs+uDR^~;U zhH5dwHLu}94Yf{fOPqMe06jzKEg;9;#~nfJJTTgrA}Sv(DPI6AK#O)D1-zRhT6wAg zadRbb%0&sQg3vmYW;K!=m|~jvxL+nx!sUPTAcf)OQ!2~U!yLhL4hTM7;ITJDj!Mh% zRc5-g=6?&k`7(p3FMfu2-B>8G=54Em!oMb#;Ijk~<|<8@Tktd|O;8){ zey!Hd-FZ`><~Mr&6h5RPSlGwP?83GNZTYPA9wy0#a4EavhL~7Iy+39%Sl-&*q)4E$ zY-CrRL{!T~9dAq&^=SUQz|$>>Hv;b?K=CR0Q zSu%y2TZ?BeL>%l=VW#5Sg;D02>vyZ)M0y+L7JIviJ!(*ZSDMI|I|VL4PFh)PiN6%2 z`hV17EJkb{YA_K)MivE%1IQORt#PRNgkCY(@sxt56dHfRCNGY>%^pH_dZA~tcD2$K zA$E&g|J!8VoR43I!;EQI8CFvMYA0tju}I?OOEY9ArR<)7;a)@h>;#iSJz+i8VGgJc z(_l3O5sl1Ju$d3{NcT~UH$m%3{B)A#9e;6EP?}vSn09Lrta?Mm7Mu*-?a}JbCZYMB zsf7XlhA;E=xq}3-`k0BIJ?*90X|R`yQ!5(*;YgD($P5zJt{57;FS>^>SnbMc!3*#t zYrlPrd9oODW*iH%cD>sMhbO&&S`ZgfEwDIrFW{|0R4;h>81P__9!+Prbj=766Ms$m zf;?QW?W)jgg52lCtnOYR_GSptiT3to(!-gbh1!xa1R*8MdZ;s~+qI7@JYJ4MD@bv* zls_>ehHQ!n+3hm#k98WiaHdL9%EKNGQH?=y3pw6YLqp`jl{A&mtP0stA~XaYWdy{; zx_%^VUsT{+VS=;s`l7h9q?ij7E`Qa4VNEdmCr!mOJc2I9kv&s3*004N>7t|3z>O-< zOo=$9^@Au$v`T^l74V((I2}y(nkbYX6 z52<-D;=X$c;-28R2Vs|+zwIqKsTI7_vAdS<10^mbnA#4~`T|2y(y*jer+>3@&efu} z`6e$8bfA9Wz>vm(PjBddRVvwVWp#4-S zDj@v|3u;>)PA|)T^QoEms6@}?&R&8)4VlJ`%jh39w^QNyuCA z;%qldMsUuu-B)9UIen#hJO+nfAJ#&{i!V#ak?&}lm*c)gsa(TEGBqWBJHxlIS|dhI zySqV1bL`;pnc*oIm@x8!Gk>-KUSkkNfzi*9OP;6siRvS!y>&d7>wka#d^|rQ_s(ZI zcC6ISpaD?ysD+0=+kCTCjOtc-@~|{g__KYAsFArc(PZA3#i$R3cfNS2pMxxj2>Z0d z7Q%&91z4zhhdyK)n)nkCm_6w-;d#gmUS4Of7| z>Usi5Qi33=j(mNKdZKge+Gs=>&Me{AZNTi|LY;MJ6!JKK-+yd{$q`f+Xb9s=b3ImU zLOFn*E;>DK(s_(4P7bC7ogEX@`=H}{4tn;cX3;e6uOljnk=pTwAs~m*A73G_ey%Dp zF@G;04EU*Mb*wrC=vQ%K0qNBOV)LGV?B{uN&(_-{KbFUWXdhC)aQn7F%26@MpQcSo z)qAl)pC5sE}*6A*0(}m9=eWh1k2D43nXUx9h#soE{SKnRS<0>c?XBVCB(wym;-MYo>>3^ClS=6m-+x=-d-3d*Zs zb1I_nCj70Wb!xjrWFnVqs2?gSbsXONSizrZbc48W5 z{k~-Kk$=iWN{bv}u~lg}$2r=F(I=MA37e+d(qPtz#4wL`)AiLOi2!8W@t=hz2t`#?h4Djb z`6zHLY9yEs`jc2yp-@A2{};{bNr1f}+frvYqkkP#5uLX45j%#QW|ii--ZwCsH?gbO zzz9h#8 zQ0i|@S_97ZW6_l)-%xX}@=hpy?l)Q=96_MCpGaEn`K=W@*9-Tf3);9BF)KyvaMg=b zihp=4SeE_JX;O{+5#f2D3*n3r;5nHXNMvL{fkF#|3TUD_PIq?b2^(&Uu<>+IN9ibB zRfac)r1TeUDrI|PZgR0Xt6Cg|%bv^Chg-gETk|>*DA!yPMWPTKpJIQ485$E7gQ4%W z2P!Q+DFa-cg(94sAZGU?Z2DH|CzDG{=wvHv^Uko(n^c7z-32Zx> zytIymwMk?>I3_$DF`gydkNWXnGFZJ}6)h--X`|myC>%bhmQywjtxl9sVWey7>D`^K zZ3w$&1~)1T&5hG1&>U|&ZEY;kyS_G%`err}oAOZ}lUyP%0N^jeBX6fOQtQXJN`Fw2 z5B8icBU)R;g;#DvanT1bfny5IckrZdxnZk9cX3 zR~AXiM_(s@HK~#f_s!qGl5vPvoM5B8j%BeH;-mx8i1u{{te|RlbyJuhd5B=z@@A`f z#pXU~xZ`a?cN(bpH+5TZ)LYZsymSO#3P?pKJINpHw&i- zvO$J(H26%bnXt#+4V|Wxv*NL%DttI7&+2SFVAHA-q5AHB?%SRqyAuqvuh^PhcvbF#n~r6fp+P2q9^Q||dcj6=qXDZTiX=PbKV@o%Xs2@P#= zr1gG<^b||N%pm|_2!DoPXAG!Q&JWoR%=dyt-bT)&$VO&pjE3N`(8tB$`jh45qSpT;-*iWNPx$CKnd>-CEG9nSLG^EtrPW2W|NVWdy`$AD3o z`_peqDwr`Qy?>;z_`-}MjYGt@y%i!vo^DuE$uXn-?cYlvXs-`%Mu2;@-^mE4*_O)B*in`%# zsN7ec7kP3{NhM|R7yY}_{#>F-M6BV0zckmQH^L;YoMeO+Ik#TkP4$W365f&o%ec@} z3aT+C&1h<7-q55DX8xg`QLI=Dw>YUNhef?ru-*;+GJw_Vb z`+v_P7*hv4=!h6+4U;fkNR|*w*uurF28eRm;3;;gY?+GTX`Z&Qd9g!mm;V)|h8xZ?ab01jwLq+Dw0P7^!Xc8q0NZKIV&PNihDk8+zjwoZF z<--F@$dhV%?oz&lV@T`72~0Q)htV!_`Z zU=eL4dT6m6^dV=q`GGulTX*_9b}o=G-BLauRC}$vtGM-wIl9E9Fmd4oqo(>&=YPiy z0#Y>mi*qM^>u#1=P#lf`hu*w+@)R}x;79H}{MHlllI~JooS&%*nRe*ckODSwmB1H1 zi>fs_1Dl3e?1;75DxHdBZVAUh)~_SI@9FBU_#HcKO_S%WI%ZEzZ%HN5*XKX{B1X43 zKrjxUdAqH(fw;Mqe!qgAj4orpHh+t$jf-2QZ1m&!n7UevWK8a9Q9c-YGQjMpDlLP@ z-FW$ban`6lycyGmEK5?!(N|)x&kUmp)eg!%fJ}9H>-Dkzz>M;8b0dJf8Cbo-DcRc$ zpOE2f<@@zXZF4(2vmFabgTL2k_Ex@RG;zZq{DU@P7Y%9Naw*a7R&kc0Cx49Ae)HH` zyW|;*gNEi|SK3bbiNX|7#lMBYZ_P1IDiXQ5(GSGmm*SJy_*zjady0u0{ZrmwIp7+l zLCa0^zII+ui+9s1oq-*q=A?AEXrw~gr#Dj&0t}AXfXaeQ+?L9kBKN%9T`vW+U{iwR zHp9fN9Yso^?Ae}k!aMsN&3}oe2Z34LqEG8OU~0yxL(jNNDSuG}g<<`M@F&V`>VC-HlIxsGAw`r6UVkQVg?aNwnhQ`) z7m8PivR`mzT=~IiE4_D@iHK*|jp(1}Q${T6TIv^ZK7qrg9z+g7f%6VsQBXPoy=Yq@ zS3AHr*IDw`7?F2-f9*Y-$}UvbjfkZ`#dJ`hoa~1#MXs=a65YyfH4Wf2ylKni-2*wH zm;Eg%s=!$9vIjX>Pk(?M0vF{!jJb!83(`l`j_?Rh1BPu64MSBhUi;FmRFp+K^k-Yx zW7AgQmE^SD0y~Rg!L4d5S`okq7{A!PClX`)Z=9GDG=AZ&$q)MkelZ80X6cn?GEk|+ zwhwE4vOlQ9n0z&LGEp_)Fq-&1^wQ6cb3&-|3r244KH|M;S%04+Rhw*U!m0$gED(h%s&T;>HidPh>W6|zVW0W#bs?a}#889N)= z032JAx~Eo8vXW zKlKE9LBQiFJJ{2wR!=N=SJF}SkSNtCJb^*RmI~F%D1Vay`Bu4tK+>GsS!J`zP%@uj z&?L<}LXkz_iEvGA6QG@E+6UqLd$CR72ZIGh3a0zHM_2B^Oyrdq2okCJUpU@T=6$cM~npxB2{w2&mN6_{@vg(ZvWuu-&?)JNh6oFYB<3@f&-u2LZT;r z&_5r7)PJ~T+9ymK8>%>=+DAJY9tH?~1FV%wl@J_l6pW1Dj&^fp5!55(Q0&tXEm@Xh z*KF|VBCvB+XDmD1X;`-MWw`w5i3dmprnuUez=Z0wv=AWp4-NO@*Fdih4uHlHmvIUg zk0CX#ic<;5z2B#r!!B%=oi_=Y*;YzXS@9^H0DppVeR>N`6fbkC!HJEI!-_5hao)PJ z-{%L2ac&td(1P?_Gq(RJVmqyp>ifKnHPZSJg6#<{CO~`t4efh@p{-`X9 z59!c_tNOC{U_Sb-6h@Gq`21&O=?3*<)_=5zFq`QVyMW^D3aAz7MSP-67kCqFL>ygmE*ZJZ;eSZV z1+7huJ>wj*&w8Q4eKh?+bBR2Q&zDH8=*jrkA=)|D%jLuah|}?>W8BX=whaMx(KGTK z>sZYavqwQ%^t0L^iC)M+y26c|Y+O76Uf{peA~7Qs2e!TXznbObLZRU8WwE9E!tl?)0c#m~`fJItS~ zjff4L!ag;uNyT?Q=svv6wnSv?k}^d`IryWJOUu5P`)V;f0lTqyX_sQHaDR4k6Rn^5 zoH&-kHMio+a6*%fEJ^uE1P8=5IcMpgs!y4L#|W0B8=jG6jbGq7N0Z<3yTlE2TPnp@ z;3=YT0TVb=0ab11q_uaA`2G=u0Z!!M>R;#%0^tX~G8zmy+1L#;xBHp80l7Id3x`l{SaPl}5U+=c~b%5Rj7S1U>y~t|?46=JkpDdGt zADCZ_0#27P9Bg>`@9*tKLaG?wq9y~NtXLRj*yMKx(W9FAJS1=kI znloS_W;L|qJK*?j0x>2yr^*l(7TU^!0Q0FRB+fM|N&5uruJSnyStTpNYSrFnBgD^2;;eHX;2g)6AX%H#+Q$oi7AQJH zW63G0pLX-z!heTD*>hVg2&7P^bjF6DS1#b}tl5p;7rFQ?9)>a*~Ac z&5;7d-exJj``9`gg7b9UW0Rm;5FqF-v&*(^+cvsv+veM48(p@#Y}>YNcG;dgGcgmp z5xeIXoG%BFnNMcr*c?Yujl&ppa5>S^_wXd4Bb^aQI_S_zzR6?IijYUue-0DV;0!5F z$a7PpN6?D~-J_qMEdzt*Elc_FkcRs)ZoRDi!>sN^EKG_nF4a9E`QOWOX?2j=a>feI zw=%%7nii6iJv&k^#cXUI{R>){g9mpQCP()?u?wzc!EVSTo2tz!H2$|5DQ|2J=6M3j zI)}mxIFf2-!eZzW7kBHGcB3B#S4XWalqW)jsFv%27O%$HTalG;L%Jkb^BV>${3WV` ztTKa&<_y9A}O zEJ(_R;HvTRiQALmk*(P+Jp?l`?AJhK^Ck(ZnIt-!P&r6TvtJSpgoD$NlYY5v&IdH+ z%lCa2K+`7?&k{!&h`n|t`N-*_sUK?*ng+8>dO!!~YuWDP(;A>--H9R z6?UR&R~e7d?ULlhC(8w=H5p(Oq+gC^k&;3Kl?&~*7EC!pcA!(Ey|TaFOyFH+G>rN5 zlD;U8C5&K5E#$zAZ5l<4oFFgrdy`A@c}hCo*q-5%EFQI|eIKE!-Dm82ZHuBUKov^h z45=NZ1wMHGzB?;|ATEL7@jZs9%n1StQo26R_a}O1wOVT`g`4O2VDF`J89K)#i$`HI zC`o>K65x1L`a{@hD1%)Mt-gWD$+X7n@xClFVfyb=4LX>F#$n)l0at_u8xHP?Zt#NC zeCehFwVvK=J>$ob5j@S#lav4=?9D3Xs(!4AA#-sXxl??!LTtteLrgzR`7i*Nl0fE^ zDcE(1Iwp{6PZM>=d*5$C)uu1nx2Izvugfic_l~^r%r1V4KcT~nQES?+Re0#}`}*K$ zPo4!&i+USL9HO-=9sH^(f`BrpLQF*(PoOp<(iAH5>O2gQ`#@IAA!Jp1cmV!2xt}%E z6sEZt3ynEQ8!?YVL1W{PnhIc>Bp3RvITn1>G^8%=2mH&_StgzIFccBeRd)%R-32e) z?A7C)3h z1!FGW6&i$C*Mk&Ja11I ze@i-FvX>OufpJ-FZ3A$8ra!T)LmCvt|>RtRVY~fN; zJnhI5Yb6vz8b1-gHAegg;%@2ZcG@PnFIj9>7)L~*h_N~S`S-`9si%kEDB%Vdc%`~3 zIz3A6J`@;glEVB2qAnRPw{n9zLjT z%$qAZi3TH88eGS5P2{EcI0*My=19nBq8x;GZf1}-p%K1RSCoD`!teP*W-n8c9Rz2T zzl3t0f?Ly5=!d>$h0E5YuB@xJ0{C#*GTH1en)aAV`uf1uo?XrR9I@~rUf#h%TE0UI zmy7@mCWYWcKfrKoP}Rp!flj51evo(lQ$`Wj-UseJrv4YLx6Y`)FtPVq zyKH(Ny7#hEOq>4MS6z_FPKp&&VRqj?lWBZ*A8WKHU{iwhsF$L!sdsd(&zjKs!MwAK9T4f36~Zmum>6L?uq{9woAml%oRP+_#=hJjvBDZ`3yiEROwNil@kRoTQX_t~LgJ>o9+ z1q)8I5EP6>On`wmypH<=vH}!NkVqkg*Qyq@t_K6cpaMo6HBV)Clt$M|=Y55DId#jl zy6!2zHozEOaIwI|MpX3Nz1f~ZZ~kx;C9k2v-}w+>Qc2D7g0lAdT<#dri;O#<0j{6? zP#Vz(7cgjnFuehe^)uW5H}X5d7PJQA%G-He^O2~QxtM+oZ`c9FjbX)Z_$A9+6qA2` zhpglT+xu-?<#MZMwzLtxBATPVi{7bND%D=j05BtzZkvQ%huv;B`@7<;(8K;xMEZfJ z!GC5?o1bMe);2V0@W5%unB4Sj$-7jt*01FjFXHi5INCD!4vGif1-GgbhcU_}vvU7p zCJJJvtBm!f;h>&F>ZhVN!UOWHca!tG*d1fcAn#G-;kC+9;TXPZo_U1>o>S`E>QLBq z6ks!oFF!TsYTG6bB8BDR^?p2=(4wV_zCPNs2!k!=_vZ~gqU_S5(sVU0Lto{p+*_bl-V@yG<*_A|k_} zD~Jri$Vg*CenyRvb=zJ$Qg27(n32OFobCIQ~O)!}?K6sG?~= z74RkfO+-%mrRz7;XeCF^O$s?_MaMzD(D9$7mx$AHNSn~BU~J7&n0~v|7Va~s10pO_ zQZ_O}pHjWxtr=)g29nZHUOT3=cfen?m!62^k4~j9IXwJ4r4&2eO(ZaQj`AN%!k}T= zTxS+IboZNs{z0&}$Xs{{J({;xto?gGZ2avB!sq)7cUWOF+$>Bby$Y{Y@h($y5V11X`8#w2rI{+9=J%$2xbE|Rl@3>EU zpI`I3Vsm*jZo%fU8HH52*2Y3-2&qNTwGun_L6&nx`>y)e6YJ?xRumVx1OTsEdEw(pS{G4)s zm4#~@YFXU!QLUPm%WRi~WS@3FvRT1okkji)W(po*mCNFj9Yg6I41bY&vyew;=As+U zl|&Q$zgg86^lT&&WJSjfbb#g%WwiVzNjs(6uRR}+M1IuyXqM9d`c&9w#^6~N(luIH z9EQHGqWadsp`}2-*)OKU;m158bDd{zka}(g9sP12(NZEAx|`~NUHy&Cdj{tnSn5Z{ z-?9!FEM(sE!e7VVzO^!c*}<-he=R-6NsQ{T34V#x%CLM^)mj5BPz|VJOcG%B+oVNp z5@j6H)`BZD#WV%;lEJGb-y#Tj{@*~FH~T{B+MBhwSaZnmv82ekg_*THPQ6MHRykZ$+wk!&zGTM zjG@z-xd^|nh?l}_^(BZykBO3k< zZcXOAd^k2l9(PvrFwW;osR8A}}V~y12 zN(U*T>${AmfR0vv#GduqCW@R)&Oq%)%mJMQqi(4iQ2n_K3VV4IX z1Zs(3XaZJycXvmk3_6&d)un4!S=sjkN1okI+uJ+zyZ!?elW3^2$xp!$I=d> zM_yM_1K2F`$A8A1M;RX){C8Er4_RCvA|YKZaSe5893j%GBA9qc9#B2`OAs1+^Cynu z9}u`Md8E)%aJ8<^5Ubzszz-%5=f>LCQg);T13G1-UbG+1kQo~v@?hQ>VA^t3u+lLSa}HkrGp}L50tVj0J)>zKT*D0p#LN8*WZFp z->QY*mnh%g|I4=@nLE^&p5Odm->&cj;y>RW-Szk4n|5=tZ+QFSJN_m&V7(Ve`uOfm zfXMv94=pQPG7#2G)BLh)1d(3z1f~CF+k3nW{E$_B?@4<5qqi{k-!XPLfc~gB?Fof3 zG&M7NMa&ItifPL}5G*|TXn{Mmyv;rQj(lJ|pB#5q$vDq=_?DqPnsj0~cq~j<3=)m~-^Zyd=%ilb-8G(9sd?0UtjyYiT zsd4aq@N7Ui@clc%mCd96#X@7TuOt=&Sh)bOznn5V+Sat@4!u;G%o>uoXe)g3Gn)Aqh-2zh%;BwBz zykzVDz({%UkSFzKjiY4KnJaMOS)my;WdBVmc$anto%vyyy4yu<{O z{jjVCNtdW&Mwj*sV#S#}VDsg@Q> z=aXeUreZDzBr%U7Ou%lX>Mlgt_B)aXp5OTkTt`{`+T#OTUq-LsN-6?~$WkC!6Qkbh zrQ}h96Jyf@Eo-E}1@NS*MFT&)ADjaGC1e4KVfVi`GC`-%V5_UFtybZ1{p~!L_ubrf z-pcl6XHag}6klGJe;)vBMa~OF9P4iBW81&4UF6xQrlmtZ?J|^mWugnB`0mO`vDHIQ zrmo;b2ZtNUGE4sDF!CD;%dOn7N_JoT-7v_dE|ar7vy>fC3@~=S$QijtGGGN?fJ)Oq zU9HDlEeMu=diAcpdl}>;zD_{VkSVeSo#r85tFSGGL^Vy_?Y}ntE(_kw7hoMBY{AlZ zO@?D%47g&Er;D!1Hn;`nPmH0e$Noxl!5}lac3D7dg^K7YLD6eyZtkGPekg=9pnOIk z@D_y&aZrPe1(pOBPy{sScXa47-{^0v6~IUS*6mYbk^|0QHRJuPVJs6L2uT6OO<`9P z!D~dM9}nL9{4h&g;J%8}rmy&atg3|XRK-ZSn?N@w9(>0V5+k}Z_*&YqH%M)nlM=CP z`_`{CX1gmRB71({V! zVof9|W1mB3X1*4lx}{8qjTF}$sIdFDvj_O-thHb4J-^I+1~#HhSJ_1@gqb}*Iz3dS znAS_Rfw!>ojPtv-19tS~+=Knj-X#}2Sd@cP*$6KO@HK`hBc5k-5+v(nT9Mo4vK8d* z#1!KZ22|acOUaVG#E-e5sXKXOX^Z8(8R_pQjP0o;czXv+?2&^^cS*>w$LcP0DxDw2 zZ3YqOrIIjq3rC>%5owe~)QG8m8!qiC;731b{uOh#JsCMDMPrcSIh;Z@IW8QZ9TMyV zIH?FeOto~&B46ov1k)c-Nyihk8;rBG9Yam!cF7GY;ss?tSV0>z@-a_>TP$|A@9@CZJ>YAW_r;??|53r^(&w$&vwoX^U&m8-b!n zQpBuveI{O_%HD9An;f+m-xPZvrH34js&UB@^s$Wa9V-ljRv+3moxmZ?L-X>0$Ix%z__znOL)$5(%?nnksjM?!W}O6T*WDt!LuA44 z9Qv&MG!zHWy4CR;Oh+ygj8e-hS;(*TXiJXttL$XwvfIM4d`g&$>BKrh2$^ser;jr@ z{Sq|Hi|?ax5t2BzGkdI^JW?{J$CXtE5wopb5&ZPFS#V*=W8!B(1M~+5#Z78slbG@o zpz6l|+x2CZ#pDN6GQgH%C&?$s8Ce^xB52H#-Jr=G z&35#5B`%_8@Zkfm(vh=;KoU!oN& zvj23$eO70&Fe{ER=xD8XO@;_cwCUQ-UdP(M1R&DRlJJzA;{R-+A^2ALPFvl#KW)}$IJUTN1nvA3vK?sDu@3Yf_^w9pg z35zrPSrf%4`!fLjnwI|BPd`HvwCI;>kp#=@hZknHf%1yN{j#G&8Gckw(e)|2jU3_$ zVVt6lVgS`8_)?bJh!B~4h1BM=%3Vlf;-$+m5GCktANO*uUZ}$g7s@M!ZEFt0ffOJ) z5+}o)OXVA$=TV1*$k(1H>p7pn^DVc8^VH4U^Oy3tatfGd_oZ~VcRknRyt%IOJ>ba5 zM9DKz7)ndwcH6qE^yFR}TU5i_a+y<NX z#35L}zYMss%VL#V`^(@nko)KtU!Ph>@>*0rXw^D(Wbd3H!$P1jOIb;96P3)`?%r_! zJ*F-Z;(Qd5K*QG=gGbNVKbqA;VQ}-pbaykklqzUJ5wybulQ(zhAa8IkVxMPac!amhV-t zv++)T)5Pb&(2n17@pl<0devPJow@aj6;IsNKlVI>> zE0MVPdYQ(mbMrLF@XtZNXV_MoXV*}8!oWgk71=K|q5f0C_;wA^O*<^gclb{KC~)r# zemcM@pt+vJUVAfRf3j25&CXh}s+tgxIs(Lxy*Hh@Hf6Iu6SE2oV45ckt#IBYyu3L? z%jeS=PajqPz9?ob!72Q^?i~Fjv2hHJg^|Q5p@{DlOgW%JpAWOvdWe2RDpjP(vD-=@ zA*yF;0l`6?%V>P}vysRvL%L;lru{K4RM%tl`xqCk=NoAT)2sZd==#|H&EQ}GPz2J! ze&QW=OQ-6B^Nvzhh>gQKkvg^&Bcv?lUxg8)(b|ahIF}cwvB1CqGS&r4*@O;60U3C& zyG`)ueO6|ApceaUPjzFs9+TS?6I`uwWtjUp>>_!0!mx?!G+n&gRNvFuE%igdW~QtK z^>4tk5?Uefe**NCBqZlPSQe`x06$IzVLXgpwp6blH#B(oQB`65mg-X0`sS4kFLQy& z6;jpdDo6ig+0;&`Lzg?5xjTw>n|ZHl2{JuC4$RA_%f7s7o=}tpf6DAei1QB|U7O24 zx1`EoyN`lC|L!BSmRMwZd5)BGs~yD#qn6ZSygG%F(NtO)PF4chkCTKOfOTn`(uk-u zH?s1Sl8v|cm&UzbY@twdBWOJ1bvmJYR*}Pio`PiVymRS9;!hF;t2lH<41YE4>lvZj zxDxf0J!R9?_&PVu1G?+{_WBGrZfVt6|LIpqr3m}Wn?f~x>4`hdX$?_>FSeE0AW1I` z^qj~&G>Qn_Os7*QY=jp#00lu(ES4LbnT3YN4C$HDh7?vr&)QO*^qo(5`|(p=rMFX{ zbrRJwOy!@m_S`c8O2@M6srudnWtFr@6}OQpr(d+c1=3G@uWjW z{vC`wDNTp@oiQYt!SudgLtw=C9Jmhk#j{WyoS!5aC80M^gHYJqIOX?Af{Lw!RK z-(t~2!79BYWWLyg|Eq9G!GmciV)~dO5?Agiw~J5jE&EvcNJ0?oo<0gXUbC^Goi$0lwN2jh=Xiw`Cc#~7SzGQ)^0&*o1;0RAcmSzqNAW$EwfxMv z6}B_9y*lm^C!#t>_1AaQ_-^zH_e|gw@9rO(P)h1k$d+T=eP6s*)WoD(ccDkBHW`ou z!!G(H>Pfvvz-lSOCOilpx)roXLuuhgAP+U!j+mHPc>ZqT56O8I60~JG>U&*J#(Q%q zgKq?3ZI-0j=5f3Hu;W*UFSb|A^#k3Lz4K0sWE&eVUUG&FFDcd!X*-EbxG_^~+~{`y zA%hF!iO1ZRsX;;86N!K}3R8~xP)aws=H(T5C2qnWfcwIklgIZHmf`W%%*~gabs z-3QmC0di&k@27Qyp9)^M4YUUD-r6$bQi!xKY_i`LRQ=XSp&B$1G$J?RW%84%n{VUK z_%p`)@O}1RZY*5WJi>(!uhX?yqH&0F7<5tuQ5FQQUcpC8*MFz*O^3Lb=)%bONa|BJ zIU@W`MORqv`Ccc?4!O-;{oO8RO$Z~@dvN)X0Nx>-l?!WXT|+kVP~GNvQu7UYkI7P! zDg<1+&$7W~;^v=6Fv!tw;LKq=C~xU(k#9)1$UIBAJbfBSh}-2pxfT$lz$(dSk4KV?R@ArQ+rnB_r7uYR^G z0J@%FvFHIgVNJfJ>$&=e; zNb_B97y||qk^C3_cG@*6SmJN`gn|DCR6zPNQg;s(>Tw)WcKerMO|kAL85&JTIT6Ab zn6tBQ1^qnryPg}bW=jNZBzKuns zZhZ1%yB3H`4>b;RFzd(l=%x+USw5?di9P6nWM*iLFxIJqM~oeXzven^qDNf{SCL&C z`IbgPxi+8Wp1R_5W8?$8qkFI@@8s7>g?CW1nt=_c1@A$sN2ndd0l4J+gf*2nKn3}a zC*JE2bJd{6>oFW%s^L?tY)qv#ovd8mpoGbVVioH9NLw~-jU!@G2P zZI?WO>0bUe^Ts%LY$2fASp)?_0Dtatcc_zCa-gAyqJNs01WN1pqR>p6tD}ivCIoZIkHAb5a6z+Z*M)baE(3$bgCAWVVXYqc z7k}T;{tQA&biGHL(h z->H-RVV6^~S^Z=6I~Dm400M9jw-=w=fZg0?Bv?}@_7{RqnJvoHVI<-|Jumr6rx1}T zOKzYew5vX55%y>3!Pl#23w(#p?^%rxemGKyZ9=;2+-N=f!>*nZBVGTpf{Fm4jWA>H z-KAfyL1DjCQ*uCwPNI1ZT$LST7cgS}>hfQs-fasoz9$!rmf_t4^lgfo!bjL1I$m)$ zu$q*{z2-V`H(#RJ#<(QB*IRU}*0?rsDty{tV7vX3_;E=#UY)`EcTN z_*^JSjyIj#&wmw_XQq*eEgs_MJd?lYQ^Q~VDZA&L-y4s7bFdn!3yC=pvkIzqBSbv*J2K}ImM6)P&tk!D(KeA!-Fr8Kt8nV7Q%!ge_8S`C#JXYP$4gBz9_ z)Y10WkF`1iY$y4*QgZX<%7>3RXDzUSm<+Wr1e9AjFZE~s_pA05#?so*`bTKxwf7(% zlLt$pL?j&#oG%4Q6$NQzR$ZiL&})cwGS!)q_SMn$vj!9Poz zlc(foIRjS!a;sCcPE3hMcO4H??0ljNVZ*{N3m~KhdSdIhmri!HPYsVdgig~q-a+=3 zAUbp6os-B@M8cn{Q}^2%D0Es-Gg>2vke7S&jGTxNp4cx-(?XmQhp}$hjfcwb!;bJusV8tHS2uf_lkz|eiD*EIrPJY-9-)j`D@Ob*=DBYd6iHa zTtwIzq+rQMYjqUVjEeNuMr^t@3@|3C9Y&Jlvf(+lB3RIdvay)HcVAO^v%Om91`{&$ zaGe)~&^Ne)gf9!xsU05^`~(kM0|siD$|BM?qVr@_H|}2fPq6(29z(m$U_ZTKl-(g6 z)hY#mHThfxokeE??|LXQt==_K_24Ui0^M6kxd}fpX+Mp4 zzHP5ZZ6Dp%=X?1Wj{lJrJ54F$UREj$Ub9Lk5ULW7nN&beKe)*%EB+D>}*T(nm7kZ~6rWV;!FMUE2@B%H%#Kw+jlG zut;{6Z9^%c@Q!!%M9I0fou8&1JAR2USOlynm~;#ZAm~LI$GW25r{;jl=u1amyBt=k zGFGyqX39rA;J&rZpASUyRg4IQC3Sp;HYaS>{i@$NKW0OEqA?1 zlaH)}drp1OJP+#=Xh8~q;E4u(Jh~2^it0x0Hh*VL2~i>pJiY>VeaNL}u-Ab1L!yKSK#{54YQdFO*+3WmC7@fR-7#XlYUG$Hf!+HB1&fS5Pd= zX)MbGqxY~Hp?pSnaK-oZRw#O#d^6MfV*NLm39+V&{c_a&2!*&Bfxs53c|sh=koD&N zJ*`{V@?+`nC`G3nAZ0IZR=kFs|Ph5kO9oyd|J6VcJLWIN@*N zGQ6HkO>F(6nG$l<{nCJrlB0(rB1an`FU=u=J-he<~sfI>=U;Q!fv2l5TgDY_G-Oc-+`GkWdHEXn% zB~=Xq!r9v%=?T{~WJL9}gJ8v|c|PtPpQ2Qp{%N`%GbC`tUKK*THhYpoKbtoB#(&T6 z_Z(q@l>Lh=+wqI6`iNl3W<~Ne`tzUHByRR+*fsjh+R)D(XmE4nOi!Y8@~#!V^dR#~oz{PT~xdOgn&*J8Yw!^(5Yo|$VI7jB*Cz9*kJUy81t*Kg>o|hju zGYqn)c}mz@hSujLo`!O7L=X|`N zI-8lzQ6F{V$8ie1kgM4r7Zxg~E8+VV=O6%oip2t?|1p&B7*m@hf+X=F@%526!^TZK zb_9Sf_!ZW$>53~rNtxrngcnFthk_(AuY6qCN=W!3hw4g)kGoI@cGE&HdG=|j^AKpP z=;zW;v&*yo>*~#oodJECw2oFrqLWTjvRg&vkRADp5$X6`Xh|yg{vxj&V|LCU{41m? z!LA=bHYxe}o`4w9O6>h`Q^TNj*O}r*Z<}bi3vG>}5J;7eZG>?|{P8hO!nUn%gWU9Z zeWRbWxvGU&!AvWl3LYq67OI31LLRYgEatBO8J#GTi%8f$eN$KEn2l$xuQQh=mz?~f!~ebk3Mdx;~ybUa3g(&=rb3|W6M1z)8D(4S`cK_rRk zqIvDa0-I#^U&{*`ZNgMfsmEG>fk_)cm|!St!x;InNj%w`laoIx``BDb=d|@r$-S26 z=r~g@Oq_RCqHtfiTg#NbAGIJJYgu=JmLI=h8sB>c%{pWYh>7|eX& zww;r*l$uQ=;g@>?>=4f)#oSEgVSL)4mz_;?5uSgsHF{m^U{SpP!@h=o6lEuneK==} z2C6uj`n$Wao<|dE(Z^T3K@MX`xiqmDg(BZ#jjf8qv6QRO*1oBVXm*Y*msMRGFOKDB z6nBmBVexh%QwO|&A@47-%LT@_El!<{DYHmmS3u8roRJlBQm2BQ?{u({9a=-QDFV6b{bJ!(YW&*qSR)W7s{`+ z|CDXd-G3BoislVVJ`S!rk+q|5xiwsi0OOWfzq|#ok?(#Nphl;t1?a4nm!g%|#l0T- z_9|wolbZ`l-=q48Rg(D0~2tCbKYu17^NUylPnx&D< zsX?sX8ZZyE z=FVq+4>k19?by-MP`@vE#=v9+DqC0tk zHvnF#VAxvTi2!J~bcEI=NtS5ZSxZI?_Ac(pey~u_I{F^S_XpDK{B|+4*wWZf**JYR zB3cqhoPrB9On+V}Y*h;-c-8BanUz!Ji(bb1C=&o_GN<-ad2BgaT#YnAjkYJM}jo5B)$KR zHWS-RE@f$8gaF2(IBu2F+|RG(WUS=_>rJ6|zF(9ubG zbq@yr!{?YKG~X`VM#nos*b2q0wrefk3w75hLGszpW(CG{FUC;aq(y#I_J2Y)dj5|? zJ!6a2Du-^ifu1V{bLK-URf64#_Scoaw1T}nK+ zc5|j{FSk(s%QH*dSTPq`MPvO$Ajh$p7AMW`Ul6baisMCgz&Lz)EQOwdJAZlGPto9c>4h5x%-dbMIZqluXllFGHYPC%`NIX}ak=)cdvID+OnJ0D1P zHrmOwqruGk4*464YfF8d(H#f~W7Oa%Axf0OsP}&j$;jfp7RAUB1QReWNN{fFX4*Ha zhXH`cjNl(pBwB{q`|&NP`ny^O0dzU}p9;SdN$3g616m6B=S5Qv7?3nqD8I?JP^RuC zTC*geii35%irzL)Q+Q1?ck7} zaXU-%WV$0a`c=B72FS`3V%GJtPp!5sWTQm^F?dCuR z7yAHYE)Y(I$#PHgP*k$q%F)*vo<=$X8Gy#mp1U@^o2o$A9(dr8*pU&O7*s*awc@q8 z{xO&?{XDN%sP>opqbV$tjnwI;1+GK1UDywMh-GgCm$RU?L6U#P?>9?~N-@PfMgi)( zsB<iQ<0$uAX(KV6M_m0z?R9ak6dKy~Jjh zJp)@=&{Hb$y-=hJ5mmI0S4V(9A>y%v^C2ZMVNBl)Aax9LZ3XQjMx~wDpZ?t)2O3`Z zv5@kmf!nIrWf}0FCN}%{#ZS6shT?7MqnL=UwliLB5|x29;(vnZ>VJ_Hyp+lfxRZin zJ$HO8d)^dnfP6tNtnf;ZB)fN*kj~%4{jl_J?ER}M!z*GXqcb0~nmh#%HpkEeRhwsI z{q~!@UQA*KS*1v>@)W&^pC=DgYMyFs*y>z!oK&bCcxKtZ6%a(Z<-~^_XSp|I^XoTQ zsK6`|Am}SR(8HEG^g+YcB#9Fh| zT<}O&5By^88m01M&x7h1D8()b%y*{L{X+(9f#%rWQj$@mt^F9r@Z}GBZ9@Od4$m#- zLifJjhH4x2cCrD6$eMyGK5Y1HE@C2ttl)?BJjTzOy5!m_k6^G-q^k7JW}5eT6+SKe z{njWpDg{NhkDyPSac&>&Rv2m#=tT*i&q+ZNTDK$3{G;V$K|S1#9zsGP*~>BFT%~b0 z%aDO!c zRAEjsr4b<7QGD+7AEx!Vleo92Wh>$O5xMAERg~TO^i_@mvp18kdNnC1KP(c%mqE7g zUb=@$^d&`uKI|NX^2Wb3Q-{!=xMfD>TNS+eI?AaDHx0ql;4!4fgN$U_gP;eX?OjTp zzn>}o(ppeaHa#HjMNY@&x1HKbzG@gnb4=oA27ugJ&N-jRxBK49J`3aK47^^dr61Bm z#wRJBc#4ybeaknp4-0!7w(GxX)cJl)P}oWt&-Zi&x1}&X3_6NSp&opEHNRz&{}X4g zahZ`I?h8Ka#a^d3uI2F8lbP()OJR8uXQaqxWo;gE@0G^8w%uB~qa76ElU$N1IQc@1 z;{gV?eqnP$5ks-WV#pY?3F^qORd|`9B`=45#d%=)Z zt#p5yvM|#Hsk3Uw=uXX@Z>Rj*InJLjws!HYA$i_it2DIk1Xkm3735!rpkG;wY=BFV z0DcKHS1MUU@h7{;M;DYESc2Z9w5`Jfn7z+Q>c>onhc%|=5(SrGN6=Pjc%Z~C4a~^~ zq8$iGx5G#<;;*#NO?X$`b~KhLC1Y2-nNkoW=*F|`6P%e4Lr+r_YHHm zd#zl|nNv>LI$fX8QJN&6JI#q-@xI0^qproO2mpz-pt4oY?jSUTI=nJ*LBR84@aMd1 zOb6Ql(ufOXg;}vfKp@%g`uK_KRVwN0DD$w@;EufLG}`zV?#C>LW1>&PYYY5i$#-go zKR{`PMUvPoZorH!j9`lvpeKRFYO1XpV~1M`@g49xJYG|%GbxGP0{q`hNAveu6z#br zTuI>VJjj&pcX%oRejxz;_+C`Ql^#kHOb+}X{`SGs=}f?08) zros&tIHNxTtTGES>T;a+@BX@s3N=s6JGQvxtyYr3lvu(-nRA*eT-UO2Ru)7Z6t&N` zfk~1mlEx9So^+hO04vuu>!SUdSt{t(G=40J89KbDyGHPWwMIUm(_q^iYo5yXN4inj zgzazO1_i_eZg;w4DqItX#_$XwLH8!yM0fYKVrQcm*|pI_0u7IYOO`#uvy>4Jr#Fn` z%3=t12DM$b)gm{bJQ#{O5mtKFM1l}p;k{w`CX1Ci1bLePARm6Jn)f#B;D8bD3#I%; z4en#MG1hk&g(4fc*ypM`3G*}7znR(zLOEc#IO_DWxN6nGvQ|~y(h5saQG9?f&9%hf z;4uG>1hmqDbla;e_O$ZCfj#Dq7LOSAJmhPRq6|QvVB60inmL@>{=m?kt)(7_`vO4cR6G`-#7{^ zb7@oe?tL(i>O-Beu-BGO2ZErB>?yuAsGJ4EPk$D3m9d<7$;qHB8@2V+t7mK}7Uk^@ zG_U0paQLuwuAD8Dohv-nbQvild)Ez?j^(B}`9_O9wAj;9GVv;_sAdQ&ofmA;vumeJ zp}r6IgE^nyCfcL04iPavPd-!mg!7NUa)2#dv{K;lAz7 z+2zPJPFAlQpo}OYMo=7?*gFoSBHrn3Glf-?yF4v>VC?D*j4wbAG&ULo!>e9aBCOy7o28?kxMEO zLbQ|tE9dciS2jZ#dPTAxwnV4>@ZSZ1#1YgYuivGmTo?5MICP1!jvliOE|rXo=juoI z^aHPcj#28bOWrL)gt5Z!sLsNtJ(veWJBHPC#Njg z8IS6IJ*K?NAUS+noKRhIRqN5LSl!ALj1!JvQwPew$JhlX^Xr&Hb4_UBXHy0Q?XNrN zVM@KG^VuS#Y<-@p+hDM;sH$TC_rZ#RYh-$=rq9nikAncFbb-e*+bO}W%p?QDa{Fz2 zOd3uXfu>uA_Tu5iTsORmT^pIa-;zcB#n3YuX9lr097g9w7gIW0mqCB$+LHcO3%R)e zG;UPU+_bAlT(VE0TcKJpeXGSL`VGlz`7`uZxJuOJJyZT5yEj<{dlaV*SUH{2g>Fqy z*$Y4)T>NL2rP#hKn4Xd3+<(%M4?LgjfGWp2FxIlFNFPvd@97w3Svo5Z(MZWa7Urg6 z=CDT(Jy;BT>h-drEt4PU;vyBQ;JEiO)OUET-4FlP=N2K!NX;wqUa*o zh13?O-_by$iyFxB&Td)UE;yO715 z`8Y7>sXATLGOf9Sj6qo~_iZGId6>0{jcV5_)>h}oK|@F-l)1rb1+|Ox{AROWiiAm{ z{t4rn)F=(tI6iuEM2-!LRl6)H)17=E9>(7WE3AgV<5x1pJXx@q9q5dh!6)3{9Hcr@9IfahUX&NPB1s*eHULX%k@ zY$4NXWT+ZvL{#}F^`rL=Z)$G@mM>^@2Nm_f`j*OEkJ>{mndu9z8;2ZQx+Vv@s`+M^qIOcBASU6+0G)oRZr;jb8bqSp5naMyKexK=_a+NkBjw&7iUap(P4udjUCK zV^z30>zld_UNEK#3N}?gXT3uUx)~2Xs(SbHcwF%iP=H!liyrTUqku`05~O4z(07Ge ziKJPE<`C|-pdbgM_|(1{7Cf|qRnB~Z`JN#R3q6@e4Xa15Z+li$o&{NvCU0Zssw{XQ z3|3nWpt(nSk}N}+r)U4OP|V-9(eWrnzxg5SXVz8h>{Mue!YFD}UiXv80O*v$N1&a76RC~5Bd`4U?x<$|Wh z^VLxkPZ&ADI3GhCnc48SzHndmtL(g!%Ts-NlIR-&53LT)$+X#XQ02cLRJgN^CHy-| zyEmjB9)y9@4E`o)1F zMn`2V+UGM|YJerJhSkVV4BVdY&mI?!6Yx&SyQnA;f0pa0p6??y#!VkcBL$Yb#u-A~ z{bCKydiU;coup_ohRsI15^?VBOGZgQZIbE6V){h|0)o_~mA@Q)xO=-f#Tz4iW8f<; zAy-4C5Ua#ew$`uiDvEcyLfK#Natf7BNB54je&1$uvpMv$8ILdAb_I%D8RsX0=7Fy@ z3C$Wx7Qc4lBQOEK^l340Tl4r|3fnIs?aW&`mME=qJ?HoDEQ3pnT8)B zCU_@Ex;Z@LI9)QAb7I^%vefd=P$Vq*YvasQA~B2EV%L60l&rdD3XN3ZiiyP> z@xC(}jK*4z5MqeqeQcrF1-?0S46xOU`S+Dem-V;g;3nnjj`N`ac!etI7>z3y?^3(D zl;wgbvmV?Iauz-UfpE!I4L~c^x-$)rM#S8}fJxBwqa%kDp+yVA*1?$*@%;XiD~);b zX$-EVDq!BK9U`f*EM^lZnl4Kmipc?-AH01tmCFB;?fC! zLMGe>M`bHj6zL55J-@UWHm-j@`1bx)^>{UX!RBKwu0 zn4z`_rq=YR6v<&Pij>0@+!@&<$=N3_YDq1$7nM;N+v*R34UQR1)i@;~yUnxMzB{eD z`~fn!&||X-rHH4^BqMOBD`X<<_;WzmoXvVj(kP3Vt5bGq58>5Lkqh>Wswe& zxLvQG-<(wO+fYz|mpa5Dr-O9l=#pi_FEYAy|KL7V;kdfao>57f%r=2)Ou5DaT+7f# zbjGQC+Nq9evSd*&{~;4Js+mUe{fU&~77K<IMvu$w8`6C` zrnOo)ESA}KI~?M*n--^41_BiOn6;*!iHa)ETjz-;dHfU;qAR1-pAT4y>*uEN-9oHXtHIpfb=Knqhz`l{(TFfX|2v!5jbyS(I;W8q)Z zWahwK<(;pA*4mDJiHAXIS zgIfzDYeMPW-51|$yX|FdIqpSnD`Gbp1)*FzUa^#iX8&QDCSO?}8zgl!(FfCS{c=J&nw5e>fd-EPBtdd{8zPtTpH|Y` zhzOUsk&BC&`Y7YXj)NC;KZ4W!J@vnEfk!ckvi)cMieLHKeG#NeN4cPvDZ1TG4eRhz zrNLr|q#RIw_j}WV5^t$bjJysAJfypMuZ=T~ufm&)Ed+`C)VUE#Uk4}i{^Bh_0byl2 zhCj(r<}P%qHsLpYHgDzmcYX36BwOlaTqtmn=c$SMo3{`Mv|=+E-t*7X@$2(UJ31GL z6Yyf9PcvI?m%+j2yeXW)CS$gC$R1@jM$@D(4>tDIQ_D6EV6m! z+qpe`SSXu$>!Rs$k=IC}%oz~>loN<(3@y-zRirKL?Xq^R zo$sKN`QqW$kA+QSwf%L=OU~qpMpy5A8ks~jT#3nZdEfX)5>rWaDl8%2yu{3~hy;H@ z=`3Yvv)w#nLrZ8kSRPaw+QA+XBU6ChGq$CcJr+6V3kPH0Ey2tR1`)8bCs>V~%FX~nl!JGL8(|k!XbAAB zBoW`%L`D>nqJj#>d>ZJSxF4#p(%_;ZHMNW)tA9H&RD3%UX;BWK3ZPTg1HgeMkS3Vi zg{X--ka#$7KSg;8#R9{_3npK=wds3VBofk10^n0|HXv6qB>lH1LYJ!*{?xjE{)+_Km9bvjYa%r*om*mezMpvfAk6jA zQ$m=P^zJK;dT!^J@`CPK*EGO&VRZ%m0Ll)g?cW#UP;e~u4h}V(k8Uv^3Ws1#ul$JE z)bz1~-E8_`zJ6Fk`s_b*66X0Q`JePQUo}+v&S*71_3xH9EZYPUIe8 zCfuGkMkC}{*mvjY6}*4@xyc#L)B~EHT$vhM+V8f1e~L=$0Vv*xy+BCgJow$*5*Wre zOkc_A@zKYHC)5>yc=byW_TTiTDzd(-tMpyy%ajEXl1L8_IICL2{Wd+Q zCy*_?-VWJ;)2ay`X?4B%4kY*_jI_wG(+A!29%<|JAeO8U+#pT}gl(Kb}?~{VqjR0tb0LRX+94 z79u&0=r+!~Q0+IXkkm`MP(t>!8~p`9-``xi7p@Vv*z%9EN#&f4ys9UO>O+v2`Rkn8 zAqjb!7J!Rw-{RIlp@W7@_v3Qa%8mPWzX_PZ5p$`uSzS~1+p`%y9R|GibaFk_ui;q+ zVME%hy>_Oq4W9>9?w^_%%}6v|MYNpuE8R1vBrIjO$T1~oPggdjo-l839_!5de6DcE z^?N(CFH!d13CJ=D8G?~L%Z)|VEHPCZHtFwr{=m#wZc21~TAnvdhRjrhr^H!jj>KCZ zWa}MX#SP6oRrmAn2cF~-ll>Y*ti#uY37Mt&Xy?URoyd6S&7T|&2^lKbMf^h~I|H9) z6mb->j%k`0e!(O0;siVXd2rZ-$YJCki`GIFGM(*epO~P9q;oOP#?Ry9{9<{-f zHQ-E84ZANib^IxAqKRt&JV;&PCk; zvsH37kraaz>09`w1lrC9^(CfE>Sc!~)Lo?~W2*~llh`Szen`xc3fB=!Kb!+3vC$K% zShY!z5{er**vfht`s{;aVa@dy3W3EN5-%ZGdw-r#S5qdK;Y$Q@xM_S7K5VJ-G#L-p zxmumJ0qXnqP_-1jYqY$6A}boP9=gSjev{dcBcv7YB@2=K@%+vA)dlfnK48Yx43pVG za7o*WM2k&M!br@lE6^#{zA-h`oMRZS9xi*}VX3MxYa}~)mZe$$mcYPkg(SaD_L8$I z$xT@1HTR!VG&L75b2T!#Rm1-EE!9q}k8V#o`9(J{*eOn;FJHshr^GvIp%=Y?t>K>7 z9@`qll^jGvLK!2a<~0FY0B8-54NDvEaTvd!w;OF=F;fP>Z(mL4iwe(o4J@u8Dl5CO z#oP8tern!`+#x@1%eFD07ShaLB3hX}>x1vrwO9|c*l>$OBFGa7aY#%hMlNh`vAW`n zs~A>5lhrLNeNcFsfAl~|wmI#si6~?qY_QGXJ*fKnv52`Vz5Nv>1FDh$RM%EPb)IVM zhg}(gnL!E6%+#LY0r7uEO(fVc%yYeyRY4KvNj)TC3G}b`X12t0cZiW|^>Bw$PWP3a z+%IKsUw?YK{M88Jr7rWd@VPo@Hqw{+lD)P00x6Qi00Y1{6VpVl{R=0s$n8JQCgB5?xBuFaOjrk;-@nXjD!E@}k|3NZA3%uWj_Y1E z<73NT)vu-qz!B5+o{uo%b}m}FR^=`7mQwF<1{#|V&v~}J5+{ijU6=#x z=wEfXS;AYV;qeFgbdyIhT2TzB$b`~MLnYox1(xNkBtaKrvfsGYRk)&|gIq76_kAUl zIT9#4%cl+DD)dq;L?wb;W(HCOJFp)3zlD&X^p*wD zq*zBBM-6Oi0``VXGHX|82M~Q~Yl`mtvhJOMb`CtYhOlp>vLx!CQ?K%0z)fW!)k>&% zUxKjoRII1%NRH;Ry17{g-YhtP>SJmruMh3(zk{twPieK94PRHmJ{Vo7eF-18^g)vQ zsxAlq7dpe!g2o;E@eZl}cQupl6xFSrY3~)eA$6icfHF)%1VMh>@^Z!b(T@+#PUd)f zNc8{+t|(JIu*vH>oYmtP@BG6iz4{SqRcKP9pP9Dbwe)JNk>J!gG6tg+c&p)Y6uH9+ z7_i@HQQR6Q+_AYl8Mvb+(-R>ZaiUQ@fWEV4|b%mD|UOQ zz@9n!f_AFOr|O$5oXFEi)ad-k;`XQqca`5Waug2~rBS;5U9qKNDGn2VC1}4PzTY(* zD$J=-LA6k%{dN=oyG3aUb9*VXB^+7OHGVA7_|KfGcKmeKJaz}M(oIdAT-M@f{Q0R6 z{+_Rmfb(aSTESy|LPXS|o;z1(-WFRk>MEx2yW4Z-gG11_)or6l7{T<8l=WI9-m@O* zhyF0(2wd|+(*%1{2tpfMB?sPa$76kpAI&Y3Y=c)5=}LzM4>7F%GB)!m0!QI|AB~2o z*1$Ida#gDB4SZQn)m3Iz7IG^h&a0f;zaJMhFyg`EA=*N*qtwqen6TEpXx&_r8%AV@XL} zjufuqGqwXlnFC30|CD}st|XCn_qd+SL7swytX3?lvlU-EGiC|4*$#dqEg0Ir0T*Ln zH81BGOX?ZBs@xO|SP?Jxkh3U?19+N69@t#l7O5&D;7Um=)%U_CA0%*QB|_Gfm{q=5 z_?w=jvc5acPH~TltIcu|LAWoc%8EIAsW5G8bFh)@Ii5B-VV4rY_#+?q2P3M|H9b6{ z|NQax(sRUYoiX*?LW$j_%E;4lcWSaXOYzr*;Uf@k@Y?g~V|nJ6tY6}wIPhi?B7{ED z9i0MCiR>=t2~V8F$=$N*(%P73Rxw#qXva zl~tq4FGc(sU0E1fe@{3#?J#PSv6h#zZunUgbRye#O2e5r5lXG^e?Y^oT}M&7PccVb zD$?bo8E~VHLT9&M@D=nG76|`|A~wnUqX{cu|BRXrU-_-`@sD0GjWS1C_FhEhcP}!I z!`u;)K*uDU3iOKa3*F2v*wqcM&I3U}(Lf)Z=a`4;lZ6bf)EKSsob}CRwDs<9JJKIF z+Fs5#!oJC_{P?XNE5!@3FLqq0^xODy0hkB}ZkuhW;{wymAYs?{!LX@WEHXpS{UDDj=%&aw=1GhRuPDt>4+WplJZ{@#3T=U;Ap}iUBuP+uT$jrAeI1F!)X^EzTh$74TE&=34@U(q;kSn4@M;QmBH1%`t6wxNICgD&&q1 z-LAI+CW4ZsuXt;?pJifX-Bd}a>8>NgQJ?Oj*VNQKTTY*bg53a=#WreO% zzJ=Gm`NA3(3y8}R&csW9cG<0R?zBo*2EMo+Ca8*$h~GxRYR*2imIiKK?e12E-w)K( zoJAtHOy)HH6-u8=+Q(qruw-t=*BU>q;HHt5zQ0+TQe;01{4rtoQ50>^uTg0QITxNN zcv3Mx=;ydDJiBj?$Bf?!E4=2YXr>sOZ|16)7W6>+2v`h@iQufYMd2Qh_INn4$HHtB zWhUy26+*6$z~RJygFRQWQ;>L~+cp(L#Dl+gS2A;@iTIXuLOnN79bU_y#g8iM~ zj!HdWqCwP+w>68wVsRyl@e)mmO+@M8v7#Pd(?)Qg`9M#38g(ydMJW2_)bcHOX}=}o zX!b=s2KX|jgU}w@1g`Sa6xw(zR*x(tEUfy>F!JJq&F86=Y_b`gr$kHpJ8v)<29IHp zk@i}Jm@W8W(MLubU%Vba2&}oHMr0PhPhmcc&Op8^pm| z)@7Coch-SPk5QZMnu<$Kq@ zs{A^=hGp=M4$wZcah0aE@xoXR#6- zjMY|vSKsqzUbyY|I14jop}?Ejx~><}@SI1vW$USsh)?S`cIXUL1OKR`avQVLpO$Cd zv=9+qcKsWO4SpOHU4Kf$3UJqQAdtChyTBctc9#a`S6|m9U7es3Q|;+5u-T1|HW#YP zE74SmQ%Ft+$w>_UIZ=cJujwO?4@`iiKQav}w472j$U-ghb0_ZBUpO+X)_&M95P4H5 zUezG0BxOvmvnCujdk$LV+B@)>7lwwfP^34C#<*YdDv}b~hbv2b*0^dK)03ilXgsKW z;#uRs`t7Y2MQ^tYfHm1S#IG?TXVA^vOaF=T8vn}v-N#kBb9|A?Xf1gGd$1SKQTZE4 zx$Fcv2S;6NL4vQ8*7#=vT0eC;ga}5N7cGtHJ@UD|&BixRYMz3_+>anI+``*YM0wmrp+~a67AN&0`lGl}g_UQ(raAk=R^6kL z%Lh!rLQW<~cKKN9{EMU7X z1HW6t{et0!w-iwYkT=Ubscwb4s$jpMlK;j-bJfFmggl&E)IrB2J}dK$Q+xlL2Nty> z9b7>ch3&Trus6v)>gRXBs;;8E$y~+VHohXkD}>-u7cx0A2!>+FO6$gCsIi!!v*tZt zb(H(k*gX66p{Xjr`3-+qo>S_!EMlZcW+SNi!C4{vkU|l~Pgz_pvs>1FA0yd_YU~EH zN?v~64gO9pb6M4=2Pa}h{K~txIiS5uoOpIgEf4jn$P2%g=;1L5EkrG#LkO7ZZohFQP+2n6@5gSZ~r-kcH_rN9;!w9by2K zUw_!%o^#>zHXH(tQ0;H94z}dnxKe7PtrjpC#D~xH2-JWFP4D%Ff~6snC(LZBC06ay zsGMcA`WU}VytPX{hh)mfy|EaJ@O)xhXLJ8|}Bw4$%BNRP6T$aT~^u6c+D!Ms>^TOP_6xTa>dv613B{b(~*`ELMRsdE96EaNi76Z9fV!i96S^iF{)i%k2|R4Nx;+N;v<)Df^f8??Ap z4B8Vq0S5xMRe93$upB-grn4ro2qj?T;0;xKYkTT`hXUZFhPup!V|@VB85OL^!(DPWdWwvopU{ukh+7U+_l*6^ zh+p9t$2C_v$habKZO_pxw`+#NcDiG zS*Y8RYksABPYM6cW!(^EGX}B_VLImSTQnQ6msYWUsChc$&r(P55{jorT~25nC-}9v zJGIuk`X~j0NRo~JDEy=KOWBYwb3nlMm9*QmXKvvuj^OD@!26vuY5=n^e zoqC_( zN;k#Q(y4Ns$wYB{j1!gNC+xd>&==EUAb`h33^<}QN&SU?>|ktx@iQX+K{L-xgp`Yy z&uL1cq?E2J{0{39FT1wTWH|tswNjvGecl;$oE*D!oP^;D+r*^iM$$hEt(zx=$$qbe zr8@l@EMV~?<51%{$N0c4(AQJe#=`WczQ&=Q8`t-`e%*XbEX9kAlHeHYb9&n{XOEAk z9=xtnbMkD1`rG1Pa_wyJ3bMZmN_h&y6>~rKZB!8Utn?8=(~S{6?6O9I*+qD3Mt?*{x=9mQ7g?9latG|0dMMA+YwAX=WdvhBnUR0PUHN zm{32c0Mcl1^|;7Edro(cu%kr^!^CS7fosU!*}FtXJ9jH3x{|H6NMpHNE~ok6s7q=m zr^$GFZuJ#xRFj8G&4MsM=ND4fP^Pc><$#Gd164^tAM`Q>UP(k6#0YcSn(AO-ZxC$H z3RUKTFdlU#-$7R{0{AxkB*Jq2>wF=+zaAZyCq(DfQZz4$?$gf@((HpjvXF@$iNA1C z(nCTlq8p3S#`F)S0f*YAkk!87ncNoi?Xm_J_SD}As%>1XP!GWX#@-KB>G&_t-9hgn z`umOrH5uk()`=G+2JoTs5XwiMyY@F~qA;JWioGzRE?7_m(jDUB@L9NzP^HXB3uhTQ z8eJQmK2&IreODyeh%FUU!SCOce28lOjK7iEYQ{ATT~+scEN5U5DbP@05D+C)c`2f!ti-5OT;5Y=}5t@bm2aZ`b4{PY!uyoAYGO|pyj08b!9nsUMTzl3u9dl-Fwy@N5iRb zG4llDH%b&q8GSOF1eLiecCSQ8s`oROulBtY?1UeAD9D&m;vIG-{MH!aT=p+IHe|az z<5=5GBipi~Q9(Xyu;y>S#HEyvgxvk9)vsS9 zh7_}EVwW+DNbJaAV&Ti+V;MjkGv>@5yM(RlJbZ3I!Y>o7faRQWw6H*tw!66KL_Zak z7{AtRtKcOb`inS4rs+)S_nYsjKN*(n$PhYLU8IK+y)$u}7MSWhR0@#gxf6I>#~>_R zzE<6_6cG!`KrJ@5DWj;`N~ZmSt)1mS3L)~+^w>p4$D zciMaps31~8v^HfC#!}x1p}v=lw&S}6UK zK7qR}XL*`)QX%VS9A-Heg6Imc1-nj^@s+kJMts|2vg`k?BB4i?^e=98^by}G3#rhdt*lec=1_-VG@7yYs6g_WsBZD+kC|Z6HAqpPfAEBYO!B%=RrRA z0d9M`dU;H3DU%M+5d0p>=iP_T__a|09=ke}<}BhHmN^=zY&GJbEAz^!!N&a~8gUtT zD+#Uwp;UVr94FPU>%AlEh)9qKHX@Zeibp6khGYq1={PZ z*c_4#XPgtoR|UG@pzLBrJ-hW;29u<{F+wac=jchV^d8{IcvHvwlxPEdoGch0>V43B z4ou?m`6Bc~(%7&KhcV}5@wa*dFCR%_D54AGoP;lHVAFW;4sXs+mM#9>znG*jM)Snu zI^A=mN5|vXPXhxJr!e7cS+Om*E3#6VQPerew8f>!LdM4m~rG z)Rl;)LEOOy_J4S{tOs1#hCNa15w}%$8QBpt#$;F_b zg1dbQuLue4Z@vK|#yl1g(7l+cY+qeVw?!;T=&Zf2fgVQ)C)uOQ^4m<>!LsB-=4lzI z(qd|apWU{)(0Gsg<4^lBm;Uf+ z=9eUHep!g*jTwVoDw?&-G2fZ{xe3_emtsAvk`mKFj=()h60se#Y5^Nt1wtd^-?0?* zb>-;JTDOb0=O}uGXf`DPKpeTgQF(Ah9*yGOM`}f;Nu?^QD2*H5y=_wC+t8?no@g`d z2{^_bu#jFX5gNMTin&ik5;u^l@XJG44$a5fuX%*m@(H ze3i7DP^pFtx0`SjKWKNIq^-l9SMSp*0+6)$c%2dL{1M{n>b%qgjZ7IDzdY$o2Zb4M znUkH|>{T=}x?t&s+ra)!YnO$+$|C&!y9`B&I`bsiYGBb4qA3wvh`lqqE$ibC#Jl)i zrTJXladL<%p?fn|Aj3ioGr5iz0qSm_m;?WTV6GBpFSTE`pmFqjdd6@bvA%N-B*4Xg zr=eUmW8&JrWwtsWF-M+LA#O& zdne_Hl?p3!MPiV5fr9?L?(>U`F>XfsbD?gne54{{iAUjVswP{n^a_i3kv>UZM@F&N{MqR6#ifE*1 zP;mEXM?(X0KhDq%uH4`CF`0uj^C5_MWBjM!9)ljk!*Ncb`1rO0@xsK6a3Gk`wP(pY zQ~hsJ>opt5_gf-EInOut{nsEFaiKy#75$AbbCOg(9j$Sl!A&sAWXjrEt9S}_WCl1oYNNN`3-S&Bx@yZEeYhJ?P|#T$HXzG8B@7ERQAU>j`U~% z4Ei4;OA)|#yTh1^+*k;l|B&Qizzk-4Slj;*F|7@MmNODx*+hp@QU(xlK|}Fzvyey3 zTFl$^Cnp?wzTm(46V>nH=bw=W(IX(U9M$V&NfB|!%Ic9wKs-Q*CpAqtUmyU+?kBK3 zbshc@td8C2fGJnRKku#X07;>PBh;)_Uh0#RVT@L*Nw7m6n@g{roy=H_tniIQQY^G8&>t2+2QIi|A z#r@=0o)PnlmbAgCxQ`@1A+Fko3h@yUL07vUc{huu>Ug&a%}}`kYqEm(qU~15ZNUBR z;_n-&jfiY2s|ASvkQ-WXDmR=t9PO?-Z0)lmZN7^GVW?#VQ?z^^Zc^UvUgkwx!ERQ| zQT15r%{JPO^Crn2b}1Gkg5CXNz_=Z`9v{Fq)h5UNWxro4wTX=gTVUC>hXThH6u2pv zitpMRaR}8)l|MRG%H($FK_dj1Zxw>hE+~?96aqc-CjlMCHynG~P*eTRC{|NwK|~j` z*b134Gy6~)Z&JDgU2TiO^S}HfiwqQmHqoYK8NU6K6*ZZPf5-F(7xvMo0AMN(cL?&ZLRjrkr;#jH4*ZEL(9kRzsl)f%fl zrBj{ox;GWrk!U(5?}~iqSRr?87)YLI@2hK-f1sV4;8KU82*=26H@rNp}{1YH>D&XI)$`5FZrRnm!fDgeWuD@yEKXC^k79e;TX!sp8E)4Hej zY>JZGvoS8;_0itg9iI5}$b|4P=?xXm2WqIMstnir{0Y3=E-2Q9bvhnB%Vcn%=6Z&C zzI^g&0AD3THdd0WgoOtql}g|5Ey+miz02N?%trmYDV$?ZkM7Ju+HvK3&>W0P5w%hm zVF28z;md6^RSzaz%cpRtc=(ljS-bpWc`U0vGiq};WoU!g-ib{N>|L@Nh^_IxPosjkkU-Bpbizp)Dd1%iL?#dVdwoRnCgrU-70oHq-q&y zpiG>^EOdQssb&@on41(Ur~TvBpPqLVp*yDv<(hxiOK!`CEq&q5XOU2hXE4z+;d-z;)upB)5-2AjV^UiCL|o52Lk@! zA6z#++o%xWPhA+IYKy#%ZhDnh#dr5ArA|#Irx7l2rt&761Igg>O+uo+j}> z$qmRz`Dq?{VI|hoKfn)DoJ}IPdBZalWxB1CK6N=`V;`a6Qh3d=QH8fHI#qlPY)$&M zTbV7w*fkE3LkCOF6**sjQ)%TPoOuOVC%wvip=AtKO?I#vU&;+P!OzyPn?&LL{&AFS za00(I)bw-pD?^(7x!m11?)hvOHc4^uRUaN|i!@h(8p3ZM^x12ZE(i@vv+{LTU~VAf z{`dRq|KBO(_#g3cw*TVA|Ka1DENuTplm9n-oRf!}^MAv~oBv;@5FUyeWutIr=Ms&; zzr9^W6P0G;3)aTwCgneR{Qu(P|8uBtnCANr2}~FRmDt);s1c-zp1zR@gjm=$Jbqrf z0IR>E0(D;jtMz%LlY`6b#*WVWMpJAN)Zg> zt3$Ac8Ysw;#Xp>8$H&K@@moc>o|Oy0g7F+o6%fvtv=Vu2GI81IMgc8{(V3Wl z)fD3P5SSUkpr|P=#K$K?DanqNgHueNPY^^}frTp!afzV&GRzE2OwC5Z=pz9RU@Px$ zU@YLPsSqIZ$+#Qlq#E)bxE(WF6NvY8lS2zb6HrV9k-qJrK7y0e`x_z{9|QwIq5n)Py|AGw&aHWh=}ckJhlzI(A(Byk%%QN(Lxy>;ETf^ivCYz#CBGJK zB>a~c1B-pxmR5-kn-^yM7zduP538}Qpc)*Zd?$7OPpps&G6jP0!a8!}bLkVo7K$@@y*u_5jKpiv)R-fw-mrl?tzchz<~F;6pL$vsv~X^dtnLZU{_>it32F z*oJ<7!iRi*8^Kux|LkH1)9MjMj!L)y(GQMbne9J<67RET@k~G_^bmEdABx!+E5}#T zffo#)V|^1N@3sK>jPk!ep-CAWRJta_M3mL%)R~?OC%+0iEPhVrs@^XU=MOMQ1ok`N zS(VX`YRLrz*K=c=oSJz8%z@|^yGPh%O6lokBIZ7biIxFqy3bz_HD&1^dN!bZOy1ZN z5Z^l_IT?flv>Qu}odYD!%8J(KR%dsh8&7KICo&}n8W_0MGvy_(ftqI4RvQQPx&kx?3lgxCLsB;Q0H=`|_BoNdMs+c@$V~%KY_r7hNa{*SM zCTe-0U3ekL`mT|E_FN!jCL*JVAKN;!EHT1nJ6on3j`y!P`NqDXf(yEKdV-cW;3+4g z)qRbbWR{mW3I4g~HuU$xI)?T{!(!7-mVg{d#fYq05a-e7n)W!xx3AgT%>0 zE&JlG4IDNixz9gQNc2wQ*yytC6}Vcpzb7KtRqYg$p4#FD$CY@UTMUDCfncZNin0XNCJRJX^%68OzdvxZPR>Xoae7WyaLbBh5$g+&ihvMJm5q#o|G{Bg0 zsEt8dY7ee=j%d=B)aM#-(C8Q+DQT-EDt5lq-;o6cYfP;6(JgKd?osnPD(Rbnd*?p0 zr+_OtP@%_=bP2B@X*A(CYL0w{1Mv5$A|N=Yn<&$Y{eiXeX|uAn`juL*Ve!24Kj=EA z?o7fqjmEZZ+qP|VY}?Ko+w3GAb!^+VZQFJ-y=KjKFl)`6RsDdf2iLu?9a4rRU;t*4 z(Vh~Re?5u#&)d6t@^PJ85wqFmxO)mWa-i`r1I6#2ZL*Vga*1HTaYOvL-9+kOa?Za{ zP{A?PMwaL+*)sln@csiF04TxN3)Py3!0F8LKww^@OpRYH#@Jrord~3r%57jN-4%>! zR0`Bzm8ao@HV2i`gfoh@QPw-v^<=B}aV)OY*6kTIWq5+X5nsSUAc z;N|;QZVJWj7FAlwgwJihj``-AupN2die0-UTH5YIy>zcSZ|nSEHMO_vy58? zbzJiLVZR4n1e;$0s0wsHO3^#Qj~}}mN2M{|&tv}(Xpk7MtDx%BbAs%YuRc z0b|dFwFJew5we{(lja?mr}j@LCss=qJ(B7K6eBEnXrOv7xhW=~dZdN}6*qIgP1l4x z3uCCQ^RL-b(n6usI;{A5uwO?a=VuWhuCOj3P^Oy?bJQIJXl#AF99B$BSeb+UAH1Ki zDekbC-E}Ocs*`}w*@&LuYnBd;#Ics!O~P(wS{xYTKdOk@{RQ8n$9{()p-iY}3ks;=w1X2SKkH2I{ zyNA;-|1j~!{8PKet|*PjIP}Rmnovfnh+N)9biEfp5L0v#$%K6v?|3eDm#cTJTi8kI`YPtoUd!BGA8Tyb$JCOZ>8n4HKDMHVT0sqcXo|O`WUKL}u5pe}4Me$J zXPHw0Je_rnGc;1|qjJU18J_oT6N$SQ?+xF|sBpdrWD`-lYtQeMUT8#$@qS<=3p@$a z6~`mTc9TFUiWRVmdV13N02N9i?!Br2pgc8+p=@%sC{s^_*i`7h&~dS3A#mMXzx`?d z^~Lh%=$jxy_fEWR156_~n zf64q^=RI(?I)ue=YS0U9#i^>-#N@SGz-ebDmDnc@GH5--CxFq*znacE z$M18#8?WET9q3;%YGES(3YbO~-h2uLSV5@;R~gunyL}aq;S#0%{`-E?C2CApEQjY> zZwBM;1mVq=Wa& zIt(q6b1Sd-xV$T;DakoN+OINwb0=Sg6(!OUS{QpAMfbi1L5?gF^RDPlZ_rc(puwyp zNsas0-0AZR*?S{Cr<(Q1&>Z=QTc%m19H~Bb0F+hrb;~Y$y;@+>k#moVwi}Vin#0}Z zlz)Z*l8(XHzKKrNIrr0jTyO`fSE{51{?sCe*-{QOX-+Pr5)Orxf_v}=KchY(<=ao+ z3W?VV(vzLKUpny0qXZFqUQ`eo@MCiq{>@_7$&0ZMx;JhuG^--wK8()qjT2D(X!bnv4neiy{?y))S1ZLD}MAJgv(778_%~DW*)}m2$JUCUS-6@Q%3BUfL)+rH#;< zI}iBc`%_O(+HA>+U;^(4pw&s3oS3rba})i0vm1r8l@7yBYa!1bh}5i3aPXIMiSjRD zrCcc)2?kShtVSa-i{cAvG6?DRw>5Kk48DBO%y^{BZ&;6Z@inYE5xG>t!4;o^gy)EM9;>r?Tf6AT4D=tQ*f6{=6LP zY0hd6gNCJL8nM9dlt2d+vSCM-o1xe#n@G-L>27CA3_fZ+ zMKJ(0laM|s%8`afW)@0;K?!ooY2mt*P|4Yeaq)n}j9>!%9x^P4`}{=Iz~(|2DFq7} z5rd$Q$s6MPvN=Yho<{1VCFdN)Z5%>7v9+ET&jr5eH^1*?->s#o(ll9i;slft%>-69 z&2jIIMKcBFW^AO^cU$z3%ngUee$#i_B^(@^f>Yaob4}R?;FLR&fH&f`KmD3sCy>-A z=86;!4DoE4_6w3sxAMvpiozk`WNIGE#o=vDJ>ZBGL$14;n8a>`o@LygC%62#h~b{- zjv!SKYoq9DVPM~%%yL@st_vg#Zk{F0N{QD+DKJ4PG&N#Nz@${jESD&vGs&_+z-O9q z84QX3;r;ju;D=Vwpn>eR;G*6#FuP@C_+(r*&w^r}$k@pGXAO>1w3CL$@}}7hWV-76 zZH|s9E4Q@!>2U*Rv<2H~4LmYeen~i)mf+0&m)}Lssp*-sIaFTr>(!ymqsZwwafuF$xB6Yk{C+x$4rwj{llSJaxkWMLbkve@vZArk(8MTIxt@e- z^b6&?jntMQ3w&qGqqXYCn>Ulk;M4V8%d0prfcbeH32sUPR4dIkErcc@F)8^@-ga^4 zLOof#3w8akpo1^u6|LycT143s*ETbX9MijxP;Ta<2 zeO+J^2GSX}X>UwH-jmZNk{vLf2`Z$SVU#g3O1l)ZL)JMp7RpVBxWG50s33KSVK^CA zKu$M2meWS|qzjP~d5B?Q3b>M%8IJ<-5&}c$aZcd_zk^>7L$O=(m_*K{O>Fx*P?Cpl z@+G;*{CE8y`;WXOO;!^VP3*Pj@gb-wq~<^uaUJXOXLB7X-xM{GQu%;=H_o+5aWc=B zra(}3)F(-|*;(1uD$od5VYMk*M1%b)KmZO(Yc|YKoBBrb+@72|w#ho0H?WQktW9Xs zj<7_FvT2|}Cc3@Hi}JwdJ%4dMOBnyw;@3KY&zSI4WiBe%eOVy5%b*C$E{BXfcH==h z=GLfDBy|&;UHa$%eq!swq`zr6PHrL-?d!wtJvp_i7I|3RgBz4jaHm;5H z8l9GF%-(=6?FLaY*$2eV562EWW_Ud#USIFu`#|av`L$9>d1iC)g5wgi%f1R9lJ2Y7 zx4&L#+GRi*S8NOzw$%A3{gC*rZw@)rNJKmhR)BG|qGTxd_2t*m+#FXU0U?oB!uvOA zv#o_V z=zuf5hMr8$W%+xpm7*Q1(=)UT-U&%~%4EyuzPuYh$W3ztMvR0(W}?jO-hBDv3eSG+@B>#RjM`?`nJ3`rfCcs-IT3ri|$x z)g7vpnq6^QBtGghb}o|X+s?sZ>`@ILT>>FzEJAU9^idF;zO~*IM1g4MY4b# z^~8e!C&D7(6+P_vv25oZ9_$E0#xEQ}0ogUz3vINfwKQAN8%>hDYrHw5mz7gHgx9gZ z0|IooOz4Ve=NycRY#^ArL3Zi+IjlE_E3c!_(8FJ%UYR%9YafTf2Q}`% z@OZ7#bsMn`A>es7(<(1RI*0YdbqXke)#{BTMLu}!mAWj!NBs4|=w5!J*aRG5R!WAP z&K%fd}Lv%qV%gdt1l1Z=gn0s1#62mks+0HBFCxb8BpSbVcS;7wwT@ z|4XB2b9D4;$vPt6262bG|NK3&r|IbWsp1TOAYcPD!q42x`4vb0H62xCJuAcI?dcW% z@@$CyLUQdM78XKKeLe4zwBrLaqmN`Mouw>hq{?n}v7PYA&Zgn?d z;dr|1K&7VPx%%;f4F>m;GX0c@K7B4?3t&ghdc?(AtyEUz4IAI(T15pP<&>E1Az zBXk$RGLwb0j^v?QybqflD7MFakZW3U^J_!m`yB0?qf29l)&VT7RC|z1GJLb`Zzo60 zST|#eK5ydp2C&2W$ zmo~kRQZE6`s@A#z`jC6Rnh7YU6Ox(-riOpQF+)Dq06)#DgU_+dJ#~1jN0pkYqw&lD zSqLNKwlF^pq8BhQ-0-G->1Ep3)a@^3FBnf`%L8pkZ`Ep?J=>nxH*z#mWfnC4QW4_z zOXQD7CF5q0b-^gtO38-B0#s^&BOuD~WMJEY(j|Ruv4l;P*(_#)AtkXLL{Jlww#kw){MaIzJOITytS zGiW%$d(Dz4lWEQjh2!bedgD{{80HXYbGZBQEh@^qlvh(w963T9=$+wICNgP5#UZ~< zSW8N-p4W``F={Mo;Rh%RJb zC1Jb41l;G}-%1KalmP-T^L2zL2{s#;#yGmTL^~ea6#1i9`tkGBg18DnWmfIft9k6A zrf~i4gya=tId7u2E$pc2zs_iB*#8{e+nQCVGyrF<1hN7M_EIv8Y+A(c8nPO#G^Ru1 zm_!FW*QL=o`ZBgvgd_FDhC!2am>06q71CIC76sdl@qd{!;sRW)hn8|9^JzczPQU9EU-id?`6q%hiD z{t&J_F~8|@rhgX6w;`ybJos6!uGB3quX`2Y(8BtdMF9Gk4g@D=z&@!w0*eU)t4UaO z3~wNjS8)8bFouI9I(vSO>mxgn%+R3MrQSdYT%z~hpI|`HcR{lpvXZ-OI?w8Yb#1n_ zY6J$gv|`KRR*|lW9OpwvERL?^GY4E^lTuGqTMcm44efSo{($tNU!8iUYee-B;M8hQ zD6NK)L;?habv}(LzigE?mtO^qA? zn$sPuk2ps@8GYLt#sEsi6I^MB%B<6+N{|(^0s?Sd46C$0QON+JoI5NU_&9Mxl5@wo z-m2cNbwrpxS)R;fD!vBW7?!oexeQ1n3K_n^NV7_~m*_FegS^^N0NHp9Uvc6u{OqMQ zsi4f{6IF6Ix6ZK;m?CLO<;ZQl+`xn^B`J3_)j?b^s@sbFVpU4$JPQYC);pPU`SP}L zhJZw}-_PUE^X0FpW~+jq?VFkuc}b(Kr}l+GKxJd|X^X)U8xD4$P#IyzW78B_nZHLi znad_9b0TJ=kt`JuxMCD@N*2E|EDlK_&4iW&R~AhnW;F#y9prv849$bO51|(v;>w<# zIg8n1-;qADaB`>)>PRFraI>$j7il=;?*V=R`EnZvWQxXPTVgOiip@b2K%bUJ@gZ~J zVP-1N8(n+xgJKr%#O_s#A)H?|lGuEcSaNU~n2TplXZJ>)OEX#=e7bUJf=`;7SZilu zAnXI*y@~lVnvO`13DSdG!ZdSO$NaEM&h}Db$4rsP9MTrYoX^T6D>l$)B+m>JNUu~bd($ZiP`F$6SQ|K~?hW2x5jCd#~-{G%_p!J>=O0;OP_VfjQ?_!oy63 zs(ii4_>>COU&a#Vs``X|uBqZ+X7; zky0Q?v16%TR{;MP2_0+30u1X_D{L^^1+ZP@(vUpXn8N#Hn|ysU<6!>oPYrx&VN(}r zI*CNXayzMWvSt$!=O}gK>Dj30jpL%{qJZv@8IF(wwRwI)dWr_ zbxq?S)Gg(cdmqR6WtzCKxwWXDaE@lcd%*I?ha&VMoMQ7}#wYQC2tXLE@zD32|q3p`}lX6030x(sdzOfHetA?qBIc!$$LStc)J8B;C^edrMiB`yyt-(RzUXq0vu~|0J@zaryveUKfyu zPmJaz3k8Cu20(iM)W_*RRJzHf8}!^$sDBD#nw-bD=5#QAkBb#KbFy!h`WyMg7W2`| zL;QKT7ybhtE^@s^4T`pliy15&)MadqexmfHIYPhW=YqP9M!x zOfAwj%FKc`2Qt11snfwb^VO3MyCN51G;=Z)AN<$D@2Tfc{oBkS{@2x>UC{yxbKWFr zzdGM5bq%1e_S4cUKI)AG^5(gXFj2vI?Z zh^u6GB%q~VlNlD<8+Q#z@!Fp(w$XVNkwlzq@ee7ZNJyCIXP6uAaa@|$RIxG^cg+dj z2rxf{C_U@24`yOW8KoQW@`9uHWS8_UT1}5_)%;K8D~_7FInPJissQ-tWHGyhm0!yrD)sv;J$-zeN42 z73z%AVZxRCPA-ko|&5w5M3=#J~%G^Pbyl<@|tSZ^x~$L4b}*l>{Xa3W&TJMi-r!8oDhnLlyZ z6hIfU%FL)=p@oLabQv_ja0Ud)eI*X5{a*K~r9|FTem)9Ooi;A;=Ge6X^+_XWPX!gY#_{?Fc#=Kkwbq#BF=~U^R1LAoa{bs|){{d`0C7%CMj~0AOnA*wI^< zY>-!++4Mjn_;1Ky&eCR=@hB)iKBEYrVo2%+^INV&C~JF&5W`^-2u$OD-lg?VQ$>k% zLvrt(+&!45tdVjdNh1@I6mcaek?V9gVE2(wNz(i%XQo9n=wnEw1!0pE5KoA->30c? z0>D%4CBGnwi-?2@=^O;P0H4G1xDXFR{nT!97>m-ACwSrWCh_%$FOuD+KIib8CG37? z3dH`RG};1kE(Xe8`8Uc&uo!PqdqwU{JYlZxl*?-$A>dCK-;NP9JKo+wra^E#cRM(Z zDe}0I?^W^CywpI}%v4xxP9c|!IH_FxsgY;R)WIlOyc*^CiNlE{0CdHSws~u>Z9e^V zCP1%bF}@%Q2J=-timc}RUhi5yNW#9Hd!r2<^0u*Jg|3&KZe+3l?);(_-68p2YMq7& z_K6d>SW5?fVuGX7-*^Kz7%|8SM*2%|8!_JuOku=)p2HRUMeX%{pN8ifWKWh_?ldH5 zbL?|VG~07=S+*;Wp|8Ai64Tq@qUAWd{9X2`699~0h@}?h*tHKam*jmK z8|yU=!2llFbJRBu!=CkR(G6m;NZn!WGIhK>_jpOM?GZO~5~CnXv5E`O9TgYAZE)p!f@+WkmdMYY#WI;Bg%lAZ!srO=YzAm^F?-StzV{ zf)j-H&AbeSz)QxR>X6Zgf#3gtFNOXUGDh1J+hQZi+}CVL`!+Oc*D6v7ealbSB1rz1 zv90VhrtNq~7oCXEfeJZnPYMBlkTDU%R94rohbegEvEv*?#^3bRdD_rF$^*@5xGPn` z$vMUpL-O3;nNyZZ@ZR8p#}oqwX0o^NeUdUSS&?@Zup-ZA&rw@t@DE!pXooy#wE0L~qiOkg^b^gkWPmLL*x5Fs+R>X!ZVX`8y3u{z@DZ#(){*7zd?NKfu2{GsC-B#f3XhjnA- zPePqz0M8$~J`Us_wN|M7N!)UoFyPnR>&9(f`R`YTb=wh=Sh_nK(x}}SKD`CYB8{&5 zuT+)1F>MGo9o!^O!^u#3!wxfc^Zkz2U!~0`2~2vW=4d@RX@a-m-hEG#CL&A_S4ftf z$TRFrdb3%SqEBe5tLVA3ourt_vQ#)9>|0VZfGXxixBM^@!&|d0DFb3SqkLVyD^&d# z1<&w8(}Me8={v;j(RAgV)!L;bb-1QwD4iX*B4P2pNM}@S_VKK^En$C>q=$lB8D#N3 zoh)Jr{R5^Zq=c;u2nvwxmtPIN$%ICLlv_n96`WnKTtZutpv}c$>7!iIuiTy^BO>)l z0D73exuPv?J)7a>&Pa4C?m&JlVv^QfOZ$&EURa6@e6bdeU*Z@fCZD&X8dE7rTb9bD;SjkU(qz?2ZdwSi>OX*!E#vbkC#Jgp82xkm z@|yUF5rZ#H9}f**$t21C8{ZB4$oDUoqA`aOvVkpD#9cL{Xgz+1_uBLIS8)mwpy)}6 zQ&zG~Tv0$6x~Z24>}LPZ^KIo;>E06!IZpb5gV@eU*#|7K@n@>xUsQ=m# zl`^ZIl)Tz3>qr}0&$}__X{2C&Z7Kl>+H{SdzH|rYdcL7+O=`V1m9I_F3~ zQ=r`brOd7(==>o%nzz};oEJZ@+ zX1@t|DeM~uX8mo;+Cb~BgZFj^Pu=j9iou}pk~X?uIHimT-FAWqFiD1le36WIwkdUZ zB%hU1cW43;&5k4ZH)bmekAU7Gf1@@g0Ng~?+}HU7-=Bha`lB%_MpKVuL;Y*N!1F`4D94P3+OKMxlWY{P^CadxaQwdY2ESY7 z%%g~xo=4xxH|WI*@Szb5-G6wB8Gey>6pR4!!ln-d-d~?FK8IYf7Hu)2dZYO4HyRe_ z{x&NoBP|P!b$nDmHTCbGLy63WTRn_lS5s=`x{2w@7VMXP?XBTy+pHq9RV#Yk60`ik z!_02fBsl*Jecoid&uqtPvL{u%D=H|c06nYJuwt3MnN@lP!1c{OwQea8Qgu{TM!4*q z#IE#6|Eui?L4ll2aI|%$C6m7ShgavxUa@r1r&%f&@XKvb&a$95GQEJxU*9O$EW`C! z?XoFWGGbP~VYLFGrYaLU^DV>#kGf#e`QC@$(uA|P+GpNN%r7Q+T4&nkaFj~;k{_?D zf*1AL@T$8Lu%*b{mSVpF|CFB*SB>rk-(-M!PTm&;vDb)OQI7Wo2?4IOXnGs3(}468 zMsU_$!1w%w!K-T2TzOP?w`m+Z6mx#P^5)hCg87=)dgg5U>_P_Cc|9i@88xq1tj8$m zC#|j}lg}B??+jm2*6r$EpWrR!ID1*Oij&Xg%!SMhxEIup%fJ`Gmlm?m0MAR99lBkO zEgZ~$`9gB^$O`qE+pT3s{hd%@P?C{i8GOW!a}EC&ao;1FM-}GvNHD-%pf1AF7&TAv znnQC$=((HXL$`GYOo+{hz05t!Z+cc(jNWQ~6ySB9%RFuXpPETEz(omSS?zl& zr9NHT7teyBO=!UT{TfdD_niIqaIG6gHSD!T6vvNXf&P8%3&}|6$Ek(n7{rAcL%bL- z0e7E>wCcJuo)j zi|B>7R(?n#7P>rOU?v84|*)_ZtA61&If-B(Lvz^#P z$d*Tpzk%P>IjJ+y42aD9V@Y;&SsL{7!-~|&*H1zU@X9=f$jE*6Am$Z zfyV2C@h89@lqwX&V5tMUn6(a;7-;qawAY3I{=Gs*;*kZhsiK4}yIZd}pt}Y{8Qf(W zyy;W`_1k2X7kwMWK=5Ekisp^p6;0UtYrTmo8kSnkkRW3A^u$W6g_K=YjLN!OF+q>0 zPWPesBSS-lo8ItOd{Y>nR<`hfeu?7CELl@1Ih4(u2{cc7p4xy>7S5cspj9dkAiLTH z?(k%?{oY4248PnWbPqgB9z+9jTvMFj@_{guXct6lOnh8e`CGse2BSh1t?d1CFSC1KxW;b&f(~18 z=(qGe6K{eC*47K*rNwO`8~=^!L7jIl=3)?k0z1${)<6a3bhAAv-eRbwzqMrPx~Z0M zE&@i;zwd}lM_xRIjnU3=`|7ubeVw-88Jvc(|V@Jwha*V_i#3kdgAmZDoqOcK}1hn-o-49f?0@of#)8 zF};qyN@fI^ewE5MpCU$@)^1@&1NM{QRl3{fUVWJbHkCls3>J&G)j02wJy`jh5OGNauYhnjsx&(044tio@ejm6G8*X{ zbnfuc%sx4Ij~?Q`KH;2UTe= z8}y&?v}H-Uzgn|_bFc3lup4oYXyFfO3&}#L{7lnZ@B-qhT`D4F0c?S-=82$XhBbHj z`ZwSb!~d=*rQ~{`}i)t%5hJ_S)cu!hq^EzKBt#l%wb8J82HxBiI-h(;}o%h{Y=mn42X+liQ*! zbj>qr*^gSrYcSY+48T}FIpA({Li*9@S6tf;KCCC)>T}{M;Km0}DY_Lq68r1Le{;Od z%4?$Odmp;)#-Kk)gm$e2NTBxg+R4uG&e#`AG%6RhdyM*{H~yBVd-x}IfoQj&}5 zLZd1&z$<;!9^}l)^^Ugux^>{RWHa7YrL98a0n5CzuGp+B8(`Eb@#yM~PpSZ9z)Y>e zm*Y>IWJ=rF?7)-14izZzn|K#RAF6W-*`9xNj??bFJJ9dcdOJ<2{+J}nFq6~tLK5n2m;3v38#|&f<8>S`kAn6(cChZ!Rtvl zVxrzz1Xa*|Ei0{2IVcCHQ?=CH2kRq5n$=()v}$Sl4&+MMCIRSNBC5|}s1`f)SxCA1 zmCz1X00z;3)_+6)y&TF81Vy3KkiWgMj|#p`cc}Zdwn`xDcm!MR+?Y0083s5Xx$*qv zU8mN}g|VO9%YPyuOpss9j{m;c;Hr%&`*Da=154}G$Vtl+8jsC{pUpU7(B^N4OKcq1 zO5@|CyNY5E6RdyfFK4l;ljN>b0!{7M_2@e#b)UD|QK?EMw!b@OqAFO)^h1|0K`bLKB{*$zbgIA8@3+=}9_x z{23X9^3r(hjIo`D(@&6PP)Q}stxfwUy&Po}R!a)mEw+XpK(7<)yE?n1BK@k^XNCA( z4fvD$fn`kl+81NAadw}ms|mshhR^kzz)2n!^bJG>k8VBp#rdI*WtX+2fEtCm`S7BK zEyX-d+*kB>7l|5z6&>Q4y)*?$#UaE%13i-7TnW<#m$ITm3l_19#4?X$nnPn0Z@F>cJ}D=9wU?1*MYe8lq(94V}-vNSl8C9 z!p<$4(?ZFS%0w{v+@UaPHN+J?hg+LCoZHVBE|F^^3Ud1kx2D7;<`BF^ncdjUuL>@M z&?*krrx1|;^6je?n!axQ$(;D72o#~9Ot~zHdj0XhBwA!%5v|MWS8(vLZcLV`H=w6x zZzoQz>-+@=2QX5`QN;b7G( z9mrb}A5=EQlCHtE1%0S<89CbL5`YnMaxu!9yXVb8*7-#QU+YrRxc45Erqplyy3zOa@v7XcBM|$ z-1^HNV2= zVHTn?=<9H7(svLaVm z^nO<>GGM1b%9t2`@! z%_ZSiun9?Af&>{Ry=EE|8STQ-SkfjX5!E*f%d3Y4m^<_Pe%8h_9vL*~g=JI#Z zVTF14D=&@Od%egs0-BpKzT4Vh;pF%+9o@c7n!w&JyS55)Q5%7*1LON{&BbDi?a0wQ z(c-&GR=L9I=-7ph3%nieM_z4b<&P`*B_Uz$Z21D~sbZ{gEqVuRQ;(LVr4>>cR_OI^ z-?Kh-fjmZ@apm-TILyrVJ=h(Kuu~iH*IC1_L%<@zd{r-T0qg4~7vgvGh4ZkXg-u?2 zrJ`lyaBE4nxD_mLz78I_*J|t4EEs=rBu>zV5`{Pe3|`k?eT);FLh6F_t#+~aI!_eL zf*8t@rq&Nenm(o>vJBbv5w13SH$cS1nC|oq;6^I0JVgafL5jdzuZlFY_Q_|N&?cB) zg3|iUm~^^I0eD5mn?ABIgb?RK4v1{t**ut}+EE&izZGEm0-jj5);D{TtNFr2Na|k8v7xqF zBGm2{R@1{K?kw3fIDRQJJ7E%0Gdv+&ka6L+Lyr8zlqM+;tsDM|@nnJZ{Z#D;N-iGoUZ zxt3ce_hnppE;Xd)7{b^^7}q;ncuXxT#`Wk&#OhXGTCbpji&w#UBIjFsCK`*;KxW+- zC;U!s@O^D)--}-1iwcp|_Z|T~G&W!!S*tm>1=vj(^<}dqg*?5E6@Q!D&eZ}r+fMyS zXw6x&l8o9@uTUXwTpwC@`?F=xX`Xxx}IO{ zL^uQcd661t5J^ZSZGu})t0T{d^#IN%9g)9U;>sV7sgHgEWr#cb7n+@QSi2b1V30KN zH$bzcJUQ{AcV|&Eru$g1QQVO$$b48^Swd}hUR8;n`fv?ep!pmi*09RWBPyDc8`B-`&APCHIgnU+x2zYE|`ahRbKGF$Lnhb;2_k0c>6y& zT8L1>#7nl%@g&d7bZ*AmT-SDq`%-ne#fnZ>W|W+Cs`Mb7El3L31`l%`bHhC-nh*!Y zbR3N#E;v&zUNYY-9NCqrExhMQYeH%1AOJ65Sb?avsDmJax^vLK8#7&-5ck%z(%b!NeCS$%Ih)fcLLHa7*~+2HgG_WV&zwKx(4>bb7KV?29yu3CqJq3LLpD#&xqJJcO6E`ag z?uU)FAg=q1uo#ia!lN7iWH@C5Ak&I$CjmAmUlQ0wQ|=mW5#wY@q9d)Ncq#ip95ARYYX~0bSOqW!y$t_&efxX|3UTI9&ySO= zsu7*qXq&gI!s}n}wzk?kaN<51*6LYxX)6crcsQmzXs==zgwDCRF}Vzo{n$i*^ha(@ zI|4YX+2u81Zb^O$IKlN4frla7a1jUmfue<}t>4ScQ%;ULHx;q)?KNV*uAI!! zgOe<{_QyC7AVVe~c?4n7K?H5b4csjSip$*UxUNp&k$$s>QkE=6N+R}HzDtHdK(<#K z`8-EpIU6IFfyLbUCMk|4{n?DgyFQmUFv`{S!~+mqi+?5zD+I*b*mw07I`8Qh&8To| zBT5NG!mH!gs_+{nzSAb|(<_FdBzeCp7N8ezD}+g0#tij09Hr}wx`)CFS|VRi_D1-z zwy787vIiF_S1ZjgdlKt~XG6AMEJDo-_5<_|G6^dA@fHuJj;ITGoNqE#8cuS3RAx|c zR{=N3WFk#}$y^s~-}zTczbD#fa?jx3%&$nzJiknX4ed@VfNEJa?xV$*wpm0Olt6UjdWmAag1 zuO>B?4U!^jkt3C?M$*%rojGwEsgPF(*QIdHcUc(!w~YuB67m4bfy0M&czpGAuoY0c zd)_qdKLgIe9Ob>hkbw`~5<=8Ria1a{XPCi@LJ zc5AUz@{lFdeCMw&1M`~_e8dk?Scip$>U@&#oN}eYXnZ;w3>-@@OTfQwbhue{ky#4X z$W+=PSD$y=x@Su>4etzkP)}sCEII}AT1PXBishp(O$^Gx@lYT(EHPWuv>|iqJ z(0|eOPEEQn(Yj^XcCE5)Yn5%=wvD%}Rkm&0wr$(C>wNn}$Bw?}{sDQL88hcIp0S{8 zrqq$df#yzL59J2>U)X`w0(nGXF-JHP)jZQ6g*S>hdF>*TqtM)U!ra0l$Ds`>>N+L> zq%_(_!e%p_mj~e~64{K!`p@|vBrR`0W>at#guFzCppN7zdNF?yHMS%u3P)QY_kgm@ zg>$3W+2)M?kYIVh_$p%IU{lmPHm>_>zGMa^($=E}s?i$U7&FdL`2mt?x0#93qb#-Q zYB3L|eVJ)~=X%j>b-Kou^jJ4JOW$EsU)dC?*B8Hw!_Ky>#SQZYB;$_@iSbnAZnS(j zKU1pbd6AWhrz>GnH3O5})Osc4W1iwEo@IJ)1nRE@9@vKK7di0;d!-$UgqkA6xMem6- z-ancEnUDd(pxv&eC`Uq_$fZ{6)7H~Dhq*6uhxI9{5Yu48IgB9I*$$GEU6f7o#gUfM zL$Y+D&F({xA;SeVDnbjxGg19?;FK5veRpUUhmrXvD(;suK`?gfi09*w3)rNN1bB#C z_{{)L)&7&J^sha=e<=lq(l%>(ivZi=pB4a+ok37jVmz+(6(ddB z)3$D`kCc##s$y6~?w|)FhJ1o}PmsM1h9v?jfKe`9bI(N}OqK?gcCh6`T^<65$v3?oPb-J-n?lQY}*-w^4 z9yAWuV)1^56zYfb?`K1;drC61fd%y?KS9%Sa5FkL&Yg`Iy`37ucKSt#=l1}LB}5#) zyPMC4nD&vP%!7Sn2p<>GM@IW>qQ*TlwR%hcerL9x=Zgn!;<2_(5T#H&3!ZdP9|54V zNn0c+p7r#p#dOa3mt@YsZq;5HfZ&z9^g4n#uQr^yhoOKg?d!gc)hI(_-rIJO{(lXb zZ;gfbBN z6CUggo%PF*vhrCJSF@DZ$>Qv@4O>kDfbHY(uCLb%|30F%e}Z)6Qb>N?AN2m>Pp}w+ ztLWibq~|;tF_-yFrxeyAUAj`=4A?}f5St^(9O4nw=ZRFAcSetuW-)+Dy67K$1-X3& zHtY}U zcGTYxKB5$fv!`fxo_}e;KC<-9LRY*Vm!X&pv4cso2sv#N~n@{TW@5-TlaLRFfwN&3S68i`QFvl8k5};3mQMK7n$a3!PuUh}_Cz z;p66yVE<9$pUCtuto1?Hy|tBUW@hh zgCLz;$N-QU!%i4i*jwLc7P$Tq8dx&IqvXZ<_kgwGfsk9DYVQ|!MP$OIqc8m9d%7nH zPShHPtbtlK*thW(|F|632;DIdF*cjcoXx{Iw(m~$wY5!W_T^Z7D}Gq;+|tBJPq%!S zhvlm!F@|}S9QRm?x{Ajq@CwOYjWl0Eysi7WfEBP7ZQ)PinC&VdYTcP2aUy}i4E}pz z_X0Hf3>S!%6|_D(E9d&+c)V1ny=PeKICDpro8$4v8M3+ z#;9y9j&U*iDX@dq?PGwxF!)(BY4J)*8!;+u*u=y5pQ9#4pzvTG+qFy?0y09&(IM49F ziw-l(x6R41)3jii01V&)_!BahZA0bdoOnTQ#hNVQy}@G9JGUDIUNvny@HyOiqydO; z@99U+?#7hwb0Us336h8VUwsV>BFv~R8WiBV2>oI{i0F||Df1I4)S6qcpn3tTuV;(; zX7D*?M^md_G(iDyOZ3}pGA^8M3=`$7RilGF@n#LXCbm9CMg1hX`<4>W<%4Zs!go4T z77*VZsRy`qkgs;gBIwscJt}7ye*m7#0s>T#zP{X)Prz8x-|UPBTpAeBUAMo3UiPU! zy839k4!x&O=W{$jFtL;w!S&_I**3D~1Zmp$mobr8KbXTN^r4V{r=4eg+DWtU+ z7wCOS0IId=)^(N)5q?p&>A|k?y`^%rG+u7RmeN^&7HHUEr8^CYz2%P;5CJ^Xrwa(* z|y(Lk%+Ob@f1&Gun{40xifVt$zX@ zuU~8sl7lFZiY9Cmtq|ORu>fx&k1alp&sj2ZSC&mWy55nb{OjP_mVrVNKGC)5>jUf{ zJT+9GB9M|=9{-Xj-~KcOoIn|n;aUcM$5-h;A%G=So0QFNvUJr~dJY^Tp&Cm26f$JZ z@NrZcy;&D9V&phg36%IqJdf^}%l`5|9yT^En7g||q}&jnqKRAIPXUaHB#uRK1fe+svPiwZj-Gs34<-AM%Oe!Llf zZSNHM3@S{DX6q@|0{|0XtkOVnKp)e>aDu^9iu0rL@Wsr1AOOrR5cS2|qy9z>VOVB_ z{}Qrc4V$kOHu`u*W6+r9OPu@?a=XM&Cu_eoXdt6W(buN?B1p-P^tqI(vlxO0Bwg`K zFv97o2t<2LF_;pyvKMlMw@qjZKpuKYswad<>mplI><6`pOaOr3n{#msXFJtt@gbr%HRtV^t)W7ix zx$Z@+DD@=A#zqr4A{auDWg-)X!P67X6(h?eA~WPD1@1ymnLuoj1+m`u9qHUvJ(}!` z>wZMG%rDtrWJYiu@i^==e4bFdR}{3eGshkQ)qN4uBXW@2KQk_fmm0k77pxwq8P! zmCehZR9NozmO~qPsQ}HR3$?m&08t0O6h3kX%P8EHeE3W6|B9YvGYQpaem7)5e4IBr!sZb=ot||a5yfv@5 z-j&A}{k;7ONO}+1yp0VV!DK^RVPp$2f;XDwpPsJckC2t=a|c;(58s0P1A0^jeEKE| z+uDzQKbgRShYSk2vj1&fnij4IAVkqLPC7m_aNYd-8uGxJKnek$x^lA@tvb0Wa#paeX_LS&o5%0iF z#T?jmn0Md$xZ1t5M7AIH#_X;kjXSL0hudI5_Um0okD?x}o!V0+k_cCstumq`1NGTk0Ic=~vANBaWr zp)AGVig+%IowzGevsE&Hmwy+MsF?79Od9LW&(Ct`&BsCp8vUEcArrwg-nQN-F@TLM z=g}xmuCBAUGGS5#3c%z}FjlE?Fw9Uh5W<7Ty?<6ZktdkYZ;2VGM@SmDt4>Ug!YT3S zb=au+3b$kXV!Et#Gvgg$T4BwWd&Xj_O}&+kK3Cm8(4Y8geQoLbw_8^qF{^`nzfFgY z%7j5A8eV=r&de^~+G>=(Lc5uMZkoAJaVg_gU9i5zaxXE08i0Kh>$*1#i*grN+^s*~ zzcB6fPn|D{dI3X07{+zj@Te}Perdt-tJn;~`JYL9?moJ&GI;qss&v-+23YNKaS#(! zv-eNi6l=B~s`{_m>D`^y4C%M{h2ES1 zP}dkjIP`6MZ2&`i+N2K$?%}bMZGrS)giL<-V`)T#{HmHVX$i`SG=U*{*JRENS~@gI zd<_`vKvV5ZmxB~#DTo}!y4$DW_p#5@n$>CFv$PBEh6Xm?gNl~;^q>^>`Qj8H!SLn$ zRe>LRSjer!08D6H$@8Ehp5hu1{1Et z6stsKe^?HZszJ;x{C+TQ3ZcZ~mR>Io;*UbI9{t0;l&TlIH0vpSjPCPUJW^25xZW1=1$8~=bd=|OJH$-;UXDO*9xA9VS zjQ@azSlarN0wlf*4=sb2Zl%(U|dDZ4eJeUwEwngrk)##Ak zo^m>O-<)O5Fy~f-KA~MmslfYE;FV@^yDAi;;KyM(iu?SB{N9J2<=7z(h5k9d-rCe8 z7NQ&PY#5E$1Mb0kF9E?HM}+=ZpN?@%x~IvuPYyQ*?j;nWBRo3A@Vt$PmJA>s64T(2 z2lS0zb(WluZM(>}T$f5~#-489b9>p=izHr;7-1!KzFqv*8wxgE|8n{?ovM7OxRgvC z-Hq)8)(hiqqZf5OUfzG>QBsCr`>P9tlscpD^d)r^r%;*1C%R> zOh3NEc$v!Q#r(4E@uQAp>7(R`(xbbi3v2W40Li*WYXGz=%w)f{VK(yKo%nFDP z+gn3eEn%ykNk->VoAFD@p6tJ!0iK2d>9B)AVwiBJ2q;#n<^NGom}|lMWY-}Vq_Dr+ zk<@09ga-D)y}1lwW|LYDDGBSeM?ix6Kw`(;nu?yle3Zc*XFSxH%`9z(uD~caMFzDMN0d9A6Z$Dd9 zEK@4J_nR%_`8vAClmWxH3WsLUR;VHl{O6mi16^BorVF%>rz3r=gKn%A=Yr_S*$^Ky z$#~a7c6H-B6brf~cGt%gfHqB)ENuN`6a)&reY|`rRS^jYB2_lSXDolQ^ETmq z4~aPm>#$s7Kz2qVUig4 z^fiSPEhAUKmb$Vs;39>F9u-_ihnZ)qYK`Qv2f{-V&&P7`utDrgv23F!9wTUjU4tbA z2_KZ$Ut2EN^6~fz^$!$AT?!-9HWp8D_0t%lP$UJC1?#We2q|iByUW+L#OvV5n01?+ zmI!xMDHzJF%}{6<#BaShyGlGa8wv3$va5e_gG=WOD@d;*z@R_@IZK;%@S^l^sqR)q zzp%M14tS&2Ro1%f=2cPD9a)scvMI&MlPQOnV4&$Q9~h`jl|eTw=8nbWWF#zd6XrJGB9h17(;z)4V-NCXU|$Lpyn15<8Hht(hEv(NeO6{irR6X)oxHZRgx+ybTA zarW`@F8+KS0NOV(tc=hxhXpZ0m0LS^F~#;rLo_519+KTY+9nvXot*QCPI82-{`vJz zr?L2}!P|Zr#d&)artTpG8L92iQONJU@&)A;%*8!{*|J=ymQwQ%DyEU|BCTXHrGJBzk4JFo6K=3{jEX+X?vUB0M6L?+U#ujoBj`nlVCfEKV6-| z+@9lVO?zpr- zXa-2vfOndiU(!_FMM&Ke+2Owc)y7Gz(ceF(B}09^|FVaDKRoG^ZdT(P!HdJpoOx%o zbj}qnZbj!i$>F!ML7XBp4k5jRu1Sn{CD(xE(VnWkizrs*7Zc(b6g~-2o#UN$7>5_V zUMoR}PqokI)ab15s!fMG?xZi(sF)qaJFM@w0dc;2+bZNgS(-~VlKTugk9$3-dgd?4 zEfZsLBny9>Zji8moMr!OekCK&m^)A)S4}0Z!kGJ}=m>lAY=+ta^1P!y=cMCwMz{{e zD$e??tp(hw?e`Y{IUJCQmHseu>X@2);8dMJVDUKNbvgZnALeCD)Ejt zm80(;$2R-83#k653*i0^#zGEv8sF>?iL*}Qoo~vqsB3hFqE!lk4duj55M)$K923Pq z?D@p)wY$<_fR$1RAgB7QbFUu-Mct*U0mwT~B6k$3GB2DR;&`qllFhg#V#wD`T{Xii zcOe{+b_5JEZi(yI2A-6Kw{-jK(((L7t}sZ%%!>&I2GYZFgtmBdq)0YcY9)qQy;wt$ zP8qh1_h8bDA>r)9!bGQ(GM-BWy+c?_x7)uYmx zst8cx!%V;L5fbM*ZAtxo01`8P0ZQj;w`j&;tNl-R_pi>Ew#U9Dm-2}l3-DF_g#%dV zO?$NP?H*lKc#Z6ILdUOWB0Bh6OyV%ZzgS{k!iH&nYG(sqRVfIrqM>nBPDrbDF?K($ zU?Z8KOB4M?Y)4%jt?ep4KYhiF(SyeYt8=QieRfP|%2S&`@I~HZrpRtuc;v=6;R^l} z31zFK$sL2BHp_m-{%RAz1o(Bs5`#Ci6ZoArX7g8rDCe{8YxQ;*WvlN99Yed`K(*4j z=VT}hZRE^vkYWC4kfMjm#Xh$a5vUW7l5}>)|GZCpinCq47!BK9#t{BaeuH8jf@?p# zTbmx!MV((>a_CRlTL1dgc6$UkMJH=OS2d)n2n|ey-95$oURdCr0Md0Z{e!0Wdjl8Q z{mq(RBn)AN>0DXEd%3l?6yC}bAL)qj_$4_s?(Jn1`M8HoJnIRDn_$?xLs&4tKLX_w z?)d5720iG;RNC#_hGZR|HlMEhwk7Y)!8<&HiBxeA@hfs!A@t$G;{uw5&SE8^FX)dO%-fZboH86$mV6b+$J7l^^M zc9rZyLXXWPtIt~%zK*pqu_0=zb%J$zty{KxH&l%MH?L=dp~Ny@xuV|Hgzd)MU+m`3 z#?K6={4N~uhUvJGGHR$pnjc99fiI% ziRM9@)Kt7I{h=0#PIQz+>&N;SMtw(wdp-Kg>Ud}S=Rvu2DJJpi`mwCFBLa52%((bs z<|C^uSsF2(Ldd~Rl3E9@I5PM#A*Zq#-34q59!y9r0684>amTQXi5C$$R@Y0NN9R4QL*m(8j!T}2oP!X9Gd!#gk`FX=c}9lJg#kA7;;vKPR|**w*HMPmEg)YGDYy z+BKhh0LC;|BFt~mi)--`q`R|1dFfxJP|rMe%yfAvq`%b@w4MB{vuWbZrlUuO%juK*+rt)5flf93{inQo;GR(i(GX0euhXd_0b~L3^RwN-?ys7;2 zHYY4IL-`!9stlG6{iJ^qWBDj{O4=cp^&xVW;bIyYRlvEu?VtQ$*3n`oFT=?=A`$WO z0Efn@V|hw;RYaQ7CIm4hg>s^{|8`9*Mii=^=#6{3^Za*E_MuWL4<8#)-G>YQxDO^k z;E4$gk@Qz3JTH*^`BH!Z<)Pry%SW)Y21u8yoerdR`8m47n{ZZG=*BOz%~$hl#SSKF z+$mtew)uRhFP5H08Q-RB(Uy0XB1na>^R4mx`-1|ua=mp)i)wap$+qY6_p7Ci76r)5 zr0+;&+41n-I}5cj>_-v*QB%-_9_}VCPn-Mv5ii5zA8Q(WbQL( zwo@`gZA@=W(0PUT&D2iTX|7J&FaX3z$BtG2Z}eXc%0a_hUPtibL-^!WEf8ix$Ahf! z7hJXC@7IuMwg6ve9J8{7L}k}cepNrGhwjB_qs6;eO&7<;R%1h6)ViuYgG}p0Jqmhq z)wwJE_L2NTLi(30NR*0v8%`FYS}jAJ+SB8YqM(|J$m+ikqSr>4Eq_coNx=6l4ZO5o zTKvLdx*_=2w0kx)Yj0)Rg^!rE@00>J1%B95RXj_S57|F-2$W!9;eRv90G%vUKTOo(kO1O&>1 ziC-^aZJj!{4sd>IBm;fhn5-z4Q9 z+WpO%UR~}fJ!Pf`y1@Q$CoycGYjoo88ju*#t?cw$?1?|X7B9e01t?lOF`wdQI!>nF zU=ExnSo$}Jh>ZRQ&CAX2UiaCpFl)74e)Q=XLbd77YJ@+O{IR{G!jS`BwfxT)7X6B% zg*;;R%tRmYpXhSFT%I+5_+b-IdINRyzw6|`7L0lMTS>!#CNvyZ%Y0B{kY|DdygH_} zCYFnYpo;9swIMjnW&nB>XVs=46(?3MXzE#>8jteX-t>y%!sm_El!KKkdW=cDMy)p- z>3Nl6l2|MIb_Ms=6y-CvnhVdi8EMneG(k#Gf=JpgdB+6VioHo6@T9lKM6${6Hg4YVGdj&nFvauUc=hSJmcRVi2z3PqmJpLEz2 zrvI80hk3oMQvk=2`NY(}bM^-Ki$5D()u(7bXBMJ%s(q^1vEI6Lj})ADh|st+>B0jg zjU(jI-u$f{=bm~`8pL>S(-$RRx<}N00y!}MQh*<|XwIVr{;5d0xpl^Aa%tuu7l0(a zZp4>TQ1$JA@`$i9&lDGm>6Uuv%CeG!AWHwxUR79!2Lr}K=*eg$ML}1TT{FOe^3j*QDf+jCf+nJHZ3oWzO2K{ z?iw;vOXgfVS`%4zi9(j2&2CML64LVY^Ob5UQ)UdWwPOAh5nWR1SlVQA^ckwWiN7M4$J z%z!zOLt@!a?B1(M-*?INRsxsFu{59I|6G&jFJDB0G{r+nBV^OEpnPd3*>GV!KJ%(M z+)@nTIZiL+p=QW+b{aK&ly3x(O3d39t?uNoBcdO!g23DxI)^RQ9MBi1<%q9bf723M zrLjsHLDYT6&?B8s^2tTM$DZF8Y_;M@W&r@|KXbZU8Z?Nv*Um61_I}Ge*=*%@e@0aL zGHh3~ZrC5WBxg{jqH5cz(5JLITUSUL*^4|vRG;IDBU?iLvxSeEx@Kk8(I&iT6A`(^J+Xvk>Bq3iO+S@G zc~#W)A~8|cO3d%}D(y6eXE_HM)ef_)YQCJyU>&}YRh!hJ@U}$!6Q%C;(d_xIyV}dL zsvx?ig5l>3OSQteH;aJ28wgU2BKH*0$M?x><^+oaOR%V*Ugz6MRm={JSp&#eGQ@H- zVZ>(|u>OSe zy_}qXGKhKI#vz)7Ji!q>Swjhw#|E*Z;VSGd|+Ha9#ZVSyWGjXn)J&M@gFVCG7n$S zT5*xi!ehYO}M#z+kD8n7>xjUzE`C!@i zR$wPU5SNBGr8rHGqKbbV|LQwjB@XYcw%CUQ=`AH`&oy=O48Q8PG?<^P>3c4f5oWE& zH;Ryo(ntmb@oPHGE4}7`EEDK9({bD+`M?GHp-_@f>ONyd3H=ZdUs)&qKZF$L|0f~E z^1r&z{|G5AR;K?2rvBfA6f+|;JLCV4{j;jc*rnLEl?<0Bxyb0Y&WHznv!&knrp@TT z8vo6zJR@!N&9bA)Q{T_0bH|<={_WFIzL9QL%##ib@Q4DK?zr-9CWWn?ne?3WfCxxJ zdrRx9gCZMy8v9u~=~_5eci^w(MiK>uaDRWXnUoi|0KZ_ZtgZi{Y6#mG4b1?;LPvb|5Zqqau(FK!G-N*;zk7ptRXQ zCxj$Cr@br=Esz=;>1%CiKgxaj-Ra-GFit@0zt45w)}OE?7Pm)NCLj$i4iI0{6_nIJ zx7^uuQCYv^*Cy|)aCID?mzGxc2M_YnzYX6Z@7AsW_J$^B5KhqT?B8)yIIuJ=Zmu;f z&#&ok%qd`#_gZG1EZXa--$oE_ASeqvFy>}pZm$2%{a^8C*tNTwTioi2qlz9+9F#ZdV_S=f|wJUV{i_`v_T=;v8{M*}e z`U^vMV`NNXZ}RC5{Nrm31c;4_$J@Kj1|9?X;bLVM%lp-jimxt?9{r`d==HJ&`qjPp z1(umuKfBckzMA?~8XW3-vM(-9Y%AuO1E|a|tPg=0n3+7foBb|S{wHA-WKVJH>)raX zt^)EhBQN-y!O`UM~Q%5BJs2e6DS z;Qf#Hll|RR zZb*>r0CK2G=@;@YK{dif&bdd(ei@VBDcstP)Q~K6sNBt ze>M|fncjt`5V)N`z-i*&OOf9GChjFTRz+=^T0j}WNh^Zzc#x>5^{=ZDB#$9X7Ax{}i`xscI4OY~UEwRrIY z!!Z3Y#0R?i@zW%@f&VK6Jo99CN9?_M^;M`YLR>b^qMeJs(Gr~(rUN=fw|M-_QP7qe zVDh>Cc?J8b(wqN7Ui*xJjBi*ECevXuRb}I7fPtrpTftq7R=Xs3ZkO->h{TB`Z@1hO znL;H?mUcXKO|9D9s9fAmBp<=|=VdV9^ktnRRc?Sio#!kdTXzNqsF8!t5|HGc4yIK3 zzMM`5I$k>{qh`w;)!)dG`Kg6DNSWD#jq0H=7?SVZN5WgjE~pC7@tfju4eaV|+!)wHIK)LFN7fH27 zce#a0NWuKqFT)NuCY52A)80HtG_npoe-&@ma9PU7fK1aY=tYOr=q;kX% z9a%9ZXAAyArLcEaq5QQiHNEh5eA8ZYQ?a5Q+n_0h`XZnS6HTdy&9Jd!1+Cm5HEpOr z9%{61GjHXlt)l%K#~ftv>P6wYB(DA{010;z1|q6P#3(8NfPL*Iub`aBo)e89ab~09 zb^)s-Yb$4t5mcDTNg#v^w#@m;KvdDb9ySgH@zs0&ch*mqiC38zkljg!v1ykSH)?y; z!3F3=r{n!?SBgibUOc@K0`#Qe0oYjozR7!bXQ8eeZ1a4z2+!~4w|XD9(-3XIK3p#m z>z}ZEEIbthT-&kgsL!q;Jln73WzxqvSbbafPSvO6Yg&pRKsZEy>sH3mvgLH&IPjWB3DW>uc>$%+sfXmG_q3 zeC4XrrY>6#0#g=1Bq%=sX`J5&cuwWuynfFo8vn;;q(f^==Qa<{da(95UzuKlTgi8Y01dh%u-cVL7VedP)n@ z$G~KhyLt!mVdnLM_kvPXVbPtF)tHZR!Ss9q&Yl$NaWqJ4Zf^U%EulODI9>{EU=A}b zkK`)F8Y`#vTSt0flwipeFJ9Xj$Oq1!z3>EI*tB+{Ix}Cxe;HC+5)y~u#xKPf=Y8FnA~Y?B>++1bv9>z$Y-UCbZdAJf zbnx#9E|pimr(Cq;Ad#+Zw|CY+WCceULV+_o3Tn3^9=C(bK-Wqys=IUs6l-=WtJ7o# zSKqvy#lRR!8dTg7qiC=o$*<-Sv~x)C2$ZvO63Bh_>RdORQCOt~{&abg-dyOXm}~Pc zKM&qolTp>C@4m}Qg{}Av+;GT$?TM%ZmX`It@VgJf8JExO&~rD-{z|6v3SJOv_)O{r z>2o@jUU<_WfRZl2eM3!ZMVxL<9EX6+ZfKI<0#rtd&(t*fRq9e%L_OohM1t?)(ZH>{7#Z7bt9qG`NRw9#YvK7>%3M7FS~9vG9_1d^S%R z=55KG;(q=5yOn=Z=1eclNeBp(=JvQB>-z>p7IbJwn!q()TQ%ZFlhb&;$Z)---tt8) za@cj|qA++pNEelkuSg<(-L7vD$4pUdkiwZs z$auTeI3ZyU&ZObUdbX#CJ24;K@4%jE_J=L;C&{FQUq>aL4C3mU5W`ut8i~=_TfQLG zLx>|n1mEr5V#^T-kcv_l+|ixc-9P0zPiFZ%WmsxriQq;`A3j3l5Rf~77~+RT!DUr6 zrs*e%FLJbm5DEEQrV0=H5mfcTLniz3BE&V$1M^|LvItC#@o^aLP~ zj+Vuoljp~U%3nnHL3$k|rdP42f0&V(%Nu+Unu)1@@=c!Myf!wf-n%g#jtDD~TO`6& z66(DPTOcvz#iMg67)%}kA3~j|lJtB;^x|4?A3Tdf>#_+tIPE7rP1_?=bCvcSrev^)m&jKWGyDI z!*x^SWLT}$$X@k>rT^+TDzRl`q*a5*X<=p;ZAq5f3R|EtJyB`_Be*fV0{B-MHfx@( zh~Bxvj`I1Q`5VBswyHp;=%Zbk!Q9hd!&gV2DC1nDlQb%Vl0NXnZtVLgVR7sKz|^F- zT9eaj+*ua7;+|0xng)?!CT)gx9;)%Q{WGF;{7aB<2`dCZt*!5t@Zu^UUnYWK__rnapV`0j|s=`qod6I-c`n$&4~=B0+Y zHnaCI|79ufRKl&d6;t7|P4>3bU9!uA+@~r>xu7N!yd8IHL9r^iFgVTzN%Wr3bex!S zxT1scy@f+(NOdfCU-U+WR%=N_A~`x)mH7OSW&{7BWq)Y^X0py-(BEL95zJHyA}B_K z2XEi@Th9pLMnziyJ$BXwTMO0HLy4B#is>p=pUvF&EZ?HRxqza=d9#gOqYhCu2$tz_ z;|J@SXv~)RmYml(JfDetGXX6US3K;dYonSeRqKJd00F%RlwIEvykQneZ?DGX7z}!h z%=XRyrVuoMn{zq?`BQg@tKcwik{#*@slx>+v*8lH!VU@D)&=NgI=Gt_76UN~7Wp`}_G^ zd_)S&Gb_OTGF0Dc*J>Nqd4x*nIyNJOd3$JywEl2?@Zsj&jLRGY%qNzhw~f>G@(=#9 ztmei~4K?H*ew6xYLuJZ~5r`z-Uz{QxNG~2**uX zDTO=0S4J|*{EyuXpAf6jJ8|fSaCf1J&-oeOW@slpi-x02QQqTAsLk4X-qzXi-k8y~K=kc$z zo$*C+#zj9sc;sJFEYC0FfD# zhOukB?#QF2$jq;h*|2C`4~}6s6Fg4=W*#cXij4Cyp3+ZW2XnMZM0z(i$CMmmxqj2k z7d$9)p=qIaQ=_RRAky15kviq|8$B_6jg^wYUObu*u-~5op+&M$$2IuM!~Q!b$L#&C z)nW4wSryY+5$t3(hLR{buj;Ha`f6j^JlF=kgJB!h|5-->z};(1~t;_Ck45OY#GIU zkbVWn%=c1|^B&La6mr)2f^r;K@|K{Qz_L1!LftuvpB{-XlKp3R1l@q;9hi~IT3~^H zRl9~%ba0QfMmzU=mi#LRvVIJ(Mc)S9t0~J#m2*}W?eXOdJ;v9JWGhHA9~bkSK_rq@ zquhJBzJikt#okwNk8PZwCrghLV}iJejj-JH z2Pp4Ju!Eji?$T+M6m50w>N(gUN^-xnw+y+{R>m1OhVUxyIxhWVOYi|;rr?1ntJ3VzVEh4h83jmh|TinxGFvL=@T=rae{|S`M?f#zVkd z-9CNypF(+2*Z2AfmhwlAMBA>TO`<@E*casPHqw7Z4T_f~M^iV?32a(T%;b5aht6is zS3yNe8?u8hxB&nwyhi{x!8TigntxU7RZdUR4oeSU11O&1wMYV0xVbNnHkVY=szfmS zQ36+5IK}oind??+IV6T)?i#5Dp>P==i6z6S!S1MI>A6Uj40P56!oVY81CE0d65V%x zQsr_)Wc^{>x)FKuqG+ZnbhDFLpOc;4Djs9jF2=kan7h@?g-(F3-Dz{uWwyJLc%$&s zj6YRDLdj9xWowPobIK%ZNS2n9+7D@HLekj-kIbA>a1@Ja0*tr;&<1nx#7a`f#<^J? zwrjmMTiOfv8UJciIF3ou@#fzjC`7EAJAwp+B3atcWVhZGQWRhxPkmS&7bobCCwdfj zqaUrtq&sAq>vtprrRb zJqVj}xM+EPWYQC0uW2to+f`6ck+-HJ9Z$@ghw2_l-DO6=PEn|xI(xAN&;n_>KY3py zFfhYwlMEvKF*RhrnkJp8gO+xG5(8(=I)SNyB?m40#7qH|A(%73J&Cn+Xb9t zW81dvO*R`l**MwQwmGqF+qP|IW81cM{#B<=)w%e-zM8)7>8}3uOh2y&==vUy6lGle zVcej+OQWFqi(-yIM#bwD`T{k%BUFcD0m z7}1!4laL_F1;kpQ2j4k77>Sf#=7L_w9FI(|NHVh1f)!!(uX*F7@VoaoE{{G08pUGq zgtv1}muT^OfIATnn!u0qaY&G(5y$QOZAd+9aGYH!`7WWo2(S;1Yl_Tnh*h7v`2{&i@%Qd-zXeE z&F=FHvAJ%kd&iU_!ixV|@Z_BmOGD{{p%_aAwus9WcSLu^-}Vwrh^x~{kzjvym}?6O zWw`lTKqaJVK?><&35OC#%FfBf>o!aN(^}5cNp^hJG3h_a#*gbf3hq0D@&+`;l@LD`0LSA6&mlxw@3S!sqgP&M_G=zClJ@ly zmv8LG7uey$KMNoK))0sNC7I%GByz$zJ&M15w5lFeOZ8!0w1(pln!_&DcgdL@7j*6) zBRMxIy%y1lL;`DN)~yt6K3DZ9P&@pl7Ssi^K;}~8sI#85IxXhCgF7EDzDrMpXvinL z1sr!CSodT#<=?F;ayDxWh@PrCWLap1TvA>o{%O(XVPgsi#)jr61vQq1-sbv#6lqbO zw0kXJx$P>wR|YS#MUhh0=8d|hubceaVOx%Y^lx1*)3)UbUIgi(6eM%Z&tFXCHdtz| z*GXLH$FL>m`7Y|Zu=_FO!!aC2_l8B70(|mP<00{Ym^aHKv@+qOj{ocJf&piRH>kaP zi04L=QzD9(P}NDYE2q+xr_Gu9c{($tQ>KN>Iwf9Cq;R?i)cWKUTDRU=xF!ZdKp=$X zGBbQmcq@)8Ga4(Krybn zV@=`eZcvm!gbf>+Oa1HRPIAq2Ey=*7VpjR2um!9Jq9g1u>bZlXk-vr%OBaA3mx!uL#gLG|I8-yU!vJ@9argu40aPg<%icGOzFO5tUhE~44C0f`(f;pvycG(q`Fb7W8*Lt?Q`Gy-hh>)i0InO$MsJDm zcy-JB78#-Pe>*75Bov`lp~8_A=d>YnZYAmZ_Mv=R4)&RM!n&hae9EpViIUXxIVje% z?S7^u5#jpu*|}mh(&O8n2gjwY0(^;Exk!l%$qkMc?v2FAfh4wmOEozq=S*sRBMj)r zv6}9PloxA_sTrqVT4_@Ez`xomP81(_>FdN|#mcl&f?ayHY|I#*!P4p+_BXFCP8j81 z{ES5ZeNRuV#!O5n>zO|@GPWnTL`Je)Y^}i*4KVhi{E4c%j~=@eHuUw_7wW{Gf1;J0 zG4&XPIKA)|dOc=^bpClf?Zxlv^=sy_`m2khl1Y85MZQcJDA8hs2Rwgr_;{I0}p=S!Rr7)-NS5J6}oP6ym+&k~UKgQ-W-E=;E72tmb*DMZPhHeFtH(LB5+ zel1LWGZ>`pPbsE$dFtJa7tf2Aj9jH%HEm;PAliuiMt#oZ25KHCKQlyqqqt_dS9N3_ z*XjtBveG^aP`9x!ro-sXbZh)EnZ@Qv5{roFKSjRY=(WR}p)iGQj>efcgk-L^s-I}V zu(}l6SlBGw=$lPccu21O*_F?-G6|cKC%D0?5nJk#8s(;%lvk5^`V5C5REVQxeFpYd zKRx*!z3O};(l@%J7MU(DT83CQ7~v8kH;4%VGj$UluuS(K^W&P_iMiDWv(Q6h^QV2{l6dYOZ}c>^Nk&B7iVJ4sd(|GM>$C1SK_;qNj6)!3 zG1%k-xWlsF;z@`VIX8n5QWsM-^z6Ay;r0r_GxxVrUro91tUhkr9N07F^SpRns~mQ% zs7v0IAQBm>zyv~61C@|pgH8lfB-*rnZXbDBb@uiT zs`x1hhagn=PXy!VydmG;wodC&3=7e5yRUD6<-t;^_<_0m)z;zhD12$V6Z&gp zMcv+UCk>In_z)|0i#pA7Vv4Q=auX+V|wE#c8Jk;tEx6WYR)UAusB zV)~Xl_EzbXKVeGna=2G8U+gg_7Sq zuRao3!hR2V6_ogQ7h0cpa_$dK45Pg+S?iy;(hDmqGgclj?7UN!w0SaQB{_Osc}daP;iXZmvMci&BU5f>a~cf0SF0u0~4Qp}h?Jinj_) z<-zX9tRg;(C#L7xE@f79p4+d0hRRzvWug~vH9UhTI}H0@sa2_n;>f_3a~$*wwMndX zxRQUKo`CkcjZO*-(KD;6Mv6VuPbT;jujQN8yZqn?X4k|Lk~`WT`fi3+Uf`v0hKgtV ze6G!u=BOE9<+>gdKYh2QVOZ5p^13#5uN5{e#bQId!bA!(hrA02s8UhZkKG7+4;@z2 z!S8GN!Lu{E^CV}=F>9&zvX%iCoA~5d#6uR-&{ua#eFh!=8jetC~v}^d*22AWj7S~%9y2#WDSX;nn!}YvQ?6wwuvj-k4Tl&jMdEu>2yzaF-+)Gz;2Sk4P^Sf~x zVqU~lLBaF*rLt90xIu4uf#q6g^oVm_2nk$MZ^9v@o&%W0)JJ$t+pMLS%zL~9Pkw=a z9N1F7=`QUZlzMp;0{{B!{TJ*_dmT;kslH~^OTITF1JlpXlPy7{=_}gL<_M!nZ4D-}f-Tq(ort0oVP3cLJ7NVu|9?Erz(<|)= zzEAtuEN{j(N6JinYp3N*0=cc`bg2@fH^)=OQPPR4L;UDTYPwryHZ(&wp9^0TBqG`i zn{xhQ3H2NuL6B_gSjDR%iL3wP5H<*u5cUhcGz$2RNe0#9f6m6p3aT#Bzl1YUlsx-E zld3$9#=$=#1Xt3*&tDJ-_$v}{F9=_SxoZ`z82YDR0r^EW`DfOe=#%oa&%DTYGT&HB z?hK^nlw~5Es{5BVB3-R>g&NV$EQ58{!nKD6BLtLH|B#~)Yx?!0x+#ZFrk;6!Cx!E> zS^x$%6+A54;E=aVB*8!CHc_l7Hjvtm)KTRG0u0t-%UW7fe#&$(xc*c9`F>*&b4nh= zbh(UZE<7>0Nnmwn2#>rUV>5CvH(w0pE&DU9!=@ROS2}OJh`zlnexilO5{|4>6Y)fHG$&c+7(MPiR6A zO=XsFrJCz)vvOu;-=@ci>*$0TWmAhj!pRpcj`t46z14_nIf?tst7Sevt*_!~(#A8F zxPBkZNAu$`?4pIa4hvw}FMCbOEKl!`i>f^*XT+jtQDg$&R!ezKT8?a(x->-~4(dGKACavwO%(KdKe z53=G!*X)`$)_1MRu`fs|r?!7afx6B<>2OlQ5Es$dXVh??Vc41ZODR}iJ%@pfvwfzB zRIm^Fi8;N8`i$K?6gCyb0{ZWtLh4x|>arokAR%=`NF2u{8tD&yM>sOfXeeF=PYCTJ3Ae8>a7=Rb1qgGNCN`DRO3w$I~p#YwPr{!r` zrATSU(Xb?d)h)% z1w9Aug8AFNlJE2yQ>DqS4r>&W20RwW$#ZA4J|@=r0(bpKh>12!=GObUZ-*9s7e`wb z1vlSbOYA_d*>$OTTe0=|rbZlh?as9#-gqK@M3t?JeDRGyEwKE%osa99!Rx2CgjRk$ zG|KW_&AJDy{a5ds9-iza=`;Hy6CHKk*19%LIJab5MVHts%RfwXa z4~j^5v`De0cZ!)oHYF?BzqT{jv-gSi<+X47CdLYl3{afsUbNAv`a|%w zo5a$V&T4Ce>Oi^j(RM1YI8Uou=W49^<`DH zO&rwyWtRVax8B>Tz{BTQyil5?AwSTYkgc+Ta@XPM2GAzlQuL6Vv)kWi0HgPF9jLsp zE&maH>? zPxW+O;!bT*%~`)t^Y;1>>ae|%7i!fYLORL}*~s-5Pqw2i;wBPUqDo4dl9epxl2sz) z)UdmV0obcP8J~Du2$i}$|KsYTBIoc?C<1dv()?AygKtXK9w(h+&<8{c+qE$7!1m}h zCmWaGqfZHq>7vPMd(;a)%E%;w0Qu{`^d+bv;;+%4&+z!FQmQ`wfQb9^^iJJ5*cEIM zT^v`QUJDrSNVL^U##U*nkr)OHl_7-HgSsdI(Av6|LN@A!gCS&0t2)00XZBnxLcN!} z9>;<5irUyP<~#s5$x&?BurqnC8Li$WK+`#sGgKUTyL!87u{+SX!?I`E!}C`nP%9ZS zAWmuYy4s~DOFge;LwJy*b-{9$3Z9y!!AZOa z@N%!SG*FaoPYq%*-yC8Uz0z`y8;TE(sc9c((s&k$iJX87j+mx#Bn-pYBHdIRKf*Rx zlU@K{l-iv7Sy@*^v-;O}lRCfP3j23#?cKmso0&-;@Lt%3Fg7Z27%d3Kr)3yp+Tz0Q zvOqR-su9Qv${EcR&1h#|3K7L|x^3`Z`h_pqk0l*y0^{Xy8v^zD+c4p_!|e(qmt_x% z?3zctYChLw12*mv&Zi?O9W^E1KNx{=i_MP`!e%!efr@|QoVNs6=y(=TIbqPcglx&Mi4j|&VLu{mAs}&yHkxU+x^QgDIa&+()e)uc+UzWmK z*^7onX<_?)omB;A?s@qZA~qFUj(Ei${?7o#(+ZBH@Oe1ip!ZB%0b1?abWY|Vu4cC z-7@$9oKja-lyFYstKFD*+F=78WPib&K}JI6g9~w%yLI9fmArVg z^=4ceMJ3uyVl?Z!7^+nfu|4faC&Opx_1|_{V$Bv!816JvZ|2aFZ^8dC8xf-Go?#gS zrAdt3kEb8iB#5_rMO(U4MA2!#)uc-xTX|cic*g9lE1&+MxG2K|4J36y@tkd#z~y(h z>cDH@@SUR|q<1r|x5NrAv)qDDkPd9;3jY_2(cT)7=wz#${mhOSTDF94F}1BCY4Yj< z(SV;UoFdHko}jcD^;9s*zbjXl5Yp{a{O?k+@rw4^rSbtQw#pX%0WB!hf+UuUao8L2 zA0OM#_VZKx)od|G(e?C)Vb>$b`XUffwyBC6p+VxKql(%6dUd8FFW zXL<_FKgwWP1AyUwA@ZrZwlq>kwZ+U==u2Q*`<(?vNI=WGRc zacJsl4L@~8GvZyB?)8urKF>=9#tYxrvm$Br3BK)EMfcdS9}VBia+aZqoAt1vlNU^qJv71}wbFIa*3e#S)`jxvI zAt49U#hSs=4$G*9VUPFZ839v)53W7urCpWvSoIWAD7f!QzC=S+HO;7hjVj@^Dcy3x zs?>6^3}q|6zyt)V*TG73l%XV#_qm@?XfcezE-1}lz_{oxwRTG}AENBYCR$8p4*UTU z5%|f?DWX)36$!bOZ=DC{07LU>3Wf7Cp%wSQ?q{2EslNeEKJrHNR-(zSpwU$eLOm4; zB*^|h>`=ssX2P2E;!dqW;my|yf=3_8vT`BWTm$}oF^9 zz2rch{zoP*55hF*F0;iv+1#~)PV26fE}sv?IK{}{fK&r!XIxu&`Q=vri--tvW)eQ63Q7c ztAvnWV(vn5C5>;tga@lVL#e@IGCTeHloAjbXc|(zvwY0awaFqqd|Zzbh=6M7z{Mn4 zZO#!6ppRY42LTH6J6JS9=PMCu5)PK^78l465WdWp{}WwG*HJ22=*vw+{BDJuf*^$U(cnr$P<>kOlD3^0cMkFT0~x8CTNbI$(*GT~)I2gbF7o>&Eq8F#jQf^T4wZ6Oqt&nm+ z?kG0pe}5?pm@F4%fKs1+R3*K-X?i1xO3n2~50?GTieHtI_d_n8NsggCF2=Eh)z8CrK83S;BS2hlLFgePj9$aVssuP(ITqcM*j=L_ zj0@yyCg!GlQ$i*0QLvp3&?jv+6t=bAIg?A$yD!9%U_SrUTOgRJO>qqL!2wX@CCFS5 zp{Nt@C>}-bvvYXFq&A;|zsgDd(-m;>zlU*qez-0V@ms3^Y>O;>v&wV=g&JUahhTCX zXjzx)JEVDfbvbn2G=KtMN^|*2q0J6~Zrdkf#?PxJxYJ03Y#Wn_{pkCIu3YCfts%h> zHRv4Lw?A}p;eo=`T`7k`y)H6{va`P7_o8onNF_G3LOIGY9)c8a=+=Jdn+{!`vTy_%5+i2)8BBzoy2LN=6%6=pK&SsRk7?+BU zH^lt@6DEHie^LU-dO-^O52M=ZHj7;l7rAjk?$vC5o=ymT&MzeOH!eRgeVKT96&Yvn z5q$>vg=nxP8SPpVvvEhM@)#l(Ca#5t-@oY7gVUH3 z-jdJ4k9mWb5fV+q7-68_G*CuCZ; z&O{+Phe}ajK$5LmMrAv*zHZrbN6DqHQGy-2X65EKgc?3>h8n}O{b-6>HC}ejdT4L- z%C}O;HULJ{M|g=^d1~&)NpfKfqM!PdSX-Qi9OG^0{eH$#_4B^78$mVL!}o1p!@l#e zr{1=V4i`zby1uat-BL|8vBpyzw6UtM1`w?lMy}&}fj7CsYqc=o8b<0-f-O|NUr6m_ z@Q~vs!ghqp)S{jkGEEkxo=P&_W=7@atQ}3mkO2pb8A7NwVL}%vCfU{?Mqt_4b?Cs{ zt9b#N?ZLFi2+1{_30%wl?xsx1~uW zPvGsyX*m8I10gy#CJCkwg6Lt|>=jIdn+HmN5=@sK>=4cDiTJ$wc*Cv**BLAdzO z14XQ<+Xh`9 zzY{&tBgwXeCB((y-<}JD4;CzZAeu z-2|~en8@h8Z6y1DG-<~8q&>8X46e7xrf9`v``{^pDjYu9c|Ce>@m}KirryyD*a2mB zc=nCk>kp9-r&)$QBX+S z)n8GGJi-wTt#6-Ca^=@fbmXK`a3*mm%<3Os0Wp@8;s#L)hh|0Lwa zZdMD{aE3Um`L?-J_?B6{LbGKl~?O!Qa%~V%VH4 z6%>_Q^9fT8*Y#5&vd{9Tk_=EKEt&A3@LyI?f1e`FToeI-OD4pbR0kWgP!Uo?%)`2{ ze~Upzn=9$we#`TDoo5>)meKT7#>Mz2CyMe{C8}aJoVbE+>O)kyhYu1g5i(XsFca1qU@g*TKkMc_hz34+$=hyy7QfJsCg^eX zA8dxrBSSZ!g2X(4g< zFr2V9xBaxE~2`zrOVwY4ko4O0VskHg-~72x@s zK;RG=8t6F7BjbTlmLlr|>=y4Vbytr1bHSw;;$N+oCoc;gza>pei z8}rvSJsd@s7fG$o{<78rCNna*FC(L(-k#AFkqh92;Nie|!WYKUz64#H(Kw&g;jf?k z#SEZjsrBAF&xk!g<_ui1URttJxws{Jh2c76=o^A@o-CAe_dc*OUr$QItW+_MR@N{s zh#_UTGqWZQ*LY-|ef2{HKq>7mQxro*B>XsdanYG7uQDXIFJlD#=;lu3^&#p@vC&Wr ztry+KNH2g0k=@>ZNKxPKirD$h z6g3SEA#=-rW!Rp$7Rzfz5elkVwCsz{?exs1IrG!4T2*$U5S`%(1KY5E$Ptot^-dH)M$c%otk?ENhnZi>bRlI%k7= z(zi?o`2?1BWUjz179y(W`!n6d4aTHi7?T zdc1Tt25j6Qqkv6^M_XWIKG`7{!?|n(p|^KpJrc*^J6bofOd44kdCGbYfjW934rtSh4tF}l!NP0VY_DoL|XM#CfdM&_b0{L4TX$Htz ziD2aDK}@ww8OwrZF*ttnS_7bYeZ~ebqS8{E)_{q+D+%X4f5ZMco2M>D?ydG@zxRGE z?hgkx-wb+h3H9ECpoKPRqJxEcqrO6-hfg{fA;y|h7(A!ZVUHQes8aRv2K64dNUc}= zekG(VbACmvA2%}y7Fj_&&OP=e^;ncy#+U4z`p~@o-tjWR!Bw?_eNPQ`gIM`~ce5RVjV( z^yY!|z2wG(wp_i9*&vF-@2?h60I#1nxh@IZetN(Jn(6HrSYP0 z&Bvwy#BggdWZoT57jf^CuxeWNRor65O5J~Qb}I{%*#@R-@WmDjk0>5vR;On4Nmu7x z*iC-(BSeDeEuc|J*Bub~A9VhY3r>WO=NHyg{D3JK%CEM!A~u9~2OzvScbz6(6K4ix z<1Xa+RedpP7V^O}*ZJ-R9ma~^Ohi?1J31Va50%OTmU1;!`x^RTR*-_h;ch1SYC3z(ee_R`#$W%p{aC>_ zeo2z{ZI(5(&XDfM2fz_z8A(bC2a(lrbD>6HcDut4K?!UAnjlEc@t~dJ*F^BCX2Ce?8kAjSu1$y5pFWkmpiiNnNx>FYD%UZm=N67U0!%f}lL0aM%* zas!5nj?L4u!2pDu@GeT@FB;HN=24|mekdfPnIXKq6fc|py400C$37(R9Z`6FgCWb4Ygrw|T9mC%YX z+Pz0ia(V1~9Dv2(CNqP#y8svQp27w~crIvkVK9pokhM9IfRs|IV7k9mte)BR<#!P} zA_dngKzW195dDUy)TUWn=KtD5yHv#HdY14(lO7mJ|A|<7;9PskLY}rAvmGDBXt$xz zyvt86;GZYIhyZq6b`<#-!ur$Lu6>`oEiP;%=A;817D_4#)(N}@69f)o(MBv|u5)4%)u#2lW zjBz|*!pD>Lz}_A(tk~}cPY+3eF{J;;Fh$7Dzt2v&B;c1A-sH2{MOadW;m@FcHizu? zFQ{c(0}^Yo!Au%Y;pO0B&d*EhR??=OS;Z>B-2Kj&2B9;-j%ppTMjvK;3JLkn&lBQ; zUgq*c5labik&$Lo0?b6ekttoVi3afG3J6#!u$s3I)GuSmFb>1ZazFG)&hmw=9DXy0 z$6(WBVnRpH6wG^2RsM?s=i`2RCXk8#-SGi{0oIIA_^ER0FVTU+c+zlakUPha4* zdtAmQfSK@jW9|M1>zvDW}$I+8#?ujjzp|X3H#_~s`+aU*Y#pY zPZ(+Sw(f1y*1R-D<)VTciWv!6TIZHS^)i0d3LF0QgEu#zbv_{!%cO5I9^|5|%eW+I za5&famt7VPh}X3ntZ{^5#36^xM5rzekW%?7zag7DTg}L4BEM?TjN#l%$GL7J16DkL zmo&J1$(i>fes@ruBPW(Yh*7HZf(9GsAVOPf7U=(maV2UNx74YG=#Y%~X3)36Cl|C( z)A~SFcBfv;o4qV4A-8Gr5R{gsgU5KNM>Dr&Oi4-o$0;0fNF;PH0`;`#*`T9=2`Vjk zZQ3xui;J`blDUzm16%6xr!wn}8365+LLInLP)^ zAF?$cj5z>#k-dC!l;o!la7CW{uVX=3tlY@Vq)Q1ye{0{5>S1 zs;iqB8r9{m4cNF^JM%XZa*FH4?I0ui9lNEl=8(~SbQdX)svY-GfEIk(Gf?Ui2cKax zWb&eRQrPp_>d4_|{kg2QfoXF)AYC>7`loS^^vS>z2vl<^%L_W(J!JFxl}^JV+3Z@}eUCTKlh0mV zF`_VdKPV+k9)mQq?GAe0npC`X&WxK)>^gF^(=2uIM)(?&@i)1hxY^W>81#SXYfR6F z$SBwhuO_a;Vc#p}`j4ZVT185CVzf;;{5vt-cjd#k{Ns|6zybjYE?PyoC<3n4Pk1Yx z)asvc#a#G2MyLPH0Osi1kF`VNa!YTur+74r!o~P6@$(37G9&~jh3VGv6_&L;u+2Bo zM{&&0gzDl%weLMM?GTa=*RUrnESJlUv5tybM|)X2kc9jdO>Xwn$vS|0p z2JUC_(ZQcix&5$)Se-{-ip*4>g$*W6eVp^tE>1*w$aw2ZQlQhZ7IzJ{*~Y3$u$dO@ z%byK2m+0#&qE@3Y{?CBVmTkw&UANVINY;&u2upJ+@T(A9)g`I(x;L~&V}6SKiSzEC zu{b2SuM0>L$MFmfyHX$h6EbvKB>p3GZCNQw@!V3d<#x!Vop#ZtXmNp4h$&funVqE3 z%a19D>4xFuBE-K%S35t5&}JNBt3+X=w*t+$j{LCV+1LxfQgrTw~cFi`hA)l^PxqKf(H6v7p$gk(HUbjc-!RIjszT z8_p{r<#U;+Bj4LG_8e}~#0?uPz;*;?pKE%-1KDP-(xAhoZ($tOhgJMUcq>3sR{s+j%xaixW5OtOzNFIYGDSR-wSk@{aSSKrlZI^md?{+L72 z6qK2&1j+iow^8M;BWd&`2*AEe2BJpwY5+AAzTixfJJX0)P~m-bf^4&4kMc|gQ>SrxG8L@|6URD8Dr-~q$^`7QxU^gr?AlZ2rl9J(!2NqztJ-_MnA3U9 zl(O?T%;m(9zw46@yxkd-YWkBo%Y;}(11b6I-;lKV+2LGIA+23#YjNARIfN;&4SBAJ z8NtAX3f5(A+S@{#Dg*ERjuzyx(;~+MU{m3yW=;=PtsxHfJjgWKPKs&Iam5TSuKSvC z@dM%C+|`;K-u(SFdhW}L!Vw1>x_$F8+nX^3>$ z?9o1*7hP^35s*py2%|*iyJxg{a)`qF)#MXSl+qZQOW$&>ybe=xa6?Qk-~W~5z^pK; zPW9-BspCDSjj3E)8)+UdOq?5@FuRcYFrXO@Q57oPFd`YdA%CP$A%T-6{j?J*9{G+WK;W)$OJzQm? zXl`)=vqaOM?fB*p9ve|gKQ;QC%ITP~cS(2BBUh`g@dKcfl(4%c7C6v=jzCrRinkST z`HaKQTd~jyp7gTHoN<9)G}OO@?|R>o4%sC-FC?wL?qgpB{I55+^ps#HK9yvj1_u=F zm=X`DVv5>%)0v_x`UkE(A^)y96X7=!I7$6R1B4#)sISAJnIrnfPNbohRef?g<%=$t z%`#^0lY6#SpW4Uz8xm#!i_SlF8DVeZ(agjV-CKK5nx`YRG%`!n{~fSO3boJ<6M@XB|i+qXp(%3qb8#L)U&ub42KpQOZ=5q#p}ZWrrTE5BObW|!d@ zFcMyF7YiYZl30w}oK0TJK@{*ru_|bd!BJ9lV znlM;oMHTtuml1nc@Mvtux4OEs?woz{hT?Rhnxbn~%B2a>T1Qx%OMAViqSE=Z1?Thg ztTE`JEeYf%X=LyS5-o97Z2uUaYGqX9*ES+`>_{qRaSC$l4g2l7pWQkI=OrXJ{LFyt z5i3seDrXU2d98B~lno7NL7eN0C-bnbCGOW;gdRPgWv9I0fC(s97KhGLw7%Qg+il=? z)+0~k9FzQLXW)hX3Guw}hY;+bGJ)QXNmGF-$)Ql|v5r#009Mv#A{opX=%u$E%m zFfzez{kAyA6+M){FrXONrkj9lWV6_m#q^j|8o#R^oR-<0VZ`Zy27$JMYDB5iCj_i@q zoF*wI5+nMJ44ME(m0?|!lv*?#`U6j!lrB(J@qovluXw-Z(}l5ep(Y{9f#n(|hS1B` zp)tjP$w!|=v3}5vJ+c~QN_8fmRUDcrxvDX6B(!VAx@ zSkUM3+%xpqv%f7g<+0&ipJ>vuDx9KNshh5WKoWlg8j-787~6qA$M-|##ZHFaV78Y? zEEO?%^UN5Trz0myr1sSwuEyB7J)*ElxZlC+8RBiQ)$oKH0-(PQhfJ-4W2Ac#isCI# zAyF-wmv&AEp@qTQM%Ho+PC!iAv1-#Z@Tx3#W%_Vv71l*M4TlclDISIpokshqLadoB`gL~%$hxsafX-#t`WHT_x4k#prlLpO8G zu%PJsNK3RSnDg@^DV6*_h@n^SINq_58;F-;ij+F^A{CLK61O~ck92?&r6VCBW)wqd z^pi0{^d>MFn!n4(zo~oJw1P&s^WCTZgHOx+n9)F0Xe=z2^;cPO+Bw?&oeP#p#@NQx$?QKKkd2+0=l^y8e;$y9ot2&Kf8hbE+*FjcE|VFquE6Ow zHvel))b#3ht_XeqJ;GceLxa0QU-fA-eFImgjw5ZGOq-vz&nw&UZAR6$Q3|4x<@wXp z7FT+Z@eZ}F`bNeEyFaKk*3;T}D|l9Dcy4H!%l+uJjkRU0L5X zWmPd;f+`ac*$`_&iT{l4nt&Pv))ffA!CKY*Krok@iG5q^!>cRf*?q@X)I;(7 z$I$Otm{=l!Q>*_Fe3~Zy>l+jRp!GfxL4o}1+uC@mnafQ3RV$JOS`1<;j{NU!0O0@> zoad{^0EF8=^P(~5Dcxw=lMWd2sOodhhqC z=K7^VwewxJwJCvv|GO#bsB*Z*(OY|mksp)`n@>3CYb0>S@%Jgb|$ZIitMetX{- z{@-dRpE+^w*Z7|TDKCIW&Nso|@x>+8v4tx`kgqyZ5Tc0T1;U#;OAuJ!p5&;iGPIqV zAVY+YZ!Ou&N^Aaax?`Ya3G$Qd{5#_H`V0s}Zfg0^3yn)k2)hS}3@lA)ERkZ{!kgg! z!RqN-yw7&_9Hu`V5mRYedj5kN1D>A;!h#OBop4o`dS{-1y1rK=jM1%+ZOfOP%WK%w z!$J%dCyvwa2wVe~@pk_~!h8R{;OZ9~I5<2E>i6-r*Jud$m>L7vuhj z^MUdH&8K|-7XmQ&R@0DQ7Lm{d^*bjhEGP)$=JxCOz9wO}r%z(-2f^fbI+-(;lIMNQ z>^oAQu0?J|!aUSIU>guK{_Xztj_UiHkeImt&i_ZOz#t_9+h!3Wm+MPOpbx-AcVJg) zXkH+uAox2Dfvxt{gRJK zlUzJaoNgL{Z_rO}f84H!?#SMl>94Njf%ar+4&wD*GmmTmG##ba!IK7Jsm_hdR!uBk z=fgKv;)3LWaKg}+3~rx5sXFo)VA$0K+HODpEh-CP@&>(}W=5BrPQY#BQVOz<6f+Hb z#;L5wm1&-~sSbx#E5FnVjoKm-iK*47TQCb9*RK|^lvLU* zf4lN}X|Up!@tah`>c-5+obfdpl&u2y8M$P>Z)I(%DUdL`?l}c)rt>%I_ zOUx0V6M0Tnf4$i|g3^wOzNjhLf=8PN7{q%^)=k|gRHO@)yfEP&i?<1xRW{<{HvU=+ zp3w+{Q>Y*`r&CPDkF$zYMfNipZAX;(J_kWIYXknNXcQ}|*dIr~6%U)^H-fJB1kq#c zg2by3AAA8p9bOO6&kRLY=_EuzTYv2fxEa<~HnJcjf8y7inz9J8v(%;b_bz5NM!x=Q zS?UyGyi6n<0WPBsQLu<3J^dN5efs(4L#eKtK5Fo<8l_Q_b|VsleKoyszBi7GOj3ja zo|lKk7@msm$h@B*=4f8VDwGE&h0cFrG^;PY=;}lzP=YE8`aB!5Cnt+36&HnhqQ1-d z6AatHh zWFAF*Rl$5rTWTS=xNWzZ8(p)o6g<3khX|xZ&Tf6zb{~3tIf7ej?S6ZrJXarLujL2G ziCv)*v#JmP0<&hPvWwp_aDFMo!$}l)Wt0_=nA-Ov#s6VaE05G3#0h%gNSBHOYY>Rh zf6s>a{AIIO&$vF*1=fWoxAil?CH3?^A+*E-aZl z9D6Spo>5ze&Sh-gd(6ITgQ;Zrhx@~W)FOT|+3qshHGolual0?2S5>8;ytM_kEB_+O zNU0j8km&^G6@QhnfrLLU3+hj>?A**S1`_E*OU=Bw`mc{ItBU8x74Q%RWi|0=06uW2jNbR?bw)ZpA6W$f=uy z5x(cOpNv#+MvM+nDP7v$9II zQ)xz2NJqxftq$3pE&1h-UnTc-0+u-9>lS3NxK@c%R9gFJ&DC76lWIo~i~$Y5k2n8R zv}@{kAQr-x#8JT=>%nh1!Ed9T)c2+o zh`Vk}NYmvutgKslZWU@WUwu_;aldO(Iif#N_Yyc7QMZA&QGbD2))|szEq=bMLV`H$xd(Ju%6-e_TdLZH1yK zVW?Y(6EY<^kX1)v`4Yu~U5)m;o|KQCmd!coIJc)@;dl2|wq0@VVo{-FMQ;>xGtXQ8 z{apTbL8QFc+7@Od=G+IbPA5vVS_N5j^Py4QWJ}0<4U9JoHDI)%=T{x zmQq-#YI0%->~2`TKDHMFe>vBxI)$ZLe(L;! zt%{QDFXP(1%Tj%d9JvP!+To8*kueMN)g_s?DHrl|ty1Pq7e$`DMD>&h^Ui-h5YRN& zmy?HEKWO>3K^RVV%G9Y^ifLuDf=iSw52bx{JH^VJFM^t20lXq`(QPr?U*yRQ!6qi^ z2uLIDuc21(t(Epff3{e=)mhEER+#g!J=)w{-rfcy9xhwtBaF9+M}Z2kaM=Wq?=3z> z6$sbD!_LiPCTo95Hme!UHj88z&%&El^XjmbMh!xoV1a9l8RDB(Xr=rhMYxF=ky~{o&b8?tf4kP&-NU-vNNa>?wV{L~ z$jwI-X9T5^Wejo6$)NCSfeG6$C9CnnEm==hWV&MSxc`Vz4S6LEH56joJgA0z|GJu& zv;!Xg`$A@zpPGc0n$iUs8%0ddR`^XcGmdVGqN~oe8sA?*Q{$(op~+LmWa~yLw$|~E=3mxwtiD5 zZY(qPe`h~o6>?lHP$p5z+k{y9uCRh7qTMwA_$q3%X2{dex4AV-ZpA0-OoE|`&z8{y>hkW^zLq5OpG5~Y95d=yYw7@XI6mJDwzaw6eLw29 z!Ik_Lsh?lX9&BWZsa$p0z*6%kxmkXu%q#d_e@)EV`sed)jr=S)s7lvQ@aZgy`3%7g zWD_hD%9QC^w*KTu(X8C>4gb#DsO&VkDCh8XIdpps-C)IGOtuS?jQkbzwUKA6{&|WQ z1Y$MyEV(1T2~($E$2i>H)RZ#ge3d1i3MUGSx@P?hsKg9Sfn*{UH ze@;WD(I&TZL&r`+;av-2W z)Y{|E+_>`YpMLn`PZvVjHfFg?R1_nW(GYNx^A?3DB_be>aZH}4Y)45b$aVQruCB&m zVGwN|JQT}J-3n9ao+r~SsxqEDH0B%YVy_B=BTDZLG&dhdM30}HWP&Q%f9vYi5hv+p zpGR7rTmgx@=+eoU9!6 zv%|`384(htnqu!r&350RAhSI>mY+$EPmkTYOe6y^kr_9jiR#Cho*YvxLzcyYBOMN7 zKl^51Xq20YlD0KCe;3-qg?JqH-b;Zq$lpt>SkhB26{5Bl{$rOGL7fVIo4vU_xetXg z8U=S9iRlpq@)NC+mHC8b%?qt_Si$O}QplpZSXtJ3!8nuj9?R1b^O9Y1XZAJ)b3{vs zSXmD}!L=c(J+m$8d%88;tGbAL4N4T@D9Th%O?UDFViwwLfAKgPCc2bSYe}lO7vH|D zIS!`=c{`C?rq`Z?gTADw^3q28+*6^kyn9?BH{YBSiA;*7Lv8(uPVJR|jjROO)p zF5Gxo=Q`&qe-~67vWnLHa#x32DeMz~5V&tP=T$XV?S9d-mflcJR9I*PNgqQ5FmFd> zIs+^8X7fmW$^giUMPQIC!#P8viXjJ{U(^Oc-IU+jJS3)7>mMI6bIN7YsV7ZWt+w%g zaem|Yw72a13wUIMBNMgV%o3re5>0Q4RN7_B+GYs@fApht4chDrFem;-ZxWqW;9U6# zqTn%x3`BuL0{`aHxc$nlmOMURN~NM=2}@txIUK=042YanHz4Z;AKO}kK+*Og?zaDY zgwl9Ks`k^#m9zGM(YG3Y9%?@_lu-Qe))Cus2m$4@{{F zKX{b~CFthRtt^x{bJA3b+F+RMity z9*a#_5RsZ4_l0V>r1Q7$0{OhuL7}p@R9t)$9zA;xQOQdiwi$z4G{!YMkZD69Wn>oD z;vq;Y-_Ir>if8+z|4sSRUS$c?YShLb62=x%e-(U#inqu4DAnfO7qyu^=Xu8yM?LdQ zLnJ;&V{sYWArxXlRE`K*x<)4+?5!zRT(n}Mdd_IW8X(X0mp628<}qmTx>5e`zlv;D z(#m5ku6x&ODyqj6VzR;pPU|Br5BFC#k+yXE&`YGE87rY0tEx=XJ`dD#vJwpfxFtqy ze@OO>)vfF4phGcPQ*hT1AKf~HF+B(!K)o@aM6ioaZFIqW4pNi~HI4Y$z+wB6!T5ZB9=RstKt}udU`&-v9f8SF% zq&n8Bi*X4jogIeD1z3jaUk}{NS6nZ9M;F|&SU zbgCuQlGf^+Oa9{WWWDZZLHcDNF7I&JQ>fpnCrJBJDeL&lHg+`yF-s9q`iYIyVZcbG zb@nk@AO(LB_hdpsxh3bdA%C69f5ymJ77Le&gHQo+ZcK#H%C_0B*uFs5UcT$QD+S|x zGx?3o*8s}WTspzg;)b-#HYAa@tPO& z=h>_t{%37viVMd^7ISd>P>t{1s#1`N_2NsgJNn<&2!x3GCmCrfo}~J@f2pWlS&)DG zO9^Q);f)DZ)X(jYCM`^JcaJ~Q@0M-adc+U{ZE$&YUR^{CEoA-vB8@gtK=>%8A;qE zqKLi=#ujBr02``+W{7>Zn%1ZmyOxcqy6kSo*OJ{*#Rmu8z(}}-#;IcSvL?w+3QCJb zyFS>z9-i+oYT4m@3n_(Bt;#iKpoCb`uV^T&{{-8#4ns73qx1;He=Pr;`e&EHxf&}{ z+Xc+`Zt=BlvaRfqTtLn!%hB2BpyEqZM?5ZEce;`AY6jLA8)b{}Lw2p2BL+pn9->?w zp3td_fvXxXgTmI@R~nk9eodV!jR(b&n`&$?f-PxyDL3?WqW6%dcnG{P;0g7rkipR2=_HfBqwj!sSZpdG@RW!c%jMdta&KRapwg0Z9&8c+% ziPFr!_W0uFg;y^lK0##`86N(rXw8sIgaXYbxpJKOF1=HTf2t?+^Ot_Bp}@da8k;WE z$SxKLVagZUt&0S|nRRzTvGZ|{Sb1y1cmP@=UeUq=gGL-;W}9`!d=6Be5whNFZTm>j`A zyAPU+y!rkbe-rzqUAPBC&S?0S2;~Xp4*TceNF#S2e$@#76-CGgAx*&D=Ybf2?uHrP zn8jySHQ*|`7DH+`5=)I22X3DDs*{I7mav-n>(eLpf95S^Qdb&0nt~P6BHoTi;fTB- z<6*H2zKZ-wnS4}?74K&a5780^%(61-l)v= zic~7fe-*#wx1ZvT$zl5*UZ?Rx5<*UCBtQgz$xAOIll(pNI2Nv+owjlxLLP3nMLY=a zGTM&4Dgv=(E@wn&_*1Kw3ui1n&7K!00@8eMP_h68T&Oc{?uH6Ja5fnVqTj+yg%;5k zN13F-JA6vbq<9LWcSzD=Gnuh7Tie=F#Sy9UXXB|M?Wcj37vbeps=B^BPb z5`P#P6{9Y&R=TT^l-ieL@hI3ClU00ZnfSyVkcb(lQ)XzB-zk9{#%8*uND3s-0Ve)SIOstMn8tQEA zXFM_wnzFD}t)v*Ra+?p0|1i)wf1nffZvELH7lgU1Wa{&mzM^j`MV`2p^MJ!6g)B5Z zKg_=Hp+oQ8a+b%KFy!d>x;l74U^*wLoNXa7>9_0z1qrIoC!UTO67loTw(VyokOzql zDLR#9(k1)(nN)2d1~mS8@nZLGw7vrJnw!!4e?P5mn>iCU6e;Jk4B4(OC zTYFw`J$wQl@Uokov+&IiD?{@M2Wj7M)Lac04$kFK5lq?pF`3CK-#uWnZI~3=IhLyH zV#(nSvV9g-E&7(VqVEhJc4zmydfTjy8p;Z9X#lv6e5}(Sv;nWp&j*fLskTd0)wL9UmmTcHXZwm8&>YdR9#Gl z=?98MUcI0{WkHE6yosQu|3UaxhW|*Zisf(e=3&alrTFsh8&WsDe@w>ACM)We8ic$L zU{vjGaxGMFtwl=0?ahxf9=C!met%g0PH5oDeZmN*y-76_IplreRnt&5LM znRyo56l!`il+u?be}0?22U?Tn1GH^S)9DO_fneGBbybGZyegt7iUo+T7aSpt-mhcwCf=C(QAsX@Y6lXII#${mJWx0Udbd! z3^6oWd}j#`){n|~^mqN4bvV9k2+&%X_9RG=9C6!1ZnYGLf9Os}s!469%|v*JCcOc_ z*~&ynQs|RkfM8+=uQu|gITlaqo0Rnay0Y58Ot{%1bp&P8Q*X|kr{LhA7?QC-R~F40 z;EX%@B9K7+ti7M;P**!h+@$0~c`}o!BEU3fL$i4GP(-kXbD)5g0@egY zyMQbK!)$@1e^MJ*qx#i1nXgE6f572bu5QPR!RUxhbQoxm(%W@X2YK)GgN~PjR?RX<#ThC5#;vj`&>48|Iep-U2%3+xtspZ^MlkO=r zzDGJ!4e!Ymnl_G~b56L_Py?)~5ycI=y;-Gf^V$x4e>Xs95!f@?l%G@)N3|(W9Hw(^ z)k?V!;iKQqh-=mwcxodmHP8_vB6IH%vy7uZV2K>m-t)(M`*n4E2fi%ODe3%iG^4kV zACI~&$b7b@g$-jS$3TMVUBZDlbNqf>aW#ZcF=&KzkG%CLmOWPwu5f#R1ZE+v3|O2= z_e=Hue=}7X6-1f^M2|BCr;z%Fr+D-7FOq=1!&b(%#cm!9(JaeJhJ!$ir1|FGY9@1p zKZlk)CD;NCGF!Wa9)sL#a1xvnJf(e+)%&091%;~we!0U!26Lx4U`)C2-$y2%=;~<1 z3^OoyuePdM{_gO5w66t>*i4Bjnz+voV%NMKe?^pP6{nTgbGqG-oI*AC(Tl7T@YqFG zhv76~3qYb$n&Q=k`4&_?@jl+269o>#uJ?;Mha(1;&>=JOdDnq5b#`_yNbh)#4_>}( z5+{Mbrx3~kMla$_>&1}(ib}p!IF*N3bXwfDe((sCbUAj^(~Z{SG+pX)dq*#Dl!J5%G@7U`ZkCw zQ7O#M*xQqh*Hqh2lvj#gc)sQwG|+X73Ko#f3-cw!(0G0`IBroh!)Q5zYHIfFf7)@o zdXdtmUuy_GbSLYz-SlhOln~U0$*pDN(a?{5=)=kE_lt(rZ1z?}CEJ<^Mz%+y?Y8e= zobWy5_1PzWF|24-RYbJEo%jg^vSH8%03>@+OWMqFv`aoSaCjdK$7j*&a5MwjJN`^w zI#?ka14qJREu4mkEE#P=hBz{~e?848Ba_=o4<>zj`gbNJ$9dcec#r5Ee0YvTSPRRr z5-;7_@VEHSQ;g5uKTi!x|j5#eQBIqOy}Nx{LF98V_`L zFS>(wXgwd;6*EPo>#(#mA4f2VUqQWq)K zjTAjtjrN|~N_*Aw*#cH#{517vM~zi8__wk8~;m zrn~-@N)f@`hF?330%dUO1ejf^nKZJ7!G7B^_1DQ1#Aj9|f(cyRa1x@BlQ(9G3cHBj zFUMYzF)e1O<8{U14AhIQe~K-1le*D@c_Vh0inS31#`Gzv65%)ZnRtDKB*E)w(rm(ZN1M9faIX!R;^H8otqFZ>uf%yzWZ zs{sX+t$lBXrtz$TSYxnu1?!&lsf~2M6A`kkw>`kGO0oSbLVSz2f0@BB9Z0FUuoq+S z;zOUSFspQ)-0Hptg6wAWJUG|wkeJ<=b~vF4cw2Nj5T_Ym*yu{HKxZ5G|H=RG%fA|R zw19;a*sqmbtevB)DpiENsJ0zs9du6qUtpCz_A<;DGhJJPC}*hF0e%+e|l9YGT8Y@g0~c(q4e%D4@38)9g0*tmKPahTUv{0SMaPtb_a9Z zb&8&=;H2S7N+aU5%IejEJ3LftNYAe8R8#9(Fa%v!NeqdvtyG#){iG-<@h)_6O&MM9 zq~nD1p~4KYQWWxwO6lpWJcn-$F#1Ve2wyz`|EL3d8pvmG8`Zmy zse0Bwg+j4I$umJA^)MnlMs)qgf9hVWyeWa}D^Eq^BDmixl*Q^) zTk(gtj|q=RiHtR7mP*w6$~T1kt1t)Nh<>lG0r^sW>ndXc3`}QT?SB?5wINdGexhAn zDUE)%Ew2$dY&5!-a>}^GgLP%+Ft5>1=2KCA-QgmbBWu<@iS2!$sN#N9P|T!ukJ~hM zDyj0ef7dZ!gpwjg_Cw=(%9dy@9Nr;IAaX_QH2Q;8ra{}|wpCiNVZS}GqVAF1_>Efe z4|zM71ZQf4hC-BYjaXS8txI6WPxLOPmxFk1U^;U3q%=wDq^Esy@ylo0Di1>66(RGOqNn07n^kfP=t5tP$=fu6* z%rZXDQTS7}7T1ZPN9m{-+9Gyg%)m^-sVkL=Glu!spJs+6xb;% zf9M^C-DVMlY^_-7TV7FHj9#@WB?KSo*It$T!jten;SKCuEYP6qp>P(1cBmN z*U4)z`fw^(xyX~{_`qHK>=k-D>72})aT}YGg@RZ+%?>%iWEX~v7I`|L^4q7h&RGuX z346}4CwZ+DHW{$up-*RC?y)GUcI>pYe>X@J<7!(G`8|oG!Hqi?Y|y`YHEo|NEg@hSVv+~ZB2zy-iCFKMd7lm4thVjDdMk`%f1{az z@TrDTyJQ1d#_h5w<%lhV^AOFX+)k>Xx|l7 zi%PayoM^1O4LD*IZLcf&jjez0Erlu(8ww;hc{|bJ2&>5r9#Jc26?pDaoVL$plb}6b z%Fh$jD_q>q5MP5SO+4FDf0TG%TD8GVlxMLx(DWox#mlwy1@#-z@@V1%72QL4F%A=* zYu!-!Cd*SAPC|PjOdYWKe9zbleb$*~S!xlo1(jeQ>UXDF{Ojd9SuNp#>u!Bvs8&~I z3mHJk8G13&!-N?2vnK)g#rQi&Vlp|FUvvV;Fyb4-9DYVTIBQ9{e`gvTYa+dR;)})w z7Ft?deCA^P7#yIkp0D0h)@!uTJO`b9F+{o%V7$CdSSQ^neh3;S)3*xWnh-a}R(qHX z0*lx!zHpaXnvNIPn`+Tpd3%^xUWXy1ugV$tc&dDsbw5iv_Ur3Ahk@}RnJRRTk|Kg5 zun(9M^F;lA?`M5~e;l=?UnL+u5$m7y`P-SN4fKyVJd2)6iltwKOSTjvDx&u-Q|L8y z?FMqW`=Sin-)NXD*Z}XxXx)*;#2q6wEaP!AkcK>S4dWj6Q@PGP&T$8 z;F0GI9)^{22k8g1^v-K`8~f0uZjbL#OmjN9R7+>{Qo}hUe`|_Vt@kg6&iRDo$e)L^ zXhMHBCsw;x%abai-W#L-o-p~s8uL_h|B7w{uEh1=x~R`s-IT(r7ujWeqeqhwA|GKK z!pLo=n8e6~v_p}}bp|!vd2zPY1kT4ANrF;fBksNY_~vXX98JG~TD9U`V-?3eQh^5V-10rs+!E~ z&N@E(zRvnUfM4~e8@ak`?p=QbWbSsRvXLJ2DOmJWe{7}CRUvBnL=kJ29r<=)e=4o; zcJ@MgFLGqykB`e5QKIntix z{k>zmS9kxUwOB=NBO&%|>nP|`OWY3RckVFA^72irNFLnOl)cREW=4`_g)sx6*gABM2c!k}vM2V# z{pn#7LK0J*4w}svk`pC;6021t1KC&%X||y{e^1iP))u2X$zm=w>9rjQxecND(c%-0 zg~4xlp!fc4@cA-Blb*{nN_H(jcrcBwBBSXr@hZHV$GU*D$~yHmay$nlc>1@J(|5V6 zD<`SETY^3h30dF?Da6LJkWf=F+b{0suaKq`n=*Kys>z}8E{wOVL zigk9`t;>P|{0Dc)^L2^Y;kv}oU`CQja+`X%cccA-e*L6(u}6+jIt4cIdGuDV2oh>6 z6=S-iqyBZgkd`>zTp$wVTSXTA^-Y!se^=p8`W_TagJx<%F4NVq7zauh_o}Owly7Z( z)xOAWAQikZai-MIDb^I|_7=N4*{?#I7&onS?6Etm9F;|t9fFZXr(Oe+0I&XO1Ii`% z6Svmva3D9C(D!+~Rul zf~y@(Mw7{M2;~!J!3+T22%{}Y`R3C2Vds*mOZ(Qbm<=Wp?4@+pwa!@6|LjSKtfVWp zKPJaYlYbiXAYPt})9mc(=N{5XgGwr6B;I7C{Mqc@XOTjstE@GlincyRvJsx~?EUHm z6GusS>Nvqmz(Z2rtT2ebozF_pf4k~(3Fi`*u%$`S$nV37?VpyCC<;Tx43%RoZcpqS zsL98oV0kW;)QD?;I{f2ve-zD567((>mr5aD1wixl;n39c}U3Xn&M_6pf}IfPupyRe#}-@_Uuf5NOD#U8mL_N2<(kXo+jb3V1a zLMgXY=4&&8|9IZ@hIooc>Q$5SE9M>V7Q>o!^)16R3dVf|t%Gij)b`>H%cv)5fSf4C z%ac2k8&CX=Y*pWc<9)pAf1S1+m`tP~Vt3oTtl~yK0Mj|<8>zEfH3b3{N3Ys zsTvZ4=&jDcCcyjMvP_9y*lBm;j=U!WiQ8{EEGg7dkJ`X122m!4f9btn_UG{cy3ttl zTVQ7M#R>F+6J~sNAG-0So@r>%<)5*>x!nRcGd=-5wTR*wM1`* zfU1jhoNU2NF+-${e;b||uD4ieH3ub=#Ke|fgD+^)NGacBucs9dEsGbH_w984IQ{Oi z_qmEe1AT3z>tL=dsZVi$@Ay{b9BqVO52yJ^u+j@pPs$L->?Kvm`$o3*ow~xz;{vQy zl(iUM3CXEJCFM|#=?T4_wH0-qh8o2Lz4r|3c-0@A!^Lshe=Segzoe%E98CWWnU2>X zyPR=Q^=ZqVG>Cz@DQ0K#s_&PLrk-M}^e=FGe!l7AUX!i?wbl68IZET^nw4ggFQP}~ z_n1zgjmCF-g)1X%7~u*SOE?&LUMhkU3LvjSe^dD2+!VfC4uxV|@@gq9IL>?Y9+Xt9C(sQJjAQ3%5ZbD+rG05(n}7lO z7bP2k=kHH09lLqS^EM|4c{@-$S(59fyf54|`jf4T5khTQN0x58b)+)Jp{HS`Jf{-j z``fc6e3i(XdOK7BU&nJ5Q4-&JdO!oB#iC2Ij7yxvf6U+jPAMaP43^Tn-JGR1Pun8Z zyNjTPF>W0hwParzd2gSBw{Hnzsxu6?V5Yks)uHqy6d|M*r%Yq<)F2Z-^Tk^>Vb(J? z(q$1MzI=OSqslnIsm$(~Od1U1ctEn0q9Uog^@txUyor{7}1549mWcptfYN!Ewp zIcVe&f3p$E7K?tv$y&UHv-Z3EF`lkn^e#mCrmY$Bf(RnTWEv$u51kP@G-otKxG5p! zv*}|E7yPnOD{TbY4Eio!t^=NWRjlPq!^aQhI?NCne!h>Ra8aILr)#NqfTGh+SE)N3 zB(sdHG|ELJczd@JIOyx7Ln-MvtwIchh3;6Re=9>?AtD`SCj;(-H@7uU9ShnzdU`KI z;FJ9G*Dsqb3>og)Y9sKXhFYV;U5<{cjml1BG*951vE_6otAqW@JrKTP?y7+S*IGjN zZuSWZ<;ZKEx<*FNz0l6>@Z4gqx1`rB&eMcR#7LvARHHHQ^}o01GWO zM_Tbk;Kz~Gg`6}8&T0fbZ|fho@ql|V>IK6#c@c4%XY%EyrY*H*Le^Yre^l!Y268^4 z1aM-6Q3QZMK_9WABVlD#(hgJDf852*)he>H3(*ARcXrP8j^`NIDl`wrn`e=i zZeOqbEF#V7US15MK6lNYxZk%Mv%6i73@?;JW&R0gC?2NQDZ`49>P^=G$XYg*vX=|A z--wi`J!Af{=%#_F9F(m2W_P{C57iWUpU4UTPLRsQyQYww220}H_XE0DusWZNf5OSz zmxy@NZZ7=a9ls~n8|)mG8p?m?gWs7)s=q@|T_Qb0aGL48tCfcf=TP|CX%_H=_u0pA zS2Bouat@2QnKk9aOtIimveFtXy3yM(i(v}S?z=|S)cYjc#;cHMg5-%w{tGOQabqXU znozMx6EZB?$whHrLo?6LyLu4-e{EU<;^fbJ>bcE>3v1cEtW8#+7voFpSZYS>SxB-7 znFBXR`xkVaX1(e!g|vIdhk;vz&)mVsFfSKXnc$Nv87td~)yy6Mh(k8?vaT7>CQ5FgTySXUG?`{j*qM$IOoejJN|R}pnk4ulB; zs&v(w6b^GDI*uJ%`WZ+If((#PmKTz2akVru<@;o>_{eXTH4W=&>1%-$umXuyN+s!D z4qj*62@{=u1+f%`s$Yp7e{SN3g6I->2J|cxi6Cn0`cxwYMh5eui9t7Ex9ZDUT094M z8BD=?`v1;g%G z7akdHSmnC#LSrK4)~%M8q0NjRVX8^#38QgT4_2K#01wKJP&U8&t3Ww}unajH`A&Yd z^T=|-O5n8vzOTaSX-!;tZV185QTyHWK&Pv5oFkNVq5(=dJek9N93Q9Fm~vCptYxmE{iAZuKVC8VigII)7L?-TxnH9WhdqAukg@H!&bE zAa7!73OqatFI0JOWgst4Vro-#Z3-_=ATcm73NJ=!a&vSbIWRN|FHB`_XLM*FH8e6X zARr(hARr2nAryZKK0XR_baG{3Z3=kW?Oa)N+engr*RR0a+A$**s!*r5Vu|f>?NERuBw@@$O@eN#ANIFzW)=VzKv0LJj@gKHNB|3U=J91#A%OxnaTG_~h{z-n z*CyfuF13U#xHdXUgo?P0BPpQF@nW=iwS=R2^DFfpbkh$Cpd&aQ2?g`7|;s37a%CDB=jtxl>!k8;UcYpOp(NxfPNAf zT?^QW8CY%ca^$|pX7|a6*iNu)=p*5t8#ds)ELZBlafFEuk2`L10?4TEr6@U|4D1~@cAbP}^N>HhYGvHeQJq`p6>Olx{ zlsLi^b&1I18WD>y1)L*XrGyNQSOREa4Wq=yPd{z2m+3s)n@);|z0O8ovmzg)8|?Jv zI*S-)Z?N6TU^>hvmt?PTbiBb%7X5-MU^Rcf@vnbTN4`x}dxP!d7Z=$qn+&pf^c$EV z8|Rb7{Bu?P<6-~b*`SDi`YB@jV~+NZPT@F$a&|PE4odYNsoZJ>WK zn-p`@te4kuHlHqLC>AaW^X8Cmy*`6}bVdzJi1L)+{EWN(!K}XM9`1n@5Iw^pJ4R&~R5Vg?b5x1Am=Ee3^Is<>a!QQ3i z1^9aQOFk^F5KrK9tK;(uBB`I9%nJt?^2iFXu1n127LxYy)yYdI5hu!lA0V z{*)2-pfG7uXjdqds}!!WwnVV`bvnpc_H8gq$Lx>Aw8)125t}T={cJYRFDGm`9gWf% zyUqZZlY*sVNX^s9&{v*Ar=yHrBMwK|Md4F~0R{rdX8HUJyB;m(Y%m>}Ph&PS`0sV;|Tr>?8Y?ePaDtI{1`(TM-LSu?_pBUo=C6X0 zihMN8Sbs4ZWd++^fXvGDQW1SX1-lqcXZfVoCFNzK5m;(IXT$XJ5~SmQP}83Ni&6Fs zl~PmdhfF4f&oG^kdLU9D`*fK-1r z{gO>k*mH2`h?csWLFLNWbT+&Iq!I9tj8Qh8dR&aAm+0Rn)1rUE^(?#0aj0y_#_0eF z8)laXXfy$u*AV3M1>t|@!CqgbgGG_C@d9lqy+prQ+6i(%eGXtY0Bb~JsapYgW5CB^ z)S#~eHb5w5(9K8s>jrbIkBUSonqu-*6E$T+}UY zd|^RCxT&%~|Cl{~%pN~xj~}zgkJ;nL?D74xN9)!dBOKz+TleM7>(;EuFS2j#8(4YU z4J=QT;%n|-tFrp`^Fm#Z5^>&>y|}u1o6RQKsP4=czK9MW zy>&f{A{TM@A`vgRijHeKi=kbCX?&bLmoh-nT<>Zt!V>GU-J;OrOvZbenz4 zjxiK1A7aOM8E*sLA*O4ncbGR)p&kQx5wFB;@e#}u03M(AP&W;9QIx97J(17Fho5ART{1hbPg;h{rwClhMz(?E4GQxknQCRy^Mb zXIGgR8Gnl7|APPL8$xr@rFwk$kbIx&Z__1q`zYs(&xG2#C6l*p9Gm zhu$8f7cN0FT9{fd;QL}J8gNO3hl`H&TD2*VhWXo`y3{jI)4u63U58PB&qEqyz&?Kp zAcu>* zcfy5mTz21`)Mfu4?oLuAjWd0DZig;Dmn!a`_xmjvtcx8zp~h@Wrp- z;IWjjsx5zv<2_TJl}&m{dDbvNxQ?@p!TofcxiF?@s~-zf9k0$t(V?~OnLEzb(irzR zm-WlO>oI6Vf3^wo!8u(>BYFZ1l}Pnj_&yo_+;$aH0|$~)Wf#8Jb!RTAs+R)DUcn^{ zE<_LCT(fwF67X71_V6u5%vXQh`O-)^L6QJMaoPuo3*^*-r;iM*L%Y}BCDDWHeZTj+Gk5Mc_s*Puo_3yR=A3!{_&sNSCsMjPBujM;!NgDDmGFm4 zt)??KyhdMwiG}ME_}y5zC|CV`jEkESeX*-R@NzFg&5(@JNuU;!g@amCCn5#$;ZpB> z&3z^wee-9eaVZNIq1emK6JT;KjMb06@6(ycHpdMb1ck3_ z#gl(BcG`SuA$~381qk3vTQ@_hB}j}*WCR1L<@~`a=t!01Ni!w?64}%!%K z`ld!HJKDgvuw^QiV*EDMd#>T^g_kKW6V&E7toul0QA(FK~}6OoSTXPT584FvsWh~4n$kZ z%wKL|En?iJ46D>eHS~-{rH7>i9?!vA(qE-jN!~2g z?P+5-#}w707#;nwknEG%o(xmOJ)@iKjbl0Wm6HjA#A}RpnXJZ`XCEkM>lSPLZjMpq zML$670KR77gzGywS!YyTjG7|TTA6q2bTMR?OoE+Z$|f@A+!);#rWUCpf<_+-o13Hr z1{5a*^~o!K@VS^xm&G6bx+9+PwYrpUP3vgAFzE6FR0v-;eOY^~oY3k1Q~e=p5^SFcW9D_SwK%VEO*XyGZQ@#xQ4 zuWR=-pEZTE{kT3z@EdrXD+TE_e7Q+%>!!=Z!+Q^m>${nVR@wdy%)EcHs3z9Q9pZ78 zIV?8FJD6U}&)(Cs09$WMWw-3yEe#|6EjOds=~m{4bgm3b4R)q<4UL+aGGBU{WLYq* zw+d?H%%)uC>@yO+F-rzUgv2Q}NZM0CpRg7uqpUfDQaEzo@YzCwI|E~(0zYi#;ZNiA z^5gu;1k%K75$eYwuYW(M=d39YZR%P?SSu?}<1r$jjr}vLSa^JWX!J-X?X%ZqsMqU* zs<^aPv6psv-#-MptZCstRVU^}jhGR?wGJUB z=~ihpS$RMj(z5X8ZtC__D*H;}eh=KT;vAEG63arny>K)$e6TohFj~?a?=d+Hk((`-yb@p5kId-c~5QO#k?O$MZg(SAQA@~MJV|HLxQDMp^^72HWT_{iHHdU$|= zfL(u5os@>Pq{?I;!~`~mjyC4XKm>leIUBX;$S zQN8HtpO8kvMe5;k>zh1YLy>K$gRw5A3v!Sa&hHIz+g-fIKYm9%c-2$!SmN22x?@Rooq@+Nj{kX_ZYWm2uNP#(t zrRPXanx*p699`Zmh7W#5ClpWWpbySk3Nwi0RSOs@_So;mhoLrR0BqcZZp^z5M3hfz zK}n6NP}r%>`Vwg&v7x2G4o-ODGsfxRs@XG6#OenZFT9vD)J<7TUAaNLB;9LR1f2ya z&RXjhK{{W|r8IxDasR`}@u%_PU}fE&n=z1w>2@oE|cb6ts@=BK{ zUG$3ZTiMz3?{u!UN@!zz0EQTS^4b8>bk<;zE>G0|F&{g_7qH9tavK9XKOPPcJ6Kvj zI{VP^xm!MDnxnLN`~m+EmEG6xT}Z>p4nnUM8^M2}VR0UEp@Kdzz(q^RYLK~oG%YQz z97PovYf|8;8%QwbBzt@Sm{JhoY}F%<)YJx5WzBd?qI|Jx)^#ibL+j`0;hTVOS$E8= zx1lL7qj+ggb6QH0bzvrX3duM;MUg#%4+KrIwKu%EU-goqpvi$Z1QztE_e3(2&Z(F< zscFq#R%B#8azv3)S#;c%|G7@Bzlp0&{sRHZ6PIa<8BSVi=?JK)p7U9&&i66FeVOL5 z9$F)z^ks;fF7Q>vK##+|OZb_L9+mnJ6k1W~zIp0jitIr6wE8YoZ0q#2Cv&vL-{q&2 zj_N@-PJ@|TArA!6qxwoK?Z2yva+UQ}{2Z62W8zAh)wXZSTH(pgn(GxoWYS=I%EA5}LpSc&Yw~3Lb7%ce zG>C#X%q{HjwuJ7?-XgZeNzY??o2!@#+sDA$!TQlP<(Xmdj_Kz0dHAh>Jsux)w@KTZ zan>E4u+y8=2pu*C-q$?iE;OMr+puLNXy@9WMeK7rfu;d34=@+68VYEFS4G5@(1gI) zX6Cb7L|?TV-R0-bis?5sQU8RKPw@C*=`IXHtvo1+Z2SDPdbYck)uDO1aISpvg2El& z7xFhRT&@xaJIzgiw5bo;+5bM$2Po?0{J;WfEeVp6laT_0#Q@Tpml&)c`qFZ#76asV zmT<6PKwt<623CMTBxN8XGBP5UZboQlErcHuD5|9hmH~rh{)3B!55mg}=?s+CLAd)O zFOynmTTAKqySqCfJU#!)ZQ@j9TOr*N944CO|fZ_A6Pg5rurn4d@fi~ z(P*5`b^hDQ1vnOpbw53?!?xRet)kNqYR|&E9z)FodYCbTx~4O-PCw-*r%{=OArMsE z?U!w0<%{d0cFQyVdm5VuubK*SkE^8g-VGjW1A0YSzWAL3FpTg zz8+E0V|1YH(S!hj+8ylv__;9a_s)*$G-ILt!D8{pe`s+EF#k!zW%!inGhbpB88gli1HSQ3+9LyyE?tfV@Feq3S1l53npmLg;3i8@oDlp*x?{k^x zUxbT5*uUo;|6$-EG-==thqLtV?#~CKMnm;HaFr}s)6Ev53(Qqq@_|WIQWcBmk4o zq3H3RKmlkRgyFt0FuW5~CTDo7z6vj;g?N#D7-WO?-r;0HCia#~ste4~%D+>t$=tt} zBqp!k(eTK%iEa#F)HvMtjp`O@+);C0Bgd+yEE%EJGm4@qxYjd2ZKk(}2!JO14s|9rV~*vFJO4$kSj+${e+7_co=JR<+M$c8%2my;(|&^wxlSN6v<5 zPivB)GIqxa zPWbBCN(JpI-3(NbJTbEUwtIsbOW$JboOy~RnvJZZt`wDTZ=E$?;GWhd-a6xI(R zHTwk2K3?cZ^x60>G0utI8Y{ntm$z}+NPn2IRWbjXWMpc`a>bURuN}HF(~cUndh;Yl zFeq+s-hZ4~cRN~W@Hr;5#{x!BrfdrrRWb{>vpFwbw2^2=x>+%ARqM6h64=ZYWYN07 zT5VZh;56GJtaJmr{2>^gN#OF}wTPHg`n2yaKGJLFm9cduem;3aGTv)%bNSQ2tIUTY zYa_TFb>IS#;tB4Wt;kEFUC+?PHbJxUB-gOAbJ68dtsEqMcE Date: Sun, 20 Mar 2022 21:58:29 -0400 Subject: [PATCH 098/116] minor documentaion fixes --- INSTALL.md | 4 ++-- gtsam/nonlinear/LevenbergMarquardtParams.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/INSTALL.md b/INSTALL.md index 965246304..1edccd3cd 100644 --- a/INSTALL.md +++ b/INSTALL.md @@ -13,7 +13,7 @@ $ make install ## Important Installation Notes 1. GTSAM requires the following libraries to be installed on your system: - - BOOST version 1.65 or greater (install through Linux repositories or MacPorts). Please see [Boost Notes](#boost-notes). + - BOOST version 1.65 or greater (install through Linux repositories or MacPorts). Please see [Boost Notes](#boost-notes) for version recommendations based on your compiler. - Cmake version 3.0 or higher - Support for XCode 4.3 command line tools on Mac requires CMake 2.8.8 or higher @@ -72,7 +72,7 @@ execute commands as follows for an out-of-source build: Versions of Boost prior to 1.65 have a known bug that prevents proper "deep" serialization of objects, which means that objects encapsulated inside other objects don't get serialized. This is particularly seen when using `clang` as the C++ compiler. -For this reason we require Boost>=1.65, and recommend installing it through alternative channels when it is not available through your operating system's primary package manager. +For this reason we recommend Boost>=1.65, and recommend installing it through alternative channels when it is not available through your operating system's primary package manager. ## Known Issues diff --git a/gtsam/nonlinear/LevenbergMarquardtParams.h b/gtsam/nonlinear/LevenbergMarquardtParams.h index 1e2c6e395..f40443457 100644 --- a/gtsam/nonlinear/LevenbergMarquardtParams.h +++ b/gtsam/nonlinear/LevenbergMarquardtParams.h @@ -35,7 +35,7 @@ class LevenbergMarquardtOptimizer; class GTSAM_EXPORT LevenbergMarquardtParams: public NonlinearOptimizerParams { public: - /** See LevenbergMarquardtParams::lmVerbosity */ + /** See LevenbergMarquardtParams::verbosityLM */ enum VerbosityLM { SILENT = 0, SUMMARY, TERMINATION, LAMBDA, TRYLAMBDA, TRYCONFIG, DAMPED, TRYDELTA }; From ea30bc35d52e6c826ee1f2949bce785fd5505d44 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 20 Mar 2022 22:01:12 -0400 Subject: [PATCH 099/116] Squashed 'wrap/' changes from 56e7c0c81..24da9d1be 24da9d1be Merge pull request #146 from borglab/fix/matlab 3101236fe fix missing semi-colon for class forward declaration e933e14a0 add missing boost header git-subtree-dir: wrap git-subtree-split: 24da9d1be2b26ecf9abbfd9153b24fbdcf007f4e --- gtwrap/pybind_wrapper.py | 4 ++-- matlab.h | 9 +++++---- tests/expected/python/class_pybind.cpp | 2 +- tests/fixtures/inheritance.i | 1 - 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 1a3f10bf5..31d8d4444 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -412,7 +412,7 @@ class PybindWrapper: def wrap_instantiated_declaration( self, instantiated_decl: instantiator.InstantiatedDeclaration): - """Wrap the class.""" + """Wrap the forward declaration.""" module_var = self._gen_module_var(instantiated_decl.namespaces()) cpp_class = instantiated_decl.to_cpp() if cpp_class in self.ignore_classes: @@ -420,7 +420,7 @@ class PybindWrapper: res = ( '\n py::class_<{cpp_class}, ' - '{shared_ptr_type}::shared_ptr<{cpp_class}>>({module_var}, "{class_name}")' + '{shared_ptr_type}::shared_ptr<{cpp_class}>>({module_var}, "{class_name}");' ).format(shared_ptr_type=('boost' if self.use_boost else 'std'), cpp_class=cpp_class, class_name=instantiated_decl.name, diff --git a/matlab.h b/matlab.h index fbed0b2e2..645ba8edf 100644 --- a/matlab.h +++ b/matlab.h @@ -37,15 +37,16 @@ extern "C" { #include } -#include +#include #include +#include #include -#include -#include -#include #include +#include #include +#include +#include using namespace std; using namespace boost; // not usual, but for conciseness of generated code diff --git a/tests/expected/python/class_pybind.cpp b/tests/expected/python/class_pybind.cpp index fd5398912..95171def4 100644 --- a/tests/expected/python/class_pybind.cpp +++ b/tests/expected/python/class_pybind.cpp @@ -105,7 +105,7 @@ PYBIND11_MODULE(class_py, m_) { return redirect.str(); }, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter); - py::class_, std::shared_ptr>>(m_, "SuperCoolFactorPose3") + py::class_, std::shared_ptr>>(m_, "SuperCoolFactorPose3"); #include "python/specializations.h" diff --git a/tests/fixtures/inheritance.i b/tests/fixtures/inheritance.i index e63f8e689..a3b64ed4b 100644 --- a/tests/fixtures/inheritance.i +++ b/tests/fixtures/inheritance.i @@ -1,6 +1,5 @@ // A base class virtual class MyBase { - }; // A templated class From a8e48d674c9a38a8bc721c55cabbecbd25fc918f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 20 Mar 2022 22:17:47 -0400 Subject: [PATCH 100/116] fix matlab wrapping for gtsam_unstable --- matlab/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/matlab/CMakeLists.txt b/matlab/CMakeLists.txt index 1755e2075..a657c6be7 100644 --- a/matlab/CMakeLists.txt +++ b/matlab/CMakeLists.txt @@ -92,8 +92,8 @@ if(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX) endif() # Wrap - matlab_wrap(${GTSAM_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i "gtsam" "" - "${mexFlags}" "${ignore}") + matlab_wrap(${GTSAM_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i "gtsam_unstable" + "${GTSAM_ADDITIONAL_LIBRARIES}" "" "${mexFlags}" "${ignore}") endif(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX) # Record the root dir for gtsam - needed during external builds, e.g., ROS From 17237becb46e5e0ee12855f3cfb5f85d1b49c72d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 11:58:06 -0400 Subject: [PATCH 101/116] print parents when printing GaussianConditional --- gtsam/linear/GaussianConditional.cpp | 10 +++-- gtsam/linear/GaussianConditional.h | 4 +- .../linear/tests/testGaussianConditional.cpp | 38 +++++++++++++++++++ 3 files changed, 47 insertions(+), 5 deletions(-) diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index cf3f78b73..8d616443a 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -89,11 +89,15 @@ namespace gtsam { /* ************************************************************************ */ void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const { - cout << s << " Conditional density "; + cout << s << "Conditional density ["; for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { - cout << (boost::format("[%1%]")%(formatter(*it))).str() << " "; + cout << (boost::format("%1%")%(formatter(*it))).str() << " "; } - cout << endl; + cout << "|"; + for (const_iterator it = beginParents(); it != endParents(); ++it) { + cout << " " << (boost::format("%1%")%(formatter(*it))).str(); + } + cout << "]" << endl; cout << formatMatrixIndented(" R = ", R()) << endl; for (const_iterator it = beginParents() ; it != endParents() ; ++it) { cout << formatMatrixIndented((boost::format(" S[%1%] = ")%(formatter(*it))).str(), getA(it)) diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index 6dd278536..e8aae4c31 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -109,8 +109,8 @@ namespace gtsam { /// @{ /** print */ - void print(const std::string& = "GaussianConditional", - const KeyFormatter& formatter = DefaultKeyFormatter) const override; + void print(const std::string& = "", const KeyFormatter& formatter = + DefaultKeyFormatter) const override; /** equals function */ bool equals(const GaussianFactor&cg, double tol = 1e-9) const override; diff --git a/gtsam/linear/tests/testGaussianConditional.cpp b/gtsam/linear/tests/testGaussianConditional.cpp index 8525cf9e0..52771960a 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -40,6 +40,7 @@ using namespace gtsam; using namespace std; using namespace boost::assign; using symbol_shorthand::X; +using symbol_shorthand::Y; static const double tol = 1e-5; @@ -396,6 +397,43 @@ TEST(GaussianConditional, sample) { // EXPECT(assert_equal(Vector2(31.0111856, 64.9850775), actual2[X(0)], 1e-5)); } +/* ************************************************************************* */ +TEST(GaussianConditional, Print) { + Matrix A1 = (Matrix(2, 2) << 1., 2., 3., 4.).finished(); + Matrix A2 = (Matrix(2, 2) << 5., 6., 7., 8.).finished(); + const Vector2 b(20, 40); + const double sigma = 3; + + auto conditional = + GaussianConditional::FromMeanAndStddev(X(0), A1, X(1), b, sigma); + + // Test printing for single parent. + std::string expected = + "Conditional density [x0 | x1]\n" + " R = [ 1 0 ]\n" + " [ 0 1 ]\n" + " S[x1] = [ -1 -2 ]\n" + " [ -3 -4 ]\n" + " d = [ 20 40 ]\n" + "isotropic dim=2 sigma=3\n"; + EXPECT(assert_print_equal(expected, conditional)); + + // Test printing for multiple parents. + auto conditional2 = GaussianConditional::FromMeanAndStddev(X(0), A1, Y(0), A2, + Y(1), b, sigma); + std::string expected2 = + "Conditional density [x0 | y0 y1]\n" + " R = [ 1 0 ]\n" + " [ 0 1 ]\n" + " S[y0] = [ -1 -2 ]\n" + " [ -3 -4 ]\n" + " S[y1] = [ -5 -6 ]\n" + " [ -7 -8 ]\n" + " d = [ 20 40 ]\n" + "isotropic dim=2 sigma=3\n"; + EXPECT(assert_print_equal(expected2, conditional2)); +} + /* ************************************************************************* */ int main() { TestResult tr; From 476eb9c0607f7884529ca10502972b0dbe15b72e Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Thu, 24 Mar 2022 13:23:10 -0400 Subject: [PATCH 102/116] Addressed comments --- doc/gtsam.lyx | 98 +++++++++++++++++++++++++++++++++++++++++--------- doc/gtsam.pdf | Bin 1620931 -> 1621850 bytes 2 files changed, 81 insertions(+), 17 deletions(-) diff --git a/doc/gtsam.lyx b/doc/gtsam.lyx index 482aaac25..705a84911 100644 --- a/doc/gtsam.lyx +++ b/doc/gtsam.lyx @@ -150,18 +150,14 @@ filename "common_macros.tex" \end_layout -\begin_layout Section* -Overview -\end_layout - -\begin_layout Standard +\begin_layout Abstract In this document I provide a hands-on introduction to both factor graphs and GTSAM. This is an updated version from the 2012 TR that is tailored to our GTSAM 4.0 library and beyond. \end_layout -\begin_layout Standard +\begin_layout Abstract \series bold Factor graphs @@ -202,7 +198,7 @@ ts or prior knowledge. robotics and vision. \end_layout -\begin_layout Standard +\begin_layout Abstract The GTSAM toolbox (GTSAM stands for \begin_inset Quotes eld \end_inset @@ -223,7 +219,7 @@ Georgia Tech Smoothing and Mapping y. \end_layout -\begin_layout Standard +\begin_layout Abstract GTSAM exploits sparsity to be computationally efficient. Typically measurements only provide information on the relationship between a handful of variables, and hence the resulting factor graph will be sparsely @@ -234,8 +230,11 @@ l complexity. GTSAM provides iterative methods that are quite efficient regardless. \end_layout -\begin_layout Standard -You can download the latest version of GTSAM from GitHub at +\begin_layout Abstract +You can download the latest version of GTSAM from GitHub at +\end_layout + +\begin_layout Abstract \begin_inset Flex URL status open @@ -1365,14 +1364,18 @@ where \end_inset is the measurement, -\begin_inset Formula $q$ +\begin_inset Formula $q\in SE(2)$ \end_inset is the unknown variable, \begin_inset Formula $h(q)$ \end_inset - is a (possibly nonlinear) measurement function, and + is a +\series bold +measurement function +\series default +, and \begin_inset Formula $\Sigma$ \end_inset @@ -1633,7 +1636,7 @@ Many of our users, when attempting to create a custom factor, are initially \begin_inset Formula $2\times3$ \end_inset - diagonal matrix. + identity matrix. This \emph on would @@ -1647,7 +1650,7 @@ would such that \begin_inset Formula \[ -h(qe^{\hat{\xi}})\approx h(q)+H\xi +h(q\exp\hat{\xi})\approx h(q)+H\xi \] \end_inset @@ -1664,7 +1667,8 @@ where \series bold exponential map \series default - for the variable we want to update, In this case + for the variable we want to update. + In this case \begin_inset Formula $q\in SE(2)$ \end_inset @@ -1689,7 +1693,7 @@ The exponential map for \[ \exp\hat{\xi}\approx\left[\begin{array}{ccc} 1 & -\delta\theta & \delta x\\ -\delta\theta & 1 & \delta x\\ +\delta\theta & 1 & \delta y\\ 0 & 0 & 1 \end{array}\right] \] @@ -1709,7 +1713,7 @@ h(qe^{\hat{\xi}})\approx h\left(\left[\begin{array}{ccc} 0 & 0 & 1 \end{array}\right]\left[\begin{array}{ccc} 1 & -\delta\theta & \delta x\\ -\delta\theta & 1 & \delta x\\ +\delta\theta & 1 & \delta y\\ 0 & 0 & 1 \end{array}\right]\right)=\left[\begin{array}{c} q_{x}+\cos(q_{\theta})\delta x-\sin(q_{\theta})\delta y\\ @@ -1726,6 +1730,66 @@ which then explains the Jacobian . \end_layout +\begin_layout Standard +Lie groups are very relevant in the robotics context, and you can read more + here: +\end_layout + +\begin_layout Itemize +\begin_inset Flex URL +status open + +\begin_layout Plain Layout + +https://github.com/borglab/gtsam/blob/develop/doc/LieGroups.pdf +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Itemize +\begin_inset Flex URL +status open + +\begin_layout Plain Layout + +https://github.com/borglab/gtsam/blob/develop/doc/math.pdf +\end_layout + +\end_inset + + +\end_layout + +\begin_layout Standard +In some cases you want to go even beyond Lie groups to a looser concept, + +\series bold +manifolds +\series default +, because not all unknown variables behave like a group, e.g., the space of + 3D planes, 2D lines, directions in space, etc. + For manifolds we do not always have an exponential map, but we have a retractio +n that plays the same role. + Some of this is explained here: +\end_layout + +\begin_layout Itemize +\begin_inset Flex URL +status open + +\begin_layout Plain Layout + +https://gtsam.org/notes/GTSAM-Concepts.html +\end_layout + +\end_inset + + +\end_layout + \begin_layout Subsection Using Custom Factors \end_layout diff --git a/doc/gtsam.pdf b/doc/gtsam.pdf index 6ea916d338b236846093f357f0bde33e0222177c..961c808d00a94cbe33558131332d690db8878a81 100644 GIT binary patch delta 78725 zcma%jV{~O*(`{_qwrzB5c5K`BiPJ&HPRF)w+a0^(bnFgq`r-TD@4I8%e{1iv_BvIw z);hc9tQx2P!D#i(C{_@_#mP=2AOPd+;$&)Q3*!M?s43^XHiF!_tG*4jSVc4e2ZZ8X zUvFK_siw+dMAL|V2oxXt1&gfZu_o_jqQGg=e)Q)#wm%a2=Xe=Ncyq5VFFp5eyO;C# zllSwC5W?yH0R`EU;+1uKnD^>80?@IT%VHv=vP4st#K)hR?{3F{a?cV~l*nM)ayHn* zu}3K$#CgwCdiS^eYdyn|{jcwwf*zbVsy`rqwUuY20df;Y5H~r08LqYI|MJ^SzeriK zukuU%1$ap5_7J51Rlq1PBOJmr{z4Wl%%A-{p2^8QgWJ3^z1-4S@^JnT=DYMg!*3($ zyM)ALw;R~>iD-x>Al_m&+}7Gy7=8McEIlmJCV-T0Mk?V#u-z6wS4P8_Zg-HmF~{F; ztSv58k}wd1$uq&?dkqKRwz;mtLVIPl=XLil@6fd0K*YD?Z|!(se`V~WlLJR=Dn&&v z1KW<+ouQL_c5$6_xD4bhZ?XmoN$Y+YR!_3F_iF1>R>F9Ih0!po~=J7$9w~%;BvqhVYy};Y>@MfNHmz2j;K;~BOHhM z#_WI^$XAr#Y%98?SdQ*w*5rGb-8^~rGZZYNPXHZ!y~X*kbV$ntnwOq|tFSq)|CU1S zl^B~c8$E6yAoW!4^TlIu>WZzHs>O*UFat^5OTD%0n$M@D7Q>Vj)r}~uhV;meoO6k# zPXs-cs9|x|YWroQ8Qu@`mWUD>=uVr@Ufs~y_M!?R<0ds)g>(&IZHo!VqzY!rtX;>m z&iv;>mCYU|OD@QL8b0kmgCP4^*;}>-TQpmzXn~S=0d99iB~W`1;#fW~Z(KL<@*3)@ zLNKP-vuK=K?54FV`_C5}snL0-^AnY3`d^oLR__qrM&&G?mA^q%OCUZzMQVRb7sI0& zh@n<|^}kR%x36s+yPWvxKO9(TtRv&dWQ~ArCtM>RzoaP&TKD^ldQ9$rh5$#CWrN&mBp>qa4{_d>?Cu0LF zWDFU2rzAxiv9XEA4Cycg!L6;I{tRzA+`}5?M&^28B>?>JjGy)kF5h?;{f^}F5*7&%yN%G$Hzg!* zQ;7_V7>ZNKkr^1gQ4ji(ug0RE4`@B)DpUatV5w+2JQ^f+1R@6^n|=QA)1Tcbt&x*8 zdr6K4NBlgkHTtjQW7akk$i^q;nO-BF(tpgLRbEneaWI3-VV$pCFlN=>CG5-qiS&bvTA^fo{>}F{h70{G^4Ht2{tVB(a~CaMa7s;ng$8aEq7H8q^M; z<+8eDn)Z#Je2!V;V@T>v!ERkoGypTY;<~aft(C&?V1G6E#f-}9*SOR43+9|)J1l|M zyS6^2D4t1mCA^vf6!Z+z`{04e1KdPIk-4$Wb_2!Zad^N72KvXIABPyIzRzh2S3>SD zJm@nm-VXFYGUiuD%A#a4PYY=&q2plyR6*JDI)+I;1xR|VARHuav@59izQeHHkBYK^ zhK^!<{a`$K!Gc2r+Dlr44Ii(uL~* z%uun+F^kG18Lb%zSCAwPL?;QdXBnwcpaz%w1BJi=Q#-F(sK!M~D#HsXiqK)ePB2un zDz;uh`A;iV*!})xN?vJE1VQcC7Wm9mQ~SpN&+V-X*e75@l=Wn8Mu@BZiR=VDI!e*$ zyQ)wayxM-h=xf6X<*s+6@r1K=!>r75!Ehk{n0`^z+J03(T3AVj^4^X*-u^N|lyA^SDM_$Bj4bqG~*2>wxE(_UB zw3BD|5R}K*o`{wQ)-1XO&_%&-Y#t5w;^X2c*Xc!KSjafpjYvpl9@y0w5SqpgelvpF3FMz zf~x7~bA$2t<7>>+O|kcY!nP*FxuPLYjvebua^hiyQP%B>JTnYCK+hLv`G%S9I@yEs zy2nLU2P}-5TsEIj>*(bCjc8S5m~<-i2ggc=xFe30#WOL!xv*IsFh&F4C$e1p$N()g z74<}{5J`C}j79^tEgNZ^I_rEW3dT>UV(JzFJUx%oWhZo@d2CS=QhhsCx;{2-B*TsZ z#EpK(h#ux_=Z=V+fGC@GjfFdNX&X&~3qNYO(1VWZpKE207ZVZ-oZHrl7j17xI;d3% zMo=xhZ40o@2$&73MIy#ULK)I%D5X0)ELhGHiVa z0j48~UXK!dD8lU9da5Ldr68MWsax-hX} z{9g&FcU+@YCwr?WkJsea`J>I@?&%(Cf^*qSTj(UFCxaFbaaFL>^L|)2uc08t?x4e9 zfv2c>5ZnN1Il}_2-=aqf5u=D$m=;YE6#9KazC?JR2#AE)XK;vHZ(6P%1u72nFT|iP zGc?}3f7;HU18_~$EGSOa_YPAmp-B^V6oW_XsT9ma#+@`k||@tAd{PuCOgH;)i~}^9yIL{#@UH_D4s(Jbb)9K z9|zn9|H|YcR)dVFj>=5~L@r90N#$oWtSuHSlfXA&An~`(<5Fn1M6!T?IxWpd` zHFixJmlg)urG4cGRwkrRiZ?MLPp~NbYKk8v9iynP{~=UvefD`4+0fW_I~mBK2)S)+ z$!t*$2cl1)hTt9SaelJOo#`yv0r9q7l){`>1G?v^WA!!6Gz`p=~KpO8QEkm)?0_El7TcZ|5LDi29KOD zs`;Zq#55gZ7c8We&co6>D9~kYZvrtRYQi~80}i8#CmReG5fhQ}N4otx<2JQ3u{W}U zVP;A&{7DI5=H_DhuRQ!rd)#e}18L)iwx$467#e9izkMKlzCrD#W{%FOEyt9{j3yjG ztkF@hX=|=G5;2YmTUyQuhtQrZK9Fdg*ZmxBJLU-e>B|dLEt2!VD-gKjmk6{@G29lR zSV#aEK@VB%v|>#DJ`TSgQD4n82%s!$rdlKdq=jHOw_YQk5W^i!prb|n+_H;$Uapm2 zC=&7LSlI8UZ_qFof(6m=BBP-N!627O1OF}WUOXxrY1Sd}!zq|j^ty@W0k}>9UKKxW z{2K1#k2D27Lc1r*Blm_!&8fcDcgp)|5(BQl04>4G%-uOFjGGr4UDJ#QGXO;O&3Ff! z{efrNKJFF6?F&+C1vCCy1h3U#`+PVE9&0F9q$66t^f)`E)uf>zm6{A`a&CHJe)4{G zMF+EUpegCS>8=B8f4)w|(_yqV%YA{OL%oeRFs&$ zi8nXvdez?HD-zQ30s}fG=?Dxy@S|YvM!BalidlX*lQ1rtf%j?;B47z3#yDp9%#j@V zlRF!--y|oiq?)BN`2=ROY17mj#Gs<5^bC0dcBFUovyJ1G1w!^g>=W+{U@^%)gK{|b zrEA|kD9F&XHVk@)zXrrq*5^Wv)`K+v-n5H;o}`?9_GZ#mt02P^MuCaJ@nyBnOCd+o zz7h2e>-=l+`q5ES1i+E}2B)eCuYHFIzJfFe-3)m6d*of}s;P(xZ2+ctr76$!jcFYV zF}xLF0#Yz9jv;^Lk3whoU4kN^lt{mRudWrc!A#;^KDnlL5?v8?0|s{IS&VNIqJ=-7 zd_3CGun-@a#=9iHL>*+Jr>496&Opr|x_p~BTrMsk6%?q#KLjM)X3O`B@;l9l0^DE(rCOyK10E!g4XksY0Dmwj#^23 zvK~@lPUQBgfddeXwHLtdht0{S=+H>&0f$&25=4DPis*c_+Q@5MH(2=W%$O?(DHCfy zAL(2|@-0n)AMu3}I3Dhe#(HSJY%hrNN1P?%VkXjJ4auRWpY`0#F%71CfmeoolWCku zoea0}Z7+s8`MC#p-CVv=mbhiM=O=$)@HzzBZOC@iPm}=fZs;+brh=rzu?(2!U!)t$ z8s7xHY@n|2v=#^1*MWv8>eM2{-XC*8pFF=l<9LEA@`|++fnuga$&BChbz*e_PrUDFE!>x^->{Xy;Nv@eamBg)*uTyF25- z;I`4Z{~1^~hm0tw*qC7Xu;`Fo ze-|Ow9Isjzf7HYpQ84K*RqM1A3&CeK5p>@Z&*6Hp2kwEe(DEu~YaS$ryjJfXC|#Gk zHll~={&U=iyv=MTc||+N@K^JteW1Tace!}sT=Fp^g{)0BdC^oV(jz-JT7>tUIAV1k zHRUpZbOQwf$IidgiN!z_9d>Fk89qGrS)lUXF3V4Pv6=SRS}g2ANIX<-O+YBxFx<=0 zg?ivI_h|=m88(mLwS-?u4C%6?d}R$4t(RnPuuM9XU8+TaGWa_u?$6=$)Z76Bg4)G` zMir`_D3zmKMYKLof9S>B5LgnhDdV&ofks$Bpt3Zl7Q>iPGo8CK5ngkdb9JN9_s+)y zN3z-UTw@;Qhsm#>it-&yEV`k=_WiT8A#g_oage>cG%+Zn6`5Pf6IC*jF@N$g+T*Bd zk{(YctZBPK-q(UidZWE;xeUY5!jwZ7ugKnfsw}B-uF=jj=f_+tcFHn4K{EeQvvPI@ zpwS+ibV|$4m*kOsY=yt~|J6uX@RI;%&Mcq?h&86Mg_LsPGS#8xydOb6y;n58t`ECx zvAm+Tzp1(K0+q|-UUxqf0^{>I_E&LjFI_K>G#Q^j%_S7^uU+Wh+M$WK>d&eWVlmZ! z@zC!N(Wr>h|9oiVU#fLk=83+oL}f`q2HcMY$YXw$-a+@FkaSIxLEJJUC+qokdzE(| z=-V+Fc5;#LNAa1a*(%U!dXs8W zt_&+#M)(hO+TpAs*GSGl=Fq$z$gj4Xq;edT&x`RBN+QA zFzYhwevg7&k6QeH3__MPlf<6bN;!SiYEsQ^PjoKN7}(j#LWHoeJ&yvroYF` zOhha!e_wDDvHWFJ*}#~IKJFQ^qGEjv z{xJFXH~pI)v9SKN0#m{fBR(+OU#ry9F};AKVELoLC7cdY|Gfx02Fo9w{`V5BO!ZN$ zDKL~QzrFgMa%mGWN{NUF8#zmT&NvHlY~cA|e{`ga^*KAzwp`ZvDJ97L@D z1o&e*+dmOzBl>5dkLhfG2Kb*qVj8=^{Enp5M*LAj{g@RF#m4sj}hBH5dJ4R|FM}r;7Cw# z$3XuBpWi6{djbRm5<1+lQs56k@W5C(nc3^>+=CDZJUi>2V%{O?z4Q70HxH0skueek zlW?f+j- z>~G^)i2mI_{{;89Q~y8P;m^GU`$0y2Kfw*d#+l&k&Ie#+=l(Ae(y6`Xv^Ip@HT*fJ zGmwHjYGZI#jzKFXL#oJfS8Lu4XCEY&D2+jE49s#ovrBEOdaIk#z>$awWy*vCg8CF7 z@IH?ChWj4G=p;DRH=rPTQY?0GLGw=d1_3be3x3DagVLng+EMz!NcbYC_w1(;8nccUCyw!mQJ3=X9rYI@ z?u0&naQ$_8y&tpI_JdQMvgQIG5a)tYY=|<*e{Tjx0aHq1dQ{iv3#Zw_DGbkD{n>*`|fFUXqs zt^=R(5uSm2`vk)#EBPCFM+}G@7uN0!yH^9NMyU!mY8a8@>Y08(Wl7U%k%yzmT)OP* zcMIZdvTd``u>>2yG(IWq0W4D;9C9t~B?lnT@e zx7NYb1){x$Tmrwik14$$dG3+UA?sEdbS+S76JAPmN>>+i!0Y zfE?sQ^h9w7(vF~}%ap4h5gy`+ZS;mnfx-^Or(EpeUCrQdsO;2 z(1#~A{^rHJl77AMe+DL_s9+GHE$@*r@%s zO=VYU{c^A5ECg5bNa;tV94j?fn@+xp@lG1itMpQ-D>YJs7?G)cJF$gwp-07YcUmxr zkVE+^`JQqoDZoa#==+zZS-uqa*th~%#!8OyvvbFG+K2MVPEU~^0)nA&1@R!d(Z?4! zN|hW$NND4$p2WeILG2s&z+aT;;|CV6k@W>tOnsMC5f{u5wVziq?CwjK&da~nH)$RD3fqss*fX+N-@Qfh6;NCN%a?i%`q+ zFI0xnJkJ$V2tV{w7l_9x^fBmP)8@{eF_5pd*uzN=y5;`jiHGrpP)oC_8k`AxR|Yj{ z-y%{Z6lvHn7=SN`U{@~Jxth<_pyr4|d#e_(;N_Rrcl{&b4wmmGhVaIRhd1smLwqDhu{%7*m?$-| z8?hr=Vu^RnA~sdz5y{boB^e*QzD;qDMX4p~JHRod&)9@t3Vf>F&42OJGsOBN8=CL^1!WLrO9jl6XVDP=Lm|}ri&0w@BEk1WT59#= zEz^p3MD`AK(*sbl50|>Bc4Pd@L>IQO$Yu%vZe&QkhVjIU7oC@TtQiZO_^X;j1)FvP zKHBTHd%ZD2WHfYy?-m4& zo2xUX?8^U1bE@O`#;jelLOmm5U9S^(^A>fkU)mSGhlODe%a_okwlX-xvg4b{Hklrv z7C)NIW}ZmXj*tM+TQiP^gn@d2m{bpqnA4m3APs)Ic|W&m_73UQX=HA(>X$P6=Ueln z*S(DA4I$|-UZS!$Cw|=h) zX9mPQXKS4*+v-Ys4}N2bM3J^fdpmvyx#GN8deb&PlcubTG7=9~rb>~~a~19+OhZ*H zktT~0Yd|C5QmkPrbQQ;x2;659k2??*QGpDZRE19VY0yWOtrc>#jQtu))z4)Fa7#8U znB@s*A`+vx_*@uwL<+B261pluHGzB&Xa?hNz><(iW+m2Nh&d`q;JV?)80tLJoLN2S z@K9w1XwJ{Za{Roz=AyB8fUKT9`Ua0)ntnbQIa*O!o+F^5q7Ju<$JK0<3;R4NWOqUl z5vX(tCytrFhXu-rziYG2EUpX!Xdgvh-O(H?uJF)Wh<7B5cI5QhK3q=Vz6L*oRtK8< zE*t2IVRu1fpdh?5pGXeBb+F9PskF;HCF+NsHN*i+i`e;vdK3IR|btx;a{| zf$1MZjNb6v@1o!dw#aS?2ra8TM1EU!9!LEQeMu@|BIevGv8{zl&#};u(4#aQ>6%=US#}12) zr_4EAO$ib<+Hi#4R4YHbLJE=wn!y<9#Rp4njW3(ljbVm2N7b2l?Q(I9+I$?!y~BwO zg#iLJjgd;D<~uAl#0JAQ!Ev=2lYBrZM_=BQSfS@9hAwC<-3mp|)bEadAkp0Ef;O4D zD#_(m&g}wQdb=7#fOhu)TwT2CE{C0xk-A=;-R`?1j0Q^^+bV7^unpFE331%M(G%EL zTchd+WUevx=4R z*kJtjAD=QS{2s|vVF#}(7qLH$J53U$YdU=eT?uXCb_RS6>K$n2{Dtcf zEC<bmAXEMQBXImT-wH3m! z(*aYr5?djL%W33L*(3~W=hzbXLu%s|<^&rW~yDzN1Ws@|m zaX5#6TpZ7U@}2RmEaka+0dwd2s&;{^8EmW2PUJ@wa{4Dv!}L>EhgV7+m-Y&%k{&(Bz|v;c@|k`MfWm(7mH!E~5i)vf(LZi^Dji2Cz*&6P9MG zYD=!Qz>o8eCoXQ7SvfyKZe|=q$FG)O<}6TCaZLD%tS{k-_59O38VxkZlcO~RSLTS! z+Pv)nB`ZWtHq^}8I)S(LjeUZr6ijOYtO)JE%V@72;H;WKI?q->m1(n+8SkJ4YTX10f}xG%|IPRQ zrq_((A4<<3wELqT^ub53lF-@yC&mAhmHjV__7CF6M8wYao5=G0L-hY8vj0y4_}`ic zJI4o2r>bvAoq-?aYp?GLk=iP-;u>Nn|*}|UN+Xz+cB&CO@_5ph=?X4ycHSY7C#LiHBcGFSz?Pq#x{4qM`G8FHJ z^?T}MktpP|${GAn7|V`pMztCh?&zi2@mmyvt@byB+Jieb9{z^>MYb^SsZeWEv*WA>psa?J~te{9!yG=J(F}I z>Bi&tw`||sn>RZ9x9WPbyS@0b?jK&3IMu`H;`gn5R|%ulM=vlr-(x#EW<9b*ils7? zlW}mLkw?(JN+(sI21RKwv2<@5a)b=0Y;ATtWn2INRquTT*$*)<{a&V7z0E)S&0JSo z2;rJwqlWEc+81_M-*4|}kTnqV?Xo;}{kk^rn#>#tCr;Rd7tjMhXn19Xhy+kj48bHAap&+>(xB`XFPlV;XE-zIR|Rt1nQ&<`Pn zLBw@i0NYw;>zbasS{D~1M}HD(b~4T6O>Z7x>*Ap~7#n(Y_)Lm1L%@3dsK2>0844^z5=p;uC&Rn#jMD$YGWXE>RSKY+K_Q55!$JI$K)|U znO%H_D~kzJT9T#Sz2%P*-@EZ&37>pZ0;CG0WlE~ATx|sSCo)aI-uYx?m}C%WRjAY? z7aQo_`5>5x%zRfxLU8TE19Vg@lY{m?bxuVRG=IU^r&E>7^f_JDT0twFU_xUd5iOmh z*W7sq3vI-Rq-&MY(=|XK&nKh3gi-SVbo&RGG59-X4O@_|f$o!=>ZjtPzmq^X!7B%Q zz?@tfCDJBwcoH(rlZd}dDyQW^e-R3Pi)#$_+2`*;*e{1N`tGU~&PW0-mzk`ZJ)y8@ zE0X+KGwFck%e751?R-(-3guNDVN$GR7IIpzS6*$Pw&qtRZRsgs49hf`MI*TmK$TLS zJnYe%zh4w_sLk9ruy(0(wJVk}fE)LCFQtO@<9=7IfmxPqj5ro(35|!cfWZM*OF)Vh zT#^Var*BV`W7LNx6trEY04vTdY+M2&U3K!)G|VY@h{&D%vmy>1VV~30@IwaZ%d|}R zIuiL9flbkXjk?7My0D35NGEPT06X_sO#;ys;Xxl#EnXmg&7S|Q3UPz^yPhImwDmTp z+L!XPy-Gy>d182wWb8mYr>V&@E)RpleMZXWUg4>^iW1YF(tM(Bm&BjM?17|$S#`n!Ilfu0ltQ12>L{GaJFl=F^L!K z!CL~76Xxu+xozZm+_Vp{Y=>NvFWDi|@TWuef6URYQ=)-@i((r%U!1XZRPvMWSwNYI zdgEhZ7vndnMpR_?f>NGM|E<;Vj71R7102j&u_7PIOdAX}PgxF<M{z_ax`e692_z>J zYdCR+6g%6_YY|bgkwt!?u@;MCFYNNXDVjGiOpUdbo^esozdY)%l8)C%~$(hwffd?1_$CLBxmS>VG+P*(@;2BS+G1Hwj zjm|_6nFb2ArN}r2cEiKXMZE^$_cP(DL3-4oO>$ZBUlY&+suS*vOJ>8r%J5F{>2scXlFC#Q?6(C6~qQt%^lK zKeqK|o^=BD6~$?d^Q|lnQJUA8*L#m*xnS%cW=v$?_4^*$H{z2t0#YVR*5KEB6TCf| z1uLTf*sb4sxP3&#-U4zRrafL9xLuu1UV~3S-FVEjXdxcHDo!ev;7NF{-a&yfh-xLx zG!xL<#QFZxM{c0HZun%i0LiBxm)(n1sye_gU?8z)DMk<~3r+^Z#jiD?z9-aEFcN2J zm#&wELY#9BG;4ajc)(jZuf%}A(ZIg{IQ~l?K;$zjT~iu{YCq|oa={&6RKju(++G>J z4LBJqiM_*?;O?t}8YoPcLW}yZO>P`$)f9Gs2_;r;9FWONw=w(=5;)EjT+W;1%3D`ohDQT~i zWlt33e*6;5g7Zok&XJGW=s1HmS zsRRNv^Jm#)Q|y;JdnDG0JMBDXMUwJ-&)t$m)PhIE5GaoxRsWt*EU|4aEn!S2(3%T3 z(Xc+NphcKgof)LCRjmu4dRQUeh6Aakx+b|DM*wTo|6q zJEGWcJqI#r2_umD34T$utwMf4C(M83E8HkgK$vcxr0n-5!nn+_T<9|}fLi)$#PSmY z4+u|CTZXoq=T&*W^rFNk?kW+PIvOXgd?JNnD-UV4xb+s}0d-EAwSBplkM?(-6tW%SQ;&4hZz-pXQ`_qOILkZBarYaJ{0ZY53Q( zk6b~%*z;hLKU1JQlQ@OSq3w1gkx&J@ayw9!LpWfqB0g*lRCN*o$RougptY1fe{*<0 z7947_lnsdPQ9IHTq8Miw?=yq=M6jdWio_Kb(~CbrSVygHdi7T0D|p?EORf1VF&tm>M6mH%eQ8z4(EnkcaP5QB>du7RP-zq<4y@Z ztiCG$&6}qc&5J7}Ee`L*R4pjP zI{g5*>HJEK_FZcsr|3Bto||`16OJY-Ca+3*14h_Kx~$aVVF=k8+0Bjq0iluhiF3P& z77#u5lq;gnIbqm~Eh;}*SR-NwzR-G4{+qwbT;KJ zjG_mUL1dqY48WCZ7olTEm#9r)H9J2MPKkV_w-hVdJ+N>O+rXRWI`r6)-A2_ZD$oIO z%6^k)=1RqS@rg(Qod53Wx8EJwmSD{}!XlN$g zD9(JZ=Ti%nYl^47o;Jky$|wtazPzXxS!B+1hM7htkix#AjC-s6 zfe^scv?sQC=n-g8f|uRgmj59AEc69#V;yQDa%Lr#! z%Abvq(iR+*C0a;l&7Rb=WqWxBZtUd9HPV{Se4}L!Bvq3`zI!(66Co%=FufLS4@D{6DwzIM2!=$^uENd)0f)7I=cZez4I10c$_ot;Aq3P zM%}43%4bbThL0;p$dh2VdI%5NBt8#$%JvIzdLM=ysF8mxVwNZ&SCk-q02(tkq-yw=8P5td4jV%6Wk{d>{ch%?4l?!T>_U{46M-5`6 zIzL1XJ0Axvj+l$8Lfa?8i3#g=vtL0uMRcRuT&G{5vF^+rrhR)5Zaz}tevZDl9lj_4 zV%F6g_W4j-B1uasjMPb8a~i@`cZ`43e4oqV8rM{PwIP;MxM*>?&67X=Sll}O2N#KU zgL5B;7^d1@dW^;2Z0FyYbvqWI35e#vTeu5g4RgVjtmOW78&biICnY(@EE|&Xa;md< zJH`AZG8`ewAxd!$IIn}Xa51A|_MQ;H5e7Pyq9-qy02$9G#ONTX?Xu)f!=C$N-eUIP zCAI|z*lQ9=SK8x=9S8Z zjfm$e05*Rjbg9Nvp`$26w%^}YkIw(PH-lVO_$y9;ZEE8jrVjhvMOZ9nN%jw-@lG`vf{i@jbsu7RHfuhWqi_oV`6mn!`D z*;?{0^=8L11{B*~%2AACeJnM=g0mpAaN}#*Ib}4d8P~BX(8I!njXKrx%AlMGflt_@ zs%$d4y6#aHaX3IGoR-biGS%>16->^ia zGrIhk6ijH)xZTso%y1xoU386-JKEKSESJ}Ao6rLJ?pN@fi%ht|D%lA@C8PcsCU;h& zY{-(^rG*o_3L=%zScW$kif<8sifXJ)ABIDcZuyaW7~9NVq36x%$?r|D`MM$-Z)qOz zjZA1W55mT=p8dls-1f=+;l@_c>T$wppe<5x^ ze#O=Ak0N~+Qr%Hb+NAqure&Wg0Z|~vp+}i_sD}8J%$f12Tf2V)bplW zWzx15*{XZ>;IA^rkMr~fO;`+5$s%a;eQ;K+kWt4-NbVda;#NR)bxjoW%GtbtqGFFR z&!l5C;VM?xQW3gvZhCwCyCj@ZalU+xYbEQuqOH&3(@)@GJ-tvwHJHeRZ+u8k9?RU-% zx(*p!?pq9BVPpVj9CBVj=0q7#17WA4A?5z42;x{Blb(;;?bmtL*K7!(ZtCV;tH!}e zN_f+8n>NMQPG6BVkpw_YiJv#!qr!S$c|X$r7xNOn$Jllk`}|<4ZuwQG0KqtIVU-IQ z^0Lyj;jl>^Lc_TN+lyOZ-U4Hd!IRIwcfa9WOVtikiuvl8myly#S9=E<9Rm)urE(bZY$nS#s2}xv32<&$Z+6d)Kw8;A<)|yiVhxJC zDnuBcdYSTe6k%JyvSDqA(^W?p{)^NnrdJr8TWa{`Ra3s1crq4;XH+~4Ub3TI*#p)NQiC&D@c1iiCDE3*sxuc+b>o>RwEdWn8NHMI+X?Z7C8C%$P9Pq=Kv8WDD z3L|q~uDG~_&dtkZVkdvfG^o~`eCGHeaxb;bazu*wit{fvl9s6Y+UG~pCJ_2{k8!Yt z?4vG~YQ?Z9sY5TgHV$G5?ZHNr6{BC*^Ipy#p8)TntqQ$eZ8BSxpY%u>Mjs38hq<~Q z?Yi|gY~MfYSKiP0q*W1KR^j1Fcr;uLBaa@zcMO1dU@9zlXQORA8t8e4Y7^Y4;@;z% z+!nW9N~h_s%Z$O5J)Lm9CU_HS5@Q~SBfj2kB$xeIdaBR)UJ!_{@8`0$6ORXa9K`UR z4hirS|HNbK@cD~xFOFdi&$i=w((8HL=IOqqqucwCRIbA%g6!Ds_JELgIV8h(p+m+hD3E5CoMwfZo^KyQ?)8ZpbT?$k;6YB?%0;x1%)7Y(P6- zQ7<>Dojb$~J@f5DmtyAbj*9#9?GnLpXPw_H_HN;3e&8&w`|!=d!t7LMbQ3u2j1KWF zV#9+kPyMLJM%=@M$6<%@NSMIpwrkJ1rC+-lT=^LFh;19~ADsF52Kv-ylCSxy3L!9zEJX5!rDGHKy|Vq36!vk-pMH z(IRdqwm9W8ySZu`?i@h+iI{y8GVpmMcJBmFY%$BZIOeYT9kL?95G%oO5cQ+A^LJk_ zImcg}p~|Mt_O4FGrp`nhfAz`!(;&#f_PcVDqEUkZpYZjB8tHdO;NRVWzdHp}0K&ku zfdB03`_J~kk51kHSxNb)GW2&vl1?3|gtZ~`t{ZhC$8QEGu;Pr%%KIY9Y9ze-DmqzZczJkC zcov}y2;3yx$%%wNv*Vn*mT;Ge(t&_^3WK5KVF8-ci%afCiSN99-XaKEo>tY4XxwKVy;o}2CAzOr56X@O*@*#l!xa6=UCot^ha z2(7!HH%EgJaV_(8#Yy*K1BABY$=&7I_Vy`xs$vt?BMFpwq7u zaq{OzbaMCWY=sl?JlHsjo{7+uuc5;Ij$@-w1K^afnbCTT={D^mNSwLYEpPnK`CvD5Przw+%fp_+?7DP~~(gU3M580rm~jUcT; z>I26nXM=j2nuFD-h%h83K!@Q+b;ezrotq2Kona?&jymJJ8s}Jhsh~&t!3ijn454_Z z?-t(4g4g@~0W1_Sn3O#H)uwY^@{gTaTcb!3d(OL6KhaYnA-;}S^Da%eI$|uWFEk3G z#~y}xpyl7}A(B`nHHu8*;|OPD1)zBoA*ibOE|3BgUoPiQx>`9q0OF@i>TM))U^#P< z@Oh8zPc_=Uczo)L_8K(ti8aHN7j*VZ9oBA>W-C#%`wtf$FnpT4gfaY2d z--t_#yPS%;;7+P5L>P`1g{+itx^1RTU#I42d-my{`}cOL3FP!TOpEqXLQ*1M!ncR< zG#h};Izj>vTMC&>0a+CBB4M}KJY(Fa7gI=6$n5UWAI)y3SAB`K3o42oRSnhk`-a)> zp*6B2As#Lp(P5c-sWm22;=~~mtr>)|epLwa#o7}jM{~1H5uQl|w6}~a!atc*@J~*) ze?hGw*rmqe#{D>sFC`{tQEQq?nDaz-tt9 z^ExMt@6kgvMpsS61I{FuPV~LBRi{0@2hhe5r^$&Mr99Bf!YhotmHo?-i&E_J=RVL3 zFl;ycfD@ppU_fCUNn@FR5`i!6f#El3R5Oyek@f#W*;_{C(WTqkxH|-Q*Wm8%?v~*0 z5}d-_-QC?CfCAy$9opVreui~_1MEd;IcXJ9sabF6Vm zZQPr>FS2_M_n%zOp3awMdT^D?;UZhNXNn}D~L ziKpT#3bZ#L+zg8%IT$+c@gFhv>!xRe$#c(jS zG(9j9(Z^l|vkgd79AN;pA4t}U=^NKrGy^H{3*4uU@`^Bt7oJ#lfaE_l%0T4EReRo! zoiA^MD;YO13}g2&1ZMkaPclz}l(%K)z?9BWTVB)9;~dDtD7-1^zSLDhk=LnNIgq@D z5F;vO5EO>B2dRqo#?GXueeEXgBHF9Q?AB+Z4=CV6`O3(}o_*%;t@ffC!8K1$(=dV3 z1L7Hg196%tO-T@|(^zz&&j;q!pM+XPl6T1jPO$_(zES2@1i)y%WV^wtR&-cvWv|zA ztOATK=vN}WBJn)sapZ1A;Toj%W+CVpG+c%5HAR+pH(-{yQNjEr)Fh8i5=GoRpQVU@ zyAV0akAU@QKMeHHl8`Cy2$dt|DlQ9F^U4fEw7)bl#7u4rOvkZ;+ld9|U^LEN9IRhj zUMkfg+upUV1G|XY^K=r@2o)`=eN;B~qX;u{9Fbp9y=a4MMo$sGQyL?ShNwd{CsRQV z!@o}Iid!|i$}Iag7$c3cZ4TKG*-2zxM?HbSCJJ?`sVRiAHT5;NEnz|+0XRdz7NNwU z@LNuBK4C9JP##uOsRO*PB*iz{(b=FN9n^!2V2^tdV3OgU($l1q|5GsedVv+visI=& zzJ~}_m=WKb{-U<(cbyAd1YRwt2QUhM&>|dMT&B{DydAwhf^c5N0~z5Z#efE4LND3 zfP7e;t(C*1_cX5Jo_EU^qpt$hgoNhoJ7I=k3`SWSE|oeVv#*FWh^G#=>OV`K?l!9g za70}d%{C6I4Ur|^gqw`npaR4ioIm5~dkY+I0{uy>MQ+C%Pf5R0LigTTgXoe*I=UgVHU<%a>u_+9a!?z6^noL%2uZM*>qCWHorSIgJp+a@;JWntF&QM1kf)V~5lD3c-*gF){1A6;uX%|{kZpUOpKP93 zNX~bKlq>igqbNUpGGZ_lYY*>u=N-K=zzH`;n8dPNF=~RcV&kah6XhPzqdQaj1{7qe zhKNeDgx<0jG-cRjFWQ?s6#5CU8a2+H#W*6Jxu)SPjDtQs2NAF;QR394F&&`Q3qa|4 zk1b(@-mjuaxJDY^)N($HbEDjPO}QXwt{>XJGktqx%0X*x+7w4YDX>{Qh~p0(7N02B z6J_0r;sX2VZ|AjAo3cI7yMzlu8+(UXQ7AQtg&1xCr%8%Ch0JgV?+JBYRCW^?HT(MNa(6nU6GXVz z+(Ja7oHsaF4&26B#*tnU02NNynU)qSq!I+FU@nfYZJS_1Y!F_RoCmCE0hB&6O8VSO z8ss9zvRWfz^C-!ZsD~;nFk&e-o7WBPPnO+EcW=A=X|t?BID@$UI?cVrWQdi@iPP>R z^Db$7!DVAH20VF=1C3qgEm0mYH}*bI$lW%k#RXl=V8_$Y5O8E^ZS}R z5u*H&BSiT6YlsCsufSWfgd@5Y;xp|!zK3kQBG;C_(0+y$y_vc|1Z0E)Fsuqg1IK8o z%J3KF@=}!cb%f&HQFR#9i}BpqXmjIl2|5$Z)(UcMDaOb#7_4WpvpW22g);||h=!O5 z#>`hZs&xabFfR_cTC|Dw;N+|QE!H$j?)|`UtxS^^_P%4~jnkQ0SS`u<1OnBYf%?BR zkSo1tL*gh1zulW516}R~R)<=!Ss4%{U~tB!jyz{LZK)h))k3gXoF}xsA=)!6Qd=~I zkxn0N;Yy_vtPR5Y6IHAvw<4aAQm7q8$Yx9R_jZ0i7cAoA(J2hz9L_a1sQloF7ExpQ z!)Q(8pl8()gCC4zJusc?7){dNTRzuiGocxr(+{{3EK!Vr*%=- z%a|Ug=23irUViWVW|mE)u;Ar+)Dal_@kWokro=vxrQ#(W*6Zup5 zago-D@Y+xyX;$HtzdsUN_DuUp)2}^lVZ3QWoG^!&*7JrS9A>Pe%%nxYDi4^@FnlK8ZRIpNjyCjw98y7il+It zyVB36AU3TBJy)14VmK66@C84ZgvuI8I)gdfvbSBhfCC2;kddVN1l$W;hIHrGLMPea z<3)PIpe?&E%*SEIQVY;rW_MA-`r|@cW*A65*6jKFbCS-@{PHwh!jyjKJaXN9(x#tC zsVs6ioba%FjW8Z1$lrw{QBz!MlRtdvBNf1@WVs9u3gK-^lTZ_w<#-LRh70sFi*{HF zU5y#Bfs1^N<{QgBmK}qr36L!cJL+`TXppGf*dv!$2S|TP7w>)~O#z~Pzi>S&A>#d5n|>~1urT#$Mb~rawLSA={RaWT0Z(Az7#XoLard# zFm2=d)OjY>aO$(T=t$}LguTSwAhsFAl>>ZkL-JyQsmR2NmkcjH+NlgE}k=l1VnY4T{8_e_GGY6Wv-ffzcZ9BFFe2!Q( zMT3@Jv4SPPLpJ4^Qzhn_!}$F3Jg>HJ0M7*$!5PH`al<@BG|>>mCR>E5+>D|IfrRDp zXI*D5?{ri@3!>B0AnSYrQA)||xT@uDA7PunzrK~_>Wp_6TOjWAjvsuJ_C!kUF&;~R?=m-eli?2;qZZGZO}j?>dW6%bx`bC2bqY4?n0kpd+_oQ z5OdKUyOe^8>3;f13lNS4)Cgv>0!I5vnVq5?wRpDN7{5XAy1E zqCp3+&dz_KcF*CRPi#-~`HH5GOe0CRaSU;v@%O>G^~U&PyBvsz00HHV5=u zz(u}M3=_z=uQ8v_EHy5vADzMPPaNT#W1JW{B`N`AQ+E+un}mD~F8(2N*@6pYF0W!spPJsuXR_s0e1?FjTNn)$yOP zpp0#hK1gR2WZ`j7^t5U{SX$3*8ia7TUAY9CG?dyQf^#q&R zZh1S7-R$#Vt${t-G^>1h(BaA&`;F2S*Z`@*8L#E@)75(woZ(#Y_%+9zvX)>m_-Y_w zFRwyUe5g#wMOjC;Bjh{!<^gskY7~jhwVjK1VaOi`dJU>jPnOHb+6(H9AqdoH zsI<;!d(Vj;@qxo90gcz9Yin8$5qI51|^=Je;wk?=U)n0j@q zp?Mn>*P1$aQHu{?8eq!!E)hHR1^iA%jbwWCE%na5myYkW(piqKaL1`&XW!B?nNUt+ z=i!Kv*k}8b{KiW{d&8Z-W(CtZj=0wE!e1X4_2k3Wei*OAiJd-!^9sF}5 ztko|j?|O-_#1{&oej^b~TO2x06wgJoOo-*BmZ1m`%`FT0pnmz zOdhgNJpYCZ{5Q1Ve-=pL{=Go@50&`;lhpj5#ZtKc14;N-%k@9O2w4AApZ~YU{7>PO zg`Jp#J9Ya4l>m&B`7bj(z{>fjB>b;h@@CzQgu*{1(x0jhKayAxW?p#&)x&?eR*x&3 zpD*`}w&@`ZNDWGj`gL`Bl7#q0?gXELC3l6DK?o z@^#F+Nv6VgI!@1pYEKmTH!U~QP0{Hy`Os8|2mQy+%-|y8HNKPP%d>34Lv7@Gng-wD z4nk@`@00xXN%Vc9>&N15q?g$iv=faZ7!#kI4^@nhtfOV0Uc-lv@y5qI54;`RMQ43T zWgC&y#ad;}T1)Qc2E({rvzN=wANZse=Qyobm+m*)kgw`*?vHA(8fy0s7v)oz#MO-2 zGE)yH&t`vEH{q+c=R7@hb!$U;=s%aMgS@T*yPw*v9X5q1rZ8kOdxID>7$593$uOkj zc4zD-DBnueq*lOAT8qSntF4NH}v5-SjEvavhL<-cDtK4oc2 z4;U+rU14y6XgskZwpN_ASlk&eD}1prWUsnpJUuX)q6;H;=we#li`nW7c5R`_J+M0k zPGRw%Ege4=Bg@PPl(s`rgxEyb=Qv=%UfMn}r@d(Huhc+Rjz&!nh~HrLJBmAOA9FO{ zDWSM)sP~?PVqb84x9PP{Sk*l--R&!7H+|6B=!IRbLiY`GiyeY9x)!c^h`?1-eyOZoB{l*#;LrsNGpuql=t;9ocM_}&8bcwlthPH0@55uuXCe_vb51dQgB zA!N|&lT~_)Bx#1S7vT7mAVBBHp(f&P2J>h-D93p<5U;cYFEw!T2u$y)ict#ncie?t z^14yFcR|wfU7bNfehAh&XtqYG1?T%b~Pk<54vODzgDnNs}LDT3jZPB z$n6BGAmf+?47#ci<+~(#($}Dv0T_C$6TSI&hRH@{fqtIQ-L$KnjF(%l&zZU~kqOz; zMd-HK>a8KZ)cFk5*PfP%IY&i?$Fdw{%!8N^<$J@Pk#o_Xg(4gvt~_esqqbTP%zjje z9J|?S*4{H}!BZ)FXmZ9)Dqtc+u*)SPrKbQJWR|z-BiKA6PRL#bQ7-5WUTKr8x8kdi{Q*5E1sXxSkd(Mc?|I# zf6G;L4+Ag^;nicF#{2P2q(BU$1`Jh9K%5D&=IHaq4&3wsggygtqb9t{bU50p5|?Kq zoc^?Q0O61YWa0wju{xWJ=*Yb?b(t-KSa%cRraKC^bQU(=V-R|Ad65IXJAx{-M+RiKYXCI|U$Ci{=x?7#?K5o;YoHy)5(LCnAXJ8X z1>#;wj8$J2QTmuNL#p`M%?-T3@NpQ*ET6RSK@4sr&%hd*(4T_3si+_~rG_ZsyuBPf zSegggyY)vI8!w(Wh$Q8%_SG4wwVOPNPj9=FcbZ~cfnIXg*3mR;Kg~-|;|_Gz%#DkP`(ke~LUl>7Fe)&4U`PQjC~1RwM(SPcxPqmkA%!b;Mo z>~XXmXazJ<(y89V*EgH(DQq7!vpGX-b$J@By0;KuA*SjwL z%#07BDwk>Isbw(E^~RXe5qYheAj|Iy0ti4kzQAr?q-e6<3t%unFwjDpWg3l&;A%1a z%zXo`wkE0*#6--6kcAF1HzoQ1(O@8)L~m0P;Q?Hj4|R;+nM&8Qa&JL_V<`!0@ZxdIebB|PJ%I$xj$zkJ#~KYg8QlYW4%kd%+EVky7}3r=JDJBbRyFeB9p2I^Sf!TL8-QIvX$L zc%*=ZKalLW8!NNxIKxtLEMQSiG4D9_8;N2iUPlGz#)g50l*ofn{~#(R^OwQ)8<$nK zsyHpg3oJyg0D_jU`b%0*4X+C*4{!X!rH4<}1%dLT_Tyo@|DGx~8_45Dqt;#!Go!Da zX4@mLo%*eXk=hNHHS_H8!VxmoOl{!~+uN2ZEbtl;IeP2(q$f%Wfz1_yeN_tWg%7r_ z%$0W?mpcXHv-D)r2VR*H)|@-vJ}9Q}yU#MEO4eW#3hvxicmy4P3`t!UudTPaER)z% z&a5~Q>W|DW=b-#&j$+$-FSwdc{met@&7%X##}Jeq>C9YPfVmH=m8!AE-5x*3Z6jpGwcQGN>VmkmX zuRBwZx1+#66Q;&y8_L0!_$QMCxPv{hX6!Z;uKWi(!aB(MJfIKG>3|LO*|Si>b~d)w zY#Z%blHCD(=m!*%u8i?O@7JCqG{<9iEr5CXG2ZKQw}BMeV7ymN_$SGWb}{-^W)ya} zX?9mF$7TGZKJDLSdX9r35G!&NN_T*M%f|5>$DrkGb>7P`fGI@epa|;$PnR(%Ckl zp9aFsLTQ?sCeCqSZ)C!x(Afdzk}+- z*~Pbx9yLsdVaVZZ9~S@FJFJZ1vUgpPP*Ew%M z{cP&ki)x|NjR`|M6+rYFF}}fBx7O?~)j;)ROb0RLv6^bkkU>I~$23f{LaxCExiQgk zG~N-J)EEJ$BF(t!B8=JEg#aYz>j}7GokZX1Qu#gmW&Kq+ygR~R8h(l^sUl<{+`o@9 zKMN2#8cIiC5G$;$R~LQFXGqW^QdE^>JI16?TI&#_Vs}OS6=)q{zQQ_&?M1&AgL6tj zZkP3wRo+H&OVucZ#O4m|r(f@3zPu3FCVHvQml)oisB(R%Zbr(KFU3GRs{(nL*@8Ja z+MG&+H>gOr#-qHp(9A3D?UHzFMQ#~M8s#|B7oDw?GkwTp>QjCAWGVx9I0K8k)qH;? z;Z%!b`Q&E$F)?a^icdUh))fj1JK>k0QdXoQqgRjZUWoQP`O0iDfj$`g)~4`S?Ayr% zFLGlgzFqZbuRGoWUlxH_0$kKS{C9d`aT6;O{IeS0>KNnwbw|>N3cUhram9hY+ALC4 z?0}ZZl(#d8!K|_QbV4DvDenGxJ%XCL**S>y2I#9rg=RwI)U7e7g^u9olnQ0c*su1> zHnVvKjUoCd1jJU1!Ww>Urrt9kt?rDSppL|RTo%9kHYi(NlxzT|%-heNWj%1xy*);% zmnm7N%oqwg?gS4~6;nb*6?B#?AU{BGAG&|SFM7!%s{=uL)jW{W+&s_OaPrEVi951B zM!jeU{qNIgU*$~}0Y$9i{6ONVAu#>Q(CoHzjpSc@G6@O5-L?t|Y-54OS=TCmd4WHg zQE?9#)JCX?=O%DT$jy4j(^rAlmaI_HVMDk8|BP#eyzL$>pb=~_I|7~VI?gfbsp)tq z=UkeR2Fs{M_$c|%nQ*&`6#51;*tE^iBhsE^E`_tfwh&X?>iJ-Ava$fyS;=CxxNigd z)t!yPN$s^?mlTl%v3W6NjKWB0KR;cMmQGQ7UZ)}2G#nUr{g&LM;!8S6e4+~vi==<0 zBok1U&7p7GD;euZLKPR2p1|4hm{Pm)b~VV^kox8O6+x0pS`acW*9?sV{eddMXj4z{ z6E+pkzP_#|?=Dna1Fsr~uoqK$J{3adA#xLo_mB`xxG(?jnsMrBm~AwfzQq(1-B~i9 zeV6DGYFD6S=L_C-+up;$OB19|{NC6LKRbC~p#-8g4zd2CgV}8aIpXQ_?%Sn!q#sWn z3y)EW%Cn`KMLKFvc*JTmFj_(29N{P(80Q{Lxy_lwf?}ZOiw!Y@1KBg0N!cr&_^skQ zE8fExgoPR*0Vfj$@p&63%oipX4^@8L8#Ra1aP`L1<>8t-B6_1yVTa#t#9} zbio2SqBO>t^9xi+6T$@Y1tWJ907QCzT_z|IMo;bf5uBAg994Qdfs$mkbW{^VA4S85 zHcHgxDgWW-fibOHx%I~F1Dcw5?brWtjVFwJO2wy#LjPYRP@Mlo8vJhw)SqwTza&uD z#TbZxA^iS#K$`i#5bXZ-dQOtx1e_4YBF(_j}^dzy^b;K#?X})q5Z6&4dn{0|JGHxAf+R#Q=6D;`H|lRHM6np zFpO)Irm`Y%E{D8g!N-OhJxq2l`Yit}Y8g6ruddtDLf2W(NYr{DIOg?gFoyeqr>B%Y z^>u#1)&p?XeBbFfudJ^ffV?)|O3HRz-+NxoJ+2em>1#VWJ~P@8 z`mXbB+FjVUeE&}Wq5kEg{q=Me&#|g{*Fd+VrqWIQCZM&us=-haLmc#F% zjeS*ORSIrLcLd1@?%UMq*qdExWo*uWh&c~>xnn@{+bkKhRo*njETlKt#j*B>D|A;m z-5S8rc<~{YXgi5RI9n51VT&U102VQ2FPN*3ub;D3Vl|bsY3SKrFPg{P`0f-g-X6d!Qw@Q7;o`p*B{ zdNvk$B>Vd9dgmb=GS@y=@apIYS@)y9_zD2Dv0q>IOjovZ+c2(z-7=3x)-r9C0&?vy zpHo}cGLP0muRaMHH24S$x*9uPb5n<+a^khWThhr30L#4{79~12u(C6Iw}%h!&w?aS zn2hvdO>h(b{RKyL?n~^7QhsVd;+OCK8Nc*B>b=^4?>={12CpxYuR`4)=e#mlD1Z)f zZddxy8Np^~_GAJ6_m z*SX);sM>cAL6-!KEDWkYn6=IXeF1OxoA;gXLdZKX=A^l+o0m*U1OoB)Pw;#$*D9B8 zf<8fHwp*ZB`tCH4EOup95bDyXG^;}CW$zPt+(y^47VAIVks0R?Mi;AV{ z>RMe*ZQ4b@nDNN;9-{SFk9dwz(|kM7EmF7nB7bO_Msa#E2xFUoJ36E7z^O(h8!!v+ zf{7~7a!c$jdtPJ{xpSCPK|ZZ8$KC4uJ=xSpuqsjaN9+88zAig#7U^+4DT2drv4sSr z&73|BSkYCQV+C_I^Um#iP&m+Dm#+`|K;g=5)PiJ3jW7bkco|i zjSdYpG+1?+*w=6?RjiU4l!Y4!tP*}HZW~2MxJx%?U_yLCNz<+=N)&L3ZwcxQajKh!*gz^fC$F83tvx)Amljj$qXqT#k5*MMMBQ~_wyqDrZBJ*eP zj*-;*nOULu=hqc3F(4ZjiBuaLT2oUVm>{cL85J`U0^(aw*6T=rNRV1d#i9Jbl|ryx zY&Vu#=EK*UFVso(43cqjG(e09l+ow~73Yo0;$>mAsgZ1}u}76hk5!W9KvOmk2$EV7 z0)sWQjwRW-;VY=7d6fQZHe7X3L&6kv+cP4P8-zn7KgqZNQ~Rv@`hXkbNNx+66pH}w zv7Ce(m=&F{sg@I-BzffH38{{9(nV}~m#_@|weLwTXDll8(y@?fppzhv5NX6eq}m~| zXL0;#GN_g7zCxL$I2qd&T0j{#Sce*9!cNAgg8`G9Bf*xK_`gZ%g}gkSy2vTit$g zK;S@riM;-xc=&1;HuUTdXY(3XaA>i_d~1n?bY-R!U{Bj`*WqF;5IqD+sFVmJs==~l2ULNxN4SXVxwh3H=w4tls zv`F}FK*G6;#^P5U9n)+pD%rN=gKrm)YK=e26#$EX07=1u7Rpk}NsCG(dNctx8q#EP z!i=Qr8S=d>at&GdFWMIl95@du^sqks&rGGn5#zYu+Ig7AxG;Vwh2`Kj6JIj4(Vtr- z>FA3lGGRv4BXz)?ZQlqtvx{Wnx@xZCj;vB20Y~Z5%86%6RwXh{lP=lTbU!22vG)i+ z(PkYVtd)Q1cc>u$sgShfm;f!Jwvmsvt%<-Hr4>&s9R0~WcsvvaI!-z8bYH{CwV>;0 z8e>sG_m3ZnaJo*Fy)JuIrY5@vyd0VWsu`Uyc8pvl$A(WGe675?=-Y14!VKu=*>%k9 z1YnNbk8Gh%ndP*R5>UdP3UblN7JU9XuREcAX0RFLX2=GU2dDBb{*X1QxLq8;;Aq@eBF5y!HbfxOVKVYbIXcEeJhay zRbCRvE~T;}mle5pS5{yYd?KV;40r?vI(_}>fT*ymJQ`eNZ_EekwnDru^Ss!;BuS;m zS`Z`|?qdB~gAd}s0iNNRR}l8b(55Mz;k4?+Ifo+P8R4msR911?K^ z@N@1^JOrNAx!X1PDcpMvCOZ{VGk(Oi!3$}{GIjkQgBW`EI1)B3etNl?1Mn^sUYg@{ z)*|{U?%PIJ5Ihr#{cA;k9e$0}b2kaWZ763og;rpJQDUHl8XXG374fF_1CqedG&4>-2Wim3eSttSi z*F?Nlm+!-l)|+E6^<^|9)Xup3RoALZ&0&LFa%&_L#3w>v zJ3P}FqV~p3aNWa27=jl&&f9@##MtT>+s|L6pdh3I^FDEQ#zny(!2pmom7Q=CMoL1~ zK{8nue%AOmIZH}&5ub9cR*d4edhV6wj+-mC`rF%Zxt8SCt6SZD1orjjnwu41s{> z6Ucy~6S6pvE>6y`M zVO`o^a`HN)qX#e})u$Om(WA*CsO+Y~4C~RYQDI|Ip+wcjbs8nk;K6z6p=YVX28Y25 zrY(|c_q$DE4`ZumxW*esSpZ-IPmrBPnf;&nsw13~Ea^3jHh}FIx$#uSp*>NVq0d8X zsx${BHdx?Q39Ly|Bc9*WgVPdk8uI zRt|#}NK*7lv%)8GRI6Yn#LhD(OjV99R?n!_yH*}i3Ll|7w20J8Qzzdho&+iOKwWV+ zI)ca^urUVRa{*Fjio%k(b^EQPP$w;gjRTW5~u>Q$;gjX}$e< zTRVrSmwhcWL1aR5j=_n7q-s&6)*vMyQp*sE@8iiS%X%6zT&)+1|Ap06tNC3?y5(yf z9Hc0P^%G=qg!3VDVEy*`w*bzgYFG>riK$SLv|)V4wsgQ16Ejl&JfZ54!G#%G&@aPGr}KwqD)&xbXVK6+Q*%U0 z{g{hiaMmNJ7>GcUZ6b^04^=NasuN4j@k3hSzQ#YqpW|kYnI$`l19xDExgkBeV!{w1 zJw#!pLS+mUNxC7=pqum$2rpB$Y7laK&~f?9=@Gy*jjK*;Ku=7is7Ck@3Co+_H@b0l z(*R5i8fKHyE8BlL$Ep%3g^^V|;r3;wpoYgVe}QxkMQ6ffPNE7N_05-AVbpRW#KvbV z!8e5xRZZw}kKeD!vSuKqQOrXzkGv$DEe>ha4&F5}H!ilKk)2W+3oMb*W>M$iCQlwn zb@dnnBUw5O`ab^0CCfd#82Ttdn_rl8Hv{O?XA__k7{X;sm2a}TLjEqWC~{30pYR;4 zNuaP<3s)gwa*WA4KcFxl^Wqs8_$|Y|s4QX$SLqp2cq>eeY%QZR+M?zoz5*iWJ>BBM zpl}SKN`gk&bc_#oD@NmNsE23L#IwUf+Ld-Qw_+Z z!za+{%NghRb-~4YD3Y-nrCT?O5WB0_@>`SqIB-;8{*=Q~OK&#JGPTE|m-KgUX!gP#{5-W;Hvq^u;7JA!qtKjDeM~rx6VaGpdXddo9I>> z-7chW0w5Ja{>PrJ2v>ia_k>|a3^pLU11>i(`ANjN)MP1RQO&J zxHUp|0B8NXvPQ6$$T`S$f#Ho#O$!ob(0v}o`*{blcVf`dC9bdFYnt}`m8HUiqBh~m@OS!r7DCfm z5IoFALaat5Xg-Wi%F+SHl6pXY+Hn!u^zXs-#ZInU<4ITs?xq;`0mlGD3_^o*Q8c}_ zTwFVBxNaH*l_-~EusxgsNUd!q8BuN74YQ!K{N?dPIGrN_`{^ssc6 z4EmQWeFylZD0)(*m5j*Q5}0)|uBi*~oz!+iS$?={kiiD(MGEp8P}f=ygVXO^CQ-bm zhGtG)Jbcf5y0QA8-Te*_8p6G}C1hM#%?AQbJKL41@!U)9tS3p8dU~(d5B!@L^7|%r z!;Ctw^^mV8fjwPPTkF4oh)a!;!0`s|tcgNfKO@s^fXDsg*MO821I~XjRi!Iq}$*qKh3V<3@R6Ns{ z?}jTFjBJd9WyR+xkH&55*WreQ+zwV@MOYIfDe$HktKqSn>Wy(oAO-r$&>sEd3 zCm-6ie}|5M3WH7rJN<`BhU3)l-@S#IJE(tS8dd(KzV@eD_FpwIHD=;Jp1yyA71daX zIseX8P-BJT{F~sY#zxHfPx#{hi0k0`r{aZ~=?^UOUllLK8sjl*92gsCbZs=m-~{Rg zV*DxSd9WoGn8J_{!lm#rgZ0bDJ5o1oCnFEKP8Y>R^=DJ01n#2OJ=5Jsb6*Fcuf+%3 zr5c1_Kb4X)urT9ZE8n4rkq$Bjh@cc#k%|6cDR$9_qhgfHX&Z7MS^`Ss;ZlX<)DaVO zyw|GF>;WFn)V^5n8(rv}%owl3O`+j}MmuNsEd*I$7YflQKhF|ZJeUT4C9?C9d>X8@ zv8%cTFMUxa!qq)#dFw!@Y4RnnW)lr!Ncpvb)wH$x<`~3#q;1;~)}<$UVwbEq>F~)z zwsL+?L5!QFuG_BF8wyan3Z({61yd1j9u3o_<3kKlDxTm*2AEb>5?(U7$UwNs5xiYl zSA0hN67odmQ2pGU+RtWBdv=?otyY%^DfgnT`8hMLsU#O?rg04zP~q6xsON~5E_Y_L z`G_oTQ8_{#-Di+nnpv;h(p^0>z`ToaW<1Uka6nQLrx35cq5wA*2;cEYk}HYf;2i}l z2`O#MLZ>Fkj`BrzJ}O1m&k^35^_VQ%n0Hlwrmvo^7(_9-xfCNq+c7hpaYl|f9+#o1 zY|E@)=h{|9m`kZ2KR^1qe1Aa>B-3F*TSjVuFso_a$FBArK0cti`C>%wS>AxMu8xI` ziYHh|5N3eDstg>WGFvQrOfarp!jfw%-TTN(sh!F|V=WKhiqQn~JaZl$ zm%JHs%oYt#i;cwTU1S00%4Q9na0ky<+7xm}vqVYba$#Osow<1XC}*r~kLV|!ilj^N z77>bZFIuAXYi)c9St0}O%#lmvR2KT=DZA07M1b;#W}NWl$f0NS@y}ORjHG-F_w`O) z#9xn@eu+oyKX*Akr-u)i$EXm~r=UlZ-Wiz0GdXAr=F)d3;#=U*J3YLoj0JpoKKqsV zGY>j~JQxm*iyz3gxHbBo?nw6er!c{uWOC+n&Fim+Ze7$iXyLHx1@mdQw7B0tZsy0K znol^_wn?@NQ}WmZ2bTQ-N*i; z5llV61*znr-a0V_riAsMb|X=$=^+>m^?z8B|9KDoP@z*>4#7A;*;;=cf=yx| z{ZG*JU%^78EdT$3Q2*La`|Iwv{<-^AF8^^kF#g)jBLDBZ`CoV3KZa3v1Q)#cD+f$j z3n#VqD+J0v6S4kr{?x6n5YB%jz5n{pp<7Seet#I%_o#L|5)@9$ab<%Kec#ZBA%f)psLC^9EE>>!F9>{p(8iD8I{3qx&vFzTdMOy~ zI;;M8{f$1dea88|^+w!%#i)%T?(5)cbD=r%a@cR)PE>WBL*@P^@x83|aI*5Z)?z38 zCDHr+lF`1o{6t#S^9dXe3Pis_Wt(w zQrA;zd>7%7@S)D?lb-a;mc$cL#hxx}ocN)ox*hOS-h&B9kypLAU24_GMZ17CMZ-yAXs1!G!;BdHdP>ot7CVP-_eSx( zdha)e-Cn}4T+F~E25Pp_w))Pbzp&kec2Ub=_LxZp3aTSO;_r68E0eezCC?|R60%Hr zB>^}%6z8;0HlPPlq1p?jujG73brWDAidqQ&OmJ0UvbxEE5&V;J>-YSmK$s`E_WkvQSnLjU^-GOYJZ}9P*ij6 zI2PZD-;&^Be)axr{x%^d)@khY{V9Rv#7QUByF%!BLWUH#IKmVnZ|PNXJ_DqDYfh@Yq_7u0tUo> zsr4(qsNiK~$)^72IarV%w@g#Ud+ODptNnDSSQz&%da2Wu9hOU>KHZ(_P}IQJo?4{G z0|}oPHUoW9BI`mUid4~{{f-mRO(SD@jfA}99EhJLcPY|%l7niMvpk=^u|M*Pbou#i zBcJrakBVkzIk3b~M?l%__Qk>0XipcSCQ&bSdw>x*``NPOj_T z0lb)O3Zn78g1yGrb4tVkPJW8TZt?RQ><2kF0^Aq!WZzRZ@iyVMmL_>|FsPjc)z0bk>nBx=vc1S<%H2|GiD(CjXFUuWYDrwM$EKc| zLf`_Eg?RaMk_ z6WR80cIvGkByN&wCc*b%OxqR%?rB&vd5-}w3eg*(XL#tWz|JpyLO4jJj5ZV@(_J9V zkVbvab}^;&a$>W(O~ON9dlJ~N+!2$o^jVB@F~23`VA0Fj$=z#mq;5U7f=M^i371;2 z1d4S~+ORoKXDbvm;i*m9 z?k-WwV$IZX^!#CJ?DvJ|$NBRgtz-ufl@&XX(YJpRSCsmqB()pnDN;jt5eD1s88|i8 zJD(W+ThbNJ9X}r$x%7gm_JyHwn>*dBfHNQhr=>zF6T$@}#~X^igldfCjs^-{+h$!) zX|m7syJWK!4D{tU1*&im|D-O@jieIMVQLl}y-Cmu@=)f`_fZuBW$ZBeu!klfI3ZkM zhl6qpqJfpvA9!ubB{JzYe5HD&I35FKSpD5Z8^|~o{j>we!-v{HiI^#FnPzNVCi%Tk z_{5+LV+n~;_{THUBx<4P#zE1y^%5R@UZ90Qv`mTp+y+^>TWCHkL%AWf)oLaw{&SR6 zd4yau*hYnZPog?+i(l2{6=@ML-~N%`7%C}CXCfZ>Q9vVyoqy{89*qGKd^P-Ch1X`) z!BR}3-OwK)p%hkHK3Zu@asV~TNuD<^TLgn%u3Tr)6S?%n-GIRs=q$Qeu;Q~+i4TUFLJ67Kf0lxoiTYp_M}QQ+j;n* zLuwPmTNqRBAho-@KYlrrkcJSvR^;~4R|9ls*DJCzw&AM*D=S*tJMI=#LmakbU-IJ4 z`661QsVxCqk_-|Qj3OTKRd@BoZD8s1&d$_woJ-7x+3^pj4XU?Y%dA<2xAU#JzK;|LGQ9M2PkpXHaidF6*Wu+SIft7>L_>L~ z@5;~YyxYFgA1rYPErcAKr8gws$#+J$r;{P1+A)U%ap%-_@KSCl0^f|6cHwU6?}(!e z3$2)KE8Orf@;AB9U5#wi_WS$W2z})PZyiPNJ2#`|K#5iDy}}p?PDch z=0oGfI-e7WLF!`!Bp0#Vj3u1~Dqja7N-bvk22xcaZyqR{$PnGgx1A@{7@>rfMGKk5 z(%wRPKi5BoJbK^K^up_}lthA|6z;@m;^Y=3-AK#c2Y{wt+!f<~frO^s!I$g0_0I)e zZJYG%^D>;^G9{>SCsqP6*hHuE|D! zn!F0==B0@kkkQQ&`uwCu=CJ^*Uw&XCFt}VYn0+UlMsnHD>8#2DLB5_$r7OjOyt>AH zirxA^cffeDkh*N@%;Ggg#hZjVKbtK|x%)c@6}7 zV@6yeWEW2-1trhVeXOE_bo@MdZCZv>M3hogcj>YZ6VTddWo}fqwP=Zb);=&OOj~o{ zdCoyyNggrt?d76%$z~-;LrQArG0|&u#_b3xgtYkF*w(4hP1De|=;taEun^O(`h7le zKr(%^>QfK%3`1%Hqy;X#{9mSkA-*f4oxe!^mmm<^Cw$+td_99T zSRpvfE-&ZhvE{Dy#WbvEGRdtHvDrTj8IHl{*w(ZX zx<|5tyav861MH05?49Avno)L)jLfC4YL)WOHMqQzTJHQaXgecP-Jb%w-U$xb6Z`)g zd^FpGcK;7-@L%23|CK)Yb36V&h61#J|5YvhfAFXO5A*n+kmvu>V$96+zqxS#uY~CT zXm|ea?qbaUdE6fy^1lH(XwDQegyj?xF5m)2;oPF&29on73z8YLQV>fRvGGz<#nVIiXXSl##_!I+T%}Q)cFn$x?ch zk%^iaRFLI?K-jn#Qvy_x$pEG*y1MoB;Sf-u?yD9K?ojZ(o13dELz_Wh?(XhTS3eKr zjeoynx306C+q%1a0UP|?UJqZ5W{VZYR>{1^6^+Zp6v^s&D6HUE>EQu3xTmQnSgk;H zg4QAw5MptSwBgd}azg`{kS}rdy$K00>lv7wz(VZA;4$PIzt~WW0si5Cko?oIdIkmu z!Q|l)!B^W>K_(~gfD)-AtW;Q88@|b2+rbP@o(R$rq#<(B;QaUY`&I{_O{{H=_FsT* zyKPHMjDQ_jIe=1uD`kH5Io)9+*X{k1a@0igZ}}7br!xReaBFl1+5$8V96N1=GgSdd zM(D{Op?4ds2hzkC7VzQC3h@?82#WU${1=2a3dv4b+Mn|HKbQJwbUjN0Ti7Q%H;!<> zxPMJtz}esmIPE|J|FVs$$c*|1zairI965jpujD&14tor{0+GQ#*f}vUL1=IV_3=o; zKzditj5z|20r>L#5?J^ZcRDO*92Y;ot>a^W^%3$q!;SsR78mdl;D^H8A=}*;pBU5^$L!fBGg3 zzq6lK@C7wAfCbdmI)Pwjr1r6l1mX%H!{>Z#moxM2bXSgi!;yX2Q{4chJ-@fnp0}+Z z^hu;&0c{`K>BoRDbmzLdzic&M7XAQ7*qtB~Sesu2ydZJlA7t1R=ieEB0@!B8F26@l zw%yCqJ|caC1=WVWs}dYoUryYGaOx5K3<|z2HoD=UTmXn5ZRwcfAb8OeKtmiJ8hznTE0GB#1)mAl_^V*9SZ~(Fbm(zjQG>+`R~b|Z_~nid&WF=al-xX%$x%Y1LF@N z(r>C4oa*?5&QFNnpCZr%#b2?H0tePcdsarE-5tM}_n>Md<)j@ehQ_clQD)ChjRJ8Y z8|cbZr=}k(L0#WS!)zRrPQOc`3#v1A{H)zF1b*t5HWLcA2+sN%-qzAAoU($h#iSPh zMb^p9jtSLYPv>X{r#j`KUpX>SbV3!5PL;HE^A+WkXum*&8ssGn;y>*LjHN7aEo1z< z*g_v&r#w|h6~}SH!?beUx`h(k*zNyZ?%M4Q_?n_Qx#HtZpP=M)!Uv(f4mRHNkl^rr zUk7OAbDWr)!)r4p8B%D=j+z?2VeY>rt6>q0ov7>~pO`0|RE33mNtEpD26?|w!HctpT3P%~zB?ly z%Qn-s5QyzL3D1cr)X~fj+k8!3MJB)hv;x3(u9|%Nu*hs8uvm6q@&g~EL+^11%}KiI zw>{vz89~-7<>-yUc#EMDX)U*%1oM3@QgCu5Xme*+5B|GzG9GbY#A3!l6W>XuAWyc^ z;HxtlkHfJp*~ucko)$;v&^=t(jR4EU;aviCFa_c>1&}CyE>&dOef~qZ_PvFG{{)<% zaDM6ZHn2`&&1S4%7$z{A0XlhxFckR%l@Rj+FDcnlR;h6WBT>-V_eACS zL)`F0USVZkdAZarF1$BPxi=4Woe}WPqSrqg4H38SB0ZRvA$z^8vA9t~xid~bZwjcL zaybidiJNocHmCcAp4Xn@zBlojJHOOgHd>Am#q993sRD)w|87rz z(_EfVPh@f{Tu(MQhxf9V`V4S4-ZVYQ<$hUxW~RwOJsTE;06+9usqFsYz!B`oLon8e zyb#{+D@@)DVhfqwdm|%vF6EdZOqa?gysbzbBwGTGjm>Ub`!WPek;y4lmb47n9U+=; z8YvEXkxLzyjXlJdfm(8hp$9rF6(7t2TZ|d{fnf|s!t$qttbL4#Nw z+nCN91^KDv{&4g8`gA#1dx{(;N1YuM0Bu7j1dGu;3T;uCN|A6=z?z=Dhz5K5i9WV# zGyBNb1Tg6^bJbp>o)RY;wn`}tX)c}>}sITN)TBtl5T565*we7Y5)>l;sg{vqsQXs%FbG!IGP zW2}$V3<0`E8r^u_@`bQ}V_S$F()|bd{!BrTX@L?DO-(h>1RD(;t$#`98()~sP>FbR z@R9lS`&35Ei3(uARdw-CkP)o_D3qc3l1GM9a(NVFj4^v{)95n zL2TX+K}tA^JuEC$K0Lb;cO^A*I9NZVNpv1J--w2Tpi&w%0uNwU2l(?5e7Is-{6pqb1-QVWu~LvJP?3c z)V&zgBnk8_J?y(t{>$;gmP}0IVK{r3d!`yJ$^Z3;lJw!L!_UOS{ZBfEgvhjy^76Cu z<<&X_IFB#p4CGfSGxZg1t`cRxvqeP|K?uNxl*r^}aO*`|Gtu?r_5s^k@|WDy^B0Np zfFG$#5(c0v-BEYlEBI&2D|nxt6qs5=ZO*n73AG^HdT(a3x19idmc5>Omj-soU)@w; z9bvpL0Vl{kQa2vtZJaf{SDKkc_ftrLM)S~?!V-4ur#Z%wMq=0KQbu|6!q#|)z{lA1 z?czVC!(DgLGKL9EUt`*iHlvfgjgyZKpi-*U!Q6nc$SuP4a1n=!+Wwz}Q|}bVtuO=X zwAF5ogkk0YKgaN_bsMl9jY>6f!y#?kbid1S9Kmq~0j&|v`s`0Bm{z;d)H%<+e~2@$ z2PN{*I7qem47KvZ=n9%s9n}4Nt0ov?~bx z{z*8<54yOYwHtbxm4f%KqWF7+*Bv^3QwKgjFmOZWQe|jOyTtMafzQYzc2gX;%jQTEuZ{I^!MC0oNG5U=h-;ID3fp*HWC#RspUBf4#+Nq)@x zdYB04Lh?_Rv&Ng5=FDGCr6(-Rg4DwzHIj4*U*};qMW=c_?@(fJ+k?LuE`g*0E7}J9 zV>gk6cqILZOxo@X9Ed8dh?3`V)-!PXjy&g@BcM-gN$$DlOgqm8%|_ zj-%{^xpW3S4;FEozWZHaRl_>_@XAu$d$8WgO}vLDLFNJstU?Z6#;tn38Mg2#89C1$ zMW0%}njD2@pu7!MKos3&P3&6nXW<>tF;i1(*>w07SWoW3c!eR-ssR2NlLQS>;suT% zWal!L#*r|ejUMG7iG?sD&BvPlZtx~6LT~qE=k0rl}c+S(3C;C_@I5noJEY}lenIzVJ^84}6iMz^xIwCR@=DIl58e)3! zYk*uRy1jQ}sz_f1@sRQE0RKb)-zIT?bk-HG(x1Bhsl8X0@B3n}GJKzq2rEyuP+bUS zXdW$JqnzM!UUV{NI9xbS7||#|v;e{sWrd0Km?^P5d?~i6YSh_Dg98lMAMNAzUVfF> z#`wOx$M{T4Yy?jwrcWQJzsY0w>kp{kSau)Bnttw~WhXz3(*PH(&>9DS)rJ$aXS!DbP-oRYfhY!ulQ@VmA z#3_3|)xk5=M^@t6Lid#;Y^zys4~-y0MM=WUKiniKyM2ktv)oBC0o&6R(e#`+DD@xC z7?EgO6||z(pOc!WCncGHJ*P0!uY#-mBT=u5o_%P&wq_f!nBdvw*qL3v0_~~?0z^l~ z=KUV5&cJLA>AcC#BXf12TDGtzwQ_#xw*FD zwcyP6@6@CuD(r}S+@GF6g_;9L7vg5uvEGpTBU*G^IcFJb)Hw8WsPD%cl%@wv78sarm1v;k!F{aJ`1YEFAEj{e+fFUj|JOgu4%%70+p7~ zvFn}>W#;wB#Dr+%UY^WbUs6*)f3;V`*^H!(xGf5aFc>yJ z5$=Hj4AH82b!yf5q#SnKe)4G4Y~{tnSj0@D9FS|&HW z;r7R$Q^&?Imt2gWt#KyEyp!tv+z>~K!H44M&@nIoi%pWI8n#;i zsa;WMT}m`Lhp-W68l@uJ{>$+Pj;_Qu)ow|}$jEprc$MR^_~3-~F4h1b*p(`_bqQv+ z_1%rIb(_c%OPIBtIbjS4%6XVzF=Q}082guaj=-iP=e6zn{wvVoK6S+;CY z!TNddS>k6oKV#~?ut!(CoWJDdF2olA)nYkCS6Ch-mO6gPk40qclowudEjB1c>~Uih z!kA7+0vGTAlFJ6eod*bx;q5SkOC*59^l_uA!9?($kW(A?%10PVecFIM)u*TUXv4{D z*^NZ^d|AQhCm#j)RC4wS#CXC=KP5&bVv{J4jJd%J+S zc~A)U2kFBF+kp>1IsSc;c#sr{VOqmqbVPfQI1Dcpi3H`?L-RMfQ-hrFG{ z%FCk0;3UrQC_I?t_SX3+`BXIn(3?|sJPpI#Eo6@euNEmRU4g15p3?O-p_UQU`5%c) z)2&qqO32WvlTpA?j7$b2RMu}C48pXg)5{bZE9F|$D*KS)_N>5*+CSdj9)4fX=qIg| z#lWj*Q28c`a@9WBj!HP>YMe`RsysTv~{ityv7#2G5c1dj`u0;kSUa}$vC5M4gHk9 z^^V_l50BxD>w9Vt^4V#$GFVOvu|@vezc_m5yI&3qO)sU@s9)_=K;>c!J~kpf$CVT3SbsE21d)*(bI?=Qn8%%>X_qjv#b=i!bJ0p&-UE;;k|Q45yf<(rDN1^jZPEoy$q%+cck)LEq{Bt2u?&Jno6 zy|*m246+2*<4@WnId}UVGn>PfF;b}M;w@4w%^4ZAOTplR7`3Cjd(i1L4qJiZb3YZP zl~L`S!L;Di`sc%F_WU6s>VN2woG8Xaz2TsdT~GfL_&1&{oM?2q_Pg zX)2)S@{(XPM0IzLkAdwuuu~(iB6LC4FNvYIkk6m~qlEH!7#IL=-KWi^qe-wgIry?!l$dV{ zxx_Ve3pud0ZGFFAe2KB^xda;EuIJ_Qi6(xThoZk+9BBRU`T#%rIB7;wTD@6dhC@%% zuRkJ)=$b>`mUr0#7e?_yEZOZ6 zN7eACdJGS9wQgKyQ?)vf1XV*kAu(`>_+OPkWy4*4a$7Dtxf^i!S!HJG^Wj%ImkH{l zeN2S*D5^*KoaQPN@wk!Bu-b&~r(!Z9oAVKUt@$VeDim*ne3~lNMx%j|+@^{|<*fpe zoFZFqjt9YI!T}AQt0j)ZIwo9oucR|mZYmFLxSbg14qU&SXZbaW3t~C7h*C5nj?pL_ zWQXg1F)v7&jVzx})l}3{_%pYr)dfoR8kDS35;H)a3LeKOT*qymO?B=o71uviJ)E;5 z!@w2*q+Q}d$1Mh~nt~x!fTNMAXmkDBY9yLhF-U?Wkd5UsG{xm}EJV|eWg%U|+nGde zLzV>db~1Mn{?2nm*@6I6nE~Z`k=IEaKGLXk#25J@SGbCLIH9E57*f@U+mcjLoXepD z60X6IZ6P-m^~?%u-lC>9$8L`cP4CAUv-9~9MZSlSRyThf1!4voO!JZm2iQW|q8&O92BaF*{ z;&t=+Uul&N(DuihOZF7bDYGlZtjheRQT^nJS#`i1>M$gYHgsPB<)ku`yV7GS3Kpdv z4YkSKKU-QfLrB6d2o+Hav6D9H(4q!P`DH>qV8@#a3-LWIziRhXBGCtQvcuQQc7Sh_ z#W*WDK<={GyZWh+sv_BcKk*MNtc}85!{5%i)49awm8pPfwomcO*s($R7K|LFHP!OVe6o6ny5n$iy52MWt{4tOd^WA_cp;+mD!FnGBj9^g; zI^I&?Mh2yArKZ#~h`e?op}xc{ve*QRL`#|kVw0>2K=epylYCtalh)iWop62ceKl`GXW}FI$_ug|bnto;qHm6WOka`F& z{gYl-4-1fm?0FEADv>sBstC|az~^qG_GnUA&tGjt6c3wZA*PJHzehtn#5rCTiHQjXDK-V9K}@Bf{Xp_ckUXLo5dYgE{2hTlJD23+WDP z?tE8*@9QJNjpQF0UHnK2au0KxNl>Jt5fzCxv$?_duvbsvTjKqJL&AmupVo;Ek827;&P;P6w0sA4pBu6kHwvr_kJ^y+beajG@s@9AibeEV1cdMxNfjL^bK{ezj`NB3+x zXYTjR_4q$8Ue=Glyc*eo!e*polqWRkN$=D@r}jNi9d&nmv+H;l+ixPM1Qbi6P37Sm z(y%Cm^;F>s9qQLNRF}AJ$zrNZ)Q~>|dRz(;EAtc;ilORMaIwSBh?9S7gfU7CU9&g+ zD%rVdT?*L-1fL4WsL)Em_2_XV_mzsMy@{mG^JSd2YBFR#sEm!;Pr7g8MqL%xGKgr= zk-oP{TH}5AzzGDFouD+hWWA|0%akC$ol1SUI<*|&fKNUzp)au%gPVp`R`c@D9cNw#AV(Qu*QB*%i5 zE`CxtS%zkZq?gz|fUam0xct_+K0Cl>b)q$sBO4rsR8fbDd09R2+{uTcn1x2(Fq3RMWue zjQTvI*1gtI8Gh+&&5-bMggynPyE34L+p#MvpJsJiWlz}Oar;VL8V-qt(Bqctovx2p zXF;o0l~~YT{3T{GOT+V8%YsV4T`P%z0TQ%!5btNBKZ8cub0+ilUoxSM@Jz@RR@_C* zsMm{+HAD&Y$`YT4UejDyyRGLXf8KV`UYd-%fASFBF%*4^xo1aE;;%LsT!|ndokM!( zOOVBoHi)^e-@GdSdSOcYA<5SZTuNW;5?Mf?oR#Vox7u2THb32Xh0Eh7+Rjx2wB*4a zwi=JrqjTz&%B;}a__69_lM&rCnL>M|8ahPeB)}9Mjt##{q7r9HIdg}=vs=nC(xze& zCyVu%l#*)-9a4UXR4xTcV9rMucGYsvg6rXq(sd+ElWCJAY7a zp;X~(G%%HC^CcZ1VCZ=UfWxX8zo>h*K^%h1xC&iDK&p|Xis&1#e=|I=h*uj!`WvxY zQ?dUE(h+oBDH2<{G^rb^_wRTy-t-pz(0PA6g|U~?_WWfKnaw`_bZ82P&j8B zj`10GorWqRB$c@tlr;L6(2ScY%ojw5b!x74{yFWpBb?=?Cd#vYB_Q#(316DSy;IZwetL76L=}mJb^I5^BOPNJI)AJ&U z$e#g66@NXXdZT<($pKc8r?JR=9Xj8Ita_Q+Lb7_qtMZ#3uTOqaI+^9;?4gEvkwR+W z42sdpZtFh-ZnQg8s)@sqRT?xSo<~74KIz5qrn<~5BbuDw|DiX=*;h9BGxJb1ChK2+ zN)=C6+L4i#C@aJlu$|9{2o#4Oe><$VAJ#ipe;&mU4?K(_TbK33lKxC ziglTylKIS?7siSF-Ps1mv;?^dV%|fuBON>96Y%l^0MAP(eBg^0EoJ~+XQI<9*F?pd zxqb`QoZH1bXu!a;xEek%7mr^kt02Q`(W3r5=)W}^e6IiS$?X~s8usvur!;V&O7jun zR{d3@tcU65gMWOXT;o-6uY7hDEfI&poiX=4NTBgMgyoz4?vJw4FOj+>x0-uI>!kDO zWGqoIz%!K9Sf2mzZ)2OG2%JT~y`s_0JK;f_Ed6VjVmx==4D92`UsQIp72cv~TIA~L zmUEDW-cv)<5>?@P3BWLN@e4zBU~+FfzO0nplbeOLbyn*BkBm~DN4N2~wnw+ZgCDv2 zj%S883wxMXO1pJUSx3f=JbAcv`(%jRJ~m7dfMlk%h{x9JgmpfTGLU1s;`9Ez=%r%r zMcuu#ohvx}y;QYatoOdHwxism3z!3Dbr*8`dl)T0G+F$6ljcH;!|ib#QI`OUdJc0C z_Hq~x%@YGEJZ+2T7!Ht`J?l6}{gv~;%~VS7PH9$&Hdd+trgq=n{aO8pqb;f>h!1Y zQ{}!stBvD=h+x#eRWhb%Lr2fVsMlpbP;iR%ClvMg}%?HWo{yMF&Pb;Bek+ zQfP}5g=JiFiuaEwe8?zb=Ha}?E8)TVPC~da$T(b+=x=B$nwzj_2A%Mf4@Wn5rb#2j z6c{?F>`Vz1EgGaQZElzgL_FGLSBmK&k$AEwy5Afync@)Vgj!@f_;&tKX=W0S0Pwa# zLctPRdjZamAz2jc&%p^QR~hVu-y{3DVGG8Q4F}KKO(x!Fi?#B`Z)1rv51|?@KB;G2 zd3VCg`F(4OCp76PW4$MseXIW@&970w2drQEiRx_5PoV;lh))Ip)-yWXwz#_~^lcBM z1SMkC1~Vf-9o-fx7Y{1bMeAj-0AZ6WjoeTvWa(rrR?{P?{6o)s56k`sAdGmg4@rfQ zmT_THU7<)g>oDM-e)iSbs-|E-Bv+-&VWT5i=39)cs(DjfO0e>fPPAd_upzDB zWNXSffe3h6)rF1PrTYpWfZk~EbMp5qQ>+-%fLhL9VQ%zn$AxfUWK`QMB+OfN=fay2 z<-a08fK%tuTb$!uo3HJd5wRo3rAo?Bb@WOweaf4xnvI4`DxqOMZ2T`)tdJOBX)?N~g&HEG3dQvbInjQW!&1EMeK)Y+r{NKrfmOt$y zvx>uMt7Xlyeq1Iw5T^HDoR_;x`qt$I#K)8R^S*C#4S0V196APZIZG-y&-~g;fA23b ztO1MH;<$B6JEk%I<_nsu^AyuD|L9lD7KPoLy`sdpM_prFxYMs=XP7*~qt0zqfusf+ zaMe`x@mTM1o(5`l0FN<{q6Db`cfMDPF+n=EfG@%apFV8n$9((h+zwQaOF14L$J&!0 zYQfqu1&*Jt*%OtsvTO2_BVg`Uqp375YvTQh{DHR*43DO@`l>L&+u%?SI(($};V?Q2 z9+!y#p1#4f?5ju9*fopO9z%E2-n+QQ7tT*|csK3`6;m$?FjBb|*N>Vz40Q;9de`x` zCvvW_MC1F*C6fugyW-q1=yET7JHBPpi3B0g($$el!p^?Bsm%ZR*xmWkL^7zAkmydaa)IR90y79w^3Y55&=%TwM4|&ir+(Y?!`&YYSyMp_kP^mUM`v`+S zZr5l1{)}FW%UNGmN>27HKU49GGQ=i7Scq_YP34Y@%bOQr;^HMY1kXxfqF!AzYDyIf zRW#lJC`TZPZa|)op7Z|>){Nz|mM216z5_LW=ed_|(etuy+)r60>h^hzSavUH;hi>#jE6#puapE(5Io#<)bL`}{O5 zhK63ZM7pl^H@f8q&X=d=@NC&TA*K2t&#BKSCC^<{FP7|IZ%RRbnWj{V4tfx=Das9_ zq722!W8MBknaSDEBR+ar*G==IbvWvPN3Z{tPnSD*(+1F7oIaaR_6$?)QX8em)OzXx zG+rYI?;^nv^U6r%lm2D;j^3;|NX5g^ZQ%9M{`ee%-fH@TXf1i^N+6v|Vw^ri(09J5 zzSjhK7G`byk!*fYGa)#OjHAalJi0i~7`kL4;}`1d`K(4wbk=SaS3C{;37>Y{&n`Zg z&-gHF=PMoEOgf-jnV`QZTP8T$`DkSWAd|*I51jV1LG17_H0g8&n@Rn?{52mU57$DI zaCqytaHcnG_A2>XRH8qT^Cywac_sNRf^&%17xrrp-c&o4-QxRiTE&nVSvkxVE|@lJ zrV#91j$^KClwzGL*`>ugiNTq-n3k#H=VB*s@9xkkcMu(7`BAO7MdWz6MgH+RU}&9! zk255ad}B36A~Hg3wG_u5a=cFV_t&MfT`*Vio?#|^FAeJC2S14XU-Qq-c6EO-P$e#G8V+ef09W?0eXf3hUqS5Dc6lLVUaU( zEbHa))s^W`=>Y@GQHe?>+^>!J4YfGR%Y3K2dE7&C`*izkP9|}LfIIYs}t%+vqaId*(p+#tpaIN|{dt|*)&{qvO`DM6^@X@f8Hmon}m74xeB4HleLg@Ei zkx99X+G`&x4tBLeHsYSo=O1k{0WdZS8!lYL=Ul+Ja?dBZ8e&uhj?3c+`bMTjN+pxV zu{xht5e)zS$qe8d0c=#fX_mkxqiy6sA39=>jLE|gC5(2o$$=zAS($X$NvIr4eBFGm z?CNJ2tZbIZeNdPm&s7qPY#BGe`#XgiggWdL&7pw=J|PsQDA0GKD}Y^oZyueUNNz0^ zWWzjX{JIgJ5MQ*bpT^R<86lIkdS#IRWC4FI&qYQtwKxX-1$bnA+degAfsgy5<;gv! zHsdMi*Wd-G1k!<9SYlEZyY}^3+IhmzFh`9l_$(5X(n?}UV`xFXel1@E%lOEm(_1KI z^x+y0_|wfrT=oT;#k;PSD~IGtL^z%ZV<`w48T*ciqV!+OJ@wLg$2fur-DQiHv2)8pWQWG`k2+pef|=7d@O=3QAgbc zsg`?NXGZjIt&E&%tf)7j^$(3Sn}ax`XUJ+Wo_n>MnL1LVvejVF`7%$PnFJX2oRhBM z6gGP)bP_}T&c-87dMGr)Yv$L)2CqrfkJ0zsFREF!6<|$^DX-bAV5#@SSc6sjlZTyXyiJQx7{8Q>p;25I+X@y$D}63B#y=Ir&JZz zxwudJ;@o@##}TYMB!<|bI=kJ>)R8E}DGCJ1>Qg7WgnfYg&OvPQ8EOtj^vHUPRbWnv zy7=|soM{P>q@1NhNJp=`u3&;xsjD(Q}G4?2X8|kpayG7pmX}v=mu)-#TZ!a7&LV^PBx;od7?; z6Tjb#d4y&ETXt+~#jAFFA1GA=k%w*I=j`#=x4LE<99@SvD1Qj4nLtVdd1s&qtO_d8 zv8W*_^f?FZJppjw^#%{oT6&PKu2CG<17wGq=WOy8n6&JGEflT3D_C$VR_~ZiEY=T) z6Km=YaC1yhAsp>CQgYh$3~n(ar)ySz)(fkh0+ltqk?<$3MVxF7Bu~l&7r1!-wj>U; zXjFQ==l!i=7LedIWwsDhsK4}+Xll*SiA1w@KVgp(8pH!_SH3u1mN{; z*i(W!uL8j8&xP{vLr%+a6VP?n!a?W8!g|ND))KQ*e-|VnmO)BMN z$bSj@;t~rO&)K5Xw}(0}C%-x8zAaNyf+vqBnRJ?BjOrLB#>?B-f>8PQ3(W}IAD zeO1xd2H3*!CEDjp?x4(F`S?1Q7FXYZ`|GNc3DgHXdw_-gGD0YKnAr;M1=y#OdM;#q zMZ$>Ss-9uS7_W?ueVBhr+c--md4k^9#A&}T?YHEFy0hbT8)$ppSCf++x2`(GkgxIm zMkXh2%vN+A#se2Hxv2YN3aHYOHO6!tN>3(p3l(6?E2_7`ssZtc`13QecY#3~&^BcA zoxfETzgg&e07}^jw1+I_03QY{h(WKkU9d27mzA$}&q6rUHJ2YUOc;L{wL1KYsa7+ z_U2G~x%Ucf&kANttb%6{u(oms!5|bWe>;xpznW);Y3^l!*t=kEToS#tNOU8kIjuKx z%4Wafzzv=LH%Te%2>2`$h}fp*#q+W@8xQ42`Nx9`*Kn@j(=Rt7ebmuY?Ywg#iw~MB zjC$Tm9qSrteLE%IjntpKuq=$NvYK zAMH`KO!u)G`hZ=nYkrK7@$xYbk3%}b?nU{J%w3Er{H%&D5CF_;S=#JH;v^#QRimF*dg&=tT1y1X zVGZB8xBa%~vJ^#ffHz3Y2n2>dl0TIH2%wZscLcJiGzz+5zY)sVd46&kbDxSyG#QbV z@^>n&7s_c=tmJMVX#ug(0`YA$RwfZ~LxrxWoA~cYH-PUSo@tJ^s*gCtX41VefvgD_ zM=HM!k1qS){fKMuY7m%Bk}69>!fg4#=->DEdUpKc;5J7tteV8D$u^%!>3tJ*arTh; z>cMkFNv}kcbhDx+NfQPhO;{Z?XQ*B{?Fx23?F#gKyQ~ZiPQ&jspiy@#SarJC(yUo| zf@9U81c15+(eYam6t8DD=NZ0f+2ZYa^TfJ`Egy?20704JZ!1HDsL95pvXK+#PX1cT z5Xao+ZP!5g@!_=SEl%u`Px=ohi<{P`{Y9svq4QH*5X~=JlSU0&eHh;%iL(7Z{L$=^ zP60hNL$aomOY*<<4Y>U!R*7W=5$vBH8hMB=D1Z=q>?MAoT81H6=8nzf8#@VV{YP)O zU$8z%3H>t^(Ch5d8`7~V-e5=JM45|;h3b;@tsPWZAuMauR6({<1ZgbHUJ+EM)nS@)yBmdC?1%=(9InqeNLBKU@ zDPZr-Nx+&uPMV7RxY~=$AWuo9zW2RGop+X#vEs-(u)}W{SGx=6{{dA%s=w1@uVL?9!b>|uO8D(A4*YYG_-aD4VNsRsE#>;NjryMjzw{@Zm~vf z+lQMx11m7R`BPH~=76L$0$vf(l{gb1S4&y{x!eDLt3vVm<(1gmtVyzK_(jnEFuG@! z0a6j;y|H~!mAb#iGr4u)R@M*}CvyCdcTDz)`T;i zL?nGCcXY4mo9z^zC5nF<9TIQp4Sg@u?r3uwuPc*nww%fE@(_0}7fo532eMI6-$i$F zPTum4jMtd`^ZP&g24}*6pKVpN{?NHdDMNOQc2;m+t@3pu)fd^&1@h#4IiF)_-{L=D4gcW$%O^ zCE1}$4P?N|$L~lKU-Ppx%<+N(%7UmQh@@>$U70SRnN$ZCH|+gO`PZyJjh_s3pFO>Q z%;<)9ep1v(Z+Z8MwYIhv{=T^j3`{-eb9Mf0u>}6?z1^dm6SM$ofsH})rbmvZZpG(& z6pg(n+c*a=EY(Bgp?Gj^NBgYTP2#LMM*{<8XgGniD2Qwwr^m%;k>%D&PD+t3(=A!> z=NIWYANG#*H|V^6P4djd?<$U!CKQr?HYm?*+7n_#Vz5oIuPAGetrx{hlL{|n;+Cd` zqxPjrGbBsWZOn?$u)W=V+EZz}iWu-JXq{7JM||A?Ucqa_?}HUV#~b>=6UfaR+g^G#$zB3~^+Pcn zaxbXKTn4jMi^`EI#=W;BaG@a%boM}_*Qs+c!lfv65CZkS%p{Hk2MD@q0eeeA0t+>^ z3WHmZJBC#wg^#5Zund^UCAqH@x9CQ#xY_H3@wW5TXgBjDdlB%6V|TZYK<1zeIrz-s z@sdCRDAsT|ButTM;$?UGCNg4whP4v#K*PJ=>)pFI3wB0Qg#wl6p&MFt5JX8CMTZhv z-w&KNwzl#CXLa^j=L&8^uF5QgJM*0M!RxX=PXay%6sj7wu=@w852z6-i@S-xqpz z>sm?xP;?7iUnVjOU_eR?1G;o;>K3t{FaVJNrK+2)Paz!nOCis4`7SX%qe4p6qN463 zJ#HOVC(@`>VWCelfUiM+edhc$pi8%J#zZ94T&Z6yll)0ZO7FsCr`J4W3}%@MsRbh^ zV+73PD(xx8vrL ze6#2a@$KFtfCAt63}+>+H~F2BI*Rg*LgXqHX;!>~rd}MSm11sxTP~p{0mX0=xw~-K zuWM1|xx^q6I^WjdAv-~#9ZlRURC=S)^78tKVSS(`{rXEL)J;uxgvmS*IH1yml|rx5MtfxLp*Dk_}a&( zvj58;{Qpw>q5S_EH~cF@{~yVNk(G&oz2nEn=k}KH{|5q<=xLK7FB6w+loB8WG&wjq zw~&+)N<5Q<6B3soR23zc644UemwM6?9GCy96$Y2Tsuc{EYSI!8mp-lK++N!m&wr*9hY{}5-*n@-xU>?|Ed)Rm%!2zFPFem5^tB#(h?B2ZqpJ-0R%TO zF*BDTf)pZ`?*bA9e_gXSnsjViE4FQ`W7}D=ZQDji9otSiR>$brHaqso^S`01coiKn!RCU||6;b8~aUf06@4?HxRwEX^%k090zq z8q~D3bpIv!=Lo>q^FK6Smd=*ub^wa6g&WYu-oX}V=kf*de{84%1Oi+vfB-W~8z4Yb zK~YOuUJ^hhDX#{Q1lj?ejBEgkuEsW&CIDGW6QG?lkQ!iS?*#Y~{Ida=*xQ*}{*#(B z!&eZ(&Hy8Tf3pM7#PZ7w=wSkM_(w$tZ~!{lS~@#_tpS$K0COiJJD0CJaIpti+L_q6 zn*I~Om)z{@8oxjsob10&*na80z!dGBU7SsvEFD|`UtSf(B>o+zi-nQPKfawUztjMG zv#*n;_9m|X+{G7`(LXR>S{EZrJ7<6k(Bn&J4=@G-e@rc%9c+v|zkGjzIXGGVD-2g> zOFQ%bihvH_1T;5tGPMCZJAc7^VgGYG|CQ%IrvH(>k%NPc=fAA&|8?p=W3Y5_2HKc0 zz%sLZ`809)@@;Nu2g~?Rqe$DC*#nrF{w+6kb@&gR8_?-r7ew_>&rp8_VPtA=XX6Pl z1)9M!f6Cjtd|fzz>i?|D41oW!BL5GR_#(_`s#FH zJM%AQU}E@c*?(Hm(pkdN18Ayf>0)95Ff+3Ge9R!HCnq||){C>s==oU{i)jQXVrnP(a?-dFRo zTj1IpOzH4_VH+Q<6+2ojj;SuPl;1pJPn=h8cjYRUfej{cX*Y8k*mNMf6h|c zVtjwQ5M5~v2{(I#3lB#GaTc^#VUuUhD*5LQx|FNrVX}-C=LZliN;FeX^*1ryOact9 z?qQl>$l0m4TN|Cw^|p*5=(3?(&G|Xj58?zo%Jw~?+4k(3MSB;cICg^xNe6`n4sJR~ zq)d3uT{~iJa{YT(L2IGijU|2rf4~&oma_=|y_I!ZV>LPg?FDj`Fh7({NY*!R`Sj!_ zP|q_~%OpJEuhYuj)4_x(0DXMe9RoOZ;Y2_Bqu|;F6M=ME|b@V4Mp%*t`5gp zmT}_qRUR4iQcAutf5Pi9Z$Fo%fg>+WnERFb!r@U_;5HvNR-tf26G{te$>)Ii zD-;d-ZJQ{KOXA-3rCC)AC<*I19Qf5O%MX;O&DHIdVRxLp4LUW28mpoY?jo49oAbg# z1uO?g!wG?Jd9H$s3F);Ivz2P#*H?V{O1qv$X+#Y;h>fGA{!|}Xf7zK>#Nx(f2&Iv8 zM8;p|OIAE^(`a;?9+~#zazWq!iS?YqTRu=Bexer0U>)dO)v0eVa}AWT*!&wb%Qn-b z!mQQbgVd6m7P)bBd@x6W{gEA&&J$jR7|L_6N`KIn>zyK2EtXc>lGcq_JG$W|f~{WP z+wrVpP!?{MNLI~}f6*+aA5=6n-65|S>>;l#!N^H=M9F`+jTn-@%xe{c=vg~SaAV%? zN57QT5@gK$hiHa6@g!mW?^-7a#dE$=uM@cWVH{m=@!K)Ey7afJnK-(gh_o@lmgL-4 zBvnTVOOTrA%tP_01k)iKN=bEtshB|P%)>wgKaRT57!O{@f2sGl@IqhwWr&JK?yewK zC<+7f@YeFld7A|uSv>sSlGhb$UX$8wpwA;VJyG2dd!#GeK^IW8yL~`d#1~c=YD3TN zfjGTQF~TK}ueJ!*iiLE3YCd(5B$_qjwF^NKI5z81^311<)kQAp-Vfi?#cIx{QyfS8 z4I^NY&#ec?e?=GL1LL*bZkvv7(gMJPF`4fpI91%2vNuj+i<=G(tipArDg5ZA zCTfffRY-MYOlwq%os$4C$3Jz8?TeGZk<#d=Ut2}L4f}A)&Lpr7kEMY52NxDw*muZ6={3iK*HXC+ ze@#&Ml$!Gdg3V^(ZGhfg0$esf`hA3N};Kw}nzYEG+pRO|1 zT3h0p3_N9i*7F+V4TBxdByXT~1r8g2aW|@2f6B)rZlq)V1LA@o?JwX#C+l^h(+&z)U41V^o*g6Pi?5&?`B4st zpL&)A7|!ExCGO?*CG>;AubqAhe|4Ae;gcprj^eGzvw@)tJ)v9ppCT(8MWV3r_A>T1 zpmQK<%PZ3aQhzPBC5p0!WyY6W=wTqC^Lxo}bHqAUe(Lv+G@r^yrRL#R!nmk-ueAk5 z1w)ITH@0*PXlAz+8f-ij8|;he?+NFQ=k)RYU=qK7Q8o>Ovtx!caV(Fkb(i_iX00s8e z{?O}rP%HS|ySYf!KKE$}+L^HvuW1%Hh0I~Q+*UVu4oo!MHuBxJv4-dngl#+>m>kpw zR`mPwJE(I|=s!T*udN;72R-1~hFT{RNc1s~i1Ni&U zjOZn)38l`x zn^$<-HGN57B1ZfI3IY17G=0PYS>KB21vhh(#8Y@kjlH(}24wWDf9n-x&&<>8vh0x+ zHa?AyX)(w5=0Phy<+8*`?XG8J{I)R9pj&4%jITZ-TGD0|p=&;SX0e@U)bh35z;{`M zZHN;ZZJ3hcgBqYgY$)3FT&NsX-X@Yt48TdUW4-Apt3*=3zC+-NKV0Y_74GufHWwOX zTDR!_%^2L#&zPesf5q7uwK!UsDb>yzn0#s;%;%Ua$<#}^U)zJK!7u4J&zJLwK-&f{ zl1qoCncC1e)NRJIhIgCGOui55WvDnbzuNyjP`U)u=E)`bf6;8k!49oxph?t;-gk4$ z-A4~@!virm3%P_~ysg)!mPF!XV%WyMqvDAY5wa*aIB}^1w(yS*Wf1%4b1BsEYOq+Z z$8ua;L-X#_WIQq3ye0`IDZvVmtTw%!!kC)T4ohnre3x9WYjC^#1H?}aRIHZWi)E5! zPwJh)aJ~qe@E_)_}O-1zJsF{^AB0~nY{9AJ_y^2DitVnb-PR3ze z;(Bt>Zg@tBUVcrEop1~TF9fIHt|cf?o)FhVS`;%-GW%K|9*3J|bX%P=WknRz9B%8! z2R%ppI`bP1O~!gW=`T{Vgyr;InEGMxaI(8<&Ik=te^8-9^~A)0MyYq3%jVTM8Nr+y z{8iu^hCXsL42^my7>Bg4qy0!4;pYf*FMKIpWynD$mvtLtmt=UcpleL zdYG$2i0ldY0J1#QO`Gl>k-l7ShVp%rx56|nQDe$o+2}-cfM3Or`Q?pe%z{|&&B8!J zNhi9xe|#ct^PY7@A_JWJ)@O2Yy#hxvHej=XIvA7`sh$mC%qq~wptbKxQ^XrR9Bs&Q z?gfj6p5*|^Md)rkjezarQ`2jD03?eW#31gb9iPfE40KiqOh$+aVtp*RdH$z+%p0y? zkDpW$@$VSQZFS{80~KSt>YynB5K1RY$q*_RV`SK%qY>O z02v2eIn$R?sw#pXX_;F;4{_?Pwwcj)< z^-2ewgzguQY6Z3r zp=*N8i>gDYl+HS%wfG#pkbI!T{V)jhSfDyO?9jWiyKho1AM!pTT{TeWx$kv|X;e62j z&UfgbMUnw1h$7t+JdiTm`}y7DDQ%~XuD|<# zF(opG!r6^H%Ww@iCSq`t(J#;8CPf>t4O`jP9XU8Stu}MW=>4HMNc@se1QP4$hh2-% z-~vy4XwF79{?>EI+5af7YU8_;Vv97CA|QSUM5YMm>Ppc00rn|REPEXRH?ROBL;0wE zPt%Sh@Qg8=)g3@7shy;Ye-JMaTzY71q42vL8{wwxw**j`Z;O32GM&D_4L&qX!6~_- zBLo^SP0mocSi4sO{|$_en~Rd~g46HLGCY)I^jW&Jf(`9j(3BdoPC{6_QRPhUG6ck5 z<@o}5ooJAkYu?7Rjw$#e9d2J?_;BpwaJxjkpE2jJ|7#ym+$`FDf19cp{~X7LTwUS| zrcx_js2I+ZSk|vTfd%a+DydF6r7I-i-8=IKagaJ;Zpr++@#!SmcqbRCbGGpA{WaA741jf`p*InuXql;;w1E!j#^t(BrwE zM9ax)NMo2Vs&Kwif36xFCkOJN^ zbQbatTmAkeXClhm+bE$P7afA3&oTx>HTEvYw7=i|2d zYgm)^7h1PWgiOuf;;c+I)iuQ`q~z_hbWOVD?lnZW*AoN(^)BgssA7t@NWYe?ghk>f z_B0^_L;pkBBO%`-Hd!ktH^T=jK-a#fCBS;SgUdA2Jn>J-vG_Io^QfIfhpJhBK!?lk9(H2SHVi zjiDUEAYTDkgag^bmGhs!F>FgyQq?LtK-urL%zsN%f9dZ#2h$tmG{F~M>b9-jxt$vx z)-B_lrg!*=bWe4U=#?bFF4UQfYS{hAS^@ZVEQz^6!YQi^zQM?*yWf4}oy3{Jdcc+R zJnD>YX2Hs@=6iv0zC9V=?La1f%ig~CY$0`-9x2dp!ur)e6fgu-fBrDjgh8e)#fB?G ze;5HFf8Wu;iBiqyOcWT)pE*u*jax#S-awf4m4xO?K2E%w6EPfFzJlagHMwQaVKycJ zpGB!z4WAn;Pc@$>!^mG&UgEpIECza~-JU`7kO;j^mx#)kagqF3L*&koP;Mbv`t?pD z!Xc-J-QEi`QW=ZNa`FxDlwU$1K7Jf(7{x;we>=%^?s3mIrrh%IS6O}ccRfLObSL|X zntZzm37Odw@^2YwJ^EHpI%OuKA;Ds#GHRF=SE=CxndSgoo)%5|(25k+Q_haE0Q+aI zRC@+()B^=iO-oNd6;4ETdgO9pkQ~pzUw|E_KqictX9JWP?aMQ8O50zZ@q8xdX+THMVbk8g#2Aw6q%vOK%%S0)!bP>d;CEHF9^IjuKbLtMCJ)8q1Z(#-dC;lP`=t zV^>wsA_3Vxm&Yqp7}7=q+TWQmD2%Jif7>$sST+&eM(%GR+~*$83|8c`q^j?!Qu>Bi zTfzte*GVRq)3mutRed|u_y!n|d2=b4WthyQ-!Yb&lc%YomHgx)yk1~TI;_s$Er_G# zHKz5i{=_%jn-DXQ&_!^s<;b1bbN;P|t%V9LxQZFuQCFa!mS$9Ve5rS32FMK-e?XDy z6TB#YXIiuLlHOshh24~D1b{=)>V<-LsCAXZV#0y)Vu-?rDz7iqP=iIUWXh+pSPpD_ zv;7Vn)sAOd^W=nNPQ^F5ztlk~dl!!>Pz-6iefs;k6cH9=g%I(#MNNhs+S+1TtyhDj zeDnzS*C7aQ1m9erzG#nMcD4R?f6MfCH9IBrwv^zbk`KdZT0bFN_efqzFd=7U6)me2 z(-tRkCy>zQIw`d$`Y`C@VU>40MjhKDY_(ucC2EYoo!jD6UnLNsex(il1WHda37WE) zHAepUW?Pm z=5M#u$YGRZ#&j?T!@Mok6m<)kwscAw#r>;NK*42?$TW*z5jU7K^Hz8UC+NpV7^h_4 z`$%K-`Ee(7K+d4Y9^W6emB42LcTaE-?rf}2TXA|vw$sZ8C^W1Ij`O}6OHlr#A`<1^ zPOWsFCwhcGiv5cNNqEIYe=Qbh1&?YhqrVhbx`@teRvHKFDaqpP=>mOtznSLD^T7$Y z82)s^7koBi8BXln6u)efjJ18s+?LsN?eiVw+fW)nrkul5)P6TRq?b9 ztI($k`Ar&}8OCAG1BNeO*ZEVN(FO~hoz;|jMbR08U_bUHe`Vkn67~;kt^WN@uMR5b z$c*7!s^N=Yl+cfj!0Jlroa!0XGq+JBq1`E(Wc4!h&u;z_cUhlU*{+GYsI|e;By+Dv zN|7gJo@b+z(MbOJt)Z9iB9i--`Rc^ZS#|{N_oxvWz7y$Gu-QXW##KnNy28g|g&e4ImEbOk z;Pqc)OX)bGkQZ53M(MHmaBP38+Bc_wsxf~KP05c31(HJG<}w_}=I4J!Pl5vOf)PKK zEz_FdnqpU56Ts^ zX@cW&11n(opwCw1UiZchQfxmVcZT{|R&3tTf1K2CnC@FgJI9rib-oy#e6nDHw5vM7 zf)y+)FOiag+h;o`iM!i475(gLf_X_&v7o)OSxSh*LbK`j4anPEQ&D0cJR0T-V2f-P z{v;|Mmh5bg2sXy=`#ElCpy1`@I_JQZ|LatSRxdo>r6{e5s;ewOpLd}?vC6K%j^9}F ze{$;_iOVH(hocecK3*P|juv#d*0lRJDkGpWY;YZU@R@avxfg5FuOC<~b45Y{Y=j)% z5w%Hjv$uIQFB+G^`#I2)B9#JVxfY+Q0bU?9(WDbK6pCh{#tusi?XOBUNz_VYoV6X| zj(uLd`F-Lkc8iLvu^tKjEGz9J`W_N1e_lMuSj`M?+Cr(9440Y|qweYmrB|DRhIssg zS48|I5K6{tcyDegS2fseTK#)ZVVT~P*tM4Y*^;F+=^4Ho_KTmaY9EHUD%el0E0DFM zbYvqEc2ZfgB?uCW1MC9Pw6hwNE@kyztV<3y&?rgy*aeuN+wK-QuXh7pI?}gOf5&}- zzh(S{mr$6(&o|ZX{nWru|36`!k7F{jrj z5XE}_eF}3EbHy3*wK+7&$)WCg%4heG*9%~Yx4&g5hHV$=+>S+q-yPhH8@ioI^(AMF zwqLyR48pSXS7`6i=(#j^Iadxyf9bly>g>m+*w4lB)-V{Q&kyYbzi|m}Rn|DJ_3o+O zZLt%$k)H%bhx)A8w-9(}6D}(Fd{~rrCb%&4f=v6o5b#A@-Xe3@x>K%jk-RKkBp~iA z>hy6RxD4lXzKmHk+q1gG#@oGTi(pxmf%v9TdP7$bi%PK%Q=4P>%?e+#E4{Q~WOY0UHMOi6=0{t7GVSpO=WNTCVqg2VDSS&rcSZqWNLR(QBM zWRq3jo9!=WFresPRX`!Lkh8S{-c;Is*wKAQ*TQJ_y88Q3AyL3@+@Y|^d!y-n)CSKB z5(fVTM%#+XFj6`n=EZ(yf9WpGy4D?&q+T%di>uk=ilvXk;7iVdxt-dx>$nUN&w;0@ z>zWPdq>+a}wByV$hUpUO#IqY$6BJ|Lk%-HUs6JmK0gL**`Z;%4rS3DEyuWGeKkwJ2 z60o}pZ;xV=iqe2Z6~@!Un|z~jxc9{M!qSgBaXO?kwSL6Kk>^lRf9Mdlo|#Pxbp}m_ z5ugHT5B|K+tEnp8E1D`(Ot*NijMDJ}X7iw_`l)P>>>cU?)uB^RB$77Y*l#E42jYkv zD<)DV{4I2ECfS$K>wc6i_=kbgC%QH}`3ixFnaaUq7OM>*Sx~ql(&a(9(a`qOs*qyJ z;j?Y{J!(hjZ5+n~fAH1yC;}SvN(pbDLF=1;@AC)aFR#ToCLsqm(*dTPB-RSK<}5FY z7O}iGtn9St46QE8{Yr79&1+>JwwM;vcyFYUa4C<-8db0mB<35~#zHw{#2q{oF$2PQ; z96&^GKR{5db;rTFn5^MudWpePJ~Ym&sBd-G-B6h}&`I}a#~`mPI{F5Ib;-|mdDTvP zG*^RCzIQ#_^8X%G_TXG2BRu-ppfVuKA`P8~7VbX^?F~g!FZ$r_>ElN1SX@rC;lr|C z0>F5#B(l7(e-sQY6puoi^xA?&(X~hW20Ej(aGF)WI%I~4QJu1fjQzqMbV!uFSs+0b zF!lw3adsz<3!L8Hs{Xlh6sJ08=Cx^Pkzq^dIUz$$`kktzkhJ$TBS+=zyLP`ev}Qd* zujs@N^7;6P8$;bQmv4U)9WkLQl&0Vet&jBDW8GblNfmcg4bK3%dRzt9kCpQ)W+DpJE%p+YIJEmrn+(Rs(_&>sDFBy)!-h>> z)XeMr!zQ+XSM9WjiiK(U#)HlWiy$v0R%cN(6<%S<{%?cWKRN~%qE>rtB+Mh;%1LWU zCH5`ne+6P=9DX#eFS$pT@hd)+m!WIs^oIfwhy#8Fkv3|rYAbf#sY46K^AdD9w;y;# z{QO?c(ZZHjU5M>D!z*>yrz{QP9OL_Lf@z?mg4Qu)T_0`am2n(oEUc}1y#q!(UD%{t zjR3+H8IB{(d#<4x;S|a30=U;W&7fT2!elww4G6|=IFGuibe#270TbaZ%^vZn1&9kIt>+d ze?_c=(W*KGj(784AB0ue*7`cIRG309){t4a=%5QG>j^5nv&IhSoL31ae()LFWaj5q z)-ZA%gy?RpLL1NG{l1}I;?w}&=%O^vQVwsXc`>06Z)W*8FoF)@ed=;V3;K3Q9})ls zJQ610|MS=UK|&m{l`5DSu_S%~u#t?be=^P*zb7zFdm6F;-`s70`nrY*3jM?%zi>-= z!K)#j>x5p~{7q@uXurWaXK>hYy^6P1`q2|*!v0aNBbL$EPm~R(z+XLt8?Pf1SzI?o z06E#6CyN=JwmH90vSZ#&5E2ySskKtJK}R*W(;dwXiBK$&TprkJaJ zm5s(Ht)dY@FAveBZ~_m)XiYZT@bCpJJg-kE>qq)TWlphHT9h($z(T0jw?nH};!Ri& zo*TNoWC0b1k_GD+(?85KuZfYNisKIySL& znq_FHK=W~<3WbJ3c<`y#>i!)}8Hp^o`~aVM1)?y|6nDN4D%ZkkS?nn6f7RiDn_rIQ zNGxroXjUsUZFr0Hwh%HXk}ep1YP1VPTL%)ESOM1N7nu#d2M^h^&dk;OWPGnt!Af2X z=$5l0iBpy#ugz4iGGG#0?zZefJV-ZBM+LSdy;gbVU67p{9AdG2)+Q`yYTkiw|3;%^ zXI}4)tlM__Yz3oxw?@+8fBeUdb-Q@By>MgGrH+XP5%v+3KTd)XX6pB>mNViPTOEWk z?JTo6%9~o#tn}T}lQn2(HcS_M_W@Y$^0vT3@$XU=nuF&K;E`ja(2F;_l4jpmJ85k< zzW(@ zDDa%+aGG@{HfPyFZ@@L9<+Xc;?LK`~XwQbLAT#zD3<9-`g}#gfqR@A(*Flv+O{!3e zhrU{lxPF)4xsJP=Jg_DuRRcmwsc2!TmkTK(zt@zFbVp!IPVZ634vm;N+ZD8I8J zVDeqx!MJg7YxDKWMc5z1A&Pk=_SCR3JGA96>1pg>V;UZvCm9u_m5NL&I#)cVcL+*6 zIyE0y#*eJkDy`G?OhE-E=7Nu$p7IS}htp9Z$NP2O_qfBuf0c}&l1LUVOnz_+^%k~^ zY=Wa2U(4I~j2q4L?c|7`fva#rO15AeScd&x*p-4bx(hESINBr1RK8PGSAZO=hp4uf zb;)@b#h{UBGrJqnvgYS9A3taj%8>?}=DbaW7g1$AFeMU{5ER`!zNy!wB{acX{v<={ zU7IU0c$-{~f6*3HaxqH`jx%(`=m@%`97h$4X6|1ZbV0tLNG}F^4U{{5Hq%NJ6_`}1 z(;O}4Q4;KH153B2uJJ9xzRN7px}KCxHUfOYcvl^uDV0qDEH~I zwe$9BFtbI*lSlC}`KxVUAM6)FzKM)(ak2;J0H}m-eI9Y=xTrbLlTC>MeY~=b{`nB46f)P1}@e6*(`8 z&RejU9HmM}Q1@T^_L%cDD;p=&mxlBGP<_Cf)(D)@HO@-O`Wg8z{%=xoq27J|JMf+D zhDCyWfB9T2eDW+HpZwo_xT(wt+qY0<7dOT3-nh4?OiXkBt&Bf3kk zqYffHWkN|RNWmCyX@w)*Om|-q6$(&a9w-0}rf7~)y<&mU3e+SKhMSS2EX?NvxV$#Ya!S-_< zTa-&5pC1obkDUmF#NJbvu8N&eC22<1#DN+3qvB!8qb&h0_~XAZy#!QoF^EV>ZCiz}Ozp(P<8^kblWS${a0I$o3@e@Wc? zQxm{Cn_|VH<2`;M?Y1FieF`9Qyj{ZwhrA0&>UJq*&fl=mXnk?6x7i?lvp-JS@0T>M z*w+|kIt7s_^Q$DPP%q64^XEd5j#P~JgFW{t4jtY1?l~4tF=eH|+6MEOc5GCy^y7tu zV47x#x2vHY#otrvSHzZWOyTS0fAi0l!GQUfT56-u!!)u(BiZ8b?AXw)>oMKcyezU@ z=0bkc3ravT9EJFU8VdEIX%&b z?2{_A=hTKMy6EGWMS>~@V+1@LEzAK7K+FZiMM6!Hc`pwaD5H7Hs(Rcrik{vNR-p(i zWdwG-A|Z~Daw2E&f_Nz|e|qi$O_8HwNy_r!@JG7Q%)&jwRL1i3Jy{Jh^H93w5YWeA zEJkv6qI_HwQ!mb`6k+zJ6nf4wFWtXcc+Uxuui<(&$G{#cGT#|&mD7yby00o%frB_Suf(*yS1u>K`8X4E@{e?VQJ{lzjHt9Lzo z5Ew|LeI`TU=FSE7Xcn>rk+e`ON4r}xB1p4%e;`SB-e2gJLv_1Q+4bve`yXn;Hj~>F`{0wlD%Wc zqIg(PhfYyCcQ)v68^b*VJ3F!KU3iZUk?Z)-vi|0fbnb2)C3_7UFhOMPOYG(*kfsQr4;Q+9}+lhVTAp(LWr|#>G&320)D)Q z%%0NEu_@HFe@xQTdlT>4?TkTXrfLnn#F}ZH$Ih49tp?48S+p5|y3CH#n&(sw>)3xN zJeypl6Av>x*(%|98Lrw-4}nH9^bb^GS?eSI~`R3VRzwoEseAAAuuf0xqkbHr&oZuE&2FZ(n6Ge-** zmLwSIxPKB>9gE_R`o|BjbMVeCMOy#m9lf8^$ACE5%!_MMH5>A9{@R6R|Su6=8AeS6aK#);c?fS0v9HJ&%v@Y6y6C>pe|35UHvabSxgkY?#F|%JN8X+=u%(u; ze=E(Uacu(FJ0Oo?OSiR_R1-Y@JOFT zeOpElK`m$775i~@)~@{X_fEBCVAAt?QZS@iaiN!FssQhWRp=+a<7ARqM7fdzRNN%r~U<9e51tVDLPB{6FL_KKJ z12J9#);8+$_z$v}PS(~{tXl&Z645-wNv{EnOIk&VvVbvF6+v(K+yE%_-TK|Ue?>@? z-Q8kea43yKWDQrF-f07+D);MrJlska*UKPJB5PZEeoGK8?bPW#?=rKF3TVE17eI%1 zgDm*lKuTPk#~2sJip_dSxCql6UIlNOo~OmnW)g1Qh_+crw?L@U9+P=7aMCBX21sJq zP)oCi@dnqGj9BgXUzFvwsidY=e@=!&PVei3PnVBu?X~^)k?v(~@2E}*ctH|Gk`94C zDv-eK5o)qjA=zUwL%WMckVhxV@p+I=I{CegRdm&w{WT@2?5~mzAoRB2d$xj(H0E>~grAP8Rl%Xgs{FWfkfvcTa<3UtFaWFzc7~I#!zG|18()3pL^uf8faD(e@4m z7rPPsY2O{(o=Af$6y5|8Dr;FMn(r9h#BG!+BnA16sH*hiq4l*Qf1H~Dq3t@4f2vk; z`)SGRjXrb2nH4R=ezfTpPMs!0GnJ264ISrRJ)#WwHfa5z-Ah^7 zP@i#qMJ*vkbZ$q(_siK%e;3#Qs=H2!Uq%$0UmOE;_Srqy%Jm&cC7ijQZ^A*uAxy#` zE+X144KE;&HBk|6B>5%NUE~gHW3ySG)jnF3!#UzjhG^WbEo~aqo9CC|0#V!VQQBW6Y-0Glnv~4m z#6Ir)iziw^VDmFhf5yx8Y?B|Rp1Vu3FRYepa;zU|k0>kOT!q|_8kxkay*Xu1Pb)n2 zHL{UQTfgC&ohH8#55Gik74NZeZ}JAkOwL*H64+eMd_DV`IX)W!D+FG-zXb}pu42V^ zO`!PZ%VB=x`y;hxn`yW47^;YFInj?Jlq1i=aS0L^KFj@be{PMryvik!xLKuORY8k6 zUyz(>m^vcedJEn*-`(zs1DvhGb8H@AW=*yr%Z1vThbIBvl`DT@z-JSy@syhrm652> zbfr-;Q**SEiYS8#P-TwT!h+2vU`DMd3H%Ws1Zmh=sM#>_c1m9?&-}SvEoEQ1XI;Wl zHsVXEeBYvDvk{zrj0H=-nXPyRRpzH@&nZ?beG05RD;^Ay4Y?34KG{0wY)}jzOyCS3 zsX}Ie451CgsC4h#-1TvOJ3!0(sCO*clO+ZnL(RaXe=tOlv3YK>d@eOs)|3Ssg*+7( z*>;v>*;+&)QahgAeRG_?q*Q0Ar9P9Be=b&tKwC+X|AWTm=7M|23lDnR2|Wiu5obpNR*S1Q z6cPu`RqTCFf3N3$wem{F;XJj70_)JiqKR-4R2ZNM@3lHvSsY0lBrG0SGT6oQM)sW; zP$JQ#O-VwM>9u^2e6vVc-1Yy`SX<-}dgRv*;yj=m1iNX7!@>zG!S!bkL9KK`;2!^o ze{|I5AH1^Lf?$DggN%%?y;+R)bxdc3Bvobzp@ zq}{dI^p{i=7w|-{<<{&3c#qo?eKs+qe;+lshb0@S60+6YoiI?5Y<>q@?WBEVWv!=j z{PvdOU~E3r!ou6ym^R*}^B}FUtChh6 zqBpW^$bRngdN7zBR7jzOsJ?ZPS>&!r+nZ1GeX66>bO|ts<3eX}Zy!nZiR2aPe~c}Z zLA*P8Xg%DKktdo0=7xsHbW8Q>~h9nz3}{ zGewR`*Yut;jx(tUCR$6==;Ch_eaS$+TiQ z)`+co@sue30+C3n2K+3*D~uILH(qnoL_pRn{H%V)>E2aGv(EdLX>tk(6J3~hZIINy z`EGjas{=hQr#FSWDwIkkOf}G7%A((<`>;j(SNl8uPY#7{yMYp7=>Z-Ae-&P%Qmga& z>V08m6^AF=USx@4Jm~QAh_iw5M!IFu=}Im;j^O(DKbJm{#Is|RKIDiaAlm4aDSCz9 z1@eZHmHjibS957dQYf72A=mqHbpMd7NgY_3sxA0v9_>7%xO(FuP9ilvP37%L79PLf z9g7d(9_pGNoD9HvRmn_9e~jAXPR~L+p~G!D1e&8GBI^nlTr=FPB|Z3sSafwi5cT@_ zhWsqxG7^{^*34YuhvH0gE{AhoWc*yNG=K%eLldl=^+ovlFDU@|NdfbpfCgHf6GVwt*9bDN>V^1 z80v`zr88OIsDR@>6O+W8+na^$*&9{w;{oX?_2pysE=yR1+ zcOszGBdKfZh-2&Xbmny>!eCPDN5}wQm!?)6kUqYJT?tf<`S+hvqDWM4QS_Enwmkb% z3~JgeWlJQQ8X;Mdo%E75V^qS6BuU9u_BWL+`!CtD%UF_-7E6Uv|NFdAJ>O@}`Old- z__*Kiz2CdvJLf!IsieHR*PTyXne=XpS?xo|8FOm!0nvwis{M}Y<(f@iJ5>>R?Q(GK z^u&Cv9b4DFT2|?s^o~vN&P&^9XlwkwpcN66S#0s_>%CViD6IdsgAZ8ufu3Cp0((84 zIR5r2;)VyWjMm*+xNcg#WyjceX7Qnm-Hu%O+S6-{j&9MKtq=8HL@w;$KX}Wz_b#nRSwFaMS;3Zwy&U!ZL6<<&rHKWp)Q$^_3X3CLVkfs*J@D|LsUwU>6^!}( z_@tsf!fQkQvm5ErmS;XXtqq<%-19AOKB>N2SZ$ZW=%lKsrRaGZ|kz-mzf4sugjmX@oY}osgd#qlRmB~1L`ujJk*%G z^on8cg{|lHk9!$B=Y`eY_LhDV<8K}yHPXE^{9-y-DQdg;d>i9w?7f?*TaXDqBo4lt zMK)ab&B>6($2{zmXSqMnGJI%Q>N4d8>vq$tJ1b&O^i=NsM^SpIzm~-XX2`JAc*FgA zvPYG!uU5TG%Pn+t=vTH+W7e&pNxEwWwvT?`>@=wE)Iqa*PH)3^!-7ZERnMfmV+zwQ@4- zdL^~GVQF^y>f#i4w)YO3bA`T_rkZwk7~O4;DqnSc=F7^GUTp5tVYsQg>K{U@!PjNQ z{j@D^rF}-&gpTo;q@(lhwEpB!_VKW9skHtr{pXR)x9X*X>uePvSIT!3u1vPeI`gd$ zX}|Yw&g1;-0c*a_P1g&TuWtXxr%QfuvgiAfTk9=8GxfP^^okxUE64u0?d`?a+|!-B ze)I0%X7<4vk4+1VLP-1j7OiTd z`p&$mkCkK;FF6>Y88QB}z2b#M@UUaC_Kr`}PdW@VNnSVR+m1UnSDk{qKUder8=N`g zZgxd=cDn0o7i}L?-%Zahmn?bVyeP52(=q*Pb^9;<#*X^_W{B0u`H$ud>-C~6a&eni zl&CMTsdgr-0_LGrUq^(T5{PrIXShfnalqc7r&bIalueirSY5f=Qbq9)jl0p zXHMa-iG2&6&@|u}(d4}_I`QZW2-3)G+>t;<#_%7>y@O_oj z;evNp-_7t!$~KR!Omg0Br|Gw2;|Ki>^rtblQJ*U#uOAs@7*hRwj_RysMK@J~a-Fkw z(tH*oSJj$8XYa)94Taa1It0Q0r+B;J-dxM@oXhMIyRnsj@78W(&urg2*8TmT zJPaN?NueexFF%|TdDAo2NzvIMrlP>ADA)SVoI@Mk5+-PM4!e7B@(aJK$G&@nnC&_+sB;AE zLAPorOaE~pUAMjQ>#PQ|sa45_T@wOxcO26`@IExHZR|yZ>zVelmmYOj_g+qoAAjPw zR_^5p%`fCcua4Ia`c#+=E}xt3b;5VBn}g2Isr&Z~i}q~GuFn0j+HQ&B&G`8i$@3m$ zyKB!dc{F>|Uq)r8~R&l{IRn2Jw#yQFk5s3}P5Y597xzE$RftM`hkMuxPRGpTLN;mlic4#`T_x+_~Z zFVYM9-s@|ob;!w)UW>(cgqY(MGCh{~HW=kbeW(OR!QbU44qyXo*_n0y;Khy6|tv&JS@N4%;P+$}CkSf8HC<%xu>oH+o<|;^usL zXi3)UJddNZv(0N?W$ZgUtO0%$ZoT8^`(9TLl>P{xaI5@`-I>tx3ZtzDBK7-TnVIrj z_Tk3jdqpMFb~!F9U#KdKTXI*@Tsh<>+{ZC4o*>&Kky9VPJYRHxIKTLjjfr%Z+=>@ z+q)VMa+ZAuv+;P-fUw16K|n(@Cb3 zuQ9Y#^)WG|SWTK!24opBs%@Tzb68FM=br|zF|?rKdTwd_4v0#bWvC)GalVmsO}U}D zwFcGVswbU{-gH-1$qZRl4P%tqUFlVB$SU9X8qMk!G$Uwc(5!j#elzFKm=_#6W3jwn zKxk;#>_tIy<_FABhD|UUqQ@|doMl4v zkmcHl+b0If?|2w=G5$;cTTRzzWwKs5FUX?OaH^#Gbd|mH=UtKSu#0bVhG(v#JFn8P zE!iIPXTo*%08ZA#(v!QK9++ODPy*wp452eGz_7@i|?YVla%g(%!WRD(}Q3X90$*t!^bkY62(aGEu zdM!7)ZXGxOsiAUtgh>z8h!i6|8x5w>7@P8p0_`*jwcV_hUA`EN(f%t4V;I%kFGf)s zjlWlFR2zNy34gCP(&?m0s7u*4Xan-!5-!-13l@a-yDb($7oaWSnYiJL7bN zU%Z!gHQvO;xsEqf!PjEatTf3+?>V*5crBrH?rO}b&h0mzM=ABk7_+MB{~Avjth~Me zeybyw4Q7>_>N*;#KQp6R?jy5eG_b}8J^n|w+)9b>Gg7;$Torvp7Da4%q|r%fpk-pG z8dW5tI%%*?&eu*U*D^6xuB(yht8P`v?DaKSwG@^rz=w8HniR<#*QUx$RH-skGD?TS zS%RP#<%>j9^QJ$v+HK04@GK_Bgn#6-5Nk`wM>HeWDhN$s3PQ|SI1C8}c?nH(EuBW~Wi-YhW`eUc zFNqSGngJC}trlMK>Gy|y(Va#ASD}FJCG4y}YQD8{5TutU=Ad1E6$7u|MIB7|z zzyPEnzqAAe44hTW7^iU|phR>a48y47xH;?u0clDi48tNJ3o0OSP9bI@T*yfhDoYZ) zm@x>$G8|%K8WKJ()*ud&FgO|!;77mc6iw=4Ni+w5ggl01GaPcGR9iGha4o%BFa!s$ z6RTgik3_;4{GTHUIp+k}S&6EX^y#_5?x*coBxv z49;`nhyV;?R!oQC9MmMS&=A|;mtxZibTsqJKNLUv1)7C&jXEIX+40Sc|bsLi(d>;N3mk5aR&SdaY76LNx{N-95SisK7o!v3p11r z9Ao7|{b^3YKnOWld>9A`#GW7w&!h29a4bQJAEK^JG>UO7*=#0-x?RKIFeFWcF=T#; zFhEBmb|-kKPAC(ez)+Jwxgto!KPUxsZm9af(>b(?Q5f`xh=5R_C0P%`hDTovbTor9 z1}h0ESgrr&rj?*zk`kGO!Z8A=`A|&2XT%o*25ux4P@rRJ2?jNy*)f%e4w$x4KzNF{ z!bt{0axGvyGe;hy($rNe~E#w45Hik0BA&8OW0W}g$m*9RRd_GgGK><^s z?JfcB^?zUtD-LXRSO2S$G-(hzeWcx0(;;377&u#F8fvlyD80AqM0 z6anK26vG+tB;-E8kV!>>lK@JX;84M&hk+2iki}8QgppB_p@cCK^?m^(NpTYZflWh| zMVLUjLXx*IZ?Y1hAw{(uej%5t=Tc;F28^bfTIyd-0Dw?<5ysG#AtMs(31Eys1q2N3 zQiLHHZKD8#8Y|`j@egx^C?r5?n&c#^2CS)d`Q=D}p@|ArJ{U z$$m*a3`w*F1Cr#$fFUE2a2C3?CLRiP`6S_SNDro7SD?+Gu);v*D>WU{e4+Y2po0xf z6O*492ki`k5zvI8+c;q*g4$ES&>BGzATwfPzz8%UL86w7#=?q4T|EW;|0Cf_kXa$U{HGs7&5*9 zQ)muQ0ZC|$kvvb61oRe&fWq7)s4wg?m5+%awnps-Uyb3gPrP&ts-(Xd`XUktqv+OEO24gWP^HT8c0O6oQZ6&hKK3hNJa zodp>98xj$))j)SKu!VrUEOuZ8fRJZUd$N#yBo_*c66D2@^CV`193Y7%7?LDT4H!is z{hzQBk*J?1ShVE=I!UDzRwrmC6tI@*R>-yj)-i+;_(BTs>9`#_@#V}|a1{gFt zV$A@?ON4>JA5BtSV8Cjz6KRZX7^c9nl@{5iPJwt3J(&q$0(m|tAaF_m6A%~}fHPBg ve)1G75Tf&U-TwbCiF~5`_uqBr&I<^ewH@>;CDr zPxsmTRMk_p*Lj{@z5Hf6aBrF@1mI$3B@q;ab9HmEF!>1Q1^QWM#bsp_)qg~56Sc~~ z#2Gq?i?73@Gl^~~vRs{Z5?or8%rr3HIjPFeviXi<C7#rT0i#rio1_-DsEBJ}RFtvqDV1toFHpQgTQD>Yipd4TpHVkueC zgx3$QYC?@WAKZcL^_oqu1IIHXaFu$`#Ld^1CeL+eyII{f*moKzzRlOo6UZHt{Cm&U zxZMV8oj&g!VXsQQw+*+mvWiatV(X(0k<=yU-8PZT<;vwug2R-hQ{=_g4%@r^$F*+9 zth3r9x$Yg*Q&*|lMnyla7{HG3k$6G~v)e0mlNpnH+7gP5?`} z$bB}3m&UuJ)@ug!)z6cw(1=sz@E|mQgJZl(aq^>sG0!8#^c=Uhrilqwn+?h&2B$oz zs9fL2m}YcGa=~Oqa{V8F9kR>OHhCu+&~{B!1E2l zW>plXi9k6v6>|H{rVcev-fvW1e8ia=7o<-vhODG5`l{u#(Cb0et72K_K+Tb)EWLyr zKN_MRH)+o@oNX50hE^+?E`E+yDzqmD&r)1A_DXmUUCozOBB;K+ns>>11Cm>KGR~{@ zt$J{C=A@#G&k(?V{+wXdx$;MTA_aTdW9TeL605MFqI_1cQaXSM}KF+`gpwhrhq!VIO=<#@Aa0cGVA zLY^eYY{vtL@Jx)z6j|R~Y42Q_5!f^HL6+1<3r-wAsRz)yZcFVG%bKuDCk6^Tf-z*+ zIy{3V7k3l!I@{~WXe)wie1I&g4gWErMHZR_nRH7dYIu+kw#W{ea2`WsB5}SFfB_PT z&3`J3c|cuc5Iyj52@4<5MjS1%Y5$XghN%~(vUE~2HG5ESqIjpZSq{m!j|Aqq_@w;d z!0~iuSaLw@mg(x_^LRtZV*n}09@EIHW$!YnThcrc2>2Ue8zAVXEnhV4=1KIBgzxcF zTCw%@jyMrDVcXu#Q^B^jl>yOJGxQMs>3q*5rLj@03o2_5ear;Z>@%%g!0UE#d9SO0 zBatZAL^qv?c)tcI$5LHQ$4JcV$dvKJaS@Rck_6COLdPC`u9_z4arPW@&Tzig*ftBrPtQ^_l-7(st z#I4%*R<3*uj{?R-c1Mc$zzX_cb-F_wcf%^|edA)DBwpYAW;I2VJ+f%*=O80FcLe2P z9!h|rVxc0=<^SDT3pK*G=ndmpoG^k{nKd(8 zH3iDRRrqzc)M`H_|N0jeo{Z%rUg6z|1sD>iFvOw{7t$MtD+C!0qC&gHSE_I*kY}0a zS+$62pLG0pgOn7!A!2Ye5Kze&9b%fZU5Eg5AGk+YT3z%9v?DvJ20Lk{jiR zagf$1zWkIBQv=wXK1rYC9wVoclV*L}D89yuFSjMMJVP;td*iVR7#@&i1n9D*k3|B$ zgTSh$#-*AWvS5|oQ^X*ZolE3BkUbu<3rbIe!|cx&)KY)vBG8Ivq@9Zy?NMlQP}huV zL!Mni^4@L+b|M2?;6U|vgdE`oA3$ymzE-GU=`oxp+a?u@-L;qFe^6Ske@RS(a%ydw zqy?mis}_$8_;uk~e}{<++T+)z!50Mxr?e4tc0XRi(J0kv*$|AuuRL}M-*jA9D+*?z zAw;ngFFZz7*?#_cYtzVPRDmE%f&Q%>1RLy?2$S^h_iqf;5Th*^&&34r6=q1>#6B2hiVlzIU`N+>ve1NAWkV3-*ntU; z#1F-I(^+I2E8Ft)I>1_q7*mu3koX0B{U*a{H3vG6i!lclR2L%y85PX!;|pUBF2#m~ zX|9;5Lo!gDZ7dNzotM6R7^>s{beoJlUMuOiqvsW4e6374czxxlc^|Gk$PT`RuXYb7 zJDo``8_6MWGck%|dK_%;MKc&mLORFMosihj9&n4dpq3Y9X#Q|85&+EvSU3^LPjVNI z7=_6MlXDDLrX-5jm1p=6`$(3N6QlIT>M^6vv57aUNl>hwq-T@w_%s6k?DfrEsZ25h zLw!J*F&=B{Mzre|l+Kq*MC*rYxT1~_)ig2ZGqP{LJ~EXNj#(qRo*XJ$sS zP`U#V&P!@5@NS5hE37PKfC?ELb5B{RYv^8SEY-9GBc4E@TwGe6`t6^3FCEz7HO~fM(+gZ&kEFV)MzPBUNA?~3NyMzYTAT<5L0B?=BLdbqhu^9jt zh4Gf@5J?d-{V9cpyD|0-_3H=R8DX5m>NcJ|KMbMuuVitqy1bc&QUtNWhZTs(%q%NXg zCDUD+0TJh!vR>xbfYKoLRsilypRlrg6^1Em z2JVT|rxJ|(l1D`wZbrAE83^z8h>5VMVvtw8BA>DSd4pLpzAq``PJ~d1Xvp1j@Uj{- za`>U+A#lq2kU3XDnf@~kll3JRZ8QOPUYYYst3g~!#)yQLfDbg!^l!yE&$Kd519|fL z5EA9c%HQJ6Qg$+M=gkHx4(YgJzt)3(A{cU8RhS``s(}8A8Wg$xbyTSfT@t)<9D1%@ zR|U@toBD{r!m_R-c3;To2PE0LCI_mOkb=Cvf3f7vm&CG^ig>o;ew{FdTc7=zo0Yak z2N{=#C;<<0a27~unX<#Loff$wc;ZIc)^-K;@#R|!Fjdvl*!~nloezMO78n63$xOes0T|N~`gXID7(1P$xo(e9PhUwET(NC6R{; zpLk*x&wZVU{X`uz1Kk*o55e;@p%*;e>k9YSsZqPYiVb6Xx+oXmCu{^ogk*s2Jvd}? zsMmnWo3V!aaJ|Iw6nVNq6^R19bmS3S!tR#T75QWTiZ+L2Ea}yvOTLJXO?P$p_llNTm^-++tg#hZMuCl^V-5rKyR86MBP;6D^s`Sr5Uwxo7h93uN|Z+^+Pm z{;eAatmnqtz407??gfnvyA7-%N`Q-t3lO7ag~zbC5(t~=k9SX-M>geLJCL!iah>X& zxkg{~_*EfE>SvPK0hL3fKb3u#c-G{w7*%+j@fRsf>l+UG9AAjQt)tIsT_UAN?U4%- zf^Js^ol)f(5nYMwrBGF<%-qfd!YguNmDVc78N#3uby_-r#|Zl#)Si~4RBIN~=H@~nl_*}YKB1oZZT zh;d8}LFu|>+*{o)%AZh|&+sJkRmdI+4_YH%oLeFD(_QNN&fx8=%x2`});G0z_ZNC@SzG_qbxH*A>fG)UfZa=~#2rE}=;HI^8iuE~T zq@K0f;S9L1i8qCd>y8+XloSV$9JwvQp^mv_N+G=7i50q9g2N({v6W7E2T{;i8hdTS zNVD@BvWb2Lej=_&@4#H883{mV$pKNJZ>hsU5T-l@JiND#V2L?)OjQa0MorP_WZ)%#{MARS8WL<~v0LqAa5QjQ2`#nB zwHV#82x6|0)62HL))RL5sE)1@R7oLa=lVcXKzr5&n?CI1!DY`$<~sk{ewggo%6G9y zn1qOTJ~sE`;F>@WoFODAVJd;vY?Hi)!dP;I`EA1O8?by=%bn}o1l+mcWlUnt*|ZB+ z695B!j|1Qs+@NW8Y%S>mksJz!LWZDF8i6c%FLSJqa~Fb`qVm?}W!ETzR~%SCDsALl|NXBq@Q)%;P&ZTE6%9`Ipd zN2lfHuxrH;I519tF&K>lb5TQhGJ7M zP!d;>R`Mw;bhT9$oqp?^jsg6lIHH`pYPv86SW6x%_8daVG!sokWpG!w;4+1RViCz^ z-RmC!`#mO7B>iJ zwV`2NmSJiySrj`n_mNY8fA$vql(!>_vA2$$HM{e&_lHb(_3F+xt-(;3eKnL5N{eBx zmvx^zJ=%G;m3`EBtq(tqSwcQU%42K-9_ix7=EXPkGH6|7R=H7kSQ`$FK^ir5j`cTa zl*l=F-HeC3kNq>5+2|RJQdIi z0Wpn05tJE>g(dCM6oLpyjY$n)W9RsnYBis%q|`5rGIa5Zaj{6G?RjU^Ar*&awky1P z*ymNI+*Be=oqpKjNz+(R5EV(lEO4_oacbV&bM%d6kbpHPIwL$4YIvBMjo-`eJwMj~KD z)#j^dba|E~^(UC~*V^y5=}wcasf1>QnJh;Kd8pFl--f%${6A7!ux2rAT-lfv&tCFk zg}!!bTiWdLTDGpfGC%Xao5w)^t zs+1RFukx&yT>~AGl9RZMZS7mcUaGi-yl&_&#OWb^m}CD2VSqDHT(2CA8pU}teev#N zgU|z-VkpS}=i8Phb!M87A}9tADT5>~dq#=r7}mE*4q9uijezs77N|9O)&w%rk~S#-wI<(W03%*24my=?JEf|Uy}*(k9ff`iMjsrk2$T@6ap85g@m0W zZDtph5=g9t4&eDK+$`)Q?0*Bt!a>6RH*)_(^e+_Qn0}#4@?UgWI7!(5hL?qlg#B-P z*-2RbUWtX9g#Ax^e+OS%$HmaT<}pEl_RK>`HVb_3d2 zBBT+RL7)PYwNXJi8%nfu5h;KB_IuOO`!!okOw`2H!kmQt&zSrjN%lVyf~q0Ok_QRH zbL(~O9dxcN@czF$R~icz27ampDB|zzMrZ#|IR4(We$97gf}#Rr|092R6#nbMuK@fj zFmV4(Zx$XBj=w|s&nW#PrGJM7*q4lj^hcn6hx3m@0CI%$gLAR4H}H9cAi>?z%?iB{ zGei^#0CRy&NdHOPUud$CuyF%Tk}-h!VK`L(sJDM0@;_<}xDke}{&#i#{{i+-xc}?b zze;U%BDYg;2}$urhioUjPsI zFF}u}Z)RSk=H-47Qc*pAKi|F100$;XC3SuxLYAvao2)eqj0aqbH z)tq}zV@Aa)yU>8j;{l)dtFiZ`p0{;?KZ6a9*j`+LEGsG&DvF!(YnMK8#q#D;<8lw% z)b^MfgkN$^wsbFbjSOBG|F(c31t=61I9AvVW$VVm-oSX8ki$vzhJH>jpxaaYyG(Yt z495Lp53CaqKJ{&K)8IovVjjmeJl6h$9~$V$7hV&I(ZU<<=a-l|VhR(2J@C`(a96B) zNVyv;CT%C0j2NDT2L4zazR9)+)$9=)0=Qvl?u3&8|sF$(>Q>*DINT1SW*6q;6-0r6cW z!(rx)=rY1H8Y&MwInqJ-U}4P%6;s&UFE1zeQfpaI+2ImU*z#XA0YcIIh-`{i@%{V? z9GmjsmZf0vqNKv>x8I5LyCS!QPE%|#%DcWhIt0@Zk93jniij_(+{_HpBblY*qS|D! zkoDgxL>|Iy@_*YY2G^cdV$VZNk7173?`Ri<9^yy#M)L&Gi~h=xqtGxaI?S8cS5p1AVB59pWO)W0o4IlnI8!Q0-nK z@h+~7JM@!+6X+HXy+F_po~&Lv4D=el5|T8%V1g7GGb34v=68f)w4V?MZwZjyf16y@K8_U zxYbwEU6=Vz4s;$qRYB&j!JTvtVCKqi_D zR!vsOJZSi%We|WqTa}GldoBz*WsYKWC7|<)r+fLwvu(>VS(MtGe@j~>by3I-}r6cu%j%+Lzd;g$u*_n+V<#Z_~=wY}P3P8cjoZ<@xej*gVISj$5RA!)5NMt+PB zw69i*W7K41V>ohv-Er^gpKB&};e{ga1+)a4DSMq`TtEOiY17oZWN#9v@h4opp>bu} ze}1=ZSUo3d>2T>;Ud`hAaDMHNBSTB0yqEs;1$EvQ989F{TMo7;j8N;!N8&)7B{CU% z2I9+GF^wM)2Di!|@1~pbx{gfqY|q}BoKwY;(8N$N#>8Cvv^RPbZ~ednz2N{!_`ST@ zTvh#0Sg_v##BTJdE6)?hLbAP|tSZb9rj83!sPoG)L{oiN3rh!Gd+3Od@IL$H53J}d z*Vlv3XB|$ZWF4PDi@+d_AAou1^&nW)%<^fH^7ddf zzd;hk!Y2H=uepUV3H8l*yAyu#L7moaG9o*S$A|F?Kpf%gdnX7p1`D>qCs%`u*L$>H ziFC;&n4#GcwhC;R2GUHFFCVI6OXV`0d#Sx+z=qGQ4a|VapNGoynmjRaY1O$i)s7!7 zV;LesL@Y|2ZH0`_Zvntu$5@`KhPENiVDp=+B0mK z<&nyqxw?XnAC}n3WI$bq)<5;4>mk;{!BbYv1w^BrJ(DUSzxs{MQR*L3dm`KtE?W{} zRqv#GOiGcc`9j7IpspX$GQ*`8InYxp^8_k+PD+6kjYq7f!!IiHpJk7L799;sKz~WO zY;+X_!}*907Z^{CXO|x;lj!<3uKBsIIFDEDQ+qq0bPP#V?KPBZo!E8>yrf0rU0YCR z79d(d6XObMq&-$2_J$Nf?r3d`B@XiWtrF2<7|u1M$WVa)i_*8I@L6S6d6?8a=cxoH zxs-<|EDX8>;CH8DX)Dgia3mntCm_a)ZGmw4i$&+1f`sy^0FGE|*9P0Y|;w2L?cy;T`g8Yjk@n%^nk*hF?GmN6b;z@(9E zA}YKL2@by!4dKzcn=IWlMTW|G-xVR&ceWv)W5WBg!t$-Yq=;1E$H|_v`uZkKq{Sq#pliyJVCN&uJG!Mv(wUb1a z=K74OM@|p+kMG5H^)Sc2D+A2aweR#laqWM4I7B@gqBQu#+2)+~fqS{2f3YDo)%u~9 zb~mS7lo8CGn8*@Vh~2XE&P>;1F|-+Z`5?DFc#t*Jq5VUcCY9|31xKs^F>5w=e--=^ zZTk6TPNhD9Gu`lh3jEr1oZq>9FH8>q5m>YN#V+j+$W1e8$h|k_H8lWMkh4N2sojZA zXwTj1&7e8h%P4BbjJ^Y^wq0Rg$*~6-cZCDbH+3SK4 z*BtpY-dyp5QNBwpT&RyYQy!_Y$n|J&J5B7e5knSWBtOEg}y*D9G4T;>hDVX#o!qb zX@W2wg0Uslxl@>Y*ky#u6>W*tzIH>&4HltUPnEdI zYWewb%w?`BHbf{fj$o28n6yZsIHVHteJr0wtwp#q{0q7jPJM`jinK$HT2(adJPs_47=yjd z;(}i*2Qx*~8Sdxw*Of&CQHJcRa6?}Pv*^4yt?})kM5caysC+~JJwmgCB5h%urG2%i zvqYJouNw{m*c+^5*A4d>zpN0{4TG+d`~T41$+sQBdt8aoF^dZsbKy{{at_Su;3l$z z@L+84KyF%-A&CEF*f&%=oc4O2<$4DLAZPq!=2}KwNr>?e?IM$RygEx9jd1}1K9Y28 zHiXCWd3$e8YjnGCktsa8aFuUpzelKc;lE7*(7sCix_jc+!^3`=5?ePs^ve{4x?#v) zrc7$@6#g=W#nWJ?uwH)x-A?~km?%vVSADjS+I7*pC#gdy{pKoS;BMIzIpp#2dyZi9 zc%~6p2M0r^vaRua2{Akjt?U@8nu$${G;-Y0U$$fz1N21Yt^~)KTaGlf%e>wJofQ+! z^b;TV5^f;|0v~T@>z4(-Tb2?W9#3dK#yT^eNeiVkN-Os~R1%%{Xc~o%kBn$;t)ls* zZO@#6*^8Mjz)0llr(0GKynKb%bv-bU;6v~^3wopBO4VdXVHqVZ^z&S_*HyFSvr6T| zKvdedZovJL%Fqt(D4(ZfC@^pbP!I2-S7m>VtZRHB6*DbCs#` z*f;|lcx_1T^ewqP*eEqpDO3rV-RUw>0>5V2oUHEnLiN=4G|lb}CPd$=XIb89D1 zlM!%hqGAlY_ny;&C$&@8jHyjEu0idQj9_*R!N(tYh~yJW8G5rMumqo`dAfx2sfTK7 zo(GAPKiQvn2Q4=3A^rz9J?}#Qi<_dM{@-k$<4?BF@dw-gL)rMB1QAQ_ALN_lZ<*y^ z#PuJ#%zr7~Kj{5$Zu*O2a&Y~otN#z(=6`3Ce@Y%{%t=_7X$oc#1P#0?Qy3V;Nv{#_ z(1NZ#)Bo`FLgi0SDLDSaz*Q|=9o=2bEL=%A|05s#&B-~L|K#MHEPv}9P=D$iz%5N| z&_Bct48Xs1hyUsNA6~JLaQ-b?{FA5u;qG6;$X^_ou^~Tbl=uyGIsRS)skkFYf3dD2veTjs0rXs9x6@{YB!_ zhnXv4PQa4m{l<=C#@3XPP|joo^xMgJrL^UYOOqgRd}-w&a!eK=y1RA8%TTm5x>A21 z5C0i;)I23Rg`PYlR-2i%XUU8+Y$VNS&F>!Ix$z?U9wsA1l=~2IJH{X4xG*wt-03WY zV~>rKu#tOLxg+&#-9!5s|p zTg^p$rnt}OH=KsaPRgGis%oD63H1l-Xp8UjS{RwvUwLRC%#W&DKUF@Th1-s zi>FiKl;v=nrU4aPP*W1)`@=thCj*zQJOV^_o{hNhU^om@&_ov?0`{7Lj3Ad~rQ6UR zE5zSC96eS}hR3kehDthIwrBN+Y?gHZH?LbxQt3&F{EkyTOE)?@lEmG*0y&C$6Xj0@ z0v{1crG*5iv4R{Nlni4tsH0oeg_S{Pt z4e{*=lt6yPYfc4%rkVhb0JO3Te5XQbQtp7@D~kvibbW*((8lBJAE80!$+*UZ#C zrF{^n!D0p9GN%CsR}w3U>|zogWv1DxA%;Rpo+u3s$tgrVx=Q*~*lmNB=L^J4%mHVR@r)x8sjhkGCYp;J{Zn{bL@`>0cAtg=CCD|%Tia8G!lu((tISU zBK@*f*_FTyEZ3Wa4=FSifjHl$h3bhH>2h z!a|dz;Z@to5FODmx|ghD0JfaHP2dQ{i_3;KGh0Hllt3(~Iwn62F|#YdYHvB7*yrgn z4SZ%ZekrrEMp38v638NcF|#rR*)P^777M$dt7cGo{*(e8XTP9j0Xif@k z)`7RouXa>E#Zq`s`g=bOS1WjD#HK2+BDDaE zyCChwsZPL3R^%#=MRRB^Iy!37(655Hgj~oG2qL3!_&_Qc0V7{P2*x5~SkEcA2Q@Oh zF^5gupQ_q!GOLsqb`EOc?xsHQzOqSk< z5y{zb=>b{ZEKi_?cjq=ef{w_(%(!F@vP7pB%=5b+5)yfCP_DEb1g~t9&{!B>5b!C~ zk&uO1%sCewD0Djk#iFLY)QGP$kehIz4|u_pwS(baXA4>BpV)sgr}hXO7Jq`Q<4wqK zRp`2nB&??r{mfu)B;r1%I#`Io(957WE2m9-SIVHOkH0)sz^<$epib$_u(?jCUx8h_ zMX2U5HtIJGk^Wq@n(C46>aKTz^N~QEbT2Gj?h>_QdGX8=04IH58;(sh7-tTpA_E)l zVuSUOG<=rcBt20?_KdTS_m)k}OqKdm&=P;|H~Rr1Ig|}FLx0VtP1gPanpBci*+B{y z(bos0XH1dSQA=``8A=Fpd0ThdQn+G!xDN~d$#!+V>*pTDB46Xh;s756KTmOnA;c9u z-k0SCvAI?@0D|ApZx(FtL+3a@{6Hv`r}EcL#~>HzgUcf3>5U>HUsoqPoK?fnwCH54 zR3B+j)CNtZRYdXB3wCd8s^da2N)u`xB;ob22aa@GmQ6_lCG1)%Qj*BftUbr{MHbcW))T;?T} zSeBh9FiR;K@CuLp%#*=6!rINDJv~JyMn96S#Z*5z1MGLbE$l zY?s))b<@vc2jG@u$b6pI z%m7Iu@g|wANdBtPfy8oMIgs)!k8bO%1xKFm6px6l(?56~9t0c`JhS`GZ#l}y|hC5>0Grhc|3Kd$GPor^i zgjv{TZVZ^A9hAZes3qA{qP7Tbbg=^5Fu+T^7DW;la{vO@oY-O?@cji@DKG90_ zOMk?-nFqpUuTf_C@ObSWVYf4}nh*l?xI|n>T`qDr&bYz-PRx{EM_4XK_ad|ul9tGG z)R@TIRKAp>A_&Kk`5`sE-L;$kbWy1TlmJ!) z?De=EW;v3PjsZ9_gcea418$^i=>&oo5?2F|*yWVaAok*xz!CgWl1=s`O8cK64Z%2? zHrOBoLE=$gM;1}N7lp$~;oV5*;QGG@V~X?VjGkVR5$2e$nO`id%r4zMl0s;ge5j`Q z1YhdQC~~MA5x^!OPyMD0CpNN6cMLfDPX3dPCmtt8$$=W2jY01Q_(N*n4x4Z0-fqE2 z8Zdu{#}XuBnO(CWK!$wW_>v_9}-y0yI#}PvJ z1ykU2h!Oitl5Z$VxzfD~ZxxxNyi5fOr;q6;7{XkbMt3FoqCN$xY2_Dr6SG91bu9Cg zXNNUJXlSPX83-EXtVdCzVCYXbDRbDX=){Ernrx0SG#pzOT}Gy&IvIzp_TfA$4$U&B ze0vRz90wAvC_+(vbF6J-P)$HMW`Om#gB12^z5JE<f&OM4SFO0>FpAP0>| z3|}io&trr636mpFI8>hNH;0kQyW3~x86A~VefIMimDGb@c~rB^ZOj4C!{-R|eu>tH zMI?_SG?_l4AN>5W&x`< zOZS6Fi&w$P8AcZt`f&mft)Pugl9Fk<)8%&HlCF%!_<(bJZzw3KDdZj3hxlCVXBS%z(TE%+o5}Y`fcwXY*+CLESe!Nm52)PW7-?WF2LElk@1x}K{ zticE|>6}ko1-V#W7m?taXnAXKR~Y6-z6-S!rZSknDdBD(*>eaWRR(p}uL;48$=Tv^ zgp$GdadTK%4fkD@NU858D>aB~V3{07ub&(x*smmD@m-McW04+T;pX%Ye++PY^kF@b zob4BRn2Y!HAkS#deW;q2mijFWm%@HE)2jPXc(EqR{QJ%T>mR=Sp{Z*Jpok{|l?44h z$lID2)u)@Pw<_a+YH-AU8%X%snB*3>miQR4&dL>(&J9JzfP*)KzySon%U}cK{in&oECvEwp?1Y9}#yy-p zu_lcjNgKk%w4bK%X?geDCVwU7V3lgQIM=eKs1lPT+eu#!|1vC{v{;Tp^^ESk_}Xyv9CE|T%IuWc`RYtJ zeZXWTJmTC^1)ei>a5isIlv<#!%`t1}er2_lN91Y<7!D(S>Rrmu#lPW792%E9j-9pv zJ#pIQh{`6*GM($~vrbogBe0*d6@2<$LPRM?kz-Ijt!ZOro6)?rNlJZwSS;)de)CyJ zbiAIyDB0&wHb|TXP6|YCIwMCg&+Jo9;f0i634t{G2Xz=%zk23vM7|f(=VWqtu>fVE zWhWv^0NuH0KGFB^Z`3_qnIY^x=Hh@85YE=fT93h13RI+SniC|YsFJI4~Yzu zPMx~+MPzKqb>U-Mr%n?P^TPWIc-yH zE4K#~`%pyf`h3m_+si#sZ;1d8vsEL+0R$=PvG@P#)?JS=x(g@rKd$H)&&IhT<$L4d zcVU||pR4vgSL!Y63HCh)_ecjc@DjJM5#UY^JZ$1#48Pssf5HKz$$j88pg=Nt4kR37Ytz#uUXGY7&K+2*?`MH~;1D#A;8I*I1PJoD z6Q>AE;m6NC_2Qmcf|qkdgmfozLYAFgP`F6Nh{Cnq4^bql2aC|`a{ zY1cULJaHL${dxAt>Pq+%l{Mr!cFg&cVlJ(^-!a3oJ`rn;WS}9Ncp6%6fQ+Z0_Yp=C zg6b&VeJz{%mIosS@e8aE*Zce!7XYog*V?jPt$AYU0{LLeGML25`D-uqWH8$)LKx_d zvRbfuBJyI?^98gg83ND9Bg?Lt|7h$L!i4PE8LmV26)0bF#A^%ln7tRGUh|+`>sNM! z#r+{LYT~u8h2_y2na7?nl=7!7F!uNpi0&u@>r{kEQj6m=_5&&UjgH5r7XUW?!RBj3 zTPL~!fy;aiq}_OTw*eEf^F1DwA?4p*+M1#%kfJ0rnd|! zTJeniVj0d*$efJcC$e!?Y+2 zhjCU%cUp8)^eyM3S|q5ioYkyk5}}0A=$!cJJ9Df#&l)XndVPt0A>ntr;Z`KC zD-kfd;j(G$*0fTJ;W&U``vR&N+e9gf8S<4~bRG0!R4+k*Da#!R+t}{uU5W09>=&Dr z6e6dHJA$tkIh!JujR(~7NP7IeNP9eRK=)v1o_uD~HpiOUSiz-_vx3UXy=J@yCmgP*`nPH3_*o*bR`meDCrzc?clxo(MzN$>C7+T(~vth z&M`R}{1cTLe(4_2ec*+&+Oq@hF$f473qfv^xz9Xpc;U4fhkO%vfNk*6qE=Cu;1{&t zf5N3ySiVyvt`+k^s?_#B7PCyYN@xG#`0%^Db%o2M$i!g#BVJ&&!|VwEm^#UFdBjJ| zIcuP|1&WFF4aZ3@0eQJVU>Pccs@I~Q#s}vGmf#!^QZBois!QpQNVlbK;WTRZnHF;L zp#VRU5KE65yT*61FAoA@wuV_GPt~*1U>KZ1h77c&r`M!TELd>T*l^+8kGY1<#awdj zBn5`R9W%0l4gw&E=Qj+rwE=9MNl<3kKUU3)M#%nH*Zy4AqHBh=4NR-x69qEIujuTT`#S}Hwos91Ft~W3dCkOAweAAzXP{cEq>pe z{&85M!L3?)V;+dU0T~twk*a9D7?#i@H)1<}-VfoU;hMagXS1n$~%?VKN&n2k6!!ZFoby1$|;&K%1ee9GnKhV4(23KVc7pYo7ry9nU6w zzdbzI0Xif@;?KCgS?}H;OrPTYSoPzdfj{4@$?73;-ugPs{{sgRQhRE<0T+4qL?sRn zvQuOq-WH+#70$7;VYiMl4$|XcR2+w~UK4EXQ}`*NTDejSK5gqfW9nV=Yu`MC1nhI{ zJ)&lRSNur1zOOZ;RyWYQNRJY5D)6dXc&XUAcXZ_JI!CEciC#R{6l?5g6RC;nQ^O9@ zAa+ytS^JP~y>Sh=WDu+<=_rz#8@o=(f}v=|9bQO9_6_^CdM%Y3 zod7f{yz0{zy&-?AR+(XMre#-$X582FnuRzR(Epx={2l?NmOp@T@Blw9JEl#$f@A#I z$N8(7`j0-&KRW-O2l0NLas1I@{qIi1Urm|+^Hk&SL!7^6{LxbT*Tr8a8Gjsc{IehT ze?9y7z1AO{j9kC_yMG;u{6E`0|85HXSH~b%nur+$HGqSK1rWay+KA%LsIz1>XYUG^NY_p4RyH@AVjY>CwTXn=sZk!I9f=??aoJ=wU+p-e zILV^t6RHQsCq^IaDB7{H4+$4@UV2do?e+!;|GAlDNmK0 zIY_2m?3?jVQjp`H+8MDur)ID{iE#sb?m3^dFfO>bW*DYssRL|1_V@hl4Be-gD(~71 zE>@tgf4oZF+M@30@h5EOIgo|FFIT^jL~m>pD%+<%PyBeXZ?pCA2tulPBV6-G?`kXZ zXPjI?ni?-Q_fSe&SEJy9Yz_d}YSv72`!}q8zw#71)|kY|H1_Tv=cjI)nwVS{av!I< z9yzzUZm+LjZhl@kTVATni;*}yY&DJ=J*KW1E1u??m_HhFl;rXZwvU@gL0S?8zLMsO zaG}GFXNWD-K06>Sv6f%=liDqHWyrQjAERMOq!t-n5m*uIHA#DE;t2pMng{|oQqJr8 zF8SrI+OMvjM{vz!_)X|tNAZqC!KK&*st_zP)!XEL$a==JChMrW^qfzsgx4#&kP^^n zdr;AZ986d6({Rsi_0EBqq0#IZO`$mEP&EB0isV6;yY^tCSEQO57<4$iW(c)1RY|_}igKa5tx?R8t$UR|Jq!t$!n#a5vz>3$Th4i@ z)j^*gPXpNL9~$1%GUkVwIhx=^a`{v4N-9X z@#_y=;@kNlUVao)ehoO7V$94a?n#kjW1>>fk~}?l8j~bj^wpoTUjostR2E4&gk|?E zVqikIBl6lK?nK4`cy$A-vzRtyASsIWC_@{Z&mZqi+>AuJOvs%}H?K9H zSkP5}4u+cH5v`-MzFt|lRi*jz)RBOBs1_=PVG+ycxRdu@D|@OD^EHDJcFHr z%Dkl)+Y_A=uuBj$)kH4a=ej}1cLXmWw&+Q*x2Ky368O59w_+)H!Z48bOag?Tmd>gb z@6#owKNo()y_OY7Jv6Ed`)*RkJGazy1=~z$o}P%G)W)r7kr-j^0mH-Nrdn{Zr#UFy zLK6#wx20zR9C8O_ikyfeK=&YK@f5F&XZzJklV0(i(R_WR&XdXd@5L^R=OK^90CwQ>n?(Xgm zf#BpL-TlmTPfyRc-d{&nRqea(+Os*2rvDEVA3CGm!dkw|Y)FlJM7vtqK^mNA- z{QaaouTAVLkk;wXLvsjJzd#<&MWLt~XWve53UW;qVUXld3;SI`%E`FVfR9n=W$Fl( zE=L)rgoA0!#+32!X>GDCf|k~biC(K742oFSF*SVF!ngh-M0P8cMT$A?wr*M16t~Us zA3N#{b^2DvUqdS0)Xs!I?dD548Axa=lPV2C`EfF4y!VN!9UHYNjPpaFC#1`ymfyZ( z#XLP(9pm@;N2;F{V9VYK-Uk~TpP?TqhaZ`c-zpSvf5{kKr)f%1 z3p-;oGbgQqlH}25%qDL|rB?RakEc>McIh*l-tE@V!j!sIDFoFvpu%AbiZY(q;}$*2 z$%|EUE*3ZDmgr;yqcDzEmPW=w%GxMNQH6XnCk^C|lvq-_@M#VO2+DCcn$|lSWZ{S~ zVe_?Ggyakjk;6dBEOS55CBUMj_bx9Vk})87rY_EK>-iw8^RBhAGzcn`ss+c$%t?pG zj^useyd?ZIw6zM6g(+#I4)5}*j-xP4X*5=e75!4F=BDoL5x;E+^yAgO?*`Rszw`!N z_FU<@LC$^rHor7A5b7i;RC>a-+uvSWoG9KS%KOk8xr7(TqVV0#d>aPoqucpOHx_vN zdZortHqD98W))Et4O6N67DE^~7tPkl%t~eiqN}kLTmy`WFONNp2OeY0K61O9x?Kn# znnNspu%l!gJZl&Z{NhvrNpYIdPwix+HwPY9jb0ZVdiZaY022Z)HpT0SQxEkOg*6Pd z8#JEh7>pD*Y9DMTsut6d`Ug}kT8WaBlnupe4Y&fI3&>MQ zLH?+xY5Vqb0G~=wh3}z$cjC!5t^}3)y3XTeunkx?j25*D6-WGDw{?D!RDRkvxH#;v zRNCn5oR{Z-wM}HOKruCmHwD=Y7y%YJ^2hbT@5QSATZIqChK)m{%BG@aFgY=OfVO*L zB+TK(3@10I=o7!>1bhn$hnLEjSlglO=IlnE5z)#KP`9>=pgqe_Kn|(CD%(wE`*{d{ zN^T*-5XIXj$ad(Yp`CGnFa*8=-iA(5CK9V<3{U)|@h-mhgZUs>Y*|Ny1(Cf(+I4%7 zbgn+FO@%1z%9gh6CpaiX0H+_=Jfk`g_MPleLNWpi&BbJItA+EGrEsGinhpxmL)lLc z_Pvt<#u*+dz06h#FoIcI#Fz0|bJ(AKo+BBN`#nzD>gp+h#!zi)Cyiza`7-UiU9N(XAUSm*LhVf@%}|)`OM_;nReLH+Y49mB zdo?D68ntp-CG;pe0WUC&Q=pF=E1Mkz_Ji|2ckF1a3*6q?t-nzvyPRj*w1MAKach(#1A>yX?n zJkKbHDvb_a&MQs#o6~SNf(2qTUVofb`)N>U@_bHr+_IK;+$%aN_sM*fbyuV3MY~2Rz5x4RytmN=Z(MM8 zZCqkR5N?Sv;_!=nz0y}^0Jk_2(C&aIkY%utUw%qdERpFg@PS@c!g7F7)a+y)q?X2< z_q)Jpbq`?ffq*}Ii18V=yW zwld3t31sOcLd(Fv1?(ouu4c2cvjm7A2?Q_+w+?lVkgXiDeJO|NQKCZzc((etH#7Ti z1dw}}+4fYGu%>%wR8*Y z&dlF08gir*rG%eNYILB>3~LWmzdUI1YAjkuH!5R0ptL1fw3BiFqr>r}45W!FVi!?8 z96A%S5j^He=oztx+*&nF5vSza+7`WpCOoZ2$hD}%hC0l-6oTszpfFMtD5oMO)`bqu zMeCJQ>#KwZeG==Jclc?oCcr|gEiwZlgw(_mUaONV(CASH$8W5L1|bDa^1;ude@==T zB{#f)N6(}ImRSj2iv!W8&inR=9@5Lhm;8e&`|m1_`nX?swmgG0UUAs<>P}WeN%h8W z&s?gDR}L}J?q7SF09ow<6G_69LInWWd;Nrm`UY($)79wrCdU;FNvRM4*6Uu zD4K!|ZLv3)hL4iGY(}|7ZG|%upu==JWFHHc7*DOBA=gAYHuS@mO_V+pk2Dnt3)pkj z_$BIs9#(~P?XAAZJ`zS+uL`(1uswijFE?plf}l>SS!B}w0!-yev4xIHX=6f}KVS_M zS7MY_?R?dhS8mXm63T8p6X#lbb41JYi)1v82uL!pWMAanK$}qr3WfH_a+M>&?f)t( zDkhPgFvdvyjgRLjMpTgcil7xi+l06|uN(n&r^Nmz`IKJ`?!>6^DSRMIhTuWB(^`Qe zO%8i1oVOCX4`2yRlF4w(U9a{H8>W`2lbtD5{B0`lYR1s|EP`F|^Z3<1SpRltvdqwp z)sfR4Iz_S6wpnRN+zzbi417v}3X4<>5?Lb(mQ!U{=B@@gCBqbgh^+aPV$7kKO}n2t zaV3x0Bd$NLYlud?GJM}H?Om2q8SE-q2sG_2A&(l8y9gxjpv9G3pmL%;PtZB20^+tYQ+HqD z2f3qzlD3fPk0Y#cOdAUvw)l_54O1Ui3&~xP-Xa@WTDvSeKYGW#)fafvkGE{HsUj2Y)lmcA- zH~4WihBJT7oIqdr4-PcdlC6nVk3L>JFDxO;woVc#@G{Y>Zuf@dew|M)Bx;V0{wPRXA0zD$Wa>{>+az!<;5 z@cBRmf{n_FKN%O?<%|K{MW8KoglaxG%gyjrH3R#47BvBwjL!~?!4iDUChaS)nyBl29Z#O;I{I$-k_bwhvsAf>n1 zD;YgOWPuyiQXLj!Rsqo?5^DN^87-iSm_J@vd9#OvU*9>PI-oZfd!$Xrxq&)TILdH; zHc0tP-q+Ae8_H3~bu6q}rJ$m=sZMgD1Wl{EdY;)nd?a*P<#yOURx~jpc2Gceg=lO{ z>ZkX}hLMFtx?&ZFFv{(`D4*;yQxr~~zTz@n6i*((T{i@B-{p~#K`Z-NNsnGQVTkNQ zWNDGR)b~Q$kKo_$t|+w?72*g4Ljq2MJQUBvM?a1uhp#-o82E8Q7oaAeuX0~ zmTFo^!BI@ApByEl5H`-fud0<}OdCSjw_Cjp>YWuk$^8;3T5-iKe}Bc~^wg~)9zs$H z-*4xRKvtJ#Z54v@i0=%zGF~6kqBk_dBjL)kK%A_s;?SZ8K@WlTl4_hnSwDhf%p@w7 zBU9>!px#r*GIB;9N_3ASZ#d>h^0S*BMUPZSYsLz0>-&>X^W(rG(X-BiLS9lj(?h*| zKuSUp>I`rh+}5X~%%7fQ2Klhp>kM-D`-o=b2aRvD{@T=>47La`Wt*EEr*oH{t7)Qw znOj2cramQl4VEy)I64qOWpzeA6-Z)=J+9wdP`?P$0joZQcK9ai#osy;h}qdTe*7z+ z!V{lp3a!^>P3t#=0+EM!!7s*9&5u4?N%Zi15-1;EhkpV1muA>C!&gRwLT6kBi=pfx zgs-MKe4q%kyF^g-ihPNtCvM!J=eC|u&*t+kpFD>Xy|%q#vkX=;w%IOZRic>1J7id( z^l}I1ag$WtqZz#kVY2tb#roThJtWv-Oc@({#OcSxa+56soX;zkgg;)d{|3>@M>_ad zEcK5>oRjBovibjoUC#AC+2ve+XO}0Gz1vZ}8&xn`|3}F;D+}zu1Fe4m(f>F4_}@WS zSXPdAemxrDzu>a}Y=`h}lEB595V=a2aDDpjn8Ef=MgM1`*GApd_|<{G8@EH4DtD=srNHRbkG!iHbomB7XQ`~m1mpw_9a>FC?Ak_k?(n#irhP8}IG-z(Wi zphVF+d>`jE-TL#rfX(WSz2*v&j`>ae8a+ng7s^dcV)YO0^;2gN3aQ) z@9s+9a^kjnmNY?Ak*?$Cj+q`(C?{roR?$GtrBK5O(ugc|0FqlogBTxgJ~1I!GcIlf z*fbbH1xdG3p$F@^GplgiT!%`HQlWPgQNT0OC;zNl{HVlVjX_<>Gd#iETNjtyLRMA- zfGeGG@i}7l8VfU`D~sg@w$de&9%*ItFf3yegD!ZP$-to2@A}3%o>DOPB2pS1usH1Q z$X=?jpp=RL=D1W1$ZAh=v}vozMiDXG$p|cld?s&ypHiAH!DCz4lt%UWtE&7MEzr46 zwByBomkW;vKaU$Cprhp|6Sg$P4K6u@e}R@{lLT#uYxBDX;e9%$>Wv{aEVa5pHq4pG zQ4*FFXP17idjZ*WW8J2)H6X^8x0+}c>=gLmkxXm=Nb^9vz*i3u-=S$;gD=lNxs;n@ zKb8fkX8UC^rC5T*m>5!;#BZ*)$vcK{o5%NPyb~hZYizz|Jg=CL#gDKWf|p~(HJEO| zNiVP{erD->$u%ve_B*p!VWA72LT;3X;5%?Q!xsqsyhVx#ndjYD`?2LP+E|yliZFoF zf5bfza3=;zEf9;u<*{RV;WLpz>gE(t_TeS)z){h_mr~vuX;0Z)gi7a-P_0rwCJLkA zzysL3I%KbEkIKj~QaNJBN*lb9uO|_@vAvm0KCsAF>+&+gGb!gh$jOcTnP_`)3D5YQgY;WNsuv8ubdNL$fkO#SdA@uvIZzcVd_nR?KyiSNDa22uu&CgYv ztQ=7<*aUL0ySV%)Wf&Rk+_2x0s`yOLI|j?s!+ABxX&Q$+o5dja5?2jVvWfj zNY?K#HHTIGC0iu7b(o5w1xYi~$oXL%S9h_wCK3nPh7i%faaqc!lx7onNJRxz5;vn% z1-v$`^095HVd6{l7?YN7B2#2r3X!9M0^ob34km~4+1#fh3Fa~C7W`=w>kki(*>lBo z0$U4lPbIw=!h50U7~Xz(f;yEKDUbONRh^?;{l=r|E+x?Iog&voF#|KdpV^L@^BgnZ za*h>V(myAa>_R`PglkRpP7eeK8hEcOA-nW|2{gl;22D}ySaU!{l9#x=xv8{AvZz&fa%{4Q$o zI_N6)KtGu~RCv)Vs>S=KDPQe^3!|g723t8?&94VMTZeFcwj$m^!fiwuoD+^|Mrhyo zpeu!_4fqVh7F}}S9gk1J4cApyKIx=!VimoT!t>F*pjoxfNHdQXv+{yxu03c>xT2Ek^ zW5r%eit$V;DxS1D4ls0oR&vQHxZUw0m~k}!HMcm2FHY3u4dSmA;C?igUQBPdbn=T? zz-fHETIYBrBSdD=$jhnS{QH7m?Z?b|;oz2gZzT8qoe9)$7fr!1=01k>BfpP3S;%}+ zdHNJDFlQsYA`Tonw~LwWav9lO2LzMGgwYFiM4}t#91$g2HULDpmC_4r&Rp}Ov?eU~ znzDO!ce*LViKctye4o7nFMHa z_0?^bQd&`*#QXrtY8*+4{o@VVBi|w&CkMZt^9HOl&QnWqRtOO{%OgDNVd%c)jbtC< zI5_r;uygjDnp0RyA7vUYGf2QRO#fKFx;jzzeys za0jbN{G`2Goc;2k-;ut#Kv{$-m^=^HOT=|Oz@*Gsoxybae}dxQbT0oqq@*laF)Ty~ zJ;%q;OaM6B`^R)HBg+@eQ?Rj%3l&I{rN!r~Tty&PRu0sRg4G>NYBkd~xzBrBaWE~I zh=*KDtaOx=kOQZSNqV;u=z-zAlvjY6Us9 zYyT>I7#4lsHB+2oAtG|gSsze{zZ#D+i%Jd7qZCqe7Y=%=8GWC#YJSIP_;&B%f8h!^joJZdw%KT;T%`S7xmalBo>*Iq*I{Z>3(AkkD7|}gwA*hq2$=d*$Z6kqrm>* zJfyvOMZLZi`5M>G0Ulz>t*5>n0%-{h3h(toVC=m8@Gx6dM_>x^YaL<)47fop3Io~Y zx4k*Hh?C9^yhL58pIT(thd3gIQYNQbxD}SaC7R?!Yun5x;=)mj)jQV{rBvfSZqosA zAzPuR^8)LsVW8iTqm?xb>he3x@R})fPS0qq4@s#ooe+OT-v%w(e}zblC)OcUV*2p0 zH3Cim>^wCb|HSij^32y`Tel%mIPw+wsYTvc8B9CD3)g{u|EEW&6>Wjf#{9gKCA86R zBin$9DND%G9fH{=s-A@gj`Z{J$2nWPx*LAk~PQQ-pXXTO{HFJET+pZ+~sN} zUgL=D)@q3DJ4}yGgVubzUPgga9z_&eXiU~HN3MKc;HkeRxIvHHi&O9B?Y|2EbZAD( zFy-9L6pI^r59O&5VfHsKu-h0vw6Pw!FvUDj3@4+TwqaQMsDo+Jdx|RU0~%^Yab@;G zD39St{m(>agPySs$PZ`xl5lmeQ*))=tZW|HV?xP;70HJQQizMu)gu$#yNV^p=uT&u z$`uEGMNea{ea0W#I^Px9@dE_|QlSoN(871-Ku8KP3JbI2J)?UBCQ{-IcK~;g4&uB* z$xr>zFwA3e#HkH;_Zr}sM2w7DLS!sQ@G3n8!)ddhVY2aWqY@4R96kL{Vx>@GOm%ha zV62e1g^pdQWqQe|nKj3JP`Y?v#>#?cFtv2fVnAN#cQ9F^z*hRI#HC&UIjKQ*044fq zN1|z%36br~O^eQ&h_oRE=WlD6TI@D3#asjZi--tle2ydV#?ZW;$qX_?B?FDEhfqT7 z)#c_(N>sg}PK0L1&#)?dX3I`(jrL6kLsE-6%~!)2S(a-9?MjbGNmY3b;98Lyogbb% zQ#~z(&@Z6+4*Vn*APpsn=M;HfeP?i0vQ+aX!d23tpTjGtjMkdsuV;UQ3a_scB>Z?| z{X?Mn`R0fG$NKE=OqYK$&U)^{0{)Ah@_&(7{?bbSjY0Fz)S7==oc+b7`R@heztUd* zxSRc1jQ+7Zld!gRNy!y~#0EIn-&Ml@ypo&O*N>rVj`O)RoPMtLgA7|8r+ogjiBHDT z9u|ji0U}(x0kw|fDbe=SlFXiM23Wjw{xDaJqsP=G`c6u*Mf$7vyzGJzQxPjd{3iD4 z`-|$Mb6M!jt-5YgD_z?+CijS&$$dyJHSJv>7>ag&8L&)mWyo3B|4cOc4Y#eh9_e8; zuR_9fL?O)v|9Qtz-}m)_D|nFzp#5E+>C>hUq+cdyq=eqk*|j>kd31FwpE^wj-0yEE z)gaZtc`ql|mz;~{U0pIEnFj*7rk$Qn?s?_{f@jH!a3$c)DR>&!#@8-d_Ukz<(`x6R zk2JV2f%^Nar&)gfABI7sNHxw{hvVq78%h@!%!c-efH(E;iZ3tsJMJ-<-R!wf#b+n2 z<+}Qiv9M4x7P9@niZiR4GE({{-XL}j-CBejfo6;%DCny54331imlmH@{UW71O>x-TZA)7p&i)3iJ7@Zx(am;>y~ns^hq_ zF(s$T`;_Px(h&*%w%nd-#5inDT`$ICh))mD{Oy*!4BXx#I%piP}` z*)y_V)gM7O#t!Dq3_`Sp*Lkr?#8p6XcmcTTkR!8jHeO-N?QK)O$(|GwOMk^42WNTl zcuT5d{>Gmzi4Cnei^D~Gt7RwERq4>Xg7*7}g3J(N0`R*|}qZ6EEK z)jqjse)VF#HFxDnFUK2G;*2Vnc>fdqWvRv2<`)yvK3V$FZoy@Xh3mY|^d(^g`y!xT zj91|n=?H@g7y0=!Om#%;u8YJFHw>;6FMB5ymQ|u~AueyoK(K{y&u;8e5XO#X@E4)< zkQ9(Kd?^2Uh)-b-4n@QpMY|3=q&B5=Y&HYkZ9`>}+I6f+H5qTS#-2E!7xPmUK@CXc%M1tHa zsJg9l=9^>~ITp+Uu~gU|qSVofnm~N?Pbqd!!aVt!@{hlu41D<6!>pBmz+acy+LB9TB zCQKr)Ky>bG<;_{T*@aA8#tXpr!%>2Fi1Blbk4)qPL38mk`Z^%1;>RQXeY%Oo8qx?- zectp`^&+AG#kFGc2r@gsigc=0tUT_7trFB=&nJW;|0iV5bXWxgq^(=^*^Q8V{4{;e zbQU4q>_8XyFv3SN-epUzc(5_?oM|bU?VFsRI5^#u7A0$$a&|7kdz!$P5DJwjwH#xF z9X5KDES!&Q3+gq4P3(>3a;DLe_MQTYUEM~cdV`E6?P9hH10+X#P0rp3R2rKq+KSSZVr?ay}mjGo!H6Ya}X+oGDChSI?PV)!%7F#X* zx=^q8qsJLH-pkB0C~{R~XUmeO@8FXow84Sp9fj=f7Y@UcB~Lw>)`{J8gSuJ9bfcaE zB9>-M4f%9sO#%%<&*{Re(HP(9!rKT+oKte&riQI-bNw5wuK-1LwIx;bEGza>8L= zpIqEtx;5{tMlsUXHr{<|UXP7lXVwk{e2J9PdEXqb#!YRQfqN=Utw0El#I01UQ8dP< z;Nu)F?0R}^L-{J+@08nx46pEAri9jZ zdr-T$1NWo6Ju>45X*e!=ZGXP5Nh_VT5u5gx@Y{I$9AQrbQo?szQi&JS;BV5rz_A3kk*p>f)Y&Iz8X%?6!JUftyKJPZ?=^F9H$6{MgKL!z zAHi5W2DJ2B+!`^(BMwyJtcXgW+H5y2d6_NcLjN}}wP~~9lXTdGJ~}B#z8^-om3^k9 zSn-{A*M*XGk$!l^hEdjbE@;q0%gF40nGUT^O zBg7|*bSu2eAgr=0G}!1*#gK4#k+WZmzs4P`npIKR#XO|2rCO7XVx$blHo}eK0Vu%D z6#^qQnugOc4I>`38aYOu?sjMwygGTq9kx$T0$rNk!1X~Dont#e+Qch`Kdwc z_}0P=hi&;O8MU@n*w~ENMJa`2Aeefk+&6rU*AO%Kj83R*L{8%Fcua!J3MUfKbLm%Z zJ{X*jS%H)|==fc333;_4vE~$L7$UqYxEJg({GljHA)#Z%h*w^1=HyG7YIgYG3EhMOteT)JQe4uBtc2$1K@j|X@H|6 zL^t*$_cY1-TQMH)baHY;sfiaT6F8 zoN<2+u_59{kSLyTBYa&R{{#MRZeqvR8(Y1e4(Nfn2|koaZL;rc=%MxCyMCf0@83hJ z0{vuS@gi}&C93=Zt{X+)GO4iHP+>;v(K0?{rE(4Jp+rs|M>-4v#MpzlRD_P%M)(dx zchH1g5%0hDi)31X#3b>j(#}|Mxsg|iMq^Us^pgV=e?(cx)Pu|1;Jn{fU4kL1iN8a= z2LvTjRWe9zb*Xki|`mLVho_L*JbmC-pu8C)=GSzXnRBiBGm{xyntjAB za8?J9fypWviZ_%|ss)?@Jz=T@aaHJnZv!yQhrs*R{?eoYj(OKzF=ap4i=7Hxk_&}J zd2w(Th(GqCPJ0GUzN;!z@?d%s=yQxuK7-4lcBghz3c`1R&#*qjr^JK7Tl1f?sRmq& z8^uEp=tV7A%AHesLEt7!aa3C?e4DI=yv9imn}E+Tz9DA7HWgS)fa2L%=obGdOUNG~ z3J`yAUge?qK(&kP!Ww>~W(kQXN0s%bq0PVen^7Z8UA}({oA46@>weFtv!?GRqXajV zAaw>GB|uOGip*=p+PUZ7uT}&6`w)2iCNj*3+-oN&a<5UbQl!{}n=t|+E_IT%dz9o$ zWX11$im1d?VxyRsWGYjjM4I9UqyXzu%pXfs&-fX|Yvu3srg1vA%tUNE=RijOr zFGP5rFh?sqKDrt5H3pG=p3>rgq2IVbkD>QKg`swwG-V?dvMg5*_u8X)05h zZSjv>7os;OVx@9Q6)DI_YXd38sRS+EB0LsNwMZyN9Zh|#Bm+cEPg){U)SCXUAwEHL z_zjTN1c>P@uzYac4ZXT!k%Lt-Xn7Ri4N?K?w&S-9@MAi)DId1AO{=05tW|U4;Kk^b zw|*GcaE!q;m@tJ~^}jI)xEYmOR~ABkb;!M#aiJesAS>pnMH4=oH3dxX3uF82&cn&8 zvyGTTn_sxPn$+9a@IHIC3z63GX-n_BytDxorLnO?AHyM8 zXspQ#h5!Z4$y|H;g&@DQ=Pr@ES7}K00`Czyl$JUB<3$&LcP5a4;&ZF7_w+@7?K^Yk zcS)$H$@m0d82=^$ig5eRX%9t%aS+BcgrW>59KMJfJ1aT9vR<-WXf;EGomF_pi-Pn! zZ)>#~Po5qkUhe4(A=Ov<%zbA6#h^^e7AbP!kNzF<)4I`nblQl&gqA!;{gJ$hkr`;N zg2_WE;`bg>$Oi%A3kPVFVrL3jbmLRLA0i zvw;F;{_&8MfY!kjePtJ&E>pJSYv)YO7xde2*Dm=k%-L@a1G7okiU1DJPoCX`r=L^S zB^19%zgE2grI(lIo@?C9KEGPEe83*@2BUW8&cAo~xiq>W3H^F&btp*`J&R!sy-nHQ z$*Z*t_(=!#QI2488J2Oo{u*?Vc%&dmDOr$?K=IiNYXTBb;>{KxUbtspeiT@30rqEy zip<>Ic*kx!p?+T#x*he6x*&Vsj-M|apH3!A{#4=yd_md>6?AA6?hS5uF0o~9rVkNT zMl_%IM_0gPxE!MSAyudjhYBWK+`s8C2!40&Ip6#O&Mz~NfyaB7MJpR)A{RQ_-UjUd zXm((34K!WUr1K7U|9IX+bV!s^L6L=VxuH9Gf8pYK7LoP3fn%DHz=VwK6~x*eh1>%> zH}okUc-wmgqq=ndM9DW)6_Xz*fRUr%YN!)hkI>T^)}d2_H7T13hr|V@LY@xv@VwP# zD<~p;evmRDa)|3Qc*}{=Uy_xB8fsI$TWw8!P6n=4w1q)5)60yWjUp4)kxBGVs0Me|rlpHp@w3hZL=PmBj}Sd zh`0N9&y{U{;OmybdST`23RY{*3Xu@jt8Jk8k8VYbu@~XTuy8}`m4+KD0I6%^YcJz6 zAQO|2;x9R#p}Y3@6#HxxL1&}U_V|WuKmJPd`y!if5-@Iy!i+jCSmg@L=&b00yjoth zxVWDcB82j~G5Qqx+sF*{^m9uQujpp>RMdJ1!GuhA*9|%6`C=IKEgj-fg#{+JZEZIa zU98>Q&cWm)r<*qT5Z{Jj3f^v=MCea+U6u ze)6*-BHA+_Z4Df3gqjLVJ?P>uRxL3YyF^$KJGeYOOM-~R z*DC~dIQz$k(9gc!rf4{La>?ll0A|2Z(^9b8rwZYBE4;D=f==(3t8pYo5uxZ`!cj?0 zlaGdu-;g?(>;^y8dX8fP29Vyp@piH>`)KBs?``!`+{5A1&@as1!Zs=v_t z|EPuKfc@{FjepbFBK)=cUrwoL%_j<=n~DFi>1ZjCd!RIUe-BOhTWA00dH*dQDaCRR zRPqD-gGuwZJMPqyM{U?VnT= zIKuzkQua@Q|AHvTBuOvB@8m#RBL2SrWa$>edKaIa=dAbS1$O5_vw?1)L}OR6Hs!1_b` z3Albw4}Q-;F@7L6D|-of&p^?726FVD=@G>L?p6TL*KpITyN=)P zf>KN`vY6s=M0)2LgZ*#czF%oyK*_cr!We9xV%@E@d#YYmcsXys_WpQV`MrZ%iCRz3 zDALX5kPze;Pt|DzmTC5Va)w*ZGZF92uycduw{a*7OK)l_RlIieDUAHu zw7ZvFJ~%X~jBe>YYR&ohzD%A22U^j{m=*_htU$!i8ZW4|YJ ze$;JulxtTeGmYik zo!c+B*Ki_X`BtpLG{h8ry%tpZ5VpcgRZ6fG-}O& z?M>cwJQB1M?u(NFLlHe@+n++%A5{C5x=1=tiO>V6G5{;pBaiVN5_4arP@%z zrf4&s97Q!KNzA)KiB5{WN;yd?$v}^{T7!$~$O1b?cD`xbU$hn`VYvChKrx@khjs-) zp-f5W6n-Gno~vm6eg$yrUGC?1s@j9;z>UPzny@Aj;8cdG2)4kyy*#nKbRXY)!_US5 zudD7{SO+nvtbRmYYX0&5FHb%Y-@AW85*2pPp}MQr>q#9}!$`vnU5+PUC03;K2jNcV zwN$y!6K02mbuLz>Pj0|Qs1-4*lI7XvXRIz-`2Xn-+h?}{1!CxWXByQ;;a zHG)1Zo6tzfamId*Yj2b2>}2@@F-d^F3tJk8E;l$)UfmvZgk`p*LjBzbU9c#?l<%r( zAv!J0%3baP3y6oj)mv>{Ig>^vI0G3|>`_2Hps{7ZG#>jYEX37ah_Fj4$?x9N^5xx) zay0y2jiZ(y7626;4_6LukVh)(mv^|^#|szb$*H5<3EqkM(rC!IVXx-!bdADf966Kz z6TUov@R*JXgz~yFDL){X#E3@PPA2{K&VtGrXGG;zjy4yW0|NB%7*%j^YVx_fj4P$y z1x)CMKl102hx%#W!j()Pgt!2~;{MNk`}BQ#-Om?^pukAVWyQMbca78ljY(+yv%_+iWB$$u|uSB!4^ytg>x-K)F3+UiLa2xflKX4BD+|D+oVx3s%&-=?Sb zTR$_mUOHAttbM50jNGd#Wgjt?BUcgDFFQG~Ru~wKBOw;oCrfgnIl8x#{=T_e4xT-P zyDw4*mD>WJLcHEAb)A6fqT;s#^P*@HP3F04ZGp++kf-Y)5?={e$;(!YRqRo(P*G4R zee0*5FYapwbY(1s>lsEcq|K3@p$v|q2H>Rgwe2&KI||_CzXqtK!Hq2F51I$;e1CLA z83k^ain6G=M8ddJ7-iJW(tV2Mi#^fC^5}a=6})$t>B;VSqxRY9S+_F4T7AvbXa{m5 zzLKy&aF^?8QxiXANpOi2#ppbFv8Xt)4D^zMW)sNcE*RP>W|;=LPly(7ppE@@pxrhG z8}oqu4JzuO#p(5O4&M_HjDjW5BY`QHB?DknM<@jeuaSwM46UJwjFd_!CXWaw4e-m= zmzlRe^p>4s$9;(p;V0vF8{d%1o@tx~;Ss^HZ#42589P916&jA^S91IEWL664 zJ%-Z_-)3VHvh&w+=*-xqfkRWi#k5mm>1{!g5Q#Q%27^0QSA}4L4e7wpaN#T zY`Euzxfh4tjRz~1VTv&x4C#ptok7knX{-6mU{CF%SnIzl3gvhSjL^Wd!*Ik;@h7OC zTBzoNLM38A@L9`{tZ&n69d`%qeA9Omy{I@ZxV5R~l?E{c^SVCkT{~!)heFa zGkK!HdlKdw(}vu{KQmJEU_m%-d;(-n62tFr^p26Jd--e*65xvah{vZtisq{MfWmQ^ zrAehv6R~D#%3RsgU>uGWYh)TYEo0}VD6o2e)WrYBNOrheYr*WvPky{l2rG@RtT;5^ zOTdz+`FTnk$HS{m`FElHhZwTkt?fC21J@t>vS1rp;(IZ{lmZDXX0ck;5f5OC#}|&xxjP^s zm3#(bC3MG_KrOtHMRrwg-XKSy6Qak>O2DWDw`6XF1@YZlnYx!$ zm=>gb5s~!q1$)`o)NY_=)f2I~Mk34t8XTfbA&%2vp8SDL>Tt>K9WGt;nW?#$g5fvW zPUwkMcZ%=r8+`24d@aC1BQGt5m1&@)%(YluUbAG`sScJmWZj1qSg*Ing3dwujWm{}M*6d^Q77&MWt$ zJ9-PBp5({SbheWPb0%3(HUmodZ$kaiN6j{`&AC-r`9o)_Ei192B{vWI0iGrTQr0!) zI74-$)7`tpLPcPgS_1BCoBoc(3Kyv4f@c%I(n>!!=3Zdc{C9*;+wq&oGZR&Sm>+>IXCw+OSiIU3w3Oh)_lw1oJOMaEJ-nxZM}PR_Bbk; ztkJ8L@b{Ctp^u(i#$vHFZifjU%`5UR6@pi=&Ch!V)zF7j7KAFt392~q@y)(rk2eZ5 zkJR#X`I7*3%sk~Urr$Y5P0~;pTNyHlKhl!Q-}`ZxV9_!d`AmSDE*y;q#zn7sW&1W= zUmVF$l0okdy(&R}PyEgF3)?gh>vckTxf|_;^;c@%lZX$0s~&rX1vIN9bx2WLVopDy za_}y)XiVKT$?weWy0PcyAcj%4c7936$*|ZuxF}7a_hxd}TWBGe+17Y)i5NS4LX~l^ zE7sD9gxdvwn?LeYBwpiTp|gVx)|FRV&XdR4a@eKOzO_Oj;h;~ZXQ?@VZMH8{MI`qw zhV4W8ey8kHYmyuuxq=yw#azjWGUrxWpnIk(Rs+KR&<@YlgxT?CiLKU~C*maUnBo=x z;LlS)X1vJO^JAuS!N+lvOcZ<;<=-RA;I+zcTgb%TzKMgFl|ubH>D1LkskZx`a&uYz zsYj=7=~TN}1>K@j!YjHN}Qd90L?S2^Sn)1<3XNe|-I8l;>agOIIVY`vMCjND-a@BAY0WeFW(eK}Hp_SCYGF8D)7oeu_EqiyhGEW)4!MgBPf;VZ z4RcOAz!Ih1>ovEuFzBY*0J8U5X2zy|2HlxEgk4e|+ivxs^i%FKC@-6$!y0Ol;$VDy zzV|(KY5vO*mn$f?DR(LzzeK^?(V2TKa%JOveRehN>Mrt-sME3 z#1J3m;TaBU%=;He9OkLJ@M%R`LfvV)LSx1iP-?vcO9N4C!yT0tWjfy*(d2CK5GTmL z{^L1jA18O*z&)t=yotoXgz*c)8AkG@M`TVjuTV9+} z05XGkuQ?BD+A#IC;5s$;M>qSHXnV3Cl#oKY5`|}r-9<-mF0qIO3k)x@ z>9;iCD$b7+Z*H8p6Yt5eF>3kSSq3#VfC*%Zzi%IPxZm*JEg3ed`Q`xw1OqnHCZGLn z^!5Yc7N|B{ra~*RP-sv0YpXiDR=Z%~v~jxEGJk@Bbirsd;y(V5#$tU_JkXDE!BI`yWs0|6#pl_z%|j|4K*x!xsK;I)da3hOYI$ zla2qa>F@vIT>p~-{jUp~JLHb_ziwc*|F&zg{r9BKe+p;+hx+*+RAl-= z<|JVI?;`B~)g`h27r%1+*RspO-UNzb4Ezs3wpak8Fe<0&N1%dXv9SE->i^m~n3-YN z|LJ#98&pt4z+wI!5~Y5rpooIQFmrGcrHZSfh@{Tkqqe2SfuVr4NUEVo0fVtK{`27a zW22D*I#kq+brKoEI)wHT%=fO*G+R45gn%Xf>|e_Vcc5SYKU;9e#qF0*yI0A{WECZ1-P~zMBUxp9f=Bf$N$+DK@}r~2&gHe z9s(X8{|g}by#~VQ`r$TJT3nbMjPG~;(7!ebVQyz-3i%%Ny2Gx_!~*I^HwAR8%5Lg+ z0~4XCc#i^P3GKn=7nGiz9vBZVFgLb3JPt-=WnyT0VlE2G2+0k^2mV6`L?OVV1gHeW z9FM+Y2i21HLhYK{nHoM>m>ydin*PK_5a`<->suY2zIwpdI)bTlVy*e}IRSxy{JoU6 z&XWFt-c_>wP9Kv)@`BtwLD-PnqD&*1MLsm&*Ec}~@%B_fL;q>v{F5S@2k_?6^r-+A zc$mp95kM^kINpVuJR(k(Vi+5n08XHQ(%XDt{DF*E{K}IHyQ1SaN^j&Cy&x+A!Fz}1 zCT4fJ$g`k$lXOvd(l(QL`1}TZbw6X%fSd=y1pt3nd{wj-sU1J2SRQYDcVFr*W3s2-B*s}^z1W$#Vdf~NUx7292$_C7+3I-8+XxzN8>xq zDZVuI&C(2r6c9pqm7w}Dxkhbx_H~f99Cxw2zcpQv-w{Awvo$l1(d;V99x+cta-5KV{*y3A-r>|&|+?N^C$We zJC28owvG&CT~Z{mQ#QPRKc^+s`}Wbo%?ZY{U+#E(bkWFXA>HMClo7S@kc|Gq(d-C){_VL(()yoYka zXKVD(q%4hFyDr2{s5iYVYZt zWve=VZf8I8Nir;_3?i&rPgs0Zr+x%ltsPR;$@7KKkBKaei}rGMKw8yIOM#D=h!&WNBI`+Xoy&^|f-= zhd9g*;LE3wlO-e`-)Lu+(xaSoQs|6+0fdO9`E zERVJLEzvUET>;c>ezE4|prqj44K=LjLJcakm7Z$}?Z!CsvISfjwaHbRcgi0#QgtkT z``b0!2xP*^HS|~Ji@xX0dVCAhQ_k63a^|r%041!uP^(zFz~d``%|cAAhu$I(ZhML+ zH0?5RT+~_#*4FAK>AYrnMgv>*IfF9;FOJ4isl$nTCZNn<)S8$6;JOb5Q>Yxm65oOi17(A9sSRZcjo9>5J?AonB zKzZ+*Z6BpS=+*MVR}-03fb;6MbB+}e=KeOHtCu~`Qys^HbeAC(oE=5?Sve(>kT01= zKoKR(i+|V=fcdAgBwy2i z<5&#drY$vfT((e+M|6(*1Iuh=$$F^s0de4|&T{M9&^o(5`DbtqKx(}J3yswTV+uAbnEAJyl0 zA8Ow+1;=TNYB%B@{RCJs=$WJz$S>bwWIdY+SShrfR3**4?S}hk7OKKXmFVzY<$X(Ydv+sPIH$0Xi4nDW`4~#O|~m~pLlZdRQ5117+={Bz#-gm0hhA9 zwi<%0K$_#dz(L~PkdWI6k+o3L+Da@@gTME}Ljet!0}O7V{}-4;&FI=KFtvEZaNTS| zg@d%aq6=qz@d!UDcPmo#qJmxUskty}05>PBp_xsXwzpgk?X{%+_3`qCZ4@KvnQrnE z>0|2=xW%o=hgvXKQnoS=09}J)d}<)VXDxQd8+M^qj*O{rdH#?uyRz7DW9IQ-j1LLe%1 z1qU-|bP@n>=&&UC9QcSRiXfyOo;0{*p)~+suBI*&V&6pSnNWiS@KUH>-gT=Md$F-X z%8*^jiu9sLTW1sl{-c7e&@f+5IBDB<@^r9|dfR?KG)EJ6-H)+{e0GaCN)eH`ekJ~C zZVm~ZVq|g6j5N?}7Svu`#)0!P&t%b9;2d3ECu>&H7Vi-F6sx&i8g4e!eHSaer^vW+ zSna3j$Siy1#4Df*U{;~+5r{D4Fn2{k(zeR72NP=EF5Y~}U!}o7Ae>67qwB?CsB`M5 z65!2TilDl5&y;zn@o5811F*(od}nb@`WA<3|MX?ed+cW;t!jXtXA&PotH3I^94If* zl9!!h2PTvpmS>XHNiBcUlF3S;@?m#w7E%f532QAoY*t1CGCYv)z-PHg!aBMc;X_Po z(T7#FSNJ9CfrZ1V{{pso$iDlN`~&|qOZPF@eVPQ)qge25m9boSin^*zQ8 z9Cjwgo)W%|&{r@@5c=GXr;Zdq%XokZTn*>xt&|`J$ihhX@c5j@5e!RkRz&ag2P{Ul zb!N%&SlP;}{zP7Ijng7}YD>*}WNo@&Au9$~#XS<)CG#H|E zK;Y@H8f{NnKpnZ(2ClYlx#t z*d)aO*ycQQF}V>Cu9~xO+_efI7knKaVO8{R)W==~TxQ~kN26uICrl-W7e0|0uor+u z(?dn22(5c8Mu(=lf9>W(Wk_o9Yl4i4&Gk^R92n&8hs8;pQ{JiQe~!ZYRu=FpI8Jq) zy$#|2<>p|!wSuSc47<`?+9$&?v|uah;i z9`2L|>((w3gGsyPQ3T>Ml0C&jhX~!AQxYm)-YFTMZLty`a8B7pT%Md%NrJ#;#m0*d zFo6}0%H}8Brpj`b8aE-)V{e0SF^PIVeSE>7VQ!g5Ec7WO&_ac5$SAhPTxgXg!eIYv z4|`s<$b#(NyNX_T`0G!-og0fn;Eu^Sg@FH5EQUld=h4y7Y2dj+9@mW_cT;1Ov{b&! z-CQsRZaJ^QAr!){X~}dp{&oOt6uL|&Ag}LLSM5kY<4V=1vmSL4O3|{+!fjCws;w3C z+#y~u_Q?AURA|Qf=^?+S=}CZ5axw@KHWtbJHz>eWOVmmOeegj`&gG8V1hh(AdksIP zEkyG#0pBwcr!zB@S;F+F$?FcyL|Qh@v1)=@GX>^mba?tVSEPvK4g0cT(|5`x01l2- z)`4rlv8Mb3Yb~CD2kNyy^_pJm4`~nfh8PwU!93vaBVn9IP0yNa^Bo{i-@o|g9$kp=-fK}G1t#|@m(7Ho$#@W^bLr9bhs1ZS@5 zu+DPM_0C)@V2WCcoNXvwNUaS+Hi@FOB8duew0bzud*9|bo7z-E1wd{Nfd17XP6y>8 zEe1X0c47`C@W&r~7SdRFOQWVQRqV~P5K}@t$yVOU5(x?WB891~*3RU4F|+1nCzGJt9>dDl^pQ&qZ$YG!{wYiF;Ligem5 z$&ceS5waJ@a*`}-8m28S0m?EPHSum`E;b{G2R>j7{mO#6f@AiLxB@?K^J6&L0(4rS z64YkL^4LxzM`O8{6^t59{|wyyNzc-99&N(iU~H3C^#$)UN7td|+7&}EJ(c=yL$AJh zdyhpsN29N$M^B?yl1hw+B}Jz^^(EG^S}rVTp|yi0!*`@QTB~**19URI|ADiSZ*&y{ zVR=%|hnF-5vnIbm53KAFzZ-j{VAq`TJStMX33`6V8ftAWid6?$B|N(QiY+XdMO&FRG0GC%uq{G%V%?>Bm`P-Y4ZgpoPLh6F z6g|)HA~h zqCE4S(MnhmX|!e57)|u4Qc%NHJ;Vn==@JfGFPk`PM%46KVqtehkGHAOj*^G#;jphZ zmy%xEwuTLhO^ASQf|l>RrpRmy1H0*Fx6d=l`}zw*;Q8ir0RSS?d96N9j{Nm)DgbZW zlnv9@rn2!+I*?vLGTeB!0xn%eAN7>_g}~e%EeQLWFlpb>5o>vjIhGa?f%WXH^kT(x zNeQ4G1qFi2V(VI}dWQ|&5WtVf zpqId$?6Pm?3g|{Ku*++KBRRxdUrP_>78|4aZXKtX77p>&6ep3P!#&65DeJW-nvS4& zp8;RgQz}RM1>S0TX>17T(j&&qv3%Z()=k={SZNtyj0k94k7#?~wxqP9G_V&EqEsII! z{tFNG+k#Jxa{rk|O#}zI&VOsJz4O!n2uG`hfkwaAw`z?zq4^dEFWxE@!p7tjE4b^R7e?y5J!D z?rKohdH@=_>|j?$BlUUS4&^>YGh{d$ea}8h?#LhwC9$O8+a(COJ;!z64AHG|HhWZ- z?p?!|PuMa6G~|o-wr23~WEnwGX{8_?XqGyC(f2skG>cTJNUUlKxQtQ+S$u|K4k;%o zcGEzZdk_M&P%L^e*``6xhs2JwxRI4%P!ts+DuCkEK6$DGd`uP@P7Co#A)*F#))?n5B z^6xNVxPvnO%dD{4qY8F)tiov%UD+pjU2pSpl^G*#8?B~(*wgExF!*|2$hN;>(JMO1 z4S;gs#?#8j3p(fH;})UetaG&MoUDprHhJmK2QAOt`yPxnp=3z0>XN^x;+!S61JqsW zr1~5U4+O#|<-CGYj(s$pjPR6eBhWt-AYsJ|&LS@?)YAA3f|@F%o9)QR|Q z)!TmA&J5Rv)$sEXWGwR>Y3O#+iYmo{0dna@O~&^7>p#))fMdsX#rG> zH^8vBKn)RvSOP7th;9m1M}X8o?+`|(NN4SMnD^%R8>*$PFO>RTaOfxDQa#~wa|X-% z94iR)6!g3DohjfYKT2+xg3M%@BVXr1-&jhUmwGn^@?N06@@M1Uz&E?~P}p}B7Pbl_ zqd-g3kRPy+^6q2bfi!;s7uBt9*8`mTA+F5Nbx4x8%TUOHUEn`nn_op(1{(;bZjhbW z08Z*Za20hFs=D|~)GPCVK9^*4Ziqow`fKk7*CqT)4A0ZmRFm?8fSQ>To54C9ozcb& zP823t#E3!P^*cWYu_mQ|<_dUWDiPA~xUdV*QIBwa&A2fxkDP7l%4YTVFuA~;#Wr8X`hg*}Ax$mm5P&pwOK98pt+_lp>19$7wUs~S%_j4mNHB-`fsPl$mwqtr zQFs<)+0NPp$%9TJHk_<-5U;19Vc^zX3S+7YHOKd1P!o>f`TBrMOl`ZMua!-k*O#T| z2;=TEka4a?4qmq?CW2FdoEM7|LkB^RKNtVIRe&NlZzFM#FmP~ZZlPD@@< zouRzz8OnWIGjs9Ny^4%ZeG2{|thGySp(wp48&n#DW1db8?l1p zzF4?6f>p8ZO}Hk<5peIEqk1Xe(AO$Jygf4AM{gfGaWwL zRazvSP(xPZy9Gaut4_#Lq*E(iSl4MB9s0T$PF0c+&A>|tW@E_dpFVXiY|DmP zp$v>0-I3Ffc=#F~N&rLOuq5TY6O1?pniT0|%ze3P7~r0bZ_ct_&$_OaOI2HlkNg zc9f2(Qf>m=P!bbEhhEg;(JL3Xo}$#sKB0RAz>2e=L>l~uCO(XPX|8B9kB1i0VGJ=r zSix$Rif*GP{6R|GRsHu_@mKchAnHFLPBg~{IdVLG;ed0qbIMZvBCsLSG3~J-JI768153FHEM)VO;t$XGCrB*qg+M7w&=5RBBwm$_x4y&$ZQgFT8A zV?b#_@jjj7ygI=L5KG91RkcGFDa*~^-eAs+5!H@t%xUr}vJ@)4iy8G^29zJTifECP zRdb{Nzp237?aao_0xN}UZRp(7&s9cp^oq$&1dvdxJk!d5wnNDlUJk z0x|4`?~?(p*r1Cw58*Lg2MwT%3XHg!2>@)D`>I30*Z{tUzYKUc)E124({9dJiupn$ zOQTe7;H5?<#x+n0${;a;e7|+2r$_1wpOuuwnVg@ROuw#kG&QePlrUN>5=s5tBpC998Y*Z1?Pem2~~Gwue<&{i)nj9KVVGp zJo8;mt??joZ2}@&QvsbU-U1u11a5>IQf#SKrdj!?9)dnEgonS8`fn3`z=ffM&tu?+ z_bi^K2gwHEK%!KA`hzk*n~pGB;>4=Z@T-+cc)g02rm%pz3R5-IY93#>R20+)Ej+Q}mN#h|Wct^}8ywqpq0Kpkt6r-XMc^e*H z;xF3Z4dp7@CIZFV55_B*ZJTc|VbGXsTh3?q5SGF93V%bt|H<1Q0(k)~Yul_hC*o4s z{fDQEV&UZN5nowx>vq=cm-#jjL{8W(uIZVJ_cY$>%n3Vk87_q6{Rbb*RlrK!B7dWk z6ss!6vm~-$-U#UU^y?RuTa`3_fVPNfv%oeYN%hi>u?E%y?j2w5aeY`Pk}(?ey7(Ii zp;LtZ$J2cv+HOFGU1nleW!G6DaquY53YdHF}HF~H@!UM!x>VQqDGoXzQ z6|w?lxfoGzdZLj7@3d_-sOMzD_m9b$WPL7sztHz#^-KGt&s!36t%zt{ARSkNBQFi* z6i!6nw-DG`|4{b?;yC}7$O@KTbpT!0*g?zK}XpE&DV1E)^gUX(3>h zj=^m_wcD++WYMV?LP8_Qm<0eX!SUI$Wa1Amdg{zkZ;l871k87>Joe-`1Dj^~n$z%i zqt+A({S;?Woq%CJ$wSYnH*|^1 zVQC~msL{~nHLjh~(gP>sc90w={wm+D%0;0Q-8ERu7o6fq(8_HWQX_5u42A3hr%U~c zPRS3CR;JEBAF>|{!P0B9|+M%6jRIW^Q=?ehvGZR$W& zSGM?tf#GWZH=MsRQa4)v{tIip%8WEHdNq?Q=BSW9n)gVn_j7tj_BrJTycIMYz z<1$-V79fnDo%~Mx>cl_LD}K>1UQVLE&5u9Qp~@%#i!2hWTPZs&DV)mfI`th%c#vzSZ^0a82x*Ii`{v!#Cc!f; z(n`FPEBCqh84AfoC=7nFW?_@PX+X=X+e2KM0FY$MT)i#}{=D6EtP-PNr&MW$*~*9Q zB#nXUw#N7ql4$wnmlXq3vOhHhUlx`$Ps^V_1fJVkk(oXni8N8D!z3e6I7i=5!$9ML zoRHhN;Aq~~v9odJ2XX9H4#_# z4d6=be-gsHzB}m}^^J=is_5=%T#yj8-n6ML@@w zZjb_Um^G6M{k3l@=erNXEu;eLwP+!O%`9m+#ASvp-Exw7n{N3&(bqL%#_~7UG1Hdd zghURImrn5J&PJs5{Ic|g5)mejY7GvJ?A94Wp>H_Hfy+C!H(H3lXjnyQ2r-OfFCcPB zYyi_$DTqTP1ab+&TE<`t63P`dO-Qejt`Fxgi)oD!l%FH37c@h9X#cM@`G!Z3EaXNA z>|h9p0*S^?0q42dwwx$Ll4eOXg2c$D23I|bni`}^JUDwI1#TcJszL^YhG=J}@c!IJ z-)+?FwcQvs<-9Z*?Tg^vmbnw?e`R>UqCA3B_bEtlj8v45xrbiLktvh`0O zER%~E*Bo|+34@~fkDMIZWOJYQtWh7m+{B-Ud!ctw;7z(daQpn#Ub2jk1^R)%L=(=l zJIxNzv9N5$#`qRCu1VkgBi+9niPw-@#UdU%@aKzef6{drvG^A(dOg|WvH`H6l{)s; zo~q%^B*wPk-{uQU3eD}W03(dVKnhFb&u9V54&|3Q7`ePxl8mX~rhydeG@Sj}6h#Q`Jna-o`i1bnUjZp}9#}`tIBJ=@YeQJ`P zNiIiHVROzwTlJRw8}sxPYn!n9&hscN{LWCwJDmztFcX;aQeW98TVfAYr6TM>{;z zGSnKV-J{HCDsuW02;l7wf0Rh>%8Mj=NFAuzNVie7i;7!+6+BXB6Bx#IJrbe*(de!r zPtsClDIQ*vKHlek&$DF@k(NiV?B;%#C0maS8c$oYWHU|%9po|z{gaO`*6Ddn@Ao`x zVw=|q>T$?)!872lr6R8{6F}&Hl!Eb2qGQFs>Jip3{vbO811Rzj4bG^aK5?4I$*kKO zvQKNZaQtz|H)Z-|Zr{ET!=ED(8A>A@qsMtcpb(zkx1f^1DtMLCh5S5yySMnI(IGIS=b7T2Mvl2dXdU+ooylmDDLzwF5Frz9iq`e5UI1({!Yj(I031@ ze}?lNmxEjD`BRI3K^M^5Bs{7R?}zeaT1if(vnp6|?-rdc?D2~D14IO#s( z#GO5he8@=#S9m@|9989MCv?~0<1mr`%I(lb0`K}#4J@%CRa!4|x*um7&F`+jwS|Kkuvg&|@@!gQYoM9}e5>ilp1c@MmiNve# z&u+LHAg$`fg$jX5BG!)pf|D>kk9H9;-$dUyJ37)#e}~NkrVERYmBLpghRxDvLc4~6 zV@z}>TAk!iK4+3j@S|qQBAyUw(%%yJ`hiE=iUGbL+R6Fli&)+G$v%f=aB(h%`l(%{ zF;*oePw+zLjbiH$U(~wYz0TnmOWAx(WQkpc-n*>Rj=MYe1$PQJG05)G7o@KAo#E~- zWg8n_&R_?%UI&OXyf4n63!s^A2LV>IitILcb)tk)t_g&zhH?Dn`%v3@oHV|kG^h(U zN&pyQZnwY6GNjR@ajwF-5 zM@!^i$qkL9UVF&U5rV0Kli9rOMxUdDU@zzd99bkRU8qzC+6>&r_~}(crj}EhA_9C{ zr5hncKS)&^qtnhI;Ci@Vl%3riTKT`a%ttk=x zC0Adrqlved6(}H<$Jsoq!IJSmVhl{+aXl9&C%CEhg2(<3op0I!Ti7)3>1`ewae8m2 zRcNPfaR=POH^BJea?MH01XlE?q+;%=FTRn>mJkRR@-}dYYb;GtNLm5s*UcbyzWV`G z*8I%MR930D&eUljt~aCW_J9)w8XO`ym~~ue1X8QaU~3=6Bep;W}EBaY!MBsKK^Yd7+N3egiaqS z@xoL*bsQjK$IAv*>sI-pg?~oWJSaq&G>CS?sDRum*}mo`zz`?fEWnV~bC20`_(^h@ zGYf^%mt+5~8(u>CmxD^DXd!*weLC?ZqH@JozXdg0(Q`|qXVdZG6Mat09i zKl5bU`bl-$78ZZBzAGQ9LMveU4}m+xWh(l4h5E$J>LJ9)9{K#+Y;g5BD`4+8-nvfL ztOCv0*>>_o;O98-kpSI>^0a;mB%;AJnjdfK=9sY+0x0VqHP^drJU)Jb*&{Up@l(=^ zSv#;}iFlox3Jo6i)6TPgf+ms zKNr$#-=mw(g#$Dhy;U@PiVsqBCgh$Y3SGwxcv6T!b;xw}WK2S&*z{Cqe=XV@E;C^TK_=L&f1zVe7tvr2rgMY z!v(Em^s@LpGS?D(o$~l(Lp)dl+sIpaxv3-*lMKTJ&D+6b=b>L%~S8J>Vn)aCu|`>ym{x z|Kw>k0W?g!{GkN`&aDl3;v@$Bx!$>d-pyYmbDK=)G|-|e zC0=5{3183wRn)>uZL|1`)E&k0gv~Sa)uaoduz2izoc~&1C!{lnbsDt4TQ^VS6`SFI zvX$^eG9fQQEA{mBpKFL))3k`pon*2K~A_pCe^8j zdy?UePbE<%AJW*?=zNwtx$GNs`XRr|@11Qq8buJM&tKTN>I>R36_mBaxO{Jf>f`8~ zD)ReWCslsoUgVdxA{=+w5$4d(cYnyZDJ#z>&6Q;3yQyn-Zkwtk>Z$;6HaFtfg#rNA z!GPGC^0rPHe3%1>_^1{WtOeY6Nl*fkUG-)Q2DO#njSYK6FeMXdJ+kbQP~>92EDCy{ z$!cF0Bo_yaxqY4vE2m404Qoz#?$;Bj&g=rAUrJ}V1kfu&m|m-$(juA5SZU{@CTPDd z=75-?KTjsQ@ZW9-D#o9>MNQu~xw3TkUjaY{pp%6S4D|DFI2J!4ztEPySEzRi(Z$VW z?C(5$<#;z#?-3JXa~21$2#?d*o)lvub3%zyUrW}ArvM5h-z=+Lr#DiEDAvoNq5G8b zZ!QE%mZbT;>~CT+Z6r^-L-XX#=qayyC!N1Bs49Ugw_Q;4&aD%kp+D6&NmIvNBLRC6 z4DpGCH}I|L#WL5PF?dga+0FCT7F}EH52~6Xl14ZXFEyWVKeaVCYx#mI)&(xCw-bz@ zTYvfIiy4%*Eskh*!<2{Xm`Zzwjc0cQ(O`F`vZV3se7Lkb&meQQ4qF!=137V&xN)%B z;>1pb-?WK;tG6nw5g82h*S^6PnE_zi-(BH`^L#OC2QZn>oGS+*$1}xStPMvFv^k=m zT<)PM?hRqi(*3;3*>Mr16|An3iWFJ-Mg~N+6jY`eJAe*IX^#{6rHYOM?KOLglMs7S zjbpn_XcG}+?R^&ORm2bDeP6OmZ<&wfQ|O-kN4QDQOgBZj826Ddn$OnzBEVsw6h*-+ zE^5v+0ckXwFJ~*k4xbnQEa$LAoxxwLicZm50W=M>;3+^;d*b<)oGVtLpx^Z5}wR*f;75yH)+LF}st>Y!Y{P0D*(F z)w4gPQR(d&hvvs1F%$C@nOetC6U+K5sM#QP+&YQ|+C|o)M_(C8$7i1IumLX+rO6THZiMS$c8nbt%1h2hti z0%U}hZlwWv zD4f(6gWlB+N$B?sPr%>F7>FvL=dZ}NH@gpyXYdiUXkm`o(a~z1wG@?KP5x%lAYiwpk9Kk@|nsXe?{nttd;)FO(=0#+Qd0h zSp&Ne6saZ(7t!LC48D(9zb*N>R*YuniwN1p8Wo63y#rxjMsD9{<3sqG`@os}%o0B; z)5BtUmv7f~t_M&)r_w-TM3~thGGBn1R^R1Wt}eUAA$%!{oC7a&b&C|@Kn2}KYv>}N z-7!Py(71qIf#YX)a3=jK*hqYUd-#2XT zP8BO5e`slkg$fr+kzlNkFGf4laAy zl>6E6CJOttZ=i1O4k?p_F7Zq%qAzO)f|k?tU6(ge(Ru#mycc z@_?7v7!8V;uy24V%w13^Z$xEZH5`;|l|w4Pv9 zp&2g|U{@&q!n-2bwFq9CZlGTh2DA_g$DW3X~C-6^X8uJly&ott)%U zF1()7*>0AVOhnV)8KH3GeX{S0NX1Bvxo8^t%eFD^w3Y-?hQP4Q#)`dpj&wRG^H~6K z(BDTghJrk}vU&E>=uda=*LcEG-kaR$}+8YyHTO#W^ zGcIQft51ktju^u!_J6K$R-p=nbJ%pU^FXD|7R_E$BUjF$=WbO(RV2@IC*T1aD4a$P zshM>Gh-H?m7()F;H<+!MG>o7}`+gfIq`%pmmO%r_6YX3DlbCQcM5q>ge4)V91dG!v zbbH84T&y;G_HaL>-U?c%a7kWMjg`QiN&m*XW6g)@^E5C{JFKES1K0B9iqKgkAlykm zH`tfO#}eol6|%b#hbJ+Y79Ijh@4Mc%VeHbCJ=6M@%w=AtT#Pf&o}ub>S+whWf`i+C z;(nsvpOv`n%%15!To6D#y)YfVSCp0m9~?~SgMamWZ?(xfL0#t@jQgdC8}^Ks#nkx4 zOQ=MGE8??8dlz58X|&R$2h3m0nsONP1dY!}=jZH2qMZ{W*bbZK{yhdTkKH7^NafvR zVBu{Y6w!D6I%Ob4Pg=HDQtIY0Ob9!QgG#-RA9OfWN_~`2UMjY59OIYjc@@w|s#H5y z?rapxs)+6XNNf6CY0{vYL#LabMLfQWQ{z2o)@^9Hz7QKCozQgB-f8x`TCQ4$6^?u( zlDi*|W&ZBoA?*R%i@peuYpA-nMCUB{k|KD(!vNntwO7bbQPqnQ((~!aqR~;hN^>1> zJ%cgYFX-->w;|hHQcmHnX!Op)$K3lk&2>yTsU5VP*HUx31WsI^{I6i7_rrrwZ^<^| z#dK?-4rFnXesZz6JCjw56*kr$Mqdhf^GPstvbhLnOuyd0>G&OxFrxX{>Q^cMYmfuv z_UGx}jM;?j6@z1oiu1p}7zs-i-L|_p{;GWn1_gK|w#rF>zOx?JSXPpJI%nW$UHtVe zzJ09Jb@fl6E~ix4430?(yMM;9Anm>t3Mok^8~2bJ$k|ymkk{g3^M-U#0xQYXhS2!% z+1=HMrn`piB2I1thv} ziT|`|l%3)Jf!r;{RKaUV{FGj8oZD_8e`l%Ns<%0gmVutB0wm zF{whPoY>|xnUjmD;V1Iv^Yo@Zot+^oWy%2Vow%LNaG{--GuM|KVRgtDNB;rN#_T(t=^qk80e=!qgr z+$Ig|49{%oFge-^XVwC=Hq5-a8#Z;4zG%xDh?L@$1h!k2>DQARQ^z-CHQ#ivh0yyi znZl60%wR^GCIe?0c8aNACu?A(lLU``#pT>$Jjnp)4A<1LTqxi*^6^Kt;49RQ*t(`* zb+m!fS>dLNwv=~$U@YuN_-#DRQqOUpn^v+eF$LZhoHq<(3fhp!>05vP6;On8*FgZX z|DVFYoPkCLyD*4VUk33_b)hbBJbDinXC0+iq2t$M7Q1;hcAm3G7@(U8q|T^wPXRv*pGc#+^;lZ(VThw>_Sv-Wrrh!pzw&}z0fP&T!PuBDLv?1#Q)Ag6GKgKW)m(RDDZ-1=v2 zo047PSZ684pV%vJJr|$@it}Cj!{QI5DtV>-Xr}M*U~@DbneVF?TEj5|V)yC^tu+86 zbT`|t&7BTYN#u^#`zvEq$_4ZmAWIJsnto4v>dvo}4m{%H=w!0JQXy})*+3Byr z8h?E1T|v)a(LWqB1hpz6Ma;LgFU%EQ($N`E9DRuEaooM8R8EcD6NQ@zd0$5Yp18=C zfN;XQqlAdXU=K}Cw@0kM>%!BM>eHu9 zh?Na2&_$;t;ro&kx5Kifx0*9Q3a*a}z<(!H{_Yx|zfIlkn=R}isk1FZ#m2Q$p8?#b zyNA-bs64u0Ak%n|%PO4KB6m;P{~ibz`B971kn~iJYNLFC=5^wyXjq1B&>j?-z6tFG1wc;#f4_LxayM9Gr$-a$EC^AuYVCM zKw5_}2J^1=Gn79o^o!7z3sdC_|BJ3kwfZper#_ryy{Ng0=FjmI>V#`7+|h}9(7SG&>de*XZV$cK+ZCwaMIKj4ik3=RGI=xXBg5wNrZRz|@LW7feF) z--0WTPt_je%FWG-4FsX0u-l(Mn$WmvEY6|kQ}XbiMh<|z$|wF?aU*8jZ3}bYdTH%d z3I@tJP#f&3Ho1TGcQwZ6v&7a|X;p@8QxY$2=#C$M5$Vzl{Lnf_OdjgXUVlv@P{C+J zE3VmOL)RHVe;pQD@L2Sop}a9_Lk*t)rqVU2j$9+cM$~t4MVKg`r8=kEKsBAqvn4nP z;H)6|>T9AI+afvmaOAem?{u;HEu~GEdlf6Z+%jIEqRpf}@#L@Q=ihk$mmh@xrS?<#|8MxW4E=v34<9QKgK)!K=?lZ_^t$Fmyz)k6PN9l5+DRMF*G%|5tkB5Jd@WH4VP?s6)TrD))Ew# z8Uhjzm$lOpxtG)86&9Dkt`!8AP_7jTm$Kp&6_-%16$Y0;t`!8AwA2zQm)znN2$xLb z6&08I)Dkb35aSgHmrUao4VSjm5)PM4)evn~k19Regcjk~+MySvl4cjIosf;$9vcL?qTcMtAPAh-_y_r2$wnKO63 z+&SNVyK2`{RlBO5)oZWa6eP-O3?k-^ra(zY2QUK*BQq~R(c0eB6{O(kAkUx*v~&f0 z2sscbD8yWVCSYqv2XPZHkQbl@GzW+S&3^!_tN<1s9v(yrfS99`r;D|v6&OIRp{hkg zM@Ro(l7F@UOg;ZY^I-|HwsZhcetftA?Hrx#fezpgi2q|lH6RcGwgLhytnGjRF(qXk z8AT}owUnX;KnmypbTP35D7%{4S(^dmt<8WAARrCE!qElrA^2wjFmrS;xBe$J5P#!G z5F#Le2>|2-G_(FN1A3SNo&HhL1Dt>^_SPWK$2Y(l1h8~5aR7gu0oV~>?Of=#R)Kmah%<9|cw2rvZ#%&kFAb|#)5zCXa6T&({UhAYV0!ScT% zpa-}BElpg^?SLTA2h0cdKd19wdH!SiAK9BYIoWys%i8f@yZ$o7PcCaj9tjdg+ZP^kSf9n6+=l{_>|95CfS35gJ6Z?+__&31-J{ZOkAP@M5W9&>^ z{$JZo?5*uQ|2GEzeWMoe-=y>Zfg=Mp`RH^J2g?s;U}pSi*?(Hm8YF4$0W?>(2Af#{ zEKKY^NZ?;`4F_|ei=DLt@MC2E#Rvcf7UutD^Pf6(D{C`bhmXkue{lR;1#~d~Z>|2% zjQlHfCM8)(4K)qA|IVrZ@}~ST+F*50r;ot??Osd4@qtUUmFA1O1l{44Q)lK+3K4E`I8goBx*`9DOU z1~zdp|6q^*6#Nsdf0?U`%Lg<4iwQmw{*U#)7#9fi0Gc7LEIOL;h1jHJrh{w0<_wLC z>-F`pKn;aDl{Baq<_AHcs-swR$d`IKA%4((VuUe6geIP61xz z5%`kP^yXu%Q?_%_?FTU#mY}4cYJK;n@=Sey%LJ?H0kGe-(fKErOu#8lQ*=;PlOfBaNf9pt5UI6i;WE0I~UnBF?1i7NHS=f`ewOrNITuVAB+a{s(-Er2yyJ zevF_;>7GXv`>sQiSkGc4=T0yY*?@5W{#6^Pv>ET2Yg@EkwtvqmWDUH#sbod~LgC*s zR*~z!@-DyGOb#J?fZW9_cctS}bxoT--Pv(8^GsE8e{l~4YjpCr^a$USfIdDP&H-Hd zNag?__MXeo5+1z))F2io#PqsYdRnq=TFQGzdy9W>v!xM{XmA{s91W-6Ecr>ck;<4L zd)5q&DBWt5&F0S6TrxnHOPbK)6B&I%#6FD%6+GBZ-fdIq&#!v_j=ZEHWy@sfo|hVA zbN(b`+l{{ ziv7hJv$eaWIBlmd11^oBrs`M&J1AzYmVAhC0n5QrNW##Yo~zK}!UoMn>?K+Rb>;8A zGOj0)T9N%u;$xV}xthOLw#OI0^58Ls(keKk6RhzkD(|~#HMmXvn)2fYW9{XBeN5sj zf9o%oIMxWHg+jPZR#y`$(lX7BSEbl)B}IW7|Vx+6BQU z)wwqrpCBF%+}}_z0_tA!N|d+Oy*!DBT*9^I6@tdjdNu?FqP(l5eyXUdES)}FQDXi* zD#{I5Im0F=Hj26spYwv3>C_mae|2jj1ffK_z!zbyk{6J${n6x zFI^WBcVr&?n(%9D=Giz-=aazJ>Ayp{zw_chc*s(O%EM-5ewCM9K|}`KmoXQ441=?yUN!#Es5xy${HA zL`c@^F5@(8(gLG60fZHx-0V1K||Zvr|sx zQ)oFus|bt*goWHpf7CY@PxAe>&c=fKzMCVa3oh)1AkTDA)>*y-oJo~9^s#5r%6}yb zPfX|^KR~RyBpx`F_4s2kV`L0d{8@m`dIIO=aJPS-6BrvXP_K2>voxhvoByNj2C|RY zx+2pUoYKrs9UUznOdIMRd|Ki)`sBB~-{Chr#A*a>Y>k9Hf8O5`{JRWW5ssao{NV;GH;8vX_CX% z@DOulW~rjre~u;NQjg}Ag~;~oefAyWsA499?fg$@bt)$_jqBcsOVg4$hIRW1Yp;#p zH8?v;ji+VE$zlhN)!GL>&aWBu1rmlxrvX6EA)>-j7>5bykcj;lC0wZNHjYy)vt2Pf z6up<1r&--17pZbta2M{4{`^6z@|FXxuPb?IdWkO)f2sCqj4XPpQeD>qfsPN}9Xg3^ z_f9(@d!TU}{j4d-{))Y4&S0Rrq$cK5e6uXtXAZ0NVN$bkROKjwsGBy>YvhBhw-3F= zY5(bR06Tq^&s9!qN?wLv0BWpySbO1jEIiL&=d7&U56&tGJkPs})sIVTxJ5YCSeINc zIo$zwe>+==@oe8!0N#)&&2cEPB(iqpk)qpkG8{@Vgb^#YLkh{Wp`3F(X&3GOm(N!= z9wtS>*A^VP^E1<48XV_6{_j%d(e~tuhlK70`M$h&u~UgfVp^lpvejud#(mXy@Oc;+ zc|y%k!UI&jUuF^uI=mf*WLgt=6WICQTE>ZFe=8@v{EFWY1bO&l6qgfT2E5*RsU9`= z3l(n>xVqUmA}eCJoj1aY-nVZKd23gqS~Bv7+C}KCXYkh%fQLs9iqW6Ry$PXqFcJ3M zJE4lXQyV+}PSzOoyfVG2C1kJ8(ANJTa%ynwS=0CHsd(iwoSo#SWlBMxkv?(R^eBHm zf8Nf}Q5e~E)=N$nN2w*8{D}%H@xiHc{xK6qGEPJ z6(%WjR;lOUVuCYkr1(XkVXKYL`{5HZe<*x_!jz(4RK7{y{!3!@V|2bw%DJ=#fStnO za-Sq9mWn1{ot{b1vLY&W=oD2e`kOyhLtcRg__K=t@*Y=NsTW9Od+MOM6K(yLIaXhv z->Ec&U_{kmv7fs;W1U1-&uD6mzl!GjQ9;B=)TdMH;{eP0Z&pxf9E^74j2$F%f1{0g z!G0%15aFlSOMbSJ-q%7RR`!Azh}qjB36Q&=zB4HPxbP$XwAaHjb3~%tT8`7bT{4HU ziK`F^?xwXu`ctpS`B}y9<>zcdR6Rvo<(FYw+N?vXu5P#`U^XjzF#6K^nE#&=KelH& z#*$$omvwI`tQ)u&$M+X3`}qjCccIe?FIp{lZ>3 z=fL{GgVZOy3QOP+f2eL^3<>;OF@{_&b)cF_$501x@~G_5+7%%TA`Nxzr#2R;PQBZ+ zVgQN=5*;D606ys}^wsxMfB(eiH^}`}j$94e?4j6y=66B}uC=EmxYKTQn3^H_ukW4Ev@f-`V! zdRgU++GlQ(r0t!@)e3M<8z4}4Aq7Zm6yF@KmHuR|S=!(|?9Qe!=fmAMlm{ikGC%H- z>52zipj1Qe>{aQKXXefdTq4Q zr&+2POds395o;g!(rkr{&%=g1w^}pNQtpc;o{Hkszo(te0T$mn^teh?z%+bSXFJ<; zj9o*Ik|Lc<@v!ToUbkJ%R0>}sRbb5#p`9L!A^Q73@P%^svk;KOS6N2nGpem(ii_C} z`(XfUYCgz^=hPP~e^$b${x-Y4S8=JsdC?jHo21*42NSO{wdYrW*n4A(^3VtpOz`L$ zj8Uf7U~OsjnyiEgdmqPKJ*ZfxX6V5(x43y}H2a%@4_~TF$o_+zi!yilP%@)WJFxN~vVHs!afF)q~|;DuZn=z-C+gwYY}`a2J86^!5{aRkOJGndHxzZ%no_lLsoNsh^na9Tf=;SC!()~lZy6v8VQPj1F?YI1V zW1GFCj=<}5f6k}&A`5S?xfZ7GSJNtC03H|>u|=H3pVI$3W4c_qH`=x(x;>0qv2xxO zgeDvur7SU%gb>{I0C{1bicO#?|A;k(x~d$6bCWhh1NX3`4`bZ-gHgNIU!+@$qw6lF zPXcxdwy|w70-h+=-|k5)OVoAQvC6lKLh&=LMAGiZfB0Pa{n7IgmO;8?(yVWeZ4l8} zZK~h!IC!5mG-6C!FVIUw@%oG zpi-hifi3F5Zhz?YbG}lHrVBOJ(!Liz^Zd0^M8qh#*PAdIsISpksR^uQTv+HK;NE=XE#U5b6G0yfUaWOtUN#dIMb4#i^{rXdG0%jxs#pvfw zoOFI{Whn?Z)5pV`{8~vwp9BOYh{2#ke+QBhe?nxI3`w&bI8U=CNFTp;0UA={kk*PV z!TYAU?|#&I=UQW&XJKkQrxdHJx!c9gTe*nSe2J}w8}mt|>FW$SzD3_^W6Ja%`Ao&$ zZDvP+ImV>cQU=Ghj5bzR^q;cd0c<8yV{U$J(ZGz`UtvjQbZf`&IUyHSUmGkIJq`#= zf85@Bexw~7p+^r0o9Nt=^s#Y7+()8;Q;gBgj8oQdOSwd$^sVmWuGa17|5m^7LX|A8<>`)`Y}kw_r_`Qy12 z5|sQpYFoDY?WBZ+feuFCafa^iV7TP~e>9I|B4xP1vtX;JhnUr+&l|4!_$j>YI?6;) ztW~^v$OqmUe_eFz zlLtf)$|J-qUUSG7l1Pf}C9`PPx41bj@VDZfWi$_qw1g1oFM@OC@z)AI0%md)eZLrN zX5I7{1gW8m+a?QY<=XsknXSc5KM&qvm0zHQ#uemSsh_J1l;!oZUX^$Lk_w5Fc)0pR zGjb-%(h%DBMEjj11)fB)5$X4ff4$QuMiku`Z9zks22!QL!#yq^ha4zNcRZ*fetnXp zKVc1d-q9d&m||JHC$S^IkK&>mT$&{VKBBAp@{wFaUU6oo+-SGquq76wn3rokM+jer zsK59tr6J|D6PO4jn((SB-0hsLSx1VLZ>cEdul--f`=XEf@Q2Tic?;k`x5PEgGTq2K1kwY~0;-%}31DJ{Xj|L5f z0e52v;MMUy64d==_gg4?cnJt*=lG{_LlnnRN#F_Mm}5j&edI@6uEjB3XjGmOXaBrPRL z-2EXRKv$IRHr*gDfAuszN}rwmS(=W;6fXD+q}(x_HTB~+?~N#0^UdEHYJnMI5cyA` ztYai8J9Xo&=4@?`ZHa^wTF<#Z;lJ_tS?RI^T+zad=p?xkbxl8bN=%>roZt7SWJ2o!E;zIX1N^Z(Dkd-(cqjDar8~a~zO2VfJap;5 zRM93iywGGLB?-~t>!8Y{7l3lBYQvHUE#WcM=r4#ff5@CmQMqy73`cKY+tm?BnuKYdWGeF&AM+4h5aq!^oDq_ysY*|N?~+<{U|{S{<6jLr3;VjZ(k4(R2mFy z*=<3%eJLv;$%scHG!+e=R~6Q=D5}R&lRm>r-u`zpHOzVc0n+wc^6H~|E2DxcUaKMCecRbEoC(^HCORBD>bP}{rp?C0H z*hVdeQ`_HJ>={OA$heN!sH?KR!Ig*RtV6%9e@w)_RUWy3EnB3Ia8K_Z3mHgwIUsvQ z$x4@XI{DTDixhw|6)*yVe7Vz&Peg+4hkwQc=zO4Re z@)-W?6<e_|OPp(M2WZgzyQ85U3oLL(d`|EVozXLAR=k}{^!vrPY}Uhhn?_M%2r(a(u)<^U=ng8B>`BxKk<3z0$Li}f z2SfM)g1^V^K#d-)&R?7$lCv+K&j>LdnkoVK)r3rcSzv+b=sTpwumRB-!=99H{m2RJ zWnDjn$2(oLwN0`)ej}AJ!)c|me_mi6g{($0MYxE1NlgMJF2%?8*t6HD=2x4DOecl= z418T^^q_~I)S{un$Xx$GSxanNDB5jyap((q7PF1n67OQ#e1_0{vrvAn*-JOMF}XvV zE-;WaZC+Vlf3g(cVC`E6(bFARlv{Wp;^1gIwc=IV-eVL*SP4ET?o0P1e@5Gec}ci0 z_CaHvnG3@J?MHxma<@Weh2IHYviulJgQ*Tcv$y=(dQax(H_iIAb$`Rl9{GtOK@0kc zuJ$_nb11R4_*W>BRbc-joZ#47FO`MImnG5kPnXSJMC0?5^MStvdxdxn0~uN{@k9Gt z6IpbVxzirCcZZt!rAGkQTWWkKi3z>>U^i3TyFWLBVR;i<2n6qKgV;%E` zLzK}S|JSchia=(Nb<7mKRmgZGMsUmUleXs{FYowQSb&JMaWI2O&(p64uv&+iwm2ew9R$Ljka`+AAg zpZMo&a^tPbxb+OH3mM7@4X6hf`WU8{bY2s}BN5^037cyq*r$kB|6%js6(=J}@Th)H zE?JSny@NinsxwZMYO%#E#G+uX!DS<8#~L3X6rT0I9ZXc=e>DhXd=_D?dg5WHG-etM zXQjx*_7bA(DnpN~`_lql0~&uzh)KXCk-3Bw1&fC(xxOzC%YcpRmV8HNjkLZ{KvV;K zv>V#=Xm(-{SChO)8jaZeWDy!8TXfmwW~9OBZKw^RqV#Ay;ZRSSr=(&9>HBt@%zwbc zz1Hy9xPyx^f4P+u-TWv7#Tq$@gCU&0z|G^!Nho6u`XPp!vsrktdi+WYVTeLA-5K%y z!nrGdVfRLEb4Jm3Z;PBaWDfMbpr2Rw?e>9?oEk7L8}2xV>sh02Tv6gK8nP2NqXphO+*YCp+Q9qi!w6g)a(Gv zcgS-0f5(tFUCx6n#h-WEjE)PMY#pV~^7#*4Ch`hkTj?#_T9;2kdj)s?hJS@4xZo~O znc^;39R8Yctx!0X-(BQQWLMwGXEkrY81#L|=bu4nSh?ZZ+M^|~Iw}8%CXY(^PjEwU2Nm1MKP=Vl1n^Jwj=WHF ze-=9KBbv73A&4X<8~9H|U-7N68XEG38*nBfD9t7d_$f)iFT~l4q>1?A?K??1nxV4@Q5m{Qx&cdskvil{ zHYn_h;NH!*vS`8mTG~0kL5z+qpg}MJf1-e5fL@S;@bx_nSATt}LD15>#eGS1Wn($0 z!YKbj9sv5B5lm4SnkaIE9`Pj!FhU}AHh|P&1CW;!Jf6SdB#wUE?yYu|Rj7`D1$2{V zkVJ3cMw;l=c^E)Y&21dY#X<2SBh^U-`Q0o)c_opx>!|bdQapw0?4{vfuW@{pmDVz! zjkzaC@y9j#-2i43Y8P+*+CE{2K(VeD4wM9zPiz9*2~%!or)IEHUG-}U99Hg2_g5xee|?f@F=_f+ ziR8Vj4PGgJRH@Ym_SE!*=LtMW+i=yVcbDEMv1AWUl476PyGh-oBSMk_JFgMIGl-u=Z@aw*OO9G z18akNjxMQ}NF&*6l{1w?f5mkz8mCnIZxyDM%q+L$`P&=kvPVmb;*h6cFy@pEJ=L1y zXO_VGtOp7xy?TXzdS_}{z1)|VDHuCRT{u|CVLRJxb|Exfnad~sxLnM?90|wPVP3bo zC;I)7waXN1)$0kG?_R7Hk$p^m`+a3mScL-C{;A+Wgj+T5cm;f8f2Zq^ADJT9$_pN) zUO^kB?smpebYj!r91}Lp#UwhyP4V(;sm^oTBca3q_KhaaxR^3XIV+9a+kf-kkQ_lX*wfhNG>wQtA!72g4xVFx$WKFJ+@<)YfoqUY5rI-L1PW9tF8C4#wht0b) zD6IeHVfUiKqfI4xVLQltW4WK47%ggR!vp82&2qZg_?X%Te*!^M%tajSl8H=e5A9p? zolZJK;y&PN#)LD_&ocsWaM+_`l32a9B-PD8JbUw-fX6euy8 zlN?8%&+F|2773(K?6x=L0zSRa-Awo~Da`QwWmh}Mvf6izC>+QfaGagF>A+piWj{pL zEwlo6rEHZWe@j2w&et%O7t^A2#Xc*I-A~4MwWL!RP0t@#mO@&rokFh7ZE5k)eg3rf zrI};y23%z~mo3)>e=mQuGt)nS#sET>{QRUH%&YiBy%WF5nbhewB8JS*0Kqnr8hx|k5!?P63<^E6m10a4GpxF-Jxe`YSxlJ?FB1ycXpvFobok$KIU zY#Mc~90IJ^TY1yOcyQMph5li}$d~R6+tqx99R<5ZZI++=$hZcOzpuJY`H@5>J-3E~ zAVq4p#H_7d~0l9W%my`Cyul4{n_Tk^3A36S0sginiq7xLw!-H{jN z?EKC|e>K3ESF4`DSHrbsae-u3a2wVno5l|EQJf7RlX0H%wvOTgiaD7vF2)?WASSZYYs ztdM`0L1arC4^&g!<2o95vMubNdFX}F1RA<0;Vs1OWJ?y98PM+Xz$Cu-T^sHX#w6zw zf9sNrtj~GiX`k+czKh$b+?cj9HTcVSw6Z)_wKAfZq$42=mB{p4*w#OO+{Y@+p5nZm z^}UJrrt55GVL|5s{GS(yklw`?9FcSp8zzV$bEyc6?SCOI)P^_Up`CWRUXJ~8%-G*X z5H2vy^2y}^tn{gL-s4wEELHi;4HJ}2f5erK8|lhscIl(`KhGZGn-T@Nwni&VG>0Z~!$;aUXuDri#0a z;=Wiq%e){Uj|*3474LFk#J}hTn{iac8-D*LU_+L`UbzNl;yMVp+{n<&XCfCbf7-av znnPY(Vf_cZ~J?d3|XUyZ!is~9@%I#PeK&6U9gDXK*hLS)q>VRD)kF7E(A zHhB6)@KIH@VRf8g0U=wK6#_A8e{wFPjovklE@Tyr&O3i4YQ+i-rcDG#w)>=75h^xy zqov<)?k~(;(}U4x5ZEV4=nZL(yT96-*relE*Ms`5O2Ufo%dPQX6te^Br+gtd4X zZxb|T&Hd8^y~-V zUqCvQY#Zd?xrU!Z-nj&*`eo7P<-ce?2Y%tdu^Uy5Qu}Q)`P>?Ex?}n|7j%X#x7D&V z_Fl^IcUiiXWp)~x6D#F$fB$W%b2=Q}mrV%!zN1iZ>MV=#$Lj=!?hNRgXfP(_U97CU zb0UA-R6<+TI+A0i!4T;im<2PaSfeQtr_J||sw3?dQg(+-zMu(-~9sp2$r~#8F6t)CX6gDL5G07W0Z5osZTue1M0DBles3xlY zv5YBNa0lTarHTbUf7vwQ%yjW&!7@3*4BbhK#d-fsz}v9TFU`n>*6|KCbt@QbD|Qq0tP&9@%xW zs2!pko2#zm7FA*^^mnde#4$NPeySWc^hmHHl#s-EYp>FYtiYK5kd*scV=kkoF4%{O zZ;AM3&?p`)e?7>`Zr2kqC}&qeLqP5xj02IDiG3stkEqa*Wr31iRr-8of4GuuxP*{oiMEsQsG+6d>q%+3;x=5u9)kV2ooi?@V%&7Wc6fWaA}UXURX~@5tH_bMAnLm-#k$^63lB?ZYIwgndtI`}ES=9q`pEQS+|F3{G4k&{mpiYq=}MA6gJeAjn7Z zCjFg*_$bdND<;!10slOd(T5ev`Gp?e})X^ip?V3({|%$W($GDSMaCiETz_(2hV=Y zK);0tQbScqE60E|-Q~LCnTRhgGL|YxoL=jM8Q&2rv)hqg0&U^2%NqU25|`E=SFf1E zw>xygg{N=Deu^*5Y5SlS?d2C>oPTT6^Da8e0vXC@mhg{-{G4dN~G)me}x*< zC`6S(acCn%#~ff61Xv1YhptRjAuun`tBs>f{tMj}rXVdweN*$iTaME4@%V&Q0@{=k zf=Lg7i^^H@?f8V@PI>9Q|LH=9qY~F?B)clu;*x!F@@$>V3 zKO)d4(_pBa*XQt?P(|>Vn_pz!d0FA}`nz1yty7@w*#h#v`uesqc}(@w(-W@ywFyiU z0b7#2VIew{T}6XtmS-?Ak{XR_?}&D0Bq)XqM-j75#x5~i=+%+ASRy(*f1x#Ri&nV| z@~yQU;rkVP-|V*l;qUE&p&3u#*8{gOKw}pJygtG)Kez{ZRYYwkwHU^2NA$v z=A$kpJV+$O9N7%Y(Q~IfQXL%nJt~c7%1SNB-u&uUWsW?y`-MQVYy2H1*1^@QPM0Pt zae9+$FMBBoleCbNHe%1we|Myg&}M|<>9e>cSaOA<6HxKc(q3{D^ryEw^tXmf?1d@1 z7_J*>4GUfKCrJEH=CXP1>&0okQEU(!u;&!vv-#q`CZF<5?WOMRe62!#X+Fp1@NIW? zZx9Q3!Sk9f;^j1{Nef{FPl>6rZecg$-QyDy5b=w3aIj<#gZ+3`fA_w4az_4a#*jCf zo~%Z1fJqWot)9K6Qb5gWg4ojY@E(l6Ef(U+^RndKr;Ip!LZ@{_p;qI_Qoe?FL^9`9 zls3hc&NU28bMC9gl~Q-vix2^J$}{=KBr#k1K?aEL=M6%gd>7<#Oa0myf_z`1Z^x*# z<5gaPtjCf0&GY`|+YRD1^x&S+1(wD=ne1xs3)MLiYt5w8dlJf8%bEjuqxq%r@KlqN$DZ zCK%9PCCwHuhA~epMB|X#J3W*EBEAfXmke*x3Q3#qF^0U9aFkC1adi9#cKJwkS`0!qN%I|!3rv6E{5M`f(v6i)p;F(+>^-6?Wv%=P>S^T#u()B)b7m@c)rWlj1c(n0H8MM zu6?buEzzP%&?0A9az-g7dYy%ckJu;X{uT`9e`VsDQ(?NRsjMu8rO-XKUT(N0mMU?J zehuu@S|{crZ25%9z?u-1Ra<8m>GzOr>9UjC069 zuma9(6mvWf7lL_%E3(wU*4QX{_4BOJjb5hmpHkFaR%K+oB~9ETJ*|Q*+j#0+b;DpO ze-cS^_;Z-uTgsh~vqFy-eVwe=zx@(HfV_E6OPb($v-@T1bbT%wuInk3*4L)RLrkwE z1*tmk%AzZPfX^dlPhBU90GWlsvFKU*e_rmDx@As;r@kB$RMGFUz{iC_-6}0u`X(xp zy6s{jsvOCTO&X;r_UG8>exo_6DnUV{xTPbXsB3gj^3Yd0D|zq4wxMb$zM)&<%*@lJ zQGIQ1-V{R}{ilLs)&QPdlb8W#{P=wWg=>iw*CTs!;(*4uis#uMs5gkxYyqP7fA{EZ z6(*o7VKKg4k~uY)%&U5dS2=bM>0y{9&kG8Uxo8=XBGVWD;j7vLc8 zX9PW^&X$328CIicgUxD`fU?)@e=r9g#*#ixx0DgjlEyCG3cBa(E-N*^Ac10^+@j~; zY0Q~>aoj?aTXzwzAYm<&E3t-Xi0;RA2Bh%m4z#5inE}vFuTGDC6GxP;YSeKFDa1yn zTFJ@rEiFmdU#S3$Fl}WF~{$Po0s^hbUl}k-YL6;hbe{TWiPwXqy zlGm<-wJHC+q4&r;*7GsjB9@G@Um_G_I!f?=B)$hnr+Q}hbn~#l<>C{f(F4Qi=Uq!& z5-%C2*RTf0`pQHomQdGQ^vgiY*iiYyd|rXAYoXejk+6`566UAO0aYX-nA#`qdMnr);wb6isjw-2RHr&<#A}Uc+bP>q=hr(S+0@P@xy$z*o@N=XWENMP zEd4cX#&XtiwwXSx`3IQ*j+$n|y!R`REni0?*%$D|XMc zYBtQk_toEeXHI+e$DhaFMTF69#p z&J!lqJ$dm9f8!uh!ShkHjkIwXE95JuBpJ;?3w~;77R#|M;#AkoS0>>ZO&B`!wh>bD zjk1P>rNU3w@HSl~5EpsIg7pfrn%480g0#I6$5F+A2k<=h`@;IQ7(2@|&=x$* zc*|q;p}Iloc-2`C@-$K3)&@7ECRA;E$GD%~ zoOJIwe=<6i6tVYz5HHp^3VFXnztC-mv%m`<2ar-{Imrd2L_T@xlHGQE`6h zvQVqKqg40~y7pW9%#}hVn$?eK|1FZ>DHQZWp?g9ms5M zn!<)U^wT#Rk$PgiF>VGGBMm+gBurprJ`Bxwe_a<8oa;7GzoDSj$)GI3Jz42NWa+JU zwmYk)ST&k5`yDE}%28j6=smW0z0>0`#wGqW!?xh&))WtI;hD#2K>x0`pR~gErR5B= zV#6S`h@7Y(3ATxa-3?#e$&jGx*-w@%B|4RGm5qS7-C!~w-ZYpZ{Q+*5aHZcug@8lY zf4ydWB5115)m9`V+NMZtQ8)kB+!-iv#w;o5N*-%VCr#xHVA*7RjkAN|F824WmIZzy!wRE!jd~RFXw&|PZKu31;Z>Hc4KYQ3KH+L zBmCMhh7_IeT3-S?1Wo;*zYHxrys?}(>v@ePv*vV#Y)Z8m*20TqHN2gm%x;j)f86k8 zh&T&5KWb5{d*4z1+)!^?-8XcFT{u}t`=-u_H=fIzK!Q(n=yFx-&S+m`kvNV(6a!O4Zn{+cH zHf+K*>B}K~K2E%sA&rH^of;1vF2(r44+qQrs@SCbcCyW-TS{3&yy~xqa!A!BY-ndM zxPJacir7Z5$c#;q&|pGZ>k^V> z{Fv1AYKy}zlRMQU!DLj5w~oIS}2CQHv-H(XoaR09I*p+YTI(c9CDAm}!Sgx8CyaG^fml zjF?Zv)l{?bSP;CSoeP%c?d_zha&xt^kH5x}jEQLzZQ4S$td_h|Aa43!(fWz(;Njs~ z`6LRwo)`r&s@mXVw|(-3T?<@}XB%I!A|ds@mA;v%D8h3;=f@~4mPocp)Q}DiC6yd% z%Y#^-!@hlK_Bu4oF(zlViPOs7Pym;tde#Y{=D1UwE4x>yM2T9$d%cF zH(aYn+C|TqzzmmRA-zNwfb_`gW)oO@YVklUi$0QHZD zE4eGSPFtsU9N<%abZ+z1;15=8*&S_{oyPku{=CqXG5KK7&Wmg3DL01{53W(!faf!x zdH)ez6EJ!Hjm|z%vG2~w{72SXch8>LFn5dN8RNf;LzfKbed2m}$6n!11@|78e%3l* z+)LZ9-FPF{nAC4FZuIqwOX)l$YJFy@`F7xrFXw)rkbkj-YU;4|{)6uACfwNT zw4&%qqPSw=U(PG5>{oW%`e48Bggx?qK8?73PhAmW96vb4=5dFl)rS` zHDkNsW$~N$WnDIgrT9yicIDo`R(7Q_VVC=aV;gpsocrf*3EBbkqpl3rldIPH)lK@!Wc<*#c*(md*S(!@?W~IJzG!~s>~20k z^t(`y8mxRatT4RY;Z4tS$_kRoy1m@u6WGPaIH$bzX6GY!TW4iV3xaQxd45pTxEu23 zHC>)$Bt42uE*Gvl7A)%XZL@0;_fyq9Ur1#|M}IveoPX%+;dv_bZhlSI)dhbv-8RJT ze0j*2!{#944zYOsLywA}S9dr4UcGlz%#UFs*M7cg@}YU>hVGVX9jo(4w2iA=>{P7G z?i&4Y#ihI34__m@Cyd$GHD_kaf}PvvXWrjXW4!K|8J_&J+vHx$LRyFYv+0LpT1}5S zZH`p0+!s5Y4d1wO@K!c=-hhPA_w5fSJ-OpKuzlN#BR8ws%vx$A7RRV}j^y0^>`duyZc{^of zu6aU`*XAX!=D!%;Y~J^KbDP!9pLfIm@spxe6Y@7YN3T{l*9K27PBG4YwQwaFPJG+f zdMwSF`)s6g@TbC{jV(4-eo;BMc-6JGw=Q;l=YC*>V9QS17F_1mUiaI4{Gga?Vk^tk@%uj zY1MZV4s?35@bf#{5A5E)`spQRLumMWJD#4d{i^iQqtPcGo}O2!1l-*Dyv3lFP1@Ve zUNpNHK9n)ISTpJ*~6usDWa!A zHvj11!b^F=PcEiDCTAaWkB?kZCDXQS_{wh!T-x(Ck|`$BD4M$;bTMaNEmJq`Q3Yy`_cOj)B1$?r~{mXtm*B`L$RM@&je+LW2`sncST zJbT0^#ZQh;PB%3lV+d&>Ns=f1C5obH^cX|1Iy5x#N5=8Mvk`ZGYZsC<<3Wl0fDbz4 zWbH@_^xV00Y-G|+Ip_JalH`j&IJU0#?tO3I&qZ0u2TqNXm+mp4b}@%a zGCFxjj(_y|`TXV2j(a%IxUwWQ`GtEQKf5!Z{yVN@V)oU%mQ4b_{5@*dvi#L!Yo}FC z+87o4{Ak-OJN1`6c8k2SYR?|KIBUR!E$L;WwtQFoU|`L~zl!=dO$%~J-5WReh|goY z@Q0n_7EUef?)LMUE9!>Q;ml(55WhWL{u}+T6@GpToaF=kS_d`HU;SCX_6uB_^>WQz zzoX9@-|Ckpu2XXiZhwrbeQ;`pbGL}FQ8T)KCx21((Q#M@S4%{vPWeLIm1<9zd6A}pupVmjz(^fz6tHTb?Q zDKdOiiNh1a0vqe!P0OAds_Wt0I)lBlEytQ*I&V5?Sp65=S{fVMhncEd8NaC?4}C*mx!j4>qgo9`v_xpM^l2At86x98gtmZ>5=jnRC4 zl9&o^8VzRS4dX|B^UBkmt!cN)%eAj$D{|)Rqg*4!hHaF3ZRbV^)MOnSVhZ%|K`VOfS_>rG56*10Qgk|KFB^oM7%rvv;!h$M@= zWV*Y~-CJc9hTyL%91*k_%P@k#B8*59qi8UgoL3YPW2~ZReSn=nEPmBS%VIf>5FQT} zMDjO-6;5X-5gB2G5fzLvf+RNz2lWpTVPrJ!m5FWCO)2^EEkhSO>V1XRNY7fkUi8#GEhJ&j`)2QKsft{#AtP#jD zye|Ai;PrMqCuiOLXx;YD5>1;AtuhgAU95H*7#mEq%68uO$jy+x7Hg<4{Hlruyi zq9nooEn^yLj=(X%iWpPiKs6XRmI={eKxW#p)Q&~`OrS))-mv=Gu^@3G&T1KUheHjl zrz>YN(SXeok-$c)ZOgA+;8IR-LA#08pH#B>Yu z!CllihT;TEgt3N-f*nX_JfY0<+6cl}Ab%YuH$FPGUTG_Y*JeKq zh8m#_7a=mlA5SPlIv_jH;ZOv%3#8f{^KsYCDs41okAxk6?FNR`>MPV{Y z)Gd$_4c!Qhe?#~oJ47VxAp=1U;oSj-goVWphZ@F08lot0ye2WJe-P)4f-{&3c7j6) z7^lr@D(nSRjwuFJ0y!21ti!3uQCUWt=@#XqtLLSnni38E!4RIQ=sE$0A9>Uc6rgr@ z^u1IsrCx7@Vt9cR!!?4+8C62(NmC0|J9yIof1~rH7*aVFJDn3KJAX5_p}fD=e=t~t zGJ$r-@<8f(4C#3SFGLC79KaOJ0URs9yT9>#p#R|22!gpWXvMJZr>{#SxnL|0ZjCbwt;MNU>1JIUZ7z>IEM-ZOsNW55{@A!Js zC%r(l`i~moJ_^OSzZnd&741%frvP5G1UFlgaI}}8P|}BA@O!=f15n0|8EU92L=+Qn za?w5tzMh~bF`02P5MhJk`W~0cL6bliF2Hm<1`H`<0%Jivq9}l>!_6Pi!0_VJ+R;V? zJWOc)c|*Yz#3dCl87Uvo3K9rHlYax1{y&+OvK3wPhN|Lu*AQi z0#XoDD`2_`2pG@>aw75qrdyD#iY^zRVbQ3GXw`qTi-9Q3p2yMqP;PE5g4;&84kdsJdgp^7sA!aM0#Lu+2{bYh!%;hYWdW0|R}uFAI{fgs)9p?G zw#5@d`-H)Z0SqTAv{_^<-Jx$wz$4{6t6%UB`WaFkhYOlqxY`M@6fD=EvjOdsMibKc zL^x4Ix4=ArV>>}sb%_KFj0p)EB|82FOvdUKx*Y;8+kmkgULdrp>mR9a^dEFK6x}&N zV070B9>=<@222-z`iRC+RiMwJi308aDbVcDfbj5v2P9@f+ET%EOEJ`HrDG)=RT0Vy zPGD%qNW6-!4uH79029)FsrKwd=n-I&0*r5bx9QauslIA7Ha#t7Vp4pXL$6+*J;Enu z#+%L@boU*{C^38-QR1Mr9TyMU3(`?i#>ug Date: Thu, 24 Mar 2022 14:13:30 -0400 Subject: [PATCH 103/116] update printing --- gtsam/linear/GaussianConditional.cpp | 4 ++-- gtsam/linear/GaussianConditional.h | 4 ++-- gtsam/linear/tests/testGaussianConditional.cpp | 10 ++++++---- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/gtsam/linear/GaussianConditional.cpp b/gtsam/linear/GaussianConditional.cpp index 8d616443a..c44ab246b 100644 --- a/gtsam/linear/GaussianConditional.cpp +++ b/gtsam/linear/GaussianConditional.cpp @@ -89,7 +89,7 @@ namespace gtsam { /* ************************************************************************ */ void GaussianConditional::print(const string &s, const KeyFormatter& formatter) const { - cout << s << "Conditional density ["; + cout << s << " p("; for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { cout << (boost::format("%1%")%(formatter(*it))).str() << " "; } @@ -97,7 +97,7 @@ namespace gtsam { for (const_iterator it = beginParents(); it != endParents(); ++it) { cout << " " << (boost::format("%1%")%(formatter(*it))).str(); } - cout << "]" << endl; + cout << ")" << endl; cout << formatMatrixIndented(" R = ", R()) << endl; for (const_iterator it = beginParents() ; it != endParents() ; ++it) { cout << formatMatrixIndented((boost::format(" S[%1%] = ")%(formatter(*it))).str(), getA(it)) diff --git a/gtsam/linear/GaussianConditional.h b/gtsam/linear/GaussianConditional.h index e8aae4c31..6dd278536 100644 --- a/gtsam/linear/GaussianConditional.h +++ b/gtsam/linear/GaussianConditional.h @@ -109,8 +109,8 @@ namespace gtsam { /// @{ /** print */ - void print(const std::string& = "", const KeyFormatter& formatter = - DefaultKeyFormatter) const override; + void print(const std::string& = "GaussianConditional", + const KeyFormatter& formatter = DefaultKeyFormatter) const override; /** equals function */ bool equals(const GaussianFactor&cg, double tol = 1e-9) const override; diff --git a/gtsam/linear/tests/testGaussianConditional.cpp b/gtsam/linear/tests/testGaussianConditional.cpp index 52771960a..4a9515207 100644 --- a/gtsam/linear/tests/testGaussianConditional.cpp +++ b/gtsam/linear/tests/testGaussianConditional.cpp @@ -404,25 +404,27 @@ TEST(GaussianConditional, Print) { const Vector2 b(20, 40); const double sigma = 3; + std::string s = "GaussianConditional"; + auto conditional = GaussianConditional::FromMeanAndStddev(X(0), A1, X(1), b, sigma); // Test printing for single parent. std::string expected = - "Conditional density [x0 | x1]\n" + "GaussianConditional p(x0 | x1)\n" " R = [ 1 0 ]\n" " [ 0 1 ]\n" " S[x1] = [ -1 -2 ]\n" " [ -3 -4 ]\n" " d = [ 20 40 ]\n" "isotropic dim=2 sigma=3\n"; - EXPECT(assert_print_equal(expected, conditional)); + EXPECT(assert_print_equal(expected, conditional, s)); // Test printing for multiple parents. auto conditional2 = GaussianConditional::FromMeanAndStddev(X(0), A1, Y(0), A2, Y(1), b, sigma); std::string expected2 = - "Conditional density [x0 | y0 y1]\n" + "GaussianConditional p(x0 | y0 y1)\n" " R = [ 1 0 ]\n" " [ 0 1 ]\n" " S[y0] = [ -1 -2 ]\n" @@ -431,7 +433,7 @@ TEST(GaussianConditional, Print) { " [ -7 -8 ]\n" " d = [ 20 40 ]\n" "isotropic dim=2 sigma=3\n"; - EXPECT(assert_print_equal(expected2, conditional2)); + EXPECT(assert_print_equal(expected2, conditional2, s)); } /* ************************************************************************* */ From 3c62ab77de142229b10ec137515120b3e346a6fc Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 14:18:43 -0400 Subject: [PATCH 104/116] remove redundancy in enumerate --- gtsam/discrete/DecisionTreeFactor.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/gtsam/discrete/DecisionTreeFactor.cpp b/gtsam/discrete/DecisionTreeFactor.cpp index ef4cc48f6..e95b8fe37 100644 --- a/gtsam/discrete/DecisionTreeFactor.cpp +++ b/gtsam/discrete/DecisionTreeFactor.cpp @@ -156,10 +156,7 @@ namespace gtsam { std::vector> DecisionTreeFactor::enumerate() const { // Get all possible assignments - std::vector> pairs; - for (auto& key : keys()) { - pairs.emplace_back(key, cardinalities_.at(key)); - } + std::vector> pairs = discreteKeys(); // Reverse to make cartesian product output a more natural ordering. std::vector> rpairs(pairs.rbegin(), pairs.rend()); const auto assignments = DiscreteValues::CartesianProduct(rpairs); From d5cc4554db9b96c78bce58d37d643cb5caa0ad01 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 14:35:50 -0400 Subject: [PATCH 105/116] add new nrLeaves method for DecisionTree --- gtsam/discrete/DecisionTree-inl.h | 16 +++++++++++++--- gtsam/discrete/DecisionTree.h | 3 +++ 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index 0ebfc86bc..b6e548297 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -635,11 +635,13 @@ namespace gtsam { std::function Y_of_X) const { using LY = DecisionTree; - // ugliness below because apparently we can't have templated virtual - // functions If leaf, apply unary conversion "op" and create a unique leaf + // Ugliness below because apparently we can't have templated virtual + // functions. + // If leaf, apply unary conversion "op" and create a unique leaf. using MXLeaf = typename DecisionTree::Leaf; - if (auto leaf = boost::dynamic_pointer_cast(f)) + if (auto leaf = boost::dynamic_pointer_cast(f)) { return NodePtr(new Leaf(Y_of_X(leaf->constant()))); + } // Check if Choice using MXChoice = typename DecisionTree::Choice; @@ -727,6 +729,14 @@ namespace gtsam { visit(root_); } + /****************************************************************************/ + template + size_t DecisionTree::nrLeaves() const { + size_t total = 0; + visit([&total](const Y& node) { total += 1; }); + return total; + } + /****************************************************************************/ // fold is just done with a visit template diff --git a/gtsam/discrete/DecisionTree.h b/gtsam/discrete/DecisionTree.h index 13ff0a8c6..c0a2a7a1c 100644 --- a/gtsam/discrete/DecisionTree.h +++ b/gtsam/discrete/DecisionTree.h @@ -262,6 +262,9 @@ namespace gtsam { template void visitWith(Func f) const; + /// Return the number of leaves in the tree. + size_t nrLeaves() const; + /** * @brief Fold a binary function over the tree, returning accumulator. * From 9ed73270f69306d532449f59d0be16eb155ee74c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 16:28:34 -0400 Subject: [PATCH 106/116] update to use pip for installation and install to user directory by default --- python/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 85ddc7b6d..f5869b145 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -172,7 +172,7 @@ endif() # Add custom target so we can install with `make python-install` set(GTSAM_PYTHON_INSTALL_TARGET python-install) add_custom_target(${GTSAM_PYTHON_INSTALL_TARGET} - COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_PYTHON_BUILD_DIRECTORY}/setup.py install + COMMAND ${PYTHON_EXECUTABLE} -m pip install --user . DEPENDS ${GTSAM_PYTHON_DEPENDENCIES} WORKING_DIRECTORY ${GTSAM_PYTHON_BUILD_DIRECTORY}) From 96c541b9970f9489e6ebb847ede6cf96c9c3da02 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 21:05:04 -0400 Subject: [PATCH 107/116] new method and wrapping for getNewFactorsIndices --- gtsam/nonlinear/ISAM2Result.h | 1 + gtsam/nonlinear/nonlinear.i | 1 + 2 files changed, 2 insertions(+) diff --git a/gtsam/nonlinear/ISAM2Result.h b/gtsam/nonlinear/ISAM2Result.h index b249af5c5..be91f17e2 100644 --- a/gtsam/nonlinear/ISAM2Result.h +++ b/gtsam/nonlinear/ISAM2Result.h @@ -175,6 +175,7 @@ struct ISAM2Result { /** Getters and Setters */ size_t getVariablesRelinearized() const { return variablesRelinearized; } size_t getVariablesReeliminated() const { return variablesReeliminated; } + FactorIndices getNewFactorsIndices() const { return newFactorsIndices; } size_t getCliques() const { return cliques; } double getErrorBefore() const { return errorBefore ? *errorBefore : std::nan(""); } double getErrorAfter() const { return errorAfter ? *errorAfter : std::nan(""); } diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 800208c33..326b84d16 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -682,6 +682,7 @@ class ISAM2Result { /** Getters and Setters for all properties */ size_t getVariablesRelinearized() const; size_t getVariablesReeliminated() const; + FactorIndices getNewFactorsIndices() const; size_t getCliques() const; double getErrorBefore() const; double getErrorAfter() const; From 173919229f7f9931f886a77ffda98ac3b057e2ec Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 21:05:14 -0400 Subject: [PATCH 108/116] wrap measured and add tests --- gtsam/sam/sam.i | 7 +++++ python/gtsam/tests/test_sam.py | 55 ++++++++++++++++++++++++++++++++++ 2 files changed, 62 insertions(+) create mode 100644 python/gtsam/tests/test_sam.py diff --git a/gtsam/sam/sam.i b/gtsam/sam/sam.i index 7ba401f1e..90c319ede 100644 --- a/gtsam/sam/sam.i +++ b/gtsam/sam/sam.i @@ -20,6 +20,8 @@ virtual class RangeFactor : gtsam::NoiseModelFactor { // enabling serialization functionality void serialize() const; + + const double measured() const; }; // between points: @@ -54,6 +56,9 @@ virtual class RangeFactorWithTransform : gtsam::NoiseModelFactor { // enabling serialization functionality void serialize() const; + + // Use `double` instead of template since that is all we need. + const double measured() const; }; typedef gtsam::RangeFactorWithTransform @@ -73,6 +78,8 @@ virtual class BearingFactor : gtsam::NoiseModelFactor { // enabling serialization functionality void serialize() const; + + const BEARING& measured() const; }; typedef gtsam::BearingFactor diff --git a/python/gtsam/tests/test_sam.py b/python/gtsam/tests/test_sam.py new file mode 100644 index 000000000..e01b9c1d1 --- /dev/null +++ b/python/gtsam/tests/test_sam.py @@ -0,0 +1,55 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Basis unit tests. +Author: Frank Dellaert & Varun Agrawal (Python) +""" +import unittest + +import gtsam +from gtsam.utils.test_case import GtsamTestCase + + +class TestSam(GtsamTestCase): + """ + Tests python binding for classes/functions in `sam.i`. + """ + def test_RangeFactor2D(self): + """ + Test that `measured` works as expected for RangeFactor2D. + """ + measurement = 10.0 + factor = gtsam.RangeFactor2D(1, 2, measurement, + gtsam.noiseModel.Isotropic.Sigma(1, 1)) + self.assertEqual(measurement, factor.measured()) + + def test_BearingFactor2D(self): + """ + Test that `measured` works as expected for BearingFactor2D. + """ + measurement = gtsam.Rot2(.3) + factor = gtsam.BearingFactor2D(1, 2, measurement, + gtsam.noiseModel.Isotropic.Sigma(1, 1)) + self.gtsamAssertEquals(measurement, factor.measured()) + + def test_BearingRangeFactor2D(self): + """ + Test that `measured` works as expected for BearingRangeFactor2D. + """ + range_measurement = 10.0 + bearing_measurement = gtsam.Rot2(0.3) + factor = gtsam.BearingRangeFactor2D( + 1, 2, bearing_measurement, range_measurement, + gtsam.noiseModel.Isotropic.Sigma(2, 1)) + measurement = factor.measured() + + self.assertEqual(range_measurement, measurement.range()) + self.gtsamAssertEquals(bearing_measurement, measurement.bearing()) + + +if __name__ == "__main__": + unittest.main() From 1f494fd1bd7382dea45f82ff58b93717f8a20c1d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 24 Mar 2022 21:05:27 -0400 Subject: [PATCH 109/116] update test for ISAM --- python/gtsam/tests/test_VisualISAMExample.py | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/python/gtsam/tests/test_VisualISAMExample.py b/python/gtsam/tests/test_VisualISAMExample.py index 6eb05eeee..ebc77e2e3 100644 --- a/python/gtsam/tests/test_VisualISAMExample.py +++ b/python/gtsam/tests/test_VisualISAMExample.py @@ -10,9 +10,6 @@ Author: Frank Dellaert & Duy Nguyen Ta (Python) """ import unittest -import numpy as np - -import gtsam import gtsam.utils.visual_data_generator as generator import gtsam.utils.visual_isam as visual_isam from gtsam import symbol @@ -20,8 +17,9 @@ from gtsam.utils.test_case import GtsamTestCase class TestVisualISAMExample(GtsamTestCase): - + """Test class for ISAM2 with visual landmarks.""" def test_VisualISAMExample(self): + """Test to see if ISAM works as expected for a simple visual SLAM example.""" # Data Options options = generator.Options() options.triangle = False @@ -39,19 +37,22 @@ class TestVisualISAMExample(GtsamTestCase): data, truth = generator.generate_data(options) # Initialize iSAM with the first pose and points - isam, result, nextPose = visual_isam.initialize(data, truth, isamOptions) + isam, result, nextPose = visual_isam.initialize( + data, truth, isamOptions) # Main loop for iSAM: stepping through all poses for currentPose in range(nextPose, options.nrCameras): - isam, result = visual_isam.step(data, isam, result, truth, currentPose) + isam, result = visual_isam.step(data, isam, result, truth, + currentPose) - for i in range(len(truth.cameras)): + for i, _ in enumerate(truth.cameras): pose_i = result.atPose3(symbol('x', i)) self.gtsamAssertEquals(pose_i, truth.cameras[i].pose(), 1e-5) - for j in range(len(truth.points)): + for j, _ in enumerate(truth.points): point_j = result.atPoint3(symbol('l', j)) self.gtsamAssertEquals(point_j, truth.points[j], 1e-5) + if __name__ == "__main__": unittest.main() From 4efdc6982e42f0ac0f5ed45ec051225ca4674787 Mon Sep 17 00:00:00 2001 From: Akash Patel <17132214+acxz@users.noreply.github.com> Date: Fri, 25 Mar 2022 17:11:05 -0400 Subject: [PATCH 110/116] fix typo Co-authored-by: Varun Agrawal --- cmake/HandleMetis.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/HandleMetis.cmake b/cmake/HandleMetis.cmake index d74621654..5cbec4ff5 100644 --- a/cmake/HandleMetis.cmake +++ b/cmake/HandleMetis.cmake @@ -22,7 +22,7 @@ if(GTSAM_USE_SYSTEM_METIS) add_library(metis-gtsam-if INTERFACE) target_include_directories(metis-gtsam-if BEFORE INTERFACE ${METIS_INCLUDE_DIR} - # gtsam_unstable/partition/FindSeparator-inl.h uses internel metislib.h API + # gtsam_unstable/partition/FindSeparator-inl.h uses internal metislib.h API # via extern "C" $ $ @@ -37,7 +37,7 @@ else() target_include_directories(metis-gtsam BEFORE PUBLIC $ $ - # gtsam_unstable/partition/FindSeparator-inl.h uses internel metislib.h API + # gtsam_unstable/partition/FindSeparator-inl.h uses internal metislib.h API # via extern "C" $ $ From 08bbcc889ee44dc52e643613c91c244b48e45a66 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 15:57:52 -0400 Subject: [PATCH 111/116] transformAllFrom/To --- gtsam/geometry/Pose3.cpp | 22 ++++++++++++++++++++++ gtsam/geometry/Pose3.h | 14 ++++++++++++++ gtsam/geometry/geometry.i | 4 ++++ python/gtsam/tests/test_Pose3.py | 27 ++++++++++++++++++++++++--- 4 files changed, 64 insertions(+), 3 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 88f128191..7a522b003 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -354,6 +354,17 @@ Point3 Pose3::transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself, return R_ * point + t_; } +Matrix Pose3::transformAllFrom(const Matrix& points) const { + if (points.rows() != 3) { + throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix."); + } + Matrix result(3, points.cols()); + for (size_t j=0; j < points.cols(); j++) { + result.col(j) = transformFrom(Point3(points.col(j))); + } + return result; +} + /* ************************************************************************* */ Point3 Pose3::transformTo(const Point3& point, OptionalJacobian<3, 6> Hself, OptionalJacobian<3, 3> Hpoint) const { @@ -374,6 +385,17 @@ Point3 Pose3::transformTo(const Point3& point, OptionalJacobian<3, 6> Hself, return q; } +Matrix Pose3::transformAllTo(const Matrix& points) const { + if (points.rows() != 3) { + throw std::invalid_argument("Pose3:transformTo expects 3*N matrix."); + } + Matrix result(3, points.cols()); + for (size_t j=0; j < points.cols(); j++) { + result.col(j) = transformTo(Point3(points.col(j))); + } + return result; +} + /* ************************************************************************* */ double Pose3::range(const Point3& point, OptionalJacobian<1, 6> Hself, OptionalJacobian<1, 3> Hpoint) const { diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 884d0760c..6a9c19d8b 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -249,6 +249,13 @@ public: Point3 transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; + /** + * @brief transform many points in Pose coordinates and transform to world. + * @param points 3*N matrix in Pose coordinates + * @return points in world coordinates, as 3*N Matrix + */ + Matrix transformAllFrom(const Matrix& points) const; + /** syntactic sugar for transformFrom */ inline Point3 operator*(const Point3& point) const { return transformFrom(point); @@ -264,6 +271,13 @@ public: Point3 transformTo(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; + /** + * @brief transform many points in world coordinates and transform to Pose. + * @param points 3*N matrix in world coordinates + * @return points in Pose coordinates, as 3*N Matrix + */ + Matrix transformAllTo(const Matrix& points) const; + /// @} /// @name Standard Interface /// @{ diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 1e42966f8..da704d5ed 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -470,6 +470,10 @@ class Pose3 { gtsam::Point3 transformFrom(const gtsam::Point3& point) const; gtsam::Point3 transformTo(const gtsam::Point3& point) const; + // Matrix versions + Matrix transformAllFrom(const Matrix& points) const; + Matrix transformAllTo(const Matrix& points) const; + // Standard Interface gtsam::Rot3 rotation() const; gtsam::Point3 translation() const; diff --git a/python/gtsam/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py index 411828890..736782943 100644 --- a/python/gtsam/tests/test_Pose3.py +++ b/python/gtsam/tests/test_Pose3.py @@ -30,13 +30,34 @@ class TestPose3(GtsamTestCase): actual = T2.between(T3) self.gtsamAssertEquals(actual, expected, 1e-6) - def test_transform_to(self): + def test_transformTo(self): """Test transformTo method.""" - transform = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) - actual = transform.transformTo(Point3(3, 2, 10)) + pose = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) + actual = pose.transformTo(Point3(3, 2, 10)) expected = Point3(2, 1, 10) self.gtsamAssertEquals(actual, expected, 1e-6) + # multi-point version + points = np.stack([Point3(3, 2, 10), Point3(3, 2, 10)]).T + actual_array = pose.transformAllTo(points) + self.assertEqual(actual_array.shape, (3, 2)) + expected_array = np.stack([expected, expected]).T + np.testing.assert_allclose(actual_array, expected_array) + + def test_transformFrom(self): + """Test transformTo method.""" + pose = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) + actual = pose.transformFrom(Point3(2, 1, 10)) + expected = Point3(3, 2, 10) + self.gtsamAssertEquals(actual, expected, 1e-6) + + # multi-point version + points = np.stack([Point3(2, 1, 10), Point3(2, 1, 10)]).T + actual_array = pose.transformAllFrom(points) + self.assertEqual(actual_array.shape, (3, 2)) + expected_array = np.stack([expected, expected]).T + np.testing.assert_allclose(actual_array, expected_array) + def test_range(self): """Test range method.""" l1 = Point3(1, 0, 0) From 96fb72eb540f5e42b2f13d6a885ed75f4b31affd Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 16:06:06 -0400 Subject: [PATCH 112/116] name change - no "All" needed --- gtsam/geometry/Pose3.cpp | 4 ++-- gtsam/geometry/Pose3.h | 4 ++-- gtsam/geometry/geometry.i | 4 ++-- python/gtsam/tests/test_Pose3.py | 14 +++++++------- 4 files changed, 13 insertions(+), 13 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 7a522b003..643416826 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -354,7 +354,7 @@ Point3 Pose3::transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself, return R_ * point + t_; } -Matrix Pose3::transformAllFrom(const Matrix& points) const { +Matrix Pose3::transformFrom(const Matrix& points) const { if (points.rows() != 3) { throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix."); } @@ -385,7 +385,7 @@ Point3 Pose3::transformTo(const Point3& point, OptionalJacobian<3, 6> Hself, return q; } -Matrix Pose3::transformAllTo(const Matrix& points) const { +Matrix Pose3::transformTo(const Matrix& points) const { if (points.rows() != 3) { throw std::invalid_argument("Pose3:transformTo expects 3*N matrix."); } diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 6a9c19d8b..01980d7af 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -254,7 +254,7 @@ public: * @param points 3*N matrix in Pose coordinates * @return points in world coordinates, as 3*N Matrix */ - Matrix transformAllFrom(const Matrix& points) const; + Matrix transformFrom(const Matrix& points) const; /** syntactic sugar for transformFrom */ inline Point3 operator*(const Point3& point) const { @@ -276,7 +276,7 @@ public: * @param points 3*N matrix in world coordinates * @return points in Pose coordinates, as 3*N Matrix */ - Matrix transformAllTo(const Matrix& points) const; + Matrix transformTo(const Matrix& points) const; /// @} /// @name Standard Interface diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index da704d5ed..0fa931dcf 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -471,8 +471,8 @@ class Pose3 { gtsam::Point3 transformTo(const gtsam::Point3& point) const; // Matrix versions - Matrix transformAllFrom(const Matrix& points) const; - Matrix transformAllTo(const Matrix& points) const; + Matrix transformFrom(const Matrix& points) const; + Matrix transformTo(const Matrix& points) const; // Standard Interface gtsam::Rot3 rotation() const; diff --git a/python/gtsam/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py index 736782943..cf96cbadb 100644 --- a/python/gtsam/tests/test_Pose3.py +++ b/python/gtsam/tests/test_Pose3.py @@ -15,7 +15,7 @@ import unittest import numpy as np import gtsam -from gtsam import Point3, Pose3, Rot3 +from gtsam import Point3, Pose3, Rot3, Point3Pairs from gtsam.utils.test_case import GtsamTestCase @@ -32,31 +32,31 @@ class TestPose3(GtsamTestCase): def test_transformTo(self): """Test transformTo method.""" - pose = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) + pose = Pose3(Rot3.Rodrigues(0, 0, -math.pi/2), Point3(2, 4, 0)) actual = pose.transformTo(Point3(3, 2, 10)) expected = Point3(2, 1, 10) self.gtsamAssertEquals(actual, expected, 1e-6) # multi-point version points = np.stack([Point3(3, 2, 10), Point3(3, 2, 10)]).T - actual_array = pose.transformAllTo(points) + actual_array = pose.transformTo(points) self.assertEqual(actual_array.shape, (3, 2)) expected_array = np.stack([expected, expected]).T - np.testing.assert_allclose(actual_array, expected_array) + np.testing.assert_allclose(actual_array, expected_array, atol=1e-6) def test_transformFrom(self): """Test transformTo method.""" - pose = Pose3(Rot3.Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)) + pose = Pose3(Rot3.Rodrigues(0, 0, -math.pi/2), Point3(2, 4, 0)) actual = pose.transformFrom(Point3(2, 1, 10)) expected = Point3(3, 2, 10) self.gtsamAssertEquals(actual, expected, 1e-6) # multi-point version points = np.stack([Point3(2, 1, 10), Point3(2, 1, 10)]).T - actual_array = pose.transformAllFrom(points) + actual_array = pose.transformFrom(points) self.assertEqual(actual_array.shape, (3, 2)) expected_array = np.stack([expected, expected]).T - np.testing.assert_allclose(actual_array, expected_array) + np.testing.assert_allclose(actual_array, expected_array, atol=1e-6) def test_range(self): """Test range method.""" From bbf4e48d3caaa542b367833dfd9349ed6243059b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 16:33:20 -0400 Subject: [PATCH 113/116] Expose Align, and add matrix version --- gtsam/geometry/Pose3.cpp | 11 +++++++++++ gtsam/geometry/Pose3.h | 3 +++ gtsam/geometry/geometry.i | 3 +++ python/gtsam/tests/test_Pose3.py | 18 ++++++++++++++++++ 4 files changed, 35 insertions(+) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 643416826..5a7bec20a 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -473,6 +473,17 @@ boost::optional Pose3::Align(const Point3Pairs &abPointPairs) { return Pose3(aRb, aTb); } +boost::optional Pose3::Align(const Matrix& a, const Matrix& b) { + if (a.rows() != 3 || b.rows() != 3 || a.cols() != b.cols()) { + throw std::invalid_argument( + "Pose3:Align expects 3*N matrices of equal shape."); + } + Point3Pairs abPointPairs; + for (size_t j=0; j < a.cols(); j++) { + abPointPairs.emplace_back(a.col(j), b.col(j)); + } + return Pose3::Align(abPointPairs); +} boost::optional align(const Point3Pairs &baPointPairs) { Point3Pairs abPointPairs; for (const Point3Pair &baPair : baPointPairs) { diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 01980d7af..c36047349 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -85,6 +85,9 @@ public: */ static boost::optional Align(const std::vector& abPointPairs); + // Version of Pose3::Align that takes 2 matrices. + static boost::optional Align(const Matrix& a, const Matrix& b); + /// @} /// @name Testable /// @{ diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 0fa931dcf..6a0f1d3ad 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -431,6 +431,9 @@ class Pose3 { Pose3(const gtsam::Pose2& pose2); Pose3(Matrix mat); + static boost::optional Align(const gtsam::Point3Pairs& abPointPairs); + static boost::optional Align(const gtsam::Matrix& a, const gtsam::Matrix& b); + // Testable void print(string s = "") const; bool equals(const gtsam::Pose3& pose, double tol) const; diff --git a/python/gtsam/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py index cf96cbadb..c37b95c79 100644 --- a/python/gtsam/tests/test_Pose3.py +++ b/python/gtsam/tests/test_Pose3.py @@ -102,6 +102,24 @@ class TestPose3(GtsamTestCase): actual.deserialize(serialized) self.gtsamAssertEquals(expected, actual, 1e-10) + def test_align_squares(self): + """Test if Align method can align 2 squares.""" + square = np.array([[0,0,0],[0,1,0],[1,1,0],[1,0,0]], float).T + sTt = Pose3(Rot3.Rodrigues(0, 0, -math.pi), Point3(2, 4, 0)) + transformed = sTt.transformTo(square) + + st_pairs = Point3Pairs() + for j in range(4): + st_pairs.append((square[:,j], transformed[:,j])) + + # Recover the transformation sTt + estimated_sTt = Pose3.Align(st_pairs) + self.gtsamAssertEquals(estimated_sTt, sTt, 1e-10) + + # Matrix version + estimated_sTt = Pose3.Align(square, transformed) + self.gtsamAssertEquals(estimated_sTt, sTt, 1e-10) + if __name__ == "__main__": unittest.main() From 56b83af6b06dc67a584913c1a5090b716475769b Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 18:53:44 -0400 Subject: [PATCH 114/116] Use matrix operations, silly me! --- gtsam/geometry/Pose3.cpp | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 5a7bec20a..536947597 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -358,11 +358,8 @@ Matrix Pose3::transformFrom(const Matrix& points) const { if (points.rows() != 3) { throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix."); } - Matrix result(3, points.cols()); - for (size_t j=0; j < points.cols(); j++) { - result.col(j) = transformFrom(Point3(points.col(j))); - } - return result; + const Matrix3 R = R_.matrix(); + return (R * points).colwise() + t_; // Eigen broadcasting! } /* ************************************************************************* */ @@ -389,11 +386,8 @@ Matrix Pose3::transformTo(const Matrix& points) const { if (points.rows() != 3) { throw std::invalid_argument("Pose3:transformTo expects 3*N matrix."); } - Matrix result(3, points.cols()); - for (size_t j=0; j < points.cols(); j++) { - result.col(j) = transformTo(Point3(points.col(j))); - } - return result; + const Matrix3 Rt = R_.transpose(); + return Rt * (points.colwise() - t_); // Eigen broadcasting! } /* ************************************************************************* */ @@ -453,7 +447,7 @@ Unit3 Pose3::bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself, boost::optional Pose3::Align(const Point3Pairs &abPointPairs) { const size_t n = abPointPairs.size(); if (n < 3) { - return boost::none; // we need at least three pairs + return boost::none; // we need at least three pairs } // calculate centroids @@ -484,6 +478,7 @@ boost::optional Pose3::Align(const Matrix& a, const Matrix& b) { } return Pose3::Align(abPointPairs); } + boost::optional align(const Point3Pairs &baPointPairs) { Point3Pairs abPointPairs; for (const Point3Pair &baPair : baPointPairs) { From 628ffb14958f80b69ef4897df703e836bf6e7fba Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 26 Mar 2022 22:55:46 -0400 Subject: [PATCH 115/116] Matrix versions for Pose2 group action --- gtsam/geometry/Pose2.cpp | 17 +++++++++++++++++ gtsam/geometry/Pose2.h | 18 +++++++++++++++++- gtsam/geometry/geometry.i | 4 ++++ python/gtsam/tests/test_Pose2.py | 32 ++++++++++++++++++++++++++++++-- python/gtsam/tests/test_Pose3.py | 2 +- 5 files changed, 69 insertions(+), 4 deletions(-) diff --git a/gtsam/geometry/Pose2.cpp b/gtsam/geometry/Pose2.cpp index a0b3d502e..cc7f8e474 100644 --- a/gtsam/geometry/Pose2.cpp +++ b/gtsam/geometry/Pose2.cpp @@ -213,6 +213,14 @@ Point2 Pose2::transformTo(const Point2& point, return q; } +Matrix Pose2::transformTo(const Matrix& points) const { + if (points.rows() != 2) { + throw std::invalid_argument("Pose2:transformTo expects 2*N matrix."); + } + const Matrix2 Rt = rotation().transpose(); + return Rt * (points.colwise() - t_); // Eigen broadcasting! +} + /* ************************************************************************* */ // see doc/math.lyx, SE(2) section Point2 Pose2::transformFrom(const Point2& point, @@ -224,6 +232,15 @@ Point2 Pose2::transformFrom(const Point2& point, return q + t_; } + +Matrix Pose2::transformFrom(const Matrix& points) const { + if (points.rows() != 2) { + throw std::invalid_argument("Pose2:transformFrom expects 2*N matrix."); + } + const Matrix2 R = rotation().matrix(); + return (R * points).colwise() + t_; // Eigen broadcasting! +} + /* ************************************************************************* */ Rot2 Pose2::bearing(const Point2& point, OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 2> Hpoint) const { diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index a54951728..1e79836f5 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -199,13 +199,29 @@ public: OptionalJacobian<2, 3> Dpose = boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; + /** + * @brief transform many points in world coordinates and transform to Pose. + * @param points 2*N matrix in world coordinates + * @return points in Pose coordinates, as 2*N Matrix + */ + Matrix transformTo(const Matrix& points) const; + /** Return point coordinates in global frame */ GTSAM_EXPORT Point2 transformFrom(const Point2& point, OptionalJacobian<2, 3> Dpose = boost::none, OptionalJacobian<2, 2> Dpoint = boost::none) const; + /** + * @brief transform many points in Pose coordinates and transform to world. + * @param points 2*N matrix in Pose coordinates + * @return points in world coordinates, as 2*N Matrix + */ + Matrix transformFrom(const Matrix& points) const; + /** syntactic sugar for transformFrom */ - inline Point2 operator*(const Point2& point) const { return transformFrom(point);} + inline Point2 operator*(const Point2& point) const { + return transformFrom(point); + } /// @} /// @name Standard Interface diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 6a0f1d3ad..5aeac37ec 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -406,6 +406,10 @@ class Pose2 { gtsam::Point2 transformFrom(const gtsam::Point2& p) const; gtsam::Point2 transformTo(const gtsam::Point2& p) const; + // Matrix versions + Matrix transformFrom(const Matrix& points) const; + Matrix transformTo(const Matrix& points) const; + // Standard Interface double x() const; double y() const; diff --git a/python/gtsam/tests/test_Pose2.py b/python/gtsam/tests/test_Pose2.py index e5ffbad7d..860487db2 100644 --- a/python/gtsam/tests/test_Pose2.py +++ b/python/gtsam/tests/test_Pose2.py @@ -8,11 +8,11 @@ See LICENSE for the license information Pose2 unit tests. Author: Frank Dellaert & Duy Nguyen Ta & John Lambert """ +import math import unittest -import numpy as np - import gtsam +import numpy as np from gtsam import Point2, Point2Pairs, Pose2 from gtsam.utils.test_case import GtsamTestCase @@ -26,6 +26,34 @@ class TestPose2(GtsamTestCase): actual = Pose2.adjoint_(xi, xi) np.testing.assert_array_equal(actual, expected) + def test_transformTo(self): + """Test transformTo method.""" + pose = Pose2(2, 4, -math.pi/2) + actual = pose.transformTo(Point2(3, 2)) + expected = Point2(2, 1) + self.gtsamAssertEquals(actual, expected, 1e-6) + + # multi-point version + points = np.stack([Point2(3, 2), Point2(3, 2)]).T + actual_array = pose.transformTo(points) + self.assertEqual(actual_array.shape, (2, 2)) + expected_array = np.stack([expected, expected]).T + np.testing.assert_allclose(actual_array, expected_array, atol=1e-6) + + def test_transformFrom(self): + """Test transformFrom method.""" + pose = Pose2(2, 4, -math.pi/2) + actual = pose.transformFrom(Point2(2, 1)) + expected = Point2(3, 2) + self.gtsamAssertEquals(actual, expected, 1e-6) + + # multi-point version + points = np.stack([Point2(2, 1), Point2(2, 1)]).T + actual_array = pose.transformFrom(points) + self.assertEqual(actual_array.shape, (2, 2)) + expected_array = np.stack([expected, expected]).T + np.testing.assert_allclose(actual_array, expected_array, atol=1e-6) + def test_align(self) -> None: """Ensure estimation of the Pose2 element to align two 2d point clouds succeeds. diff --git a/python/gtsam/tests/test_Pose3.py b/python/gtsam/tests/test_Pose3.py index c37b95c79..cde71de53 100644 --- a/python/gtsam/tests/test_Pose3.py +++ b/python/gtsam/tests/test_Pose3.py @@ -45,7 +45,7 @@ class TestPose3(GtsamTestCase): np.testing.assert_allclose(actual_array, expected_array, atol=1e-6) def test_transformFrom(self): - """Test transformTo method.""" + """Test transformFrom method.""" pose = Pose3(Rot3.Rodrigues(0, 0, -math.pi/2), Point3(2, 4, 0)) actual = pose.transformFrom(Point3(2, 1, 10)) expected = Point3(3, 2, 10) From fb3f42f7f67cfc7420b1f89bc361037fd7f57bd6 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 27 Mar 2022 11:24:45 -0400 Subject: [PATCH 116/116] Bump version --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b86598663..cfb251663 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ endif() set (GTSAM_VERSION_MAJOR 4) set (GTSAM_VERSION_MINOR 2) set (GTSAM_VERSION_PATCH 0) -set (GTSAM_PRERELEASE_VERSION "a5") +set (GTSAM_PRERELEASE_VERSION "a6") math (EXPR GTSAM_VERSION_NUMERIC "10000 * ${GTSAM_VERSION_MAJOR} + 100 * ${GTSAM_VERSION_MINOR} + ${GTSAM_VERSION_PATCH}") if (${GTSAM_VERSION_PATCH} EQUAL 0)